From 74b247577714b3d72b569ab8d7c7ae82d20f92dc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E5=A7=9C=E5=86=AC=E8=87=B4?= Date: Mon, 2 May 2016 23:39:14 +0800 Subject: [PATCH] Added files via GitHub desktop --- Adjust_profile_position.m | 77 + Adjust_profile_velocity.m | 79 + CTM_to_Euler.m | 28 + Calculate_errors_NED.m | 51 + ECEF_to_ECI.m | 47 + ECEF_to_NED.m | 85 + ECI_to_ECEF.m | 47 + Euler_to_CTM.m | 42 + GNSS_Demo_1.m | 86 + GNSS_Demo_2.m | 108 + GNSS_Demo_3.m | 108 + GNSS_Demo_4.m | 108 + GNSS_Demo_5.m | 108 + GNSS_Demo_6.m | 105 + GNSS_KF_Epoch.m | 146 + GNSS_Kalman_Filter.m | 253 + GNSS_LS_position_velocity.m | 149 + GNSS_Least_Squares.m | 214 + Generate_GNSS_measurements.m | 109 + Gravitation_ECI.m | 42 + Gravity_ECEF.m | 47 + Gravity_NED.m | 43 + IMU_model.m | 79 + INS_GNSS_Demo_1.m | 155 + INS_GNSS_Demo_10.m | 155 + INS_GNSS_Demo_11.m | 155 + INS_GNSS_Demo_12.m | 155 + INS_GNSS_Demo_2.m | 155 + INS_GNSS_Demo_3.m | 147 + INS_GNSS_Demo_4.m | 147 + INS_GNSS_Demo_5.m | 155 + INS_GNSS_Demo_6.m | 155 + INS_GNSS_Demo_7.m | 157 + INS_GNSS_Demo_8.m | 157 + INS_GNSS_Demo_9.m | 155 + Inertial_Demo_1ECEF.m | 89 + Inertial_Demo_1ECI.m | 98 + Inertial_Demo_1NED.m | 89 + Inertial_Demo_2.m | 89 + Inertial_Demo_3.m | 89 + Inertial_Demo_4.m | 89 + Inertial_Demo_5.m | 89 + Inertial_Demo_6.m | 89 + Inertial_Demo_7.m | 88 + Inertial_navigation_ECEF.m | 181 + Inertial_navigation_ECI.m | 190 + Inertial_navigation_NED.m | 177 + Initialize_GNSS_KF.m | 50 + Initialize_GNSS_biases.m | 66 + Initialize_LC_P_matrix.m | 34 + Initialize_NED.m | 50 + Initialize_NED_attitude.m | 27 + Initialize_TC_P_matrix.m | 38 + Interpolate_profile.m | 95 + Kinematics_ECEF.m | 90 + Kinematics_ECI.m | 76 + Kinematics_NED.m | 101 + LC_KF_Epoch.m | 128 + License.txt | 24 + Loosely_coupled_INS_GNSS.m | 338 + NED_to_ECEF.m | 57 + Nav_equations_ECEF.m | 87 + Nav_equations_ECI.m | 74 + Nav_equations_NED.m | 113 + Plot_errors.m | 91 + Plot_profile.m | 94 + Profile_0.csv | 6001 ++++ Profile_1.csv | 6001 ++++ Profile_2.csv | 17501 +++++++++++ Profile_3.csv | 41801 +++++++++++++++++++++++++ Profile_4.csv | 30001 ++++++++++++++++++ Radii_of_curvature.m | 33 + Read_profile.m | 53 + Satellite_positions_and_velocities.m | 75 + Skew_symmetric.m | 23 + Smooth_profile_velocity.m | 70 + TC_KF_Epoch.m | 184 + Tightly_coupled_INS_GNSS.m | 336 + Update_curvilinear_position.m | 47 + Velocity_from_curvilinear.m | 46 + Write_errors.m | 38 + Write_profile.m | 39 + pv_ECEF_to_NED.m | 80 + pv_NED_to_ECEF.m | 52 + 84 files changed, 109380 insertions(+) create mode 100644 Adjust_profile_position.m create mode 100644 Adjust_profile_velocity.m create mode 100644 CTM_to_Euler.m create mode 100644 Calculate_errors_NED.m create mode 100644 ECEF_to_ECI.m create mode 100644 ECEF_to_NED.m create mode 100644 ECI_to_ECEF.m create mode 100644 Euler_to_CTM.m create mode 100644 GNSS_Demo_1.m create mode 100644 GNSS_Demo_2.m create mode 100644 GNSS_Demo_3.m create mode 100644 GNSS_Demo_4.m create mode 100644 GNSS_Demo_5.m create mode 100644 GNSS_Demo_6.m create mode 100644 GNSS_KF_Epoch.m create mode 100644 GNSS_Kalman_Filter.m create mode 100644 GNSS_LS_position_velocity.m create mode 100644 GNSS_Least_Squares.m create mode 100644 Generate_GNSS_measurements.m create mode 100644 Gravitation_ECI.m create mode 100644 Gravity_ECEF.m create mode 100644 Gravity_NED.m create mode 100644 IMU_model.m create mode 100644 INS_GNSS_Demo_1.m create mode 100644 INS_GNSS_Demo_10.m create mode 100644 INS_GNSS_Demo_11.m create mode 100644 INS_GNSS_Demo_12.m create mode 100644 INS_GNSS_Demo_2.m create mode 100644 INS_GNSS_Demo_3.m create mode 100644 INS_GNSS_Demo_4.m create mode 100644 INS_GNSS_Demo_5.m create mode 100644 INS_GNSS_Demo_6.m create mode 100644 INS_GNSS_Demo_7.m create mode 100644 INS_GNSS_Demo_8.m create mode 100644 INS_GNSS_Demo_9.m create mode 100644 Inertial_Demo_1ECEF.m create mode 100644 Inertial_Demo_1ECI.m create mode 100644 Inertial_Demo_1NED.m create mode 100644 Inertial_Demo_2.m create mode 100644 Inertial_Demo_3.m create mode 100644 Inertial_Demo_4.m create mode 100644 Inertial_Demo_5.m create mode 100644 Inertial_Demo_6.m create mode 100644 Inertial_Demo_7.m create mode 100644 Inertial_navigation_ECEF.m create mode 100644 Inertial_navigation_ECI.m create mode 100644 Inertial_navigation_NED.m create mode 100644 Initialize_GNSS_KF.m create mode 100644 Initialize_GNSS_biases.m create mode 100644 Initialize_LC_P_matrix.m create mode 100644 Initialize_NED.m create mode 100644 Initialize_NED_attitude.m create mode 100644 Initialize_TC_P_matrix.m create mode 100644 Interpolate_profile.m create mode 100644 Kinematics_ECEF.m create mode 100644 Kinematics_ECI.m create mode 100644 Kinematics_NED.m create mode 100644 LC_KF_Epoch.m create mode 100644 License.txt create mode 100644 Loosely_coupled_INS_GNSS.m create mode 100644 NED_to_ECEF.m create mode 100644 Nav_equations_ECEF.m create mode 100644 Nav_equations_ECI.m create mode 100644 Nav_equations_NED.m create mode 100644 Plot_errors.m create mode 100644 Plot_profile.m create mode 100644 Profile_0.csv create mode 100644 Profile_1.csv create mode 100644 Profile_2.csv create mode 100644 Profile_3.csv create mode 100644 Profile_4.csv create mode 100644 Radii_of_curvature.m create mode 100644 Read_profile.m create mode 100644 Satellite_positions_and_velocities.m create mode 100644 Skew_symmetric.m create mode 100644 Smooth_profile_velocity.m create mode 100644 TC_KF_Epoch.m create mode 100644 Tightly_coupled_INS_GNSS.m create mode 100644 Update_curvilinear_position.m create mode 100644 Velocity_from_curvilinear.m create mode 100644 Write_errors.m create mode 100644 Write_profile.m create mode 100644 pv_ECEF_to_NED.m create mode 100644 pv_NED_to_ECEF.m diff --git a/Adjust_profile_position.m b/Adjust_profile_position.m new file mode 100644 index 0000000..2a7df5a --- /dev/null +++ b/Adjust_profile_position.m @@ -0,0 +1,77 @@ +function Adjust_profile_position(in_filename,out_filename) +%Adjust_profile_position - Adjusts the position in a motion profile file to +% make it consistent with the velocity +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 2/4/2012 by Paul Groves +% +% Inputs +% in_filename Name of inpit file, e.g. 'In_profile.csv' +% out_filename Name of inpit file, e.g. 'Out_profile.csv' + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Parameters +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; + + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(in_filename); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% Initialize navigation solution +old_time = in_profile(1,1); +old_L_b = in_profile(1,2); +old_lambda_b = in_profile(1,3); +old_h_b = in_profile(1,4); +old_v_eb_n = in_profile(1,5:7)'; +old_eul_nb = in_profile(1,8:10)'; +out_profile(1,:) = in_profile(1,:); + +% Main loop +for epoch = 2:no_epochs + + % Input data from profile + time = in_profile(epoch,1); + v_eb_n = in_profile(epoch,5:7)'; + eul_nb = in_profile(epoch,8:10)'; + + % Time interval + tor_i = time - old_time; + + % Update position + [L_b,lambda_b,h_b]= Update_curvilinear_position(tor_i,old_L_b,... + old_lambda_b,old_h_b,old_v_eb_n,v_eb_n); + + % Generate output profile record + out_profile(epoch,1) = time; + out_profile(epoch,2) = L_b; + out_profile(epoch,3) = lambda_b; + out_profile(epoch,4) = h_b; + out_profile(epoch,5:7) = v_eb_n'; + out_profile(epoch,8:10) = eul_nb'; + + % Reset old values + old_time = time; + old_L_b = L_b; + old_lambda_b = lambda_b; + old_h_b = h_b; + old_v_eb_n = v_eb_n; + old_eul_nb = eul_nb; + +end %epoch + +% Write output profile +Write_profile(out_filename,out_profile); + +% Ends \ No newline at end of file diff --git a/Adjust_profile_velocity.m b/Adjust_profile_velocity.m new file mode 100644 index 0000000..a0dbe9c --- /dev/null +++ b/Adjust_profile_velocity.m @@ -0,0 +1,79 @@ +function Adjust_profile_velocity(in_filename,out_filename) +%Adjust_profile_velocity - Adjusts the velocity in a motion profile file to +% make it consistent with the position +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 2/4/2012 by Paul Groves +% +% Inputs +% in_filename Name of inpit file, e.g. 'In_profile.csv' +% out_filename Name of inpit file, e.g. 'Out_profile.csv' + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Parameters +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; + + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(in_filename); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% Initialize navigation solution +old_time = in_profile(1,1); +old_L_b = in_profile(1,2); +old_lambda_b = in_profile(1,3); +old_h_b = in_profile(1,4); +old_v_eb_n = in_profile(1,5:7)'; +old_eul_nb = in_profile(1,8:10)'; +out_profile(1,:) = in_profile(1,:); + +% Main loop +for epoch = 2:no_epochs + + % Input data from profile + time = in_profile(epoch,1); + L_b = in_profile(epoch,2); + lambda_b = in_profile(epoch,3); + h_b = in_profile(epoch,4); + eul_nb = in_profile(epoch,8:10)'; + + % Time interval + tor_i = time - old_time; + + % Update velocity + v_eb_n = Velocity_from_curvilinear(tor_i,old_L_b,... + old_lambda_b,old_h_b,old_v_eb_n,L_b,lambda_b,h_b); + + % Generate output profile record + out_profile(epoch,1) = time; + out_profile(epoch,2) = L_b; + out_profile(epoch,3) = lambda_b; + out_profile(epoch,4) = h_b; + out_profile(epoch,5:7) = v_eb_n'; + out_profile(epoch,8:10) = eul_nb'; + + % Reset old values + old_time = time; + old_L_b = L_b; + old_lambda_b = lambda_b; + old_h_b = h_b; + old_v_eb_n = v_eb_n; + old_eul_nb = eul_nb; + +end %epoch + +% Write output profile +Write_profile(out_filename,out_profile); + +% Ends \ No newline at end of file diff --git a/CTM_to_Euler.m b/CTM_to_Euler.m new file mode 100644 index 0000000..faa5c16 --- /dev/null +++ b/CTM_to_Euler.m @@ -0,0 +1,28 @@ +function eul = CTM_to_Euler(C) +%CTM_to_Euler - Converts a coordinate transformation matrix to the +%corresponding set of Euler angles% +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 1/4/2012 by Paul Groves +% +% Inputs: +% C coordinate transformation matrix describing transformation from +% beta to alpha +% +% Outputs: +% eul Euler angles describing rotation from beta to alpha in the +% order roll, pitch, yaw(rad) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Calculate Euler angles using (2.23) +eul(1,1) = atan2(C(2,3),C(3,3)); % roll +eul(2,1) = - asin(C(1,3)); % pitch +eul(3,1) = atan2(C(1,2),C(1,1)); % yaw + +% Ends \ No newline at end of file diff --git a/Calculate_errors_NED.m b/Calculate_errors_NED.m new file mode 100644 index 0000000..2c4308d --- /dev/null +++ b/Calculate_errors_NED.m @@ -0,0 +1,51 @@ +function [delta_r_eb_n,delta_v_eb_n,delta_eul_nb_n] = Calculate_errors_NED(... + est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n,true_L_b,... + true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n) +%Calculate_errors_NED - Calculates the position, velocity, and attitude +% errors of a NED navigation solution. +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 3/4/2012 by Paul Groves +% +% Inputs: +% est_L_b latitude solution (rad) +% est_lambda_b longitude solution (rad) +% est_h_b height solution (m) +% est_v_eb_n velocity solution of body frame w.r.t. ECEF frame, +% resolved along north, east, and down (m/s) +% est_C_b_n body-to-NED coordinate transformation matrix solution +% true_L_b true latitude (rad) +% true_lambda_b true longitude (rad) +% true_h_b true height (m) +% true_v_eb_n true velocity of body frame w.r.t. ECEF frame, resolved +% along north, east, and down (m/s) +% C_b_n true body-to-NED coordinate transformation matrix +% +% Outputs: +% delta_r_eb_n position error resolved along NED (m) +% delta_v_eb_n velocity error resolved along NED (m/s) +% delta_eul_nb_n attitude error as NED Euler angles (rad) +% These are expressed about north, east, and down + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Position error calculation, using (2.119) +[R_N,R_E] = Radii_of_curvature(true_L_b); +delta_r_eb_n(1) = (est_L_b - true_L_b) * (R_N + true_h_b); +delta_r_eb_n(2) = (est_lambda_b - true_lambda_b) * (R_E + true_h_b) *... + cos(true_L_b); +delta_r_eb_n(3) = -(est_h_b - true_h_b); + +% Velocity error calculation +delta_v_eb_n = est_v_eb_n - true_v_eb_n; + +% Attitude error calculation, using (5.109) and (5.111) +delta_C_b_n = est_C_b_n * true_C_b_n'; +delta_eul_nb_n = -CTM_to_Euler(delta_C_b_n); + +% Ends \ No newline at end of file diff --git a/ECEF_to_ECI.m b/ECEF_to_ECI.m new file mode 100644 index 0000000..f766539 --- /dev/null +++ b/ECEF_to_ECI.m @@ -0,0 +1,47 @@ +function [r_ib_i,v_ib_i,C_b_i] = ECEF_to_ECI(t,r_eb_e,v_eb_e,C_b_e) +%ECEF_to_ECI - Converts position, velocity, and attitude from ECEF- to +%ECI-frame referenced and resolved +%地心地固坐标系转换到地心惯性坐标系 +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 2/4/2012 by Paul Groves +% +% Inputs: +% t time (s) +% r_eb_e Cartesian position of body frame w.r.t. ECEF frame, resolved +% along ECEF-frame axes (m) +% v_eb_e velocity of body frame w.r.t. ECEF frame, resolved along +% ECEF-frame axes (m/s) +% C_b_e body-to-ECEF-frame coordinate transformation matrix +% +% Outputs: +% r_ib_i Cartesian position of body frame w.r.t. ECI frame, resolved +% along ECI-frame axes (m) +% v_ib_i velocity of body frame w.r.t. ECI frame, resolved along +% ECI-frame axes (m/s) +% C_b_i body-to-ECI-frame coordinate transformation matrix + +% Parameters +omega_ie = 7.292115E-5; % Earth rotation rate (rad/s) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Calculate ECEF to ECI coordinate transformation matrix using (2.145) +C_e_i = [cos(omega_ie * t), -sin(omega_ie * t), 0;... + sin(omega_ie * t), cos(omega_ie * t), 0;... + 0, 0, 1]; + +% Transform position using (2.146) +r_ib_i = C_e_i * r_eb_e; + +% Transform velocity using (2.145) +v_ib_i = C_e_i * (v_eb_e + omega_ie * [-r_eb_e(2);r_eb_e(1);0]); + +% Transform attitude using (2.15) +C_b_i = C_e_i * C_b_e; + +% Ends \ No newline at end of file diff --git a/ECEF_to_NED.m b/ECEF_to_NED.m new file mode 100644 index 0000000..046615c --- /dev/null +++ b/ECEF_to_NED.m @@ -0,0 +1,85 @@ +function [L_b,lambda_b,h_b,v_eb_n,C_b_n] = ECEF_to_NED(r_eb_e,v_eb_e,C_b_e) +%ECEF_to_NED - Converts Cartesian to curvilinear position, velocity +%resolving axes from ECEF to NED and attitude from ECEF- to NED-referenced +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 2/4/2012 by Paul Groves +% +% Inputs: +% r_eb_e Cartesian position of body frame w.r.t. ECEF frame, resolved +% along ECEF-frame axes (m) +% v_eb_e velocity of body frame w.r.t. ECEF frame, resolved along +% ECEF-frame axes (m/s) +% C_b_e body-to-ECEF-frame coordinate transformation matrix +% +% Outputs: +% L_b latitude (rad) +% lambda_b longitude (rad) +% h_b height (m) +% v_eb_n velocity of body frame w.r.t. ECEF frame, resolved along +% north, east, and down (m/s) +% C_b_n body-to-NED coordinate transformation matrix + +% Parameters +R_0 = 6378137; %WGS84 Equatorial radius in meters +e = 0.0818191908425; %WGS84 eccentricity + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Convert position using Borkowski closed-form exact solution +% From (2.113) +lambda_b = atan2(r_eb_e(2),r_eb_e(1)); + +% From (C.29) and (C.30) +k1 = sqrt(1 - e^2) * abs (r_eb_e(3)); +k2 = e^2 * R_0; +beta = sqrt(r_eb_e(1)^2 + r_eb_e(2)^2); +E = (k1 - k2) / beta; +F = (k1 + k2) / beta; + +% From (C.31) +P = 4/3 * (E*F + 1); + +% From (C.32) +Q = 2 * (E^2 - F^2); + +% From (C.33) +D = P^3 + Q^2; + +% From (C.34) +V = (sqrt(D) - Q)^(1/3) - (sqrt(D) + Q)^(1/3); + +% From (C.35) +G = 0.5 * (sqrt(E^2 + V) + E); + +% From (C.36) +T = sqrt(G^2 + (F - V * G) / (2 * G - E)) - G; + +% From (C.37) +L_b = sign(r_eb_e(3)) * atan((1 - T^2) / (2 * T * sqrt (1 - e^2))); + +% From (C.38) +h_b = (beta - R_0 * T) * cos(L_b) +... + (r_eb_e(3) - sign(r_eb_e(3)) * R_0 * sqrt(1 - e^2)) * sin (L_b); + +% Calculate ECEF to NED coordinate transformation matrix using (2.150) +cos_lat = cos(L_b); +sin_lat = sin(L_b); +cos_long = cos(lambda_b); +sin_long = sin(lambda_b); +C_e_n = [-sin_lat * cos_long, -sin_lat * sin_long, cos_lat;... + -sin_long, cos_long, 0;... + -cos_lat * cos_long, -cos_lat * sin_long, -sin_lat]; + +% Transform velocity using (2.73) +v_eb_n = C_e_n * v_eb_e; + +% Transform attitude using (2.15) +C_b_n = C_e_n * C_b_e; + +% Ends \ No newline at end of file diff --git a/ECI_to_ECEF.m b/ECI_to_ECEF.m new file mode 100644 index 0000000..438c27d --- /dev/null +++ b/ECI_to_ECEF.m @@ -0,0 +1,47 @@ +function [r_eb_e,v_eb_e,C_b_e] = ECI_to_ECEF(t,r_ib_i,v_ib_i,C_b_i) +%ECI_to_ECEF - Converts position, velocity, and attitude from ECI- to +%ECEF-frame referenced and resolved +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 2/4/2012 by Paul Groves +% +% Inputs: +% t time (s) +% r_ib_i Cartesian position of body frame w.r.t. ECI frame, resolved +% along ECI-frame axes (m) +% v_ib_i velocity of body frame w.r.t. ECI frame, resolved along +% ECI-frame axes (m/s) +% C_b_i body-to-ECI-frame coordinate transformation matrix +% +% Outputs: +% r_eb_e Cartesian position of body frame w.r.t. ECEF frame, resolved +% along ECEF-frame axes (m) +% v_eb_e velocity of body frame w.r.t. ECEF frame, resolved along +% ECEF-frame axes (m/s) +% C_b_e body-to-ECEF-frame coordinate transformation matrix + +% Parameters +omega_ie = 7.292115E-5; % Earth rotation rate (rad/s) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Calculate ECI to ECEF coordinate transformation matrix using (2.145) +C_i_e = [cos(omega_ie * t), sin(omega_ie * t), 0;... + -sin(omega_ie * t), cos(omega_ie * t), 0;... + 0, 0, 1]; + +% Transform position using (2.146) +r_eb_e = C_i_e * r_ib_i; + +% Transform velocity using (2.145) +v_eb_e = C_i_e * (v_ib_i - omega_ie * [-r_ib_i(2);r_ib_i(1);0]); + +% Transform attitude using (2.15) +C_b_e = C_i_e * C_b_i; + +% Ends \ No newline at end of file diff --git a/Euler_to_CTM.m b/Euler_to_CTM.m new file mode 100644 index 0000000..958b748 --- /dev/null +++ b/Euler_to_CTM.m @@ -0,0 +1,42 @@ +function C = Euler_to_CTM(eul) +%Euler_to_CTM - Converts a set of Euler angles to the corresponding +%coordinate transformation matrix 把欧拉角转换为相应的坐标转换矩阵 P.35 +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 1/4/2012 by Paul Groves +% +% Inputs: +% eul Euler angles describing rotation from beta to alpha in the +% order roll, pitch, yaw(rad) +% +% Outputs: +% C coordinate transformation matrix describing transformation from +% beta to alpha + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Precalculate sines and cosines of the Euler angles +sin_phi = sin(eul(1)); +cos_phi = cos(eul(1)); +sin_theta = sin(eul(2)); +cos_theta = cos(eul(2)); +sin_psi = sin(eul(3)); +cos_psi = cos(eul(3)); + +% Calculate coordinate transformation matrix using (2.22) +C(1,1) = cos_theta * cos_psi; +C(1,2) = cos_theta * sin_psi; +C(1,3) = -sin_theta; +C(2,1) = -cos_phi * sin_psi + sin_phi * sin_theta * cos_psi; +C(2,2) = cos_phi * cos_psi + sin_phi * sin_theta * sin_psi; +C(2,3) = sin_phi * cos_theta; +C(3,1) = sin_phi * sin_psi + cos_phi * sin_theta * cos_psi; +C(3,2) = -sin_phi * cos_psi + cos_phi * sin_theta * sin_psi; +C(3,3) = cos_phi * cos_theta; + +% Ends \ No newline at end of file diff --git a/GNSS_Demo_1.m b/GNSS_Demo_1.m new file mode 100644 index 0000000..b0eb62c --- /dev/null +++ b/GNSS_Demo_1.m @@ -0,0 +1,86 @@ +%GNSS_Demo_1 +%SCRIPT Stand-alone GNSS demo with least-squares solution: +% Profile_1 (60s artificial car motion with two 90 deg turns) +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 11/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_1.csv'; +% Output motion profile and error filenames +output_profile_name = 'GNSS_Demo_1_Profile.csv'; +output_errors_name = 'GNSS_Demo_1_Errors.csv'; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 1; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +% RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% NED Inertial navigation simulation +[out_profile,out_errors,out_clock] = GNSS_Least_Squares(in_profile,... + no_epochs,GNSS_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/GNSS_Demo_2.m b/GNSS_Demo_2.m new file mode 100644 index 0000000..e53c57e --- /dev/null +++ b/GNSS_Demo_2.m @@ -0,0 +1,108 @@ +%GNSS_Demo_2 +%SCRIPT Stand-alone GNSS demo with Kalman filter solution: +% Profile_1 (60s artificial car motion with two 90 deg turns) +% +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 12/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_1.csv'; +% Output motion profile and error filenames +output_profile_name = 'GNSS_Demo_2_Profile.csv'; +output_errors_name = 'GNSS_Demo_2_Errors.csv'; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 1; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial position uncertainty per axis (m) +GNSS_KF_config.init_pos_unc = 10; +% Initial velocity uncertainty per axis (m/s) +GNSS_KF_config.init_vel_unc = 0.1; +% Initial clock offset uncertainty per axis (m) +GNSS_KF_config.init_clock_offset_unc = 10; +% Initial clock drift uncertainty per axis (m/s) +GNSS_KF_config.init_clock_drift_unc = 0.1; + +% Acceleration PSD per axis (m^2/s^3) +GNSS_KF_config.accel_PSD = 10; +% Receiver clock frequency-drift PSD (m^2/s^3) +GNSS_KF_config.clock_freq_PSD = 1; +% Receiver clock phase-drift PSD (m^2/s) +GNSS_KF_config.clock_phase_PSD = 1; + +% Pseudo-range measurement noise SD (m) +GNSS_KF_config.pseudo_range_SD = 2.5; +% Pseudo-range rate measurement noise SD (m/s) +GNSS_KF_config.range_rate_SD = 0.05; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% NED Inertial navigation simulation +[out_profile,out_errors,out_clock,out_KF_SD] = GNSS_Kalman_Filter(... + in_profile,no_epochs,GNSS_config,GNSS_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/GNSS_Demo_3.m b/GNSS_Demo_3.m new file mode 100644 index 0000000..2f5d317 --- /dev/null +++ b/GNSS_Demo_3.m @@ -0,0 +1,108 @@ +%GNSS_Demo_3 +%SCRIPT Stand-alone GNSS demo with Kalman filter solution: +% Profile_0 (60s stationary and level) +% +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 12/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_0.csv'; +% Output motion profile and error filenames +output_profile_name = 'GNSS_Demo_3_Profile.csv'; +output_errors_name = 'GNSS_Demo_3_Errors.csv'; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 1; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial position uncertainty per axis (m) +GNSS_KF_config.init_pos_unc = 10; +% Initial velocity uncertainty per axis (m/s) +GNSS_KF_config.init_vel_unc = 0.1; +% Initial clock offset uncertainty per axis (m) +GNSS_KF_config.init_clock_offset_unc = 10; +% Initial clock drift uncertainty per axis (m/s) +GNSS_KF_config.init_clock_drift_unc = 0.1; + +% Acceleration PSD per axis (m^2/s^3) +GNSS_KF_config.accel_PSD = 0.01; +% Receiver clock frequency-drift PSD (m^2/s^3) +GNSS_KF_config.clock_freq_PSD = 1; +% Receiver clock phase-drift PSD (m^2/s) +GNSS_KF_config.clock_phase_PSD = 1; + +% Pseudo-range measurement noise SD (m) +GNSS_KF_config.pseudo_range_SD = 2.5; +% Pseudo-range rate measurement noise SD (m/s) +GNSS_KF_config.range_rate_SD = 0.05; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% NED Inertial navigation simulation +[out_profile,out_errors,out_clock,out_KF_SD] = GNSS_Kalman_Filter(... + in_profile,no_epochs,GNSS_config,GNSS_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/GNSS_Demo_4.m b/GNSS_Demo_4.m new file mode 100644 index 0000000..2810455 --- /dev/null +++ b/GNSS_Demo_4.m @@ -0,0 +1,108 @@ +%GNSS_Demo_4 +%SCRIPT Stand-alone GNSS demo with Kalman filter solution: +% Profile_2 (175s car) +% +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 27/5/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_2.csv'; +% Output motion profile and error filenames +output_profile_name = 'GNSS_Demo_4_Profile.csv'; +output_errors_name = 'GNSS_Demo_4_Errors.csv'; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 1; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial position uncertainty per axis (m) +GNSS_KF_config.init_pos_unc = 10; +% Initial velocity uncertainty per axis (m/s) +GNSS_KF_config.init_vel_unc = 0.1; +% Initial clock offset uncertainty per axis (m) +GNSS_KF_config.init_clock_offset_unc = 10; +% Initial clock drift uncertainty per axis (m/s) +GNSS_KF_config.init_clock_drift_unc = 0.1; + +% Acceleration PSD per axis (m^2/s^3) +GNSS_KF_config.accel_PSD = 10; +% Receiver clock frequency-drift PSD (m^2/s^3) +GNSS_KF_config.clock_freq_PSD = 1; +% Receiver clock phase-drift PSD (m^2/s) +GNSS_KF_config.clock_phase_PSD = 1; + +% Pseudo-range measurement noise SD (m) +GNSS_KF_config.pseudo_range_SD = 2.5; +% Pseudo-range rate measurement noise SD (m/s) +GNSS_KF_config.range_rate_SD = 0.05; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% NED Inertial navigation simulation +[out_profile,out_errors,out_clock,out_KF_SD] = GNSS_Kalman_Filter(... + in_profile,no_epochs,GNSS_config,GNSS_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/GNSS_Demo_5.m b/GNSS_Demo_5.m new file mode 100644 index 0000000..24efb7a --- /dev/null +++ b/GNSS_Demo_5.m @@ -0,0 +1,108 @@ +%GNSS_Demo_5 +%SCRIPT Stand-alone GNSS demo with Kalman filter solution: +% Profile_3 (418s aircraft) +% +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 27/5/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_3.csv'; +% Output motion profile and error filenames +output_profile_name = 'GNSS_Demo_5_Profile.csv'; +output_errors_name = 'GNSS_Demo_5_Errors.csv'; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 1; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial position uncertainty per axis (m) +GNSS_KF_config.init_pos_unc = 10; +% Initial velocity uncertainty per axis (m/s) +GNSS_KF_config.init_vel_unc = 0.1; +% Initial clock offset uncertainty per axis (m) +GNSS_KF_config.init_clock_offset_unc = 10; +% Initial clock drift uncertainty per axis (m/s) +GNSS_KF_config.init_clock_drift_unc = 0.1; + +% Acceleration PSD per axis (m^2/s^3) +GNSS_KF_config.accel_PSD = 10; +% Receiver clock frequency-drift PSD (m^2/s^3) +GNSS_KF_config.clock_freq_PSD = 1; +% Receiver clock phase-drift PSD (m^2/s) +GNSS_KF_config.clock_phase_PSD = 1; + +% Pseudo-range measurement noise SD (m) +GNSS_KF_config.pseudo_range_SD = 2.5; +% Pseudo-range rate measurement noise SD (m/s) +GNSS_KF_config.range_rate_SD = 0.05; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% NED Inertial navigation simulation +[out_profile,out_errors,out_clock,out_KF_SD] = GNSS_Kalman_Filter(... + in_profile,no_epochs,GNSS_config,GNSS_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/GNSS_Demo_6.m b/GNSS_Demo_6.m new file mode 100644 index 0000000..5454385 --- /dev/null +++ b/GNSS_Demo_6.m @@ -0,0 +1,105 @@ +%GNSS_Demo_6 +%SCRIPT Stand-alone GNSS demo with Kalman filter solution: +% Profile_4 (300s boat) +% +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 27/5/12 by Paul Groves + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_4.csv'; +% Output motion profile and error filenames +output_profile_name = 'GNSS_Demo_6_Profile.csv'; +output_errors_name = 'GNSS_Demo_6_Errors.csv'; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 1; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial position uncertainty per axis (m) +GNSS_KF_config.init_pos_unc = 10; +% Initial velocity uncertainty per axis (m/s) +GNSS_KF_config.init_vel_unc = 0.1; +% Initial clock offset uncertainty per axis (m) +GNSS_KF_config.init_clock_offset_unc = 10; +% Initial clock drift uncertainty per axis (m/s) +GNSS_KF_config.init_clock_drift_unc = 0.1; + +% Acceleration PSD per axis (m^2/s^3) +GNSS_KF_config.accel_PSD = 10; +% Receiver clock frequency-drift PSD (m^2/s^3) +GNSS_KF_config.clock_freq_PSD = 1; +% Receiver clock phase-drift PSD (m^2/s) +GNSS_KF_config.clock_phase_PSD = 1; + +% Pseudo-range measurement noise SD (m) +GNSS_KF_config.pseudo_range_SD = 2.5; +% Pseudo-range rate measurement noise SD (m/s) +GNSS_KF_config.range_rate_SD = 0.05; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% NED Inertial navigation simulation +[out_profile,out_errors,out_clock,out_KF_SD] = GNSS_Kalman_Filter(... + in_profile,no_epochs,GNSS_config,GNSS_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/GNSS_KF_Epoch.m b/GNSS_KF_Epoch.m new file mode 100644 index 0000000..8b52b5d --- /dev/null +++ b/GNSS_KF_Epoch.m @@ -0,0 +1,146 @@ +function [x_est_new,P_matrix_new] = GNSS_KF_Epoch(GNSS_measurements,... + no_meas,tor_s,x_est_old,P_matrix_old,GNSS_KF_config) +%GNSS_KF_Epoch - Implements one cycle of the GNSS extended Kalman filter +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 12/4/2012 by Paul Groves +% +% Inputs: +% GNSS_measurements GNSS measurement data: +% Column 1 Pseudo-range measurements (m) +% Column 2 Pseudo-range rate measurements (m/s) +% Columns 3-5 Satellite ECEF position (m) +% Columns 6-8 Satellite ECEF velocity (m/s) +% no_meas Number of satellites for which measurements are +% supplied +% tor_s propagation interval (s) +% x_est_old previous Kalman filter state estimates +% P_matrix_old previous Kalman filter error covariance matrix +% GNSS_KF_config +% .accel_PSD Acceleration PSD per axis (m^2/s^3) +% .clock_freq_PSD Receiver clock frequency-drift PSD (m^2/s^3) +% .clock_phase_PSD Receiver clock phase-drift PSD (m^2/s) +% .pseudo_range_SD Pseudo-range measurement noise SD (m) +% .range_rate_SD Pseudo-range rate measurement noise SD (m/s) +% +% Outputs: +% x_est_new updated Kalman filter state estimates +% Rows 1-3 estimated ECEF user position (m) +% Rows 4-6 estimated ECEF user velocity (m/s) +% Row 7 estimated receiver clock offset (m) +% Row 8 estimated receiver clock drift (m/s) +% P_matrix_new updated Kalman filter error covariance matrix + + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants (sone of these could be changed to inputs at a later date) +c = 299792458; % Speed of light in m/s +omega_ie = 7.292115E-5; % Earth rotation rate in rad/s + +% Begins + +% SYSTEM PROPAGATION PHASE + +% 1. Determine transition matrix using (9.147) and (9.150) +Phi_matrix = eye(8); +Phi_matrix(1,4) = tor_s; +Phi_matrix(2,5) = tor_s; +Phi_matrix(3,6) = tor_s; +Phi_matrix(7,8) = tor_s; + +% 2. Determine system noise covariance matrix using (9.152) +Q_matrix = zeros(8); +Q_matrix(1:3,1:3) = eye(3) * GNSS_KF_config.accel_PSD * tor_s^3 / 3; +Q_matrix(1:3,4:6) = eye(3) * GNSS_KF_config.accel_PSD * tor_s^2 / 2; +Q_matrix(4:6,1:3) = eye(3) * GNSS_KF_config.accel_PSD * tor_s^2 / 2; +Q_matrix(4:6,4:6) = eye(3) * GNSS_KF_config.accel_PSD * tor_s; +Q_matrix(7,7) = (GNSS_KF_config.clock_freq_PSD * tor_s^3 / 3) +... + GNSS_KF_config.clock_phase_PSD * tor_s; +Q_matrix(7,8) = GNSS_KF_config.clock_freq_PSD * tor_s^2 / 2; +Q_matrix(8,7) = GNSS_KF_config.clock_freq_PSD * tor_s^2 / 2; +Q_matrix(8,8) = GNSS_KF_config.clock_freq_PSD * tor_s; + +% 3. Propagate state estimates using (3.14) +x_est_propagated = Phi_matrix * x_est_old; + +% 4. Propagate state estimation error covariance matrix using (3.15) +P_matrix_propagated = Phi_matrix * P_matrix_old * Phi_matrix' + Q_matrix; + +% MEASUREMENT UPDATE PHASE + +% Skew symmetric matrix of Earth rate +Omega_ie = Skew_symmetric([0,0,omega_ie]); + +u_as_e_T = zeros(no_meas,3); +pred_meas = zeros(no_meas,2); + +% Loop measurements +for j = 1:no_meas + + % Predict approx range + delta_r = GNSS_measurements(j,3:5)' - x_est_propagated(1:3); + approx_range = sqrt(delta_r' * delta_r); + + % Calculate frame rotation during signal transit time using (8.36) + C_e_I = [1, omega_ie * approx_range / c, 0;... + -omega_ie * approx_range / c, 1, 0;... + 0, 0, 1]; + + % Predict pseudo-range using (9.165) + delta_r = C_e_I * GNSS_measurements(j,3:5)' - x_est_propagated(1:3); + range = sqrt(delta_r' * delta_r); + pred_meas(j,1) = range + x_est_propagated(7); + + % Predict line of sight + u_as_e_T(j,1:3) = delta_r' / range; + + % Predict pseudo-range rate using (9.165) + range_rate = u_as_e_T(j,1:3) * (C_e_I * (GNSS_measurements(j,6:8)' +... + Omega_ie * GNSS_measurements(j,3:5)') - (x_est_propagated(4:6) +... + Omega_ie * x_est_propagated(1:3))); + pred_meas(j,2) = range_rate + x_est_propagated(8); + +end % for j + +% 5. Set-up measurement matrix using (9.163) +H_matrix(1:no_meas,1:3) = -u_as_e_T(1:no_meas,1:3); +H_matrix(1:no_meas,4:6) = zeros(no_meas,3); +H_matrix(1:no_meas,7) = ones(no_meas,1); +H_matrix(1:no_meas,8) = zeros(no_meas,1); +H_matrix((no_meas + 1):(2 * no_meas),1:3) = zeros(no_meas,3); +H_matrix((no_meas + 1):(2 * no_meas),4:6) = -u_as_e_T(1:no_meas,1:3); +H_matrix((no_meas + 1):(2 * no_meas),7) = zeros(no_meas,1); +H_matrix((no_meas + 1):(2 * no_meas),8) = ones(no_meas,1); + +% 6. Set-up measurement noise covariance matrix assuming all measurements +% are independent and have equal variance for a given measurement type +R_matrix(1:no_meas,1:no_meas) = eye(no_meas) *... + GNSS_KF_config.pseudo_range_SD^2; +R_matrix(1:no_meas,(no_meas + 1):(2 * no_meas)) =... + zeros(no_meas); +R_matrix((no_meas + 1):(2 * no_meas),1:no_meas) =... + zeros(no_meas); +R_matrix((no_meas + 1):(2 * no_meas),(no_meas + 1):(2 * no_meas)) =... + eye(no_meas) * GNSS_KF_config.range_rate_SD^2; + +% 7. Calculate Kalman gain using (3.21) +K_matrix = P_matrix_propagated * H_matrix' * inv(H_matrix *... + P_matrix_propagated * H_matrix' + R_matrix); + +% 8. Formulate measurement innovations using (3.88) +delta_z(1:no_meas,1) = GNSS_measurements(1:no_meas,1) -... + pred_meas(1:no_meas,1); +delta_z((no_meas + 1):(2 * no_meas),1) = GNSS_measurements(1:no_meas,2) -... + pred_meas(1:no_meas,2); + +% 9. Update state estimates using (3.24) +x_est_new = x_est_propagated + K_matrix * delta_z; + +% 10. Update state estimation error covariance matrix using (3.25) +P_matrix_new = (eye(8) - K_matrix * H_matrix) * P_matrix_propagated; + +% Ends \ No newline at end of file diff --git a/GNSS_Kalman_Filter.m b/GNSS_Kalman_Filter.m new file mode 100644 index 0000000..5f23f8f --- /dev/null +++ b/GNSS_Kalman_Filter.m @@ -0,0 +1,253 @@ +function [out_profile,out_errors,out_clock,out_KF_SD] = GNSS_Kalman_Filter(... + in_profile,no_epochs,GNSS_config,GNSS_KF_config) +%GNSS_Kalman_Filter - Simulates stand-alone GNSS using an Extended Kalman +%filter positioning algorithm +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 11/4/2012 by Paul Groves +% +% Inputs: +% in_profile True motion profile array +% no_epochs Number of epochs of profile data +% GNSS_config +% .epoch_interval Interval between GNSS epochs (s) +% .init_est_r_ea_e Initial estimated position (m; ECEF) +% .no_sat Number of satellites in constellation +% .r_os Orbital radius of satellites (m) +% .inclination Inclination angle of satellites (deg) +% .const_delta_lambda Longitude offset of constellation (deg) +% .const_delta_t Timing offset of constellation (s) +% .mask_angle Mask angle (deg) +% .SIS_err_SD Signal in space error SD (m) +% .zenith_iono_err_SD Zenith ionosphere error SD (m) +% .zenith_trop_err_SD Zenith troposphere error SD (m) +% .code_track_err_SD Code tracking error SD (m) +% .rate_track_err_SD Range rate tracking error SD (m/s) +% .rx_clock_offset Receiver clock offset at time=0 (m) +% .rx_clock_drift Receiver clock drift at time=0 (m/s) +% GNSS_KF_config +% .init_pos_unc Initial position uncertainty per axis (m) +% .init_vel_unc Initial velocity uncertainty per axis (m/s) +% .init_clock_offset_unc Initial clock offset uncertainty per axis (m) +% .init_clock_drift_unc Initial clock drift uncertainty per axis (m/s) +% .accel_PSD Acceleration PSD per axis (m^2/s^3) +% .clock_freq_PSD Receiver clock frequency-drift PSD (m^2/s^3) +% .clock_phase_PSD Receiver clock phase-drift PSD (m^2/s) +% .pseudo_range_SD Pseudo-range measurement noise SD (m) +% .range_rate_SD Pseudo-range rate measurement noise SD (m/s) +% +% Outputs: +% out_profile Navigation solution as a motion profile array +% out_errors Navigation solution error array +% out_clock Receiver clock estimate array +% out_KF_SD Output Kalman filter state uncertainties +% +% Format of motion profiles: +% Column 1: time (sec) +% Column 2: latitude (rad) +% Column 3: longitude (rad) +% Column 4: height (m) +% Column 5: north velocity (m/s) +% Column 6: east velocity (m/s) +% Column 7: down velocity (m/s) +% Column 8: roll angle of body w.r.t NED (rad) +% Column 9: pitch angle of body w.r.t NED (rad) +% Column 10: yaw angle of body w.r.t NED (rad) +% +% Format of error array: +% Column 1: time (sec) +% Column 2: north position error (m) +% Column 3: east position error (m) +% Column 4: down position error (m) +% Column 5: north velocity error (m/s) +% Column 6: east velocity error (m/s) +% Column 7: down velocity (error m/s) +% Column 8: NOT USED (attitude error about north (rad)) +% Column 9: NOT USED (attitude error about east (rad)) +% Column 10: NOT USED (attitude error about down = heading error (rad)) +% +% Format of receiver clock array: +% Column 1: time (sec) +% Column 2: estimated clock offset (m) +% Column 3: estimated clock drift (m/s) +% +% Format of KF state uncertainties array: +% Column 1: time (sec) +% Column 2: X position uncertainty (m) +% Column 3: Y position uncertainty (m) +% Column 4: Z position uncertainty (m) +% Column 5: X velocity uncertainty (m/s) +% Column 6: Y velocity uncertainty (m/s) +% Column 7: Z velocity uncertainty (m/s) +% Column 8: clock offset uncertainty (m) +% Column 9: clock drift uncertainty (m/s) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Initialize true navigation solution +old_time = in_profile(1,1); +true_L_b = in_profile(1,2); +true_lambda_b = in_profile(1,3); +true_h_b = in_profile(1,4); +true_v_eb_n = in_profile(1,5:7)'; +true_eul_nb = in_profile(1,8:10)'; +true_C_b_n = Euler_to_CTM(true_eul_nb)'; +[true_r_eb_e,true_v_eb_e] =... + pv_NED_to_ECEF(true_L_b,true_lambda_b,true_h_b,true_v_eb_n); + +time_last_GNSS = old_time; +GNSS_epoch = 1; + +% Determine satellite positions and velocities +[sat_r_es_e,sat_v_es_e] = Satellite_positions_and_velocities(old_time,... + GNSS_config); + +% Initialize the GNSS biases. Note that these are assumed constant throughout +% the simulation and are based on the initial elevation angles. Therefore, +% this function is unsuited to simulations longer than about 30 min. +GNSS_biases = Initialize_GNSS_biases(sat_r_es_e,true_r_eb_e,true_L_b,... + true_lambda_b,GNSS_config); + +% Generate GNSS measurements +[GNSS_measurements,no_GNSS_meas] = Generate_GNSS_measurements(old_time,... + sat_r_es_e,sat_v_es_e,true_r_eb_e,true_L_b,true_lambda_b,true_v_eb_e,... + GNSS_biases,GNSS_config); + +% Determine Least-squares GNSS position solution +[est_r_eb_e,est_v_eb_e,est_clock] = GNSS_LS_position_velocity(... + GNSS_measurements,no_GNSS_meas,GNSS_config.init_est_r_ea_e,[0;0;0]); + +% Initialize Kalman filter +[x_est,P_matrix] = Initialize_GNSS_KF(est_r_eb_e,est_v_eb_e,est_clock,... + GNSS_KF_config); + +est_C_b_n = true_C_b_n; % This sets the attitude errors to zero + + +[est_L_b,est_lambda_b,est_h_b,est_v_eb_n] =... + pv_ECEF_to_NED(x_est(1:3),x_est(4:6)); + +% Generate output profile record +out_profile(1,1) = old_time; +out_profile(1,2) = est_L_b; +out_profile(1,3) = est_lambda_b; +out_profile(1,4) = est_h_b; +out_profile(1,5:7) = est_v_eb_n'; +out_profile(1,8:10) = CTM_to_Euler(est_C_b_n')'; + +% Determine errors and generate output record +[delta_r_eb_n,delta_v_eb_n,delta_eul_nb_n] = Calculate_errors_NED(... + est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n,true_L_b,... + true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); +out_errors(1,1) = old_time; +out_errors(1,2:4) = delta_r_eb_n'; +out_errors(1,5:7) = delta_v_eb_n'; +out_errors(1,8:10) = [0;0;0]; + +% Generate clock output record +out_clock(1,1) = old_time; +out_clock(1,2:3) = x_est(7:8); + +% Generate KF uncertainty record +out_KF_SD(1,1) = old_time; +for i =1:8 + out_KF_SD(1,i+1) = sqrt(P_matrix(i,i)); +end % for i + +% Progress bar +dots = '....................'; +bars = '||||||||||||||||||||'; +rewind = '\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b'; +fprintf(strcat('Processing: ',dots)); +progress_mark = 0; +progress_epoch = 0; + +% Main loop +for epoch = 2:no_epochs + + % Update progress bar + if (epoch - progress_epoch) > (no_epochs/20) + progress_mark = progress_mark + 1; + progress_epoch = epoch; + fprintf(strcat(rewind,bars(1:progress_mark),... + dots(1:(20 - progress_mark)))); + end % if epoch + + % Input time from motion profile + time = in_profile(epoch,1); + + % Determine whether to update GNSS simulation + if (time - time_last_GNSS) >= GNSS_config.epoch_interval + GNSS_epoch = GNSS_epoch + 1; + tor_s = time - time_last_GNSS; % KF time interval + time_last_GNSS = time; + + % Input data from motion profile + true_L_b = in_profile(epoch,2); + true_lambda_b = in_profile(epoch,3); + true_h_b = in_profile(epoch,4); + true_v_eb_n = in_profile(epoch,5:7)'; + true_eul_nb = in_profile(epoch,8:10)'; + true_C_b_n = Euler_to_CTM(true_eul_nb)'; + [true_r_eb_e,true_v_eb_e] =... + pv_NED_to_ECEF(true_L_b,true_lambda_b,true_h_b,true_v_eb_n); + + % Determine satellite positions and velocities + [sat_r_es_e,sat_v_es_e] = Satellite_positions_and_velocities(time,... + GNSS_config); + + % Generate GNSS measurements + [GNSS_measurements,no_GNSS_meas] = Generate_GNSS_measurements(... + time,sat_r_es_e,sat_v_es_e,true_r_eb_e,true_L_b,true_lambda_b,... + true_v_eb_e,GNSS_biases,GNSS_config); + + % Update GNSS position solution + [x_est,P_matrix] = GNSS_KF_Epoch(GNSS_measurements,no_GNSS_meas,... + tor_s,x_est,P_matrix,GNSS_KF_config); + [est_L_b,est_lambda_b,est_h_b,est_v_eb_n] =... + pv_ECEF_to_NED(x_est(1:3),x_est(4:6)); + + est_C_b_n = true_C_b_n; % This sets the attitude errors to zero + + % Generate output profile record + out_profile(GNSS_epoch,1) = time; + out_profile(GNSS_epoch,2) = est_L_b; + out_profile(GNSS_epoch,3) = est_lambda_b; + out_profile(GNSS_epoch,4) = est_h_b; + out_profile(GNSS_epoch,5:7) = est_v_eb_n'; + out_profile(GNSS_epoch,8:10) = CTM_to_Euler(est_C_b_n')'; + + % Determine errors and generate output record + [delta_r_eb_n,delta_v_eb_n,delta_eul_nb_n] = Calculate_errors_NED(... + est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n,true_L_b,... + true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); + out_errors(GNSS_epoch,1) = time; + out_errors(GNSS_epoch,2:4) = delta_r_eb_n'; + out_errors(GNSS_epoch,5:7) = delta_v_eb_n'; + out_errors(GNSS_epoch,8:10) = [0;0;0]; + + % Generate clock output record + out_clock(GNSS_epoch,1) = time; + out_clock(GNSS_epoch,2:3) = x_est(7:8); + + % Generate KF uncertainty record + out_KF_SD(GNSS_epoch,1) = time; + for i =1:8 + out_KF_SD(GNSS_epoch,i+1) = sqrt(P_matrix(i,i)); + end % for i + + % Reset old values + old_time = time; + end % if time + +end %epoch + +% Complete progress bar +fprintf(strcat(rewind,bars,'\n')); + +% Ends \ No newline at end of file diff --git a/GNSS_LS_position_velocity.m b/GNSS_LS_position_velocity.m new file mode 100644 index 0000000..4bcb05d --- /dev/null +++ b/GNSS_LS_position_velocity.m @@ -0,0 +1,149 @@ +function [est_r_ea_e,est_v_ea_e,est_clock] = GNSS_LS_position_velocity(... + GNSS_measurements,no_GNSS_meas,predicted_r_ea_e,predicted_v_ea_e) +%GNSS_LS_position_velocity - Calculates position, velocity, clock offset, +%and clock drift using unweighted iterated least squares. Separate +%calculations are implemented for position and clock offset and for +%velocity and clock drift +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 11/4/2012 by Paul Groves +% +% Inputs: +% GNSS_measurements GNSS measurement data: +% Column 1 Pseudo-range measurements (m) +% Column 2 Pseudo-range rate measurements (m/s) +% Columns 3-5 Satellite ECEF position (m) +% Columns 6-8 Satellite ECEF velocity (m/s) +% no_GNSS_meas Number of satellites for which measurements are +% supplied +% predicted_r_ea_e prior predicted ECEF user position (m) +% predicted_v_ea_e prior predicted ECEF user velocity (m/s) +% +% Outputs: +% est_r_ea_e estimated ECEF user position (m) +% est_v_ea_e estimated ECEF user velocity (m/s) +% est_clock estimated receiver clock offset (m) and drift (m/s) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants (sone of these could be changed to inputs at a later date) +c = 299792458; % Speed of light in m/s +omega_ie = 7.292115E-5; % Earth rotation rate in rad/s + +% Begins + +% POSITION AND CLOCK OFFSET + +% Setup predicted state +x_pred(1:3,1) = predicted_r_ea_e; +x_pred(4,1) = 0; +test_convergence = 1; + +% Repeat until convergence +while test_convergence>0.0001 + + % Loop measurements + for j = 1:no_GNSS_meas + + % Predict approx range + delta_r = GNSS_measurements(j,3:5)' - x_pred(1:3); + approx_range = sqrt(delta_r' * delta_r); + + % Calculate frame rotation during signal transit time using (8.36) + C_e_I = [1, omega_ie * approx_range / c, 0;... + -omega_ie * approx_range / c, 1, 0;... + 0, 0, 1]; + + % Predict pseudo-range using (9.143) + delta_r = C_e_I * GNSS_measurements(j,3:5)' - x_pred(1:3); + range = sqrt(delta_r' * delta_r); + pred_meas(j,1) = range + x_pred(4); + + % Predict line of sight and deploy in measurement matrix, (9.144) + H_matrix (j,1:3) = - delta_r' / range; + H_matrix (j,4) = 1; + + end % for j + + % Unweighted least-squares solution, (9.35)/(9.141) + x_est = x_pred + inv(H_matrix(1:no_GNSS_meas,:)' *... + H_matrix(1:no_GNSS_meas,:)) * H_matrix(1:no_GNSS_meas,:)' *... + (GNSS_measurements(1:no_GNSS_meas,1) - pred_meas(1:no_GNSS_meas)); + + % Test convergence + test_convergence = sqrt((x_est - x_pred)' * (x_est - x_pred)); + + % Set predictions to estimates for next iteration + x_pred = x_est; + +end % while + +% Set outputs to estimates +est_r_ea_e(1:3,1) = x_est(1:3); +est_clock(1) = x_est(4); + +% VELOCITY AND CLOCK DRIFT + +% Skew symmetric matrix of Earth rate +Omega_ie = Skew_symmetric([0,0,omega_ie]); + +% Setup predicted state +x_pred(1:3,1) = predicted_v_ea_e; +x_pred(4,1) = 0; +test_convergence = 1; + +% Repeat until convergence +while test_convergence>0.0001 + + % Loop measurements + for j = 1:no_GNSS_meas + + % Predict approx range + delta_r = GNSS_measurements(j,3:5)' - est_r_ea_e; + approx_range = sqrt(delta_r' * delta_r); + + % Calculate frame rotation during signal transit time using (8.36) + C_e_I = [1, omega_ie * approx_range / c, 0;... + -omega_ie * approx_range / c, 1, 0;... + 0, 0, 1]; + + % Calculate range using (8.35) + delta_r = C_e_I * GNSS_measurements(j,3:5)' - est_r_ea_e; + range = sqrt(delta_r' * delta_r); + + % Calculate line of sight using (8.41) + u_as_e = delta_r / range; + + % Predict pseudo-range rate using (9.143) + range_rate = u_as_e' * (C_e_I * (GNSS_measurements(j,6:8)' +... + Omega_ie * GNSS_measurements(j,3:5)') - (x_pred(1:3) +... + Omega_ie * est_r_ea_e)); + pred_meas(j,1) = range_rate + x_pred(4); + + % Predict line of sight and deploy in measurement matrix, (9.144) + H_matrix (j,1:3) = - u_as_e'; + H_matrix (j,4) = 1; + + end % for j + + % Unweighted least-squares solution, (9.35)/(9.141) + x_est = x_pred + inv(H_matrix(1:no_GNSS_meas,:)' *... + H_matrix(1:no_GNSS_meas,:)) * H_matrix(1:no_GNSS_meas,:)' *... + (GNSS_measurements(1:no_GNSS_meas,2) - pred_meas(1:no_GNSS_meas)); + + % Test convergence + test_convergence = sqrt((x_est - x_pred)' * (x_est - x_pred)); + + % Set predictions to estimates for next iteration + x_pred = x_est; + +end % while + +% Set outputs to estimates +est_v_ea_e(1:3,1) = x_est(1:3); +est_clock(2) = x_est(4); + +% Ends \ No newline at end of file diff --git a/GNSS_Least_Squares.m b/GNSS_Least_Squares.m new file mode 100644 index 0000000..41061fd --- /dev/null +++ b/GNSS_Least_Squares.m @@ -0,0 +1,214 @@ +function [out_profile,out_errors,out_clock] = GNSS_Least_Squares(in_profile,... + no_epochs,GNSS_config) +%GNSS_Least_Squares - Simulates stand-alone GNSS using a least-squares +%positioning algorithm +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 11/4/2012 by Paul Groves +% +% Inputs: +% in_profile True motion profile array +% no_epochs Number of epochs of profile data +% GNSS_config +% .epoch_interval Interval between GNSS epochs (s) +% .init_est_r_ea_e Initial estimated position (m; ECEF) +% .no_sat Number of satellites in constellation +% .r_os Orbital radius of satellites (m) +% .inclination Inclination angle of satellites (deg) +% .const_delta_lambda Longitude offset of constellation (deg) +% .const_delta_t Timing offset of constellation (s) +% .mask_angle Mask angle (deg) +% .SIS_err_SD Signal in space error SD (m) +% .zenith_iono_err_SD Zenith ionosphere error SD (m) +% .zenith_trop_err_SD Zenith troposphere error SD (m) +% .code_track_err_SD Code tracking error SD (m) +% .rate_track_err_SD Range rate tracking error SD (m/s) +% .rx_clock_offset Receiver clock offset at time=0 (m) +% .rx_clock_drift Receiver clock drift at time=0 (m/s) +% +% Outputs: +% out_profile Navigation solution as a motion profile array +% out_errors Navigation solution error array +% out_clock Receiver clock estimate array +% +% Format of motion profiles: +% Column 1: time (sec) +% Column 2: latitude (rad) +% Column 3: longitude (rad) +% Column 4: height (m) +% Column 5: north velocity (m/s) +% Column 6: east velocity (m/s) +% Column 7: down velocity (m/s) +% Column 8: roll angle of body w.r.t NED (rad) +% Column 9: pitch angle of body w.r.t NED (rad) +% Column 10: yaw angle of body w.r.t NED (rad) +% +% Format of error array: +% Column 1: time (sec) +% Column 2: north position error (m) +% Column 3: east position error (m) +% Column 4: down position error (m) +% Column 5: north velocity error (m/s) +% Column 6: east velocity error (m/s) +% Column 7: down velocity error (m/s) +% Column 8: NOT USED (attitude error about north (rad)) +% Column 9: NOT USED (attitude error about east (rad)) +% Column 10: NOT USED (attitude error about down = heading error (rad)) +% +% Format of receiver clock array: +% Column 1: time (sec) +% Column 2: estimated clock offset (m) +% Column 3: estimated clock drift (m/s) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Initialize true navigation solution +old_time = in_profile(1,1); +true_L_b = in_profile(1,2); +true_lambda_b = in_profile(1,3); +true_h_b = in_profile(1,4); +true_v_eb_n = in_profile(1,5:7)'; +true_eul_nb = in_profile(1,8:10)'; +true_C_b_n = Euler_to_CTM(true_eul_nb)'; +[true_r_eb_e,true_v_eb_e] =... + pv_NED_to_ECEF(true_L_b,true_lambda_b,true_h_b,true_v_eb_n); + +time_last_GNSS = old_time; +GNSS_epoch = 1; + +% Determine satellite positions and velocities +[sat_r_es_e,sat_v_es_e] = Satellite_positions_and_velocities(old_time,... + GNSS_config); + +% Initialize the GNSS biases. Note that these are assumed constant throughout +% the simulation and are based on the initial elevation angles. Therefore, +% this function is unsuited to simulations longer than about 30 min. +GNSS_biases = Initialize_GNSS_biases(sat_r_es_e,true_r_eb_e,true_L_b,... + true_lambda_b,GNSS_config); + +% Generate GNSS measurements +[GNSS_measurements,no_GNSS_meas] = Generate_GNSS_measurements(old_time,... + sat_r_es_e,sat_v_es_e,true_r_eb_e,true_L_b,true_lambda_b,true_v_eb_e,... + GNSS_biases,GNSS_config); + +% Determine GNSS position solution +[est_r_eb_e,est_v_eb_e,est_clock] = GNSS_LS_position_velocity(... + GNSS_measurements,no_GNSS_meas,GNSS_config.init_est_r_ea_e,[0;0;0]); + +est_C_b_n = true_C_b_n; % This sets the attitude errors to zero + + +[est_L_b,est_lambda_b,est_h_b,est_v_eb_n] =... + pv_ECEF_to_NED(est_r_eb_e,est_v_eb_e); + +% Generate output profile record +out_profile(1,1) = old_time; +out_profile(1,2) = est_L_b; +out_profile(1,3) = est_lambda_b; +out_profile(1,4) = est_h_b; +out_profile(1,5:7) = est_v_eb_n'; +out_profile(1,8:10) = CTM_to_Euler(est_C_b_n')'; + +% Determine errors and generate output record +[delta_r_eb_n,delta_v_eb_n,delta_eul_nb_n] = Calculate_errors_NED(... + est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n,true_L_b,... + true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); +out_errors(1,1) = old_time; +out_errors(1,2:4) = delta_r_eb_n'; +out_errors(1,5:7) = delta_v_eb_n'; +out_errors(1,8:10) = [0;0;0]; + +% Generate clock output record +out_clock(1,1) = old_time; +out_clock(1,2:3) = est_clock(1:2); + +% Progress bar +dots = '....................'; +bars = '||||||||||||||||||||'; +rewind = '\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b'; +fprintf(strcat('Processing: ',dots)); +progress_mark = 0; +progress_epoch = 0; + +% Main loop +for epoch = 2:no_epochs + + % Update progress bar + if (epoch - progress_epoch) > (no_epochs/20) + progress_mark = progress_mark + 1; + progress_epoch = epoch; + fprintf(strcat(rewind,bars(1:progress_mark),... + dots(1:(20 - progress_mark)))); + end % if epoch + + % Input time from motion profile + time = in_profile(epoch,1); + + % Determine whether to update GNSS simulation + if (time - time_last_GNSS) >= GNSS_config.epoch_interval + GNSS_epoch = GNSS_epoch + 1; + time_last_GNSS = time; + + % Input data from motion profile + true_L_b = in_profile(epoch,2); + true_lambda_b = in_profile(epoch,3); + true_h_b = in_profile(epoch,4); + true_v_eb_n = in_profile(epoch,5:7)'; + true_eul_nb = in_profile(epoch,8:10)'; + true_C_b_n = Euler_to_CTM(true_eul_nb)'; + [true_r_eb_e,true_v_eb_e] =... + pv_NED_to_ECEF(true_L_b,true_lambda_b,true_h_b,true_v_eb_n); + + % Determine satellite positions and velocities + [sat_r_es_e,sat_v_es_e] = Satellite_positions_and_velocities(time,... + GNSS_config); + + % Generate GNSS measurements + [GNSS_measurements,no_GNSS_meas] = Generate_GNSS_measurements(... + time,sat_r_es_e,sat_v_es_e,true_r_eb_e,true_L_b,true_lambda_b,... + true_v_eb_e,GNSS_biases,GNSS_config); + + % Determine GNSS position solution + [est_r_eb_e,est_v_eb_e,est_clock] = GNSS_LS_position_velocity(... + GNSS_measurements,no_GNSS_meas,est_r_eb_e,est_v_eb_e); + [est_L_b,est_lambda_b,est_h_b,est_v_eb_n] =... + pv_ECEF_to_NED(est_r_eb_e,est_v_eb_e); + + est_C_b_n = true_C_b_n; % This sets the attitude errors to zero + + % Generate output profile record + out_profile(GNSS_epoch,1) = time; + out_profile(GNSS_epoch,2) = est_L_b; + out_profile(GNSS_epoch,3) = est_lambda_b; + out_profile(GNSS_epoch,4) = est_h_b; + out_profile(GNSS_epoch,5:7) = est_v_eb_n'; + out_profile(GNSS_epoch,8:10) = CTM_to_Euler(est_C_b_n')'; + + % Determine errors and generate output record + [delta_r_eb_n,delta_v_eb_n,delta_eul_nb_n] = Calculate_errors_NED(... + est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n,true_L_b,... + true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); + out_errors(GNSS_epoch,1) = time; + out_errors(GNSS_epoch,2:4) = delta_r_eb_n'; + out_errors(GNSS_epoch,5:7) = delta_v_eb_n'; + out_errors(GNSS_epoch,8:10) = [0;0;0]; + + % Generate clock output record + out_clock(GNSS_epoch,1) = time; + out_clock(GNSS_epoch,2:3) = est_clock(1:2); + + % Reset old values + old_time = time; + end % if time + +end %epoch + +% Complete progress bar +fprintf(strcat(rewind,bars,'\n')); + +% Ends \ No newline at end of file diff --git a/Generate_GNSS_measurements.m b/Generate_GNSS_measurements.m new file mode 100644 index 0000000..d2e582f --- /dev/null +++ b/Generate_GNSS_measurements.m @@ -0,0 +1,109 @@ +function [GNSS_measurements,no_GNSS_meas] = Generate_GNSS_measurements(... + time, sat_r_es_e,sat_v_es_e,r_ea_e,L_a,lambda_a,v_ea_e,... + GNSS_biases,GNSS_config) +%Generate_GNSS_measurements - Generates a set of pseudo-range and pseudo- +%range rate measurements for all satellites above the elevation mask angle +%and adds satellite positions and velocities to the datesets. +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 11/4/2012 by Paul Groves +% +% Inputs: +% time Current simulation time +% sat_r_es_e (no_sat x 3) ECEF satellite positions (m) +% sat_v_es_e (no_sat x 3) ECEF satellite velocities (m/s) +% r_ea_e ECEF user position (m) +% L_a user latitude (rad) +% lambda_a user longitude (rad) +% v_ea_e ECEF user velocity (m/s) +% GNSS_biases (no_sat) Bias-like GNSS range errors (m) +% GNSS_config +% .no_sat Number of satellites in constellation +% .mask_angle Mask angle (deg) +% .code_track_err_SD Code tracking error SD (m) +% .rate_track_err_SD Range rate tracking error SD (m/s) +% .rx_clock_offset Receiver clock offset at time=0 (m) +% .rx_clock_drift Receiver clock drift at time=0 (m/s) +% +% Outputs: +% GNSS_measurements GNSS measurement data: +% Column 1 Pseudo-range measurements (m) +% Column 2 Pseudo-range rate measurements (m/s) +% Columns 3-5 Satellite ECEF position (m) +% Columns 6-8 Satellite ECEF velocity (m/s) +% no_GNSS_meas Number of satellites for which measurements are +% supplied + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants (sone of these could be changed to inputs at a later date) +c = 299792458; % Speed of light in m/s +omega_ie = 7.292115E-5; % Earth rotation rate in rad/s + +% Begins +no_GNSS_meas = 0; + +% Calculate ECEF to NED coordinate transformation matrix using (2.150) +cos_lat = cos(L_a); +sin_lat = sin(L_a); +cos_long = cos(lambda_a); +sin_long = sin(lambda_a); +C_e_n = [-sin_lat * cos_long, -sin_lat * sin_long, cos_lat;... + -sin_long, cos_long, 0;... + -cos_lat * cos_long, -cos_lat * sin_long, -sin_lat]; + +% Skew symmetric matrix of Earth rate +Omega_ie = Skew_symmetric([0,0,omega_ie]); + +% Loop satellites +for j = 1:GNSS_config.no_sat + + % Determine ECEF line-of-sight vector using (8.41) + delta_r = sat_r_es_e(j,1:3)' - r_ea_e; + approx_range = sqrt(delta_r' * delta_r); + u_as_e = delta_r / approx_range; + + % Convert line-of-sight vector to NED using (8.39) and determine + % elevation using (8.57) + elevation = -asin(C_e_n(3,:) * u_as_e); + + % Determine if satellite is above the masking angle + if (elevation >= degtorad(GNSS_config.mask_angle)); + + % Increment number of measurements + no_GNSS_meas = no_GNSS_meas + 1; + + % Calculate frame rotation during signal transit time using (8.36) + C_e_I = [1, omega_ie * approx_range / c, 0;... + -omega_ie * approx_range / c, 1, 0;... + 0, 0, 1]; + + % Calculate range using (8.35) + delta_r = C_e_I * sat_r_es_e(j,1:3)' - r_ea_e; + range = sqrt(delta_r' * delta_r); + + % Calculate range rate using (8.44) + range_rate = u_as_e' * (C_e_I * (sat_v_es_e(j,1:3)' + Omega_ie *... + sat_r_es_e(j,1:3)') - (v_ea_e + Omega_ie * r_ea_e)); + + % Calculate pseudo-range measurement + GNSS_measurements(no_GNSS_meas,1) = range + GNSS_biases(j) +... + GNSS_config.rx_clock_offset + GNSS_config.rx_clock_drift *... + time + GNSS_config.code_track_err_SD * randn; + + % Calculate pseudo-range rate measurement + GNSS_measurements(no_GNSS_meas,2) = range_rate +... + GNSS_config.rx_clock_drift + GNSS_config.rate_track_err_SD *... + randn; + + % Append satellite position and velocity to output data + GNSS_measurements(no_GNSS_meas,3:5) = sat_r_es_e(j,1:3); + GNSS_measurements(no_GNSS_meas,6:8) = sat_v_es_e(j,1:3); + + end % elevation +end % for j + +% Ends \ No newline at end of file diff --git a/Gravitation_ECI.m b/Gravitation_ECI.m new file mode 100644 index 0000000..b281293 --- /dev/null +++ b/Gravitation_ECI.m @@ -0,0 +1,42 @@ +function gamma = Gravitation_ECI(r_ib_i) +%Gravitation_ECI - Calculates gravitational acceleration resolved about +%ECI-frame axes +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. + +% This function created 1/4/2012 by Paul Groves +% +% Inputs: +% r_ib_i Cartesian position of body frame w.r.t. ECI frame, resolved +% about ECI-frame axes (m) +% Outputs: +% gamma Acceleration due to gravitational force (m/s^2) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +%Parameters +R_0 = 6378137; %WGS84 Equatorial radius in meters +mu = 3.986004418E14; %WGS84 Earth gravitational constant (m^3 s^-2) +J_2 = 1.082627E-3; %WGS84 Earth's second gravitational constant + +% Begins + +% Calculate distance from center of the Earth +mag_r = sqrt(r_ib_i' * r_ib_i); + +% If the input position is 0,0,0, produce a dummy output +if mag_r==0 + gamma = [0;0;0]; + +% Calculate gravitational acceleration using (2.141) +else + z_scale = 5 * (r_ib_i(3) / mag_r)^2; + gamma = -mu / mag_r^3 *(r_ib_i + 1.5 * J_2 * (R_0 / mag_r)^2 *... + [(1 - z_scale) * r_ib_i(1); (1 - z_scale) * r_ib_i(2);... + (3 - z_scale) * r_ib_i(3)]); + +end % if + +% Ends \ No newline at end of file diff --git a/Gravity_ECEF.m b/Gravity_ECEF.m new file mode 100644 index 0000000..a3c8d44 --- /dev/null +++ b/Gravity_ECEF.m @@ -0,0 +1,47 @@ +function g = Gravity_ECEF(r_eb_e) +%Gravitation_ECI - Calculates acceleration due to gravity resolved about +%ECEF-frame +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 1/4/2012 by Paul Groves +% +% Inputs: +% r_eb_e Cartesian position of body frame w.r.t. ECEF frame, resolved +% about ECEF-frame axes (m) +% Outputs: +% g Acceleration due to gravity (m/s^2) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +%Parameters +R_0 = 6378137; %WGS84 Equatorial radius in meters +mu = 3.986004418E14; %WGS84 Earth gravitational constant (m^3 s^-2) +J_2 = 1.082627E-3; %WGS84 Earth's second gravitational constant +omega_ie = 7.292115E-5; % Earth rotation rate (rad/s) + +% Begins + +% Calculate distance from center of the Earth +mag_r = sqrt(r_eb_e' * r_eb_e); + +% If the input position is 0,0,0, produce a dummy output +if mag_r==0 + g = [0;0;0]; + +% Calculate gravitational acceleration using (2.142) +else + z_scale = 5 * (r_eb_e(3) / mag_r)^2; + gamma = -mu / mag_r^3 *(r_eb_e + 1.5 * J_2 * (R_0 / mag_r)^2 *... + [(1 - z_scale) * r_eb_e(1); (1 - z_scale) * r_eb_e(2);... + (3 - z_scale) * r_eb_e(3)]); + + % Add centripetal acceleration using (2.133) + g(1:2,1) = gamma(1:2) + omega_ie^2 * r_eb_e(1:2); + g(3) = gamma(3); + +end % if + +% Ends \ No newline at end of file diff --git a/Gravity_NED.m b/Gravity_NED.m new file mode 100644 index 0000000..ce8ac48 --- /dev/null +++ b/Gravity_NED.m @@ -0,0 +1,43 @@ +function g = Gravity_NED(L_b,h_b) +%Gravity_ECEF - Calculates acceleration due to gravity resolved about +%north, east, and down +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 2/4/2012 by Paul Groves +% +% Inputs: +% L_b latitude (rad) +% h_b height (m) +% Outputs: +% g Acceleration due to gravity (m/s^2) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Parameters +R_0 = 6378137; %WGS84 Equatorial radius in meters +R_P = 6356752.31425; %WGS84 Polar radius in meters +e = 0.0818191908425; %WGS84 eccentricity +f = 1 / 298.257223563; %WGS84 flattening +mu = 3.986004418E14; %WGS84 Earth gravitational constant (m^3 s^-2) +omega_ie = 7.292115E-5; % Earth rotation rate (rad/s) + +% Begins + +% Calculate surface gravity using the Somigliana model, (2.134) +sinsqL = sin(L_b)^2; +g_0 = 9.7803253359 * (1 + 0.001931853 * sinsqL) / sqrt(1 - e^2 * sinsqL); + +% Calculate north gravity using (2.140) +g(1,1) = -8.08E-9 * h_b * sin(2 * L_b); + +% East gravity is zero +g(2,1) = 0; + +% Calculate down gravity using (2.139) +g(3,1) = g_0 * (1 - (2 / R_0) * (1 + f * (1 - 2 * sinsqL) +... + (omega_ie^2 * R_0^2 * R_P / mu)) * h_b + (3 * h_b^2 / R_0^2)); + +% Ends \ No newline at end of file diff --git a/IMU_model.m b/IMU_model.m new file mode 100644 index 0000000..25372cf --- /dev/null +++ b/IMU_model.m @@ -0,0 +1,79 @@ +function [meas_f_ib_b,meas_omega_ib_b,quant_residuals] = IMU_model(tor_i,... + true_f_ib_b,true_omega_ib_b,IMU_errors,old_quant_residuals) +%IMU_model - Simulates an inertial measurement unit (IMU body axes used +%throughout this function) +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 3/4/2012 by Paul Groves +% +% Inputs: +% tor_i time interval between epochs (s) +% true_f_ib_b true specific force of body frame w.r.t. ECEF frame, resolved +% along body-frame axes, averaged over time interval (m/s^2) +% true_omega_ib_b true angular rate of body frame w.r.t. ECEF frame, resolved +% about body-frame axes, averaged over time interval (rad/s) +% IMU_errors +% .delta_r_eb_n position error resolved along NED (m) +% .b_a Accelerometer biases (m/s^2) +% .b_g Gyro biases (rad/s) +% .M_a Accelerometer scale factor and cross coupling errors +% .M_g Gyro scale factor and cross coupling errors +% .G_g Gyro g-dependent biases (rad-sec/m) +% .accel_noise_root_PSD Accelerometer noise root PSD (m s^-1.5) +% .gyro_noise_root_PSD Gyro noise root PSD (rad s^-0.5) +% .accel_quant_level Accelerometer quantization level (m/s^2) +% .gyro_quant_level Gyro quantization level (rad/s) +% old_quant_residuals residuals of previous output quantization process +% +% Outputs: +% meas_f_ib_b output specific force of body frame w.r.t. ECEF frame, resolved +% along body-frame axes, averaged over time interval (m/s^2) +% meas_omega_ib_b output angular rate of body frame w.r.t. ECEF frame, resolved +% about body-frame axes, averaged over time interval (rad/s) +% quant_residuals residuals of output quantization process + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Generate noise +if tor_i>0 + accel_noise = randn(3,1) * IMU_errors.accel_noise_root_PSD / sqrt(tor_i); + gyro_noise = randn(3,1) * IMU_errors.gyro_noise_root_PSD / sqrt(tor_i); +else + accel_noise = [0;0;0]; + gyro_noise = [0;0;0]; +end %if tor_i + +% Calculate accelerometer and gyro outputs using (4.16) and (4.17) +uq_f_ib_b = IMU_errors.b_a + (eye(3) + IMU_errors.M_a) * true_f_ib_b +... + accel_noise; +uq_omega_ib_b = IMU_errors.b_g + (eye(3) + IMU_errors.M_g) *... + true_omega_ib_b + IMU_errors.G_g * true_f_ib_b + gyro_noise; + +% Quantize accelerometer outputs +if IMU_errors.accel_quant_level>0 + meas_f_ib_b = IMU_errors.accel_quant_level * round((uq_f_ib_b +... + old_quant_residuals(1:3)) / IMU_errors.accel_quant_level); + quant_residuals(1:3,1) = uq_f_ib_b + old_quant_residuals(1:3) -... + meas_f_ib_b; +else + meas_f_ib_b = uq_f_ib_b; + quant_residuals(1:3,1) = [0;0;0]; +end %if IMU_errors.accel_quant_level + +% Quantize gyro outputs +if IMU_errors.gyro_quant_level>0 + meas_omega_ib_b = IMU_errors.gyro_quant_level * round((uq_omega_ib_b +... + old_quant_residuals(4:6)) / IMU_errors.gyro_quant_level); + quant_residuals(4:6,1) = uq_omega_ib_b + old_quant_residuals(4:6) -... + meas_omega_ib_b; +else + meas_omega_ib_b = uq_omega_ib_b; + quant_residuals(4:6,1) = [0;0;0]; +end %if IMU_errors.gyro_quant_level + +% Ends \ No newline at end of file diff --git a/INS_GNSS_Demo_1.m b/INS_GNSS_Demo_1.m new file mode 100644 index 0000000..ac9899e --- /dev/null +++ b/INS_GNSS_Demo_1.m @@ -0,0 +1,155 @@ +%INS_GNSS_Demo_1 +%SCRIPT Tightly coupled INS/GNSS demo: +% Profile_1 (60s artificial car motion with two 90 deg turns) +% Tactical-grade IMU +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 12/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_1.csv'; +% Output motion profile and error filenames +output_profile_name = 'INS_GNSS_Demo_1_Profile.csv'; +output_errors_name = 'INS_GNSS_Demo_1_Errors.csv'; + +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.05;0.04;1]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [900;-1300;800] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-9;13;-8] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [500, -300, 200;... + -150, -600, 250;... + -250, 100, 450] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [400, -300, 250;... + 0, -300, -150;... + 0, 0, -350] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0.9, -1.1, -0.6;... + -0.5, 1.9, -1.6;... + 0.3, 1.1, -1.3] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 100 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.01 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 1E-2; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 2E-4; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 0.5; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial attitude uncertainty per axis (deg, converted to rad) +TC_KF_config.init_att_unc = degtorad(1); +% Initial velocity uncertainty per axis (m/s) +TC_KF_config.init_vel_unc = 0.1; +% Initial position uncertainty per axis (m) +TC_KF_config.init_pos_unc = 10; +% Initial accelerometer bias uncertainty per instrument (micro-g, converted +% to m/s^2) +TC_KF_config.init_b_a_unc = 1000 * micro_g_to_meters_per_second_squared; +% Initial gyro bias uncertainty per instrument (deg/hour, converted to rad/sec) +TC_KF_config.init_b_g_unc = 10 * deg_to_rad / 3600; +% Initial clock offset uncertainty per axis (m) +TC_KF_config.init_clock_offset_unc = 10; +% Initial clock drift uncertainty per axis (m/s) +TC_KF_config.init_clock_drift_unc = 0.1; + +% Gyro noise PSD (deg^2 per hour, converted to rad^2/s) +TC_KF_config.gyro_noise_PSD = (0.02 * deg_to_rad / 60)^2; +% Accelerometer noise PSD (micro-g^2 per Hz, converted to m^2 s^-3) +TC_KF_config.accel_noise_PSD = (200 *... + micro_g_to_meters_per_second_squared)^2; +% Accelerometer bias random walk PSD (m^2 s^-5) +TC_KF_config.accel_bias_PSD = 1.0E-7; +% Gyro bias random walk PSD (rad^2 s^-3) +TC_KF_config.gyro_bias_PSD = 2.0E-12; +% Receiver clock frequency-drift PSD (m^2/s^3) +TC_KF_config.clock_freq_PSD = 1; +% Receiver clock phase-drift PSD (m^2/s) +TC_KF_config.clock_phase_PSD = 1; + +% Pseudo-range measurement noise SD (m) +TC_KF_config.pseudo_range_SD = 2.5; +% Pseudo-range rate measurement noise SD (m/s) +TC_KF_config.range_rate_SD = 0.1; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% Tightly coupled ECEF Inertial navigation and GNSS integrated navigation +% simulation +[out_profile,out_errors,out_IMU_bias_est,out_clock,out_KF_SD] =... + Tightly_coupled_INS_GNSS(in_profile,no_epochs,initialization_errors... + ,IMU_errors,GNSS_config,TC_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/INS_GNSS_Demo_10.m b/INS_GNSS_Demo_10.m new file mode 100644 index 0000000..080988d --- /dev/null +++ b/INS_GNSS_Demo_10.m @@ -0,0 +1,155 @@ +%INS_GNSS_Demo_10 +%SCRIPT Tightly coupled INS/GNSS demo: +% Profile_3 (418s aircraft) +% Tactical-grade IMU +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 27/5/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_3.csv'; +% Output motion profile and error filenames +output_profile_name = 'INS_GNSS_Demo_10_Profile.csv'; +output_errors_name = 'INS_GNSS_Demo_10_Errors.csv'; + +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.05;0.04;1]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [900;-1300;800] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-9;13;-8] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [500, -300, 200;... + -150, -600, 250;... + -250, 100, 450] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [400, -300, 250;... + 0, -300, -150;... + 0, 0, -350] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0.9, -1.1, -0.6;... + -0.5, 1.9, -1.6;... + 0.3, 1.1, -1.3] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 100 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.01 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 1E-2; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 2E-4; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 0.5; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial attitude uncertainty per axis (deg, converted to rad) +TC_KF_config.init_att_unc = degtorad(1); +% Initial velocity uncertainty per axis (m/s) +TC_KF_config.init_vel_unc = 0.1; +% Initial position uncertainty per axis (m) +TC_KF_config.init_pos_unc = 10; +% Initial accelerometer bias uncertainty per instrument (micro-g, converted +% to m/s^2) +TC_KF_config.init_b_a_unc = 1000 * micro_g_to_meters_per_second_squared; +% Initial gyro bias uncertainty per instrument (deg/hour, converted to rad/sec) +TC_KF_config.init_b_g_unc = 10 * deg_to_rad / 3600; +% Initial clock offset uncertainty per axis (m) +TC_KF_config.init_clock_offset_unc = 10; +% Initial clock drift uncertainty per axis (m/s) +TC_KF_config.init_clock_drift_unc = 0.1; + +% Gyro noise PSD (deg^2 per hour, converted to rad^2/s) +TC_KF_config.gyro_noise_PSD = (0.02 * deg_to_rad / 60)^2; +% Accelerometer noise PSD (micro-g^2 per Hz, converted to m^2 s^-3) +TC_KF_config.accel_noise_PSD = (200 *... + micro_g_to_meters_per_second_squared)^2; +% Accelerometer bias random walk PSD (m^2 s^-5) +TC_KF_config.accel_bias_PSD = 1.0E-7; +% Gyro bias random walk PSD (rad^2 s^-3) +TC_KF_config.gyro_bias_PSD = 2.0E-12; +% Receiver clock frequency-drift PSD (m^2/s^3) +TC_KF_config.clock_freq_PSD = 1; +% Receiver clock phase-drift PSD (m^2/s) +TC_KF_config.clock_phase_PSD = 1; + +% Pseudo-range measurement noise SD (m) +TC_KF_config.pseudo_range_SD = 2.5; +% Pseudo-range rate measurement noise SD (m/s) +TC_KF_config.range_rate_SD = 0.1; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% Tightly coupled ECEF Inertial navigation and GNSS integrated navigation +% simulation +[out_profile,out_errors,out_IMU_bias_est,out_clock,out_KF_SD] =... + Tightly_coupled_INS_GNSS(in_profile,no_epochs,initialization_errors... + ,IMU_errors,GNSS_config,TC_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/INS_GNSS_Demo_11.m b/INS_GNSS_Demo_11.m new file mode 100644 index 0000000..398f86f --- /dev/null +++ b/INS_GNSS_Demo_11.m @@ -0,0 +1,155 @@ +%INS_GNSS_Demo_11 +%SCRIPT Tightly coupled INS/GNSS demo: +% Profile_4 (300s boat) +% Tactical-grade IMU +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 27/5/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_4.csv'; +% Output motion profile and error filenames +output_profile_name = 'INS_GNSS_Demo_11_Profile.csv'; +output_errors_name = 'INS_GNSS_Demo_11_Errors.csv'; + +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.05;0.04;1]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [900;-1300;800] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-9;13;-8] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [500, -300, 200;... + -150, -600, 250;... + -250, 100, 450] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [400, -300, 250;... + 0, -300, -150;... + 0, 0, -350] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0.9, -1.1, -0.6;... + -0.5, 1.9, -1.6;... + 0.3, 1.1, -1.3] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 100 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.01 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 1E-2; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 2E-4; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 0.5; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial attitude uncertainty per axis (deg, converted to rad) +TC_KF_config.init_att_unc = degtorad(1); +% Initial velocity uncertainty per axis (m/s) +TC_KF_config.init_vel_unc = 0.1; +% Initial position uncertainty per axis (m) +TC_KF_config.init_pos_unc = 10; +% Initial accelerometer bias uncertainty per instrument (micro-g, converted +% to m/s^2) +TC_KF_config.init_b_a_unc = 1000 * micro_g_to_meters_per_second_squared; +% Initial gyro bias uncertainty per instrument (deg/hour, converted to rad/sec) +TC_KF_config.init_b_g_unc = 10 * deg_to_rad / 3600; +% Initial clock offset uncertainty per axis (m) +TC_KF_config.init_clock_offset_unc = 10; +% Initial clock drift uncertainty per axis (m/s) +TC_KF_config.init_clock_drift_unc = 0.1; + +% Gyro noise PSD (deg^2 per hour, converted to rad^2/s) +TC_KF_config.gyro_noise_PSD = (0.02 * deg_to_rad / 60)^2; +% Accelerometer noise PSD (micro-g^2 per Hz, converted to m^2 s^-3) +TC_KF_config.accel_noise_PSD = (200 *... + micro_g_to_meters_per_second_squared)^2; +% Accelerometer bias random walk PSD (m^2 s^-5) +TC_KF_config.accel_bias_PSD = 1.0E-7; +% Gyro bias random walk PSD (rad^2 s^-3) +TC_KF_config.gyro_bias_PSD = 2.0E-12; +% Receiver clock frequency-drift PSD (m^2/s^3) +TC_KF_config.clock_freq_PSD = 1; +% Receiver clock phase-drift PSD (m^2/s) +TC_KF_config.clock_phase_PSD = 1; + +% Pseudo-range measurement noise SD (m) +TC_KF_config.pseudo_range_SD = 2.5; +% Pseudo-range rate measurement noise SD (m/s) +TC_KF_config.range_rate_SD = 0.1; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% Tightly coupled ECEF Inertial navigation and GNSS integrated navigation +% simulation +[out_profile,out_errors,out_IMU_bias_est,out_clock,out_KF_SD] =... + Tightly_coupled_INS_GNSS(in_profile,no_epochs,initialization_errors... + ,IMU_errors,GNSS_config,TC_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/INS_GNSS_Demo_12.m b/INS_GNSS_Demo_12.m new file mode 100644 index 0000000..182f478 --- /dev/null +++ b/INS_GNSS_Demo_12.m @@ -0,0 +1,155 @@ +%INS_GNSS_Demo_12 +%SCRIPT Tightly coupled INS/GNSS demo: +% Profile_3 (418s aircraft) +% Aviation-grade IMU +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 27/5/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_3.csv'; +% Output motion profile and error filenames +output_profile_name = 'INS_GNSS_Demo_12_Profile.csv'; +output_errors_name = 'INS_GNSS_Demo_12_Errors.csv'; + +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.01;0.008;0.01]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [30;-45;26] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-0.0009;0.0013;-0.0008] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [100, -120, 80;... + -60, -120, 100;... + -100, 40, 90] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [8, -120, 100;... + 0, -6, -60;... + 0, 0, -7] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0, 0, 0;... + 0, 0, 0;... + 0, 0, 0] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 20 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.002 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 5E-5; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 1E-6; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 0.5; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial attitude uncertainty per axis (deg, converted to rad) +TC_KF_config.init_att_unc = degtorad(0.01); +% Initial velocity uncertainty per axis (m/s) +TC_KF_config.init_vel_unc = 0.1; +% Initial position uncertainty per axis (m) +TC_KF_config.init_pos_unc = 10; +% Initial accelerometer bias uncertainty per instrument (micro-g, converted +% to m/s^2) +TC_KF_config.init_b_a_unc = 30 * micro_g_to_meters_per_second_squared; +% Initial gyro bias uncertainty per instrument (deg/hour, converted to rad/sec) +TC_KF_config.init_b_g_unc = 0.001 * deg_to_rad / 3600; +% Initial clock offset uncertainty per axis (m) +TC_KF_config.init_clock_offset_unc = 10; +% Initial clock drift uncertainty per axis (m/s) +TC_KF_config.init_clock_drift_unc = 0.1; + +% Gyro noise PSD (deg^2 per hour, converted to rad^2/s) +TC_KF_config.gyro_noise_PSD = (0.004 * deg_to_rad / 60)^2; +% Accelerometer noise PSD (micro-g^2 per Hz, converted to m^2 s^-3) +TC_KF_config.accel_noise_PSD = (40 *... + micro_g_to_meters_per_second_squared)^2; +% Accelerometer bias random walk PSD (m^2 s^-5) +TC_KF_config.accel_bias_PSD = 3.0E-9; +% Gyro bias random walk PSD (rad^2 s^-3) +TC_KF_config.gyro_bias_PSD = 2.0E-16; +% Receiver clock frequency-drift PSD (m^2/s^3) +TC_KF_config.clock_freq_PSD = 1; +% Receiver clock phase-drift PSD (m^2/s) +TC_KF_config.clock_phase_PSD = 1; + +% Pseudo-range measurement noise SD (m) +TC_KF_config.pseudo_range_SD = 2.5; +% Pseudo-range rate measurement noise SD (m/s) +TC_KF_config.range_rate_SD = 0.1; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% Tightly coupled ECEF Inertial navigation and GNSS integrated navigation +% simulation +[out_profile,out_errors,out_IMU_bias_est,out_clock,out_KF_SD] =... + Tightly_coupled_INS_GNSS(in_profile,no_epochs,initialization_errors... + ,IMU_errors,GNSS_config,TC_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/INS_GNSS_Demo_2.m b/INS_GNSS_Demo_2.m new file mode 100644 index 0000000..371c771 --- /dev/null +++ b/INS_GNSS_Demo_2.m @@ -0,0 +1,155 @@ +%INS_GNSS_Demo_2 +%SCRIPT Tightly coupled INS/GNSS demo: +% Profile_0 (Stationary) +% Tactical-grade IMU +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 12/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_0.csv'; +% Output motion profile and error filenames +output_profile_name = 'INS_GNSS_Demo_2_Profile.csv'; +output_errors_name = 'INS_GNSS_Demo_2_Errors.csv'; + +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.05;0.04;1]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [900;-1300;800] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-9;13;-8] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [500, -300, 200;... + -150, -600, 250;... + -250, 100, 450] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [400, -300, 250;... + 0, -300, -150;... + 0, 0, -350] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0.9, -1.1, -0.6;... + -0.5, 1.9, -1.6;... + 0.3, 1.1, -1.3] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 100 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.01 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 1E-2; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 2E-4; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 0.5; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial attitude uncertainty per axis (deg, converted to rad) +TC_KF_config.init_att_unc = degtorad(1); +% Initial velocity uncertainty per axis (m/s) +TC_KF_config.init_vel_unc = 0.1; +% Initial position uncertainty per axis (m) +TC_KF_config.init_pos_unc = 10; +% Initial accelerometer bias uncertainty per instrument (micro-g, converted +% to m/s^2) +TC_KF_config.init_b_a_unc = 1000 * micro_g_to_meters_per_second_squared; +% Initial gyro bias uncertainty per instrument (deg/hour, converted to rad/sec) +TC_KF_config.init_b_g_unc = 10 * deg_to_rad / 3600; +% Initial clock offset uncertainty per axis (m) +TC_KF_config.init_clock_offset_unc = 10; +% Initial clock drift uncertainty per axis (m/s) +TC_KF_config.init_clock_drift_unc = 0.1; + +% Gyro noise PSD (deg^2 per hour, converted to rad^2/s) +TC_KF_config.gyro_noise_PSD = (0.02 * deg_to_rad / 60)^2; +% Accelerometer noise PSD (micro-g^2 per Hz, converted to m^2 s^-3) +TC_KF_config.accel_noise_PSD = (200 *... + micro_g_to_meters_per_second_squared)^2; +% Accelerometer bias random walk PSD (m^2 s^-5) +TC_KF_config.accel_bias_PSD = 1.0E-7; +% Gyro bias random walk PSD (rad^2 s^-3) +TC_KF_config.gyro_bias_PSD = 2.0E-12; +% Receiver clock frequency-drift PSD (m^2/s^3) +TC_KF_config.clock_freq_PSD = 1; +% Receiver clock phase-drift PSD (m^2/s) +TC_KF_config.clock_phase_PSD = 1; + +% Pseudo-range measurement noise SD (m) +TC_KF_config.pseudo_range_SD = 2.5; +% Pseudo-range rate measurement noise SD (m/s) +TC_KF_config.range_rate_SD = 0.1; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% Tightly coupled ECEF Inertial navigation and GNSS integrated navigation +% simulation +[out_profile,out_errors,out_IMU_bias_est,out_clock,out_KF_SD] =... + Tightly_coupled_INS_GNSS(in_profile,no_epochs,initialization_errors... + ,IMU_errors,GNSS_config,TC_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/INS_GNSS_Demo_3.m b/INS_GNSS_Demo_3.m new file mode 100644 index 0000000..3c694c4 --- /dev/null +++ b/INS_GNSS_Demo_3.m @@ -0,0 +1,147 @@ +%INS_GNSS_Demo_3 +%SCRIPT Loosely coupled INS/GNSS demo: +% Profile_1 (60s artificial car motion with two 90 deg turns) +% Tactical-grade IMU +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 12/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_1.csv'; +% Output motion profile and error filenames +output_profile_name = 'INS_GNSS_Demo_3_Profile.csv'; +output_errors_name = 'INS_GNSS_Demo_3_Errors.csv'; + +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.05;0.04;1]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [900;-1300;800] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-9;13;-8] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [500, -300, 200;... + -150, -600, 250;... + -250, 100, 450] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [400, -300, 250;... + 0, -300, -150;... + 0, 0, -350] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0.9, -1.1, -0.6;... + -0.5, 1.9, -1.6;... + 0.3, 1.1, -1.3] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 100 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.01 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 1E-2; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 2E-4; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 0.5; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial attitude uncertainty per axis (deg, converted to rad) +LC_KF_config.init_att_unc = degtorad(1); +% Initial velocity uncertainty per axis (m/s) +LC_KF_config.init_vel_unc = 0.1; +% Initial position uncertainty per axis (m) +LC_KF_config.init_pos_unc = 10; +% Initial accelerometer bias uncertainty per instrument (micro-g, converted +% to m/s^2) +LC_KF_config.init_b_a_unc = 1000 * micro_g_to_meters_per_second_squared; +% Initial gyro bias uncertainty per instrument (deg/hour, converted to rad/sec) +LC_KF_config.init_b_g_unc = 10 * deg_to_rad / 3600; + +% Gyro noise PSD (deg^2 per hour, converted to rad^2/s) +LC_KF_config.gyro_noise_PSD = (0.02 * deg_to_rad / 60)^2; +% Accelerometer noise PSD (micro-g^2 per Hz, converted to m^2 s^-3) +LC_KF_config.accel_noise_PSD = (200 *... + micro_g_to_meters_per_second_squared)^2; +% Accelerometer bias random walk PSD (m^2 s^-5) +LC_KF_config.accel_bias_PSD = 1.0E-7; +% Gyro bias random walk PSD (rad^2 s^-3) +LC_KF_config.gyro_bias_PSD = 2.0E-12; + +% Position measurement noise SD per axis (m) +LC_KF_config.pos_meas_SD = 2.5; +% Velocity measurement noise SD per axis (m/s) +LC_KF_config.vel_meas_SD = 0.1; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% Tightly coupled ECEF Inertial navigation and GNSS integrated navigation +% simulation +[out_profile,out_errors,out_IMU_bias_est,out_clock,out_KF_SD] =... + Loosely_coupled_INS_GNSS(in_profile,no_epochs,initialization_errors... + ,IMU_errors,GNSS_config,LC_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/INS_GNSS_Demo_4.m b/INS_GNSS_Demo_4.m new file mode 100644 index 0000000..9615e75 --- /dev/null +++ b/INS_GNSS_Demo_4.m @@ -0,0 +1,147 @@ +%INS_GNSS_Demo_4 +%SCRIPT Loosely coupled INS/GNSS demo: +% Profile_0 (Stationary) +% Tactical-grade IMU +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 12/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_0.csv'; +% Output motion profile and error filenames +output_profile_name = 'INS_GNSS_Demo_4_Profile.csv'; +output_errors_name = 'INS_GNSS_Demo_4_Errors.csv'; + +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.05;0.04;1]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [900;-1300;800] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-9;13;-8] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [500, -300, 200;... + -150, -600, 250;... + -250, 100, 450] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [400, -300, 250;... + 0, -300, -150;... + 0, 0, -350] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0.9, -1.1, -0.6;... + -0.5, 1.9, -1.6;... + 0.3, 1.1, -1.3] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 100 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.01 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 1E-2; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 2E-4; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 0.5; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial attitude uncertainty per axis (deg, converted to rad) +LC_KF_config.init_att_unc = degtorad(1); +% Initial velocity uncertainty per axis (m/s) +LC_KF_config.init_vel_unc = 0.1; +% Initial position uncertainty per axis (m) +LC_KF_config.init_pos_unc = 10; +% Initial accelerometer bias uncertainty per instrument (micro-g, converted +% to m/s^2) +LC_KF_config.init_b_a_unc = 1000 * micro_g_to_meters_per_second_squared; +% Initial gyro bias uncertainty per instrument (deg/hour, converted to rad/sec) +LC_KF_config.init_b_g_unc = 10 * deg_to_rad / 3600; + +% Gyro noise PSD (deg^2 per hour, converted to rad^2/s) +LC_KF_config.gyro_noise_PSD = (0.02 * deg_to_rad / 60)^2; +% Accelerometer noise PSD (micro-g^2 per Hz, converted to m^2 s^-3) +LC_KF_config.accel_noise_PSD = (200 *... + micro_g_to_meters_per_second_squared)^2; +% Accelerometer bias random walk PSD (m^2 s^-5) +LC_KF_config.accel_bias_PSD = 1.0E-7; +% Gyro bias random walk PSD (rad^2 s^-3) +LC_KF_config.gyro_bias_PSD = 2.0E-12; + +% Position measurement noise SD per axis (m) +LC_KF_config.pos_meas_SD = 2.5; +% Velocity measurement noise SD per axis (m/s) +LC_KF_config.vel_meas_SD = 0.1; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% Tightly coupled ECEF Inertial navigation and GNSS integrated navigation +% simulation +[out_profile,out_errors,out_IMU_bias_est,out_clock,out_KF_SD] =... + Loosely_coupled_INS_GNSS(in_profile,no_epochs,initialization_errors... + ,IMU_errors,GNSS_config,LC_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/INS_GNSS_Demo_5.m b/INS_GNSS_Demo_5.m new file mode 100644 index 0000000..f97b7d5 --- /dev/null +++ b/INS_GNSS_Demo_5.m @@ -0,0 +1,155 @@ +%INS_GNSS_Demo_5 +%SCRIPT Tightly coupled INS/GNSS demo: +% Profile_1 (60s artificial car motion with two 90 deg turns) +% Aviation-grade IMU +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 13/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_1.csv'; +% Output motion profile and error filenames +output_profile_name = 'INS_GNSS_Demo_5_Profile.csv'; +output_errors_name = 'INS_GNSS_Demo_5_Errors.csv'; + +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.01;0.008;0.01]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [30;-45;26] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-0.0009;0.0013;-0.0008] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [100, -120, 80;... + -60, -120, 100;... + -100, 40, 90] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [8, -120, 100;... + 0, -6, -60;... + 0, 0, -7] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0, 0, 0;... + 0, 0, 0;... + 0, 0, 0] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 20 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.002 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 5E-5; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 1E-6; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 0.5; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial attitude uncertainty per axis (deg, converted to rad) +TC_KF_config.init_att_unc = degtorad(0.01); +% Initial velocity uncertainty per axis (m/s) +TC_KF_config.init_vel_unc = 0.1; +% Initial position uncertainty per axis (m) +TC_KF_config.init_pos_unc = 10; +% Initial accelerometer bias uncertainty per instrument (micro-g, converted +% to m/s^2) +TC_KF_config.init_b_a_unc = 30 * micro_g_to_meters_per_second_squared; +% Initial gyro bias uncertainty per instrument (deg/hour, converted to rad/sec) +TC_KF_config.init_b_g_unc = 0.001 * deg_to_rad / 3600; +% Initial clock offset uncertainty per axis (m) +TC_KF_config.init_clock_offset_unc = 10; +% Initial clock drift uncertainty per axis (m/s) +TC_KF_config.init_clock_drift_unc = 0.1; + +% Gyro noise PSD (deg^2 per hour, converted to rad^2/s) +TC_KF_config.gyro_noise_PSD = (0.004 * deg_to_rad / 60)^2; +% Accelerometer noise PSD (micro-g^2 per Hz, converted to m^2 s^-3) +TC_KF_config.accel_noise_PSD = (40 *... + micro_g_to_meters_per_second_squared)^2; +% Accelerometer bias random walk PSD (m^2 s^-5) +TC_KF_config.accel_bias_PSD = 3.0E-9; +% Gyro bias random walk PSD (rad^2 s^-3) +TC_KF_config.gyro_bias_PSD = 2.0E-16; +% Receiver clock frequency-drift PSD (m^2/s^3) +TC_KF_config.clock_freq_PSD = 1; +% Receiver clock phase-drift PSD (m^2/s) +TC_KF_config.clock_phase_PSD = 1; + +% Pseudo-range measurement noise SD (m) +TC_KF_config.pseudo_range_SD = 2.5; +% Pseudo-range rate measurement noise SD (m/s) +TC_KF_config.range_rate_SD = 0.1; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% Tightly coupled ECEF Inertial navigation and GNSS integrated navigation +% simulation +[out_profile,out_errors,out_IMU_bias_est,out_clock,out_KF_SD] =... + Tightly_coupled_INS_GNSS(in_profile,no_epochs,initialization_errors... + ,IMU_errors,GNSS_config,TC_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/INS_GNSS_Demo_6.m b/INS_GNSS_Demo_6.m new file mode 100644 index 0000000..db38c08 --- /dev/null +++ b/INS_GNSS_Demo_6.m @@ -0,0 +1,155 @@ +%INS_GNSS_Demo_6 +%SCRIPT Tightly coupled INS/GNSS demo: +% Profile_0 (Stationary) +% Aviation-grade IMU +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 13/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_0.csv'; +% Output motion profile and error filenames +output_profile_name = 'INS_GNSS_Demo_6_Profile.csv'; +output_errors_name = 'INS_GNSS_Demo_6_Errors.csv'; + +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.01;0.008;0.01]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [30;-45;26] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-0.0009;0.0013;-0.0008] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [100, -120, 80;... + -60, -120, 100;... + -100, 40, 90] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [8, -120, 100;... + 0, -6, -60;... + 0, 0, -7] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0, 0, 0;... + 0, 0, 0;... + 0, 0, 0] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 20 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.002 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 5E-5; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 1E-6; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 0.5; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial attitude uncertainty per axis (deg, converted to rad) +TC_KF_config.init_att_unc = degtorad(0.01); +% Initial velocity uncertainty per axis (m/s) +TC_KF_config.init_vel_unc = 0.1; +% Initial position uncertainty per axis (m) +TC_KF_config.init_pos_unc = 10; +% Initial accelerometer bias uncertainty per instrument (micro-g, converted +% to m/s^2) +TC_KF_config.init_b_a_unc = 30 * micro_g_to_meters_per_second_squared; +% Initial gyro bias uncertainty per instrument (deg/hour, converted to rad/sec) +TC_KF_config.init_b_g_unc = 0.001 * deg_to_rad / 3600; +% Initial clock offset uncertainty per axis (m) +TC_KF_config.init_clock_offset_unc = 10; +% Initial clock drift uncertainty per axis (m/s) +TC_KF_config.init_clock_drift_unc = 0.1; + +% Gyro noise PSD (deg^2 per hour, converted to rad^2/s) +TC_KF_config.gyro_noise_PSD = (0.004 * deg_to_rad / 60)^2; +% Accelerometer noise PSD (micro-g^2 per Hz, converted to m^2 s^-3) +TC_KF_config.accel_noise_PSD = (40 *... + micro_g_to_meters_per_second_squared)^2; +% Accelerometer bias random walk PSD (m^2 s^-5) +TC_KF_config.accel_bias_PSD = 3.0E-9; +% Gyro bias random walk PSD (rad^2 s^-3) +TC_KF_config.gyro_bias_PSD = 2.0E-16; +% Receiver clock frequency-drift PSD (m^2/s^3) +TC_KF_config.clock_freq_PSD = 1; +% Receiver clock phase-drift PSD (m^2/s) +TC_KF_config.clock_phase_PSD = 1; + +% Pseudo-range measurement noise SD (m) +TC_KF_config.pseudo_range_SD = 2.5; +% Pseudo-range rate measurement noise SD (m/s) +TC_KF_config.range_rate_SD = 0.1; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% Tightly coupled ECEF Inertial navigation and GNSS integrated navigation +% simulation +[out_profile,out_errors,out_IMU_bias_est,out_clock,out_KF_SD] =... + Tightly_coupled_INS_GNSS(in_profile,no_epochs,initialization_errors... + ,IMU_errors,GNSS_config,TC_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/INS_GNSS_Demo_7.m b/INS_GNSS_Demo_7.m new file mode 100644 index 0000000..7bad06f --- /dev/null +++ b/INS_GNSS_Demo_7.m @@ -0,0 +1,157 @@ +%INS_GNSS_Demo_7 +%SCRIPT Tightly coupled INS/GNSS demo: +% Profile_1 (60s artificial car motion with two 90 deg turns) +% Consumer-grade IMU +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 12/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_1.csv'; +% Output motion profile and error filenames +output_profile_name = 'INS_GNSS_Demo_7_Profile.csv'; +output_errors_name = 'INS_GNSS_Demo_7_Errors.csv'; + +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.5;0.4;2]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [9000;-13000;8000] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-180;260;-160] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [50000, -15000, 10000;... + -7500, -60000, 12500;... + -12500, 5000, 20000] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [40000, -14000, 12500;... + 0, -30000, -7500;... + 0, 0, -17500] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [90, -110, -60;... + -50, 190, -160;... + 30, 110, -130] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 1000 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 1 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 1E-1; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 2E-3; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 0.5; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial attitude uncertainty per axis (deg, converted to rad) +TC_KF_config.init_att_unc = degtorad(2); +% Initial velocity uncertainty per axis (m/s) +TC_KF_config.init_vel_unc = 0.1; +% Initial position uncertainty per axis (m) +TC_KF_config.init_pos_unc = 10; +% Initial accelerometer bias uncertainty per instrument (micro-g, converted +% to m/s^2) +TC_KF_config.init_b_a_unc = 10000 * micro_g_to_meters_per_second_squared; +% Initial gyro bias uncertainty per instrument (deg/hour, converted to rad/sec) +TC_KF_config.init_b_g_unc = 200 * deg_to_rad / 3600; +% Initial clock offset uncertainty per axis (m) +TC_KF_config.init_clock_offset_unc = 10; +% Initial clock drift uncertainty per axis (m/s) +TC_KF_config.init_clock_drift_unc = 0.1; + +% Gyro noise PSD (deg^2 per hour, converted to rad^2/s) +TC_KF_config.gyro_noise_PSD = 0.01^2; +% Accelerometer noise PSD (micro-g^2 per Hz, converted to m^2 s^-3) +TC_KF_config.accel_noise_PSD = 0.2^2; +% NOTE: A large noise PSD is modeled to account for the scale-factor and +% cross-coupling errors that are not directly included in the Kalman filter +% model +% Accelerometer bias random walk PSD (m^2 s^-5) +TC_KF_config.accel_bias_PSD = 1.0E-5; +% Gyro bias random walk PSD (rad^2 s^-3) +TC_KF_config.gyro_bias_PSD = 4.0E-11; +% Receiver clock frequency-drift PSD (m^2/s^3) +TC_KF_config.clock_freq_PSD = 1; +% Receiver clock phase-drift PSD (m^2/s) +TC_KF_config.clock_phase_PSD = 1; + +% Pseudo-range measurement noise SD (m) +TC_KF_config.pseudo_range_SD = 2.5; +% Pseudo-range rate measurement noise SD (m/s) +TC_KF_config.range_rate_SD = 0.1; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% Tightly coupled ECEF Inertial navigation and GNSS integrated navigation +% simulation +[out_profile,out_errors,out_IMU_bias_est,out_clock,out_KF_SD] =... + Tightly_coupled_INS_GNSS(in_profile,no_epochs,initialization_errors... + ,IMU_errors,GNSS_config,TC_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/INS_GNSS_Demo_8.m b/INS_GNSS_Demo_8.m new file mode 100644 index 0000000..2853164 --- /dev/null +++ b/INS_GNSS_Demo_8.m @@ -0,0 +1,157 @@ +%INS_GNSS_Demo_8 +%SCRIPT Tightly coupled INS/GNSS demo: +% Profile_0 (Stationary) +% Consumer-grade IMU +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 12/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_0.csv'; +% Output motion profile and error filenames +output_profile_name = 'INS_GNSS_Demo_8_Profile.csv'; +output_errors_name = 'INS_GNSS_Demo_8_Errors.csv'; + +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.5;0.4;2]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [9000;-13000;8000] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-180;260;-160] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [50000, -15000, 10000;... + -7500, -60000, 12500;... + -12500, 5000, 20000] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [40000, -14000, 12500;... + 0, -30000, -7500;... + 0, 0, -17500] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [90, -110, -60;... + -50, 190, -160;... + 30, 110, -130] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 1000 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 1 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 1E-1; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 2E-3; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 0.5; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial attitude uncertainty per axis (deg, converted to rad) +TC_KF_config.init_att_unc = degtorad(2); +% Initial velocity uncertainty per axis (m/s) +TC_KF_config.init_vel_unc = 0.1; +% Initial position uncertainty per axis (m) +TC_KF_config.init_pos_unc = 10; +% Initial accelerometer bias uncertainty per instrument (micro-g, converted +% to m/s^2) +TC_KF_config.init_b_a_unc = 10000 * micro_g_to_meters_per_second_squared; +% Initial gyro bias uncertainty per instrument (deg/hour, converted to rad/sec) +TC_KF_config.init_b_g_unc = 200 * deg_to_rad / 3600; +% Initial clock offset uncertainty per axis (m) +TC_KF_config.init_clock_offset_unc = 10; +% Initial clock drift uncertainty per axis (m/s) +TC_KF_config.init_clock_drift_unc = 0.1; + +% Gyro noise PSD (deg^2 per hour, converted to rad^2/s) +TC_KF_config.gyro_noise_PSD = 0.01^2; +% Accelerometer noise PSD (micro-g^2 per Hz, converted to m^2 s^-3) +TC_KF_config.accel_noise_PSD = 0.2^2; +% NOTE: A large noise PSD is modeled to account for the scale-factor and +% cross-coupling errors that are not directly included in the Kalman filter +% model +% Accelerometer bias random walk PSD (m^2 s^-5) +TC_KF_config.accel_bias_PSD = 1.0E-5; +% Gyro bias random walk PSD (rad^2 s^-3) +TC_KF_config.gyro_bias_PSD = 4.0E-11; +% Receiver clock frequency-drift PSD (m^2/s^3) +TC_KF_config.clock_freq_PSD = 1; +% Receiver clock phase-drift PSD (m^2/s) +TC_KF_config.clock_phase_PSD = 1; + +% Pseudo-range measurement noise SD (m) +TC_KF_config.pseudo_range_SD = 2.5; +% Pseudo-range rate measurement noise SD (m/s) +TC_KF_config.range_rate_SD = 0.1; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% Tightly coupled ECEF Inertial navigation and GNSS integrated navigation +% simulation +[out_profile,out_errors,out_IMU_bias_est,out_clock,out_KF_SD] =... + Tightly_coupled_INS_GNSS(in_profile,no_epochs,initialization_errors... + ,IMU_errors,GNSS_config,TC_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/INS_GNSS_Demo_9.m b/INS_GNSS_Demo_9.m new file mode 100644 index 0000000..cf3f34b --- /dev/null +++ b/INS_GNSS_Demo_9.m @@ -0,0 +1,155 @@ +%INS_GNSS_Demo_9 +%SCRIPT Tightly coupled INS/GNSS demo: +% Profile_2 (175s car) +% Tactical-grade IMU +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 27/5/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_2.csv'; +% Output motion profile and error filenames +output_profile_name = 'INS_GNSS_Demo_9_Profile.csv'; +output_errors_name = 'INS_GNSS_Demo_9_Errors.csv'; + +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.05;0.04;1]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [900;-1300;800] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-9;13;-8] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [500, -300, 200;... + -150, -600, 250;... + -250, 100, 450] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [400, -300, 250;... + 0, -300, -150;... + 0, 0, -350] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0.9, -1.1, -0.6;... + -0.5, 1.9, -1.6;... + 0.3, 1.1, -1.3] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 100 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.01 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 1E-2; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 2E-4; + +% Interval between GNSS epochs (s) +GNSS_config.epoch_interval = 0.5; + +% Initial estimated position (m; ECEF) +GNSS_config.init_est_r_ea_e = [0;0;0]; + +% Number of satellites in constellation +GNSS_config.no_sat = 30; +% Orbital radius of satellites (m) +GNSS_config.r_os = 2.656175E7; +% Inclination angle of satellites (deg) +GNSS_config.inclination = 55; +% Longitude offset of constellation (deg) +GNSS_config.const_delta_lambda = 0; +% Timing offset of constellation (s) +GNSS_config.const_delta_t = 0; + +% Mask angle (deg) +GNSS_config.mask_angle = 10; +% Signal in space error SD (m) *Give residual where corrections are applied +GNSS_config.SIS_err_SD = 1; +% Zenith ionosphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_iono_err_SD = 2; +% Zenith troposphere error SD (m) *Give residual where corrections are applied +GNSS_config.zenith_trop_err_SD = 0.2; +% Code tracking error SD (m) *Can extend to account for multipath +GNSS_config.code_track_err_SD = 1; +% Range rate tracking error SD (m/s) *Can extend to account for multipath +GNSS_config.rate_track_err_SD = 0.02; +% Receiver clock offset at time=0 (m); +GNSS_config.rx_clock_offset = 10000; +% Receiver clock drift at time=0 (m/s); +GNSS_config.rx_clock_drift = 100; + +% Initial attitude uncertainty per axis (deg, converted to rad) +TC_KF_config.init_att_unc = degtorad(1); +% Initial velocity uncertainty per axis (m/s) +TC_KF_config.init_vel_unc = 0.1; +% Initial position uncertainty per axis (m) +TC_KF_config.init_pos_unc = 10; +% Initial accelerometer bias uncertainty per instrument (micro-g, converted +% to m/s^2) +TC_KF_config.init_b_a_unc = 1000 * micro_g_to_meters_per_second_squared; +% Initial gyro bias uncertainty per instrument (deg/hour, converted to rad/sec) +TC_KF_config.init_b_g_unc = 10 * deg_to_rad / 3600; +% Initial clock offset uncertainty per axis (m) +TC_KF_config.init_clock_offset_unc = 10; +% Initial clock drift uncertainty per axis (m/s) +TC_KF_config.init_clock_drift_unc = 0.1; + +% Gyro noise PSD (deg^2 per hour, converted to rad^2/s) +TC_KF_config.gyro_noise_PSD = (0.02 * deg_to_rad / 60)^2; +% Accelerometer noise PSD (micro-g^2 per Hz, converted to m^2 s^-3) +TC_KF_config.accel_noise_PSD = (200 *... + micro_g_to_meters_per_second_squared)^2; +% Accelerometer bias random walk PSD (m^2 s^-5) +TC_KF_config.accel_bias_PSD = 1.0E-7; +% Gyro bias random walk PSD (rad^2 s^-3) +TC_KF_config.gyro_bias_PSD = 2.0E-12; +% Receiver clock frequency-drift PSD (m^2/s^3) +TC_KF_config.clock_freq_PSD = 1; +% Receiver clock phase-drift PSD (m^2/s) +TC_KF_config.clock_phase_PSD = 1; + +% Pseudo-range measurement noise SD (m) +TC_KF_config.pseudo_range_SD = 2.5; +% Pseudo-range rate measurement noise SD (m/s) +TC_KF_config.range_rate_SD = 0.1; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% Tightly coupled ECEF Inertial navigation and GNSS integrated navigation +% simulation +[out_profile,out_errors,out_IMU_bias_est,out_clock,out_KF_SD] =... + Tightly_coupled_INS_GNSS(in_profile,no_epochs,initialization_errors... + ,IMU_errors,GNSS_config,TC_KF_config); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/Inertial_Demo_1ECEF.m b/Inertial_Demo_1ECEF.m new file mode 100644 index 0000000..a72fae8 --- /dev/null +++ b/Inertial_Demo_1ECEF.m @@ -0,0 +1,89 @@ +%Inertial_Demo_1ECEF +%SCRIPT Inertial navigation demonstration: +% Profile_1 (60s artificial car motion with two 90 deg turns) +% ECEF-frame inertial navigation equations +% Tactical-grade IMU error model +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 3/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_1.csv'; +% Output motion profile and error filenames +output_profile_name = 'Inertial_Demo_1ECEF_Profile.csv'; +output_errors_name = 'Inertial_Demo_1ECEF_Errors.csv'; + +% Position initialization error (m; N,E,D) +initialization_errors.delta_r_eb_n = [4;2;3]; +% Velocity initialization error (m/s; N,E,D) +initialization_errors.delta_v_eb_n = [0.05;-0.05;0.1]; +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.05;0.04;1]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [900;-1300;800] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-9;13;-8] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [500, -300, 200;... + -150, -600, 250;... + -250, 100, 450] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [400, -300, 250;... + 0, -300, -150;... + 0, 0, -350] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0.9, -1.1, -0.6;... + -0.5, 1.9, -1.6;... + 0.3, 1.1, -1.3] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 100 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.01 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 1E-2; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 2E-4; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +% RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% ECEF Inertial navigation simulation +[out_profile,out_errors] = Inertial_navigation_ECEF(in_profile,no_epochs,... + initialization_errors,IMU_errors); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/Inertial_Demo_1ECI.m b/Inertial_Demo_1ECI.m new file mode 100644 index 0000000..7caf411 --- /dev/null +++ b/Inertial_Demo_1ECI.m @@ -0,0 +1,98 @@ +%Inertial_Demo_1ECI +%SCRIPT Inertial navigation demonstration: +% Profile_1 (60s artificial car motion with two 90 deg turns) +% ECI-frame inertial navigation equations +% Tactical-grade IMU error model +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 3/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details +clear all; +clc; +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_1.csv'; +% Output motion profile and error filenames +output_profile_name = 'Inertial_Demo_1ECI_Profile.csv'; +output_errors_name = 'Inertial_Demo_1ECI_Errors.csv'; + +% Position initialization error (m; N,E,D)位置初始误差 +initialization_errors.delta_r_eb_n = [4;2;3]; + +%===========可以改,只影响第一个历元的误差。Apr.30,2016 17:10===========% +% initialization_errors.delta_r_eb_n = [0;0;0];% +%===========可以改,只影响第一个历元的误差。Apr.30,2016 17:10===========% + +% Velocity initialization error (m/s; N,E,D)速度初始误差 +initialization_errors.delta_v_eb_n = [0.05;-0.05;0.1]; +% Attitude initialization error (deg, converted to rad; @N,E,D)姿态初始误差 +initialization_errors.delta_eul_nb_n = [-0.05;0.04;1]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes)加速度计零偏 +IMU_errors.b_a = [900;-1300;800] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes)陀螺仪零偏 P.133 +IMU_errors.b_g = [-9;13;-8] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes)加速度计比例因子和交叉耦合误差 +IMU_errors.M_a = [500, -300, 200;... + -150, -600, 250;... + -250, 100, 450] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes)陀螺仪比例因子和交叉耦合误差 P.135 +IMU_errors.M_g = [400, -300, 250;... + 0, -300, -150;... + 0, 0, -350] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body +% axes)陀螺仪g相关零偏 P.139 +IMU_errors.G_g = [0.9, -1.1, -0.6;... + -0.5, 1.9, -1.6;... + 0.3, 1.1, -1.3] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +% 加速度计随机噪声的功率密度方根 +IMU_errors.accel_noise_root_PSD = 100 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5)陀螺仪随机 +% 噪声的功率密度方根 P.138 +IMU_errors.gyro_noise_root_PSD = 0.01 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2)量化因子的数量级 +IMU_errors.accel_quant_level = 1E-2; +% Gyro quantization level (rad/s)量化因子的数量级 P.138 +IMU_errors.gyro_quant_level = 2E-4; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +% RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file开始读取文件 +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file 判断读取文件是否有错误 +if ~ok + return; +end %if + +% ECI Inertial navigation simulation 开始惯导仿真 +[out_profile,out_errors] = Inertial_navigation_ECI(in_profile,no_epochs,... + initialization_errors,IMU_errors); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/Inertial_Demo_1NED.m b/Inertial_Demo_1NED.m new file mode 100644 index 0000000..fdd0380 --- /dev/null +++ b/Inertial_Demo_1NED.m @@ -0,0 +1,89 @@ +%Inertial_Demo_1NED +%SCRIPT Inertial navigation demonstration: +% Profile_1 (60s artificial car motion with two 90 deg turns) +% Local-navigation-frame inertial navigation equations +% Tactical-grade IMU error model +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 3/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_1.csv'; +% Output motion profile and error filenames +output_profile_name = 'Inertial_Demo_1NED_Profile.csv'; +output_errors_name = 'Inertial_Demo_1NED_Errors.csv'; + +% Position initialization error (m; N,E,D) +initialization_errors.delta_r_eb_n = [4;2;3]; +% Velocity initialization error (m/s; N,E,D) +initialization_errors.delta_v_eb_n = [0.05;-0.05;0.1]; +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.05;0.04;1]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [900;-1300;800] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-9;13;-8] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [500, -300, 200;... + -150, -600, 250;... + -250, 100, 450] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [400, -300, 250;... + 0, -300, -150;... + 0, 0, -350] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0.9, -1.1, -0.6;... + -0.5, 1.9, -1.6;... + 0.3, 1.1, -1.3] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 100 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.01 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 1E-2; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 2E-4; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% NED Inertial navigation simulation +[out_profile,out_errors] = Inertial_navigation_NED(in_profile,no_epochs,... + initialization_errors,IMU_errors); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/Inertial_Demo_2.m b/Inertial_Demo_2.m new file mode 100644 index 0000000..072a6cb --- /dev/null +++ b/Inertial_Demo_2.m @@ -0,0 +1,89 @@ +%Inertial_Demo_2 +%SCRIPT Inertial navigation demonstration: +% Profile_1 (60s artificial car motion with two 90 deg turns) +% Local-navigation-frame inertial navigation equations +% Aviation-grade IMU error model +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 4/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_1.csv'; +% Output motion profile and error filenames +output_profile_name = 'Inertial_Demo_2_Profile.csv'; +output_errors_name = 'Inertial_Demo_2_Errors.csv'; + +% Position initialization error (m; N,E,D) +initialization_errors.delta_r_eb_n = [4;2;3]; +% Velocity initialization error (m/s; N,E,D) +initialization_errors.delta_v_eb_n = [0.05;-0.05;0.1]; +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.01;0.008;0.01]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [30;-45;26] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-0.0009;0.0013;-0.0008] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [100, -120, 80;... + -60, -120, 100;... + -100, 40, 90] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [8, -120, 100;... + 0, -6, -60;... + 0, 0, -7] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0, 0, 0;... + 0, 0, 0;... + 0, 0, 0] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 20 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.002 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 5E-5; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 1E-6; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% NED Inertial navigation simulation +[out_profile,out_errors] = Inertial_navigation_NED(in_profile,no_epochs,... + initialization_errors,IMU_errors); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/Inertial_Demo_3.m b/Inertial_Demo_3.m new file mode 100644 index 0000000..6bcaed8 --- /dev/null +++ b/Inertial_Demo_3.m @@ -0,0 +1,89 @@ +%Inertial_Demo_3 +%SCRIPT Inertial navigation demonstration: +% Profile_1 (60s artificial car motion with two 90 deg turns) +% Local-navigation-frame inertial navigation equations +% Consumer-grade IMU error model +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 4/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_1.csv'; +% Output motion profile and error filenames +output_profile_name = 'Inertial_Demo_3_Profile.csv'; +output_errors_name = 'Inertial_Demo_3_Errors.csv'; + +% Position initialization error (m; N,E,D) +initialization_errors.delta_r_eb_n = [4;2;3]; +% Velocity initialization error (m/s; N,E,D) +initialization_errors.delta_v_eb_n = [0.05;-0.05;0.1]; +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.5;0.4;2]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [9000;-13000;8000] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-180;260;-160] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [50000, -15000, 10000;... + -7500, -60000, 12500;... + -12500, 5000, 20000] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [40000, -14000, 12500;... + 0, -30000, -7500;... + 0, 0, -17500] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [90, -110, -60;... + -50, 190, -160;... + 30, 110, -130] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 1000 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 1 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 1E-1; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 2E-3; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% NED Inertial navigation simulation +[out_profile,out_errors] = Inertial_navigation_NED(in_profile,no_epochs,... + initialization_errors,IMU_errors); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/Inertial_Demo_4.m b/Inertial_Demo_4.m new file mode 100644 index 0000000..49e8783 --- /dev/null +++ b/Inertial_Demo_4.m @@ -0,0 +1,89 @@ +%Inertial_Demo_4 +%SCRIPT Inertial navigation demonstration: +% Profile_0 (60s stationary and level) +% Local-navigation-frame inertial navigation equations +% Tactical-grade IMU error model +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 4/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_0.csv'; +% Output motion profile and error filenames +output_profile_name = 'Inertial_Demo_4_Profile.csv'; +output_errors_name = 'Inertial_Demo_4_Errors.csv'; + +% Position initialization error (m; N,E,D) +initialization_errors.delta_r_eb_n = [4;2;3]; +% Velocity initialization error (m/s; N,E,D) +initialization_errors.delta_v_eb_n = [0.05;-0.05;0.1]; +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.05;0.04;1]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [900;-1300;800] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-9;13;-8] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [500, -300, 200;... + -150, -600, 250;... + -250, 100, 450] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [400, -300, 250;... + 0, -300, -150;... + 0, 0, -350] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0.9, -1.1, -0.6;... + -0.5, 1.9, -1.6;... + 0.3, 1.1, -1.3] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 100 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.01 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 1E-2; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 2E-4; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% NED Inertial navigation simulation +[out_profile,out_errors] = Inertial_navigation_NED(in_profile,no_epochs,... + initialization_errors,IMU_errors); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/Inertial_Demo_5.m b/Inertial_Demo_5.m new file mode 100644 index 0000000..bfd579b --- /dev/null +++ b/Inertial_Demo_5.m @@ -0,0 +1,89 @@ +%Inertial_Demo_5 +%SCRIPT Inertial navigation demonstration: +% Profile_2 (175s car) +% Local-navigation-frame inertial navigation equations +% Tactical-grade IMU error model +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 27/5/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_2.csv'; +% Output motion profile and error filenames +output_profile_name = 'Inertial_Demo_5_Profile.csv'; +output_errors_name = 'Inertial_Demo_5_Errors.csv'; + +% Position initialization error (m; N,E,D) +initialization_errors.delta_r_eb_n = [4;2;3]; +% Velocity initialization error (m/s; N,E,D) +initialization_errors.delta_v_eb_n = [0.05;-0.05;0.1]; +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.05;0.04;1]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [900;-1300;800] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-9;13;-8] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [500, -300, 200;... + -150, -600, 250;... + -250, 100, 450] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [400, -300, 250;... + 0, -300, -150;... + 0, 0, -350] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0.9, -1.1, -0.6;... + -0.5, 1.9, -1.6;... + 0.3, 1.1, -1.3] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 100 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.01 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 1E-2; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 2E-4; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% NED Inertial navigation simulation +[out_profile,out_errors] = Inertial_navigation_NED(in_profile,no_epochs,... + initialization_errors,IMU_errors); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/Inertial_Demo_6.m b/Inertial_Demo_6.m new file mode 100644 index 0000000..085e1b0 --- /dev/null +++ b/Inertial_Demo_6.m @@ -0,0 +1,89 @@ +%Inertial_Demo_6 +%SCRIPT Inertial navigation demonstration: +% Profile_3 (418s aircraft) +% Local-navigation-frame inertial navigation equations +% Aviation-grade IMU error model +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 27/5/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_3.csv'; +% Output motion profile and error filenames +output_profile_name = 'Inertial_Demo_6_Profile.csv'; +output_errors_name = 'Inertial_Demo_6_Errors.csv'; + +% Position initialization error (m; N,E,D) +initialization_errors.delta_r_eb_n = [4;2;3]; +% Velocity initialization error (m/s; N,E,D) +initialization_errors.delta_v_eb_n = [0.05;-0.05;0.1]; +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.01;0.008;0.01]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [30;-45;26] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-0.0009;0.0013;-0.0008] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [100, -120, 80;... + -60, -120, 100;... + -100, 40, 90] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [8, -120, 100;... + 0, -6, -60;... + 0, 0, -7] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0, 0, 0;... + 0, 0, 0;... + 0, 0, 0] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 20 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.002 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 5E-5; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 1E-6; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% NED Inertial navigation simulation +[out_profile,out_errors] = Inertial_navigation_NED(in_profile,no_epochs,... + initialization_errors,IMU_errors); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/Inertial_Demo_7.m b/Inertial_Demo_7.m new file mode 100644 index 0000000..95f5b3c --- /dev/null +++ b/Inertial_Demo_7.m @@ -0,0 +1,88 @@ +%Inertial_Demo_7 +%SCRIPT Inertial navigation demonstration: +% Profile_4 (300s boat) +% Local-navigation-frame inertial navigation equations +% Tactical-grade IMU error model +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% Created 27/5/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; +micro_g_to_meters_per_second_squared = 9.80665E-6; + +% CONFIGURATION +% Input truth motion profile filename +input_profile_name = 'Profile_4.csv'; +% Output motion profile and error filenames +output_profile_name = 'Inertial_Demo_7_Profile.csv'; +output_errors_name = 'Inertial_Demo_7_Errors.csv'; + +% Position initialization error (m; N,E,D) +initialization_errors.delta_r_eb_n = [4;2;3]; +% Velocity initialization error (m/s; N,E,D) +initialization_errors.delta_v_eb_n = [0.05;-0.05;0.1]; +% Attitude initialization error (deg, converted to rad; @N,E,D) +initialization_errors.delta_eul_nb_n = [-0.05;0.04;1]*deg_to_rad; % rad + +% Accelerometer biases (micro-g, converted to m/s^2; body axes) +IMU_errors.b_a = [900;-1300;800] * micro_g_to_meters_per_second_squared; +% Gyro biases (deg/hour, converted to rad/sec; body axes) +IMU_errors.b_g = [-9;13;-8] * deg_to_rad / 3600; +% Accelerometer scale factor and cross coupling errors (ppm, converted to +% unitless; body axes) +IMU_errors.M_a = [500, -300, 200;... + -150, -600, 250;... + -250, 100, 450] * 1E-6; +% Gyro scale factor and cross coupling errors (ppm, converted to unitless; +% body axes) +IMU_errors.M_g = [400, -300, 250;... + 0, -300, -150;... + 0, 0, -350] * 1E-6; +% Gyro g-dependent biases (deg/hour/g, converted to rad-sec/m; body axes) +IMU_errors.G_g = [0.9, -1.1, -0.6;... + -0.5, 1.9, -1.6;... + 0.3, 1.1, -1.3] * deg_to_rad / (3600 * 9.80665); +% Accelerometer noise root PSD (micro-g per root Hz, converted to m s^-1.5) +IMU_errors.accel_noise_root_PSD = 100 *... + micro_g_to_meters_per_second_squared; +% Gyro noise root PSD (deg per root hour, converted to rad s^-0.5) +IMU_errors.gyro_noise_root_PSD = 0.01 * deg_to_rad / 60; +% Accelerometer quantization level (m/s^2) +IMU_errors.accel_quant_level = 1E-2; +% Gyro quantization level (rad/s) +IMU_errors.gyro_quant_level = 2E-4; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence (may not work in Octave). +RandStream.setDefaultStream(RandStream('mt19937ar','seed',1)); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% NED Inertial navigation simulation +[out_profile,out_errors] = Inertial_navigation_NED(in_profile,no_epochs,... + initialization_errors,IMU_errors); + +% Plot the input motion profile and the errors (may not work in Octave). +close all; +Plot_profile(in_profile); +Plot_errors(out_errors); + +% Write output profile and errors file +Write_profile(output_profile_name,out_profile); +Write_errors(output_errors_name,out_errors); + +% Ends \ No newline at end of file diff --git a/Inertial_navigation_ECEF.m b/Inertial_navigation_ECEF.m new file mode 100644 index 0000000..092d1ac --- /dev/null +++ b/Inertial_navigation_ECEF.m @@ -0,0 +1,181 @@ +function [out_profile,out_errors] = Inertial_navigation_ECEF(in_profile,... + no_epochs,initialization_errors,IMU_errors) +%Inertial_navigation_ECEF - Simulates inertial navigation using ECEF +% navigation equations and kinematic model +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 3/4/2012 by Paul Groves +% +% Inputs: +% in_profile True motion profile array +% no_epochs Number of epochs of profile data +% initialization_errors +% .delta_r_eb_n position error resolved along NED (m) +% .delta_v_eb_n velocity error resolved along NED (m/s) +% .delta_eul_nb_n attitude error as NED Euler angles (rad) +% IMU_errors +% .delta_r_eb_n position error resolved along NED (m) +% .b_a Accelerometer biases (m/s^2) +% .b_g Gyro biases (rad/s) +% .M_a Accelerometer scale factor and cross coupling errors +% .M_g Gyro scale factor and cross coupling errors +% .G_g Gyro g-dependent biases (rad-sec/m) +% .accel_noise_root_PSD Accelerometer noise root PSD (m s^-1.5) +% .gyro_noise_root_PSD Gyro noise root PSD (rad s^-0.5) +% .accel_quant_level Accelerometer quantization level (m/s^2) +% .gyro_quant_level Gyro quantization level (rad/s) +% +% Outputs: +% out_profile Navigation solution as a motion profile array +% out_errors Navigation solution error array +% +% Format of motion profiles: +% Column 1: time (sec) +% Column 2: latitude (rad) +% Column 3: longitude (rad) +% Column 4: height (m) +% Column 5: north velocity (m/s) +% Column 6: east velocity (m/s) +% Column 7: down velocity (m/s) +% Column 8: roll angle of body w.r.t NED (rad) +% Column 9: pitch angle of body w.r.t NED (rad) +% Column 10: yaw angle of body w.r.t NED (rad) +% +% Format of error array: +% Column 1: time (sec) +% Column 2: north position error (m) +% Column 3: east position error (m) +% Column 4: down position error (m) +% Column 5: north velocity (m/s) +% Column 6: east velocity (m/s) +% Column 7: down velocity (m/s) +% Column 8: attitude error about north (rad) +% Column 9: attitude error about east (rad) +% Column 10: attitude error about down = heading error (rad) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Initialize true navigation solution +old_time = in_profile(1,1); +true_L_b = in_profile(1,2); +true_lambda_b = in_profile(1,3); +true_h_b = in_profile(1,4); +true_v_eb_n = in_profile(1,5:7)'; +true_eul_nb = in_profile(1,8:10)'; +true_C_b_n = Euler_to_CTM(true_eul_nb)'; +[old_true_r_eb_e,old_true_v_eb_e,old_true_C_b_e] =... + NED_to_ECEF(true_L_b,true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); + +% Initialize estimated navigation solution +[old_est_L_b,old_est_lambda_b,old_est_h_b,old_est_v_eb_n,old_est_C_b_n] =... + Initialize_NED(true_L_b,true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n,... + initialization_errors); + +% Initialize output profile record and errors record +out_profile = zeros(no_epochs,10); +out_errors = zeros(no_epochs,10); + +% Generate output profile record +out_profile(1,1) = old_time; +out_profile(1,2) = old_est_L_b; +out_profile(1,3) = old_est_lambda_b; +out_profile(1,4) = old_est_h_b; +out_profile(1,5:7) = old_est_v_eb_n'; +out_profile(1,8:10) = CTM_to_Euler(old_est_C_b_n')'; + +out_errors(1,1) = old_time; +out_errors(1,2:4) = initialization_errors.delta_r_eb_n'; +out_errors(1,5:7) = initialization_errors.delta_v_eb_n'; +out_errors(1,8:10) = initialization_errors.delta_eul_nb_n'; +[old_est_r_eb_e,old_est_v_eb_e,old_est_C_b_e] = NED_to_ECEF(old_est_L_b,... + old_est_lambda_b,old_est_h_b,old_est_v_eb_n,old_est_C_b_n); + +% Initialize IMU quantization residuals +quant_residuals = [0;0;0;0;0;0]; + +% Progress bar +dots = '....................'; +bars = '||||||||||||||||||||'; +rewind = '\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b'; +fprintf(strcat('Processing: ',dots)); +progress_mark = 0; +progress_epoch = 0; + +% Main loop +for epoch = 2:no_epochs + + % Update progress bar + if (epoch - progress_epoch) > (no_epochs/20) + progress_mark = progress_mark + 1; + progress_epoch = epoch; + fprintf(strcat(rewind,bars(1:progress_mark),... + dots(1:(20 - progress_mark)))); + end % if epoch + + % Input data from motion profile + time = in_profile(epoch,1); + true_L_b = in_profile(epoch,2); + true_lambda_b = in_profile(epoch,3); + true_h_b = in_profile(epoch,4); + true_v_eb_n = in_profile(epoch,5:7)'; + true_eul_nb = in_profile(epoch,8:10)'; + true_C_b_n = Euler_to_CTM(true_eul_nb)'; + [true_r_eb_e,true_v_eb_e,true_C_b_e] =... + NED_to_ECEF(true_L_b,true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); + + % Time interval + tor_i = time - old_time; + + % Calculate specific force and angular rate + [true_f_ib_b,true_omega_ib_b] = Kinematics_ECEF(tor_i,true_C_b_e,... + old_true_C_b_e,true_v_eb_e,old_true_v_eb_e,old_true_r_eb_e); + + % Simulate IMU errors + [meas_f_ib_b,meas_omega_ib_b,quant_residuals] = IMU_model(tor_i,... + true_f_ib_b,true_omega_ib_b,IMU_errors,quant_residuals); + + % Update estimated navigation solution + [est_r_eb_e,est_v_eb_e,est_C_b_e] = Nav_equations_ECEF(tor_i,... + old_est_r_eb_e,old_est_v_eb_e,old_est_C_b_e,meas_f_ib_b,... + meas_omega_ib_b); + + [est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n] =... + ECEF_to_NED(est_r_eb_e,est_v_eb_e,est_C_b_e); + + % Generate output profile record + out_profile(epoch,1) = time; + out_profile(epoch,2) = est_L_b; + out_profile(epoch,3) = est_lambda_b; + out_profile(epoch,4) = est_h_b; + out_profile(epoch,5:7) = est_v_eb_n'; + out_profile(epoch,8:10) = CTM_to_Euler(est_C_b_n')'; + + % Determine errors and generate output record + [delta_r_eb_n,delta_v_eb_n,delta_eul_nb_n] = Calculate_errors_NED(... + est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n,true_L_b,... + true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); + out_errors(epoch,1) = time; + out_errors(epoch,2:4) = delta_r_eb_n'; + out_errors(epoch,5:7) = delta_v_eb_n'; + out_errors(epoch,8:10) = delta_eul_nb_n'; + + % Reset old values + old_time = time; + old_true_r_eb_e = true_r_eb_e; + old_true_v_eb_e = true_v_eb_e; + old_true_C_b_e = true_C_b_e; + old_est_r_eb_e = est_r_eb_e; + old_est_v_eb_e = est_v_eb_e; + old_est_C_b_e = est_C_b_e; + +end %epoch + +% Complete progress bar +fprintf(strcat(rewind,bars,'\n')); + +% Ends \ No newline at end of file diff --git a/Inertial_navigation_ECI.m b/Inertial_navigation_ECI.m new file mode 100644 index 0000000..84287d1 --- /dev/null +++ b/Inertial_navigation_ECI.m @@ -0,0 +1,190 @@ +function [out_profile,out_errors] = Inertial_navigation_ECI(in_profile,... + no_epochs,initialization_errors,IMU_errors) +%Inertial_navigation_ECI - Simulates inertial navigation using ECI +% navigation equations and kinematic model +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 3/4/2012 by Paul Groves +% +% Inputs: +% in_profile True motion profile array +% no_epochs Number of epochs of profile data +% initialization_errors +% .delta_r_eb_n position error resolved along NED (m) +% .delta_v_eb_n velocity error resolved along NED (m/s) +% .delta_eul_nb_n attitude error as NED Euler angles (rad) +% IMU_errors +% .delta_r_eb_n position error resolved along NED (m) +% .b_a Accelerometer biases (m/s^2) +% .b_g Gyro biases (rad/s) +% .M_a Accelerometer scale factor and cross coupling errors +% .M_g Gyro scale factor and cross coupling errors +% .G_g Gyro g-dependent biases (rad-sec/m) +% .accel_noise_root_PSD Accelerometer noise root PSD (m s^-1.5) +% .gyro_noise_root_PSD Gyro noise root PSD (rad s^-0.5) +% .accel_quant_level Accelerometer quantization level (m/s^2) +% .gyro_quant_level Gyro quantization level (rad/s) +% +% Outputs: +% out_profile Navigation solution as a motion profile array +% out_errors Navigation solution error array +% +% Format of motion profiles: +% Column 1: time (sec) +% Column 2: latitude (rad)纬度 +% Column 3: longitude (rad)经度 +% Column 4: height (m) +% Column 5: north velocity (m/s) +% Column 6: east velocity (m/s) +% Column 7: down velocity (m/s) +% Column 8: roll angle of body w.r.t NED (rad) +% Column 9: pitch angle of body w.r.t NED (rad) +% Column 10: yaw angle of body w.r.t NED (rad) +% +% Format of error array: +% Column 1: time (sec) +% Column 2: north position error (m) +% Column 3: east position error (m) +% Column 4: down position error (m) +% Column 5: north velocity (m/s) +% Column 6: east velocity (m/s) +% Column 7: down velocity (m/s) +% Column 8: attitude error about north (rad) +% Column 9: attitude error about east (rad) +% Column 10: attitude error about down = heading error (rad) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Initialize true navigation solution 初始化,输入读取到的参数,使用第一个历元 +old_time = in_profile(1,1); +true_L_b = in_profile(1,2);%纬度 +true_lambda_b = in_profile(1,3);%经度 +true_h_b = in_profile(1,4); +true_v_eb_n = in_profile(1,5:7)'; +true_eul_nb = in_profile(1,8:10)'; +true_C_b_n = Euler_to_CTM(true_eul_nb)';%坐标转换矩阵 +[true_r_eb_e,true_v_eb_e,true_C_b_e] =... + NED_to_ECEF(true_L_b,true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); +[old_true_r_ib_i,old_true_v_ib_i,old_true_C_b_i] =... + ECEF_to_ECI(old_time,true_r_eb_e,true_v_eb_e,true_C_b_e); + +% Initialize estimated navigation solution +[old_est_L_b,old_est_lambda_b,old_est_h_b,old_est_v_eb_n,old_est_C_b_n] =... + Initialize_NED(true_L_b,true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n,... + initialization_errors); + +% Initialize output profile record and errors record +out_profile = zeros(no_epochs,10); +out_errors = zeros(no_epochs,10); + +% Generate output profile record +out_profile(1,1) = old_time; +out_profile(1,2) = old_est_L_b; +out_profile(1,3) = old_est_lambda_b; +out_profile(1,4) = old_est_h_b; +out_profile(1,5:7) = old_est_v_eb_n'; +out_profile(1,8:10) = CTM_to_Euler(old_est_C_b_n')'; + +out_errors(1,1) = old_time; +out_errors(1,2:4) = initialization_errors.delta_r_eb_n'; +out_errors(1,5:7) = initialization_errors.delta_v_eb_n'; +out_errors(1,8:10) = initialization_errors.delta_eul_nb_n'; +[old_est_r_eb_e,old_est_v_eb_e,old_est_C_b_e] = NED_to_ECEF(old_est_L_b,... + old_est_lambda_b,old_est_h_b,old_est_v_eb_n,old_est_C_b_n); +[old_est_r_ib_i,old_est_v_ib_i,old_est_C_b_i] =... + ECEF_to_ECI(old_time,old_est_r_eb_e,old_est_v_eb_e,old_est_C_b_e); + +% Initialize IMU quantization residuals +quant_residuals = [0;0;0;0;0;0]; + +% Progress bar 进度条,可以不要 +dots = '....................'; +bars = '||||||||||||||||||||'; +rewind = '\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b'; +fprintf(strcat('Processing: ',dots)); +progress_mark = 0; +progress_epoch = 0; + +% Main loop +for epoch = 2:no_epochs + + % Update progress bar 更新进度条,没用 + if (epoch - progress_epoch) > (no_epochs/20) + progress_mark = progress_mark + 1; + progress_epoch = epoch; + fprintf(strcat(rewind,bars(1:progress_mark),... + dots(1:(20 - progress_mark)))); + end % if epoch + + % Input data from motion profile + time = in_profile(epoch,1); + true_L_b = in_profile(epoch,2); + true_lambda_b = in_profile(epoch,3); + true_h_b = in_profile(epoch,4); + true_v_eb_n = in_profile(epoch,5:7)'; + true_eul_nb = in_profile(epoch,8:10)'; + true_C_b_n = Euler_to_CTM(true_eul_nb)'; + [true_r_eb_e,true_v_eb_e,true_C_b_e] =... + NED_to_ECEF(true_L_b,true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); + [true_r_ib_i,true_v_ib_i,true_C_b_i] =... + ECEF_to_ECI(time,true_r_eb_e,true_v_eb_e,true_C_b_e); + + % Time interval + tor_i = time - old_time; + + % Calculate specific force and angular rate + + [true_f_ib_b,true_omega_ib_b] = Kinematics_ECI(tor_i,true_C_b_i,... + old_true_C_b_i,true_v_ib_i,old_true_v_ib_i,old_true_r_ib_i); + + % Simulate IMU errors + [meas_f_ib_b,meas_omega_ib_b,quant_residuals] = IMU_model(tor_i,... + true_f_ib_b,true_omega_ib_b,IMU_errors,quant_residuals); + + % Update estimated navigation solution + [est_r_ib_i,est_v_ib_i,est_C_b_i] = Nav_equations_ECI(tor_i,... + old_est_r_ib_i,old_est_v_ib_i,old_est_C_b_i,meas_f_ib_b,... + meas_omega_ib_b); + + [est_r_eb_e,est_v_eb_e,est_C_b_e] =... + ECI_to_ECEF(time,est_r_ib_i,est_v_ib_i,est_C_b_i); + [est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n] =... + ECEF_to_NED(est_r_eb_e,est_v_eb_e,est_C_b_e); + + % Generate output profile record + out_profile(epoch,1) = time; + out_profile(epoch,2) = est_L_b; + out_profile(epoch,3) = est_lambda_b; + out_profile(epoch,4) = est_h_b; + out_profile(epoch,5:7) = est_v_eb_n'; + out_profile(epoch,8:10) = CTM_to_Euler(est_C_b_n')'; + + % Determine errors and generate output record + [delta_r_eb_n,delta_v_eb_n,delta_eul_nb_n] = Calculate_errors_NED(... + est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n,true_L_b,... + true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); + out_errors(epoch,1) = time; + out_errors(epoch,2:4) = delta_r_eb_n'; + out_errors(epoch,5:7) = delta_v_eb_n'; + out_errors(epoch,8:10) = delta_eul_nb_n'; + + % Reset old values + old_time = time; + old_true_r_ib_i = true_r_ib_i; + old_true_v_ib_i = true_v_ib_i; + old_true_C_b_i = true_C_b_i; + old_est_r_ib_i = est_r_ib_i; + old_est_v_ib_i = est_v_ib_i; + old_est_C_b_i = est_C_b_i; + +end %epoch + +% Complete progress bar +fprintf(strcat(rewind,bars,'\n')); + +% Ends \ No newline at end of file diff --git a/Inertial_navigation_NED.m b/Inertial_navigation_NED.m new file mode 100644 index 0000000..29bb464 --- /dev/null +++ b/Inertial_navigation_NED.m @@ -0,0 +1,177 @@ +function [out_profile,out_errors] = Inertial_navigation_NED(in_profile,... + no_epochs,initialization_errors,IMU_errors) +%Inertial_navigation_NED - Simulates inertial navigation using local +%navigation frame (NED) navigation equations and kinematic model +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 3/4/2012 by Paul Groves +% +% Inputs: +% in_profile True motion profile array +% no_epochs Number of epochs of profile data +% initialization_errors +% .delta_r_eb_n position error resolved along NED (m) +% .delta_v_eb_n velocity error resolved along NED (m/s) +% .delta_eul_nb_n attitude error as NED Euler angles (rad) +% IMU_errors +% .delta_r_eb_n position error resolved along NED (m) +% .b_a Accelerometer biases (m/s^2) +% .b_g Gyro biases (rad/s) +% .M_a Accelerometer scale factor and cross coupling errors +% .M_g Gyro scale factor and cross coupling errors +% .G_g Gyro g-dependent biases (rad-sec/m) +% .accel_noise_root_PSD Accelerometer noise root PSD (m s^-1.5) +% .gyro_noise_root_PSD Gyro noise root PSD (rad s^-0.5) +% .accel_quant_level Accelerometer quantization level (m/s^2) +% .gyro_quant_level Gyro quantization level (rad/s) +% +% Outputs: +% out_profile Navigation solution as a motion profile array +% out_errors Navigation solution error array +% +% Format of motion profiles: +% Column 1: time (sec) +% Column 2: latitude (rad) +% Column 3: longitude (rad) +% Column 4: height (m) +% Column 5: north velocity (m/s) +% Column 6: east velocity (m/s) +% Column 7: down velocity (m/s) +% Column 8: roll angle of body w.r.t NED (rad) +% Column 9: pitch angle of body w.r.t NED (rad) +% Column 10: yaw angle of body w.r.t NED (rad) +% +% Format of error array: +% Column 1: time (sec) +% Column 2: north position error (m) +% Column 3: east position error (m) +% Column 4: down position error (m) +% Column 5: north velocity (m/s) +% Column 6: east velocity (m/s) +% Column 7: down velocity (m/s) +% Column 8: attitude error about north (rad) +% Column 9: attitude error about east (rad) +% Column 10: attitude error about down = heading error (rad) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Initialize true navigation solution +old_time = in_profile(1,1); +old_true_L_b = in_profile(1,2); +old_true_lambda_b = in_profile(1,3); +old_true_h_b = in_profile(1,4); +old_true_v_eb_n = in_profile(1,5:7)'; +old_true_eul_nb = in_profile(1,8:10)'; +old_true_C_b_n = Euler_to_CTM(old_true_eul_nb)'; + +% Initialize estimated navigation solution +[old_est_L_b,old_est_lambda_b,old_est_h_b,old_est_v_eb_n,old_est_C_b_n] =... + Initialize_NED(old_true_L_b,old_true_lambda_b,old_true_h_b,... + old_true_v_eb_n,old_true_C_b_n,initialization_errors); + +% Initialize output profile record and errors record +out_profile = zeros(no_epochs,10); +out_errors = zeros(no_epochs,10); + +% Generate output profile record +out_profile(1,1) = old_time; +out_profile(1,2) = old_est_L_b; +out_profile(1,3) = old_est_lambda_b; +out_profile(1,4) = old_est_h_b; +out_profile(1,5:7) = old_est_v_eb_n'; +out_profile(1,8:10) = CTM_to_Euler(old_est_C_b_n')'; + +out_errors(1,1) = old_time; +out_errors(1,2:4) = initialization_errors.delta_r_eb_n'; +out_errors(1,5:7) = initialization_errors.delta_v_eb_n'; +out_errors(1,8:10) = initialization_errors.delta_eul_nb_n'; + +% Initialize IMU quantization residuals +quant_residuals = [0;0;0;0;0;0]; + +% Progress bar +dots = '....................'; +bars = '||||||||||||||||||||'; +rewind = '\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b'; +fprintf(strcat('Processing: ',dots)); +progress_mark = 0; +progress_epoch = 0; + +% Main loop +for epoch = 2:no_epochs + + % Update progress bar + if (epoch - progress_epoch) > (no_epochs/20) + progress_mark = progress_mark + 1; + progress_epoch = epoch; + fprintf(strcat(rewind,bars(1:progress_mark),... + dots(1:(20 - progress_mark)))); + end % if epoch + + % Input data from motion profile + time = in_profile(epoch,1); + true_L_b = in_profile(epoch,2); + true_lambda_b = in_profile(epoch,3); + true_h_b = in_profile(epoch,4); + true_v_eb_n = in_profile(epoch,5:7)'; + true_eul_nb = in_profile(epoch,8:10)'; + true_C_b_n = Euler_to_CTM(true_eul_nb)'; + + % Time interval + tor_i = time - old_time; + + % Calculate true specific force and angular rate + [true_f_ib_b,true_omega_ib_b] = Kinematics_NED(tor_i,true_C_b_n,... + old_true_C_b_n,true_v_eb_n,old_true_v_eb_n,true_L_b,true_h_b,... + old_true_L_b,old_true_h_b); + + % Simulate IMU errors + [meas_f_ib_b,meas_omega_ib_b,quant_residuals] = IMU_model(tor_i,... + true_f_ib_b,true_omega_ib_b,IMU_errors,quant_residuals); + + % Update estimated navigation solution + [est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n] = ... + Nav_equations_NED(tor_i,old_est_L_b,old_est_lambda_b,old_est_h_b,... + old_est_v_eb_n,old_est_C_b_n,meas_f_ib_b,meas_omega_ib_b); + + % Generate output profile record + out_profile(epoch,1) = time; + out_profile(epoch,2) = est_L_b; + out_profile(epoch,3) = est_lambda_b; + out_profile(epoch,4) = est_h_b; + out_profile(epoch,5:7) = est_v_eb_n'; + out_profile(epoch,8:10) = CTM_to_Euler(est_C_b_n')'; + + % Determine errors and generate output record + [delta_r_eb_n,delta_v_eb_n,delta_eul_nb_n] = Calculate_errors_NED(... + est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n,true_L_b,... + true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); + out_errors(epoch,1) = time; + out_errors(epoch,2:4) = delta_r_eb_n'; + out_errors(epoch,5:7) = delta_v_eb_n'; + out_errors(epoch,8:10) = delta_eul_nb_n'; + + % Reset old values + old_time = time; + old_true_L_b = true_L_b; + old_true_lambda_b = true_lambda_b; + old_true_h_b = true_h_b; + old_true_v_eb_n = true_v_eb_n; + old_true_C_b_n = true_C_b_n; + old_est_L_b = est_L_b; + old_est_lambda_b = est_lambda_b; + old_est_h_b = est_h_b; + old_est_v_eb_n = est_v_eb_n; + old_est_C_b_n = est_C_b_n; + +end %epoch + +% Complete progress bar +fprintf(strcat(rewind,bars,'\n')); + +% Ends \ No newline at end of file diff --git a/Initialize_GNSS_KF.m b/Initialize_GNSS_KF.m new file mode 100644 index 0000000..0c10cac --- /dev/null +++ b/Initialize_GNSS_KF.m @@ -0,0 +1,50 @@ +function [x_est,P_matrix] = Initialize_GNSS_KF(est_r_ea_e,est_v_ea_e,... + est_clock,GNSS_KF_config) +%Initialize_GNSS_KF - Initializes the GNSS EKF state estimates and error +%covariance matrix +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 11/4/2012 by Paul Groves +% +% Inputs: +% est_r_ea_e estimated ECEF user position (m) +% est_v_ea_e estimated ECEF user velocity (m/s) +% est_clock estimated receiver clock offset (m) and drift (m/s) +% GNSS_KF_config +% .init_pos_unc Initial position uncertainty per axis (m) +% .init_vel_unc Initial velocity uncertainty per axis (m/s) +% .init_clock_offset_unc Initial clock offset uncertainty per axis (m) +% .init_clock_drift_unc Initial clock drift uncertainty per axis (m/s) +% +% Outputs: +% x_est Kalman filter estimates: +% Rows 1-3 estimated ECEF user position (m) +% Rows 4-6 estimated ECEF user velocity (m/s) +% Row 7 estimated receiver clock offset (m) +% Row 8 estimated receiver clock drift (m/s) +% P_matrix state estimation error covariance matrix + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Initialize state estimates +x_est(1:3,1) = est_r_ea_e; +x_est(4:6,1) = est_v_ea_e; +x_est(7:8,1) = est_clock'; + +% Initialize error covariance matrix +P_matrix = zeros(8); +P_matrix(1,1) = GNSS_KF_config.init_pos_unc^2; +P_matrix(2,2) = GNSS_KF_config.init_pos_unc^2; +P_matrix(3,3) = GNSS_KF_config.init_pos_unc^2; +P_matrix(4,4) = GNSS_KF_config.init_vel_unc^2; +P_matrix(5,5) = GNSS_KF_config.init_vel_unc^2; +P_matrix(6,6) = GNSS_KF_config.init_vel_unc^2; +P_matrix(7,7) = GNSS_KF_config.init_clock_offset_unc^2; +P_matrix(8,8) = GNSS_KF_config.init_clock_drift_unc^2; + +% Ends \ No newline at end of file diff --git a/Initialize_GNSS_biases.m b/Initialize_GNSS_biases.m new file mode 100644 index 0000000..7513a0b --- /dev/null +++ b/Initialize_GNSS_biases.m @@ -0,0 +1,66 @@ +function GNSS_biases = Initialize_GNSS_biases(sat_r_es_e,r_ea_e,L_a,... + lambda_a,GNSS_config) +%Initialize_GNSS_biases - Initializes the GNSS range errors due to signal +%in space, ionosphere and troposphere errors based on the elevation angles. +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 11/4/2012 by Paul Groves +% +% Inputs: +% sat_r_es_e (no_sat x 3) ECEF satellite positions (m) +% r_ea_e ECEF user position (m) +% L_a user latitude (rad) +% lambda_a user longitude (rad) +% GNSS_config +% .no_sat Number of satellites in constellation +% .mask_angle Mask angle (deg) +% .SIS_err_SD Signal in space error SD (m) +% .zenith_iono_err_SD Zenith ionosphere error SD (m) +% .zenith_trop_err_SD Zenith troposphere error SD (m) +% +% Outputs: +% GNSS_biases (no_sat) Bias-like GNSS range errors + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Calculate ECEF to NED coordinate transformation matrix using (2.150) +cos_lat = cos(L_a); +sin_lat = sin(L_a); +cos_long = cos(lambda_a); +sin_long = sin(lambda_a); +C_e_n = [-sin_lat * cos_long, -sin_lat * sin_long, cos_lat;... + -sin_long, cos_long, 0;... + -cos_lat * cos_long, -cos_lat * sin_long, -sin_lat]; + +% Loop satellites +for j = 1:GNSS_config.no_sat + + % Determine ECEF line-of-sight vector using (8.41) + delta_r = sat_r_es_e(j,1:3)' - r_ea_e; + u_as_e = delta_r / sqrt(delta_r' * delta_r); + + % Convert line-of-sight vector to NED using (8.39) and determine + % elevation using (8.57) + elevation = -asin(C_e_n(3,:) * u_as_e); + + % Limit the minimum elevation angle to the masking angle + elevation = max(elevation,degtorad(GNSS_config.mask_angle)); + + % Calculate ionosphere and troposphere error SDs using (9.79) and (9.80) + iono_SD = GNSS_config.zenith_iono_err_SD / sqrt(1 - 0.899 *... + cos(elevation)^2); + trop_SD = GNSS_config.zenith_trop_err_SD / sqrt(1 - 0.998 *... + cos(elevation)^2); + + % Determine range bias + GNSS_biases(j) = GNSS_config.SIS_err_SD*randn + iono_SD*randn +... + trop_SD*randn; + +end % for j + +% Ends \ No newline at end of file diff --git a/Initialize_LC_P_matrix.m b/Initialize_LC_P_matrix.m new file mode 100644 index 0000000..1b75a15 --- /dev/null +++ b/Initialize_LC_P_matrix.m @@ -0,0 +1,34 @@ +function P_matrix = Initialize_LC_P_matrix(LC_KF_config) +%Initialize_LC_P_matrix - Initializes the loosely coupled INS/GNSS KF +%error covariance matrix +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 12/4/2012 by Paul Groves +% +% Inputs: +% TC_KF_config +% .init_att_unc Initial attitude uncertainty per axis (rad) +% .init_vel_unc Initial velocity uncertainty per axis (m/s) +% .init_pos_unc Initial position uncertainty per axis (m) +% .init_b_a_unc Initial accel. bias uncertainty (m/s^2) +% .init_b_g_unc Initial gyro. bias uncertainty (rad/s) +% +% Outputs: +% P_matrix state estimation error covariance matrix + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Initialize error covariance matrix +P_matrix = zeros(15); +P_matrix(1:3,1:3) = eye(3) * LC_KF_config.init_att_unc^2; +P_matrix(4:6,4:6) = eye(3) * LC_KF_config.init_vel_unc^2; +P_matrix(7:9,7:9) = eye(3) * LC_KF_config.init_pos_unc^2; +P_matrix(10:12,10:12) = eye(3) * LC_KF_config.init_b_a_unc^2; +P_matrix(13:15,13:15) = eye(3) * LC_KF_config.init_b_g_unc^2; + +% Ends \ No newline at end of file diff --git a/Initialize_NED.m b/Initialize_NED.m new file mode 100644 index 0000000..a22ac92 --- /dev/null +++ b/Initialize_NED.m @@ -0,0 +1,50 @@ +function [est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n] =... + Initialize_NED(L_b,lambda_b,h_b,v_eb_n,C_b_n,initialization_errors) +%Initialize_NED - Initializes the curvilinear position, velocity, and +%attitude solution by adding errors to the truth. +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 3/4/2012 by Paul Groves +% +% Inputs: +% L_b true latitude (rad) +% lambda_b true longitude (rad) +% h_b true height (m) +% v_eb_n true velocity of body frame w.r.t. ECEF frame, resolved +% along north, east, and down (m/s) +% C_b_n true body-to-NED coordinate transformation matrix +% initialization_errors +% .delta_r_eb_n position error resolved along NED (m) +% .delta_v_eb_n velocity error resolved along NED (m/s) +% .delta_eul_nb_n attitude error as NED Euler angles (rad) +% +% Outputs: +% est_L_b latitude solution (rad) +% est_lambda_b longitude solution (rad) +% est_h_b height solution (m) +% est_v_eb_n velocity solution of body frame w.r.t. ECEF frame, +% resolved along north, east, and down (m/s) +% est_C_b_n body-to-NED coordinate transformation matrix solution + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Position initialization, using (2.119) +[R_N,R_E] = Radii_of_curvature(L_b); +est_L_b = L_b + initialization_errors.delta_r_eb_n(1) / (R_N + h_b); +est_lambda_b = lambda_b + initialization_errors.delta_r_eb_n(2) /... + ((R_E + h_b) * cos(L_b)); +est_h_b = h_b - initialization_errors.delta_r_eb_n(3); + +% Velocity initialization +est_v_eb_n = v_eb_n + initialization_errors.delta_v_eb_n; + +% Attitude initialization, using (5.109) and (5.111) +delta_C_b_n = Euler_to_CTM(-initialization_errors.delta_eul_nb_n); +est_C_b_n = delta_C_b_n * C_b_n; + +% Ends \ No newline at end of file diff --git a/Initialize_NED_attitude.m b/Initialize_NED_attitude.m new file mode 100644 index 0000000..6e32b6a --- /dev/null +++ b/Initialize_NED_attitude.m @@ -0,0 +1,27 @@ +function est_C_b_n = Initialize_NED_attitude(C_b_n,initialization_errors) +%Initialize_NED_attitude - Initializes the attitude solution by adding +%errors to the truth. +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 12/4/2012 by Paul Groves +% +% Inputs: +% C_b_n true body-to-NED coordinate transformation matrix +% initialization_errors +% .delta_eul_nb_n attitude error as NED Euler angles (rad) +% +% Outputs: +% est_C_b_n body-to-NED coordinate transformation matrix solution + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Attitude initialization, using (5.109) and (5.111) +delta_C_b_n = Euler_to_CTM(-initialization_errors.delta_eul_nb_n); +est_C_b_n = delta_C_b_n * C_b_n; + +% Ends \ No newline at end of file diff --git a/Initialize_TC_P_matrix.m b/Initialize_TC_P_matrix.m new file mode 100644 index 0000000..cbae62d --- /dev/null +++ b/Initialize_TC_P_matrix.m @@ -0,0 +1,38 @@ +function P_matrix = Initialize_TC_P_matrix(TC_KF_config) +%Initialize_TC_P_matrix - Initializes the tightly coupled INS/GNSS EKF +%error covariance matrix +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 12/4/2012 by Paul Groves +% +% Inputs: +% TC_KF_config +% .init_att_unc Initial attitude uncertainty per axis (rad) +% .init_vel_unc Initial velocity uncertainty per axis (m/s) +% .init_pos_unc Initial position uncertainty per axis (m) +% .init_b_a_unc Initial accel. bias uncertainty (m/s^2) +% .init_b_g_unc Initial gyro. bias uncertainty (rad/s) +% .init_clock_offset_unc Initial clock offset uncertainty per axis (m) +% .init_clock_drift_unc Initial clock drift uncertainty per axis (m/s) +% +% Outputs: +% P_matrix state estimation error covariance matrix + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Initialize error covariance matrix +P_matrix = zeros(17); +P_matrix(1:3,1:3) = eye(3) * TC_KF_config.init_att_unc^2; +P_matrix(4:6,4:6) = eye(3) * TC_KF_config.init_vel_unc^2; +P_matrix(7:9,7:9) = eye(3) * TC_KF_config.init_pos_unc^2; +P_matrix(10:12,10:12) = eye(3) * TC_KF_config.init_b_a_unc^2; +P_matrix(13:15,13:15) = eye(3) * TC_KF_config.init_b_g_unc^2; +P_matrix(16,16) = TC_KF_config.init_clock_offset_unc^2; +P_matrix(17,17) = TC_KF_config.init_clock_drift_unc^2; + +% Ends \ No newline at end of file diff --git a/Interpolate_profile.m b/Interpolate_profile.m new file mode 100644 index 0000000..c44bff7 --- /dev/null +++ b/Interpolate_profile.m @@ -0,0 +1,95 @@ +function Interpolate_profile(input_profile_name,output_profile_name) +%Interpolate_profile - Interpolating .csv motion profiles: +% +% Inputs +% input_profile_name Input motion profile filename +% output_profile_name Output motion profile filename +% +% Created 3/4/12 by Paul Groves + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% CONFIGURATION +% Jitter standard deviation on interpolated velocity (m/s) +Velocity_jitter = 0.001; +% Jitter standard deviation on interpolated attitude (rad) +Attitude_jitter = 0.00002; + +% Seeding of the random number generator for reproducability. Change +% this value for a different random number sequence. +rng(1); + +% Begins + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(input_profile_name); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% Initialize true navigation solution +old_time = in_profile(1,1); +old_true_L_b = in_profile(1,2); +old_true_lambda_b = in_profile(1,3); +old_true_h_b = in_profile(1,4); +old_true_v_eb_n = in_profile(1,5:7)'; +old_true_eul_nb = in_profile(1,8:10)'; + +out_profile(1,:)=in_profile(1,:); + +% Main loop +for epoch = 2:no_epochs + + % Input data from motion profile + time = in_profile(epoch,1); + true_L_b = in_profile(epoch,2); + true_lambda_b = in_profile(epoch,3); + true_h_b = in_profile(epoch,4); + true_v_eb_n = in_profile(epoch,5:7)'; + true_eul_nb = in_profile(epoch,8:10)'; + + % Time interval + tor_i = time - old_time; + + % Interpolate + inter_L_b = 0.5 * (true_L_b + old_true_L_b); + inter_lambda_b = 0.5 * (true_lambda_b + old_true_lambda_b); + inter_h_b = 0.5 * (true_h_b + old_true_h_b); + inter_v_eb_n = 0.5 * (true_v_eb_n + old_true_v_eb_n) +... + randn(3,1) * Velocity_jitter; + inter_eul_nb = 0.5 * (true_eul_nb + old_true_eul_nb) +... + randn(3,1) * Attitude_jitter; + + % Generate output profile records + epoch1 = 2 * epoch -2; + epoch2 = 2 * epoch -1; + out_profile(epoch1,1) = 0.5* (time + old_time); + out_profile(epoch1,2) = inter_L_b; + out_profile(epoch1,3) = inter_lambda_b; + out_profile(epoch1,4) = inter_h_b; + out_profile(epoch1,5:7) = inter_v_eb_n'; + out_profile(epoch1,8:10) = inter_eul_nb'; + out_profile(epoch2,1) = time; + out_profile(epoch2,2) = true_L_b; + out_profile(epoch2,3) = true_lambda_b; + out_profile(epoch2,4) = true_h_b; + out_profile(epoch2,5:7) = true_v_eb_n'; + out_profile(epoch2,8:10) = true_eul_nb'; + + % Reset old values + old_time = time; + old_true_L_b = true_L_b; + old_true_lambda_b = true_lambda_b; + old_true_h_b = true_h_b; + old_true_v_eb_n = true_v_eb_n; + old_true_eul_nb = true_eul_nb; + +end %epoch + +% Write output profile +Write_profile(output_profile_name,out_profile); + +% Ends \ No newline at end of file diff --git a/Kinematics_ECEF.m b/Kinematics_ECEF.m new file mode 100644 index 0000000..daf8a4c --- /dev/null +++ b/Kinematics_ECEF.m @@ -0,0 +1,90 @@ +function [f_ib_b,omega_ib_b] = Kinematics_ECEF(tor_i,C_b_e,... + old_C_b_e,v_eb_e,old_v_eb_e,r_eb_e) +%Kinematics_ECEF - calculates specific force and angular rate from input +%w.r.t and resolved along ECEF-frame axes +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 1/4/2012 by Paul Groves +% +% Inputs: +% tor_i time interval between epochs (s) +% C_b_e body-to-ECEF-frame coordinate transformation matrix +% old_C_b_e previous body-to-ECEF-frame coordinate transformation matrix +% v_eb_e velocity of body frame w.r.t. ECEF frame, resolved along +% ECEF-frame axes (m/s) +% old_v_eb_e previous velocity of body frame w.r.t. ECEF frame, resolved +% along ECEF-frame axes (m/s) +% r_eb_e Cartesian position of body frame w.r.t. ECEF frame, resolved +% along ECEF-frame axes (m) +% Outputs: +% f_ib_b specific force of body frame w.r.t. ECEF frame, resolved +% along body-frame axes, averaged over time interval (m/s^2) +% omega_ib_b angular rate of body frame w.r.t. ECEF frame, resolved +% about body-frame axes, averaged over time interval (rad/s) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Parameters +omega_ie = 7.292115E-5; % Earth rotation rate (rad/s) + +% Begins + +if tor_i > 0 + + % From (2.145) determine the Earth rotation over the update interval + % C_Earth = C_e_i' * old_C_e_i + alpha_ie = omega_ie * tor_i; + C_Earth = [cos(alpha_ie), sin(alpha_ie), 0;... + -sin(alpha_ie), cos(alpha_ie), 0;... + 0, 0, 1]; + + % Obtain coordinate transformation matrix from the old attitude (w.r.t. + % an inertial frame) to the new + C_old_new = C_b_e' * C_Earth * old_C_b_e; + + % Calculate the approximate angular rate w.r.t. an inertial frame + alpha_ib_b(1,1) = 0.5 * (C_old_new(2,3) - C_old_new(3,2)); + alpha_ib_b(2,1) = 0.5 * (C_old_new(3,1) - C_old_new(1,3)); + alpha_ib_b(3,1) = 0.5 * (C_old_new(1,2) - C_old_new(2,1)); + + % Calculate and apply the scaling factor + temp = acos(0.5 * (C_old_new(1,1) + C_old_new(2,2) + C_old_new(3,3)... + - 1.0)); + if temp>2e-5 %scaling is 1 if temp is less than this + alpha_ib_b = alpha_ib_b * temp/sin(temp); + end %if temp + + % Calculate the angular rate + omega_ib_b = alpha_ib_b / tor_i; + + % Calculate the specific force resolved about ECEF-frame axes + % From (5.36), + f_ib_e = ((v_eb_e - old_v_eb_e) / tor_i) - Gravity_ECEF(r_eb_e)... + + 2 * Skew_symmetric([0;0;omega_ie]) * old_v_eb_e; + + % Calculate the average body-to-ECEF-frame coordinate transformation + % matrix over the update interval using (5.84) and (5.85) + mag_alpha = sqrt(alpha_ib_b' * alpha_ib_b); + Alpha_ib_b = Skew_symmetric(alpha_ib_b); + if mag_alpha>1.E-8 + ave_C_b_e = old_C_b_e * (eye(3) + (1 - cos(mag_alpha)) /mag_alpha^2 ... + * Alpha_ib_b + (1 - sin(mag_alpha) / mag_alpha) / mag_alpha^2 ... + * Alpha_ib_b * Alpha_ib_b) - 0.5 * ... + Skew_symmetric([0;0;alpha_ie]) * old_C_b_e; + else + ave_C_b_e = old_C_b_e -... + 0.5 * Skew_symmetric([0;0;alpha_ie]) * old_C_b_e; + end %if mag_alpha + + % Transform specific force to body-frame resolving axes using (5.81) + f_ib_b = inv(ave_C_b_e) * f_ib_e; + +else + % If time interval is zero, set angular rate and specific force to zero + omega_ib_b = [0;0;0]; + f_ib_b = [0;0;0]; +end %if tor_i +% Ends \ No newline at end of file diff --git a/Kinematics_ECI.m b/Kinematics_ECI.m new file mode 100644 index 0000000..84d5709 --- /dev/null +++ b/Kinematics_ECI.m @@ -0,0 +1,76 @@ +function [f_ib_b,omega_ib_b] = Kinematics_ECI(tor_i,C_b_i,... + old_C_b_i,v_ib_i,old_v_ib_i,r_ib_i); +%Kinematics_ECI - calculates specific force and angular rate from input +%w.r.t and resolved along ECI-frame axes +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 1/4/2012 by Paul Groves +% +% Inputs: +% tor_i time interval between epochs (s) +% C_b_i body-to-ECI-frame coordinate transformation matrix +% old_C_b_i previous body-to-ECI-frame coordinate transformation matrix +% v_ib_i velocity of body frame w.r.t. ECI frame, resolved along +% ECI-frame axes (m/s) +% old_v_ib_i previous velocity of body frame w.r.t. ECI frame, resolved +% along ECI-frame axes (m/s) +% r_ib_i Cartesian position of body frame w.r.t. ECI frame, resolved +% along ECI-frame axes (m) +% Outputs: +% f_ib_b specific force of body frame w.r.t. ECI frame, resolved +% along body-frame axes, averaged over time interval (m/s^2) +% omega_ib_b angular rate of body frame w.r.t. ECI frame, resolved +% about body-frame axes, averaged over time interval (rad/s) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +if tor_i > 0 + + % Obtain coordinate transformation matrix from the old attitude to the new + C_old_new = C_b_i' * old_C_b_i; + + % Calculate the approximate angular rate + alpha_ib_b(1,1) = 0.5 * (C_old_new(2,3) - C_old_new(3,2)); + alpha_ib_b(2,1) = 0.5 * (C_old_new(3,1) - C_old_new(1,3)); + alpha_ib_b(3,1) = 0.5 * (C_old_new(1,2) - C_old_new(2,1)); + + % Calculate and apply the scaling factor + temp = acos(0.5 * (C_old_new(1,1) + C_old_new(2,2) + C_old_new(3,3)... + - 1.0)); + if temp>2e-5 %scaling is 1 if temp is less than this + alpha_ib_b = alpha_ib_b * temp/sin(temp); + end %if temp + + % Calculate the angular rate + omega_ib_b = alpha_ib_b / tor_i; + + % Calculate the specific force resolved about ECI-frame axes + % From (5.18) and (5.20), + f_ib_i = ((v_ib_i - old_v_ib_i) / tor_i) - Gravitation_ECI(r_ib_i); + + % Calculate the average body-to-ECI-frame coordinate transformation + % matrix over the update interval using (5.84) + mag_alpha = sqrt(alpha_ib_b' * alpha_ib_b); + Alpha_ib_b = Skew_symmetric(alpha_ib_b); + if mag_alpha>1.E-8 + ave_C_b_i = old_C_b_i * (eye(3) + (1 - cos(mag_alpha)) /mag_alpha^2 ... + * Alpha_ib_b + (1 - sin(mag_alpha) / mag_alpha) / mag_alpha^2 ... + * Alpha_ib_b * Alpha_ib_b); + else + ave_C_b_i = old_C_b_i; + end %if mag_alpha + + % Transform specific force to body-frame resolving axes using (5.81) + f_ib_b = inv(ave_C_b_i) * f_ib_i; + +else + % If time interval is zero, set angular rate and specific force to zero + omega_ib_b = [0;0;0]; + f_ib_b = [0;0;0]; +end %if tor_i +% Ends \ No newline at end of file diff --git a/Kinematics_NED.m b/Kinematics_NED.m new file mode 100644 index 0000000..06597bd --- /dev/null +++ b/Kinematics_NED.m @@ -0,0 +1,101 @@ +function [f_ib_b,omega_ib_b] = Kinematics_NED(tor_i,C_b_n,old_C_b_n,... + v_eb_n,old_v_eb_n,L_b,h_b,old_L_b,old_h_b) +%Kinematics_NED - calculates specific force and angular rate from input +%w.r.t and resolved along north, east, and down +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 1/4/2012 by Paul Groves +% +% Inputs: +% tor_i time interval between epochs (s) +% C_b_n body-to-NED coordinate transformation matrix +% old_C_b_n previous body-to-NED coordinate transformation matrix +% v_eb_n velocity of body frame w.r.t. ECEF frame, resolved along +% north, east, and down (m/s) +% old_v_eb_n previous velocity of body frame w.r.t. ECEF frame, resolved +% along north, east, and down (m/s) +% L_b latitude (rad) +% h_b height (m) +% old_L_b previous latitude (rad) +% old_h_b previous height (m) +% Outputs: +% f_ib_b specific force of body frame w.r.t. ECEF frame, resolved +% along body-frame axes, averaged over time interval (m/s^2) +% omega_ib_b angular rate of body frame w.r.t. ECEF frame, resolved +% about body-frame axes, averaged over time interval (rad/s) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Parameters +omega_ie = 7.292115E-5; % Earth rotation rate (rad/s) + +% Begins + +if tor_i > 0 + + % From (2.123) , determine the angular rate of the ECEF frame + % w.r.t the ECI frame, resolved about NED + omega_ie_n = omega_ie * [cos(old_L_b); 0; - sin(old_L_b)]; + + % From (5.44), determine the angular rate of the NED frame + % w.r.t the ECEF frame, resolved about NED + [old_R_N,old_R_E] = Radii_of_curvature(old_L_b); + [R_N,R_E] = Radii_of_curvature(L_b); + old_omega_en_n = [old_v_eb_n(2) / (old_R_E + old_h_b);... + -old_v_eb_n(1) / (old_R_N + old_h_b);... + -old_v_eb_n(2) * tan(old_L_b) / (old_R_E + old_h_b)]; + omega_en_n = [v_eb_n(2) / (R_E + h_b);... + -v_eb_n(1) / (R_N + h_b);... + -v_eb_n(2) * tan(L_b) / (R_E + h_b)]; + + % Obtain coordinate transformation matrix from the old attitude (w.r.t. + % an inertial frame) to the new using (5.77) + C_old_new = C_b_n' * (eye(3) - Skew_symmetric(omega_ie_n + 0.5 *... + omega_en_n + 0.5 * old_omega_en_n) * tor_i) * old_C_b_n; + + % Calculate the approximate angular rate w.r.t. an inertial frame + alpha_ib_b(1,1) = 0.5 * (C_old_new(2,3) - C_old_new(3,2)); + alpha_ib_b(2,1) = 0.5 * (C_old_new(3,1) - C_old_new(1,3)); + alpha_ib_b(3,1) = 0.5 * (C_old_new(1,2) - C_old_new(2,1)); + + % Calculate and apply the scaling factor + temp = acos(0.5 * (C_old_new(1,1) + C_old_new(2,2) + C_old_new(3,3)... + - 1.0)); + if temp>2e-5 %scaling is 1 if temp is less than this + alpha_ib_b = alpha_ib_b * temp/sin(temp); + end %if temp + + % Calculate the angular rate + omega_ib_b = alpha_ib_b / tor_i; + + % Calculate the specific force resolved about ECEF-frame axes + % From (5.54), + f_ib_n = ((v_eb_n - old_v_eb_n) / tor_i) - Gravity_NED(old_L_b,old_h_b)... + + Skew_symmetric(old_omega_en_n + 2 * omega_ie_n) * old_v_eb_n; + + % Calculate the average body-to-NED coordinate transformation + % matrix over the update interval using (5.84) and (5.86) + mag_alpha = sqrt(alpha_ib_b' * alpha_ib_b); + Alpha_ib_b = Skew_symmetric(alpha_ib_b); + if mag_alpha>1.E-8 + ave_C_b_n = old_C_b_n * (eye(3) + (1 - cos(mag_alpha)) /mag_alpha^2 ... + * Alpha_ib_b + (1 - sin(mag_alpha) / mag_alpha) / mag_alpha^2 ... + * Alpha_ib_b * Alpha_ib_b) -... + 0.5 * Skew_symmetric(old_omega_en_n + omega_ie_n) * old_C_b_n; + else + ave_C_b_n = old_C_b_n -... + 0.5 * Skew_symmetric(old_omega_en_n + omega_ie_n) * old_C_b_n; + end %if mag_alpha + + % Transform specific force to body-frame resolving axes using (5.81) + f_ib_b = inv(ave_C_b_n) * f_ib_n; + +else + % If time interval is zero, set angular rate and specific force to zero + omega_ib_b = [0;0;0]; + f_ib_b = [0;0;0]; +end %if tor_i +% Ends \ No newline at end of file diff --git a/LC_KF_Epoch.m b/LC_KF_Epoch.m new file mode 100644 index 0000000..e14e2c4 --- /dev/null +++ b/LC_KF_Epoch.m @@ -0,0 +1,128 @@ +function [est_C_b_e_new,est_v_eb_e_new,est_r_eb_e_new,est_IMU_bias_new,... + P_matrix_new] = LC_KF_Epoch(GNSS_r_eb_e,GNSS_v_eb_e,tor_s,... + est_C_b_e_old,est_v_eb_e_old,est_r_eb_e_old,est_IMU_bias_old,... + P_matrix_old,meas_f_ib_b,est_L_b_old,LC_KF_config) +%LC_KF_Epoch - Implements one cycle of the loosely coupled INS/GNSS +% Kalman filter plus closed-loop correction of all inertial states +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 12/4/2012 by Paul Groves +% +% Inputs: +% GNSS_r_eb_e GNSS estimated ECEF user position (m) +% GNSS_v_eb_e GNSS estimated ECEF user velocity (m/s) +% tor_s propagation interval (s) +% est_C_b_e_old prior estimated body to ECEF coordinate +% transformation matrix +% est_v_eb_e_old prior estimated ECEF user velocity (m/s) +% est_r_eb_e_old prior estimated ECEF user position (m) +% est_IMU_bias_old prior estimated IMU biases (body axes) +% P_matrix_old previous Kalman filter error covariance matrix +% meas_f_ib_b measured specific force +% est_L_b_old previous latitude solution +% LC_KF_config +% .gyro_noise_PSD Gyro noise PSD (rad^2/s) +% .accel_noise_PSD Accelerometer noise PSD (m^2 s^-3) +% .accel_bias_PSD Accelerometer bias random walk PSD (m^2 s^-5) +% .gyro_bias_PSD Gyro bias random walk PSD (rad^2 s^-3) +% .pos_meas_SD Position measurement noise SD per axis (m) +% .vel_meas_SD Velocity measurement noise SD per axis (m/s) +% +% Outputs: +% est_C_b_e_new updated estimated body to ECEF coordinate +% transformation matrix +% est_v_eb_e_new updated estimated ECEF user velocity (m/s) +% est_r_eb_e_new updated estimated ECEF user position (m) +% est_IMU_bias_new updated estimated IMU biases +% Rows 1-3 estimated accelerometer biases (m/s^2) +% Rows 4-6 estimated gyro biases (rad/s) +% P_matrix_new updated Kalman filter error covariance matrix + + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants (sone of these could be changed to inputs at a later date) +c = 299792458; % Speed of light in m/s +omega_ie = 7.292115E-5; % Earth rotation rate in rad/s +R_0 = 6378137; %WGS84 Equatorial radius in meters +e = 0.0818191908425; %WGS84 eccentricity + +% Begins + +% Skew symmetric matrix of Earth rate +Omega_ie = Skew_symmetric([0,0,omega_ie]); + +% SYSTEM PROPAGATION PHASE + +% 1. Determine transition matrix using (14.50) (first-order approx) +Phi_matrix = eye(15); +Phi_matrix(1:3,1:3) = Phi_matrix(1:3,1:3) - Omega_ie * tor_s; +Phi_matrix(1:3,13:15) = est_C_b_e_old * tor_s; +Phi_matrix(4:6,1:3) = -tor_s * Skew_symmetric(est_C_b_e_old * meas_f_ib_b); +Phi_matrix(4:6,4:6) = Phi_matrix(4:6,4:6) - 2 * Omega_ie * tor_s; +geocentric_radius = R_0 / sqrt(1 - (e * sin(est_L_b_old))^2) *... + sqrt(cos(est_L_b_old)^2 + (1 - e^2)^2 * sin(est_L_b_old)^2); % from (2.137) +Phi_matrix(4:6,7:9) = -tor_s * 2 * Gravity_ECEF(est_r_eb_e_old) /... + geocentric_radius * est_r_eb_e_old' / sqrt (est_r_eb_e_old' *... + est_r_eb_e_old); +Phi_matrix(4:6,10:12) = est_C_b_e_old * tor_s; +Phi_matrix(7:9,4:6) = eye(3) * tor_s; + +% 2. Determine approximate system noise covariance matrix using (14.82) +Q_prime_matrix = zeros(15); +Q_prime_matrix(1:3,1:3) = eye(3) * LC_KF_config.gyro_noise_PSD * tor_s; +Q_prime_matrix(4:6,4:6) = eye(3) * LC_KF_config.accel_noise_PSD * tor_s; +Q_prime_matrix(10:12,10:12) = eye(3) * LC_KF_config.accel_bias_PSD * tor_s; +Q_prime_matrix(13:15,13:15) = eye(3) * LC_KF_config.gyro_bias_PSD * tor_s; + +% 3. Propagate state estimates using (3.14) noting that all states are zero +% due to closed-loop correction. +x_est_propagated(1:15,1) = 0; + +% 4. Propagate state estimation error covariance matrix using (3.46) +P_matrix_propagated = Phi_matrix * (P_matrix_old + 0.5 * Q_prime_matrix) *... + Phi_matrix' + 0.5 * Q_prime_matrix; + +% MEASUREMENT UPDATE PHASE + +% 5. Set-up measurement matrix using (14.115) +H_matrix = zeros(6,15); +H_matrix(1:3,7:9) = -eye(3); +H_matrix(4:6,4:6) = -eye(3); + +% 6. Set-up measurement noise covariance matrix assuming all components of +% GNSS position and velocity are independent and have equal variance. +R_matrix(1:3,1:3) = eye(3) * LC_KF_config.pos_meas_SD^2; +R_matrix(1:3,4:6) = zeros(3); +R_matrix(4:6,1:3) = zeros(3); +R_matrix(4:6,4:6) = eye(3) * LC_KF_config.vel_meas_SD^2; + +% 7. Calculate Kalman gain using (3.21) +K_matrix = P_matrix_propagated * H_matrix' * inv(H_matrix *... + P_matrix_propagated * H_matrix' + R_matrix); + +% 8. Formulate measurement innovations using (14.102), noting that zero +% lever arm is assumed here +delta_z(1:3,1) = GNSS_r_eb_e -est_r_eb_e_old; +delta_z(4:6,1) = GNSS_v_eb_e -est_v_eb_e_old; + +% 9. Update state estimates using (3.24) +x_est_new = x_est_propagated + K_matrix * delta_z; + +% 10. Update state estimation error covariance matrix using (3.25) +P_matrix_new = (eye(15) - K_matrix * H_matrix) * P_matrix_propagated; + +% CLOSED-LOOP CORRECTION + +% Correct attitude, velocity, and position using (14.7-9) +est_C_b_e_new = (eye(3) - Skew_symmetric(x_est_new(1:3))) * est_C_b_e_old; +est_v_eb_e_new = est_v_eb_e_old - x_est_new(4:6); +est_r_eb_e_new = est_r_eb_e_old - x_est_new(7:9); + +% Update IMU bias estimates +est_IMU_bias_new = est_IMU_bias_old + x_est_new(10:15); + +% Ends \ No newline at end of file diff --git a/License.txt b/License.txt new file mode 100644 index 0000000..ca3c71b --- /dev/null +++ b/License.txt @@ -0,0 +1,24 @@ +This software is distributed under a Modified BSD License as follows: +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the distribution. +* * Neither the authors' names nor the +* names of its contributors may be used to endorse or promote products +* derived from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE AUTHORS ``AS IS'' AND ANY +* EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY +* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +* diff --git a/Loosely_coupled_INS_GNSS.m b/Loosely_coupled_INS_GNSS.m new file mode 100644 index 0000000..b48dcd1 --- /dev/null +++ b/Loosely_coupled_INS_GNSS.m @@ -0,0 +1,338 @@ +function [out_profile,out_errors,out_IMU_bias_est,out_clock,out_KF_SD] =... + Loosely_coupled_INS_GNSS(in_profile,no_epochs,initialization_errors,... + IMU_errors,GNSS_config,LC_KF_config) +%Loosely_coupled_INS_GNSS - Simulates inertial navigation using ECEF +% navigation equations and kinematic model, GNSS using a least-squares +% positioning algorithm, and loosely-coupled INS/GNSS integration. +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 12/4/2012 by Paul Groves +% +% Inputs: +% in_profile True motion profile array +% no_epochs Number of epochs of profile data +% initialization_errors +% .delta_r_eb_n position error resolved along NED (m) +% .delta_v_eb_n velocity error resolved along NED (m/s) +% .delta_eul_nb_n attitude error as NED Euler angles (rad) +% IMU_errors +% .delta_r_eb_n position error resolved along NED (m) +% .b_a Accelerometer biases (m/s^2) +% .b_g Gyro biases (rad/s) +% .M_a Accelerometer scale factor and cross coupling errors +% .M_g Gyro scale factor and cross coupling errors +% .G_g Gyro g-dependent biases (rad-sec/m) +% .accel_noise_root_PSD Accelerometer noise root PSD (m s^-1.5) +% .gyro_noise_root_PSD Gyro noise root PSD (rad s^-0.5) +% .accel_quant_level Accelerometer quantization level (m/s^2) +% .gyro_quant_level Gyro quantization level (rad/s) +% GNSS_config +% .epoch_interval Interval between GNSS epochs (s) +% .init_est_r_ea_e Initial estimated position (m; ECEF) +% .no_sat Number of satellites in constellation +% .r_os Orbital radius of satellites (m) +% .inclination Inclination angle of satellites (deg) +% .const_delta_lambda Longitude offset of constellation (deg) +% .const_delta_t Timing offset of constellation (s) +% .mask_angle Mask angle (deg) +% .SIS_err_SD Signal in space error SD (m) +% .zenith_iono_err_SD Zenith ionosphere error SD (m) +% .zenith_trop_err_SD Zenith troposphere error SD (m) +% .code_track_err_SD Code tracking error SD (m) +% .rate_track_err_SD Range rate tracking error SD (m/s) +% .rx_clock_offset Receiver clock offset at time=0 (m) +% .rx_clock_drift Receiver clock drift at time=0 (m/s) +% LC_KF_config +% .init_att_unc Initial attitude uncertainty per axis (rad) +% .init_vel_unc Initial velocity uncertainty per axis (m/s) +% .init_pos_unc Initial position uncertainty per axis (m) +% .init_b_a_unc Initial accel. bias uncertainty (m/s^2) +% .init_b_g_unc Initial gyro. bias uncertainty (rad/s) +% .gyro_noise_PSD Gyro noise PSD (rad^2/s) +% .accel_noise_PSD Accelerometer noise PSD (m^2 s^-3) +% .accel_bias_PSD Accelerometer bias random walk PSD (m^2 s^-5) +% .gyro_bias_PSD Gyro bias random walk PSD (rad^2 s^-3) +% .pos_meas_SD Position measurement noise SD per axis (m) +% .vel_meas_SD Velocity measurement noise SD per axis (m/s) +% +% Outputs: +% out_profile Navigation solution as a motion profile array +% out_errors Navigation solution error array +% out_IMU_bias_est Kalman filter IMU bias estimate array +% out_clock GNSS Receiver clock estimate array +% out_KF_SD Output Kalman filter state uncertainties +% +% Format of motion profiles: +% Column 1: time (sec) +% Column 2: latitude (rad) +% Column 3: longitude (rad) +% Column 4: height (m) +% Column 5: north velocity (m/s) +% Column 6: east velocity (m/s) +% Column 7: down velocity (m/s) +% Column 8: roll angle of body w.r.t NED (rad) +% Column 9: pitch angle of body w.r.t NED (rad) +% Column 10: yaw angle of body w.r.t NED (rad) +% +% Format of error array: +% Column 1: time (sec) +% Column 2: north position error (m) +% Column 3: east position error (m) +% Column 4: down position error (m) +% Column 5: north velocity error (m/s) +% Column 6: east velocity error (m/s) +% Column 7: down velocity (error m/s) +% Column 8: attitude error about north (rad) +% Column 9: attitude error about east (rad) +% Column 10: attitude error about down = heading error (rad) +% +% Format of output IMU biases array: +% Column 1: time (sec) +% Column 2: estimated X accelerometer bias (m/s^2) +% Column 3: estimated Y accelerometer bias (m/s^2) +% Column 4: estimated Z accelerometer bias (m/s^2) +% Column 5: estimated X gyro bias (rad/s) +% Column 6: estimated Y gyro bias (rad/s) +% Column 7: estimated Z gyro bias (rad/s) +% +% Format of receiver clock array: +% Column 1: time (sec) +% Column 2: estimated clock offset (m) +% Column 3: estimated clock drift (m/s) +% +% Format of KF state uncertainties array: +% Column 1: time (sec) +% Column 2: X attitude error uncertainty (rad) +% Column 3: Y attitude error uncertainty (rad) +% Column 4: Z attitude error uncertainty (rad) +% Column 5: X velocity error uncertainty (m/s) +% Column 6: Y velocity error uncertainty (m/s) +% Column 7: Z velocity error uncertainty (m/s) +% Column 8: X position error uncertainty (m) +% Column 9: Y position error uncertainty (m) +% Column 10: Z position error uncertainty (m) +% Column 11: X accelerometer bias uncertainty (m/s^2) +% Column 12: Y accelerometer bias uncertainty (m/s^2) +% Column 13: Z accelerometer bias uncertainty (m/s^2) +% Column 14: X gyro bias uncertainty (rad/s) +% Column 15: Y gyro bias uncertainty (rad/s) +% Column 16: Z gyro bias uncertainty (rad/s) +% Column 17: clock offset uncertainty (m) +% Column 18: clock drift uncertainty (m/s) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Initialize true navigation solution +old_time = in_profile(1,1); +true_L_b = in_profile(1,2); +true_lambda_b = in_profile(1,3); +true_h_b = in_profile(1,4); +true_v_eb_n = in_profile(1,5:7)'; +true_eul_nb = in_profile(1,8:10)'; +true_C_b_n = Euler_to_CTM(true_eul_nb)'; +[old_true_r_eb_e,old_true_v_eb_e,old_true_C_b_e] =... + NED_to_ECEF(true_L_b,true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); + +% Determine satellite positions and velocities +[sat_r_es_e,sat_v_es_e] = Satellite_positions_and_velocities(old_time,... + GNSS_config); + +% Initialize the GNSS biases. Note that these are assumed constant throughout +% the simulation and are based on the initial elevation angles. Therefore, +% this function is unsuited to simulations longer than about 30 min. +GNSS_biases = Initialize_GNSS_biases(sat_r_es_e,old_true_r_eb_e,true_L_b,... + true_lambda_b,GNSS_config); + +% Generate GNSS measurements +[GNSS_measurements,no_GNSS_meas] = Generate_GNSS_measurements(old_time,... + sat_r_es_e,sat_v_es_e,old_true_r_eb_e,true_L_b,true_lambda_b,... + old_true_v_eb_e,GNSS_biases,GNSS_config); + +% Determine Least-squares GNSS position solution and use to initialize INS +[GNSS_r_eb_e,GNSS_v_eb_e,est_clock] = GNSS_LS_position_velocity(... + GNSS_measurements,no_GNSS_meas,GNSS_config.init_est_r_ea_e,[0;0;0]); +old_est_r_eb_e = GNSS_r_eb_e; +old_est_v_eb_e = GNSS_v_eb_e; +[old_est_L_b,old_est_lambda_b,old_est_h_b,old_est_v_eb_n] =... + pv_ECEF_to_NED(old_est_r_eb_e,old_est_v_eb_e); +est_L_b = old_est_L_b; + +% Initialize estimated attitude solution +old_est_C_b_n = Initialize_NED_attitude(true_C_b_n,initialization_errors); +[temp1,temp2,old_est_C_b_e] = NED_to_ECEF(old_est_L_b,... + old_est_lambda_b,old_est_h_b,old_est_v_eb_n,old_est_C_b_n); + +% Initialize output profile record and errors record +out_profile = zeros(no_epochs,10); +out_errors = zeros(no_epochs,10); + +% Generate output profile record +out_profile(1,1) = old_time; +out_profile(1,2) = old_est_L_b; +out_profile(1,3) = old_est_lambda_b; +out_profile(1,4) = old_est_h_b; +out_profile(1,5:7) = old_est_v_eb_n'; +out_profile(1,8:10) = CTM_to_Euler(old_est_C_b_n')'; + +% Determine errors and generate output record +[delta_r_eb_n,delta_v_eb_n,delta_eul_nb_n] = Calculate_errors_NED(... + old_est_L_b,old_est_lambda_b,old_est_h_b,old_est_v_eb_n,old_est_C_b_n,... + true_L_b,true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); +out_errors(1,1) = old_time; +out_errors(1,2:4) = delta_r_eb_n'; +out_errors(1,5:7) = delta_v_eb_n'; +out_errors(1,8:10) = delta_eul_nb_n'; + +% Initialize Kalman filter P matrix and IMU bias states +P_matrix = Initialize_LC_P_matrix(LC_KF_config); +est_IMU_bias = zeros(6,1); + +% Initialize IMU quantization residuals +quant_residuals = [0;0;0;0;0;0]; + +% Generate IMU bias and clock output records +out_IMU_bias_est(1,1) = old_time; +out_IMU_bias_est(1,2:7) = est_IMU_bias'; +out_clock(1,1) = old_time; +out_clock(1,2:3) = est_clock; + +% Generate KF uncertainty record +out_KF_SD(1,1) = old_time; +for i =1:15 + out_KF_SD(1,i+1) = sqrt(P_matrix(i,i)); +end % for i + +% Initialize GNSS model timing +time_last_GNSS = old_time; +GNSS_epoch = 1; + +% Progress bar +dots = '....................'; +bars = '||||||||||||||||||||'; +rewind = '\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b'; +fprintf(strcat('Processing: ',dots)); +progress_mark = 0; +progress_epoch = 0; + +% Main loop +for epoch = 2:no_epochs + + % Update progress bar + if (epoch - progress_epoch) > (no_epochs/20) + progress_mark = progress_mark + 1; + progress_epoch = epoch; + fprintf(strcat(rewind,bars(1:progress_mark),... + dots(1:(20 - progress_mark)))); + end % if epoch + + % Input data from motion profile + time = in_profile(epoch,1); + true_L_b = in_profile(epoch,2); + true_lambda_b = in_profile(epoch,3); + true_h_b = in_profile(epoch,4); + true_v_eb_n = in_profile(epoch,5:7)'; + true_eul_nb = in_profile(epoch,8:10)'; + true_C_b_n = Euler_to_CTM(true_eul_nb)'; + [true_r_eb_e,true_v_eb_e,true_C_b_e] =... + NED_to_ECEF(true_L_b,true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); + + % Time interval + tor_i = time - old_time; + + % Calculate specific force and angular rate + [true_f_ib_b,true_omega_ib_b] = Kinematics_ECEF(tor_i,true_C_b_e,... + old_true_C_b_e,true_v_eb_e,old_true_v_eb_e,old_true_r_eb_e); + + % Simulate IMU errors + [meas_f_ib_b,meas_omega_ib_b,quant_residuals] = IMU_model(tor_i,... + true_f_ib_b,true_omega_ib_b,IMU_errors,quant_residuals); + + % Correct IMU errors + meas_f_ib_b = meas_f_ib_b - est_IMU_bias(1:3); + meas_omega_ib_b = meas_omega_ib_b - est_IMU_bias(4:6); + + % Update estimated navigation solution + [est_r_eb_e,est_v_eb_e,est_C_b_e] = Nav_equations_ECEF(tor_i,... + old_est_r_eb_e,old_est_v_eb_e,old_est_C_b_e,meas_f_ib_b,... + meas_omega_ib_b); + + % Determine whether to update GNSS simulation and run Kalman filter + if (time - time_last_GNSS) >= GNSS_config.epoch_interval + GNSS_epoch = GNSS_epoch + 1; + tor_s = time - time_last_GNSS; % KF time interval + time_last_GNSS = time; + + % Determine satellite positions and velocities + [sat_r_es_e,sat_v_es_e] = Satellite_positions_and_velocities(time,... + GNSS_config); + + % Generate GNSS measurements + [GNSS_measurements,no_GNSS_meas] = Generate_GNSS_measurements(... + time,sat_r_es_e,sat_v_es_e,true_r_eb_e,true_L_b,true_lambda_b,... + true_v_eb_e,GNSS_biases,GNSS_config); + + % Determine GNSS position solution + [GNSS_r_eb_e,GNSS_v_eb_e,est_clock] = GNSS_LS_position_velocity(... + GNSS_measurements,no_GNSS_meas,GNSS_r_eb_e,GNSS_v_eb_e); + + % Run Integration Kalman filter + [est_C_b_e,est_v_eb_e,est_r_eb_e,est_IMU_bias,P_matrix] =... + LC_KF_Epoch(GNSS_r_eb_e,GNSS_v_eb_e,tor_s,est_C_b_e,... + est_v_eb_e,est_r_eb_e,est_IMU_bias,P_matrix,meas_f_ib_b,... + est_L_b,LC_KF_config); + + % Generate IMU bias and clock output records + out_IMU_bias_est(GNSS_epoch,1) = time; + out_IMU_bias_est(GNSS_epoch,2:7) = est_IMU_bias'; + out_clock(GNSS_epoch,1) = time; + out_clock(GNSS_epoch,2:3) = est_clock; + + % Generate KF uncertainty output record + out_KF_SD(GNSS_epoch,1) = time; + for i =1:15 + out_KF_SD(GNSS_epoch,i+1) = sqrt(P_matrix(i,i)); + end % for i + + end % if time + + % Convert navigation solution to NED + [est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n] =... + ECEF_to_NED(est_r_eb_e,est_v_eb_e,est_C_b_e); + + % Generate output profile record + out_profile(epoch,1) = time; + out_profile(epoch,2) = est_L_b; + out_profile(epoch,3) = est_lambda_b; + out_profile(epoch,4) = est_h_b; + out_profile(epoch,5:7) = est_v_eb_n'; + out_profile(epoch,8:10) = CTM_to_Euler(est_C_b_n')'; + + % Determine errors and generate output record + [delta_r_eb_n,delta_v_eb_n,delta_eul_nb_n] = Calculate_errors_NED(... + est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n,true_L_b,... + true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); + out_errors(epoch,1) = time; + out_errors(epoch,2:4) = delta_r_eb_n'; + out_errors(epoch,5:7) = delta_v_eb_n'; + out_errors(epoch,8:10) = delta_eul_nb_n'; + + % Reset old values + old_time = time; + old_true_r_eb_e = true_r_eb_e; + old_true_v_eb_e = true_v_eb_e; + old_true_C_b_e = true_C_b_e; + old_est_r_eb_e = est_r_eb_e; + old_est_v_eb_e = est_v_eb_e; + old_est_C_b_e = est_C_b_e; + +end %epoch + +% Complete progress bar +fprintf(strcat(rewind,bars,'\n')); + +% Ends \ No newline at end of file diff --git a/NED_to_ECEF.m b/NED_to_ECEF.m new file mode 100644 index 0000000..b8e1eaf --- /dev/null +++ b/NED_to_ECEF.m @@ -0,0 +1,57 @@ +function [r_eb_e,v_eb_e,C_b_e] = NED_to_ECEF(L_b,lambda_b,h_b,v_eb_n,C_b_n) +%NED_to_ECEF - Converts curvilinear to Cartesian position, velocity +%resolving axes from NED to ECEF and attitude from NED- to ECEF-referenced +%当地导航坐标系转换到地心地固坐标系 +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 2/4/2012 by Paul Groves +% +% Inputs: +% L_b latitude (rad) +% lambda_b longitude (rad) +% h_b height (m) +% v_eb_n velocity of body frame w.r.t. ECEF frame, resolved along +% north, east, and down (m/s) +% C_b_n body-to-NED coordinate transformation matrix +% +% Outputs: +% r_eb_e Cartesian position of body frame w.r.t. ECEF frame, resolved +% along ECEF-frame axes (m) +% v_eb_e velocity of body frame w.r.t. ECEF frame, resolved along +% ECEF-frame axes (m/s) +% C_b_e body-to-ECEF-frame coordinate transformation matrix + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Parameters +R_0 = 6378137; %WGS84 Equatorial radius in meters +e = 0.0818191908425; %WGS84 eccentricity + +% Begins + +% Calculate transverse radius of curvature using (2.105) +R_E = R_0 / sqrt(1 - (e * sin(L_b))^2); + +% Convert position using (2.112) +cos_lat = cos(L_b); +sin_lat = sin(L_b); +cos_long = cos(lambda_b); +sin_long = sin(lambda_b); +r_eb_e = [(R_E + h_b) * cos_lat * cos_long;... + (R_E + h_b) * cos_lat * sin_long;... + ((1 - e^2) * R_E + h_b) * sin_lat]; + +% Calculate ECEF to NED coordinate transformation matrix using (2.150) +C_e_n = [-sin_lat * cos_long, -sin_lat * sin_long, cos_lat;... + -sin_long, cos_long, 0;... + -cos_lat * cos_long, -cos_lat * sin_long, -sin_lat]; + +% Transform velocity using (2.73) +v_eb_e = C_e_n' * v_eb_n; + +% Transform attitude using (2.15) +C_b_e = C_e_n' * C_b_n; + +% Ends \ No newline at end of file diff --git a/Nav_equations_ECEF.m b/Nav_equations_ECEF.m new file mode 100644 index 0000000..97b1282 --- /dev/null +++ b/Nav_equations_ECEF.m @@ -0,0 +1,87 @@ +function [r_eb_e,v_eb_e,C_b_e] = Nav_equations_ECEF(tor_i,old_r_eb_e,... + old_v_eb_e,old_C_b_e,f_ib_b,omega_ib_b) +%Nav_equations_ECEF - Runs precision ECEF-frame inertial navigation +%equations +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 1/4/2012 by Paul Groves +% +% Inputs: +% tor_i time interval between epochs (s) +% old_r_eb_e previous Cartesian position of body frame w.r.t. ECEF +% frame, resolved along ECEF-frame axes (m) +% old_C_b_e previous body-to-ECEF-frame coordinate transformation matrix +% old_v_eb_e previous velocity of body frame w.r.t. ECEF frame, resolved +% along ECEF-frame axes (m/s) +% f_ib_b specific force of body frame w.r.t. ECEF frame, resolved +% along body-frame axes, averaged over time interval (m/s^2) +% omega_ib_b angular rate of body frame w.r.t. ECEF frame, resolved +% about body-frame axes, averaged over time interval (rad/s) +% Outputs: +% r_eb_e Cartesian position of body frame w.r.t. ECEF frame, resolved +% along ECEF-frame axes (m) +% v_eb_e velocity of body frame w.r.t. ECEF frame, resolved along +% ECEF-frame axes (m/s) +% C_b_e body-to-ECEF-frame coordinate transformation matrix + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% parameters +omega_ie = 7.292115E-5; % Earth rotation rate (rad/s) + +% Begins + +% ATTITUDE UPDATE +% From (2.145) determine the Earth rotation over the update interval +% C_Earth = C_e_i' * old_C_e_i +alpha_ie = omega_ie * tor_i; +C_Earth = [cos(alpha_ie), sin(alpha_ie), 0;... + -sin(alpha_ie), cos(alpha_ie), 0;... + 0, 0, 1]; + +% Calculate attitude increment, magnitude, and skew-symmetric matrix +alpha_ib_b = omega_ib_b * tor_i; +mag_alpha = sqrt(alpha_ib_b' * alpha_ib_b); +Alpha_ib_b = Skew_symmetric(alpha_ib_b); + +% Obtain coordinate transformation matrix from the new attitude w.r.t. an +% inertial frame to the old using Rodrigues' formula, (5.73) +if mag_alpha>1.E-8 + C_new_old = eye(3) + sin(mag_alpha) / mag_alpha * Alpha_ib_b +... + (1 - cos(mag_alpha)) / mag_alpha^2 * Alpha_ib_b * Alpha_ib_b; +else + C_new_old = eye(3) + Alpha_ib_b; +end %if mag_alpha + +% Update attitude using (5.75) +C_b_e = C_Earth * old_C_b_e * C_new_old; + +% SPECIFIC FORCE FRAME TRANSFORMATION +% Calculate the average body-to-ECEF-frame coordinate transformation +% matrix over the update interval using (5.84) and (5.85) +if mag_alpha>1.E-8 + ave_C_b_e = old_C_b_e * (eye(3) + (1 - cos(mag_alpha)) / mag_alpha^2 ... + * Alpha_ib_b + (1 - sin(mag_alpha) / mag_alpha) / mag_alpha^2 ... + * Alpha_ib_b * Alpha_ib_b) - 0.5 * Skew_symmetric([0;0;alpha_ie])... + * old_C_b_e; +else + ave_C_b_e = old_C_b_e - 0.5 * Skew_symmetric([0;0;alpha_ie]) *... + old_C_b_e; +end %if mag_alpha + +% Transform specific force to ECEF-frame resolving axes using (5.85) +f_ib_e = ave_C_b_e * f_ib_b; + +% UPDATE VELOCITY +% From (5.36), +v_eb_e = old_v_eb_e + tor_i * (f_ib_e + Gravity_ECEF(old_r_eb_e) -... + 2 * Skew_symmetric([0;0;omega_ie]) * old_v_eb_e); + +% UPDATE CARTESIAN POSITION +% From (5.38), +r_eb_e = old_r_eb_e + (v_eb_e + old_v_eb_e) * 0.5 * tor_i; + +% Ends \ No newline at end of file diff --git a/Nav_equations_ECI.m b/Nav_equations_ECI.m new file mode 100644 index 0000000..493fe07 --- /dev/null +++ b/Nav_equations_ECI.m @@ -0,0 +1,74 @@ +function [r_ib_i,v_ib_i,C_b_i] = Nav_equations_ECI(tor_i,old_r_ib_i,... + old_v_ib_i,old_C_b_i,f_ib_b,omega_ib_b) +%Nav_equations_ECI - Runs precision ECI-frame inertial navigation +%equations +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 1/4/2012 by Paul Groves +% +% Inputs: +% tor_i time interval between epochs (s) +% old_r_ib_i previous Cartesian position of body frame w.r.t. ECI +% frame, resolved along ECI-frame axes (m) +% old_C_b_i previous body-to-ECI-frame coordinate transformation matrix +% old_v_ib_i previous velocity of body frame w.r.t. ECI frame, resolved +% along ECI-frame axes (m/s) +% f_ib_b specific force of body frame w.r.t. ECI frame, resolved +% along body-frame axes, averaged over time interval (m/s^2) +% omega_ib_b angular rate of body frame w.r.t. ECI frame, resolved +% about body-frame axes, averaged over time interval (rad/s) +% Outputs: +% r_ib_i Cartesian position of body frame w.r.t. ECI frame, resolved +% along ECI-frame axes (m) +% v_ib_i velocity of body frame w.r.t. ECI frame, resolved along +% ECI-frame axes (m/s) +% C_b_i body-to-ECI-frame coordinate transformation matrix + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% ATTITUDE UPDATE +% Calculate attitude increment, magnitude, and skew-symmetric matrix +alpha_ib_b = omega_ib_b * tor_i; +mag_alpha = sqrt(alpha_ib_b' * alpha_ib_b); +Alpha_ib_b = Skew_symmetric(alpha_ib_b); + +% Obtain coordinate transformation matrix from the new attitude to the old +% using Rodrigues' formula, (5.73) +if mag_alpha>1.E-8 + C_new_old = eye(3) + sin(mag_alpha) / mag_alpha * Alpha_ib_b +... + (1 - cos(mag_alpha)) / mag_alpha^2 * Alpha_ib_b * Alpha_ib_b; +else + C_new_old = eye(3) + Alpha_ib_b; +end %if mag_alpha + +% Update attitude +C_b_i = old_C_b_i * C_new_old; + +% SPECIFIC FORCE FRAME TRANSFORMATION +% Calculate the average body-to-ECI-frame coordinate transformation +% matrix over the update interval using (5.84) +if mag_alpha>1.E-8 + ave_C_b_i = old_C_b_i * (eye(3) + (1 - cos(mag_alpha)) / mag_alpha^2 ... + * Alpha_ib_b + (1 - sin(mag_alpha) / mag_alpha) / mag_alpha^2 ... + * Alpha_ib_b * Alpha_ib_b); +else + ave_C_b_i = old_C_b_i; +end %if mag_alpha + +% Transform specific force to ECI-frame resolving axes using (5.81) +f_ib_i = ave_C_b_i * f_ib_b; + +% UPDATE VELOCITY +% From (5.18) and (5.20), +v_ib_i = old_v_ib_i + tor_i * (f_ib_i + Gravitation_ECI(old_r_ib_i)); + +% UPDATE CARTESIAN POSITION +% From (5.23), +r_ib_i = old_r_ib_i + (v_ib_i + old_v_ib_i) * 0.5 * tor_i; + +% Ends \ No newline at end of file diff --git a/Nav_equations_NED.m b/Nav_equations_NED.m new file mode 100644 index 0000000..123ab7a --- /dev/null +++ b/Nav_equations_NED.m @@ -0,0 +1,113 @@ +function [L_b,lambda_b,h_b,v_eb_n,C_b_n] = Nav_equations_NED(tor_i,... + old_L_b,old_lambda_b,old_h_b,old_v_eb_n,old_C_b_n,f_ib_b,omega_ib_b) +%Nav_equations_NED - Runs precision local-navigation-frame inertial +%navigation equations (Note: only the attitude update and specific force +%frame transformation phases are precise.) +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 1/4/2012 by Paul Groves +% +% Inputs: +% tor_i time interval between epochs (s) +% old_L_b previous latitude (rad) +% old_lambda_b previous longitude (rad) +% old_h_b previous height (m) +% old_C_b_n previous body-to-NED coordinate transformation matrix +% old_v_eb_n previous velocity of body frame w.r.t. ECEF frame, resolved +% along north, east, and down (m/s) +% f_ib_b specific force of body frame w.r.t. ECEF frame, resolved +% along body-frame axes, averaged over time interval (m/s^2) +% omega_ib_b angular rate of body frame w.r.t. ECEF frame, resolved +% about body-frame axes, averaged over time interval (rad/s) +% Outputs: +% L_b latitude (rad) +% lambda_b longitude (rad) +% h_b height (m) +% v_eb_n velocity of body frame w.r.t. ECEF frame, resolved along +% north, east, and down (m/s) +% C_b_n body-to-NED coordinate transformation matrix + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% parameters +omega_ie = 7.292115E-5; % Earth rotation rate (rad/s) + +% Begins + +% PRELIMINARIES +% Calculate attitude increment, magnitude, and skew-symmetric matrix +alpha_ib_b = omega_ib_b * tor_i; +mag_alpha = sqrt(alpha_ib_b' * alpha_ib_b); +Alpha_ib_b = Skew_symmetric(alpha_ib_b); + +% From (2.123) , determine the angular rate of the ECEF frame +% w.r.t the ECI frame, resolved about NED +omega_ie_n = omega_ie * [cos(old_L_b); 0; - sin(old_L_b)]; + +% From (5.44), determine the angular rate of the NED frame +% w.r.t the ECEF frame, resolved about NED +[old_R_N,old_R_E] = Radii_of_curvature(old_L_b); +old_omega_en_n = [old_v_eb_n(2) / (old_R_E + old_h_b);... + -old_v_eb_n(1) / (old_R_N + old_h_b);... + -old_v_eb_n(2) * tan(old_L_b) / (old_R_E + old_h_b)]; + +% SPECIFIC FORCE FRAME TRANSFORMATION +% Calculate the average body-to-ECEF-frame coordinate transformation +% matrix over the update interval using (5.84) and (5.86) +if mag_alpha>1.E-8 + ave_C_b_n = old_C_b_n * (eye(3) + (1 - cos(mag_alpha)) / mag_alpha^2 ... + * Alpha_ib_b + (1 - sin(mag_alpha) / mag_alpha) / mag_alpha^2 ... + * Alpha_ib_b * Alpha_ib_b) -... + 0.5 * Skew_symmetric(old_omega_en_n + omega_ie_n) * old_C_b_n; +else + ave_C_b_n = old_C_b_n -... + 0.5 * Skew_symmetric(old_omega_en_n + omega_ie_n) * old_C_b_n; +end %if mag_alpha + +% Transform specific force to ECEF-frame resolving axes using (5.86) +f_ib_n = ave_C_b_n * f_ib_b; + +% UPDATE VELOCITY +% From (5.54), +v_eb_n = old_v_eb_n + tor_i * (f_ib_n + Gravity_NED(old_L_b,old_h_b) -... + Skew_symmetric(old_omega_en_n + 2 * omega_ie_n) * old_v_eb_n); + +% UPDATE CURVILINEAR POSITION +% Update height using (5.56) +h_b = old_h_b - 0.5 * tor_i * (old_v_eb_n(3) + v_eb_n(3)); + +% Update latitude using (5.56) +L_b = old_L_b + 0.5 * tor_i * (old_v_eb_n(1) / (old_R_N + old_h_b) +... + v_eb_n(1) / (old_R_N + h_b)); + +% Calculate meridian and transverse radii of curvature +[R_N,R_E]= Radii_of_curvature(L_b); + +% Update longitude using (5.56) +lambda_b = old_lambda_b + 0.5 * tor_i * (old_v_eb_n(2) / ((old_R_E +... + old_h_b) * cos(old_L_b)) + v_eb_n(2) / ((R_E + h_b) * cos(L_b))); + +% ATTITUDE UPDATE +% From (5.44), determine the angular rate of the NED frame +% w.r.t the ECEF frame, resolved about NED +omega_en_n = [v_eb_n(2) / (R_E + h_b);... + -v_eb_n(1) / (R_N + h_b);... + -v_eb_n(2) * tan(L_b) / (R_E + h_b)]; + +% Obtain coordinate transformation matrix from the new attitude w.r.t. an +% inertial frame to the old using Rodrigues' formula, (5.73) +if mag_alpha>1.E-8 + C_new_old = eye(3) + sin(mag_alpha) / mag_alpha * Alpha_ib_b +... + (1 - cos(mag_alpha)) / mag_alpha^2 * Alpha_ib_b * Alpha_ib_b; +else + C_new_old = eye(3) + Alpha_ib_b; +end %if mag_alpha + +% Update attitude using (5.77) +C_b_n = (eye(3) - Skew_symmetric(omega_ie_n + 0.5 * omega_en_n + 0.5 *... + old_omega_en_n) * tor_i) * old_C_b_n * C_new_old; + +% Ends \ No newline at end of file diff --git a/Plot_errors.m b/Plot_errors.m new file mode 100644 index 0000000..783187c --- /dev/null +++ b/Plot_errors.m @@ -0,0 +1,91 @@ +function Plot_errors(errors) +%Plots navigation solution errors +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 3/4/2012 by Paul Groves +% +% Input: +% errors Array of error data to plot +% Format is +% Column 1: time (sec) +% Column 2: north position error (m) +% Column 3: east position error (m) +% Column 4: down position error (m) +% Column 5: north velocity (m/s) +% Column 6: east velocity (m/s) +% Column 7: down velocity (m/s) +% Column 8: roll component of NED attitude error (deg) +% Column 9: pitch component of NED attitude error (deg) +% Column 10: yaw component of NED attitude error (deg) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins +fig = figure; +set(fig,'units','normalized'); +set(fig,'OuterPosition',[0.5,0.4,0.45,0.6]); + +subplot(3,3,1); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0.9,0.45,0]); +plot(errors(:,1),errors(:,2),'LineWidth',1.5); +title('North position error, m'); +set(gca,'OuterPosition',[0.01,0.68,0.32,0.31]); +subplot(3,3,2); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0,0.9,0.45]); +plot(errors(:,1),errors(:,3),'LineWidth',1.5); +title('East position error, m'); +set(gca,'OuterPosition',[0.34,0.68,0.32,0.31]); +subplot(3,3,3); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0.45,0,0.9]); +plot(errors(:,1),errors(:,4),'LineWidth',1.5); +title('Down position error, m'); +set(gca,'OuterPosition',[0.67,0.68,0.32,0.31]); + +subplot(3,3,4); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0.9,0,0.45]); +plot(errors(:,1),errors(:,5),'LineWidth',1.5); +title('North velocity error, m/s'); +set(gca,'OuterPosition',[0.01,0.36,0.32,0.31]); +subplot(3,3,5); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0.45,0.9,0]); +plot(errors(:,1),errors(:,6),'LineWidth',1.5); +title('East velocity error, m/s'); +set(gca,'OuterPosition',[0.34,0.36,0.32,0.31]); +subplot(3,3,6); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0,0.45,0.9]); +plot(errors(:,1),errors(:,7),'LineWidth',1.5); +title('Down velocity error, m/s'); +set(gca,'OuterPosition',[0.67,0.36,0.32,0.31]); + +subplot(3,3,7); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0,0.7,0.7]); +plot(errors(:,1),radtodeg(errors(:,8)),'LineWidth',1.5); +xlabel('Time, s'); +title('Attitude error about North, deg'); +set(gca,'OuterPosition',[0.01,0,0.32,0.35]); +subplot(3,3,8); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0.7,0,0.7]); +plot(errors(:,1),radtodeg(errors(:,9)),'LineWidth',1.5); +xlabel('Time, s'); +title('Attitude error about East, deg'); +set(gca,'OuterPosition',[0.34,0,0.32,0.35]); +subplot(3,3,9); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0.7,0.7,0]); +plot(errors(:,1),radtodeg(errors(:,10)),'LineWidth',1.5); +xlabel('Time, s'); +title('Heading error, deg'); +set(gca,'OuterPosition',[0.67,0,0.32,0.35]); + +% Ends \ No newline at end of file diff --git a/Plot_profile.m b/Plot_profile.m new file mode 100644 index 0000000..e6ced96 --- /dev/null +++ b/Plot_profile.m @@ -0,0 +1,94 @@ +function Plot_profile(profile) +%Plots a motion profile +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 3/4/2012 by Paul Groves +% +% Input: +% profile Array of motion profile data to plot +% Format is +% Column 1: time (sec) +% Column 2: latitude (deg) +% Column 3: longitude (deg) +% Column 4: height (m) +% Column 5: north velocity (m/s) +% Column 6: east velocity (m/s) +% Column 7: down velocity (m/s) +% Column 8: roll angle of body w.r.t NED (deg) +% Column 9: pitch angle of body w.r.t NED (deg) +% Column 10: yaw angle of body w.r.t NED (deg) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins +fig = figure; +set(fig,'units','normalized'); +set(fig,'OuterPosition',[0.05,0.4,0.45,0.6]); + +[R_N,R_E] = Radii_of_curvature(profile(1,2)); +subplot(3,3,1); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0.9,0.45,0]); +plot(profile(:,1),((profile(:,2) - profile(1,2)) * (R_N + profile(1,4))),... + 'LineWidth',1.5); +title('North displacement, m'); +set(gca,'OuterPosition',[0.01,0.68,0.32,0.31]); +subplot(3,3,2); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0,0.9,0.45]); +plot(profile(:,1),((profile(:,3) - profile(1,3)) * (R_N + profile(1,4)) *... + cos(profile(1,2))),'LineWidth',1.5); +title('East displacement, m'); +set(gca,'OuterPosition',[0.34,0.68,0.32,0.31]); +subplot(3,3,3); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0.45,0,0.9]); +plot(profile(:,1),(profile(1,4) - profile(:,4)),'LineWidth',1.5); +title('Down displacement, m'); +set(gca,'OuterPosition',[0.67,0.68,0.32,0.31]); + +subplot(3,3,4); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0.9,0,0.45]); +plot(profile(:,1),profile(:,5),'LineWidth',1.5); +title('North velocity, m/s'); +set(gca,'OuterPosition',[0.01,0.36,0.32,0.31]); +subplot(3,3,5); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0.45,0.9,0]); +plot(profile(:,1),profile(:,6),'LineWidth',1.5); +title('East velocity, m/s'); +set(gca,'OuterPosition',[0.34,0.36,0.32,0.31]); +subplot(3,3,6); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0,0.45,0.9]); +plot(profile(:,1),profile(:,7),'LineWidth',1.5); +title('Down velocity, m/s'); +set(gca,'OuterPosition',[0.67,0.36,0.32,0.31]); + +subplot(3,3,7); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0,0.7,0.7]); +plot(profile(:,1),radtodeg(profile(:,8)),'LineWidth',1.5); +xlabel('Time, s'); +title('Bank, deg'); +set(gca,'OuterPosition',[0.01,0,0.32,0.35]); +subplot(3,3,8); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0.7,0,0.7]); +plot(profile(:,1),radtodeg(profile(:,9)),'LineWidth',1.5); +xlabel('Time, s'); +title('Elevation, deg'); +set(gca,'OuterPosition',[0.34,0,0.32,0.35]); +subplot(3,3,9); +set(gca,'NextPlot','replacechildren'); +set(gca,'ColorOrder',[0.7,0.7,0]); +plot(profile(:,1),radtodeg(profile(:,10)),'LineWidth',1.5); +xlabel('Time, s'); +title('Heading, deg'); +set(gca,'OuterPosition',[0.67,0,0.32,0.35]); + +% Ends \ No newline at end of file diff --git a/Profile_0.csv b/Profile_0.csv new file mode 100644 index 0000000..5aad976 --- /dev/null +++ b/Profile_0.csv @@ -0,0 +1,6001 @@ +0,51,0,10,0,0,0,0,0,0 +0.01,51,0,10,0,0,0,0,0,0 +0.02,51,0,10,0,0,0,0,0,0 +0.03,51,0,10,0,0,0,0,0,0 +0.04,51,0,10,0,0,0,0,0,0 +0.05,51,0,10,0,0,0,0,0,0 +0.06,51,0,10,0,0,0,0,0,0 +0.07,51,0,10,0,0,0,0,0,0 +0.08,51,0,10,0,0,0,0,0,0 +0.09,51,0,10,0,0,0,0,0,0 +0.1,51,0,10,0,0,0,0,0,0 +0.11,51,0,10,0,0,0,0,0,0 +0.12,51,0,10,0,0,0,0,0,0 +0.13,51,0,10,0,0,0,0,0,0 +0.14,51,0,10,0,0,0,0,0,0 +0.15,51,0,10,0,0,0,0,0,0 +0.16,51,0,10,0,0,0,0,0,0 +0.17,51,0,10,0,0,0,0,0,0 +0.18,51,0,10,0,0,0,0,0,0 +0.19,51,0,10,0,0,0,0,0,0 +0.2,51,0,10,0,0,0,0,0,0 +0.21,51,0,10,0,0,0,0,0,0 +0.22,51,0,10,0,0,0,0,0,0 +0.23,51,0,10,0,0,0,0,0,0 +0.24,51,0,10,0,0,0,0,0,0 +0.25,51,0,10,0,0,0,0,0,0 +0.26,51,0,10,0,0,0,0,0,0 +0.27,51,0,10,0,0,0,0,0,0 +0.28,51,0,10,0,0,0,0,0,0 +0.29,51,0,10,0,0,0,0,0,0 +0.3,51,0,10,0,0,0,0,0,0 +0.31,51,0,10,0,0,0,0,0,0 +0.32,51,0,10,0,0,0,0,0,0 +0.33,51,0,10,0,0,0,0,0,0 +0.34,51,0,10,0,0,0,0,0,0 +0.35,51,0,10,0,0,0,0,0,0 +0.36,51,0,10,0,0,0,0,0,0 +0.37,51,0,10,0,0,0,0,0,0 +0.38,51,0,10,0,0,0,0,0,0 +0.39,51,0,10,0,0,0,0,0,0 +0.4,51,0,10,0,0,0,0,0,0 +0.41,51,0,10,0,0,0,0,0,0 +0.42,51,0,10,0,0,0,0,0,0 +0.43,51,0,10,0,0,0,0,0,0 +0.44,51,0,10,0,0,0,0,0,0 +0.45,51,0,10,0,0,0,0,0,0 +0.46,51,0,10,0,0,0,0,0,0 +0.47,51,0,10,0,0,0,0,0,0 +0.48,51,0,10,0,0,0,0,0,0 +0.49,51,0,10,0,0,0,0,0,0 +0.5,51,0,10,0,0,0,0,0,0 +0.51,51,0,10,0,0,0,0,0,0 +0.52,51,0,10,0,0,0,0,0,0 +0.53,51,0,10,0,0,0,0,0,0 +0.54,51,0,10,0,0,0,0,0,0 +0.55,51,0,10,0,0,0,0,0,0 +0.56,51,0,10,0,0,0,0,0,0 +0.57,51,0,10,0,0,0,0,0,0 +0.58,51,0,10,0,0,0,0,0,0 +0.59,51,0,10,0,0,0,0,0,0 +0.6,51,0,10,0,0,0,0,0,0 +0.61,51,0,10,0,0,0,0,0,0 +0.62,51,0,10,0,0,0,0,0,0 +0.63,51,0,10,0,0,0,0,0,0 +0.64,51,0,10,0,0,0,0,0,0 +0.65,51,0,10,0,0,0,0,0,0 +0.66,51,0,10,0,0,0,0,0,0 +0.67,51,0,10,0,0,0,0,0,0 +0.68,51,0,10,0,0,0,0,0,0 +0.69,51,0,10,0,0,0,0,0,0 +0.7,51,0,10,0,0,0,0,0,0 +0.71,51,0,10,0,0,0,0,0,0 +0.72,51,0,10,0,0,0,0,0,0 +0.73,51,0,10,0,0,0,0,0,0 +0.74,51,0,10,0,0,0,0,0,0 +0.75,51,0,10,0,0,0,0,0,0 +0.76,51,0,10,0,0,0,0,0,0 +0.77,51,0,10,0,0,0,0,0,0 +0.78,51,0,10,0,0,0,0,0,0 +0.79,51,0,10,0,0,0,0,0,0 +0.8,51,0,10,0,0,0,0,0,0 +0.81,51,0,10,0,0,0,0,0,0 +0.82,51,0,10,0,0,0,0,0,0 +0.83,51,0,10,0,0,0,0,0,0 +0.84,51,0,10,0,0,0,0,0,0 +0.85,51,0,10,0,0,0,0,0,0 +0.86,51,0,10,0,0,0,0,0,0 +0.87,51,0,10,0,0,0,0,0,0 +0.88,51,0,10,0,0,0,0,0,0 +0.89,51,0,10,0,0,0,0,0,0 +0.9,51,0,10,0,0,0,0,0,0 +0.91,51,0,10,0,0,0,0,0,0 +0.92,51,0,10,0,0,0,0,0,0 +0.93,51,0,10,0,0,0,0,0,0 +0.94,51,0,10,0,0,0,0,0,0 +0.95,51,0,10,0,0,0,0,0,0 +0.96,51,0,10,0,0,0,0,0,0 +0.97,51,0,10,0,0,0,0,0,0 +0.98,51,0,10,0,0,0,0,0,0 +0.99,51,0,10,0,0,0,0,0,0 +1,51,0,10,0,0,0,0,0,0 +1.01,51,0,10,0,0,0,0,0,0 +1.02,51,0,10,0,0,0,0,0,0 +1.03,51,0,10,0,0,0,0,0,0 +1.04,51,0,10,0,0,0,0,0,0 +1.05,51,0,10,0,0,0,0,0,0 +1.06,51,0,10,0,0,0,0,0,0 +1.07,51,0,10,0,0,0,0,0,0 +1.08,51,0,10,0,0,0,0,0,0 +1.09,51,0,10,0,0,0,0,0,0 +1.1,51,0,10,0,0,0,0,0,0 +1.11,51,0,10,0,0,0,0,0,0 +1.12,51,0,10,0,0,0,0,0,0 +1.13,51,0,10,0,0,0,0,0,0 +1.14,51,0,10,0,0,0,0,0,0 +1.15,51,0,10,0,0,0,0,0,0 +1.16,51,0,10,0,0,0,0,0,0 +1.17,51,0,10,0,0,0,0,0,0 +1.18,51,0,10,0,0,0,0,0,0 +1.19,51,0,10,0,0,0,0,0,0 +1.2,51,0,10,0,0,0,0,0,0 +1.21,51,0,10,0,0,0,0,0,0 +1.22,51,0,10,0,0,0,0,0,0 +1.23,51,0,10,0,0,0,0,0,0 +1.24,51,0,10,0,0,0,0,0,0 +1.25,51,0,10,0,0,0,0,0,0 +1.26,51,0,10,0,0,0,0,0,0 +1.27,51,0,10,0,0,0,0,0,0 +1.28,51,0,10,0,0,0,0,0,0 +1.29,51,0,10,0,0,0,0,0,0 +1.3,51,0,10,0,0,0,0,0,0 +1.31,51,0,10,0,0,0,0,0,0 +1.32,51,0,10,0,0,0,0,0,0 +1.33,51,0,10,0,0,0,0,0,0 +1.34,51,0,10,0,0,0,0,0,0 +1.35,51,0,10,0,0,0,0,0,0 +1.36,51,0,10,0,0,0,0,0,0 +1.37,51,0,10,0,0,0,0,0,0 +1.38,51,0,10,0,0,0,0,0,0 +1.39,51,0,10,0,0,0,0,0,0 +1.4,51,0,10,0,0,0,0,0,0 +1.41,51,0,10,0,0,0,0,0,0 +1.42,51,0,10,0,0,0,0,0,0 +1.43,51,0,10,0,0,0,0,0,0 +1.44,51,0,10,0,0,0,0,0,0 +1.45,51,0,10,0,0,0,0,0,0 +1.46,51,0,10,0,0,0,0,0,0 +1.47,51,0,10,0,0,0,0,0,0 +1.48,51,0,10,0,0,0,0,0,0 +1.49,51,0,10,0,0,0,0,0,0 +1.5,51,0,10,0,0,0,0,0,0 +1.51,51,0,10,0,0,0,0,0,0 +1.52,51,0,10,0,0,0,0,0,0 +1.53,51,0,10,0,0,0,0,0,0 +1.54,51,0,10,0,0,0,0,0,0 +1.55,51,0,10,0,0,0,0,0,0 +1.56,51,0,10,0,0,0,0,0,0 +1.57,51,0,10,0,0,0,0,0,0 +1.58,51,0,10,0,0,0,0,0,0 +1.59,51,0,10,0,0,0,0,0,0 +1.6,51,0,10,0,0,0,0,0,0 +1.61,51,0,10,0,0,0,0,0,0 +1.62,51,0,10,0,0,0,0,0,0 +1.63,51,0,10,0,0,0,0,0,0 +1.64,51,0,10,0,0,0,0,0,0 +1.65,51,0,10,0,0,0,0,0,0 +1.66,51,0,10,0,0,0,0,0,0 +1.67,51,0,10,0,0,0,0,0,0 +1.68,51,0,10,0,0,0,0,0,0 +1.69,51,0,10,0,0,0,0,0,0 +1.7,51,0,10,0,0,0,0,0,0 +1.71,51,0,10,0,0,0,0,0,0 +1.72,51,0,10,0,0,0,0,0,0 +1.73,51,0,10,0,0,0,0,0,0 +1.74,51,0,10,0,0,0,0,0,0 +1.75,51,0,10,0,0,0,0,0,0 +1.76,51,0,10,0,0,0,0,0,0 +1.77,51,0,10,0,0,0,0,0,0 +1.78,51,0,10,0,0,0,0,0,0 +1.79,51,0,10,0,0,0,0,0,0 +1.8,51,0,10,0,0,0,0,0,0 +1.81,51,0,10,0,0,0,0,0,0 +1.82,51,0,10,0,0,0,0,0,0 +1.83,51,0,10,0,0,0,0,0,0 +1.84,51,0,10,0,0,0,0,0,0 +1.85,51,0,10,0,0,0,0,0,0 +1.86,51,0,10,0,0,0,0,0,0 +1.87,51,0,10,0,0,0,0,0,0 +1.88,51,0,10,0,0,0,0,0,0 +1.89,51,0,10,0,0,0,0,0,0 +1.9,51,0,10,0,0,0,0,0,0 +1.91,51,0,10,0,0,0,0,0,0 +1.92,51,0,10,0,0,0,0,0,0 +1.93,51,0,10,0,0,0,0,0,0 +1.94,51,0,10,0,0,0,0,0,0 +1.95,51,0,10,0,0,0,0,0,0 +1.96,51,0,10,0,0,0,0,0,0 +1.97,51,0,10,0,0,0,0,0,0 +1.98,51,0,10,0,0,0,0,0,0 +1.99,51,0,10,0,0,0,0,0,0 +2,51,0,10,0,0,0,0,0,0 +2.01,51,0,10,0,0,0,0,0,0 +2.02,51,0,10,0,0,0,0,0,0 +2.03,51,0,10,0,0,0,0,0,0 +2.04,51,0,10,0,0,0,0,0,0 +2.05,51,0,10,0,0,0,0,0,0 +2.06,51,0,10,0,0,0,0,0,0 +2.07,51,0,10,0,0,0,0,0,0 +2.08,51,0,10,0,0,0,0,0,0 +2.09,51,0,10,0,0,0,0,0,0 +2.1,51,0,10,0,0,0,0,0,0 +2.11,51,0,10,0,0,0,0,0,0 +2.12,51,0,10,0,0,0,0,0,0 +2.13,51,0,10,0,0,0,0,0,0 +2.14,51,0,10,0,0,0,0,0,0 +2.15,51,0,10,0,0,0,0,0,0 +2.16,51,0,10,0,0,0,0,0,0 +2.17,51,0,10,0,0,0,0,0,0 +2.18,51,0,10,0,0,0,0,0,0 +2.19,51,0,10,0,0,0,0,0,0 +2.2,51,0,10,0,0,0,0,0,0 +2.21,51,0,10,0,0,0,0,0,0 +2.22,51,0,10,0,0,0,0,0,0 +2.23,51,0,10,0,0,0,0,0,0 +2.24,51,0,10,0,0,0,0,0,0 +2.25,51,0,10,0,0,0,0,0,0 +2.26,51,0,10,0,0,0,0,0,0 +2.27,51,0,10,0,0,0,0,0,0 +2.28,51,0,10,0,0,0,0,0,0 +2.29,51,0,10,0,0,0,0,0,0 +2.3,51,0,10,0,0,0,0,0,0 +2.31,51,0,10,0,0,0,0,0,0 +2.32,51,0,10,0,0,0,0,0,0 +2.33,51,0,10,0,0,0,0,0,0 +2.34,51,0,10,0,0,0,0,0,0 +2.35,51,0,10,0,0,0,0,0,0 +2.36,51,0,10,0,0,0,0,0,0 +2.37,51,0,10,0,0,0,0,0,0 +2.38,51,0,10,0,0,0,0,0,0 +2.39,51,0,10,0,0,0,0,0,0 +2.4,51,0,10,0,0,0,0,0,0 +2.41,51,0,10,0,0,0,0,0,0 +2.42,51,0,10,0,0,0,0,0,0 +2.43,51,0,10,0,0,0,0,0,0 +2.44,51,0,10,0,0,0,0,0,0 +2.45,51,0,10,0,0,0,0,0,0 +2.46,51,0,10,0,0,0,0,0,0 +2.47,51,0,10,0,0,0,0,0,0 +2.48,51,0,10,0,0,0,0,0,0 +2.49,51,0,10,0,0,0,0,0,0 +2.5,51,0,10,0,0,0,0,0,0 +2.51,51,0,10,0,0,0,0,0,0 +2.52,51,0,10,0,0,0,0,0,0 +2.53,51,0,10,0,0,0,0,0,0 +2.54,51,0,10,0,0,0,0,0,0 +2.55,51,0,10,0,0,0,0,0,0 +2.56,51,0,10,0,0,0,0,0,0 +2.57,51,0,10,0,0,0,0,0,0 +2.58,51,0,10,0,0,0,0,0,0 +2.59,51,0,10,0,0,0,0,0,0 +2.6,51,0,10,0,0,0,0,0,0 +2.61,51,0,10,0,0,0,0,0,0 +2.62,51,0,10,0,0,0,0,0,0 +2.63,51,0,10,0,0,0,0,0,0 +2.64,51,0,10,0,0,0,0,0,0 +2.65,51,0,10,0,0,0,0,0,0 +2.66,51,0,10,0,0,0,0,0,0 +2.67,51,0,10,0,0,0,0,0,0 +2.68,51,0,10,0,0,0,0,0,0 +2.69,51,0,10,0,0,0,0,0,0 +2.7,51,0,10,0,0,0,0,0,0 +2.71,51,0,10,0,0,0,0,0,0 +2.72,51,0,10,0,0,0,0,0,0 +2.73,51,0,10,0,0,0,0,0,0 +2.74,51,0,10,0,0,0,0,0,0 +2.75,51,0,10,0,0,0,0,0,0 +2.76,51,0,10,0,0,0,0,0,0 +2.77,51,0,10,0,0,0,0,0,0 +2.78,51,0,10,0,0,0,0,0,0 +2.79,51,0,10,0,0,0,0,0,0 +2.8,51,0,10,0,0,0,0,0,0 +2.81,51,0,10,0,0,0,0,0,0 +2.82,51,0,10,0,0,0,0,0,0 +2.83,51,0,10,0,0,0,0,0,0 +2.84,51,0,10,0,0,0,0,0,0 +2.85,51,0,10,0,0,0,0,0,0 +2.86,51,0,10,0,0,0,0,0,0 +2.87,51,0,10,0,0,0,0,0,0 +2.88,51,0,10,0,0,0,0,0,0 +2.89,51,0,10,0,0,0,0,0,0 +2.9,51,0,10,0,0,0,0,0,0 +2.91,51,0,10,0,0,0,0,0,0 +2.92,51,0,10,0,0,0,0,0,0 +2.93,51,0,10,0,0,0,0,0,0 +2.94,51,0,10,0,0,0,0,0,0 +2.95,51,0,10,0,0,0,0,0,0 +2.96,51,0,10,0,0,0,0,0,0 +2.97,51,0,10,0,0,0,0,0,0 +2.98,51,0,10,0,0,0,0,0,0 +2.99,51,0,10,0,0,0,0,0,0 +3,51,0,10,0,0,0,0,0,0 +3.01,51,0,10,0,0,0,0,0,0 +3.02,51,0,10,0,0,0,0,0,0 +3.03,51,0,10,0,0,0,0,0,0 +3.04,51,0,10,0,0,0,0,0,0 +3.05,51,0,10,0,0,0,0,0,0 +3.06,51,0,10,0,0,0,0,0,0 +3.07,51,0,10,0,0,0,0,0,0 +3.08,51,0,10,0,0,0,0,0,0 +3.09,51,0,10,0,0,0,0,0,0 +3.1,51,0,10,0,0,0,0,0,0 +3.11,51,0,10,0,0,0,0,0,0 +3.12,51,0,10,0,0,0,0,0,0 +3.13,51,0,10,0,0,0,0,0,0 +3.14,51,0,10,0,0,0,0,0,0 +3.15,51,0,10,0,0,0,0,0,0 +3.16,51,0,10,0,0,0,0,0,0 +3.17,51,0,10,0,0,0,0,0,0 +3.18,51,0,10,0,0,0,0,0,0 +3.19,51,0,10,0,0,0,0,0,0 +3.2,51,0,10,0,0,0,0,0,0 +3.21,51,0,10,0,0,0,0,0,0 +3.22,51,0,10,0,0,0,0,0,0 +3.23,51,0,10,0,0,0,0,0,0 +3.24,51,0,10,0,0,0,0,0,0 +3.25,51,0,10,0,0,0,0,0,0 +3.26,51,0,10,0,0,0,0,0,0 +3.27,51,0,10,0,0,0,0,0,0 +3.28,51,0,10,0,0,0,0,0,0 +3.29,51,0,10,0,0,0,0,0,0 +3.3,51,0,10,0,0,0,0,0,0 +3.31,51,0,10,0,0,0,0,0,0 +3.32,51,0,10,0,0,0,0,0,0 +3.33,51,0,10,0,0,0,0,0,0 +3.34,51,0,10,0,0,0,0,0,0 +3.35,51,0,10,0,0,0,0,0,0 +3.36,51,0,10,0,0,0,0,0,0 +3.37,51,0,10,0,0,0,0,0,0 +3.38,51,0,10,0,0,0,0,0,0 +3.39,51,0,10,0,0,0,0,0,0 +3.4,51,0,10,0,0,0,0,0,0 +3.41,51,0,10,0,0,0,0,0,0 +3.42,51,0,10,0,0,0,0,0,0 +3.43,51,0,10,0,0,0,0,0,0 +3.44,51,0,10,0,0,0,0,0,0 +3.45,51,0,10,0,0,0,0,0,0 +3.46,51,0,10,0,0,0,0,0,0 +3.47,51,0,10,0,0,0,0,0,0 +3.48,51,0,10,0,0,0,0,0,0 +3.49,51,0,10,0,0,0,0,0,0 +3.5,51,0,10,0,0,0,0,0,0 +3.51,51,0,10,0,0,0,0,0,0 +3.52,51,0,10,0,0,0,0,0,0 +3.53,51,0,10,0,0,0,0,0,0 +3.54,51,0,10,0,0,0,0,0,0 +3.55,51,0,10,0,0,0,0,0,0 +3.56,51,0,10,0,0,0,0,0,0 +3.57,51,0,10,0,0,0,0,0,0 +3.58,51,0,10,0,0,0,0,0,0 +3.59,51,0,10,0,0,0,0,0,0 +3.6,51,0,10,0,0,0,0,0,0 +3.61,51,0,10,0,0,0,0,0,0 +3.62,51,0,10,0,0,0,0,0,0 +3.63,51,0,10,0,0,0,0,0,0 +3.64,51,0,10,0,0,0,0,0,0 +3.65,51,0,10,0,0,0,0,0,0 +3.66,51,0,10,0,0,0,0,0,0 +3.67,51,0,10,0,0,0,0,0,0 +3.68,51,0,10,0,0,0,0,0,0 +3.69,51,0,10,0,0,0,0,0,0 +3.7,51,0,10,0,0,0,0,0,0 +3.71,51,0,10,0,0,0,0,0,0 +3.72,51,0,10,0,0,0,0,0,0 +3.73,51,0,10,0,0,0,0,0,0 +3.74,51,0,10,0,0,0,0,0,0 +3.75,51,0,10,0,0,0,0,0,0 +3.76,51,0,10,0,0,0,0,0,0 +3.77,51,0,10,0,0,0,0,0,0 +3.78,51,0,10,0,0,0,0,0,0 +3.79,51,0,10,0,0,0,0,0,0 +3.8,51,0,10,0,0,0,0,0,0 +3.81,51,0,10,0,0,0,0,0,0 +3.82,51,0,10,0,0,0,0,0,0 +3.83,51,0,10,0,0,0,0,0,0 +3.84,51,0,10,0,0,0,0,0,0 +3.85,51,0,10,0,0,0,0,0,0 +3.86,51,0,10,0,0,0,0,0,0 +3.87,51,0,10,0,0,0,0,0,0 +3.88,51,0,10,0,0,0,0,0,0 +3.89,51,0,10,0,0,0,0,0,0 +3.9,51,0,10,0,0,0,0,0,0 +3.91,51,0,10,0,0,0,0,0,0 +3.92,51,0,10,0,0,0,0,0,0 +3.93,51,0,10,0,0,0,0,0,0 +3.94,51,0,10,0,0,0,0,0,0 +3.95,51,0,10,0,0,0,0,0,0 +3.96,51,0,10,0,0,0,0,0,0 +3.97,51,0,10,0,0,0,0,0,0 +3.98,51,0,10,0,0,0,0,0,0 +3.99,51,0,10,0,0,0,0,0,0 +4,51,0,10,0,0,0,0,0,0 +4.01,51,0,10,0,0,0,0,0,0 +4.02,51,0,10,0,0,0,0,0,0 +4.03,51,0,10,0,0,0,0,0,0 +4.04,51,0,10,0,0,0,0,0,0 +4.05,51,0,10,0,0,0,0,0,0 +4.06,51,0,10,0,0,0,0,0,0 +4.07,51,0,10,0,0,0,0,0,0 +4.08,51,0,10,0,0,0,0,0,0 +4.09,51,0,10,0,0,0,0,0,0 +4.1,51,0,10,0,0,0,0,0,0 +4.11,51,0,10,0,0,0,0,0,0 +4.12,51,0,10,0,0,0,0,0,0 +4.13,51,0,10,0,0,0,0,0,0 +4.14,51,0,10,0,0,0,0,0,0 +4.15,51,0,10,0,0,0,0,0,0 +4.16,51,0,10,0,0,0,0,0,0 +4.17,51,0,10,0,0,0,0,0,0 +4.18,51,0,10,0,0,0,0,0,0 +4.19,51,0,10,0,0,0,0,0,0 +4.2,51,0,10,0,0,0,0,0,0 +4.21,51,0,10,0,0,0,0,0,0 +4.22,51,0,10,0,0,0,0,0,0 +4.23,51,0,10,0,0,0,0,0,0 +4.24,51,0,10,0,0,0,0,0,0 +4.25,51,0,10,0,0,0,0,0,0 +4.26,51,0,10,0,0,0,0,0,0 +4.27,51,0,10,0,0,0,0,0,0 +4.28,51,0,10,0,0,0,0,0,0 +4.29,51,0,10,0,0,0,0,0,0 +4.3,51,0,10,0,0,0,0,0,0 +4.31,51,0,10,0,0,0,0,0,0 +4.32,51,0,10,0,0,0,0,0,0 +4.33,51,0,10,0,0,0,0,0,0 +4.34,51,0,10,0,0,0,0,0,0 +4.35,51,0,10,0,0,0,0,0,0 +4.36,51,0,10,0,0,0,0,0,0 +4.37,51,0,10,0,0,0,0,0,0 +4.38,51,0,10,0,0,0,0,0,0 +4.39,51,0,10,0,0,0,0,0,0 +4.4,51,0,10,0,0,0,0,0,0 +4.41,51,0,10,0,0,0,0,0,0 +4.42,51,0,10,0,0,0,0,0,0 +4.43,51,0,10,0,0,0,0,0,0 +4.44,51,0,10,0,0,0,0,0,0 +4.45,51,0,10,0,0,0,0,0,0 +4.46,51,0,10,0,0,0,0,0,0 +4.47,51,0,10,0,0,0,0,0,0 +4.48,51,0,10,0,0,0,0,0,0 +4.49,51,0,10,0,0,0,0,0,0 +4.5,51,0,10,0,0,0,0,0,0 +4.51,51,0,10,0,0,0,0,0,0 +4.52,51,0,10,0,0,0,0,0,0 +4.53,51,0,10,0,0,0,0,0,0 +4.54,51,0,10,0,0,0,0,0,0 +4.55,51,0,10,0,0,0,0,0,0 +4.56,51,0,10,0,0,0,0,0,0 +4.57,51,0,10,0,0,0,0,0,0 +4.58,51,0,10,0,0,0,0,0,0 +4.59,51,0,10,0,0,0,0,0,0 +4.6,51,0,10,0,0,0,0,0,0 +4.61,51,0,10,0,0,0,0,0,0 +4.62,51,0,10,0,0,0,0,0,0 +4.63,51,0,10,0,0,0,0,0,0 +4.64,51,0,10,0,0,0,0,0,0 +4.65,51,0,10,0,0,0,0,0,0 +4.66,51,0,10,0,0,0,0,0,0 +4.67,51,0,10,0,0,0,0,0,0 +4.68,51,0,10,0,0,0,0,0,0 +4.69,51,0,10,0,0,0,0,0,0 +4.7,51,0,10,0,0,0,0,0,0 +4.71,51,0,10,0,0,0,0,0,0 +4.72,51,0,10,0,0,0,0,0,0 +4.73,51,0,10,0,0,0,0,0,0 +4.74,51,0,10,0,0,0,0,0,0 +4.75,51,0,10,0,0,0,0,0,0 +4.76,51,0,10,0,0,0,0,0,0 +4.77,51,0,10,0,0,0,0,0,0 +4.78,51,0,10,0,0,0,0,0,0 +4.79,51,0,10,0,0,0,0,0,0 +4.8,51,0,10,0,0,0,0,0,0 +4.81,51,0,10,0,0,0,0,0,0 +4.82,51,0,10,0,0,0,0,0,0 +4.83,51,0,10,0,0,0,0,0,0 +4.84,51,0,10,0,0,0,0,0,0 +4.85,51,0,10,0,0,0,0,0,0 +4.86,51,0,10,0,0,0,0,0,0 +4.87,51,0,10,0,0,0,0,0,0 +4.88,51,0,10,0,0,0,0,0,0 +4.89,51,0,10,0,0,0,0,0,0 +4.9,51,0,10,0,0,0,0,0,0 +4.91,51,0,10,0,0,0,0,0,0 +4.92,51,0,10,0,0,0,0,0,0 +4.93,51,0,10,0,0,0,0,0,0 +4.94,51,0,10,0,0,0,0,0,0 +4.95,51,0,10,0,0,0,0,0,0 +4.96,51,0,10,0,0,0,0,0,0 +4.97,51,0,10,0,0,0,0,0,0 +4.98,51,0,10,0,0,0,0,0,0 +4.99,51,0,10,0,0,0,0,0,0 +5,51,0,10,0,0,0,0,0,0 +5.01,51,0,10,0,0,0,0,0,0 +5.02,51,0,10,0,0,0,0,0,0 +5.03,51,0,10,0,0,0,0,0,0 +5.04,51,0,10,0,0,0,0,0,0 +5.05,51,0,10,0,0,0,0,0,0 +5.06,51,0,10,0,0,0,0,0,0 +5.07,51,0,10,0,0,0,0,0,0 +5.08,51,0,10,0,0,0,0,0,0 +5.09,51,0,10,0,0,0,0,0,0 +5.1,51,0,10,0,0,0,0,0,0 +5.11,51,0,10,0,0,0,0,0,0 +5.12,51,0,10,0,0,0,0,0,0 +5.13,51,0,10,0,0,0,0,0,0 +5.14,51,0,10,0,0,0,0,0,0 +5.15,51,0,10,0,0,0,0,0,0 +5.16,51,0,10,0,0,0,0,0,0 +5.17,51,0,10,0,0,0,0,0,0 +5.18,51,0,10,0,0,0,0,0,0 +5.19,51,0,10,0,0,0,0,0,0 +5.2,51,0,10,0,0,0,0,0,0 +5.21,51,0,10,0,0,0,0,0,0 +5.22,51,0,10,0,0,0,0,0,0 +5.23,51,0,10,0,0,0,0,0,0 +5.24,51,0,10,0,0,0,0,0,0 +5.25,51,0,10,0,0,0,0,0,0 +5.26,51,0,10,0,0,0,0,0,0 +5.27,51,0,10,0,0,0,0,0,0 +5.28,51,0,10,0,0,0,0,0,0 +5.29,51,0,10,0,0,0,0,0,0 +5.3,51,0,10,0,0,0,0,0,0 +5.31,51,0,10,0,0,0,0,0,0 +5.32,51,0,10,0,0,0,0,0,0 +5.33,51,0,10,0,0,0,0,0,0 +5.34,51,0,10,0,0,0,0,0,0 +5.35,51,0,10,0,0,0,0,0,0 +5.36,51,0,10,0,0,0,0,0,0 +5.37,51,0,10,0,0,0,0,0,0 +5.38,51,0,10,0,0,0,0,0,0 +5.39,51,0,10,0,0,0,0,0,0 +5.4,51,0,10,0,0,0,0,0,0 +5.41,51,0,10,0,0,0,0,0,0 +5.42,51,0,10,0,0,0,0,0,0 +5.43,51,0,10,0,0,0,0,0,0 +5.44,51,0,10,0,0,0,0,0,0 +5.45,51,0,10,0,0,0,0,0,0 +5.46,51,0,10,0,0,0,0,0,0 +5.47,51,0,10,0,0,0,0,0,0 +5.48,51,0,10,0,0,0,0,0,0 +5.49,51,0,10,0,0,0,0,0,0 +5.5,51,0,10,0,0,0,0,0,0 +5.51,51,0,10,0,0,0,0,0,0 +5.52,51,0,10,0,0,0,0,0,0 +5.53,51,0,10,0,0,0,0,0,0 +5.54,51,0,10,0,0,0,0,0,0 +5.55,51,0,10,0,0,0,0,0,0 +5.56,51,0,10,0,0,0,0,0,0 +5.57,51,0,10,0,0,0,0,0,0 +5.58,51,0,10,0,0,0,0,0,0 +5.59,51,0,10,0,0,0,0,0,0 +5.6,51,0,10,0,0,0,0,0,0 +5.61,51,0,10,0,0,0,0,0,0 +5.62,51,0,10,0,0,0,0,0,0 +5.63,51,0,10,0,0,0,0,0,0 +5.64,51,0,10,0,0,0,0,0,0 +5.65,51,0,10,0,0,0,0,0,0 +5.66,51,0,10,0,0,0,0,0,0 +5.67,51,0,10,0,0,0,0,0,0 +5.68,51,0,10,0,0,0,0,0,0 +5.69,51,0,10,0,0,0,0,0,0 +5.7,51,0,10,0,0,0,0,0,0 +5.71,51,0,10,0,0,0,0,0,0 +5.72,51,0,10,0,0,0,0,0,0 +5.73,51,0,10,0,0,0,0,0,0 +5.74,51,0,10,0,0,0,0,0,0 +5.75,51,0,10,0,0,0,0,0,0 +5.76,51,0,10,0,0,0,0,0,0 +5.77,51,0,10,0,0,0,0,0,0 +5.78,51,0,10,0,0,0,0,0,0 +5.79,51,0,10,0,0,0,0,0,0 +5.8,51,0,10,0,0,0,0,0,0 +5.81,51,0,10,0,0,0,0,0,0 +5.82,51,0,10,0,0,0,0,0,0 +5.83,51,0,10,0,0,0,0,0,0 +5.84,51,0,10,0,0,0,0,0,0 +5.85,51,0,10,0,0,0,0,0,0 +5.86,51,0,10,0,0,0,0,0,0 +5.87,51,0,10,0,0,0,0,0,0 +5.88,51,0,10,0,0,0,0,0,0 +5.89,51,0,10,0,0,0,0,0,0 +5.9,51,0,10,0,0,0,0,0,0 +5.91,51,0,10,0,0,0,0,0,0 +5.92,51,0,10,0,0,0,0,0,0 +5.93,51,0,10,0,0,0,0,0,0 +5.94,51,0,10,0,0,0,0,0,0 +5.95,51,0,10,0,0,0,0,0,0 +5.96,51,0,10,0,0,0,0,0,0 +5.97,51,0,10,0,0,0,0,0,0 +5.98,51,0,10,0,0,0,0,0,0 +5.99,51,0,10,0,0,0,0,0,0 +6,51,0,10,0,0,0,0,0,0 +6.01,51,0,10,0,0,0,0,0,0 +6.02,51,0,10,0,0,0,0,0,0 +6.03,51,0,10,0,0,0,0,0,0 +6.04,51,0,10,0,0,0,0,0,0 +6.05,51,0,10,0,0,0,0,0,0 +6.06,51,0,10,0,0,0,0,0,0 +6.07,51,0,10,0,0,0,0,0,0 +6.08,51,0,10,0,0,0,0,0,0 +6.09,51,0,10,0,0,0,0,0,0 +6.1,51,0,10,0,0,0,0,0,0 +6.11,51,0,10,0,0,0,0,0,0 +6.12,51,0,10,0,0,0,0,0,0 +6.13,51,0,10,0,0,0,0,0,0 +6.14,51,0,10,0,0,0,0,0,0 +6.15,51,0,10,0,0,0,0,0,0 +6.16,51,0,10,0,0,0,0,0,0 +6.17,51,0,10,0,0,0,0,0,0 +6.18,51,0,10,0,0,0,0,0,0 +6.19,51,0,10,0,0,0,0,0,0 +6.2,51,0,10,0,0,0,0,0,0 +6.21,51,0,10,0,0,0,0,0,0 +6.22,51,0,10,0,0,0,0,0,0 +6.23,51,0,10,0,0,0,0,0,0 +6.24,51,0,10,0,0,0,0,0,0 +6.25,51,0,10,0,0,0,0,0,0 +6.26,51,0,10,0,0,0,0,0,0 +6.27,51,0,10,0,0,0,0,0,0 +6.28,51,0,10,0,0,0,0,0,0 +6.29,51,0,10,0,0,0,0,0,0 +6.3,51,0,10,0,0,0,0,0,0 +6.31,51,0,10,0,0,0,0,0,0 +6.32,51,0,10,0,0,0,0,0,0 +6.33,51,0,10,0,0,0,0,0,0 +6.34,51,0,10,0,0,0,0,0,0 +6.35,51,0,10,0,0,0,0,0,0 +6.36,51,0,10,0,0,0,0,0,0 +6.37,51,0,10,0,0,0,0,0,0 +6.38,51,0,10,0,0,0,0,0,0 +6.39,51,0,10,0,0,0,0,0,0 +6.4,51,0,10,0,0,0,0,0,0 +6.41,51,0,10,0,0,0,0,0,0 +6.42,51,0,10,0,0,0,0,0,0 +6.43,51,0,10,0,0,0,0,0,0 +6.44,51,0,10,0,0,0,0,0,0 +6.45,51,0,10,0,0,0,0,0,0 +6.46,51,0,10,0,0,0,0,0,0 +6.47,51,0,10,0,0,0,0,0,0 +6.48,51,0,10,0,0,0,0,0,0 +6.49,51,0,10,0,0,0,0,0,0 +6.5,51,0,10,0,0,0,0,0,0 +6.51,51,0,10,0,0,0,0,0,0 +6.52,51,0,10,0,0,0,0,0,0 +6.53,51,0,10,0,0,0,0,0,0 +6.54,51,0,10,0,0,0,0,0,0 +6.55,51,0,10,0,0,0,0,0,0 +6.56,51,0,10,0,0,0,0,0,0 +6.57,51,0,10,0,0,0,0,0,0 +6.58,51,0,10,0,0,0,0,0,0 +6.59,51,0,10,0,0,0,0,0,0 +6.6,51,0,10,0,0,0,0,0,0 +6.61,51,0,10,0,0,0,0,0,0 +6.62,51,0,10,0,0,0,0,0,0 +6.63,51,0,10,0,0,0,0,0,0 +6.64,51,0,10,0,0,0,0,0,0 +6.65,51,0,10,0,0,0,0,0,0 +6.66,51,0,10,0,0,0,0,0,0 +6.67,51,0,10,0,0,0,0,0,0 +6.68,51,0,10,0,0,0,0,0,0 +6.69,51,0,10,0,0,0,0,0,0 +6.7,51,0,10,0,0,0,0,0,0 +6.71,51,0,10,0,0,0,0,0,0 +6.72,51,0,10,0,0,0,0,0,0 +6.73,51,0,10,0,0,0,0,0,0 +6.74,51,0,10,0,0,0,0,0,0 +6.75,51,0,10,0,0,0,0,0,0 +6.76,51,0,10,0,0,0,0,0,0 +6.77,51,0,10,0,0,0,0,0,0 +6.78,51,0,10,0,0,0,0,0,0 +6.79,51,0,10,0,0,0,0,0,0 +6.8,51,0,10,0,0,0,0,0,0 +6.81,51,0,10,0,0,0,0,0,0 +6.82,51,0,10,0,0,0,0,0,0 +6.83,51,0,10,0,0,0,0,0,0 +6.84,51,0,10,0,0,0,0,0,0 +6.85,51,0,10,0,0,0,0,0,0 +6.86,51,0,10,0,0,0,0,0,0 +6.87,51,0,10,0,0,0,0,0,0 +6.88,51,0,10,0,0,0,0,0,0 +6.89,51,0,10,0,0,0,0,0,0 +6.9,51,0,10,0,0,0,0,0,0 +6.91,51,0,10,0,0,0,0,0,0 +6.92,51,0,10,0,0,0,0,0,0 +6.93,51,0,10,0,0,0,0,0,0 +6.94,51,0,10,0,0,0,0,0,0 +6.95,51,0,10,0,0,0,0,0,0 +6.96,51,0,10,0,0,0,0,0,0 +6.97,51,0,10,0,0,0,0,0,0 +6.98,51,0,10,0,0,0,0,0,0 +6.99,51,0,10,0,0,0,0,0,0 +7,51,0,10,0,0,0,0,0,0 +7.01,51,0,10,0,0,0,0,0,0 +7.02,51,0,10,0,0,0,0,0,0 +7.03,51,0,10,0,0,0,0,0,0 +7.04,51,0,10,0,0,0,0,0,0 +7.05,51,0,10,0,0,0,0,0,0 +7.06,51,0,10,0,0,0,0,0,0 +7.07,51,0,10,0,0,0,0,0,0 +7.08,51,0,10,0,0,0,0,0,0 +7.09,51,0,10,0,0,0,0,0,0 +7.1,51,0,10,0,0,0,0,0,0 +7.11,51,0,10,0,0,0,0,0,0 +7.12,51,0,10,0,0,0,0,0,0 +7.13,51,0,10,0,0,0,0,0,0 +7.14,51,0,10,0,0,0,0,0,0 +7.15,51,0,10,0,0,0,0,0,0 +7.16,51,0,10,0,0,0,0,0,0 +7.17,51,0,10,0,0,0,0,0,0 +7.18,51,0,10,0,0,0,0,0,0 +7.19,51,0,10,0,0,0,0,0,0 +7.2,51,0,10,0,0,0,0,0,0 +7.21,51,0,10,0,0,0,0,0,0 +7.22,51,0,10,0,0,0,0,0,0 +7.23,51,0,10,0,0,0,0,0,0 +7.24,51,0,10,0,0,0,0,0,0 +7.25,51,0,10,0,0,0,0,0,0 +7.26,51,0,10,0,0,0,0,0,0 +7.27,51,0,10,0,0,0,0,0,0 +7.28,51,0,10,0,0,0,0,0,0 +7.29,51,0,10,0,0,0,0,0,0 +7.3,51,0,10,0,0,0,0,0,0 +7.31,51,0,10,0,0,0,0,0,0 +7.32,51,0,10,0,0,0,0,0,0 +7.33,51,0,10,0,0,0,0,0,0 +7.34,51,0,10,0,0,0,0,0,0 +7.35,51,0,10,0,0,0,0,0,0 +7.36,51,0,10,0,0,0,0,0,0 +7.37,51,0,10,0,0,0,0,0,0 +7.38,51,0,10,0,0,0,0,0,0 +7.39,51,0,10,0,0,0,0,0,0 +7.4,51,0,10,0,0,0,0,0,0 +7.41,51,0,10,0,0,0,0,0,0 +7.42,51,0,10,0,0,0,0,0,0 +7.43,51,0,10,0,0,0,0,0,0 +7.44,51,0,10,0,0,0,0,0,0 +7.45,51,0,10,0,0,0,0,0,0 +7.46,51,0,10,0,0,0,0,0,0 +7.47,51,0,10,0,0,0,0,0,0 +7.48,51,0,10,0,0,0,0,0,0 +7.49,51,0,10,0,0,0,0,0,0 +7.5,51,0,10,0,0,0,0,0,0 +7.51,51,0,10,0,0,0,0,0,0 +7.52,51,0,10,0,0,0,0,0,0 +7.53,51,0,10,0,0,0,0,0,0 +7.54,51,0,10,0,0,0,0,0,0 +7.55,51,0,10,0,0,0,0,0,0 +7.56,51,0,10,0,0,0,0,0,0 +7.57,51,0,10,0,0,0,0,0,0 +7.58,51,0,10,0,0,0,0,0,0 +7.59,51,0,10,0,0,0,0,0,0 +7.6,51,0,10,0,0,0,0,0,0 +7.61,51,0,10,0,0,0,0,0,0 +7.62,51,0,10,0,0,0,0,0,0 +7.63,51,0,10,0,0,0,0,0,0 +7.64,51,0,10,0,0,0,0,0,0 +7.65,51,0,10,0,0,0,0,0,0 +7.66,51,0,10,0,0,0,0,0,0 +7.67,51,0,10,0,0,0,0,0,0 +7.68,51,0,10,0,0,0,0,0,0 +7.69,51,0,10,0,0,0,0,0,0 +7.7,51,0,10,0,0,0,0,0,0 +7.71,51,0,10,0,0,0,0,0,0 +7.72,51,0,10,0,0,0,0,0,0 +7.73,51,0,10,0,0,0,0,0,0 +7.74,51,0,10,0,0,0,0,0,0 +7.75,51,0,10,0,0,0,0,0,0 +7.76,51,0,10,0,0,0,0,0,0 +7.77,51,0,10,0,0,0,0,0,0 +7.78,51,0,10,0,0,0,0,0,0 +7.79,51,0,10,0,0,0,0,0,0 +7.8,51,0,10,0,0,0,0,0,0 +7.81,51,0,10,0,0,0,0,0,0 +7.82,51,0,10,0,0,0,0,0,0 +7.83,51,0,10,0,0,0,0,0,0 +7.84,51,0,10,0,0,0,0,0,0 +7.85,51,0,10,0,0,0,0,0,0 +7.86,51,0,10,0,0,0,0,0,0 +7.87,51,0,10,0,0,0,0,0,0 +7.88,51,0,10,0,0,0,0,0,0 +7.89,51,0,10,0,0,0,0,0,0 +7.9,51,0,10,0,0,0,0,0,0 +7.91,51,0,10,0,0,0,0,0,0 +7.92,51,0,10,0,0,0,0,0,0 +7.93,51,0,10,0,0,0,0,0,0 +7.94,51,0,10,0,0,0,0,0,0 +7.95,51,0,10,0,0,0,0,0,0 +7.96,51,0,10,0,0,0,0,0,0 +7.97,51,0,10,0,0,0,0,0,0 +7.98,51,0,10,0,0,0,0,0,0 +7.99,51,0,10,0,0,0,0,0,0 +8,51,0,10,0,0,0,0,0,0 +8.01,51,0,10,0,0,0,0,0,0 +8.02,51,0,10,0,0,0,0,0,0 +8.03,51,0,10,0,0,0,0,0,0 +8.04,51,0,10,0,0,0,0,0,0 +8.05,51,0,10,0,0,0,0,0,0 +8.06,51,0,10,0,0,0,0,0,0 +8.07,51,0,10,0,0,0,0,0,0 +8.08,51,0,10,0,0,0,0,0,0 +8.09,51,0,10,0,0,0,0,0,0 +8.1,51,0,10,0,0,0,0,0,0 +8.11,51,0,10,0,0,0,0,0,0 +8.12,51,0,10,0,0,0,0,0,0 +8.13,51,0,10,0,0,0,0,0,0 +8.14,51,0,10,0,0,0,0,0,0 +8.15,51,0,10,0,0,0,0,0,0 +8.16,51,0,10,0,0,0,0,0,0 +8.17,51,0,10,0,0,0,0,0,0 +8.18,51,0,10,0,0,0,0,0,0 +8.19,51,0,10,0,0,0,0,0,0 +8.2,51,0,10,0,0,0,0,0,0 +8.21,51,0,10,0,0,0,0,0,0 +8.22,51,0,10,0,0,0,0,0,0 +8.23,51,0,10,0,0,0,0,0,0 +8.24,51,0,10,0,0,0,0,0,0 +8.25,51,0,10,0,0,0,0,0,0 +8.26,51,0,10,0,0,0,0,0,0 +8.27,51,0,10,0,0,0,0,0,0 +8.28,51,0,10,0,0,0,0,0,0 +8.29,51,0,10,0,0,0,0,0,0 +8.3,51,0,10,0,0,0,0,0,0 +8.31,51,0,10,0,0,0,0,0,0 +8.32,51,0,10,0,0,0,0,0,0 +8.33,51,0,10,0,0,0,0,0,0 +8.34,51,0,10,0,0,0,0,0,0 +8.35,51,0,10,0,0,0,0,0,0 +8.36,51,0,10,0,0,0,0,0,0 +8.37,51,0,10,0,0,0,0,0,0 +8.38,51,0,10,0,0,0,0,0,0 +8.39,51,0,10,0,0,0,0,0,0 +8.4,51,0,10,0,0,0,0,0,0 +8.41,51,0,10,0,0,0,0,0,0 +8.42,51,0,10,0,0,0,0,0,0 +8.43,51,0,10,0,0,0,0,0,0 +8.44,51,0,10,0,0,0,0,0,0 +8.45,51,0,10,0,0,0,0,0,0 +8.46,51,0,10,0,0,0,0,0,0 +8.47,51,0,10,0,0,0,0,0,0 +8.48,51,0,10,0,0,0,0,0,0 +8.49,51,0,10,0,0,0,0,0,0 +8.5,51,0,10,0,0,0,0,0,0 +8.51,51,0,10,0,0,0,0,0,0 +8.52,51,0,10,0,0,0,0,0,0 +8.53,51,0,10,0,0,0,0,0,0 +8.54,51,0,10,0,0,0,0,0,0 +8.55,51,0,10,0,0,0,0,0,0 +8.56,51,0,10,0,0,0,0,0,0 +8.57,51,0,10,0,0,0,0,0,0 +8.58,51,0,10,0,0,0,0,0,0 +8.59,51,0,10,0,0,0,0,0,0 +8.6,51,0,10,0,0,0,0,0,0 +8.61,51,0,10,0,0,0,0,0,0 +8.62,51,0,10,0,0,0,0,0,0 +8.63,51,0,10,0,0,0,0,0,0 +8.64,51,0,10,0,0,0,0,0,0 +8.65,51,0,10,0,0,0,0,0,0 +8.66,51,0,10,0,0,0,0,0,0 +8.67,51,0,10,0,0,0,0,0,0 +8.68,51,0,10,0,0,0,0,0,0 +8.69,51,0,10,0,0,0,0,0,0 +8.7,51,0,10,0,0,0,0,0,0 +8.71,51,0,10,0,0,0,0,0,0 +8.72,51,0,10,0,0,0,0,0,0 +8.73,51,0,10,0,0,0,0,0,0 +8.74,51,0,10,0,0,0,0,0,0 +8.75,51,0,10,0,0,0,0,0,0 +8.76,51,0,10,0,0,0,0,0,0 +8.77,51,0,10,0,0,0,0,0,0 +8.78,51,0,10,0,0,0,0,0,0 +8.79,51,0,10,0,0,0,0,0,0 +8.8,51,0,10,0,0,0,0,0,0 +8.81,51,0,10,0,0,0,0,0,0 +8.82,51,0,10,0,0,0,0,0,0 +8.83,51,0,10,0,0,0,0,0,0 +8.84,51,0,10,0,0,0,0,0,0 +8.85,51,0,10,0,0,0,0,0,0 +8.86,51,0,10,0,0,0,0,0,0 +8.87,51,0,10,0,0,0,0,0,0 +8.88,51,0,10,0,0,0,0,0,0 +8.89,51,0,10,0,0,0,0,0,0 +8.9,51,0,10,0,0,0,0,0,0 +8.91,51,0,10,0,0,0,0,0,0 +8.92,51,0,10,0,0,0,0,0,0 +8.93,51,0,10,0,0,0,0,0,0 +8.94,51,0,10,0,0,0,0,0,0 +8.95,51,0,10,0,0,0,0,0,0 +8.96,51,0,10,0,0,0,0,0,0 +8.97,51,0,10,0,0,0,0,0,0 +8.98,51,0,10,0,0,0,0,0,0 +8.99,51,0,10,0,0,0,0,0,0 +9,51,0,10,0,0,0,0,0,0 +9.01,51,0,10,0,0,0,0,0,0 +9.02,51,0,10,0,0,0,0,0,0 +9.03,51,0,10,0,0,0,0,0,0 +9.04,51,0,10,0,0,0,0,0,0 +9.05,51,0,10,0,0,0,0,0,0 +9.06,51,0,10,0,0,0,0,0,0 +9.07,51,0,10,0,0,0,0,0,0 +9.08,51,0,10,0,0,0,0,0,0 +9.09,51,0,10,0,0,0,0,0,0 +9.1,51,0,10,0,0,0,0,0,0 +9.11,51,0,10,0,0,0,0,0,0 +9.12,51,0,10,0,0,0,0,0,0 +9.13,51,0,10,0,0,0,0,0,0 +9.14,51,0,10,0,0,0,0,0,0 +9.15,51,0,10,0,0,0,0,0,0 +9.16,51,0,10,0,0,0,0,0,0 +9.17,51,0,10,0,0,0,0,0,0 +9.18,51,0,10,0,0,0,0,0,0 +9.19,51,0,10,0,0,0,0,0,0 +9.2,51,0,10,0,0,0,0,0,0 +9.21,51,0,10,0,0,0,0,0,0 +9.22,51,0,10,0,0,0,0,0,0 +9.23,51,0,10,0,0,0,0,0,0 +9.24,51,0,10,0,0,0,0,0,0 +9.25,51,0,10,0,0,0,0,0,0 +9.26,51,0,10,0,0,0,0,0,0 +9.27,51,0,10,0,0,0,0,0,0 +9.28,51,0,10,0,0,0,0,0,0 +9.29,51,0,10,0,0,0,0,0,0 +9.3,51,0,10,0,0,0,0,0,0 +9.31,51,0,10,0,0,0,0,0,0 +9.32,51,0,10,0,0,0,0,0,0 +9.33,51,0,10,0,0,0,0,0,0 +9.34,51,0,10,0,0,0,0,0,0 +9.35,51,0,10,0,0,0,0,0,0 +9.36,51,0,10,0,0,0,0,0,0 +9.37,51,0,10,0,0,0,0,0,0 +9.38,51,0,10,0,0,0,0,0,0 +9.39,51,0,10,0,0,0,0,0,0 +9.4,51,0,10,0,0,0,0,0,0 +9.41,51,0,10,0,0,0,0,0,0 +9.42,51,0,10,0,0,0,0,0,0 +9.43,51,0,10,0,0,0,0,0,0 +9.44,51,0,10,0,0,0,0,0,0 +9.45,51,0,10,0,0,0,0,0,0 +9.46,51,0,10,0,0,0,0,0,0 +9.47,51,0,10,0,0,0,0,0,0 +9.48,51,0,10,0,0,0,0,0,0 +9.49,51,0,10,0,0,0,0,0,0 +9.5,51,0,10,0,0,0,0,0,0 +9.51,51,0,10,0,0,0,0,0,0 +9.52,51,0,10,0,0,0,0,0,0 +9.53,51,0,10,0,0,0,0,0,0 +9.54,51,0,10,0,0,0,0,0,0 +9.55,51,0,10,0,0,0,0,0,0 +9.56,51,0,10,0,0,0,0,0,0 +9.57,51,0,10,0,0,0,0,0,0 +9.58,51,0,10,0,0,0,0,0,0 +9.59,51,0,10,0,0,0,0,0,0 +9.6,51,0,10,0,0,0,0,0,0 +9.61,51,0,10,0,0,0,0,0,0 +9.62,51,0,10,0,0,0,0,0,0 +9.63,51,0,10,0,0,0,0,0,0 +9.64,51,0,10,0,0,0,0,0,0 +9.65,51,0,10,0,0,0,0,0,0 +9.66,51,0,10,0,0,0,0,0,0 +9.67,51,0,10,0,0,0,0,0,0 +9.68,51,0,10,0,0,0,0,0,0 +9.69,51,0,10,0,0,0,0,0,0 +9.7,51,0,10,0,0,0,0,0,0 +9.71,51,0,10,0,0,0,0,0,0 +9.72,51,0,10,0,0,0,0,0,0 +9.73,51,0,10,0,0,0,0,0,0 +9.74,51,0,10,0,0,0,0,0,0 +9.75,51,0,10,0,0,0,0,0,0 +9.76,51,0,10,0,0,0,0,0,0 +9.77,51,0,10,0,0,0,0,0,0 +9.78,51,0,10,0,0,0,0,0,0 +9.79,51,0,10,0,0,0,0,0,0 +9.8,51,0,10,0,0,0,0,0,0 +9.81,51,0,10,0,0,0,0,0,0 +9.82,51,0,10,0,0,0,0,0,0 +9.83,51,0,10,0,0,0,0,0,0 +9.84,51,0,10,0,0,0,0,0,0 +9.85,51,0,10,0,0,0,0,0,0 +9.86,51,0,10,0,0,0,0,0,0 +9.87,51,0,10,0,0,0,0,0,0 +9.88,51,0,10,0,0,0,0,0,0 +9.89,51,0,10,0,0,0,0,0,0 +9.9,51,0,10,0,0,0,0,0,0 +9.91,51,0,10,0,0,0,0,0,0 +9.92,51,0,10,0,0,0,0,0,0 +9.93,51,0,10,0,0,0,0,0,0 +9.94,51,0,10,0,0,0,0,0,0 +9.95,51,0,10,0,0,0,0,0,0 +9.96,51,0,10,0,0,0,0,0,0 +9.97,51,0,10,0,0,0,0,0,0 +9.98,51,0,10,0,0,0,0,0,0 +9.99,51,0,10,0,0,0,0,0,0 +10,51,0,10,0,0,0,0,0,0 +10.01,51,0,10,0,0,0,0,0,0 +10.02,51,0,10,0,0,0,0,0,0 +10.03,51,0,10,0,0,0,0,0,0 +10.04,51,0,10,0,0,0,0,0,0 +10.05,51,0,10,0,0,0,0,0,0 +10.06,51,0,10,0,0,0,0,0,0 +10.07,51,0,10,0,0,0,0,0,0 +10.08,51,0,10,0,0,0,0,0,0 +10.09,51,0,10,0,0,0,0,0,0 +10.1,51,0,10,0,0,0,0,0,0 +10.11,51,0,10,0,0,0,0,0,0 +10.12,51,0,10,0,0,0,0,0,0 +10.13,51,0,10,0,0,0,0,0,0 +10.14,51,0,10,0,0,0,0,0,0 +10.15,51,0,10,0,0,0,0,0,0 +10.16,51,0,10,0,0,0,0,0,0 +10.17,51,0,10,0,0,0,0,0,0 +10.18,51,0,10,0,0,0,0,0,0 +10.19,51,0,10,0,0,0,0,0,0 +10.2,51,0,10,0,0,0,0,0,0 +10.21,51,0,10,0,0,0,0,0,0 +10.22,51,0,10,0,0,0,0,0,0 +10.23,51,0,10,0,0,0,0,0,0 +10.24,51,0,10,0,0,0,0,0,0 +10.25,51,0,10,0,0,0,0,0,0 +10.26,51,0,10,0,0,0,0,0,0 +10.27,51,0,10,0,0,0,0,0,0 +10.28,51,0,10,0,0,0,0,0,0 +10.29,51,0,10,0,0,0,0,0,0 +10.3,51,0,10,0,0,0,0,0,0 +10.31,51,0,10,0,0,0,0,0,0 +10.32,51,0,10,0,0,0,0,0,0 +10.33,51,0,10,0,0,0,0,0,0 +10.34,51,0,10,0,0,0,0,0,0 +10.35,51,0,10,0,0,0,0,0,0 +10.36,51,0,10,0,0,0,0,0,0 +10.37,51,0,10,0,0,0,0,0,0 +10.38,51,0,10,0,0,0,0,0,0 +10.39,51,0,10,0,0,0,0,0,0 +10.4,51,0,10,0,0,0,0,0,0 +10.41,51,0,10,0,0,0,0,0,0 +10.42,51,0,10,0,0,0,0,0,0 +10.43,51,0,10,0,0,0,0,0,0 +10.44,51,0,10,0,0,0,0,0,0 +10.45,51,0,10,0,0,0,0,0,0 +10.46,51,0,10,0,0,0,0,0,0 +10.47,51,0,10,0,0,0,0,0,0 +10.48,51,0,10,0,0,0,0,0,0 +10.49,51,0,10,0,0,0,0,0,0 +10.5,51,0,10,0,0,0,0,0,0 +10.51,51,0,10,0,0,0,0,0,0 +10.52,51,0,10,0,0,0,0,0,0 +10.53,51,0,10,0,0,0,0,0,0 +10.54,51,0,10,0,0,0,0,0,0 +10.55,51,0,10,0,0,0,0,0,0 +10.56,51,0,10,0,0,0,0,0,0 +10.57,51,0,10,0,0,0,0,0,0 +10.58,51,0,10,0,0,0,0,0,0 +10.59,51,0,10,0,0,0,0,0,0 +10.6,51,0,10,0,0,0,0,0,0 +10.61,51,0,10,0,0,0,0,0,0 +10.62,51,0,10,0,0,0,0,0,0 +10.63,51,0,10,0,0,0,0,0,0 +10.64,51,0,10,0,0,0,0,0,0 +10.65,51,0,10,0,0,0,0,0,0 +10.66,51,0,10,0,0,0,0,0,0 +10.67,51,0,10,0,0,0,0,0,0 +10.68,51,0,10,0,0,0,0,0,0 +10.69,51,0,10,0,0,0,0,0,0 +10.7,51,0,10,0,0,0,0,0,0 +10.71,51,0,10,0,0,0,0,0,0 +10.72,51,0,10,0,0,0,0,0,0 +10.73,51,0,10,0,0,0,0,0,0 +10.74,51,0,10,0,0,0,0,0,0 +10.75,51,0,10,0,0,0,0,0,0 +10.76,51,0,10,0,0,0,0,0,0 +10.77,51,0,10,0,0,0,0,0,0 +10.78,51,0,10,0,0,0,0,0,0 +10.79,51,0,10,0,0,0,0,0,0 +10.8,51,0,10,0,0,0,0,0,0 +10.81,51,0,10,0,0,0,0,0,0 +10.82,51,0,10,0,0,0,0,0,0 +10.83,51,0,10,0,0,0,0,0,0 +10.84,51,0,10,0,0,0,0,0,0 +10.85,51,0,10,0,0,0,0,0,0 +10.86,51,0,10,0,0,0,0,0,0 +10.87,51,0,10,0,0,0,0,0,0 +10.88,51,0,10,0,0,0,0,0,0 +10.89,51,0,10,0,0,0,0,0,0 +10.9,51,0,10,0,0,0,0,0,0 +10.91,51,0,10,0,0,0,0,0,0 +10.92,51,0,10,0,0,0,0,0,0 +10.93,51,0,10,0,0,0,0,0,0 +10.94,51,0,10,0,0,0,0,0,0 +10.95,51,0,10,0,0,0,0,0,0 +10.96,51,0,10,0,0,0,0,0,0 +10.97,51,0,10,0,0,0,0,0,0 +10.98,51,0,10,0,0,0,0,0,0 +10.99,51,0,10,0,0,0,0,0,0 +11,51,0,10,0,0,0,0,0,0 +11.01,51,0,10,0,0,0,0,0,0 +11.02,51,0,10,0,0,0,0,0,0 +11.03,51,0,10,0,0,0,0,0,0 +11.04,51,0,10,0,0,0,0,0,0 +11.05,51,0,10,0,0,0,0,0,0 +11.06,51,0,10,0,0,0,0,0,0 +11.07,51,0,10,0,0,0,0,0,0 +11.08,51,0,10,0,0,0,0,0,0 +11.09,51,0,10,0,0,0,0,0,0 +11.1,51,0,10,0,0,0,0,0,0 +11.11,51,0,10,0,0,0,0,0,0 +11.12,51,0,10,0,0,0,0,0,0 +11.13,51,0,10,0,0,0,0,0,0 +11.14,51,0,10,0,0,0,0,0,0 +11.15,51,0,10,0,0,0,0,0,0 +11.16,51,0,10,0,0,0,0,0,0 +11.17,51,0,10,0,0,0,0,0,0 +11.18,51,0,10,0,0,0,0,0,0 +11.19,51,0,10,0,0,0,0,0,0 +11.2,51,0,10,0,0,0,0,0,0 +11.21,51,0,10,0,0,0,0,0,0 +11.22,51,0,10,0,0,0,0,0,0 +11.23,51,0,10,0,0,0,0,0,0 +11.24,51,0,10,0,0,0,0,0,0 +11.25,51,0,10,0,0,0,0,0,0 +11.26,51,0,10,0,0,0,0,0,0 +11.27,51,0,10,0,0,0,0,0,0 +11.28,51,0,10,0,0,0,0,0,0 +11.29,51,0,10,0,0,0,0,0,0 +11.3,51,0,10,0,0,0,0,0,0 +11.31,51,0,10,0,0,0,0,0,0 +11.32,51,0,10,0,0,0,0,0,0 +11.33,51,0,10,0,0,0,0,0,0 +11.34,51,0,10,0,0,0,0,0,0 +11.35,51,0,10,0,0,0,0,0,0 +11.36,51,0,10,0,0,0,0,0,0 +11.37,51,0,10,0,0,0,0,0,0 +11.38,51,0,10,0,0,0,0,0,0 +11.39,51,0,10,0,0,0,0,0,0 +11.4,51,0,10,0,0,0,0,0,0 +11.41,51,0,10,0,0,0,0,0,0 +11.42,51,0,10,0,0,0,0,0,0 +11.43,51,0,10,0,0,0,0,0,0 +11.44,51,0,10,0,0,0,0,0,0 +11.45,51,0,10,0,0,0,0,0,0 +11.46,51,0,10,0,0,0,0,0,0 +11.47,51,0,10,0,0,0,0,0,0 +11.48,51,0,10,0,0,0,0,0,0 +11.49,51,0,10,0,0,0,0,0,0 +11.5,51,0,10,0,0,0,0,0,0 +11.51,51,0,10,0,0,0,0,0,0 +11.52,51,0,10,0,0,0,0,0,0 +11.53,51,0,10,0,0,0,0,0,0 +11.54,51,0,10,0,0,0,0,0,0 +11.55,51,0,10,0,0,0,0,0,0 +11.56,51,0,10,0,0,0,0,0,0 +11.57,51,0,10,0,0,0,0,0,0 +11.58,51,0,10,0,0,0,0,0,0 +11.59,51,0,10,0,0,0,0,0,0 +11.6,51,0,10,0,0,0,0,0,0 +11.61,51,0,10,0,0,0,0,0,0 +11.62,51,0,10,0,0,0,0,0,0 +11.63,51,0,10,0,0,0,0,0,0 +11.64,51,0,10,0,0,0,0,0,0 +11.65,51,0,10,0,0,0,0,0,0 +11.66,51,0,10,0,0,0,0,0,0 +11.67,51,0,10,0,0,0,0,0,0 +11.68,51,0,10,0,0,0,0,0,0 +11.69,51,0,10,0,0,0,0,0,0 +11.7,51,0,10,0,0,0,0,0,0 +11.71,51,0,10,0,0,0,0,0,0 +11.72,51,0,10,0,0,0,0,0,0 +11.73,51,0,10,0,0,0,0,0,0 +11.74,51,0,10,0,0,0,0,0,0 +11.75,51,0,10,0,0,0,0,0,0 +11.76,51,0,10,0,0,0,0,0,0 +11.77,51,0,10,0,0,0,0,0,0 +11.78,51,0,10,0,0,0,0,0,0 +11.79,51,0,10,0,0,0,0,0,0 +11.8,51,0,10,0,0,0,0,0,0 +11.81,51,0,10,0,0,0,0,0,0 +11.82,51,0,10,0,0,0,0,0,0 +11.83,51,0,10,0,0,0,0,0,0 +11.84,51,0,10,0,0,0,0,0,0 +11.85,51,0,10,0,0,0,0,0,0 +11.86,51,0,10,0,0,0,0,0,0 +11.87,51,0,10,0,0,0,0,0,0 +11.88,51,0,10,0,0,0,0,0,0 +11.89,51,0,10,0,0,0,0,0,0 +11.9,51,0,10,0,0,0,0,0,0 +11.91,51,0,10,0,0,0,0,0,0 +11.92,51,0,10,0,0,0,0,0,0 +11.93,51,0,10,0,0,0,0,0,0 +11.94,51,0,10,0,0,0,0,0,0 +11.95,51,0,10,0,0,0,0,0,0 +11.96,51,0,10,0,0,0,0,0,0 +11.97,51,0,10,0,0,0,0,0,0 +11.98,51,0,10,0,0,0,0,0,0 +11.99,51,0,10,0,0,0,0,0,0 +12,51,0,10,0,0,0,0,0,0 +12.01,51,0,10,0,0,0,0,0,0 +12.02,51,0,10,0,0,0,0,0,0 +12.03,51,0,10,0,0,0,0,0,0 +12.04,51,0,10,0,0,0,0,0,0 +12.05,51,0,10,0,0,0,0,0,0 +12.06,51,0,10,0,0,0,0,0,0 +12.07,51,0,10,0,0,0,0,0,0 +12.08,51,0,10,0,0,0,0,0,0 +12.09,51,0,10,0,0,0,0,0,0 +12.1,51,0,10,0,0,0,0,0,0 +12.11,51,0,10,0,0,0,0,0,0 +12.12,51,0,10,0,0,0,0,0,0 +12.13,51,0,10,0,0,0,0,0,0 +12.14,51,0,10,0,0,0,0,0,0 +12.15,51,0,10,0,0,0,0,0,0 +12.16,51,0,10,0,0,0,0,0,0 +12.17,51,0,10,0,0,0,0,0,0 +12.18,51,0,10,0,0,0,0,0,0 +12.19,51,0,10,0,0,0,0,0,0 +12.2,51,0,10,0,0,0,0,0,0 +12.21,51,0,10,0,0,0,0,0,0 +12.22,51,0,10,0,0,0,0,0,0 +12.23,51,0,10,0,0,0,0,0,0 +12.24,51,0,10,0,0,0,0,0,0 +12.25,51,0,10,0,0,0,0,0,0 +12.26,51,0,10,0,0,0,0,0,0 +12.27,51,0,10,0,0,0,0,0,0 +12.28,51,0,10,0,0,0,0,0,0 +12.29,51,0,10,0,0,0,0,0,0 +12.3,51,0,10,0,0,0,0,0,0 +12.31,51,0,10,0,0,0,0,0,0 +12.32,51,0,10,0,0,0,0,0,0 +12.33,51,0,10,0,0,0,0,0,0 +12.34,51,0,10,0,0,0,0,0,0 +12.35,51,0,10,0,0,0,0,0,0 +12.36,51,0,10,0,0,0,0,0,0 +12.37,51,0,10,0,0,0,0,0,0 +12.38,51,0,10,0,0,0,0,0,0 +12.39,51,0,10,0,0,0,0,0,0 +12.4,51,0,10,0,0,0,0,0,0 +12.41,51,0,10,0,0,0,0,0,0 +12.42,51,0,10,0,0,0,0,0,0 +12.43,51,0,10,0,0,0,0,0,0 +12.44,51,0,10,0,0,0,0,0,0 +12.45,51,0,10,0,0,0,0,0,0 +12.46,51,0,10,0,0,0,0,0,0 +12.47,51,0,10,0,0,0,0,0,0 +12.48,51,0,10,0,0,0,0,0,0 +12.49,51,0,10,0,0,0,0,0,0 +12.5,51,0,10,0,0,0,0,0,0 +12.51,51,0,10,0,0,0,0,0,0 +12.52,51,0,10,0,0,0,0,0,0 +12.53,51,0,10,0,0,0,0,0,0 +12.54,51,0,10,0,0,0,0,0,0 +12.55,51,0,10,0,0,0,0,0,0 +12.56,51,0,10,0,0,0,0,0,0 +12.57,51,0,10,0,0,0,0,0,0 +12.58,51,0,10,0,0,0,0,0,0 +12.59,51,0,10,0,0,0,0,0,0 +12.6,51,0,10,0,0,0,0,0,0 +12.61,51,0,10,0,0,0,0,0,0 +12.62,51,0,10,0,0,0,0,0,0 +12.63,51,0,10,0,0,0,0,0,0 +12.64,51,0,10,0,0,0,0,0,0 +12.65,51,0,10,0,0,0,0,0,0 +12.66,51,0,10,0,0,0,0,0,0 +12.67,51,0,10,0,0,0,0,0,0 +12.68,51,0,10,0,0,0,0,0,0 +12.69,51,0,10,0,0,0,0,0,0 +12.7,51,0,10,0,0,0,0,0,0 +12.71,51,0,10,0,0,0,0,0,0 +12.72,51,0,10,0,0,0,0,0,0 +12.73,51,0,10,0,0,0,0,0,0 +12.74,51,0,10,0,0,0,0,0,0 +12.75,51,0,10,0,0,0,0,0,0 +12.76,51,0,10,0,0,0,0,0,0 +12.77,51,0,10,0,0,0,0,0,0 +12.78,51,0,10,0,0,0,0,0,0 +12.79,51,0,10,0,0,0,0,0,0 +12.8,51,0,10,0,0,0,0,0,0 +12.81,51,0,10,0,0,0,0,0,0 +12.82,51,0,10,0,0,0,0,0,0 +12.83,51,0,10,0,0,0,0,0,0 +12.84,51,0,10,0,0,0,0,0,0 +12.85,51,0,10,0,0,0,0,0,0 +12.86,51,0,10,0,0,0,0,0,0 +12.87,51,0,10,0,0,0,0,0,0 +12.88,51,0,10,0,0,0,0,0,0 +12.89,51,0,10,0,0,0,0,0,0 +12.9,51,0,10,0,0,0,0,0,0 +12.91,51,0,10,0,0,0,0,0,0 +12.92,51,0,10,0,0,0,0,0,0 +12.93,51,0,10,0,0,0,0,0,0 +12.94,51,0,10,0,0,0,0,0,0 +12.95,51,0,10,0,0,0,0,0,0 +12.96,51,0,10,0,0,0,0,0,0 +12.97,51,0,10,0,0,0,0,0,0 +12.98,51,0,10,0,0,0,0,0,0 +12.99,51,0,10,0,0,0,0,0,0 +13,51,0,10,0,0,0,0,0,0 +13.01,51,0,10,0,0,0,0,0,0 +13.02,51,0,10,0,0,0,0,0,0 +13.03,51,0,10,0,0,0,0,0,0 +13.04,51,0,10,0,0,0,0,0,0 +13.05,51,0,10,0,0,0,0,0,0 +13.06,51,0,10,0,0,0,0,0,0 +13.07,51,0,10,0,0,0,0,0,0 +13.08,51,0,10,0,0,0,0,0,0 +13.09,51,0,10,0,0,0,0,0,0 +13.1,51,0,10,0,0,0,0,0,0 +13.11,51,0,10,0,0,0,0,0,0 +13.12,51,0,10,0,0,0,0,0,0 +13.13,51,0,10,0,0,0,0,0,0 +13.14,51,0,10,0,0,0,0,0,0 +13.15,51,0,10,0,0,0,0,0,0 +13.16,51,0,10,0,0,0,0,0,0 +13.17,51,0,10,0,0,0,0,0,0 +13.18,51,0,10,0,0,0,0,0,0 +13.19,51,0,10,0,0,0,0,0,0 +13.2,51,0,10,0,0,0,0,0,0 +13.21,51,0,10,0,0,0,0,0,0 +13.22,51,0,10,0,0,0,0,0,0 +13.23,51,0,10,0,0,0,0,0,0 +13.24,51,0,10,0,0,0,0,0,0 +13.25,51,0,10,0,0,0,0,0,0 +13.26,51,0,10,0,0,0,0,0,0 +13.27,51,0,10,0,0,0,0,0,0 +13.28,51,0,10,0,0,0,0,0,0 +13.29,51,0,10,0,0,0,0,0,0 +13.3,51,0,10,0,0,0,0,0,0 +13.31,51,0,10,0,0,0,0,0,0 +13.32,51,0,10,0,0,0,0,0,0 +13.33,51,0,10,0,0,0,0,0,0 +13.34,51,0,10,0,0,0,0,0,0 +13.35,51,0,10,0,0,0,0,0,0 +13.36,51,0,10,0,0,0,0,0,0 +13.37,51,0,10,0,0,0,0,0,0 +13.38,51,0,10,0,0,0,0,0,0 +13.39,51,0,10,0,0,0,0,0,0 +13.4,51,0,10,0,0,0,0,0,0 +13.41,51,0,10,0,0,0,0,0,0 +13.42,51,0,10,0,0,0,0,0,0 +13.43,51,0,10,0,0,0,0,0,0 +13.44,51,0,10,0,0,0,0,0,0 +13.45,51,0,10,0,0,0,0,0,0 +13.46,51,0,10,0,0,0,0,0,0 +13.47,51,0,10,0,0,0,0,0,0 +13.48,51,0,10,0,0,0,0,0,0 +13.49,51,0,10,0,0,0,0,0,0 +13.5,51,0,10,0,0,0,0,0,0 +13.51,51,0,10,0,0,0,0,0,0 +13.52,51,0,10,0,0,0,0,0,0 +13.53,51,0,10,0,0,0,0,0,0 +13.54,51,0,10,0,0,0,0,0,0 +13.55,51,0,10,0,0,0,0,0,0 +13.56,51,0,10,0,0,0,0,0,0 +13.57,51,0,10,0,0,0,0,0,0 +13.58,51,0,10,0,0,0,0,0,0 +13.59,51,0,10,0,0,0,0,0,0 +13.6,51,0,10,0,0,0,0,0,0 +13.61,51,0,10,0,0,0,0,0,0 +13.62,51,0,10,0,0,0,0,0,0 +13.63,51,0,10,0,0,0,0,0,0 +13.64,51,0,10,0,0,0,0,0,0 +13.65,51,0,10,0,0,0,0,0,0 +13.66,51,0,10,0,0,0,0,0,0 +13.67,51,0,10,0,0,0,0,0,0 +13.68,51,0,10,0,0,0,0,0,0 +13.69,51,0,10,0,0,0,0,0,0 +13.7,51,0,10,0,0,0,0,0,0 +13.71,51,0,10,0,0,0,0,0,0 +13.72,51,0,10,0,0,0,0,0,0 +13.73,51,0,10,0,0,0,0,0,0 +13.74,51,0,10,0,0,0,0,0,0 +13.75,51,0,10,0,0,0,0,0,0 +13.76,51,0,10,0,0,0,0,0,0 +13.77,51,0,10,0,0,0,0,0,0 +13.78,51,0,10,0,0,0,0,0,0 +13.79,51,0,10,0,0,0,0,0,0 +13.8,51,0,10,0,0,0,0,0,0 +13.81,51,0,10,0,0,0,0,0,0 +13.82,51,0,10,0,0,0,0,0,0 +13.83,51,0,10,0,0,0,0,0,0 +13.84,51,0,10,0,0,0,0,0,0 +13.85,51,0,10,0,0,0,0,0,0 +13.86,51,0,10,0,0,0,0,0,0 +13.87,51,0,10,0,0,0,0,0,0 +13.88,51,0,10,0,0,0,0,0,0 +13.89,51,0,10,0,0,0,0,0,0 +13.9,51,0,10,0,0,0,0,0,0 +13.91,51,0,10,0,0,0,0,0,0 +13.92,51,0,10,0,0,0,0,0,0 +13.93,51,0,10,0,0,0,0,0,0 +13.94,51,0,10,0,0,0,0,0,0 +13.95,51,0,10,0,0,0,0,0,0 +13.96,51,0,10,0,0,0,0,0,0 +13.97,51,0,10,0,0,0,0,0,0 +13.98,51,0,10,0,0,0,0,0,0 +13.99,51,0,10,0,0,0,0,0,0 +14,51,0,10,0,0,0,0,0,0 +14.01,51,0,10,0,0,0,0,0,0 +14.02,51,0,10,0,0,0,0,0,0 +14.03,51,0,10,0,0,0,0,0,0 +14.04,51,0,10,0,0,0,0,0,0 +14.05,51,0,10,0,0,0,0,0,0 +14.06,51,0,10,0,0,0,0,0,0 +14.07,51,0,10,0,0,0,0,0,0 +14.08,51,0,10,0,0,0,0,0,0 +14.09,51,0,10,0,0,0,0,0,0 +14.1,51,0,10,0,0,0,0,0,0 +14.11,51,0,10,0,0,0,0,0,0 +14.12,51,0,10,0,0,0,0,0,0 +14.13,51,0,10,0,0,0,0,0,0 +14.14,51,0,10,0,0,0,0,0,0 +14.15,51,0,10,0,0,0,0,0,0 +14.16,51,0,10,0,0,0,0,0,0 +14.17,51,0,10,0,0,0,0,0,0 +14.18,51,0,10,0,0,0,0,0,0 +14.19,51,0,10,0,0,0,0,0,0 +14.2,51,0,10,0,0,0,0,0,0 +14.21,51,0,10,0,0,0,0,0,0 +14.22,51,0,10,0,0,0,0,0,0 +14.23,51,0,10,0,0,0,0,0,0 +14.24,51,0,10,0,0,0,0,0,0 +14.25,51,0,10,0,0,0,0,0,0 +14.26,51,0,10,0,0,0,0,0,0 +14.27,51,0,10,0,0,0,0,0,0 +14.28,51,0,10,0,0,0,0,0,0 +14.29,51,0,10,0,0,0,0,0,0 +14.3,51,0,10,0,0,0,0,0,0 +14.31,51,0,10,0,0,0,0,0,0 +14.32,51,0,10,0,0,0,0,0,0 +14.33,51,0,10,0,0,0,0,0,0 +14.34,51,0,10,0,0,0,0,0,0 +14.35,51,0,10,0,0,0,0,0,0 +14.36,51,0,10,0,0,0,0,0,0 +14.37,51,0,10,0,0,0,0,0,0 +14.38,51,0,10,0,0,0,0,0,0 +14.39,51,0,10,0,0,0,0,0,0 +14.4,51,0,10,0,0,0,0,0,0 +14.41,51,0,10,0,0,0,0,0,0 +14.42,51,0,10,0,0,0,0,0,0 +14.43,51,0,10,0,0,0,0,0,0 +14.44,51,0,10,0,0,0,0,0,0 +14.45,51,0,10,0,0,0,0,0,0 +14.46,51,0,10,0,0,0,0,0,0 +14.47,51,0,10,0,0,0,0,0,0 +14.48,51,0,10,0,0,0,0,0,0 +14.49,51,0,10,0,0,0,0,0,0 +14.5,51,0,10,0,0,0,0,0,0 +14.51,51,0,10,0,0,0,0,0,0 +14.52,51,0,10,0,0,0,0,0,0 +14.53,51,0,10,0,0,0,0,0,0 +14.54,51,0,10,0,0,0,0,0,0 +14.55,51,0,10,0,0,0,0,0,0 +14.56,51,0,10,0,0,0,0,0,0 +14.57,51,0,10,0,0,0,0,0,0 +14.58,51,0,10,0,0,0,0,0,0 +14.59,51,0,10,0,0,0,0,0,0 +14.6,51,0,10,0,0,0,0,0,0 +14.61,51,0,10,0,0,0,0,0,0 +14.62,51,0,10,0,0,0,0,0,0 +14.63,51,0,10,0,0,0,0,0,0 +14.64,51,0,10,0,0,0,0,0,0 +14.65,51,0,10,0,0,0,0,0,0 +14.66,51,0,10,0,0,0,0,0,0 +14.67,51,0,10,0,0,0,0,0,0 +14.68,51,0,10,0,0,0,0,0,0 +14.69,51,0,10,0,0,0,0,0,0 +14.7,51,0,10,0,0,0,0,0,0 +14.71,51,0,10,0,0,0,0,0,0 +14.72,51,0,10,0,0,0,0,0,0 +14.73,51,0,10,0,0,0,0,0,0 +14.74,51,0,10,0,0,0,0,0,0 +14.75,51,0,10,0,0,0,0,0,0 +14.76,51,0,10,0,0,0,0,0,0 +14.77,51,0,10,0,0,0,0,0,0 +14.78,51,0,10,0,0,0,0,0,0 +14.79,51,0,10,0,0,0,0,0,0 +14.8,51,0,10,0,0,0,0,0,0 +14.81,51,0,10,0,0,0,0,0,0 +14.82,51,0,10,0,0,0,0,0,0 +14.83,51,0,10,0,0,0,0,0,0 +14.84,51,0,10,0,0,0,0,0,0 +14.85,51,0,10,0,0,0,0,0,0 +14.86,51,0,10,0,0,0,0,0,0 +14.87,51,0,10,0,0,0,0,0,0 +14.88,51,0,10,0,0,0,0,0,0 +14.89,51,0,10,0,0,0,0,0,0 +14.9,51,0,10,0,0,0,0,0,0 +14.91,51,0,10,0,0,0,0,0,0 +14.92,51,0,10,0,0,0,0,0,0 +14.93,51,0,10,0,0,0,0,0,0 +14.94,51,0,10,0,0,0,0,0,0 +14.95,51,0,10,0,0,0,0,0,0 +14.96,51,0,10,0,0,0,0,0,0 +14.97,51,0,10,0,0,0,0,0,0 +14.98,51,0,10,0,0,0,0,0,0 +14.99,51,0,10,0,0,0,0,0,0 +15,51,0,10,0,0,0,0,0,0 +15.01,51,0,10,0,0,0,0,0,0 +15.02,51,0,10,0,0,0,0,0,0 +15.03,51,0,10,0,0,0,0,0,0 +15.04,51,0,10,0,0,0,0,0,0 +15.05,51,0,10,0,0,0,0,0,0 +15.06,51,0,10,0,0,0,0,0,0 +15.07,51,0,10,0,0,0,0,0,0 +15.08,51,0,10,0,0,0,0,0,0 +15.09,51,0,10,0,0,0,0,0,0 +15.1,51,0,10,0,0,0,0,0,0 +15.11,51,0,10,0,0,0,0,0,0 +15.12,51,0,10,0,0,0,0,0,0 +15.13,51,0,10,0,0,0,0,0,0 +15.14,51,0,10,0,0,0,0,0,0 +15.15,51,0,10,0,0,0,0,0,0 +15.16,51,0,10,0,0,0,0,0,0 +15.17,51,0,10,0,0,0,0,0,0 +15.18,51,0,10,0,0,0,0,0,0 +15.19,51,0,10,0,0,0,0,0,0 +15.2,51,0,10,0,0,0,0,0,0 +15.21,51,0,10,0,0,0,0,0,0 +15.22,51,0,10,0,0,0,0,0,0 +15.23,51,0,10,0,0,0,0,0,0 +15.24,51,0,10,0,0,0,0,0,0 +15.25,51,0,10,0,0,0,0,0,0 +15.26,51,0,10,0,0,0,0,0,0 +15.27,51,0,10,0,0,0,0,0,0 +15.28,51,0,10,0,0,0,0,0,0 +15.29,51,0,10,0,0,0,0,0,0 +15.3,51,0,10,0,0,0,0,0,0 +15.31,51,0,10,0,0,0,0,0,0 +15.32,51,0,10,0,0,0,0,0,0 +15.33,51,0,10,0,0,0,0,0,0 +15.34,51,0,10,0,0,0,0,0,0 +15.35,51,0,10,0,0,0,0,0,0 +15.36,51,0,10,0,0,0,0,0,0 +15.37,51,0,10,0,0,0,0,0,0 +15.38,51,0,10,0,0,0,0,0,0 +15.39,51,0,10,0,0,0,0,0,0 +15.4,51,0,10,0,0,0,0,0,0 +15.41,51,0,10,0,0,0,0,0,0 +15.42,51,0,10,0,0,0,0,0,0 +15.43,51,0,10,0,0,0,0,0,0 +15.44,51,0,10,0,0,0,0,0,0 +15.45,51,0,10,0,0,0,0,0,0 +15.46,51,0,10,0,0,0,0,0,0 +15.47,51,0,10,0,0,0,0,0,0 +15.48,51,0,10,0,0,0,0,0,0 +15.49,51,0,10,0,0,0,0,0,0 +15.5,51,0,10,0,0,0,0,0,0 +15.51,51,0,10,0,0,0,0,0,0 +15.52,51,0,10,0,0,0,0,0,0 +15.53,51,0,10,0,0,0,0,0,0 +15.54,51,0,10,0,0,0,0,0,0 +15.55,51,0,10,0,0,0,0,0,0 +15.56,51,0,10,0,0,0,0,0,0 +15.57,51,0,10,0,0,0,0,0,0 +15.58,51,0,10,0,0,0,0,0,0 +15.59,51,0,10,0,0,0,0,0,0 +15.6,51,0,10,0,0,0,0,0,0 +15.61,51,0,10,0,0,0,0,0,0 +15.62,51,0,10,0,0,0,0,0,0 +15.63,51,0,10,0,0,0,0,0,0 +15.64,51,0,10,0,0,0,0,0,0 +15.65,51,0,10,0,0,0,0,0,0 +15.66,51,0,10,0,0,0,0,0,0 +15.67,51,0,10,0,0,0,0,0,0 +15.68,51,0,10,0,0,0,0,0,0 +15.69,51,0,10,0,0,0,0,0,0 +15.7,51,0,10,0,0,0,0,0,0 +15.71,51,0,10,0,0,0,0,0,0 +15.72,51,0,10,0,0,0,0,0,0 +15.73,51,0,10,0,0,0,0,0,0 +15.74,51,0,10,0,0,0,0,0,0 +15.75,51,0,10,0,0,0,0,0,0 +15.76,51,0,10,0,0,0,0,0,0 +15.77,51,0,10,0,0,0,0,0,0 +15.78,51,0,10,0,0,0,0,0,0 +15.79,51,0,10,0,0,0,0,0,0 +15.8,51,0,10,0,0,0,0,0,0 +15.81,51,0,10,0,0,0,0,0,0 +15.82,51,0,10,0,0,0,0,0,0 +15.83,51,0,10,0,0,0,0,0,0 +15.84,51,0,10,0,0,0,0,0,0 +15.85,51,0,10,0,0,0,0,0,0 +15.86,51,0,10,0,0,0,0,0,0 +15.87,51,0,10,0,0,0,0,0,0 +15.88,51,0,10,0,0,0,0,0,0 +15.89,51,0,10,0,0,0,0,0,0 +15.9,51,0,10,0,0,0,0,0,0 +15.91,51,0,10,0,0,0,0,0,0 +15.92,51,0,10,0,0,0,0,0,0 +15.93,51,0,10,0,0,0,0,0,0 +15.94,51,0,10,0,0,0,0,0,0 +15.95,51,0,10,0,0,0,0,0,0 +15.96,51,0,10,0,0,0,0,0,0 +15.97,51,0,10,0,0,0,0,0,0 +15.98,51,0,10,0,0,0,0,0,0 +15.99,51,0,10,0,0,0,0,0,0 +16,51,0,10,0,0,0,0,0,0 +16.01,51,0,10,0,0,0,0,0,0 +16.02,51,0,10,0,0,0,0,0,0 +16.03,51,0,10,0,0,0,0,0,0 +16.04,51,0,10,0,0,0,0,0,0 +16.05,51,0,10,0,0,0,0,0,0 +16.06,51,0,10,0,0,0,0,0,0 +16.07,51,0,10,0,0,0,0,0,0 +16.08,51,0,10,0,0,0,0,0,0 +16.09,51,0,10,0,0,0,0,0,0 +16.1,51,0,10,0,0,0,0,0,0 +16.11,51,0,10,0,0,0,0,0,0 +16.12,51,0,10,0,0,0,0,0,0 +16.13,51,0,10,0,0,0,0,0,0 +16.14,51,0,10,0,0,0,0,0,0 +16.15,51,0,10,0,0,0,0,0,0 +16.16,51,0,10,0,0,0,0,0,0 +16.17,51,0,10,0,0,0,0,0,0 +16.18,51,0,10,0,0,0,0,0,0 +16.19,51,0,10,0,0,0,0,0,0 +16.2,51,0,10,0,0,0,0,0,0 +16.21,51,0,10,0,0,0,0,0,0 +16.22,51,0,10,0,0,0,0,0,0 +16.23,51,0,10,0,0,0,0,0,0 +16.24,51,0,10,0,0,0,0,0,0 +16.25,51,0,10,0,0,0,0,0,0 +16.26,51,0,10,0,0,0,0,0,0 +16.27,51,0,10,0,0,0,0,0,0 +16.28,51,0,10,0,0,0,0,0,0 +16.29,51,0,10,0,0,0,0,0,0 +16.3,51,0,10,0,0,0,0,0,0 +16.31,51,0,10,0,0,0,0,0,0 +16.32,51,0,10,0,0,0,0,0,0 +16.33,51,0,10,0,0,0,0,0,0 +16.34,51,0,10,0,0,0,0,0,0 +16.35,51,0,10,0,0,0,0,0,0 +16.36,51,0,10,0,0,0,0,0,0 +16.37,51,0,10,0,0,0,0,0,0 +16.38,51,0,10,0,0,0,0,0,0 +16.39,51,0,10,0,0,0,0,0,0 +16.4,51,0,10,0,0,0,0,0,0 +16.41,51,0,10,0,0,0,0,0,0 +16.42,51,0,10,0,0,0,0,0,0 +16.43,51,0,10,0,0,0,0,0,0 +16.44,51,0,10,0,0,0,0,0,0 +16.45,51,0,10,0,0,0,0,0,0 +16.46,51,0,10,0,0,0,0,0,0 +16.47,51,0,10,0,0,0,0,0,0 +16.48,51,0,10,0,0,0,0,0,0 +16.49,51,0,10,0,0,0,0,0,0 +16.5,51,0,10,0,0,0,0,0,0 +16.51,51,0,10,0,0,0,0,0,0 +16.52,51,0,10,0,0,0,0,0,0 +16.53,51,0,10,0,0,0,0,0,0 +16.54,51,0,10,0,0,0,0,0,0 +16.55,51,0,10,0,0,0,0,0,0 +16.56,51,0,10,0,0,0,0,0,0 +16.57,51,0,10,0,0,0,0,0,0 +16.58,51,0,10,0,0,0,0,0,0 +16.59,51,0,10,0,0,0,0,0,0 +16.6,51,0,10,0,0,0,0,0,0 +16.61,51,0,10,0,0,0,0,0,0 +16.62,51,0,10,0,0,0,0,0,0 +16.63,51,0,10,0,0,0,0,0,0 +16.64,51,0,10,0,0,0,0,0,0 +16.65,51,0,10,0,0,0,0,0,0 +16.66,51,0,10,0,0,0,0,0,0 +16.67,51,0,10,0,0,0,0,0,0 +16.68,51,0,10,0,0,0,0,0,0 +16.69,51,0,10,0,0,0,0,0,0 +16.7,51,0,10,0,0,0,0,0,0 +16.71,51,0,10,0,0,0,0,0,0 +16.72,51,0,10,0,0,0,0,0,0 +16.73,51,0,10,0,0,0,0,0,0 +16.74,51,0,10,0,0,0,0,0,0 +16.75,51,0,10,0,0,0,0,0,0 +16.76,51,0,10,0,0,0,0,0,0 +16.77,51,0,10,0,0,0,0,0,0 +16.78,51,0,10,0,0,0,0,0,0 +16.79,51,0,10,0,0,0,0,0,0 +16.8,51,0,10,0,0,0,0,0,0 +16.81,51,0,10,0,0,0,0,0,0 +16.82,51,0,10,0,0,0,0,0,0 +16.83,51,0,10,0,0,0,0,0,0 +16.84,51,0,10,0,0,0,0,0,0 +16.85,51,0,10,0,0,0,0,0,0 +16.86,51,0,10,0,0,0,0,0,0 +16.87,51,0,10,0,0,0,0,0,0 +16.88,51,0,10,0,0,0,0,0,0 +16.89,51,0,10,0,0,0,0,0,0 +16.9,51,0,10,0,0,0,0,0,0 +16.91,51,0,10,0,0,0,0,0,0 +16.92,51,0,10,0,0,0,0,0,0 +16.93,51,0,10,0,0,0,0,0,0 +16.94,51,0,10,0,0,0,0,0,0 +16.95,51,0,10,0,0,0,0,0,0 +16.96,51,0,10,0,0,0,0,0,0 +16.97,51,0,10,0,0,0,0,0,0 +16.98,51,0,10,0,0,0,0,0,0 +16.99,51,0,10,0,0,0,0,0,0 +17,51,0,10,0,0,0,0,0,0 +17.01,51,0,10,0,0,0,0,0,0 +17.02,51,0,10,0,0,0,0,0,0 +17.03,51,0,10,0,0,0,0,0,0 +17.04,51,0,10,0,0,0,0,0,0 +17.05,51,0,10,0,0,0,0,0,0 +17.06,51,0,10,0,0,0,0,0,0 +17.07,51,0,10,0,0,0,0,0,0 +17.08,51,0,10,0,0,0,0,0,0 +17.09,51,0,10,0,0,0,0,0,0 +17.1,51,0,10,0,0,0,0,0,0 +17.11,51,0,10,0,0,0,0,0,0 +17.12,51,0,10,0,0,0,0,0,0 +17.13,51,0,10,0,0,0,0,0,0 +17.14,51,0,10,0,0,0,0,0,0 +17.15,51,0,10,0,0,0,0,0,0 +17.16,51,0,10,0,0,0,0,0,0 +17.17,51,0,10,0,0,0,0,0,0 +17.18,51,0,10,0,0,0,0,0,0 +17.19,51,0,10,0,0,0,0,0,0 +17.2,51,0,10,0,0,0,0,0,0 +17.21,51,0,10,0,0,0,0,0,0 +17.22,51,0,10,0,0,0,0,0,0 +17.23,51,0,10,0,0,0,0,0,0 +17.24,51,0,10,0,0,0,0,0,0 +17.25,51,0,10,0,0,0,0,0,0 +17.26,51,0,10,0,0,0,0,0,0 +17.27,51,0,10,0,0,0,0,0,0 +17.28,51,0,10,0,0,0,0,0,0 +17.29,51,0,10,0,0,0,0,0,0 +17.3,51,0,10,0,0,0,0,0,0 +17.31,51,0,10,0,0,0,0,0,0 +17.32,51,0,10,0,0,0,0,0,0 +17.33,51,0,10,0,0,0,0,0,0 +17.34,51,0,10,0,0,0,0,0,0 +17.35,51,0,10,0,0,0,0,0,0 +17.36,51,0,10,0,0,0,0,0,0 +17.37,51,0,10,0,0,0,0,0,0 +17.38,51,0,10,0,0,0,0,0,0 +17.39,51,0,10,0,0,0,0,0,0 +17.4,51,0,10,0,0,0,0,0,0 +17.41,51,0,10,0,0,0,0,0,0 +17.42,51,0,10,0,0,0,0,0,0 +17.43,51,0,10,0,0,0,0,0,0 +17.44,51,0,10,0,0,0,0,0,0 +17.45,51,0,10,0,0,0,0,0,0 +17.46,51,0,10,0,0,0,0,0,0 +17.47,51,0,10,0,0,0,0,0,0 +17.48,51,0,10,0,0,0,0,0,0 +17.49,51,0,10,0,0,0,0,0,0 +17.5,51,0,10,0,0,0,0,0,0 +17.51,51,0,10,0,0,0,0,0,0 +17.52,51,0,10,0,0,0,0,0,0 +17.53,51,0,10,0,0,0,0,0,0 +17.54,51,0,10,0,0,0,0,0,0 +17.55,51,0,10,0,0,0,0,0,0 +17.56,51,0,10,0,0,0,0,0,0 +17.57,51,0,10,0,0,0,0,0,0 +17.58,51,0,10,0,0,0,0,0,0 +17.59,51,0,10,0,0,0,0,0,0 +17.6,51,0,10,0,0,0,0,0,0 +17.61,51,0,10,0,0,0,0,0,0 +17.62,51,0,10,0,0,0,0,0,0 +17.63,51,0,10,0,0,0,0,0,0 +17.64,51,0,10,0,0,0,0,0,0 +17.65,51,0,10,0,0,0,0,0,0 +17.66,51,0,10,0,0,0,0,0,0 +17.67,51,0,10,0,0,0,0,0,0 +17.68,51,0,10,0,0,0,0,0,0 +17.69,51,0,10,0,0,0,0,0,0 +17.7,51,0,10,0,0,0,0,0,0 +17.71,51,0,10,0,0,0,0,0,0 +17.72,51,0,10,0,0,0,0,0,0 +17.73,51,0,10,0,0,0,0,0,0 +17.74,51,0,10,0,0,0,0,0,0 +17.75,51,0,10,0,0,0,0,0,0 +17.76,51,0,10,0,0,0,0,0,0 +17.77,51,0,10,0,0,0,0,0,0 +17.78,51,0,10,0,0,0,0,0,0 +17.79,51,0,10,0,0,0,0,0,0 +17.8,51,0,10,0,0,0,0,0,0 +17.81,51,0,10,0,0,0,0,0,0 +17.82,51,0,10,0,0,0,0,0,0 +17.83,51,0,10,0,0,0,0,0,0 +17.84,51,0,10,0,0,0,0,0,0 +17.85,51,0,10,0,0,0,0,0,0 +17.86,51,0,10,0,0,0,0,0,0 +17.87,51,0,10,0,0,0,0,0,0 +17.88,51,0,10,0,0,0,0,0,0 +17.89,51,0,10,0,0,0,0,0,0 +17.9,51,0,10,0,0,0,0,0,0 +17.91,51,0,10,0,0,0,0,0,0 +17.92,51,0,10,0,0,0,0,0,0 +17.93,51,0,10,0,0,0,0,0,0 +17.94,51,0,10,0,0,0,0,0,0 +17.95,51,0,10,0,0,0,0,0,0 +17.96,51,0,10,0,0,0,0,0,0 +17.97,51,0,10,0,0,0,0,0,0 +17.98,51,0,10,0,0,0,0,0,0 +17.99,51,0,10,0,0,0,0,0,0 +18,51,0,10,0,0,0,0,0,0 +18.01,51,0,10,0,0,0,0,0,0 +18.02,51,0,10,0,0,0,0,0,0 +18.03,51,0,10,0,0,0,0,0,0 +18.04,51,0,10,0,0,0,0,0,0 +18.05,51,0,10,0,0,0,0,0,0 +18.06,51,0,10,0,0,0,0,0,0 +18.07,51,0,10,0,0,0,0,0,0 +18.08,51,0,10,0,0,0,0,0,0 +18.09,51,0,10,0,0,0,0,0,0 +18.1,51,0,10,0,0,0,0,0,0 +18.11,51,0,10,0,0,0,0,0,0 +18.12,51,0,10,0,0,0,0,0,0 +18.13,51,0,10,0,0,0,0,0,0 +18.14,51,0,10,0,0,0,0,0,0 +18.15,51,0,10,0,0,0,0,0,0 +18.16,51,0,10,0,0,0,0,0,0 +18.17,51,0,10,0,0,0,0,0,0 +18.18,51,0,10,0,0,0,0,0,0 +18.19,51,0,10,0,0,0,0,0,0 +18.2,51,0,10,0,0,0,0,0,0 +18.21,51,0,10,0,0,0,0,0,0 +18.22,51,0,10,0,0,0,0,0,0 +18.23,51,0,10,0,0,0,0,0,0 +18.24,51,0,10,0,0,0,0,0,0 +18.25,51,0,10,0,0,0,0,0,0 +18.26,51,0,10,0,0,0,0,0,0 +18.27,51,0,10,0,0,0,0,0,0 +18.28,51,0,10,0,0,0,0,0,0 +18.29,51,0,10,0,0,0,0,0,0 +18.3,51,0,10,0,0,0,0,0,0 +18.31,51,0,10,0,0,0,0,0,0 +18.32,51,0,10,0,0,0,0,0,0 +18.33,51,0,10,0,0,0,0,0,0 +18.34,51,0,10,0,0,0,0,0,0 +18.35,51,0,10,0,0,0,0,0,0 +18.36,51,0,10,0,0,0,0,0,0 +18.37,51,0,10,0,0,0,0,0,0 +18.38,51,0,10,0,0,0,0,0,0 +18.39,51,0,10,0,0,0,0,0,0 +18.4,51,0,10,0,0,0,0,0,0 +18.41,51,0,10,0,0,0,0,0,0 +18.42,51,0,10,0,0,0,0,0,0 +18.43,51,0,10,0,0,0,0,0,0 +18.44,51,0,10,0,0,0,0,0,0 +18.45,51,0,10,0,0,0,0,0,0 +18.46,51,0,10,0,0,0,0,0,0 +18.47,51,0,10,0,0,0,0,0,0 +18.48,51,0,10,0,0,0,0,0,0 +18.49,51,0,10,0,0,0,0,0,0 +18.5,51,0,10,0,0,0,0,0,0 +18.51,51,0,10,0,0,0,0,0,0 +18.52,51,0,10,0,0,0,0,0,0 +18.53,51,0,10,0,0,0,0,0,0 +18.54,51,0,10,0,0,0,0,0,0 +18.55,51,0,10,0,0,0,0,0,0 +18.56,51,0,10,0,0,0,0,0,0 +18.57,51,0,10,0,0,0,0,0,0 +18.58,51,0,10,0,0,0,0,0,0 +18.59,51,0,10,0,0,0,0,0,0 +18.6,51,0,10,0,0,0,0,0,0 +18.61,51,0,10,0,0,0,0,0,0 +18.62,51,0,10,0,0,0,0,0,0 +18.63,51,0,10,0,0,0,0,0,0 +18.64,51,0,10,0,0,0,0,0,0 +18.65,51,0,10,0,0,0,0,0,0 +18.66,51,0,10,0,0,0,0,0,0 +18.67,51,0,10,0,0,0,0,0,0 +18.68,51,0,10,0,0,0,0,0,0 +18.69,51,0,10,0,0,0,0,0,0 +18.7,51,0,10,0,0,0,0,0,0 +18.71,51,0,10,0,0,0,0,0,0 +18.72,51,0,10,0,0,0,0,0,0 +18.73,51,0,10,0,0,0,0,0,0 +18.74,51,0,10,0,0,0,0,0,0 +18.75,51,0,10,0,0,0,0,0,0 +18.76,51,0,10,0,0,0,0,0,0 +18.77,51,0,10,0,0,0,0,0,0 +18.78,51,0,10,0,0,0,0,0,0 +18.79,51,0,10,0,0,0,0,0,0 +18.8,51,0,10,0,0,0,0,0,0 +18.81,51,0,10,0,0,0,0,0,0 +18.82,51,0,10,0,0,0,0,0,0 +18.83,51,0,10,0,0,0,0,0,0 +18.84,51,0,10,0,0,0,0,0,0 +18.85,51,0,10,0,0,0,0,0,0 +18.86,51,0,10,0,0,0,0,0,0 +18.87,51,0,10,0,0,0,0,0,0 +18.88,51,0,10,0,0,0,0,0,0 +18.89,51,0,10,0,0,0,0,0,0 +18.9,51,0,10,0,0,0,0,0,0 +18.91,51,0,10,0,0,0,0,0,0 +18.92,51,0,10,0,0,0,0,0,0 +18.93,51,0,10,0,0,0,0,0,0 +18.94,51,0,10,0,0,0,0,0,0 +18.95,51,0,10,0,0,0,0,0,0 +18.96,51,0,10,0,0,0,0,0,0 +18.97,51,0,10,0,0,0,0,0,0 +18.98,51,0,10,0,0,0,0,0,0 +18.99,51,0,10,0,0,0,0,0,0 +19,51,0,10,0,0,0,0,0,0 +19.01,51,0,10,0,0,0,0,0,0 +19.02,51,0,10,0,0,0,0,0,0 +19.03,51,0,10,0,0,0,0,0,0 +19.04,51,0,10,0,0,0,0,0,0 +19.05,51,0,10,0,0,0,0,0,0 +19.06,51,0,10,0,0,0,0,0,0 +19.07,51,0,10,0,0,0,0,0,0 +19.08,51,0,10,0,0,0,0,0,0 +19.09,51,0,10,0,0,0,0,0,0 +19.1,51,0,10,0,0,0,0,0,0 +19.11,51,0,10,0,0,0,0,0,0 +19.12,51,0,10,0,0,0,0,0,0 +19.13,51,0,10,0,0,0,0,0,0 +19.14,51,0,10,0,0,0,0,0,0 +19.15,51,0,10,0,0,0,0,0,0 +19.16,51,0,10,0,0,0,0,0,0 +19.17,51,0,10,0,0,0,0,0,0 +19.18,51,0,10,0,0,0,0,0,0 +19.19,51,0,10,0,0,0,0,0,0 +19.2,51,0,10,0,0,0,0,0,0 +19.21,51,0,10,0,0,0,0,0,0 +19.22,51,0,10,0,0,0,0,0,0 +19.23,51,0,10,0,0,0,0,0,0 +19.24,51,0,10,0,0,0,0,0,0 +19.25,51,0,10,0,0,0,0,0,0 +19.26,51,0,10,0,0,0,0,0,0 +19.27,51,0,10,0,0,0,0,0,0 +19.28,51,0,10,0,0,0,0,0,0 +19.29,51,0,10,0,0,0,0,0,0 +19.3,51,0,10,0,0,0,0,0,0 +19.31,51,0,10,0,0,0,0,0,0 +19.32,51,0,10,0,0,0,0,0,0 +19.33,51,0,10,0,0,0,0,0,0 +19.34,51,0,10,0,0,0,0,0,0 +19.35,51,0,10,0,0,0,0,0,0 +19.36,51,0,10,0,0,0,0,0,0 +19.37,51,0,10,0,0,0,0,0,0 +19.38,51,0,10,0,0,0,0,0,0 +19.39,51,0,10,0,0,0,0,0,0 +19.4,51,0,10,0,0,0,0,0,0 +19.41,51,0,10,0,0,0,0,0,0 +19.42,51,0,10,0,0,0,0,0,0 +19.43,51,0,10,0,0,0,0,0,0 +19.44,51,0,10,0,0,0,0,0,0 +19.45,51,0,10,0,0,0,0,0,0 +19.46,51,0,10,0,0,0,0,0,0 +19.47,51,0,10,0,0,0,0,0,0 +19.48,51,0,10,0,0,0,0,0,0 +19.49,51,0,10,0,0,0,0,0,0 +19.5,51,0,10,0,0,0,0,0,0 +19.51,51,0,10,0,0,0,0,0,0 +19.52,51,0,10,0,0,0,0,0,0 +19.53,51,0,10,0,0,0,0,0,0 +19.54,51,0,10,0,0,0,0,0,0 +19.55,51,0,10,0,0,0,0,0,0 +19.56,51,0,10,0,0,0,0,0,0 +19.57,51,0,10,0,0,0,0,0,0 +19.58,51,0,10,0,0,0,0,0,0 +19.59,51,0,10,0,0,0,0,0,0 +19.6,51,0,10,0,0,0,0,0,0 +19.61,51,0,10,0,0,0,0,0,0 +19.62,51,0,10,0,0,0,0,0,0 +19.63,51,0,10,0,0,0,0,0,0 +19.64,51,0,10,0,0,0,0,0,0 +19.65,51,0,10,0,0,0,0,0,0 +19.66,51,0,10,0,0,0,0,0,0 +19.67,51,0,10,0,0,0,0,0,0 +19.68,51,0,10,0,0,0,0,0,0 +19.69,51,0,10,0,0,0,0,0,0 +19.7,51,0,10,0,0,0,0,0,0 +19.71,51,0,10,0,0,0,0,0,0 +19.72,51,0,10,0,0,0,0,0,0 +19.73,51,0,10,0,0,0,0,0,0 +19.74,51,0,10,0,0,0,0,0,0 +19.75,51,0,10,0,0,0,0,0,0 +19.76,51,0,10,0,0,0,0,0,0 +19.77,51,0,10,0,0,0,0,0,0 +19.78,51,0,10,0,0,0,0,0,0 +19.79,51,0,10,0,0,0,0,0,0 +19.8,51,0,10,0,0,0,0,0,0 +19.81,51,0,10,0,0,0,0,0,0 +19.82,51,0,10,0,0,0,0,0,0 +19.83,51,0,10,0,0,0,0,0,0 +19.84,51,0,10,0,0,0,0,0,0 +19.85,51,0,10,0,0,0,0,0,0 +19.86,51,0,10,0,0,0,0,0,0 +19.87,51,0,10,0,0,0,0,0,0 +19.88,51,0,10,0,0,0,0,0,0 +19.89,51,0,10,0,0,0,0,0,0 +19.9,51,0,10,0,0,0,0,0,0 +19.91,51,0,10,0,0,0,0,0,0 +19.92,51,0,10,0,0,0,0,0,0 +19.93,51,0,10,0,0,0,0,0,0 +19.94,51,0,10,0,0,0,0,0,0 +19.95,51,0,10,0,0,0,0,0,0 +19.96,51,0,10,0,0,0,0,0,0 +19.97,51,0,10,0,0,0,0,0,0 +19.98,51,0,10,0,0,0,0,0,0 +19.99,51,0,10,0,0,0,0,0,0 +20,51,0,10,0,0,0,0,0,0 +20.01,51,0,10,0,0,0,0,0,0 +20.02,51,0,10,0,0,0,0,0,0 +20.03,51,0,10,0,0,0,0,0,0 +20.04,51,0,10,0,0,0,0,0,0 +20.05,51,0,10,0,0,0,0,0,0 +20.06,51,0,10,0,0,0,0,0,0 +20.07,51,0,10,0,0,0,0,0,0 +20.08,51,0,10,0,0,0,0,0,0 +20.09,51,0,10,0,0,0,0,0,0 +20.1,51,0,10,0,0,0,0,0,0 +20.11,51,0,10,0,0,0,0,0,0 +20.12,51,0,10,0,0,0,0,0,0 +20.13,51,0,10,0,0,0,0,0,0 +20.14,51,0,10,0,0,0,0,0,0 +20.15,51,0,10,0,0,0,0,0,0 +20.16,51,0,10,0,0,0,0,0,0 +20.17,51,0,10,0,0,0,0,0,0 +20.18,51,0,10,0,0,0,0,0,0 +20.19,51,0,10,0,0,0,0,0,0 +20.2,51,0,10,0,0,0,0,0,0 +20.21,51,0,10,0,0,0,0,0,0 +20.22,51,0,10,0,0,0,0,0,0 +20.23,51,0,10,0,0,0,0,0,0 +20.24,51,0,10,0,0,0,0,0,0 +20.25,51,0,10,0,0,0,0,0,0 +20.26,51,0,10,0,0,0,0,0,0 +20.27,51,0,10,0,0,0,0,0,0 +20.28,51,0,10,0,0,0,0,0,0 +20.29,51,0,10,0,0,0,0,0,0 +20.3,51,0,10,0,0,0,0,0,0 +20.31,51,0,10,0,0,0,0,0,0 +20.32,51,0,10,0,0,0,0,0,0 +20.33,51,0,10,0,0,0,0,0,0 +20.34,51,0,10,0,0,0,0,0,0 +20.35,51,0,10,0,0,0,0,0,0 +20.36,51,0,10,0,0,0,0,0,0 +20.37,51,0,10,0,0,0,0,0,0 +20.38,51,0,10,0,0,0,0,0,0 +20.39,51,0,10,0,0,0,0,0,0 +20.4,51,0,10,0,0,0,0,0,0 +20.41,51,0,10,0,0,0,0,0,0 +20.42,51,0,10,0,0,0,0,0,0 +20.43,51,0,10,0,0,0,0,0,0 +20.44,51,0,10,0,0,0,0,0,0 +20.45,51,0,10,0,0,0,0,0,0 +20.46,51,0,10,0,0,0,0,0,0 +20.47,51,0,10,0,0,0,0,0,0 +20.48,51,0,10,0,0,0,0,0,0 +20.49,51,0,10,0,0,0,0,0,0 +20.5,51,0,10,0,0,0,0,0,0 +20.51,51,0,10,0,0,0,0,0,0 +20.52,51,0,10,0,0,0,0,0,0 +20.53,51,0,10,0,0,0,0,0,0 +20.54,51,0,10,0,0,0,0,0,0 +20.55,51,0,10,0,0,0,0,0,0 +20.56,51,0,10,0,0,0,0,0,0 +20.57,51,0,10,0,0,0,0,0,0 +20.58,51,0,10,0,0,0,0,0,0 +20.59,51,0,10,0,0,0,0,0,0 +20.6,51,0,10,0,0,0,0,0,0 +20.61,51,0,10,0,0,0,0,0,0 +20.62,51,0,10,0,0,0,0,0,0 +20.63,51,0,10,0,0,0,0,0,0 +20.64,51,0,10,0,0,0,0,0,0 +20.65,51,0,10,0,0,0,0,0,0 +20.66,51,0,10,0,0,0,0,0,0 +20.67,51,0,10,0,0,0,0,0,0 +20.68,51,0,10,0,0,0,0,0,0 +20.69,51,0,10,0,0,0,0,0,0 +20.7,51,0,10,0,0,0,0,0,0 +20.71,51,0,10,0,0,0,0,0,0 +20.72,51,0,10,0,0,0,0,0,0 +20.73,51,0,10,0,0,0,0,0,0 +20.74,51,0,10,0,0,0,0,0,0 +20.75,51,0,10,0,0,0,0,0,0 +20.76,51,0,10,0,0,0,0,0,0 +20.77,51,0,10,0,0,0,0,0,0 +20.78,51,0,10,0,0,0,0,0,0 +20.79,51,0,10,0,0,0,0,0,0 +20.8,51,0,10,0,0,0,0,0,0 +20.81,51,0,10,0,0,0,0,0,0 +20.82,51,0,10,0,0,0,0,0,0 +20.83,51,0,10,0,0,0,0,0,0 +20.84,51,0,10,0,0,0,0,0,0 +20.85,51,0,10,0,0,0,0,0,0 +20.86,51,0,10,0,0,0,0,0,0 +20.87,51,0,10,0,0,0,0,0,0 +20.88,51,0,10,0,0,0,0,0,0 +20.89,51,0,10,0,0,0,0,0,0 +20.9,51,0,10,0,0,0,0,0,0 +20.91,51,0,10,0,0,0,0,0,0 +20.92,51,0,10,0,0,0,0,0,0 +20.93,51,0,10,0,0,0,0,0,0 +20.94,51,0,10,0,0,0,0,0,0 +20.95,51,0,10,0,0,0,0,0,0 +20.96,51,0,10,0,0,0,0,0,0 +20.97,51,0,10,0,0,0,0,0,0 +20.98,51,0,10,0,0,0,0,0,0 +20.99,51,0,10,0,0,0,0,0,0 +21,51,0,10,0,0,0,0,0,0 +21.01,51,0,10,0,0,0,0,0,0 +21.02,51,0,10,0,0,0,0,0,0 +21.03,51,0,10,0,0,0,0,0,0 +21.04,51,0,10,0,0,0,0,0,0 +21.05,51,0,10,0,0,0,0,0,0 +21.06,51,0,10,0,0,0,0,0,0 +21.07,51,0,10,0,0,0,0,0,0 +21.08,51,0,10,0,0,0,0,0,0 +21.09,51,0,10,0,0,0,0,0,0 +21.1,51,0,10,0,0,0,0,0,0 +21.11,51,0,10,0,0,0,0,0,0 +21.12,51,0,10,0,0,0,0,0,0 +21.13,51,0,10,0,0,0,0,0,0 +21.14,51,0,10,0,0,0,0,0,0 +21.15,51,0,10,0,0,0,0,0,0 +21.16,51,0,10,0,0,0,0,0,0 +21.17,51,0,10,0,0,0,0,0,0 +21.18,51,0,10,0,0,0,0,0,0 +21.19,51,0,10,0,0,0,0,0,0 +21.2,51,0,10,0,0,0,0,0,0 +21.21,51,0,10,0,0,0,0,0,0 +21.22,51,0,10,0,0,0,0,0,0 +21.23,51,0,10,0,0,0,0,0,0 +21.24,51,0,10,0,0,0,0,0,0 +21.25,51,0,10,0,0,0,0,0,0 +21.26,51,0,10,0,0,0,0,0,0 +21.27,51,0,10,0,0,0,0,0,0 +21.28,51,0,10,0,0,0,0,0,0 +21.29,51,0,10,0,0,0,0,0,0 +21.3,51,0,10,0,0,0,0,0,0 +21.31,51,0,10,0,0,0,0,0,0 +21.32,51,0,10,0,0,0,0,0,0 +21.33,51,0,10,0,0,0,0,0,0 +21.34,51,0,10,0,0,0,0,0,0 +21.35,51,0,10,0,0,0,0,0,0 +21.36,51,0,10,0,0,0,0,0,0 +21.37,51,0,10,0,0,0,0,0,0 +21.38,51,0,10,0,0,0,0,0,0 +21.39,51,0,10,0,0,0,0,0,0 +21.4,51,0,10,0,0,0,0,0,0 +21.41,51,0,10,0,0,0,0,0,0 +21.42,51,0,10,0,0,0,0,0,0 +21.43,51,0,10,0,0,0,0,0,0 +21.44,51,0,10,0,0,0,0,0,0 +21.45,51,0,10,0,0,0,0,0,0 +21.46,51,0,10,0,0,0,0,0,0 +21.47,51,0,10,0,0,0,0,0,0 +21.48,51,0,10,0,0,0,0,0,0 +21.49,51,0,10,0,0,0,0,0,0 +21.5,51,0,10,0,0,0,0,0,0 +21.51,51,0,10,0,0,0,0,0,0 +21.52,51,0,10,0,0,0,0,0,0 +21.53,51,0,10,0,0,0,0,0,0 +21.54,51,0,10,0,0,0,0,0,0 +21.55,51,0,10,0,0,0,0,0,0 +21.56,51,0,10,0,0,0,0,0,0 +21.57,51,0,10,0,0,0,0,0,0 +21.58,51,0,10,0,0,0,0,0,0 +21.59,51,0,10,0,0,0,0,0,0 +21.6,51,0,10,0,0,0,0,0,0 +21.61,51,0,10,0,0,0,0,0,0 +21.62,51,0,10,0,0,0,0,0,0 +21.63,51,0,10,0,0,0,0,0,0 +21.64,51,0,10,0,0,0,0,0,0 +21.65,51,0,10,0,0,0,0,0,0 +21.66,51,0,10,0,0,0,0,0,0 +21.67,51,0,10,0,0,0,0,0,0 +21.68,51,0,10,0,0,0,0,0,0 +21.69,51,0,10,0,0,0,0,0,0 +21.7,51,0,10,0,0,0,0,0,0 +21.71,51,0,10,0,0,0,0,0,0 +21.72,51,0,10,0,0,0,0,0,0 +21.73,51,0,10,0,0,0,0,0,0 +21.74,51,0,10,0,0,0,0,0,0 +21.75,51,0,10,0,0,0,0,0,0 +21.76,51,0,10,0,0,0,0,0,0 +21.77,51,0,10,0,0,0,0,0,0 +21.78,51,0,10,0,0,0,0,0,0 +21.79,51,0,10,0,0,0,0,0,0 +21.8,51,0,10,0,0,0,0,0,0 +21.81,51,0,10,0,0,0,0,0,0 +21.82,51,0,10,0,0,0,0,0,0 +21.83,51,0,10,0,0,0,0,0,0 +21.84,51,0,10,0,0,0,0,0,0 +21.85,51,0,10,0,0,0,0,0,0 +21.86,51,0,10,0,0,0,0,0,0 +21.87,51,0,10,0,0,0,0,0,0 +21.88,51,0,10,0,0,0,0,0,0 +21.89,51,0,10,0,0,0,0,0,0 +21.9,51,0,10,0,0,0,0,0,0 +21.91,51,0,10,0,0,0,0,0,0 +21.92,51,0,10,0,0,0,0,0,0 +21.93,51,0,10,0,0,0,0,0,0 +21.94,51,0,10,0,0,0,0,0,0 +21.95,51,0,10,0,0,0,0,0,0 +21.96,51,0,10,0,0,0,0,0,0 +21.97,51,0,10,0,0,0,0,0,0 +21.98,51,0,10,0,0,0,0,0,0 +21.99,51,0,10,0,0,0,0,0,0 +22,51,0,10,0,0,0,0,0,0 +22.01,51,0,10,0,0,0,0,0,0 +22.02,51,0,10,0,0,0,0,0,0 +22.03,51,0,10,0,0,0,0,0,0 +22.04,51,0,10,0,0,0,0,0,0 +22.05,51,0,10,0,0,0,0,0,0 +22.06,51,0,10,0,0,0,0,0,0 +22.07,51,0,10,0,0,0,0,0,0 +22.08,51,0,10,0,0,0,0,0,0 +22.09,51,0,10,0,0,0,0,0,0 +22.1,51,0,10,0,0,0,0,0,0 +22.11,51,0,10,0,0,0,0,0,0 +22.12,51,0,10,0,0,0,0,0,0 +22.13,51,0,10,0,0,0,0,0,0 +22.14,51,0,10,0,0,0,0,0,0 +22.15,51,0,10,0,0,0,0,0,0 +22.16,51,0,10,0,0,0,0,0,0 +22.17,51,0,10,0,0,0,0,0,0 +22.18,51,0,10,0,0,0,0,0,0 +22.19,51,0,10,0,0,0,0,0,0 +22.2,51,0,10,0,0,0,0,0,0 +22.21,51,0,10,0,0,0,0,0,0 +22.22,51,0,10,0,0,0,0,0,0 +22.23,51,0,10,0,0,0,0,0,0 +22.24,51,0,10,0,0,0,0,0,0 +22.25,51,0,10,0,0,0,0,0,0 +22.26,51,0,10,0,0,0,0,0,0 +22.27,51,0,10,0,0,0,0,0,0 +22.28,51,0,10,0,0,0,0,0,0 +22.29,51,0,10,0,0,0,0,0,0 +22.3,51,0,10,0,0,0,0,0,0 +22.31,51,0,10,0,0,0,0,0,0 +22.32,51,0,10,0,0,0,0,0,0 +22.33,51,0,10,0,0,0,0,0,0 +22.34,51,0,10,0,0,0,0,0,0 +22.35,51,0,10,0,0,0,0,0,0 +22.36,51,0,10,0,0,0,0,0,0 +22.37,51,0,10,0,0,0,0,0,0 +22.38,51,0,10,0,0,0,0,0,0 +22.39,51,0,10,0,0,0,0,0,0 +22.4,51,0,10,0,0,0,0,0,0 +22.41,51,0,10,0,0,0,0,0,0 +22.42,51,0,10,0,0,0,0,0,0 +22.43,51,0,10,0,0,0,0,0,0 +22.44,51,0,10,0,0,0,0,0,0 +22.45,51,0,10,0,0,0,0,0,0 +22.46,51,0,10,0,0,0,0,0,0 +22.47,51,0,10,0,0,0,0,0,0 +22.48,51,0,10,0,0,0,0,0,0 +22.49,51,0,10,0,0,0,0,0,0 +22.5,51,0,10,0,0,0,0,0,0 +22.51,51,0,10,0,0,0,0,0,0 +22.52,51,0,10,0,0,0,0,0,0 +22.53,51,0,10,0,0,0,0,0,0 +22.54,51,0,10,0,0,0,0,0,0 +22.55,51,0,10,0,0,0,0,0,0 +22.56,51,0,10,0,0,0,0,0,0 +22.57,51,0,10,0,0,0,0,0,0 +22.58,51,0,10,0,0,0,0,0,0 +22.59,51,0,10,0,0,0,0,0,0 +22.6,51,0,10,0,0,0,0,0,0 +22.61,51,0,10,0,0,0,0,0,0 +22.62,51,0,10,0,0,0,0,0,0 +22.63,51,0,10,0,0,0,0,0,0 +22.64,51,0,10,0,0,0,0,0,0 +22.65,51,0,10,0,0,0,0,0,0 +22.66,51,0,10,0,0,0,0,0,0 +22.67,51,0,10,0,0,0,0,0,0 +22.68,51,0,10,0,0,0,0,0,0 +22.69,51,0,10,0,0,0,0,0,0 +22.7,51,0,10,0,0,0,0,0,0 +22.71,51,0,10,0,0,0,0,0,0 +22.72,51,0,10,0,0,0,0,0,0 +22.73,51,0,10,0,0,0,0,0,0 +22.74,51,0,10,0,0,0,0,0,0 +22.75,51,0,10,0,0,0,0,0,0 +22.76,51,0,10,0,0,0,0,0,0 +22.77,51,0,10,0,0,0,0,0,0 +22.78,51,0,10,0,0,0,0,0,0 +22.79,51,0,10,0,0,0,0,0,0 +22.8,51,0,10,0,0,0,0,0,0 +22.81,51,0,10,0,0,0,0,0,0 +22.82,51,0,10,0,0,0,0,0,0 +22.83,51,0,10,0,0,0,0,0,0 +22.84,51,0,10,0,0,0,0,0,0 +22.85,51,0,10,0,0,0,0,0,0 +22.86,51,0,10,0,0,0,0,0,0 +22.87,51,0,10,0,0,0,0,0,0 +22.88,51,0,10,0,0,0,0,0,0 +22.89,51,0,10,0,0,0,0,0,0 +22.9,51,0,10,0,0,0,0,0,0 +22.91,51,0,10,0,0,0,0,0,0 +22.92,51,0,10,0,0,0,0,0,0 +22.93,51,0,10,0,0,0,0,0,0 +22.94,51,0,10,0,0,0,0,0,0 +22.95,51,0,10,0,0,0,0,0,0 +22.96,51,0,10,0,0,0,0,0,0 +22.97,51,0,10,0,0,0,0,0,0 +22.98,51,0,10,0,0,0,0,0,0 +22.99,51,0,10,0,0,0,0,0,0 +23,51,0,10,0,0,0,0,0,0 +23.01,51,0,10,0,0,0,0,0,0 +23.02,51,0,10,0,0,0,0,0,0 +23.03,51,0,10,0,0,0,0,0,0 +23.04,51,0,10,0,0,0,0,0,0 +23.05,51,0,10,0,0,0,0,0,0 +23.06,51,0,10,0,0,0,0,0,0 +23.07,51,0,10,0,0,0,0,0,0 +23.08,51,0,10,0,0,0,0,0,0 +23.09,51,0,10,0,0,0,0,0,0 +23.1,51,0,10,0,0,0,0,0,0 +23.11,51,0,10,0,0,0,0,0,0 +23.12,51,0,10,0,0,0,0,0,0 +23.13,51,0,10,0,0,0,0,0,0 +23.14,51,0,10,0,0,0,0,0,0 +23.15,51,0,10,0,0,0,0,0,0 +23.16,51,0,10,0,0,0,0,0,0 +23.17,51,0,10,0,0,0,0,0,0 +23.18,51,0,10,0,0,0,0,0,0 +23.19,51,0,10,0,0,0,0,0,0 +23.2,51,0,10,0,0,0,0,0,0 +23.21,51,0,10,0,0,0,0,0,0 +23.22,51,0,10,0,0,0,0,0,0 +23.23,51,0,10,0,0,0,0,0,0 +23.24,51,0,10,0,0,0,0,0,0 +23.25,51,0,10,0,0,0,0,0,0 +23.26,51,0,10,0,0,0,0,0,0 +23.27,51,0,10,0,0,0,0,0,0 +23.28,51,0,10,0,0,0,0,0,0 +23.29,51,0,10,0,0,0,0,0,0 +23.3,51,0,10,0,0,0,0,0,0 +23.31,51,0,10,0,0,0,0,0,0 +23.32,51,0,10,0,0,0,0,0,0 +23.33,51,0,10,0,0,0,0,0,0 +23.34,51,0,10,0,0,0,0,0,0 +23.35,51,0,10,0,0,0,0,0,0 +23.36,51,0,10,0,0,0,0,0,0 +23.37,51,0,10,0,0,0,0,0,0 +23.38,51,0,10,0,0,0,0,0,0 +23.39,51,0,10,0,0,0,0,0,0 +23.4,51,0,10,0,0,0,0,0,0 +23.41,51,0,10,0,0,0,0,0,0 +23.42,51,0,10,0,0,0,0,0,0 +23.43,51,0,10,0,0,0,0,0,0 +23.44,51,0,10,0,0,0,0,0,0 +23.45,51,0,10,0,0,0,0,0,0 +23.46,51,0,10,0,0,0,0,0,0 +23.47,51,0,10,0,0,0,0,0,0 +23.48,51,0,10,0,0,0,0,0,0 +23.49,51,0,10,0,0,0,0,0,0 +23.5,51,0,10,0,0,0,0,0,0 +23.51,51,0,10,0,0,0,0,0,0 +23.52,51,0,10,0,0,0,0,0,0 +23.53,51,0,10,0,0,0,0,0,0 +23.54,51,0,10,0,0,0,0,0,0 +23.55,51,0,10,0,0,0,0,0,0 +23.56,51,0,10,0,0,0,0,0,0 +23.57,51,0,10,0,0,0,0,0,0 +23.58,51,0,10,0,0,0,0,0,0 +23.59,51,0,10,0,0,0,0,0,0 +23.6,51,0,10,0,0,0,0,0,0 +23.61,51,0,10,0,0,0,0,0,0 +23.62,51,0,10,0,0,0,0,0,0 +23.63,51,0,10,0,0,0,0,0,0 +23.64,51,0,10,0,0,0,0,0,0 +23.65,51,0,10,0,0,0,0,0,0 +23.66,51,0,10,0,0,0,0,0,0 +23.67,51,0,10,0,0,0,0,0,0 +23.68,51,0,10,0,0,0,0,0,0 +23.69,51,0,10,0,0,0,0,0,0 +23.7,51,0,10,0,0,0,0,0,0 +23.71,51,0,10,0,0,0,0,0,0 +23.72,51,0,10,0,0,0,0,0,0 +23.73,51,0,10,0,0,0,0,0,0 +23.74,51,0,10,0,0,0,0,0,0 +23.75,51,0,10,0,0,0,0,0,0 +23.76,51,0,10,0,0,0,0,0,0 +23.77,51,0,10,0,0,0,0,0,0 +23.78,51,0,10,0,0,0,0,0,0 +23.79,51,0,10,0,0,0,0,0,0 +23.8,51,0,10,0,0,0,0,0,0 +23.81,51,0,10,0,0,0,0,0,0 +23.82,51,0,10,0,0,0,0,0,0 +23.83,51,0,10,0,0,0,0,0,0 +23.84,51,0,10,0,0,0,0,0,0 +23.85,51,0,10,0,0,0,0,0,0 +23.86,51,0,10,0,0,0,0,0,0 +23.87,51,0,10,0,0,0,0,0,0 +23.88,51,0,10,0,0,0,0,0,0 +23.89,51,0,10,0,0,0,0,0,0 +23.9,51,0,10,0,0,0,0,0,0 +23.91,51,0,10,0,0,0,0,0,0 +23.92,51,0,10,0,0,0,0,0,0 +23.93,51,0,10,0,0,0,0,0,0 +23.94,51,0,10,0,0,0,0,0,0 +23.95,51,0,10,0,0,0,0,0,0 +23.96,51,0,10,0,0,0,0,0,0 +23.97,51,0,10,0,0,0,0,0,0 +23.98,51,0,10,0,0,0,0,0,0 +23.99,51,0,10,0,0,0,0,0,0 +24,51,0,10,0,0,0,0,0,0 +24.01,51,0,10,0,0,0,0,0,0 +24.02,51,0,10,0,0,0,0,0,0 +24.03,51,0,10,0,0,0,0,0,0 +24.04,51,0,10,0,0,0,0,0,0 +24.05,51,0,10,0,0,0,0,0,0 +24.06,51,0,10,0,0,0,0,0,0 +24.07,51,0,10,0,0,0,0,0,0 +24.08,51,0,10,0,0,0,0,0,0 +24.09,51,0,10,0,0,0,0,0,0 +24.1,51,0,10,0,0,0,0,0,0 +24.11,51,0,10,0,0,0,0,0,0 +24.12,51,0,10,0,0,0,0,0,0 +24.13,51,0,10,0,0,0,0,0,0 +24.14,51,0,10,0,0,0,0,0,0 +24.15,51,0,10,0,0,0,0,0,0 +24.16,51,0,10,0,0,0,0,0,0 +24.17,51,0,10,0,0,0,0,0,0 +24.18,51,0,10,0,0,0,0,0,0 +24.19,51,0,10,0,0,0,0,0,0 +24.2,51,0,10,0,0,0,0,0,0 +24.21,51,0,10,0,0,0,0,0,0 +24.22,51,0,10,0,0,0,0,0,0 +24.23,51,0,10,0,0,0,0,0,0 +24.24,51,0,10,0,0,0,0,0,0 +24.25,51,0,10,0,0,0,0,0,0 +24.26,51,0,10,0,0,0,0,0,0 +24.27,51,0,10,0,0,0,0,0,0 +24.28,51,0,10,0,0,0,0,0,0 +24.29,51,0,10,0,0,0,0,0,0 +24.3,51,0,10,0,0,0,0,0,0 +24.31,51,0,10,0,0,0,0,0,0 +24.32,51,0,10,0,0,0,0,0,0 +24.33,51,0,10,0,0,0,0,0,0 +24.34,51,0,10,0,0,0,0,0,0 +24.35,51,0,10,0,0,0,0,0,0 +24.36,51,0,10,0,0,0,0,0,0 +24.37,51,0,10,0,0,0,0,0,0 +24.38,51,0,10,0,0,0,0,0,0 +24.39,51,0,10,0,0,0,0,0,0 +24.4,51,0,10,0,0,0,0,0,0 +24.41,51,0,10,0,0,0,0,0,0 +24.42,51,0,10,0,0,0,0,0,0 +24.43,51,0,10,0,0,0,0,0,0 +24.44,51,0,10,0,0,0,0,0,0 +24.45,51,0,10,0,0,0,0,0,0 +24.46,51,0,10,0,0,0,0,0,0 +24.47,51,0,10,0,0,0,0,0,0 +24.48,51,0,10,0,0,0,0,0,0 +24.49,51,0,10,0,0,0,0,0,0 +24.5,51,0,10,0,0,0,0,0,0 +24.51,51,0,10,0,0,0,0,0,0 +24.52,51,0,10,0,0,0,0,0,0 +24.53,51,0,10,0,0,0,0,0,0 +24.54,51,0,10,0,0,0,0,0,0 +24.55,51,0,10,0,0,0,0,0,0 +24.56,51,0,10,0,0,0,0,0,0 +24.57,51,0,10,0,0,0,0,0,0 +24.58,51,0,10,0,0,0,0,0,0 +24.59,51,0,10,0,0,0,0,0,0 +24.6,51,0,10,0,0,0,0,0,0 +24.61,51,0,10,0,0,0,0,0,0 +24.62,51,0,10,0,0,0,0,0,0 +24.63,51,0,10,0,0,0,0,0,0 +24.64,51,0,10,0,0,0,0,0,0 +24.65,51,0,10,0,0,0,0,0,0 +24.66,51,0,10,0,0,0,0,0,0 +24.67,51,0,10,0,0,0,0,0,0 +24.68,51,0,10,0,0,0,0,0,0 +24.69,51,0,10,0,0,0,0,0,0 +24.7,51,0,10,0,0,0,0,0,0 +24.71,51,0,10,0,0,0,0,0,0 +24.72,51,0,10,0,0,0,0,0,0 +24.73,51,0,10,0,0,0,0,0,0 +24.74,51,0,10,0,0,0,0,0,0 +24.75,51,0,10,0,0,0,0,0,0 +24.76,51,0,10,0,0,0,0,0,0 +24.77,51,0,10,0,0,0,0,0,0 +24.78,51,0,10,0,0,0,0,0,0 +24.79,51,0,10,0,0,0,0,0,0 +24.8,51,0,10,0,0,0,0,0,0 +24.81,51,0,10,0,0,0,0,0,0 +24.82,51,0,10,0,0,0,0,0,0 +24.83,51,0,10,0,0,0,0,0,0 +24.84,51,0,10,0,0,0,0,0,0 +24.85,51,0,10,0,0,0,0,0,0 +24.86,51,0,10,0,0,0,0,0,0 +24.87,51,0,10,0,0,0,0,0,0 +24.88,51,0,10,0,0,0,0,0,0 +24.89,51,0,10,0,0,0,0,0,0 +24.9,51,0,10,0,0,0,0,0,0 +24.91,51,0,10,0,0,0,0,0,0 +24.92,51,0,10,0,0,0,0,0,0 +24.93,51,0,10,0,0,0,0,0,0 +24.94,51,0,10,0,0,0,0,0,0 +24.95,51,0,10,0,0,0,0,0,0 +24.96,51,0,10,0,0,0,0,0,0 +24.97,51,0,10,0,0,0,0,0,0 +24.98,51,0,10,0,0,0,0,0,0 +24.99,51,0,10,0,0,0,0,0,0 +25,51,0,10,0,0,0,0,0,0 +25.01,51,0,10,0,0,0,0,0,0 +25.02,51,0,10,0,0,0,0,0,0 +25.03,51,0,10,0,0,0,0,0,0 +25.04,51,0,10,0,0,0,0,0,0 +25.05,51,0,10,0,0,0,0,0,0 +25.06,51,0,10,0,0,0,0,0,0 +25.07,51,0,10,0,0,0,0,0,0 +25.08,51,0,10,0,0,0,0,0,0 +25.09,51,0,10,0,0,0,0,0,0 +25.1,51,0,10,0,0,0,0,0,0 +25.11,51,0,10,0,0,0,0,0,0 +25.12,51,0,10,0,0,0,0,0,0 +25.13,51,0,10,0,0,0,0,0,0 +25.14,51,0,10,0,0,0,0,0,0 +25.15,51,0,10,0,0,0,0,0,0 +25.16,51,0,10,0,0,0,0,0,0 +25.17,51,0,10,0,0,0,0,0,0 +25.18,51,0,10,0,0,0,0,0,0 +25.19,51,0,10,0,0,0,0,0,0 +25.2,51,0,10,0,0,0,0,0,0 +25.21,51,0,10,0,0,0,0,0,0 +25.22,51,0,10,0,0,0,0,0,0 +25.23,51,0,10,0,0,0,0,0,0 +25.24,51,0,10,0,0,0,0,0,0 +25.25,51,0,10,0,0,0,0,0,0 +25.26,51,0,10,0,0,0,0,0,0 +25.27,51,0,10,0,0,0,0,0,0 +25.28,51,0,10,0,0,0,0,0,0 +25.29,51,0,10,0,0,0,0,0,0 +25.3,51,0,10,0,0,0,0,0,0 +25.31,51,0,10,0,0,0,0,0,0 +25.32,51,0,10,0,0,0,0,0,0 +25.33,51,0,10,0,0,0,0,0,0 +25.34,51,0,10,0,0,0,0,0,0 +25.35,51,0,10,0,0,0,0,0,0 +25.36,51,0,10,0,0,0,0,0,0 +25.37,51,0,10,0,0,0,0,0,0 +25.38,51,0,10,0,0,0,0,0,0 +25.39,51,0,10,0,0,0,0,0,0 +25.4,51,0,10,0,0,0,0,0,0 +25.41,51,0,10,0,0,0,0,0,0 +25.42,51,0,10,0,0,0,0,0,0 +25.43,51,0,10,0,0,0,0,0,0 +25.44,51,0,10,0,0,0,0,0,0 +25.45,51,0,10,0,0,0,0,0,0 +25.46,51,0,10,0,0,0,0,0,0 +25.47,51,0,10,0,0,0,0,0,0 +25.48,51,0,10,0,0,0,0,0,0 +25.49,51,0,10,0,0,0,0,0,0 +25.5,51,0,10,0,0,0,0,0,0 +25.51,51,0,10,0,0,0,0,0,0 +25.52,51,0,10,0,0,0,0,0,0 +25.53,51,0,10,0,0,0,0,0,0 +25.54,51,0,10,0,0,0,0,0,0 +25.55,51,0,10,0,0,0,0,0,0 +25.56,51,0,10,0,0,0,0,0,0 +25.57,51,0,10,0,0,0,0,0,0 +25.58,51,0,10,0,0,0,0,0,0 +25.59,51,0,10,0,0,0,0,0,0 +25.6,51,0,10,0,0,0,0,0,0 +25.61,51,0,10,0,0,0,0,0,0 +25.62,51,0,10,0,0,0,0,0,0 +25.63,51,0,10,0,0,0,0,0,0 +25.64,51,0,10,0,0,0,0,0,0 +25.65,51,0,10,0,0,0,0,0,0 +25.66,51,0,10,0,0,0,0,0,0 +25.67,51,0,10,0,0,0,0,0,0 +25.68,51,0,10,0,0,0,0,0,0 +25.69,51,0,10,0,0,0,0,0,0 +25.7,51,0,10,0,0,0,0,0,0 +25.71,51,0,10,0,0,0,0,0,0 +25.72,51,0,10,0,0,0,0,0,0 +25.73,51,0,10,0,0,0,0,0,0 +25.74,51,0,10,0,0,0,0,0,0 +25.75,51,0,10,0,0,0,0,0,0 +25.76,51,0,10,0,0,0,0,0,0 +25.77,51,0,10,0,0,0,0,0,0 +25.78,51,0,10,0,0,0,0,0,0 +25.79,51,0,10,0,0,0,0,0,0 +25.8,51,0,10,0,0,0,0,0,0 +25.81,51,0,10,0,0,0,0,0,0 +25.82,51,0,10,0,0,0,0,0,0 +25.83,51,0,10,0,0,0,0,0,0 +25.84,51,0,10,0,0,0,0,0,0 +25.85,51,0,10,0,0,0,0,0,0 +25.86,51,0,10,0,0,0,0,0,0 +25.87,51,0,10,0,0,0,0,0,0 +25.88,51,0,10,0,0,0,0,0,0 +25.89,51,0,10,0,0,0,0,0,0 +25.9,51,0,10,0,0,0,0,0,0 +25.91,51,0,10,0,0,0,0,0,0 +25.92,51,0,10,0,0,0,0,0,0 +25.93,51,0,10,0,0,0,0,0,0 +25.94,51,0,10,0,0,0,0,0,0 +25.95,51,0,10,0,0,0,0,0,0 +25.96,51,0,10,0,0,0,0,0,0 +25.97,51,0,10,0,0,0,0,0,0 +25.98,51,0,10,0,0,0,0,0,0 +25.99,51,0,10,0,0,0,0,0,0 +26,51,0,10,0,0,0,0,0,0 +26.01,51,0,10,0,0,0,0,0,0 +26.02,51,0,10,0,0,0,0,0,0 +26.03,51,0,10,0,0,0,0,0,0 +26.04,51,0,10,0,0,0,0,0,0 +26.05,51,0,10,0,0,0,0,0,0 +26.06,51,0,10,0,0,0,0,0,0 +26.07,51,0,10,0,0,0,0,0,0 +26.08,51,0,10,0,0,0,0,0,0 +26.09,51,0,10,0,0,0,0,0,0 +26.1,51,0,10,0,0,0,0,0,0 +26.11,51,0,10,0,0,0,0,0,0 +26.12,51,0,10,0,0,0,0,0,0 +26.13,51,0,10,0,0,0,0,0,0 +26.14,51,0,10,0,0,0,0,0,0 +26.15,51,0,10,0,0,0,0,0,0 +26.16,51,0,10,0,0,0,0,0,0 +26.17,51,0,10,0,0,0,0,0,0 +26.18,51,0,10,0,0,0,0,0,0 +26.19,51,0,10,0,0,0,0,0,0 +26.2,51,0,10,0,0,0,0,0,0 +26.21,51,0,10,0,0,0,0,0,0 +26.22,51,0,10,0,0,0,0,0,0 +26.23,51,0,10,0,0,0,0,0,0 +26.24,51,0,10,0,0,0,0,0,0 +26.25,51,0,10,0,0,0,0,0,0 +26.26,51,0,10,0,0,0,0,0,0 +26.27,51,0,10,0,0,0,0,0,0 +26.28,51,0,10,0,0,0,0,0,0 +26.29,51,0,10,0,0,0,0,0,0 +26.3,51,0,10,0,0,0,0,0,0 +26.31,51,0,10,0,0,0,0,0,0 +26.32,51,0,10,0,0,0,0,0,0 +26.33,51,0,10,0,0,0,0,0,0 +26.34,51,0,10,0,0,0,0,0,0 +26.35,51,0,10,0,0,0,0,0,0 +26.36,51,0,10,0,0,0,0,0,0 +26.37,51,0,10,0,0,0,0,0,0 +26.38,51,0,10,0,0,0,0,0,0 +26.39,51,0,10,0,0,0,0,0,0 +26.4,51,0,10,0,0,0,0,0,0 +26.41,51,0,10,0,0,0,0,0,0 +26.42,51,0,10,0,0,0,0,0,0 +26.43,51,0,10,0,0,0,0,0,0 +26.44,51,0,10,0,0,0,0,0,0 +26.45,51,0,10,0,0,0,0,0,0 +26.46,51,0,10,0,0,0,0,0,0 +26.47,51,0,10,0,0,0,0,0,0 +26.48,51,0,10,0,0,0,0,0,0 +26.49,51,0,10,0,0,0,0,0,0 +26.5,51,0,10,0,0,0,0,0,0 +26.51,51,0,10,0,0,0,0,0,0 +26.52,51,0,10,0,0,0,0,0,0 +26.53,51,0,10,0,0,0,0,0,0 +26.54,51,0,10,0,0,0,0,0,0 +26.55,51,0,10,0,0,0,0,0,0 +26.56,51,0,10,0,0,0,0,0,0 +26.57,51,0,10,0,0,0,0,0,0 +26.58,51,0,10,0,0,0,0,0,0 +26.59,51,0,10,0,0,0,0,0,0 +26.6,51,0,10,0,0,0,0,0,0 +26.61,51,0,10,0,0,0,0,0,0 +26.62,51,0,10,0,0,0,0,0,0 +26.63,51,0,10,0,0,0,0,0,0 +26.64,51,0,10,0,0,0,0,0,0 +26.65,51,0,10,0,0,0,0,0,0 +26.66,51,0,10,0,0,0,0,0,0 +26.67,51,0,10,0,0,0,0,0,0 +26.68,51,0,10,0,0,0,0,0,0 +26.69,51,0,10,0,0,0,0,0,0 +26.7,51,0,10,0,0,0,0,0,0 +26.71,51,0,10,0,0,0,0,0,0 +26.72,51,0,10,0,0,0,0,0,0 +26.73,51,0,10,0,0,0,0,0,0 +26.74,51,0,10,0,0,0,0,0,0 +26.75,51,0,10,0,0,0,0,0,0 +26.76,51,0,10,0,0,0,0,0,0 +26.77,51,0,10,0,0,0,0,0,0 +26.78,51,0,10,0,0,0,0,0,0 +26.79,51,0,10,0,0,0,0,0,0 +26.8,51,0,10,0,0,0,0,0,0 +26.81,51,0,10,0,0,0,0,0,0 +26.82,51,0,10,0,0,0,0,0,0 +26.83,51,0,10,0,0,0,0,0,0 +26.84,51,0,10,0,0,0,0,0,0 +26.85,51,0,10,0,0,0,0,0,0 +26.86,51,0,10,0,0,0,0,0,0 +26.87,51,0,10,0,0,0,0,0,0 +26.88,51,0,10,0,0,0,0,0,0 +26.89,51,0,10,0,0,0,0,0,0 +26.9,51,0,10,0,0,0,0,0,0 +26.91,51,0,10,0,0,0,0,0,0 +26.92,51,0,10,0,0,0,0,0,0 +26.93,51,0,10,0,0,0,0,0,0 +26.94,51,0,10,0,0,0,0,0,0 +26.95,51,0,10,0,0,0,0,0,0 +26.96,51,0,10,0,0,0,0,0,0 +26.97,51,0,10,0,0,0,0,0,0 +26.98,51,0,10,0,0,0,0,0,0 +26.99,51,0,10,0,0,0,0,0,0 +27,51,0,10,0,0,0,0,0,0 +27.01,51,0,10,0,0,0,0,0,0 +27.02,51,0,10,0,0,0,0,0,0 +27.03,51,0,10,0,0,0,0,0,0 +27.04,51,0,10,0,0,0,0,0,0 +27.05,51,0,10,0,0,0,0,0,0 +27.06,51,0,10,0,0,0,0,0,0 +27.07,51,0,10,0,0,0,0,0,0 +27.08,51,0,10,0,0,0,0,0,0 +27.09,51,0,10,0,0,0,0,0,0 +27.1,51,0,10,0,0,0,0,0,0 +27.11,51,0,10,0,0,0,0,0,0 +27.12,51,0,10,0,0,0,0,0,0 +27.13,51,0,10,0,0,0,0,0,0 +27.14,51,0,10,0,0,0,0,0,0 +27.15,51,0,10,0,0,0,0,0,0 +27.16,51,0,10,0,0,0,0,0,0 +27.17,51,0,10,0,0,0,0,0,0 +27.18,51,0,10,0,0,0,0,0,0 +27.19,51,0,10,0,0,0,0,0,0 +27.2,51,0,10,0,0,0,0,0,0 +27.21,51,0,10,0,0,0,0,0,0 +27.22,51,0,10,0,0,0,0,0,0 +27.23,51,0,10,0,0,0,0,0,0 +27.24,51,0,10,0,0,0,0,0,0 +27.25,51,0,10,0,0,0,0,0,0 +27.26,51,0,10,0,0,0,0,0,0 +27.27,51,0,10,0,0,0,0,0,0 +27.28,51,0,10,0,0,0,0,0,0 +27.29,51,0,10,0,0,0,0,0,0 +27.3,51,0,10,0,0,0,0,0,0 +27.31,51,0,10,0,0,0,0,0,0 +27.32,51,0,10,0,0,0,0,0,0 +27.33,51,0,10,0,0,0,0,0,0 +27.34,51,0,10,0,0,0,0,0,0 +27.35,51,0,10,0,0,0,0,0,0 +27.36,51,0,10,0,0,0,0,0,0 +27.37,51,0,10,0,0,0,0,0,0 +27.38,51,0,10,0,0,0,0,0,0 +27.39,51,0,10,0,0,0,0,0,0 +27.4,51,0,10,0,0,0,0,0,0 +27.41,51,0,10,0,0,0,0,0,0 +27.42,51,0,10,0,0,0,0,0,0 +27.43,51,0,10,0,0,0,0,0,0 +27.44,51,0,10,0,0,0,0,0,0 +27.45,51,0,10,0,0,0,0,0,0 +27.46,51,0,10,0,0,0,0,0,0 +27.47,51,0,10,0,0,0,0,0,0 +27.48,51,0,10,0,0,0,0,0,0 +27.49,51,0,10,0,0,0,0,0,0 +27.5,51,0,10,0,0,0,0,0,0 +27.51,51,0,10,0,0,0,0,0,0 +27.52,51,0,10,0,0,0,0,0,0 +27.53,51,0,10,0,0,0,0,0,0 +27.54,51,0,10,0,0,0,0,0,0 +27.55,51,0,10,0,0,0,0,0,0 +27.56,51,0,10,0,0,0,0,0,0 +27.57,51,0,10,0,0,0,0,0,0 +27.58,51,0,10,0,0,0,0,0,0 +27.59,51,0,10,0,0,0,0,0,0 +27.6,51,0,10,0,0,0,0,0,0 +27.61,51,0,10,0,0,0,0,0,0 +27.62,51,0,10,0,0,0,0,0,0 +27.63,51,0,10,0,0,0,0,0,0 +27.64,51,0,10,0,0,0,0,0,0 +27.65,51,0,10,0,0,0,0,0,0 +27.66,51,0,10,0,0,0,0,0,0 +27.67,51,0,10,0,0,0,0,0,0 +27.68,51,0,10,0,0,0,0,0,0 +27.69,51,0,10,0,0,0,0,0,0 +27.7,51,0,10,0,0,0,0,0,0 +27.71,51,0,10,0,0,0,0,0,0 +27.72,51,0,10,0,0,0,0,0,0 +27.73,51,0,10,0,0,0,0,0,0 +27.74,51,0,10,0,0,0,0,0,0 +27.75,51,0,10,0,0,0,0,0,0 +27.76,51,0,10,0,0,0,0,0,0 +27.77,51,0,10,0,0,0,0,0,0 +27.78,51,0,10,0,0,0,0,0,0 +27.79,51,0,10,0,0,0,0,0,0 +27.8,51,0,10,0,0,0,0,0,0 +27.81,51,0,10,0,0,0,0,0,0 +27.82,51,0,10,0,0,0,0,0,0 +27.83,51,0,10,0,0,0,0,0,0 +27.84,51,0,10,0,0,0,0,0,0 +27.85,51,0,10,0,0,0,0,0,0 +27.86,51,0,10,0,0,0,0,0,0 +27.87,51,0,10,0,0,0,0,0,0 +27.88,51,0,10,0,0,0,0,0,0 +27.89,51,0,10,0,0,0,0,0,0 +27.9,51,0,10,0,0,0,0,0,0 +27.91,51,0,10,0,0,0,0,0,0 +27.92,51,0,10,0,0,0,0,0,0 +27.93,51,0,10,0,0,0,0,0,0 +27.94,51,0,10,0,0,0,0,0,0 +27.95,51,0,10,0,0,0,0,0,0 +27.96,51,0,10,0,0,0,0,0,0 +27.97,51,0,10,0,0,0,0,0,0 +27.98,51,0,10,0,0,0,0,0,0 +27.99,51,0,10,0,0,0,0,0,0 +28,51,0,10,0,0,0,0,0,0 +28.01,51,0,10,0,0,0,0,0,0 +28.02,51,0,10,0,0,0,0,0,0 +28.03,51,0,10,0,0,0,0,0,0 +28.04,51,0,10,0,0,0,0,0,0 +28.05,51,0,10,0,0,0,0,0,0 +28.06,51,0,10,0,0,0,0,0,0 +28.07,51,0,10,0,0,0,0,0,0 +28.08,51,0,10,0,0,0,0,0,0 +28.09,51,0,10,0,0,0,0,0,0 +28.1,51,0,10,0,0,0,0,0,0 +28.11,51,0,10,0,0,0,0,0,0 +28.12,51,0,10,0,0,0,0,0,0 +28.13,51,0,10,0,0,0,0,0,0 +28.14,51,0,10,0,0,0,0,0,0 +28.15,51,0,10,0,0,0,0,0,0 +28.16,51,0,10,0,0,0,0,0,0 +28.17,51,0,10,0,0,0,0,0,0 +28.18,51,0,10,0,0,0,0,0,0 +28.19,51,0,10,0,0,0,0,0,0 +28.2,51,0,10,0,0,0,0,0,0 +28.21,51,0,10,0,0,0,0,0,0 +28.22,51,0,10,0,0,0,0,0,0 +28.23,51,0,10,0,0,0,0,0,0 +28.24,51,0,10,0,0,0,0,0,0 +28.25,51,0,10,0,0,0,0,0,0 +28.26,51,0,10,0,0,0,0,0,0 +28.27,51,0,10,0,0,0,0,0,0 +28.28,51,0,10,0,0,0,0,0,0 +28.29,51,0,10,0,0,0,0,0,0 +28.3,51,0,10,0,0,0,0,0,0 +28.31,51,0,10,0,0,0,0,0,0 +28.32,51,0,10,0,0,0,0,0,0 +28.33,51,0,10,0,0,0,0,0,0 +28.34,51,0,10,0,0,0,0,0,0 +28.35,51,0,10,0,0,0,0,0,0 +28.36,51,0,10,0,0,0,0,0,0 +28.37,51,0,10,0,0,0,0,0,0 +28.38,51,0,10,0,0,0,0,0,0 +28.39,51,0,10,0,0,0,0,0,0 +28.4,51,0,10,0,0,0,0,0,0 +28.41,51,0,10,0,0,0,0,0,0 +28.42,51,0,10,0,0,0,0,0,0 +28.43,51,0,10,0,0,0,0,0,0 +28.44,51,0,10,0,0,0,0,0,0 +28.45,51,0,10,0,0,0,0,0,0 +28.46,51,0,10,0,0,0,0,0,0 +28.47,51,0,10,0,0,0,0,0,0 +28.48,51,0,10,0,0,0,0,0,0 +28.49,51,0,10,0,0,0,0,0,0 +28.5,51,0,10,0,0,0,0,0,0 +28.51,51,0,10,0,0,0,0,0,0 +28.52,51,0,10,0,0,0,0,0,0 +28.53,51,0,10,0,0,0,0,0,0 +28.54,51,0,10,0,0,0,0,0,0 +28.55,51,0,10,0,0,0,0,0,0 +28.56,51,0,10,0,0,0,0,0,0 +28.57,51,0,10,0,0,0,0,0,0 +28.58,51,0,10,0,0,0,0,0,0 +28.59,51,0,10,0,0,0,0,0,0 +28.6,51,0,10,0,0,0,0,0,0 +28.61,51,0,10,0,0,0,0,0,0 +28.62,51,0,10,0,0,0,0,0,0 +28.63,51,0,10,0,0,0,0,0,0 +28.64,51,0,10,0,0,0,0,0,0 +28.65,51,0,10,0,0,0,0,0,0 +28.66,51,0,10,0,0,0,0,0,0 +28.67,51,0,10,0,0,0,0,0,0 +28.68,51,0,10,0,0,0,0,0,0 +28.69,51,0,10,0,0,0,0,0,0 +28.7,51,0,10,0,0,0,0,0,0 +28.71,51,0,10,0,0,0,0,0,0 +28.72,51,0,10,0,0,0,0,0,0 +28.73,51,0,10,0,0,0,0,0,0 +28.74,51,0,10,0,0,0,0,0,0 +28.75,51,0,10,0,0,0,0,0,0 +28.76,51,0,10,0,0,0,0,0,0 +28.77,51,0,10,0,0,0,0,0,0 +28.78,51,0,10,0,0,0,0,0,0 +28.79,51,0,10,0,0,0,0,0,0 +28.8,51,0,10,0,0,0,0,0,0 +28.81,51,0,10,0,0,0,0,0,0 +28.82,51,0,10,0,0,0,0,0,0 +28.83,51,0,10,0,0,0,0,0,0 +28.84,51,0,10,0,0,0,0,0,0 +28.85,51,0,10,0,0,0,0,0,0 +28.86,51,0,10,0,0,0,0,0,0 +28.87,51,0,10,0,0,0,0,0,0 +28.88,51,0,10,0,0,0,0,0,0 +28.89,51,0,10,0,0,0,0,0,0 +28.9,51,0,10,0,0,0,0,0,0 +28.91,51,0,10,0,0,0,0,0,0 +28.92,51,0,10,0,0,0,0,0,0 +28.93,51,0,10,0,0,0,0,0,0 +28.94,51,0,10,0,0,0,0,0,0 +28.95,51,0,10,0,0,0,0,0,0 +28.96,51,0,10,0,0,0,0,0,0 +28.97,51,0,10,0,0,0,0,0,0 +28.98,51,0,10,0,0,0,0,0,0 +28.99,51,0,10,0,0,0,0,0,0 +29,51,0,10,0,0,0,0,0,0 +29.01,51,0,10,0,0,0,0,0,0 +29.02,51,0,10,0,0,0,0,0,0 +29.03,51,0,10,0,0,0,0,0,0 +29.04,51,0,10,0,0,0,0,0,0 +29.05,51,0,10,0,0,0,0,0,0 +29.06,51,0,10,0,0,0,0,0,0 +29.07,51,0,10,0,0,0,0,0,0 +29.08,51,0,10,0,0,0,0,0,0 +29.09,51,0,10,0,0,0,0,0,0 +29.1,51,0,10,0,0,0,0,0,0 +29.11,51,0,10,0,0,0,0,0,0 +29.12,51,0,10,0,0,0,0,0,0 +29.13,51,0,10,0,0,0,0,0,0 +29.14,51,0,10,0,0,0,0,0,0 +29.15,51,0,10,0,0,0,0,0,0 +29.16,51,0,10,0,0,0,0,0,0 +29.17,51,0,10,0,0,0,0,0,0 +29.18,51,0,10,0,0,0,0,0,0 +29.19,51,0,10,0,0,0,0,0,0 +29.2,51,0,10,0,0,0,0,0,0 +29.21,51,0,10,0,0,0,0,0,0 +29.22,51,0,10,0,0,0,0,0,0 +29.23,51,0,10,0,0,0,0,0,0 +29.24,51,0,10,0,0,0,0,0,0 +29.25,51,0,10,0,0,0,0,0,0 +29.26,51,0,10,0,0,0,0,0,0 +29.27,51,0,10,0,0,0,0,0,0 +29.28,51,0,10,0,0,0,0,0,0 +29.29,51,0,10,0,0,0,0,0,0 +29.3,51,0,10,0,0,0,0,0,0 +29.31,51,0,10,0,0,0,0,0,0 +29.32,51,0,10,0,0,0,0,0,0 +29.33,51,0,10,0,0,0,0,0,0 +29.34,51,0,10,0,0,0,0,0,0 +29.35,51,0,10,0,0,0,0,0,0 +29.36,51,0,10,0,0,0,0,0,0 +29.37,51,0,10,0,0,0,0,0,0 +29.38,51,0,10,0,0,0,0,0,0 +29.39,51,0,10,0,0,0,0,0,0 +29.4,51,0,10,0,0,0,0,0,0 +29.41,51,0,10,0,0,0,0,0,0 +29.42,51,0,10,0,0,0,0,0,0 +29.43,51,0,10,0,0,0,0,0,0 +29.44,51,0,10,0,0,0,0,0,0 +29.45,51,0,10,0,0,0,0,0,0 +29.46,51,0,10,0,0,0,0,0,0 +29.47,51,0,10,0,0,0,0,0,0 +29.48,51,0,10,0,0,0,0,0,0 +29.49,51,0,10,0,0,0,0,0,0 +29.5,51,0,10,0,0,0,0,0,0 +29.51,51,0,10,0,0,0,0,0,0 +29.52,51,0,10,0,0,0,0,0,0 +29.53,51,0,10,0,0,0,0,0,0 +29.54,51,0,10,0,0,0,0,0,0 +29.55,51,0,10,0,0,0,0,0,0 +29.56,51,0,10,0,0,0,0,0,0 +29.57,51,0,10,0,0,0,0,0,0 +29.58,51,0,10,0,0,0,0,0,0 +29.59,51,0,10,0,0,0,0,0,0 +29.6,51,0,10,0,0,0,0,0,0 +29.61,51,0,10,0,0,0,0,0,0 +29.62,51,0,10,0,0,0,0,0,0 +29.63,51,0,10,0,0,0,0,0,0 +29.64,51,0,10,0,0,0,0,0,0 +29.65,51,0,10,0,0,0,0,0,0 +29.66,51,0,10,0,0,0,0,0,0 +29.67,51,0,10,0,0,0,0,0,0 +29.68,51,0,10,0,0,0,0,0,0 +29.69,51,0,10,0,0,0,0,0,0 +29.7,51,0,10,0,0,0,0,0,0 +29.71,51,0,10,0,0,0,0,0,0 +29.72,51,0,10,0,0,0,0,0,0 +29.73,51,0,10,0,0,0,0,0,0 +29.74,51,0,10,0,0,0,0,0,0 +29.75,51,0,10,0,0,0,0,0,0 +29.76,51,0,10,0,0,0,0,0,0 +29.77,51,0,10,0,0,0,0,0,0 +29.78,51,0,10,0,0,0,0,0,0 +29.79,51,0,10,0,0,0,0,0,0 +29.8,51,0,10,0,0,0,0,0,0 +29.81,51,0,10,0,0,0,0,0,0 +29.82,51,0,10,0,0,0,0,0,0 +29.83,51,0,10,0,0,0,0,0,0 +29.84,51,0,10,0,0,0,0,0,0 +29.85,51,0,10,0,0,0,0,0,0 +29.86,51,0,10,0,0,0,0,0,0 +29.87,51,0,10,0,0,0,0,0,0 +29.88,51,0,10,0,0,0,0,0,0 +29.89,51,0,10,0,0,0,0,0,0 +29.9,51,0,10,0,0,0,0,0,0 +29.91,51,0,10,0,0,0,0,0,0 +29.92,51,0,10,0,0,0,0,0,0 +29.93,51,0,10,0,0,0,0,0,0 +29.94,51,0,10,0,0,0,0,0,0 +29.95,51,0,10,0,0,0,0,0,0 +29.96,51,0,10,0,0,0,0,0,0 +29.97,51,0,10,0,0,0,0,0,0 +29.98,51,0,10,0,0,0,0,0,0 +29.99,51,0,10,0,0,0,0,0,0 +30,51,0,10,0,0,0,0,0,0 +30.01,51,0,10,0,0,0,0,0,0 +30.02,51,0,10,0,0,0,0,0,0 +30.03,51,0,10,0,0,0,0,0,0 +30.04,51,0,10,0,0,0,0,0,0 +30.05,51,0,10,0,0,0,0,0,0 +30.06,51,0,10,0,0,0,0,0,0 +30.07,51,0,10,0,0,0,0,0,0 +30.08,51,0,10,0,0,0,0,0,0 +30.09,51,0,10,0,0,0,0,0,0 +30.1,51,0,10,0,0,0,0,0,0 +30.11,51,0,10,0,0,0,0,0,0 +30.12,51,0,10,0,0,0,0,0,0 +30.13,51,0,10,0,0,0,0,0,0 +30.14,51,0,10,0,0,0,0,0,0 +30.15,51,0,10,0,0,0,0,0,0 +30.16,51,0,10,0,0,0,0,0,0 +30.17,51,0,10,0,0,0,0,0,0 +30.18,51,0,10,0,0,0,0,0,0 +30.19,51,0,10,0,0,0,0,0,0 +30.2,51,0,10,0,0,0,0,0,0 +30.21,51,0,10,0,0,0,0,0,0 +30.22,51,0,10,0,0,0,0,0,0 +30.23,51,0,10,0,0,0,0,0,0 +30.24,51,0,10,0,0,0,0,0,0 +30.25,51,0,10,0,0,0,0,0,0 +30.26,51,0,10,0,0,0,0,0,0 +30.27,51,0,10,0,0,0,0,0,0 +30.28,51,0,10,0,0,0,0,0,0 +30.29,51,0,10,0,0,0,0,0,0 +30.3,51,0,10,0,0,0,0,0,0 +30.31,51,0,10,0,0,0,0,0,0 +30.32,51,0,10,0,0,0,0,0,0 +30.33,51,0,10,0,0,0,0,0,0 +30.34,51,0,10,0,0,0,0,0,0 +30.35,51,0,10,0,0,0,0,0,0 +30.36,51,0,10,0,0,0,0,0,0 +30.37,51,0,10,0,0,0,0,0,0 +30.38,51,0,10,0,0,0,0,0,0 +30.39,51,0,10,0,0,0,0,0,0 +30.4,51,0,10,0,0,0,0,0,0 +30.41,51,0,10,0,0,0,0,0,0 +30.42,51,0,10,0,0,0,0,0,0 +30.43,51,0,10,0,0,0,0,0,0 +30.44,51,0,10,0,0,0,0,0,0 +30.45,51,0,10,0,0,0,0,0,0 +30.46,51,0,10,0,0,0,0,0,0 +30.47,51,0,10,0,0,0,0,0,0 +30.48,51,0,10,0,0,0,0,0,0 +30.49,51,0,10,0,0,0,0,0,0 +30.5,51,0,10,0,0,0,0,0,0 +30.51,51,0,10,0,0,0,0,0,0 +30.52,51,0,10,0,0,0,0,0,0 +30.53,51,0,10,0,0,0,0,0,0 +30.54,51,0,10,0,0,0,0,0,0 +30.55,51,0,10,0,0,0,0,0,0 +30.56,51,0,10,0,0,0,0,0,0 +30.57,51,0,10,0,0,0,0,0,0 +30.58,51,0,10,0,0,0,0,0,0 +30.59,51,0,10,0,0,0,0,0,0 +30.6,51,0,10,0,0,0,0,0,0 +30.61,51,0,10,0,0,0,0,0,0 +30.62,51,0,10,0,0,0,0,0,0 +30.63,51,0,10,0,0,0,0,0,0 +30.64,51,0,10,0,0,0,0,0,0 +30.65,51,0,10,0,0,0,0,0,0 +30.66,51,0,10,0,0,0,0,0,0 +30.67,51,0,10,0,0,0,0,0,0 +30.68,51,0,10,0,0,0,0,0,0 +30.69,51,0,10,0,0,0,0,0,0 +30.7,51,0,10,0,0,0,0,0,0 +30.71,51,0,10,0,0,0,0,0,0 +30.72,51,0,10,0,0,0,0,0,0 +30.73,51,0,10,0,0,0,0,0,0 +30.74,51,0,10,0,0,0,0,0,0 +30.75,51,0,10,0,0,0,0,0,0 +30.76,51,0,10,0,0,0,0,0,0 +30.77,51,0,10,0,0,0,0,0,0 +30.78,51,0,10,0,0,0,0,0,0 +30.79,51,0,10,0,0,0,0,0,0 +30.8,51,0,10,0,0,0,0,0,0 +30.81,51,0,10,0,0,0,0,0,0 +30.82,51,0,10,0,0,0,0,0,0 +30.83,51,0,10,0,0,0,0,0,0 +30.84,51,0,10,0,0,0,0,0,0 +30.85,51,0,10,0,0,0,0,0,0 +30.86,51,0,10,0,0,0,0,0,0 +30.87,51,0,10,0,0,0,0,0,0 +30.88,51,0,10,0,0,0,0,0,0 +30.89,51,0,10,0,0,0,0,0,0 +30.9,51,0,10,0,0,0,0,0,0 +30.91,51,0,10,0,0,0,0,0,0 +30.92,51,0,10,0,0,0,0,0,0 +30.93,51,0,10,0,0,0,0,0,0 +30.94,51,0,10,0,0,0,0,0,0 +30.95,51,0,10,0,0,0,0,0,0 +30.96,51,0,10,0,0,0,0,0,0 +30.97,51,0,10,0,0,0,0,0,0 +30.98,51,0,10,0,0,0,0,0,0 +30.99,51,0,10,0,0,0,0,0,0 +31,51,0,10,0,0,0,0,0,0 +31.01,51,0,10,0,0,0,0,0,0 +31.02,51,0,10,0,0,0,0,0,0 +31.03,51,0,10,0,0,0,0,0,0 +31.04,51,0,10,0,0,0,0,0,0 +31.05,51,0,10,0,0,0,0,0,0 +31.06,51,0,10,0,0,0,0,0,0 +31.07,51,0,10,0,0,0,0,0,0 +31.08,51,0,10,0,0,0,0,0,0 +31.09,51,0,10,0,0,0,0,0,0 +31.1,51,0,10,0,0,0,0,0,0 +31.11,51,0,10,0,0,0,0,0,0 +31.12,51,0,10,0,0,0,0,0,0 +31.13,51,0,10,0,0,0,0,0,0 +31.14,51,0,10,0,0,0,0,0,0 +31.15,51,0,10,0,0,0,0,0,0 +31.16,51,0,10,0,0,0,0,0,0 +31.17,51,0,10,0,0,0,0,0,0 +31.18,51,0,10,0,0,0,0,0,0 +31.19,51,0,10,0,0,0,0,0,0 +31.2,51,0,10,0,0,0,0,0,0 +31.21,51,0,10,0,0,0,0,0,0 +31.22,51,0,10,0,0,0,0,0,0 +31.23,51,0,10,0,0,0,0,0,0 +31.24,51,0,10,0,0,0,0,0,0 +31.25,51,0,10,0,0,0,0,0,0 +31.26,51,0,10,0,0,0,0,0,0 +31.27,51,0,10,0,0,0,0,0,0 +31.28,51,0,10,0,0,0,0,0,0 +31.29,51,0,10,0,0,0,0,0,0 +31.3,51,0,10,0,0,0,0,0,0 +31.31,51,0,10,0,0,0,0,0,0 +31.32,51,0,10,0,0,0,0,0,0 +31.33,51,0,10,0,0,0,0,0,0 +31.34,51,0,10,0,0,0,0,0,0 +31.35,51,0,10,0,0,0,0,0,0 +31.36,51,0,10,0,0,0,0,0,0 +31.37,51,0,10,0,0,0,0,0,0 +31.38,51,0,10,0,0,0,0,0,0 +31.39,51,0,10,0,0,0,0,0,0 +31.4,51,0,10,0,0,0,0,0,0 +31.41,51,0,10,0,0,0,0,0,0 +31.42,51,0,10,0,0,0,0,0,0 +31.43,51,0,10,0,0,0,0,0,0 +31.44,51,0,10,0,0,0,0,0,0 +31.45,51,0,10,0,0,0,0,0,0 +31.46,51,0,10,0,0,0,0,0,0 +31.47,51,0,10,0,0,0,0,0,0 +31.48,51,0,10,0,0,0,0,0,0 +31.49,51,0,10,0,0,0,0,0,0 +31.5,51,0,10,0,0,0,0,0,0 +31.51,51,0,10,0,0,0,0,0,0 +31.52,51,0,10,0,0,0,0,0,0 +31.53,51,0,10,0,0,0,0,0,0 +31.54,51,0,10,0,0,0,0,0,0 +31.55,51,0,10,0,0,0,0,0,0 +31.56,51,0,10,0,0,0,0,0,0 +31.57,51,0,10,0,0,0,0,0,0 +31.58,51,0,10,0,0,0,0,0,0 +31.59,51,0,10,0,0,0,0,0,0 +31.6,51,0,10,0,0,0,0,0,0 +31.61,51,0,10,0,0,0,0,0,0 +31.62,51,0,10,0,0,0,0,0,0 +31.63,51,0,10,0,0,0,0,0,0 +31.64,51,0,10,0,0,0,0,0,0 +31.65,51,0,10,0,0,0,0,0,0 +31.66,51,0,10,0,0,0,0,0,0 +31.67,51,0,10,0,0,0,0,0,0 +31.68,51,0,10,0,0,0,0,0,0 +31.69,51,0,10,0,0,0,0,0,0 +31.7,51,0,10,0,0,0,0,0,0 +31.71,51,0,10,0,0,0,0,0,0 +31.72,51,0,10,0,0,0,0,0,0 +31.73,51,0,10,0,0,0,0,0,0 +31.74,51,0,10,0,0,0,0,0,0 +31.75,51,0,10,0,0,0,0,0,0 +31.76,51,0,10,0,0,0,0,0,0 +31.77,51,0,10,0,0,0,0,0,0 +31.78,51,0,10,0,0,0,0,0,0 +31.79,51,0,10,0,0,0,0,0,0 +31.8,51,0,10,0,0,0,0,0,0 +31.81,51,0,10,0,0,0,0,0,0 +31.82,51,0,10,0,0,0,0,0,0 +31.83,51,0,10,0,0,0,0,0,0 +31.84,51,0,10,0,0,0,0,0,0 +31.85,51,0,10,0,0,0,0,0,0 +31.86,51,0,10,0,0,0,0,0,0 +31.87,51,0,10,0,0,0,0,0,0 +31.88,51,0,10,0,0,0,0,0,0 +31.89,51,0,10,0,0,0,0,0,0 +31.9,51,0,10,0,0,0,0,0,0 +31.91,51,0,10,0,0,0,0,0,0 +31.92,51,0,10,0,0,0,0,0,0 +31.93,51,0,10,0,0,0,0,0,0 +31.94,51,0,10,0,0,0,0,0,0 +31.95,51,0,10,0,0,0,0,0,0 +31.96,51,0,10,0,0,0,0,0,0 +31.97,51,0,10,0,0,0,0,0,0 +31.98,51,0,10,0,0,0,0,0,0 +31.99,51,0,10,0,0,0,0,0,0 +32,51,0,10,0,0,0,0,0,0 +32.01,51,0,10,0,0,0,0,0,0 +32.02,51,0,10,0,0,0,0,0,0 +32.03,51,0,10,0,0,0,0,0,0 +32.04,51,0,10,0,0,0,0,0,0 +32.05,51,0,10,0,0,0,0,0,0 +32.06,51,0,10,0,0,0,0,0,0 +32.07,51,0,10,0,0,0,0,0,0 +32.08,51,0,10,0,0,0,0,0,0 +32.09,51,0,10,0,0,0,0,0,0 +32.1,51,0,10,0,0,0,0,0,0 +32.11,51,0,10,0,0,0,0,0,0 +32.12,51,0,10,0,0,0,0,0,0 +32.13,51,0,10,0,0,0,0,0,0 +32.14,51,0,10,0,0,0,0,0,0 +32.15,51,0,10,0,0,0,0,0,0 +32.16,51,0,10,0,0,0,0,0,0 +32.17,51,0,10,0,0,0,0,0,0 +32.18,51,0,10,0,0,0,0,0,0 +32.19,51,0,10,0,0,0,0,0,0 +32.2,51,0,10,0,0,0,0,0,0 +32.21,51,0,10,0,0,0,0,0,0 +32.22,51,0,10,0,0,0,0,0,0 +32.23,51,0,10,0,0,0,0,0,0 +32.24,51,0,10,0,0,0,0,0,0 +32.25,51,0,10,0,0,0,0,0,0 +32.26,51,0,10,0,0,0,0,0,0 +32.27,51,0,10,0,0,0,0,0,0 +32.28,51,0,10,0,0,0,0,0,0 +32.29,51,0,10,0,0,0,0,0,0 +32.3,51,0,10,0,0,0,0,0,0 +32.31,51,0,10,0,0,0,0,0,0 +32.32,51,0,10,0,0,0,0,0,0 +32.33,51,0,10,0,0,0,0,0,0 +32.34,51,0,10,0,0,0,0,0,0 +32.35,51,0,10,0,0,0,0,0,0 +32.36,51,0,10,0,0,0,0,0,0 +32.37,51,0,10,0,0,0,0,0,0 +32.38,51,0,10,0,0,0,0,0,0 +32.39,51,0,10,0,0,0,0,0,0 +32.4,51,0,10,0,0,0,0,0,0 +32.41,51,0,10,0,0,0,0,0,0 +32.42,51,0,10,0,0,0,0,0,0 +32.43,51,0,10,0,0,0,0,0,0 +32.44,51,0,10,0,0,0,0,0,0 +32.45,51,0,10,0,0,0,0,0,0 +32.46,51,0,10,0,0,0,0,0,0 +32.47,51,0,10,0,0,0,0,0,0 +32.48,51,0,10,0,0,0,0,0,0 +32.49,51,0,10,0,0,0,0,0,0 +32.5,51,0,10,0,0,0,0,0,0 +32.51,51,0,10,0,0,0,0,0,0 +32.52,51,0,10,0,0,0,0,0,0 +32.53,51,0,10,0,0,0,0,0,0 +32.54,51,0,10,0,0,0,0,0,0 +32.55,51,0,10,0,0,0,0,0,0 +32.56,51,0,10,0,0,0,0,0,0 +32.57,51,0,10,0,0,0,0,0,0 +32.58,51,0,10,0,0,0,0,0,0 +32.59,51,0,10,0,0,0,0,0,0 +32.6,51,0,10,0,0,0,0,0,0 +32.61,51,0,10,0,0,0,0,0,0 +32.62,51,0,10,0,0,0,0,0,0 +32.63,51,0,10,0,0,0,0,0,0 +32.64,51,0,10,0,0,0,0,0,0 +32.65,51,0,10,0,0,0,0,0,0 +32.66,51,0,10,0,0,0,0,0,0 +32.67,51,0,10,0,0,0,0,0,0 +32.68,51,0,10,0,0,0,0,0,0 +32.69,51,0,10,0,0,0,0,0,0 +32.7,51,0,10,0,0,0,0,0,0 +32.71,51,0,10,0,0,0,0,0,0 +32.72,51,0,10,0,0,0,0,0,0 +32.73,51,0,10,0,0,0,0,0,0 +32.74,51,0,10,0,0,0,0,0,0 +32.75,51,0,10,0,0,0,0,0,0 +32.76,51,0,10,0,0,0,0,0,0 +32.77,51,0,10,0,0,0,0,0,0 +32.78,51,0,10,0,0,0,0,0,0 +32.79,51,0,10,0,0,0,0,0,0 +32.8,51,0,10,0,0,0,0,0,0 +32.81,51,0,10,0,0,0,0,0,0 +32.82,51,0,10,0,0,0,0,0,0 +32.83,51,0,10,0,0,0,0,0,0 +32.84,51,0,10,0,0,0,0,0,0 +32.85,51,0,10,0,0,0,0,0,0 +32.86,51,0,10,0,0,0,0,0,0 +32.87,51,0,10,0,0,0,0,0,0 +32.88,51,0,10,0,0,0,0,0,0 +32.89,51,0,10,0,0,0,0,0,0 +32.9,51,0,10,0,0,0,0,0,0 +32.91,51,0,10,0,0,0,0,0,0 +32.92,51,0,10,0,0,0,0,0,0 +32.93,51,0,10,0,0,0,0,0,0 +32.94,51,0,10,0,0,0,0,0,0 +32.95,51,0,10,0,0,0,0,0,0 +32.96,51,0,10,0,0,0,0,0,0 +32.97,51,0,10,0,0,0,0,0,0 +32.98,51,0,10,0,0,0,0,0,0 +32.99,51,0,10,0,0,0,0,0,0 +33,51,0,10,0,0,0,0,0,0 +33.01,51,0,10,0,0,0,0,0,0 +33.02,51,0,10,0,0,0,0,0,0 +33.03,51,0,10,0,0,0,0,0,0 +33.04,51,0,10,0,0,0,0,0,0 +33.05,51,0,10,0,0,0,0,0,0 +33.06,51,0,10,0,0,0,0,0,0 +33.07,51,0,10,0,0,0,0,0,0 +33.08,51,0,10,0,0,0,0,0,0 +33.09,51,0,10,0,0,0,0,0,0 +33.1,51,0,10,0,0,0,0,0,0 +33.11,51,0,10,0,0,0,0,0,0 +33.12,51,0,10,0,0,0,0,0,0 +33.13,51,0,10,0,0,0,0,0,0 +33.14,51,0,10,0,0,0,0,0,0 +33.15,51,0,10,0,0,0,0,0,0 +33.16,51,0,10,0,0,0,0,0,0 +33.17,51,0,10,0,0,0,0,0,0 +33.18,51,0,10,0,0,0,0,0,0 +33.19,51,0,10,0,0,0,0,0,0 +33.2,51,0,10,0,0,0,0,0,0 +33.21,51,0,10,0,0,0,0,0,0 +33.22,51,0,10,0,0,0,0,0,0 +33.23,51,0,10,0,0,0,0,0,0 +33.24,51,0,10,0,0,0,0,0,0 +33.25,51,0,10,0,0,0,0,0,0 +33.26,51,0,10,0,0,0,0,0,0 +33.27,51,0,10,0,0,0,0,0,0 +33.28,51,0,10,0,0,0,0,0,0 +33.29,51,0,10,0,0,0,0,0,0 +33.3,51,0,10,0,0,0,0,0,0 +33.31,51,0,10,0,0,0,0,0,0 +33.32,51,0,10,0,0,0,0,0,0 +33.33,51,0,10,0,0,0,0,0,0 +33.34,51,0,10,0,0,0,0,0,0 +33.35,51,0,10,0,0,0,0,0,0 +33.36,51,0,10,0,0,0,0,0,0 +33.37,51,0,10,0,0,0,0,0,0 +33.38,51,0,10,0,0,0,0,0,0 +33.39,51,0,10,0,0,0,0,0,0 +33.4,51,0,10,0,0,0,0,0,0 +33.41,51,0,10,0,0,0,0,0,0 +33.42,51,0,10,0,0,0,0,0,0 +33.43,51,0,10,0,0,0,0,0,0 +33.44,51,0,10,0,0,0,0,0,0 +33.45,51,0,10,0,0,0,0,0,0 +33.46,51,0,10,0,0,0,0,0,0 +33.47,51,0,10,0,0,0,0,0,0 +33.48,51,0,10,0,0,0,0,0,0 +33.49,51,0,10,0,0,0,0,0,0 +33.5,51,0,10,0,0,0,0,0,0 +33.51,51,0,10,0,0,0,0,0,0 +33.52,51,0,10,0,0,0,0,0,0 +33.53,51,0,10,0,0,0,0,0,0 +33.54,51,0,10,0,0,0,0,0,0 +33.55,51,0,10,0,0,0,0,0,0 +33.56,51,0,10,0,0,0,0,0,0 +33.57,51,0,10,0,0,0,0,0,0 +33.58,51,0,10,0,0,0,0,0,0 +33.59,51,0,10,0,0,0,0,0,0 +33.6,51,0,10,0,0,0,0,0,0 +33.61,51,0,10,0,0,0,0,0,0 +33.62,51,0,10,0,0,0,0,0,0 +33.63,51,0,10,0,0,0,0,0,0 +33.64,51,0,10,0,0,0,0,0,0 +33.65,51,0,10,0,0,0,0,0,0 +33.66,51,0,10,0,0,0,0,0,0 +33.67,51,0,10,0,0,0,0,0,0 +33.68,51,0,10,0,0,0,0,0,0 +33.69,51,0,10,0,0,0,0,0,0 +33.7,51,0,10,0,0,0,0,0,0 +33.71,51,0,10,0,0,0,0,0,0 +33.72,51,0,10,0,0,0,0,0,0 +33.73,51,0,10,0,0,0,0,0,0 +33.74,51,0,10,0,0,0,0,0,0 +33.75,51,0,10,0,0,0,0,0,0 +33.76,51,0,10,0,0,0,0,0,0 +33.77,51,0,10,0,0,0,0,0,0 +33.78,51,0,10,0,0,0,0,0,0 +33.79,51,0,10,0,0,0,0,0,0 +33.8,51,0,10,0,0,0,0,0,0 +33.81,51,0,10,0,0,0,0,0,0 +33.82,51,0,10,0,0,0,0,0,0 +33.83,51,0,10,0,0,0,0,0,0 +33.84,51,0,10,0,0,0,0,0,0 +33.85,51,0,10,0,0,0,0,0,0 +33.86,51,0,10,0,0,0,0,0,0 +33.87,51,0,10,0,0,0,0,0,0 +33.88,51,0,10,0,0,0,0,0,0 +33.89,51,0,10,0,0,0,0,0,0 +33.9,51,0,10,0,0,0,0,0,0 +33.91,51,0,10,0,0,0,0,0,0 +33.92,51,0,10,0,0,0,0,0,0 +33.93,51,0,10,0,0,0,0,0,0 +33.94,51,0,10,0,0,0,0,0,0 +33.95,51,0,10,0,0,0,0,0,0 +33.96,51,0,10,0,0,0,0,0,0 +33.97,51,0,10,0,0,0,0,0,0 +33.98,51,0,10,0,0,0,0,0,0 +33.99,51,0,10,0,0,0,0,0,0 +34,51,0,10,0,0,0,0,0,0 +34.01,51,0,10,0,0,0,0,0,0 +34.02,51,0,10,0,0,0,0,0,0 +34.03,51,0,10,0,0,0,0,0,0 +34.04,51,0,10,0,0,0,0,0,0 +34.05,51,0,10,0,0,0,0,0,0 +34.06,51,0,10,0,0,0,0,0,0 +34.07,51,0,10,0,0,0,0,0,0 +34.08,51,0,10,0,0,0,0,0,0 +34.09,51,0,10,0,0,0,0,0,0 +34.1,51,0,10,0,0,0,0,0,0 +34.11,51,0,10,0,0,0,0,0,0 +34.12,51,0,10,0,0,0,0,0,0 +34.13,51,0,10,0,0,0,0,0,0 +34.14,51,0,10,0,0,0,0,0,0 +34.15,51,0,10,0,0,0,0,0,0 +34.16,51,0,10,0,0,0,0,0,0 +34.17,51,0,10,0,0,0,0,0,0 +34.18,51,0,10,0,0,0,0,0,0 +34.19,51,0,10,0,0,0,0,0,0 +34.2,51,0,10,0,0,0,0,0,0 +34.21,51,0,10,0,0,0,0,0,0 +34.22,51,0,10,0,0,0,0,0,0 +34.23,51,0,10,0,0,0,0,0,0 +34.24,51,0,10,0,0,0,0,0,0 +34.25,51,0,10,0,0,0,0,0,0 +34.26,51,0,10,0,0,0,0,0,0 +34.27,51,0,10,0,0,0,0,0,0 +34.28,51,0,10,0,0,0,0,0,0 +34.29,51,0,10,0,0,0,0,0,0 +34.3,51,0,10,0,0,0,0,0,0 +34.31,51,0,10,0,0,0,0,0,0 +34.32,51,0,10,0,0,0,0,0,0 +34.33,51,0,10,0,0,0,0,0,0 +34.34,51,0,10,0,0,0,0,0,0 +34.35,51,0,10,0,0,0,0,0,0 +34.36,51,0,10,0,0,0,0,0,0 +34.37,51,0,10,0,0,0,0,0,0 +34.38,51,0,10,0,0,0,0,0,0 +34.39,51,0,10,0,0,0,0,0,0 +34.4,51,0,10,0,0,0,0,0,0 +34.41,51,0,10,0,0,0,0,0,0 +34.42,51,0,10,0,0,0,0,0,0 +34.43,51,0,10,0,0,0,0,0,0 +34.44,51,0,10,0,0,0,0,0,0 +34.45,51,0,10,0,0,0,0,0,0 +34.46,51,0,10,0,0,0,0,0,0 +34.47,51,0,10,0,0,0,0,0,0 +34.48,51,0,10,0,0,0,0,0,0 +34.49,51,0,10,0,0,0,0,0,0 +34.5,51,0,10,0,0,0,0,0,0 +34.51,51,0,10,0,0,0,0,0,0 +34.52,51,0,10,0,0,0,0,0,0 +34.53,51,0,10,0,0,0,0,0,0 +34.54,51,0,10,0,0,0,0,0,0 +34.55,51,0,10,0,0,0,0,0,0 +34.56,51,0,10,0,0,0,0,0,0 +34.57,51,0,10,0,0,0,0,0,0 +34.58,51,0,10,0,0,0,0,0,0 +34.59,51,0,10,0,0,0,0,0,0 +34.6,51,0,10,0,0,0,0,0,0 +34.61,51,0,10,0,0,0,0,0,0 +34.62,51,0,10,0,0,0,0,0,0 +34.63,51,0,10,0,0,0,0,0,0 +34.64,51,0,10,0,0,0,0,0,0 +34.65,51,0,10,0,0,0,0,0,0 +34.66,51,0,10,0,0,0,0,0,0 +34.67,51,0,10,0,0,0,0,0,0 +34.68,51,0,10,0,0,0,0,0,0 +34.69,51,0,10,0,0,0,0,0,0 +34.7,51,0,10,0,0,0,0,0,0 +34.71,51,0,10,0,0,0,0,0,0 +34.72,51,0,10,0,0,0,0,0,0 +34.73,51,0,10,0,0,0,0,0,0 +34.74,51,0,10,0,0,0,0,0,0 +34.75,51,0,10,0,0,0,0,0,0 +34.76,51,0,10,0,0,0,0,0,0 +34.77,51,0,10,0,0,0,0,0,0 +34.78,51,0,10,0,0,0,0,0,0 +34.79,51,0,10,0,0,0,0,0,0 +34.8,51,0,10,0,0,0,0,0,0 +34.81,51,0,10,0,0,0,0,0,0 +34.82,51,0,10,0,0,0,0,0,0 +34.83,51,0,10,0,0,0,0,0,0 +34.84,51,0,10,0,0,0,0,0,0 +34.85,51,0,10,0,0,0,0,0,0 +34.86,51,0,10,0,0,0,0,0,0 +34.87,51,0,10,0,0,0,0,0,0 +34.88,51,0,10,0,0,0,0,0,0 +34.89,51,0,10,0,0,0,0,0,0 +34.9,51,0,10,0,0,0,0,0,0 +34.91,51,0,10,0,0,0,0,0,0 +34.92,51,0,10,0,0,0,0,0,0 +34.93,51,0,10,0,0,0,0,0,0 +34.94,51,0,10,0,0,0,0,0,0 +34.95,51,0,10,0,0,0,0,0,0 +34.96,51,0,10,0,0,0,0,0,0 +34.97,51,0,10,0,0,0,0,0,0 +34.98,51,0,10,0,0,0,0,0,0 +34.99,51,0,10,0,0,0,0,0,0 +35,51,0,10,0,0,0,0,0,0 +35.01,51,0,10,0,0,0,0,0,0 +35.02,51,0,10,0,0,0,0,0,0 +35.03,51,0,10,0,0,0,0,0,0 +35.04,51,0,10,0,0,0,0,0,0 +35.05,51,0,10,0,0,0,0,0,0 +35.06,51,0,10,0,0,0,0,0,0 +35.07,51,0,10,0,0,0,0,0,0 +35.08,51,0,10,0,0,0,0,0,0 +35.09,51,0,10,0,0,0,0,0,0 +35.1,51,0,10,0,0,0,0,0,0 +35.11,51,0,10,0,0,0,0,0,0 +35.12,51,0,10,0,0,0,0,0,0 +35.13,51,0,10,0,0,0,0,0,0 +35.14,51,0,10,0,0,0,0,0,0 +35.15,51,0,10,0,0,0,0,0,0 +35.16,51,0,10,0,0,0,0,0,0 +35.17,51,0,10,0,0,0,0,0,0 +35.18,51,0,10,0,0,0,0,0,0 +35.19,51,0,10,0,0,0,0,0,0 +35.2,51,0,10,0,0,0,0,0,0 +35.21,51,0,10,0,0,0,0,0,0 +35.22,51,0,10,0,0,0,0,0,0 +35.23,51,0,10,0,0,0,0,0,0 +35.24,51,0,10,0,0,0,0,0,0 +35.25,51,0,10,0,0,0,0,0,0 +35.26,51,0,10,0,0,0,0,0,0 +35.27,51,0,10,0,0,0,0,0,0 +35.28,51,0,10,0,0,0,0,0,0 +35.29,51,0,10,0,0,0,0,0,0 +35.3,51,0,10,0,0,0,0,0,0 +35.31,51,0,10,0,0,0,0,0,0 +35.32,51,0,10,0,0,0,0,0,0 +35.33,51,0,10,0,0,0,0,0,0 +35.34,51,0,10,0,0,0,0,0,0 +35.35,51,0,10,0,0,0,0,0,0 +35.36,51,0,10,0,0,0,0,0,0 +35.37,51,0,10,0,0,0,0,0,0 +35.38,51,0,10,0,0,0,0,0,0 +35.39,51,0,10,0,0,0,0,0,0 +35.4,51,0,10,0,0,0,0,0,0 +35.41,51,0,10,0,0,0,0,0,0 +35.42,51,0,10,0,0,0,0,0,0 +35.43,51,0,10,0,0,0,0,0,0 +35.44,51,0,10,0,0,0,0,0,0 +35.45,51,0,10,0,0,0,0,0,0 +35.46,51,0,10,0,0,0,0,0,0 +35.47,51,0,10,0,0,0,0,0,0 +35.48,51,0,10,0,0,0,0,0,0 +35.49,51,0,10,0,0,0,0,0,0 +35.5,51,0,10,0,0,0,0,0,0 +35.51,51,0,10,0,0,0,0,0,0 +35.52,51,0,10,0,0,0,0,0,0 +35.53,51,0,10,0,0,0,0,0,0 +35.54,51,0,10,0,0,0,0,0,0 +35.55,51,0,10,0,0,0,0,0,0 +35.56,51,0,10,0,0,0,0,0,0 +35.57,51,0,10,0,0,0,0,0,0 +35.58,51,0,10,0,0,0,0,0,0 +35.59,51,0,10,0,0,0,0,0,0 +35.6,51,0,10,0,0,0,0,0,0 +35.61,51,0,10,0,0,0,0,0,0 +35.62,51,0,10,0,0,0,0,0,0 +35.63,51,0,10,0,0,0,0,0,0 +35.64,51,0,10,0,0,0,0,0,0 +35.65,51,0,10,0,0,0,0,0,0 +35.66,51,0,10,0,0,0,0,0,0 +35.67,51,0,10,0,0,0,0,0,0 +35.68,51,0,10,0,0,0,0,0,0 +35.69,51,0,10,0,0,0,0,0,0 +35.7,51,0,10,0,0,0,0,0,0 +35.71,51,0,10,0,0,0,0,0,0 +35.72,51,0,10,0,0,0,0,0,0 +35.73,51,0,10,0,0,0,0,0,0 +35.74,51,0,10,0,0,0,0,0,0 +35.75,51,0,10,0,0,0,0,0,0 +35.76,51,0,10,0,0,0,0,0,0 +35.77,51,0,10,0,0,0,0,0,0 +35.78,51,0,10,0,0,0,0,0,0 +35.79,51,0,10,0,0,0,0,0,0 +35.8,51,0,10,0,0,0,0,0,0 +35.81,51,0,10,0,0,0,0,0,0 +35.82,51,0,10,0,0,0,0,0,0 +35.83,51,0,10,0,0,0,0,0,0 +35.84,51,0,10,0,0,0,0,0,0 +35.85,51,0,10,0,0,0,0,0,0 +35.86,51,0,10,0,0,0,0,0,0 +35.87,51,0,10,0,0,0,0,0,0 +35.88,51,0,10,0,0,0,0,0,0 +35.89,51,0,10,0,0,0,0,0,0 +35.9,51,0,10,0,0,0,0,0,0 +35.91,51,0,10,0,0,0,0,0,0 +35.92,51,0,10,0,0,0,0,0,0 +35.93,51,0,10,0,0,0,0,0,0 +35.94,51,0,10,0,0,0,0,0,0 +35.95,51,0,10,0,0,0,0,0,0 +35.96,51,0,10,0,0,0,0,0,0 +35.97,51,0,10,0,0,0,0,0,0 +35.98,51,0,10,0,0,0,0,0,0 +35.99,51,0,10,0,0,0,0,0,0 +36,51,0,10,0,0,0,0,0,0 +36.01,51,0,10,0,0,0,0,0,0 +36.02,51,0,10,0,0,0,0,0,0 +36.03,51,0,10,0,0,0,0,0,0 +36.04,51,0,10,0,0,0,0,0,0 +36.05,51,0,10,0,0,0,0,0,0 +36.06,51,0,10,0,0,0,0,0,0 +36.07,51,0,10,0,0,0,0,0,0 +36.08,51,0,10,0,0,0,0,0,0 +36.09,51,0,10,0,0,0,0,0,0 +36.1,51,0,10,0,0,0,0,0,0 +36.11,51,0,10,0,0,0,0,0,0 +36.12,51,0,10,0,0,0,0,0,0 +36.13,51,0,10,0,0,0,0,0,0 +36.14,51,0,10,0,0,0,0,0,0 +36.15,51,0,10,0,0,0,0,0,0 +36.16,51,0,10,0,0,0,0,0,0 +36.17,51,0,10,0,0,0,0,0,0 +36.18,51,0,10,0,0,0,0,0,0 +36.19,51,0,10,0,0,0,0,0,0 +36.2,51,0,10,0,0,0,0,0,0 +36.21,51,0,10,0,0,0,0,0,0 +36.22,51,0,10,0,0,0,0,0,0 +36.23,51,0,10,0,0,0,0,0,0 +36.24,51,0,10,0,0,0,0,0,0 +36.25,51,0,10,0,0,0,0,0,0 +36.26,51,0,10,0,0,0,0,0,0 +36.27,51,0,10,0,0,0,0,0,0 +36.28,51,0,10,0,0,0,0,0,0 +36.29,51,0,10,0,0,0,0,0,0 +36.3,51,0,10,0,0,0,0,0,0 +36.31,51,0,10,0,0,0,0,0,0 +36.32,51,0,10,0,0,0,0,0,0 +36.33,51,0,10,0,0,0,0,0,0 +36.34,51,0,10,0,0,0,0,0,0 +36.35,51,0,10,0,0,0,0,0,0 +36.36,51,0,10,0,0,0,0,0,0 +36.37,51,0,10,0,0,0,0,0,0 +36.38,51,0,10,0,0,0,0,0,0 +36.39,51,0,10,0,0,0,0,0,0 +36.4,51,0,10,0,0,0,0,0,0 +36.41,51,0,10,0,0,0,0,0,0 +36.42,51,0,10,0,0,0,0,0,0 +36.43,51,0,10,0,0,0,0,0,0 +36.44,51,0,10,0,0,0,0,0,0 +36.45,51,0,10,0,0,0,0,0,0 +36.46,51,0,10,0,0,0,0,0,0 +36.47,51,0,10,0,0,0,0,0,0 +36.48,51,0,10,0,0,0,0,0,0 +36.49,51,0,10,0,0,0,0,0,0 +36.5,51,0,10,0,0,0,0,0,0 +36.51,51,0,10,0,0,0,0,0,0 +36.52,51,0,10,0,0,0,0,0,0 +36.53,51,0,10,0,0,0,0,0,0 +36.54,51,0,10,0,0,0,0,0,0 +36.55,51,0,10,0,0,0,0,0,0 +36.56,51,0,10,0,0,0,0,0,0 +36.57,51,0,10,0,0,0,0,0,0 +36.58,51,0,10,0,0,0,0,0,0 +36.59,51,0,10,0,0,0,0,0,0 +36.6,51,0,10,0,0,0,0,0,0 +36.61,51,0,10,0,0,0,0,0,0 +36.62,51,0,10,0,0,0,0,0,0 +36.63,51,0,10,0,0,0,0,0,0 +36.64,51,0,10,0,0,0,0,0,0 +36.65,51,0,10,0,0,0,0,0,0 +36.66,51,0,10,0,0,0,0,0,0 +36.67,51,0,10,0,0,0,0,0,0 +36.68,51,0,10,0,0,0,0,0,0 +36.69,51,0,10,0,0,0,0,0,0 +36.7,51,0,10,0,0,0,0,0,0 +36.71,51,0,10,0,0,0,0,0,0 +36.72,51,0,10,0,0,0,0,0,0 +36.73,51,0,10,0,0,0,0,0,0 +36.74,51,0,10,0,0,0,0,0,0 +36.75,51,0,10,0,0,0,0,0,0 +36.76,51,0,10,0,0,0,0,0,0 +36.77,51,0,10,0,0,0,0,0,0 +36.78,51,0,10,0,0,0,0,0,0 +36.79,51,0,10,0,0,0,0,0,0 +36.8,51,0,10,0,0,0,0,0,0 +36.81,51,0,10,0,0,0,0,0,0 +36.82,51,0,10,0,0,0,0,0,0 +36.83,51,0,10,0,0,0,0,0,0 +36.84,51,0,10,0,0,0,0,0,0 +36.85,51,0,10,0,0,0,0,0,0 +36.86,51,0,10,0,0,0,0,0,0 +36.87,51,0,10,0,0,0,0,0,0 +36.88,51,0,10,0,0,0,0,0,0 +36.89,51,0,10,0,0,0,0,0,0 +36.9,51,0,10,0,0,0,0,0,0 +36.91,51,0,10,0,0,0,0,0,0 +36.92,51,0,10,0,0,0,0,0,0 +36.93,51,0,10,0,0,0,0,0,0 +36.94,51,0,10,0,0,0,0,0,0 +36.95,51,0,10,0,0,0,0,0,0 +36.96,51,0,10,0,0,0,0,0,0 +36.97,51,0,10,0,0,0,0,0,0 +36.98,51,0,10,0,0,0,0,0,0 +36.99,51,0,10,0,0,0,0,0,0 +37,51,0,10,0,0,0,0,0,0 +37.01,51,0,10,0,0,0,0,0,0 +37.02,51,0,10,0,0,0,0,0,0 +37.03,51,0,10,0,0,0,0,0,0 +37.04,51,0,10,0,0,0,0,0,0 +37.05,51,0,10,0,0,0,0,0,0 +37.06,51,0,10,0,0,0,0,0,0 +37.07,51,0,10,0,0,0,0,0,0 +37.08,51,0,10,0,0,0,0,0,0 +37.09,51,0,10,0,0,0,0,0,0 +37.1,51,0,10,0,0,0,0,0,0 +37.11,51,0,10,0,0,0,0,0,0 +37.12,51,0,10,0,0,0,0,0,0 +37.13,51,0,10,0,0,0,0,0,0 +37.14,51,0,10,0,0,0,0,0,0 +37.15,51,0,10,0,0,0,0,0,0 +37.16,51,0,10,0,0,0,0,0,0 +37.17,51,0,10,0,0,0,0,0,0 +37.18,51,0,10,0,0,0,0,0,0 +37.19,51,0,10,0,0,0,0,0,0 +37.2,51,0,10,0,0,0,0,0,0 +37.21,51,0,10,0,0,0,0,0,0 +37.22,51,0,10,0,0,0,0,0,0 +37.23,51,0,10,0,0,0,0,0,0 +37.24,51,0,10,0,0,0,0,0,0 +37.25,51,0,10,0,0,0,0,0,0 +37.26,51,0,10,0,0,0,0,0,0 +37.27,51,0,10,0,0,0,0,0,0 +37.28,51,0,10,0,0,0,0,0,0 +37.29,51,0,10,0,0,0,0,0,0 +37.3,51,0,10,0,0,0,0,0,0 +37.31,51,0,10,0,0,0,0,0,0 +37.32,51,0,10,0,0,0,0,0,0 +37.33,51,0,10,0,0,0,0,0,0 +37.34,51,0,10,0,0,0,0,0,0 +37.35,51,0,10,0,0,0,0,0,0 +37.36,51,0,10,0,0,0,0,0,0 +37.37,51,0,10,0,0,0,0,0,0 +37.38,51,0,10,0,0,0,0,0,0 +37.39,51,0,10,0,0,0,0,0,0 +37.4,51,0,10,0,0,0,0,0,0 +37.41,51,0,10,0,0,0,0,0,0 +37.42,51,0,10,0,0,0,0,0,0 +37.43,51,0,10,0,0,0,0,0,0 +37.44,51,0,10,0,0,0,0,0,0 +37.45,51,0,10,0,0,0,0,0,0 +37.46,51,0,10,0,0,0,0,0,0 +37.47,51,0,10,0,0,0,0,0,0 +37.48,51,0,10,0,0,0,0,0,0 +37.49,51,0,10,0,0,0,0,0,0 +37.5,51,0,10,0,0,0,0,0,0 +37.51,51,0,10,0,0,0,0,0,0 +37.52,51,0,10,0,0,0,0,0,0 +37.53,51,0,10,0,0,0,0,0,0 +37.54,51,0,10,0,0,0,0,0,0 +37.55,51,0,10,0,0,0,0,0,0 +37.56,51,0,10,0,0,0,0,0,0 +37.57,51,0,10,0,0,0,0,0,0 +37.58,51,0,10,0,0,0,0,0,0 +37.59,51,0,10,0,0,0,0,0,0 +37.6,51,0,10,0,0,0,0,0,0 +37.61,51,0,10,0,0,0,0,0,0 +37.62,51,0,10,0,0,0,0,0,0 +37.63,51,0,10,0,0,0,0,0,0 +37.64,51,0,10,0,0,0,0,0,0 +37.65,51,0,10,0,0,0,0,0,0 +37.66,51,0,10,0,0,0,0,0,0 +37.67,51,0,10,0,0,0,0,0,0 +37.68,51,0,10,0,0,0,0,0,0 +37.69,51,0,10,0,0,0,0,0,0 +37.7,51,0,10,0,0,0,0,0,0 +37.71,51,0,10,0,0,0,0,0,0 +37.72,51,0,10,0,0,0,0,0,0 +37.73,51,0,10,0,0,0,0,0,0 +37.74,51,0,10,0,0,0,0,0,0 +37.75,51,0,10,0,0,0,0,0,0 +37.76,51,0,10,0,0,0,0,0,0 +37.77,51,0,10,0,0,0,0,0,0 +37.78,51,0,10,0,0,0,0,0,0 +37.79,51,0,10,0,0,0,0,0,0 +37.8,51,0,10,0,0,0,0,0,0 +37.81,51,0,10,0,0,0,0,0,0 +37.82,51,0,10,0,0,0,0,0,0 +37.83,51,0,10,0,0,0,0,0,0 +37.84,51,0,10,0,0,0,0,0,0 +37.85,51,0,10,0,0,0,0,0,0 +37.86,51,0,10,0,0,0,0,0,0 +37.87,51,0,10,0,0,0,0,0,0 +37.88,51,0,10,0,0,0,0,0,0 +37.89,51,0,10,0,0,0,0,0,0 +37.9,51,0,10,0,0,0,0,0,0 +37.91,51,0,10,0,0,0,0,0,0 +37.92,51,0,10,0,0,0,0,0,0 +37.93,51,0,10,0,0,0,0,0,0 +37.94,51,0,10,0,0,0,0,0,0 +37.95,51,0,10,0,0,0,0,0,0 +37.96,51,0,10,0,0,0,0,0,0 +37.97,51,0,10,0,0,0,0,0,0 +37.98,51,0,10,0,0,0,0,0,0 +37.99,51,0,10,0,0,0,0,0,0 +38,51,0,10,0,0,0,0,0,0 +38.01,51,0,10,0,0,0,0,0,0 +38.02,51,0,10,0,0,0,0,0,0 +38.03,51,0,10,0,0,0,0,0,0 +38.04,51,0,10,0,0,0,0,0,0 +38.05,51,0,10,0,0,0,0,0,0 +38.06,51,0,10,0,0,0,0,0,0 +38.07,51,0,10,0,0,0,0,0,0 +38.08,51,0,10,0,0,0,0,0,0 +38.09,51,0,10,0,0,0,0,0,0 +38.1,51,0,10,0,0,0,0,0,0 +38.11,51,0,10,0,0,0,0,0,0 +38.12,51,0,10,0,0,0,0,0,0 +38.13,51,0,10,0,0,0,0,0,0 +38.14,51,0,10,0,0,0,0,0,0 +38.15,51,0,10,0,0,0,0,0,0 +38.16,51,0,10,0,0,0,0,0,0 +38.17,51,0,10,0,0,0,0,0,0 +38.18,51,0,10,0,0,0,0,0,0 +38.19,51,0,10,0,0,0,0,0,0 +38.2,51,0,10,0,0,0,0,0,0 +38.21,51,0,10,0,0,0,0,0,0 +38.22,51,0,10,0,0,0,0,0,0 +38.23,51,0,10,0,0,0,0,0,0 +38.24,51,0,10,0,0,0,0,0,0 +38.25,51,0,10,0,0,0,0,0,0 +38.26,51,0,10,0,0,0,0,0,0 +38.27,51,0,10,0,0,0,0,0,0 +38.28,51,0,10,0,0,0,0,0,0 +38.29,51,0,10,0,0,0,0,0,0 +38.3,51,0,10,0,0,0,0,0,0 +38.31,51,0,10,0,0,0,0,0,0 +38.32,51,0,10,0,0,0,0,0,0 +38.33,51,0,10,0,0,0,0,0,0 +38.34,51,0,10,0,0,0,0,0,0 +38.35,51,0,10,0,0,0,0,0,0 +38.36,51,0,10,0,0,0,0,0,0 +38.37,51,0,10,0,0,0,0,0,0 +38.38,51,0,10,0,0,0,0,0,0 +38.39,51,0,10,0,0,0,0,0,0 +38.4,51,0,10,0,0,0,0,0,0 +38.41,51,0,10,0,0,0,0,0,0 +38.42,51,0,10,0,0,0,0,0,0 +38.43,51,0,10,0,0,0,0,0,0 +38.44,51,0,10,0,0,0,0,0,0 +38.45,51,0,10,0,0,0,0,0,0 +38.46,51,0,10,0,0,0,0,0,0 +38.47,51,0,10,0,0,0,0,0,0 +38.48,51,0,10,0,0,0,0,0,0 +38.49,51,0,10,0,0,0,0,0,0 +38.5,51,0,10,0,0,0,0,0,0 +38.51,51,0,10,0,0,0,0,0,0 +38.52,51,0,10,0,0,0,0,0,0 +38.53,51,0,10,0,0,0,0,0,0 +38.54,51,0,10,0,0,0,0,0,0 +38.55,51,0,10,0,0,0,0,0,0 +38.56,51,0,10,0,0,0,0,0,0 +38.57,51,0,10,0,0,0,0,0,0 +38.58,51,0,10,0,0,0,0,0,0 +38.59,51,0,10,0,0,0,0,0,0 +38.6,51,0,10,0,0,0,0,0,0 +38.61,51,0,10,0,0,0,0,0,0 +38.62,51,0,10,0,0,0,0,0,0 +38.63,51,0,10,0,0,0,0,0,0 +38.64,51,0,10,0,0,0,0,0,0 +38.65,51,0,10,0,0,0,0,0,0 +38.66,51,0,10,0,0,0,0,0,0 +38.67,51,0,10,0,0,0,0,0,0 +38.68,51,0,10,0,0,0,0,0,0 +38.69,51,0,10,0,0,0,0,0,0 +38.7,51,0,10,0,0,0,0,0,0 +38.71,51,0,10,0,0,0,0,0,0 +38.72,51,0,10,0,0,0,0,0,0 +38.73,51,0,10,0,0,0,0,0,0 +38.74,51,0,10,0,0,0,0,0,0 +38.75,51,0,10,0,0,0,0,0,0 +38.76,51,0,10,0,0,0,0,0,0 +38.77,51,0,10,0,0,0,0,0,0 +38.78,51,0,10,0,0,0,0,0,0 +38.79,51,0,10,0,0,0,0,0,0 +38.8,51,0,10,0,0,0,0,0,0 +38.81,51,0,10,0,0,0,0,0,0 +38.82,51,0,10,0,0,0,0,0,0 +38.83,51,0,10,0,0,0,0,0,0 +38.84,51,0,10,0,0,0,0,0,0 +38.85,51,0,10,0,0,0,0,0,0 +38.86,51,0,10,0,0,0,0,0,0 +38.87,51,0,10,0,0,0,0,0,0 +38.88,51,0,10,0,0,0,0,0,0 +38.89,51,0,10,0,0,0,0,0,0 +38.9,51,0,10,0,0,0,0,0,0 +38.91,51,0,10,0,0,0,0,0,0 +38.92,51,0,10,0,0,0,0,0,0 +38.93,51,0,10,0,0,0,0,0,0 +38.94,51,0,10,0,0,0,0,0,0 +38.95,51,0,10,0,0,0,0,0,0 +38.96,51,0,10,0,0,0,0,0,0 +38.97,51,0,10,0,0,0,0,0,0 +38.98,51,0,10,0,0,0,0,0,0 +38.99,51,0,10,0,0,0,0,0,0 +39,51,0,10,0,0,0,0,0,0 +39.01,51,0,10,0,0,0,0,0,0 +39.02,51,0,10,0,0,0,0,0,0 +39.03,51,0,10,0,0,0,0,0,0 +39.04,51,0,10,0,0,0,0,0,0 +39.05,51,0,10,0,0,0,0,0,0 +39.06,51,0,10,0,0,0,0,0,0 +39.07,51,0,10,0,0,0,0,0,0 +39.08,51,0,10,0,0,0,0,0,0 +39.09,51,0,10,0,0,0,0,0,0 +39.1,51,0,10,0,0,0,0,0,0 +39.11,51,0,10,0,0,0,0,0,0 +39.12,51,0,10,0,0,0,0,0,0 +39.13,51,0,10,0,0,0,0,0,0 +39.14,51,0,10,0,0,0,0,0,0 +39.15,51,0,10,0,0,0,0,0,0 +39.16,51,0,10,0,0,0,0,0,0 +39.17,51,0,10,0,0,0,0,0,0 +39.18,51,0,10,0,0,0,0,0,0 +39.19,51,0,10,0,0,0,0,0,0 +39.2,51,0,10,0,0,0,0,0,0 +39.21,51,0,10,0,0,0,0,0,0 +39.22,51,0,10,0,0,0,0,0,0 +39.23,51,0,10,0,0,0,0,0,0 +39.24,51,0,10,0,0,0,0,0,0 +39.25,51,0,10,0,0,0,0,0,0 +39.26,51,0,10,0,0,0,0,0,0 +39.27,51,0,10,0,0,0,0,0,0 +39.28,51,0,10,0,0,0,0,0,0 +39.29,51,0,10,0,0,0,0,0,0 +39.3,51,0,10,0,0,0,0,0,0 +39.31,51,0,10,0,0,0,0,0,0 +39.32,51,0,10,0,0,0,0,0,0 +39.33,51,0,10,0,0,0,0,0,0 +39.34,51,0,10,0,0,0,0,0,0 +39.35,51,0,10,0,0,0,0,0,0 +39.36,51,0,10,0,0,0,0,0,0 +39.37,51,0,10,0,0,0,0,0,0 +39.38,51,0,10,0,0,0,0,0,0 +39.39,51,0,10,0,0,0,0,0,0 +39.4,51,0,10,0,0,0,0,0,0 +39.41,51,0,10,0,0,0,0,0,0 +39.42,51,0,10,0,0,0,0,0,0 +39.43,51,0,10,0,0,0,0,0,0 +39.44,51,0,10,0,0,0,0,0,0 +39.45,51,0,10,0,0,0,0,0,0 +39.46,51,0,10,0,0,0,0,0,0 +39.47,51,0,10,0,0,0,0,0,0 +39.48,51,0,10,0,0,0,0,0,0 +39.49,51,0,10,0,0,0,0,0,0 +39.5,51,0,10,0,0,0,0,0,0 +39.51,51,0,10,0,0,0,0,0,0 +39.52,51,0,10,0,0,0,0,0,0 +39.53,51,0,10,0,0,0,0,0,0 +39.54,51,0,10,0,0,0,0,0,0 +39.55,51,0,10,0,0,0,0,0,0 +39.56,51,0,10,0,0,0,0,0,0 +39.57,51,0,10,0,0,0,0,0,0 +39.58,51,0,10,0,0,0,0,0,0 +39.59,51,0,10,0,0,0,0,0,0 +39.6,51,0,10,0,0,0,0,0,0 +39.61,51,0,10,0,0,0,0,0,0 +39.62,51,0,10,0,0,0,0,0,0 +39.63,51,0,10,0,0,0,0,0,0 +39.64,51,0,10,0,0,0,0,0,0 +39.65,51,0,10,0,0,0,0,0,0 +39.66,51,0,10,0,0,0,0,0,0 +39.67,51,0,10,0,0,0,0,0,0 +39.68,51,0,10,0,0,0,0,0,0 +39.69,51,0,10,0,0,0,0,0,0 +39.7,51,0,10,0,0,0,0,0,0 +39.71,51,0,10,0,0,0,0,0,0 +39.72,51,0,10,0,0,0,0,0,0 +39.73,51,0,10,0,0,0,0,0,0 +39.74,51,0,10,0,0,0,0,0,0 +39.75,51,0,10,0,0,0,0,0,0 +39.76,51,0,10,0,0,0,0,0,0 +39.77,51,0,10,0,0,0,0,0,0 +39.78,51,0,10,0,0,0,0,0,0 +39.79,51,0,10,0,0,0,0,0,0 +39.8,51,0,10,0,0,0,0,0,0 +39.81,51,0,10,0,0,0,0,0,0 +39.82,51,0,10,0,0,0,0,0,0 +39.83,51,0,10,0,0,0,0,0,0 +39.84,51,0,10,0,0,0,0,0,0 +39.85,51,0,10,0,0,0,0,0,0 +39.86,51,0,10,0,0,0,0,0,0 +39.87,51,0,10,0,0,0,0,0,0 +39.88,51,0,10,0,0,0,0,0,0 +39.89,51,0,10,0,0,0,0,0,0 +39.9,51,0,10,0,0,0,0,0,0 +39.91,51,0,10,0,0,0,0,0,0 +39.92,51,0,10,0,0,0,0,0,0 +39.93,51,0,10,0,0,0,0,0,0 +39.94,51,0,10,0,0,0,0,0,0 +39.95,51,0,10,0,0,0,0,0,0 +39.96,51,0,10,0,0,0,0,0,0 +39.97,51,0,10,0,0,0,0,0,0 +39.98,51,0,10,0,0,0,0,0,0 +39.99,51,0,10,0,0,0,0,0,0 +40,51,0,10,0,0,0,0,0,0 +40.01,51,0,10,0,0,0,0,0,0 +40.02,51,0,10,0,0,0,0,0,0 +40.03,51,0,10,0,0,0,0,0,0 +40.04,51,0,10,0,0,0,0,0,0 +40.05,51,0,10,0,0,0,0,0,0 +40.06,51,0,10,0,0,0,0,0,0 +40.07,51,0,10,0,0,0,0,0,0 +40.08,51,0,10,0,0,0,0,0,0 +40.09,51,0,10,0,0,0,0,0,0 +40.1,51,0,10,0,0,0,0,0,0 +40.11,51,0,10,0,0,0,0,0,0 +40.12,51,0,10,0,0,0,0,0,0 +40.13,51,0,10,0,0,0,0,0,0 +40.14,51,0,10,0,0,0,0,0,0 +40.15,51,0,10,0,0,0,0,0,0 +40.16,51,0,10,0,0,0,0,0,0 +40.17,51,0,10,0,0,0,0,0,0 +40.18,51,0,10,0,0,0,0,0,0 +40.19,51,0,10,0,0,0,0,0,0 +40.2,51,0,10,0,0,0,0,0,0 +40.21,51,0,10,0,0,0,0,0,0 +40.22,51,0,10,0,0,0,0,0,0 +40.23,51,0,10,0,0,0,0,0,0 +40.24,51,0,10,0,0,0,0,0,0 +40.25,51,0,10,0,0,0,0,0,0 +40.26,51,0,10,0,0,0,0,0,0 +40.27,51,0,10,0,0,0,0,0,0 +40.28,51,0,10,0,0,0,0,0,0 +40.29,51,0,10,0,0,0,0,0,0 +40.3,51,0,10,0,0,0,0,0,0 +40.31,51,0,10,0,0,0,0,0,0 +40.32,51,0,10,0,0,0,0,0,0 +40.33,51,0,10,0,0,0,0,0,0 +40.34,51,0,10,0,0,0,0,0,0 +40.35,51,0,10,0,0,0,0,0,0 +40.36,51,0,10,0,0,0,0,0,0 +40.37,51,0,10,0,0,0,0,0,0 +40.38,51,0,10,0,0,0,0,0,0 +40.39,51,0,10,0,0,0,0,0,0 +40.4,51,0,10,0,0,0,0,0,0 +40.41,51,0,10,0,0,0,0,0,0 +40.42,51,0,10,0,0,0,0,0,0 +40.43,51,0,10,0,0,0,0,0,0 +40.44,51,0,10,0,0,0,0,0,0 +40.45,51,0,10,0,0,0,0,0,0 +40.46,51,0,10,0,0,0,0,0,0 +40.47,51,0,10,0,0,0,0,0,0 +40.48,51,0,10,0,0,0,0,0,0 +40.49,51,0,10,0,0,0,0,0,0 +40.5,51,0,10,0,0,0,0,0,0 +40.51,51,0,10,0,0,0,0,0,0 +40.52,51,0,10,0,0,0,0,0,0 +40.53,51,0,10,0,0,0,0,0,0 +40.54,51,0,10,0,0,0,0,0,0 +40.55,51,0,10,0,0,0,0,0,0 +40.56,51,0,10,0,0,0,0,0,0 +40.57,51,0,10,0,0,0,0,0,0 +40.58,51,0,10,0,0,0,0,0,0 +40.59,51,0,10,0,0,0,0,0,0 +40.6,51,0,10,0,0,0,0,0,0 +40.61,51,0,10,0,0,0,0,0,0 +40.62,51,0,10,0,0,0,0,0,0 +40.63,51,0,10,0,0,0,0,0,0 +40.64,51,0,10,0,0,0,0,0,0 +40.65,51,0,10,0,0,0,0,0,0 +40.66,51,0,10,0,0,0,0,0,0 +40.67,51,0,10,0,0,0,0,0,0 +40.68,51,0,10,0,0,0,0,0,0 +40.69,51,0,10,0,0,0,0,0,0 +40.7,51,0,10,0,0,0,0,0,0 +40.71,51,0,10,0,0,0,0,0,0 +40.72,51,0,10,0,0,0,0,0,0 +40.73,51,0,10,0,0,0,0,0,0 +40.74,51,0,10,0,0,0,0,0,0 +40.75,51,0,10,0,0,0,0,0,0 +40.76,51,0,10,0,0,0,0,0,0 +40.77,51,0,10,0,0,0,0,0,0 +40.78,51,0,10,0,0,0,0,0,0 +40.79,51,0,10,0,0,0,0,0,0 +40.8,51,0,10,0,0,0,0,0,0 +40.81,51,0,10,0,0,0,0,0,0 +40.82,51,0,10,0,0,0,0,0,0 +40.83,51,0,10,0,0,0,0,0,0 +40.84,51,0,10,0,0,0,0,0,0 +40.85,51,0,10,0,0,0,0,0,0 +40.86,51,0,10,0,0,0,0,0,0 +40.87,51,0,10,0,0,0,0,0,0 +40.88,51,0,10,0,0,0,0,0,0 +40.89,51,0,10,0,0,0,0,0,0 +40.9,51,0,10,0,0,0,0,0,0 +40.91,51,0,10,0,0,0,0,0,0 +40.92,51,0,10,0,0,0,0,0,0 +40.93,51,0,10,0,0,0,0,0,0 +40.94,51,0,10,0,0,0,0,0,0 +40.95,51,0,10,0,0,0,0,0,0 +40.96,51,0,10,0,0,0,0,0,0 +40.97,51,0,10,0,0,0,0,0,0 +40.98,51,0,10,0,0,0,0,0,0 +40.99,51,0,10,0,0,0,0,0,0 +41,51,0,10,0,0,0,0,0,0 +41.01,51,0,10,0,0,0,0,0,0 +41.02,51,0,10,0,0,0,0,0,0 +41.03,51,0,10,0,0,0,0,0,0 +41.04,51,0,10,0,0,0,0,0,0 +41.05,51,0,10,0,0,0,0,0,0 +41.06,51,0,10,0,0,0,0,0,0 +41.07,51,0,10,0,0,0,0,0,0 +41.08,51,0,10,0,0,0,0,0,0 +41.09,51,0,10,0,0,0,0,0,0 +41.1,51,0,10,0,0,0,0,0,0 +41.11,51,0,10,0,0,0,0,0,0 +41.12,51,0,10,0,0,0,0,0,0 +41.13,51,0,10,0,0,0,0,0,0 +41.14,51,0,10,0,0,0,0,0,0 +41.15,51,0,10,0,0,0,0,0,0 +41.16,51,0,10,0,0,0,0,0,0 +41.17,51,0,10,0,0,0,0,0,0 +41.18,51,0,10,0,0,0,0,0,0 +41.19,51,0,10,0,0,0,0,0,0 +41.2,51,0,10,0,0,0,0,0,0 +41.21,51,0,10,0,0,0,0,0,0 +41.22,51,0,10,0,0,0,0,0,0 +41.23,51,0,10,0,0,0,0,0,0 +41.24,51,0,10,0,0,0,0,0,0 +41.25,51,0,10,0,0,0,0,0,0 +41.26,51,0,10,0,0,0,0,0,0 +41.27,51,0,10,0,0,0,0,0,0 +41.28,51,0,10,0,0,0,0,0,0 +41.29,51,0,10,0,0,0,0,0,0 +41.3,51,0,10,0,0,0,0,0,0 +41.31,51,0,10,0,0,0,0,0,0 +41.32,51,0,10,0,0,0,0,0,0 +41.33,51,0,10,0,0,0,0,0,0 +41.34,51,0,10,0,0,0,0,0,0 +41.35,51,0,10,0,0,0,0,0,0 +41.36,51,0,10,0,0,0,0,0,0 +41.37,51,0,10,0,0,0,0,0,0 +41.38,51,0,10,0,0,0,0,0,0 +41.39,51,0,10,0,0,0,0,0,0 +41.4,51,0,10,0,0,0,0,0,0 +41.41,51,0,10,0,0,0,0,0,0 +41.42,51,0,10,0,0,0,0,0,0 +41.43,51,0,10,0,0,0,0,0,0 +41.44,51,0,10,0,0,0,0,0,0 +41.45,51,0,10,0,0,0,0,0,0 +41.46,51,0,10,0,0,0,0,0,0 +41.47,51,0,10,0,0,0,0,0,0 +41.48,51,0,10,0,0,0,0,0,0 +41.49,51,0,10,0,0,0,0,0,0 +41.5,51,0,10,0,0,0,0,0,0 +41.51,51,0,10,0,0,0,0,0,0 +41.52,51,0,10,0,0,0,0,0,0 +41.53,51,0,10,0,0,0,0,0,0 +41.54,51,0,10,0,0,0,0,0,0 +41.55,51,0,10,0,0,0,0,0,0 +41.56,51,0,10,0,0,0,0,0,0 +41.57,51,0,10,0,0,0,0,0,0 +41.58,51,0,10,0,0,0,0,0,0 +41.59,51,0,10,0,0,0,0,0,0 +41.6,51,0,10,0,0,0,0,0,0 +41.61,51,0,10,0,0,0,0,0,0 +41.62,51,0,10,0,0,0,0,0,0 +41.63,51,0,10,0,0,0,0,0,0 +41.64,51,0,10,0,0,0,0,0,0 +41.65,51,0,10,0,0,0,0,0,0 +41.66,51,0,10,0,0,0,0,0,0 +41.67,51,0,10,0,0,0,0,0,0 +41.68,51,0,10,0,0,0,0,0,0 +41.69,51,0,10,0,0,0,0,0,0 +41.7,51,0,10,0,0,0,0,0,0 +41.71,51,0,10,0,0,0,0,0,0 +41.72,51,0,10,0,0,0,0,0,0 +41.73,51,0,10,0,0,0,0,0,0 +41.74,51,0,10,0,0,0,0,0,0 +41.75,51,0,10,0,0,0,0,0,0 +41.76,51,0,10,0,0,0,0,0,0 +41.77,51,0,10,0,0,0,0,0,0 +41.78,51,0,10,0,0,0,0,0,0 +41.79,51,0,10,0,0,0,0,0,0 +41.8,51,0,10,0,0,0,0,0,0 +41.81,51,0,10,0,0,0,0,0,0 +41.82,51,0,10,0,0,0,0,0,0 +41.83,51,0,10,0,0,0,0,0,0 +41.84,51,0,10,0,0,0,0,0,0 +41.85,51,0,10,0,0,0,0,0,0 +41.86,51,0,10,0,0,0,0,0,0 +41.87,51,0,10,0,0,0,0,0,0 +41.88,51,0,10,0,0,0,0,0,0 +41.89,51,0,10,0,0,0,0,0,0 +41.9,51,0,10,0,0,0,0,0,0 +41.91,51,0,10,0,0,0,0,0,0 +41.92,51,0,10,0,0,0,0,0,0 +41.93,51,0,10,0,0,0,0,0,0 +41.94,51,0,10,0,0,0,0,0,0 +41.95,51,0,10,0,0,0,0,0,0 +41.96,51,0,10,0,0,0,0,0,0 +41.97,51,0,10,0,0,0,0,0,0 +41.98,51,0,10,0,0,0,0,0,0 +41.99,51,0,10,0,0,0,0,0,0 +42,51,0,10,0,0,0,0,0,0 +42.01,51,0,10,0,0,0,0,0,0 +42.02,51,0,10,0,0,0,0,0,0 +42.03,51,0,10,0,0,0,0,0,0 +42.04,51,0,10,0,0,0,0,0,0 +42.05,51,0,10,0,0,0,0,0,0 +42.06,51,0,10,0,0,0,0,0,0 +42.07,51,0,10,0,0,0,0,0,0 +42.08,51,0,10,0,0,0,0,0,0 +42.09,51,0,10,0,0,0,0,0,0 +42.1,51,0,10,0,0,0,0,0,0 +42.11,51,0,10,0,0,0,0,0,0 +42.12,51,0,10,0,0,0,0,0,0 +42.13,51,0,10,0,0,0,0,0,0 +42.14,51,0,10,0,0,0,0,0,0 +42.15,51,0,10,0,0,0,0,0,0 +42.16,51,0,10,0,0,0,0,0,0 +42.17,51,0,10,0,0,0,0,0,0 +42.18,51,0,10,0,0,0,0,0,0 +42.19,51,0,10,0,0,0,0,0,0 +42.2,51,0,10,0,0,0,0,0,0 +42.21,51,0,10,0,0,0,0,0,0 +42.22,51,0,10,0,0,0,0,0,0 +42.23,51,0,10,0,0,0,0,0,0 +42.24,51,0,10,0,0,0,0,0,0 +42.25,51,0,10,0,0,0,0,0,0 +42.26,51,0,10,0,0,0,0,0,0 +42.27,51,0,10,0,0,0,0,0,0 +42.28,51,0,10,0,0,0,0,0,0 +42.29,51,0,10,0,0,0,0,0,0 +42.3,51,0,10,0,0,0,0,0,0 +42.31,51,0,10,0,0,0,0,0,0 +42.32,51,0,10,0,0,0,0,0,0 +42.33,51,0,10,0,0,0,0,0,0 +42.34,51,0,10,0,0,0,0,0,0 +42.35,51,0,10,0,0,0,0,0,0 +42.36,51,0,10,0,0,0,0,0,0 +42.37,51,0,10,0,0,0,0,0,0 +42.38,51,0,10,0,0,0,0,0,0 +42.39,51,0,10,0,0,0,0,0,0 +42.4,51,0,10,0,0,0,0,0,0 +42.41,51,0,10,0,0,0,0,0,0 +42.42,51,0,10,0,0,0,0,0,0 +42.43,51,0,10,0,0,0,0,0,0 +42.44,51,0,10,0,0,0,0,0,0 +42.45,51,0,10,0,0,0,0,0,0 +42.46,51,0,10,0,0,0,0,0,0 +42.47,51,0,10,0,0,0,0,0,0 +42.48,51,0,10,0,0,0,0,0,0 +42.49,51,0,10,0,0,0,0,0,0 +42.5,51,0,10,0,0,0,0,0,0 +42.51,51,0,10,0,0,0,0,0,0 +42.52,51,0,10,0,0,0,0,0,0 +42.53,51,0,10,0,0,0,0,0,0 +42.54,51,0,10,0,0,0,0,0,0 +42.55,51,0,10,0,0,0,0,0,0 +42.56,51,0,10,0,0,0,0,0,0 +42.57,51,0,10,0,0,0,0,0,0 +42.58,51,0,10,0,0,0,0,0,0 +42.59,51,0,10,0,0,0,0,0,0 +42.6,51,0,10,0,0,0,0,0,0 +42.61,51,0,10,0,0,0,0,0,0 +42.62,51,0,10,0,0,0,0,0,0 +42.63,51,0,10,0,0,0,0,0,0 +42.64,51,0,10,0,0,0,0,0,0 +42.65,51,0,10,0,0,0,0,0,0 +42.66,51,0,10,0,0,0,0,0,0 +42.67,51,0,10,0,0,0,0,0,0 +42.68,51,0,10,0,0,0,0,0,0 +42.69,51,0,10,0,0,0,0,0,0 +42.7,51,0,10,0,0,0,0,0,0 +42.71,51,0,10,0,0,0,0,0,0 +42.72,51,0,10,0,0,0,0,0,0 +42.73,51,0,10,0,0,0,0,0,0 +42.74,51,0,10,0,0,0,0,0,0 +42.75,51,0,10,0,0,0,0,0,0 +42.76,51,0,10,0,0,0,0,0,0 +42.77,51,0,10,0,0,0,0,0,0 +42.78,51,0,10,0,0,0,0,0,0 +42.79,51,0,10,0,0,0,0,0,0 +42.8,51,0,10,0,0,0,0,0,0 +42.81,51,0,10,0,0,0,0,0,0 +42.82,51,0,10,0,0,0,0,0,0 +42.83,51,0,10,0,0,0,0,0,0 +42.84,51,0,10,0,0,0,0,0,0 +42.85,51,0,10,0,0,0,0,0,0 +42.86,51,0,10,0,0,0,0,0,0 +42.87,51,0,10,0,0,0,0,0,0 +42.88,51,0,10,0,0,0,0,0,0 +42.89,51,0,10,0,0,0,0,0,0 +42.9,51,0,10,0,0,0,0,0,0 +42.91,51,0,10,0,0,0,0,0,0 +42.92,51,0,10,0,0,0,0,0,0 +42.93,51,0,10,0,0,0,0,0,0 +42.94,51,0,10,0,0,0,0,0,0 +42.95,51,0,10,0,0,0,0,0,0 +42.96,51,0,10,0,0,0,0,0,0 +42.97,51,0,10,0,0,0,0,0,0 +42.98,51,0,10,0,0,0,0,0,0 +42.99,51,0,10,0,0,0,0,0,0 +43,51,0,10,0,0,0,0,0,0 +43.01,51,0,10,0,0,0,0,0,0 +43.02,51,0,10,0,0,0,0,0,0 +43.03,51,0,10,0,0,0,0,0,0 +43.04,51,0,10,0,0,0,0,0,0 +43.05,51,0,10,0,0,0,0,0,0 +43.06,51,0,10,0,0,0,0,0,0 +43.07,51,0,10,0,0,0,0,0,0 +43.08,51,0,10,0,0,0,0,0,0 +43.09,51,0,10,0,0,0,0,0,0 +43.1,51,0,10,0,0,0,0,0,0 +43.11,51,0,10,0,0,0,0,0,0 +43.12,51,0,10,0,0,0,0,0,0 +43.13,51,0,10,0,0,0,0,0,0 +43.14,51,0,10,0,0,0,0,0,0 +43.15,51,0,10,0,0,0,0,0,0 +43.16,51,0,10,0,0,0,0,0,0 +43.17,51,0,10,0,0,0,0,0,0 +43.18,51,0,10,0,0,0,0,0,0 +43.19,51,0,10,0,0,0,0,0,0 +43.2,51,0,10,0,0,0,0,0,0 +43.21,51,0,10,0,0,0,0,0,0 +43.22,51,0,10,0,0,0,0,0,0 +43.23,51,0,10,0,0,0,0,0,0 +43.24,51,0,10,0,0,0,0,0,0 +43.25,51,0,10,0,0,0,0,0,0 +43.26,51,0,10,0,0,0,0,0,0 +43.27,51,0,10,0,0,0,0,0,0 +43.28,51,0,10,0,0,0,0,0,0 +43.29,51,0,10,0,0,0,0,0,0 +43.3,51,0,10,0,0,0,0,0,0 +43.31,51,0,10,0,0,0,0,0,0 +43.32,51,0,10,0,0,0,0,0,0 +43.33,51,0,10,0,0,0,0,0,0 +43.34,51,0,10,0,0,0,0,0,0 +43.35,51,0,10,0,0,0,0,0,0 +43.36,51,0,10,0,0,0,0,0,0 +43.37,51,0,10,0,0,0,0,0,0 +43.38,51,0,10,0,0,0,0,0,0 +43.39,51,0,10,0,0,0,0,0,0 +43.4,51,0,10,0,0,0,0,0,0 +43.41,51,0,10,0,0,0,0,0,0 +43.42,51,0,10,0,0,0,0,0,0 +43.43,51,0,10,0,0,0,0,0,0 +43.44,51,0,10,0,0,0,0,0,0 +43.45,51,0,10,0,0,0,0,0,0 +43.46,51,0,10,0,0,0,0,0,0 +43.47,51,0,10,0,0,0,0,0,0 +43.48,51,0,10,0,0,0,0,0,0 +43.49,51,0,10,0,0,0,0,0,0 +43.5,51,0,10,0,0,0,0,0,0 +43.51,51,0,10,0,0,0,0,0,0 +43.52,51,0,10,0,0,0,0,0,0 +43.53,51,0,10,0,0,0,0,0,0 +43.54,51,0,10,0,0,0,0,0,0 +43.55,51,0,10,0,0,0,0,0,0 +43.56,51,0,10,0,0,0,0,0,0 +43.57,51,0,10,0,0,0,0,0,0 +43.58,51,0,10,0,0,0,0,0,0 +43.59,51,0,10,0,0,0,0,0,0 +43.6,51,0,10,0,0,0,0,0,0 +43.61,51,0,10,0,0,0,0,0,0 +43.62,51,0,10,0,0,0,0,0,0 +43.63,51,0,10,0,0,0,0,0,0 +43.64,51,0,10,0,0,0,0,0,0 +43.65,51,0,10,0,0,0,0,0,0 +43.66,51,0,10,0,0,0,0,0,0 +43.67,51,0,10,0,0,0,0,0,0 +43.68,51,0,10,0,0,0,0,0,0 +43.69,51,0,10,0,0,0,0,0,0 +43.7,51,0,10,0,0,0,0,0,0 +43.71,51,0,10,0,0,0,0,0,0 +43.72,51,0,10,0,0,0,0,0,0 +43.73,51,0,10,0,0,0,0,0,0 +43.74,51,0,10,0,0,0,0,0,0 +43.75,51,0,10,0,0,0,0,0,0 +43.76,51,0,10,0,0,0,0,0,0 +43.77,51,0,10,0,0,0,0,0,0 +43.78,51,0,10,0,0,0,0,0,0 +43.79,51,0,10,0,0,0,0,0,0 +43.8,51,0,10,0,0,0,0,0,0 +43.81,51,0,10,0,0,0,0,0,0 +43.82,51,0,10,0,0,0,0,0,0 +43.83,51,0,10,0,0,0,0,0,0 +43.84,51,0,10,0,0,0,0,0,0 +43.85,51,0,10,0,0,0,0,0,0 +43.86,51,0,10,0,0,0,0,0,0 +43.87,51,0,10,0,0,0,0,0,0 +43.88,51,0,10,0,0,0,0,0,0 +43.89,51,0,10,0,0,0,0,0,0 +43.9,51,0,10,0,0,0,0,0,0 +43.91,51,0,10,0,0,0,0,0,0 +43.92,51,0,10,0,0,0,0,0,0 +43.93,51,0,10,0,0,0,0,0,0 +43.94,51,0,10,0,0,0,0,0,0 +43.95,51,0,10,0,0,0,0,0,0 +43.96,51,0,10,0,0,0,0,0,0 +43.97,51,0,10,0,0,0,0,0,0 +43.98,51,0,10,0,0,0,0,0,0 +43.99,51,0,10,0,0,0,0,0,0 +44,51,0,10,0,0,0,0,0,0 +44.01,51,0,10,0,0,0,0,0,0 +44.02,51,0,10,0,0,0,0,0,0 +44.03,51,0,10,0,0,0,0,0,0 +44.04,51,0,10,0,0,0,0,0,0 +44.05,51,0,10,0,0,0,0,0,0 +44.06,51,0,10,0,0,0,0,0,0 +44.07,51,0,10,0,0,0,0,0,0 +44.08,51,0,10,0,0,0,0,0,0 +44.09,51,0,10,0,0,0,0,0,0 +44.1,51,0,10,0,0,0,0,0,0 +44.11,51,0,10,0,0,0,0,0,0 +44.12,51,0,10,0,0,0,0,0,0 +44.13,51,0,10,0,0,0,0,0,0 +44.14,51,0,10,0,0,0,0,0,0 +44.15,51,0,10,0,0,0,0,0,0 +44.16,51,0,10,0,0,0,0,0,0 +44.17,51,0,10,0,0,0,0,0,0 +44.18,51,0,10,0,0,0,0,0,0 +44.19,51,0,10,0,0,0,0,0,0 +44.2,51,0,10,0,0,0,0,0,0 +44.21,51,0,10,0,0,0,0,0,0 +44.22,51,0,10,0,0,0,0,0,0 +44.23,51,0,10,0,0,0,0,0,0 +44.24,51,0,10,0,0,0,0,0,0 +44.25,51,0,10,0,0,0,0,0,0 +44.26,51,0,10,0,0,0,0,0,0 +44.27,51,0,10,0,0,0,0,0,0 +44.28,51,0,10,0,0,0,0,0,0 +44.29,51,0,10,0,0,0,0,0,0 +44.3,51,0,10,0,0,0,0,0,0 +44.31,51,0,10,0,0,0,0,0,0 +44.32,51,0,10,0,0,0,0,0,0 +44.33,51,0,10,0,0,0,0,0,0 +44.34,51,0,10,0,0,0,0,0,0 +44.35,51,0,10,0,0,0,0,0,0 +44.36,51,0,10,0,0,0,0,0,0 +44.37,51,0,10,0,0,0,0,0,0 +44.38,51,0,10,0,0,0,0,0,0 +44.39,51,0,10,0,0,0,0,0,0 +44.4,51,0,10,0,0,0,0,0,0 +44.41,51,0,10,0,0,0,0,0,0 +44.42,51,0,10,0,0,0,0,0,0 +44.43,51,0,10,0,0,0,0,0,0 +44.44,51,0,10,0,0,0,0,0,0 +44.45,51,0,10,0,0,0,0,0,0 +44.46,51,0,10,0,0,0,0,0,0 +44.47,51,0,10,0,0,0,0,0,0 +44.48,51,0,10,0,0,0,0,0,0 +44.49,51,0,10,0,0,0,0,0,0 +44.5,51,0,10,0,0,0,0,0,0 +44.51,51,0,10,0,0,0,0,0,0 +44.52,51,0,10,0,0,0,0,0,0 +44.53,51,0,10,0,0,0,0,0,0 +44.54,51,0,10,0,0,0,0,0,0 +44.55,51,0,10,0,0,0,0,0,0 +44.56,51,0,10,0,0,0,0,0,0 +44.57,51,0,10,0,0,0,0,0,0 +44.58,51,0,10,0,0,0,0,0,0 +44.59,51,0,10,0,0,0,0,0,0 +44.6,51,0,10,0,0,0,0,0,0 +44.61,51,0,10,0,0,0,0,0,0 +44.62,51,0,10,0,0,0,0,0,0 +44.63,51,0,10,0,0,0,0,0,0 +44.64,51,0,10,0,0,0,0,0,0 +44.65,51,0,10,0,0,0,0,0,0 +44.66,51,0,10,0,0,0,0,0,0 +44.67,51,0,10,0,0,0,0,0,0 +44.68,51,0,10,0,0,0,0,0,0 +44.69,51,0,10,0,0,0,0,0,0 +44.7,51,0,10,0,0,0,0,0,0 +44.71,51,0,10,0,0,0,0,0,0 +44.72,51,0,10,0,0,0,0,0,0 +44.73,51,0,10,0,0,0,0,0,0 +44.74,51,0,10,0,0,0,0,0,0 +44.75,51,0,10,0,0,0,0,0,0 +44.76,51,0,10,0,0,0,0,0,0 +44.77,51,0,10,0,0,0,0,0,0 +44.78,51,0,10,0,0,0,0,0,0 +44.79,51,0,10,0,0,0,0,0,0 +44.8,51,0,10,0,0,0,0,0,0 +44.81,51,0,10,0,0,0,0,0,0 +44.82,51,0,10,0,0,0,0,0,0 +44.83,51,0,10,0,0,0,0,0,0 +44.84,51,0,10,0,0,0,0,0,0 +44.85,51,0,10,0,0,0,0,0,0 +44.86,51,0,10,0,0,0,0,0,0 +44.87,51,0,10,0,0,0,0,0,0 +44.88,51,0,10,0,0,0,0,0,0 +44.89,51,0,10,0,0,0,0,0,0 +44.9,51,0,10,0,0,0,0,0,0 +44.91,51,0,10,0,0,0,0,0,0 +44.92,51,0,10,0,0,0,0,0,0 +44.93,51,0,10,0,0,0,0,0,0 +44.94,51,0,10,0,0,0,0,0,0 +44.95,51,0,10,0,0,0,0,0,0 +44.96,51,0,10,0,0,0,0,0,0 +44.97,51,0,10,0,0,0,0,0,0 +44.98,51,0,10,0,0,0,0,0,0 +44.99,51,0,10,0,0,0,0,0,0 +45,51,0,10,0,0,0,0,0,0 +45.01,51,0,10,0,0,0,0,0,0 +45.02,51,0,10,0,0,0,0,0,0 +45.03,51,0,10,0,0,0,0,0,0 +45.04,51,0,10,0,0,0,0,0,0 +45.05,51,0,10,0,0,0,0,0,0 +45.06,51,0,10,0,0,0,0,0,0 +45.07,51,0,10,0,0,0,0,0,0 +45.08,51,0,10,0,0,0,0,0,0 +45.09,51,0,10,0,0,0,0,0,0 +45.1,51,0,10,0,0,0,0,0,0 +45.11,51,0,10,0,0,0,0,0,0 +45.12,51,0,10,0,0,0,0,0,0 +45.13,51,0,10,0,0,0,0,0,0 +45.14,51,0,10,0,0,0,0,0,0 +45.15,51,0,10,0,0,0,0,0,0 +45.16,51,0,10,0,0,0,0,0,0 +45.17,51,0,10,0,0,0,0,0,0 +45.18,51,0,10,0,0,0,0,0,0 +45.19,51,0,10,0,0,0,0,0,0 +45.2,51,0,10,0,0,0,0,0,0 +45.21,51,0,10,0,0,0,0,0,0 +45.22,51,0,10,0,0,0,0,0,0 +45.23,51,0,10,0,0,0,0,0,0 +45.24,51,0,10,0,0,0,0,0,0 +45.25,51,0,10,0,0,0,0,0,0 +45.26,51,0,10,0,0,0,0,0,0 +45.27,51,0,10,0,0,0,0,0,0 +45.28,51,0,10,0,0,0,0,0,0 +45.29,51,0,10,0,0,0,0,0,0 +45.3,51,0,10,0,0,0,0,0,0 +45.31,51,0,10,0,0,0,0,0,0 +45.32,51,0,10,0,0,0,0,0,0 +45.33,51,0,10,0,0,0,0,0,0 +45.34,51,0,10,0,0,0,0,0,0 +45.35,51,0,10,0,0,0,0,0,0 +45.36,51,0,10,0,0,0,0,0,0 +45.37,51,0,10,0,0,0,0,0,0 +45.38,51,0,10,0,0,0,0,0,0 +45.39,51,0,10,0,0,0,0,0,0 +45.4,51,0,10,0,0,0,0,0,0 +45.41,51,0,10,0,0,0,0,0,0 +45.42,51,0,10,0,0,0,0,0,0 +45.43,51,0,10,0,0,0,0,0,0 +45.44,51,0,10,0,0,0,0,0,0 +45.45,51,0,10,0,0,0,0,0,0 +45.46,51,0,10,0,0,0,0,0,0 +45.47,51,0,10,0,0,0,0,0,0 +45.48,51,0,10,0,0,0,0,0,0 +45.49,51,0,10,0,0,0,0,0,0 +45.5,51,0,10,0,0,0,0,0,0 +45.51,51,0,10,0,0,0,0,0,0 +45.52,51,0,10,0,0,0,0,0,0 +45.53,51,0,10,0,0,0,0,0,0 +45.54,51,0,10,0,0,0,0,0,0 +45.55,51,0,10,0,0,0,0,0,0 +45.56,51,0,10,0,0,0,0,0,0 +45.57,51,0,10,0,0,0,0,0,0 +45.58,51,0,10,0,0,0,0,0,0 +45.59,51,0,10,0,0,0,0,0,0 +45.6,51,0,10,0,0,0,0,0,0 +45.61,51,0,10,0,0,0,0,0,0 +45.62,51,0,10,0,0,0,0,0,0 +45.63,51,0,10,0,0,0,0,0,0 +45.64,51,0,10,0,0,0,0,0,0 +45.65,51,0,10,0,0,0,0,0,0 +45.66,51,0,10,0,0,0,0,0,0 +45.67,51,0,10,0,0,0,0,0,0 +45.68,51,0,10,0,0,0,0,0,0 +45.69,51,0,10,0,0,0,0,0,0 +45.7,51,0,10,0,0,0,0,0,0 +45.71,51,0,10,0,0,0,0,0,0 +45.72,51,0,10,0,0,0,0,0,0 +45.73,51,0,10,0,0,0,0,0,0 +45.74,51,0,10,0,0,0,0,0,0 +45.75,51,0,10,0,0,0,0,0,0 +45.76,51,0,10,0,0,0,0,0,0 +45.77,51,0,10,0,0,0,0,0,0 +45.78,51,0,10,0,0,0,0,0,0 +45.79,51,0,10,0,0,0,0,0,0 +45.8,51,0,10,0,0,0,0,0,0 +45.81,51,0,10,0,0,0,0,0,0 +45.82,51,0,10,0,0,0,0,0,0 +45.83,51,0,10,0,0,0,0,0,0 +45.84,51,0,10,0,0,0,0,0,0 +45.85,51,0,10,0,0,0,0,0,0 +45.86,51,0,10,0,0,0,0,0,0 +45.87,51,0,10,0,0,0,0,0,0 +45.88,51,0,10,0,0,0,0,0,0 +45.89,51,0,10,0,0,0,0,0,0 +45.9,51,0,10,0,0,0,0,0,0 +45.91,51,0,10,0,0,0,0,0,0 +45.92,51,0,10,0,0,0,0,0,0 +45.93,51,0,10,0,0,0,0,0,0 +45.94,51,0,10,0,0,0,0,0,0 +45.95,51,0,10,0,0,0,0,0,0 +45.96,51,0,10,0,0,0,0,0,0 +45.97,51,0,10,0,0,0,0,0,0 +45.98,51,0,10,0,0,0,0,0,0 +45.99,51,0,10,0,0,0,0,0,0 +46,51,0,10,0,0,0,0,0,0 +46.01,51,0,10,0,0,0,0,0,0 +46.02,51,0,10,0,0,0,0,0,0 +46.03,51,0,10,0,0,0,0,0,0 +46.04,51,0,10,0,0,0,0,0,0 +46.05,51,0,10,0,0,0,0,0,0 +46.06,51,0,10,0,0,0,0,0,0 +46.07,51,0,10,0,0,0,0,0,0 +46.08,51,0,10,0,0,0,0,0,0 +46.09,51,0,10,0,0,0,0,0,0 +46.1,51,0,10,0,0,0,0,0,0 +46.11,51,0,10,0,0,0,0,0,0 +46.12,51,0,10,0,0,0,0,0,0 +46.13,51,0,10,0,0,0,0,0,0 +46.14,51,0,10,0,0,0,0,0,0 +46.15,51,0,10,0,0,0,0,0,0 +46.16,51,0,10,0,0,0,0,0,0 +46.17,51,0,10,0,0,0,0,0,0 +46.18,51,0,10,0,0,0,0,0,0 +46.19,51,0,10,0,0,0,0,0,0 +46.2,51,0,10,0,0,0,0,0,0 +46.21,51,0,10,0,0,0,0,0,0 +46.22,51,0,10,0,0,0,0,0,0 +46.23,51,0,10,0,0,0,0,0,0 +46.24,51,0,10,0,0,0,0,0,0 +46.25,51,0,10,0,0,0,0,0,0 +46.26,51,0,10,0,0,0,0,0,0 +46.27,51,0,10,0,0,0,0,0,0 +46.28,51,0,10,0,0,0,0,0,0 +46.29,51,0,10,0,0,0,0,0,0 +46.3,51,0,10,0,0,0,0,0,0 +46.31,51,0,10,0,0,0,0,0,0 +46.32,51,0,10,0,0,0,0,0,0 +46.33,51,0,10,0,0,0,0,0,0 +46.34,51,0,10,0,0,0,0,0,0 +46.35,51,0,10,0,0,0,0,0,0 +46.36,51,0,10,0,0,0,0,0,0 +46.37,51,0,10,0,0,0,0,0,0 +46.38,51,0,10,0,0,0,0,0,0 +46.39,51,0,10,0,0,0,0,0,0 +46.4,51,0,10,0,0,0,0,0,0 +46.41,51,0,10,0,0,0,0,0,0 +46.42,51,0,10,0,0,0,0,0,0 +46.43,51,0,10,0,0,0,0,0,0 +46.44,51,0,10,0,0,0,0,0,0 +46.45,51,0,10,0,0,0,0,0,0 +46.46,51,0,10,0,0,0,0,0,0 +46.47,51,0,10,0,0,0,0,0,0 +46.48,51,0,10,0,0,0,0,0,0 +46.49,51,0,10,0,0,0,0,0,0 +46.5,51,0,10,0,0,0,0,0,0 +46.51,51,0,10,0,0,0,0,0,0 +46.52,51,0,10,0,0,0,0,0,0 +46.53,51,0,10,0,0,0,0,0,0 +46.54,51,0,10,0,0,0,0,0,0 +46.55,51,0,10,0,0,0,0,0,0 +46.56,51,0,10,0,0,0,0,0,0 +46.57,51,0,10,0,0,0,0,0,0 +46.58,51,0,10,0,0,0,0,0,0 +46.59,51,0,10,0,0,0,0,0,0 +46.6,51,0,10,0,0,0,0,0,0 +46.61,51,0,10,0,0,0,0,0,0 +46.62,51,0,10,0,0,0,0,0,0 +46.63,51,0,10,0,0,0,0,0,0 +46.64,51,0,10,0,0,0,0,0,0 +46.65,51,0,10,0,0,0,0,0,0 +46.66,51,0,10,0,0,0,0,0,0 +46.67,51,0,10,0,0,0,0,0,0 +46.68,51,0,10,0,0,0,0,0,0 +46.69,51,0,10,0,0,0,0,0,0 +46.7,51,0,10,0,0,0,0,0,0 +46.71,51,0,10,0,0,0,0,0,0 +46.72,51,0,10,0,0,0,0,0,0 +46.73,51,0,10,0,0,0,0,0,0 +46.74,51,0,10,0,0,0,0,0,0 +46.75,51,0,10,0,0,0,0,0,0 +46.76,51,0,10,0,0,0,0,0,0 +46.77,51,0,10,0,0,0,0,0,0 +46.78,51,0,10,0,0,0,0,0,0 +46.79,51,0,10,0,0,0,0,0,0 +46.8,51,0,10,0,0,0,0,0,0 +46.81,51,0,10,0,0,0,0,0,0 +46.82,51,0,10,0,0,0,0,0,0 +46.83,51,0,10,0,0,0,0,0,0 +46.84,51,0,10,0,0,0,0,0,0 +46.85,51,0,10,0,0,0,0,0,0 +46.86,51,0,10,0,0,0,0,0,0 +46.87,51,0,10,0,0,0,0,0,0 +46.88,51,0,10,0,0,0,0,0,0 +46.89,51,0,10,0,0,0,0,0,0 +46.9,51,0,10,0,0,0,0,0,0 +46.91,51,0,10,0,0,0,0,0,0 +46.92,51,0,10,0,0,0,0,0,0 +46.93,51,0,10,0,0,0,0,0,0 +46.94,51,0,10,0,0,0,0,0,0 +46.95,51,0,10,0,0,0,0,0,0 +46.96,51,0,10,0,0,0,0,0,0 +46.97,51,0,10,0,0,0,0,0,0 +46.98,51,0,10,0,0,0,0,0,0 +46.99,51,0,10,0,0,0,0,0,0 +47,51,0,10,0,0,0,0,0,0 +47.01,51,0,10,0,0,0,0,0,0 +47.02,51,0,10,0,0,0,0,0,0 +47.03,51,0,10,0,0,0,0,0,0 +47.04,51,0,10,0,0,0,0,0,0 +47.05,51,0,10,0,0,0,0,0,0 +47.06,51,0,10,0,0,0,0,0,0 +47.07,51,0,10,0,0,0,0,0,0 +47.08,51,0,10,0,0,0,0,0,0 +47.09,51,0,10,0,0,0,0,0,0 +47.1,51,0,10,0,0,0,0,0,0 +47.11,51,0,10,0,0,0,0,0,0 +47.12,51,0,10,0,0,0,0,0,0 +47.13,51,0,10,0,0,0,0,0,0 +47.14,51,0,10,0,0,0,0,0,0 +47.15,51,0,10,0,0,0,0,0,0 +47.16,51,0,10,0,0,0,0,0,0 +47.17,51,0,10,0,0,0,0,0,0 +47.18,51,0,10,0,0,0,0,0,0 +47.19,51,0,10,0,0,0,0,0,0 +47.2,51,0,10,0,0,0,0,0,0 +47.21,51,0,10,0,0,0,0,0,0 +47.22,51,0,10,0,0,0,0,0,0 +47.23,51,0,10,0,0,0,0,0,0 +47.24,51,0,10,0,0,0,0,0,0 +47.25,51,0,10,0,0,0,0,0,0 +47.26,51,0,10,0,0,0,0,0,0 +47.27,51,0,10,0,0,0,0,0,0 +47.28,51,0,10,0,0,0,0,0,0 +47.29,51,0,10,0,0,0,0,0,0 +47.3,51,0,10,0,0,0,0,0,0 +47.31,51,0,10,0,0,0,0,0,0 +47.32,51,0,10,0,0,0,0,0,0 +47.33,51,0,10,0,0,0,0,0,0 +47.34,51,0,10,0,0,0,0,0,0 +47.35,51,0,10,0,0,0,0,0,0 +47.36,51,0,10,0,0,0,0,0,0 +47.37,51,0,10,0,0,0,0,0,0 +47.38,51,0,10,0,0,0,0,0,0 +47.39,51,0,10,0,0,0,0,0,0 +47.4,51,0,10,0,0,0,0,0,0 +47.41,51,0,10,0,0,0,0,0,0 +47.42,51,0,10,0,0,0,0,0,0 +47.43,51,0,10,0,0,0,0,0,0 +47.44,51,0,10,0,0,0,0,0,0 +47.45,51,0,10,0,0,0,0,0,0 +47.46,51,0,10,0,0,0,0,0,0 +47.47,51,0,10,0,0,0,0,0,0 +47.48,51,0,10,0,0,0,0,0,0 +47.49,51,0,10,0,0,0,0,0,0 +47.5,51,0,10,0,0,0,0,0,0 +47.51,51,0,10,0,0,0,0,0,0 +47.52,51,0,10,0,0,0,0,0,0 +47.53,51,0,10,0,0,0,0,0,0 +47.54,51,0,10,0,0,0,0,0,0 +47.55,51,0,10,0,0,0,0,0,0 +47.56,51,0,10,0,0,0,0,0,0 +47.57,51,0,10,0,0,0,0,0,0 +47.58,51,0,10,0,0,0,0,0,0 +47.59,51,0,10,0,0,0,0,0,0 +47.6,51,0,10,0,0,0,0,0,0 +47.61,51,0,10,0,0,0,0,0,0 +47.62,51,0,10,0,0,0,0,0,0 +47.63,51,0,10,0,0,0,0,0,0 +47.64,51,0,10,0,0,0,0,0,0 +47.65,51,0,10,0,0,0,0,0,0 +47.66,51,0,10,0,0,0,0,0,0 +47.67,51,0,10,0,0,0,0,0,0 +47.68,51,0,10,0,0,0,0,0,0 +47.69,51,0,10,0,0,0,0,0,0 +47.7,51,0,10,0,0,0,0,0,0 +47.71,51,0,10,0,0,0,0,0,0 +47.72,51,0,10,0,0,0,0,0,0 +47.73,51,0,10,0,0,0,0,0,0 +47.74,51,0,10,0,0,0,0,0,0 +47.75,51,0,10,0,0,0,0,0,0 +47.76,51,0,10,0,0,0,0,0,0 +47.77,51,0,10,0,0,0,0,0,0 +47.78,51,0,10,0,0,0,0,0,0 +47.79,51,0,10,0,0,0,0,0,0 +47.8,51,0,10,0,0,0,0,0,0 +47.81,51,0,10,0,0,0,0,0,0 +47.82,51,0,10,0,0,0,0,0,0 +47.83,51,0,10,0,0,0,0,0,0 +47.84,51,0,10,0,0,0,0,0,0 +47.85,51,0,10,0,0,0,0,0,0 +47.86,51,0,10,0,0,0,0,0,0 +47.87,51,0,10,0,0,0,0,0,0 +47.88,51,0,10,0,0,0,0,0,0 +47.89,51,0,10,0,0,0,0,0,0 +47.9,51,0,10,0,0,0,0,0,0 +47.91,51,0,10,0,0,0,0,0,0 +47.92,51,0,10,0,0,0,0,0,0 +47.93,51,0,10,0,0,0,0,0,0 +47.94,51,0,10,0,0,0,0,0,0 +47.95,51,0,10,0,0,0,0,0,0 +47.96,51,0,10,0,0,0,0,0,0 +47.97,51,0,10,0,0,0,0,0,0 +47.98,51,0,10,0,0,0,0,0,0 +47.99,51,0,10,0,0,0,0,0,0 +48,51,0,10,0,0,0,0,0,0 +48.01,51,0,10,0,0,0,0,0,0 +48.02,51,0,10,0,0,0,0,0,0 +48.03,51,0,10,0,0,0,0,0,0 +48.04,51,0,10,0,0,0,0,0,0 +48.05,51,0,10,0,0,0,0,0,0 +48.06,51,0,10,0,0,0,0,0,0 +48.07,51,0,10,0,0,0,0,0,0 +48.08,51,0,10,0,0,0,0,0,0 +48.09,51,0,10,0,0,0,0,0,0 +48.1,51,0,10,0,0,0,0,0,0 +48.11,51,0,10,0,0,0,0,0,0 +48.12,51,0,10,0,0,0,0,0,0 +48.13,51,0,10,0,0,0,0,0,0 +48.14,51,0,10,0,0,0,0,0,0 +48.15,51,0,10,0,0,0,0,0,0 +48.16,51,0,10,0,0,0,0,0,0 +48.17,51,0,10,0,0,0,0,0,0 +48.18,51,0,10,0,0,0,0,0,0 +48.19,51,0,10,0,0,0,0,0,0 +48.2,51,0,10,0,0,0,0,0,0 +48.21,51,0,10,0,0,0,0,0,0 +48.22,51,0,10,0,0,0,0,0,0 +48.23,51,0,10,0,0,0,0,0,0 +48.24,51,0,10,0,0,0,0,0,0 +48.25,51,0,10,0,0,0,0,0,0 +48.26,51,0,10,0,0,0,0,0,0 +48.27,51,0,10,0,0,0,0,0,0 +48.28,51,0,10,0,0,0,0,0,0 +48.29,51,0,10,0,0,0,0,0,0 +48.3,51,0,10,0,0,0,0,0,0 +48.31,51,0,10,0,0,0,0,0,0 +48.32,51,0,10,0,0,0,0,0,0 +48.33,51,0,10,0,0,0,0,0,0 +48.34,51,0,10,0,0,0,0,0,0 +48.35,51,0,10,0,0,0,0,0,0 +48.36,51,0,10,0,0,0,0,0,0 +48.37,51,0,10,0,0,0,0,0,0 +48.38,51,0,10,0,0,0,0,0,0 +48.39,51,0,10,0,0,0,0,0,0 +48.4,51,0,10,0,0,0,0,0,0 +48.41,51,0,10,0,0,0,0,0,0 +48.42,51,0,10,0,0,0,0,0,0 +48.43,51,0,10,0,0,0,0,0,0 +48.44,51,0,10,0,0,0,0,0,0 +48.45,51,0,10,0,0,0,0,0,0 +48.46,51,0,10,0,0,0,0,0,0 +48.47,51,0,10,0,0,0,0,0,0 +48.48,51,0,10,0,0,0,0,0,0 +48.49,51,0,10,0,0,0,0,0,0 +48.5,51,0,10,0,0,0,0,0,0 +48.51,51,0,10,0,0,0,0,0,0 +48.52,51,0,10,0,0,0,0,0,0 +48.53,51,0,10,0,0,0,0,0,0 +48.54,51,0,10,0,0,0,0,0,0 +48.55,51,0,10,0,0,0,0,0,0 +48.56,51,0,10,0,0,0,0,0,0 +48.57,51,0,10,0,0,0,0,0,0 +48.58,51,0,10,0,0,0,0,0,0 +48.59,51,0,10,0,0,0,0,0,0 +48.6,51,0,10,0,0,0,0,0,0 +48.61,51,0,10,0,0,0,0,0,0 +48.62,51,0,10,0,0,0,0,0,0 +48.63,51,0,10,0,0,0,0,0,0 +48.64,51,0,10,0,0,0,0,0,0 +48.65,51,0,10,0,0,0,0,0,0 +48.66,51,0,10,0,0,0,0,0,0 +48.67,51,0,10,0,0,0,0,0,0 +48.68,51,0,10,0,0,0,0,0,0 +48.69,51,0,10,0,0,0,0,0,0 +48.7,51,0,10,0,0,0,0,0,0 +48.71,51,0,10,0,0,0,0,0,0 +48.72,51,0,10,0,0,0,0,0,0 +48.73,51,0,10,0,0,0,0,0,0 +48.74,51,0,10,0,0,0,0,0,0 +48.75,51,0,10,0,0,0,0,0,0 +48.76,51,0,10,0,0,0,0,0,0 +48.77,51,0,10,0,0,0,0,0,0 +48.78,51,0,10,0,0,0,0,0,0 +48.79,51,0,10,0,0,0,0,0,0 +48.8,51,0,10,0,0,0,0,0,0 +48.81,51,0,10,0,0,0,0,0,0 +48.82,51,0,10,0,0,0,0,0,0 +48.83,51,0,10,0,0,0,0,0,0 +48.84,51,0,10,0,0,0,0,0,0 +48.85,51,0,10,0,0,0,0,0,0 +48.86,51,0,10,0,0,0,0,0,0 +48.87,51,0,10,0,0,0,0,0,0 +48.88,51,0,10,0,0,0,0,0,0 +48.89,51,0,10,0,0,0,0,0,0 +48.9,51,0,10,0,0,0,0,0,0 +48.91,51,0,10,0,0,0,0,0,0 +48.92,51,0,10,0,0,0,0,0,0 +48.93,51,0,10,0,0,0,0,0,0 +48.94,51,0,10,0,0,0,0,0,0 +48.95,51,0,10,0,0,0,0,0,0 +48.96,51,0,10,0,0,0,0,0,0 +48.97,51,0,10,0,0,0,0,0,0 +48.98,51,0,10,0,0,0,0,0,0 +48.99,51,0,10,0,0,0,0,0,0 +49,51,0,10,0,0,0,0,0,0 +49.01,51,0,10,0,0,0,0,0,0 +49.02,51,0,10,0,0,0,0,0,0 +49.03,51,0,10,0,0,0,0,0,0 +49.04,51,0,10,0,0,0,0,0,0 +49.05,51,0,10,0,0,0,0,0,0 +49.06,51,0,10,0,0,0,0,0,0 +49.07,51,0,10,0,0,0,0,0,0 +49.08,51,0,10,0,0,0,0,0,0 +49.09,51,0,10,0,0,0,0,0,0 +49.1,51,0,10,0,0,0,0,0,0 +49.11,51,0,10,0,0,0,0,0,0 +49.12,51,0,10,0,0,0,0,0,0 +49.13,51,0,10,0,0,0,0,0,0 +49.14,51,0,10,0,0,0,0,0,0 +49.15,51,0,10,0,0,0,0,0,0 +49.16,51,0,10,0,0,0,0,0,0 +49.17,51,0,10,0,0,0,0,0,0 +49.18,51,0,10,0,0,0,0,0,0 +49.19,51,0,10,0,0,0,0,0,0 +49.2,51,0,10,0,0,0,0,0,0 +49.21,51,0,10,0,0,0,0,0,0 +49.22,51,0,10,0,0,0,0,0,0 +49.23,51,0,10,0,0,0,0,0,0 +49.24,51,0,10,0,0,0,0,0,0 +49.25,51,0,10,0,0,0,0,0,0 +49.26,51,0,10,0,0,0,0,0,0 +49.27,51,0,10,0,0,0,0,0,0 +49.28,51,0,10,0,0,0,0,0,0 +49.29,51,0,10,0,0,0,0,0,0 +49.3,51,0,10,0,0,0,0,0,0 +49.31,51,0,10,0,0,0,0,0,0 +49.32,51,0,10,0,0,0,0,0,0 +49.33,51,0,10,0,0,0,0,0,0 +49.34,51,0,10,0,0,0,0,0,0 +49.35,51,0,10,0,0,0,0,0,0 +49.36,51,0,10,0,0,0,0,0,0 +49.37,51,0,10,0,0,0,0,0,0 +49.38,51,0,10,0,0,0,0,0,0 +49.39,51,0,10,0,0,0,0,0,0 +49.4,51,0,10,0,0,0,0,0,0 +49.41,51,0,10,0,0,0,0,0,0 +49.42,51,0,10,0,0,0,0,0,0 +49.43,51,0,10,0,0,0,0,0,0 +49.44,51,0,10,0,0,0,0,0,0 +49.45,51,0,10,0,0,0,0,0,0 +49.46,51,0,10,0,0,0,0,0,0 +49.47,51,0,10,0,0,0,0,0,0 +49.48,51,0,10,0,0,0,0,0,0 +49.49,51,0,10,0,0,0,0,0,0 +49.5,51,0,10,0,0,0,0,0,0 +49.51,51,0,10,0,0,0,0,0,0 +49.52,51,0,10,0,0,0,0,0,0 +49.53,51,0,10,0,0,0,0,0,0 +49.54,51,0,10,0,0,0,0,0,0 +49.55,51,0,10,0,0,0,0,0,0 +49.56,51,0,10,0,0,0,0,0,0 +49.57,51,0,10,0,0,0,0,0,0 +49.58,51,0,10,0,0,0,0,0,0 +49.59,51,0,10,0,0,0,0,0,0 +49.6,51,0,10,0,0,0,0,0,0 +49.61,51,0,10,0,0,0,0,0,0 +49.62,51,0,10,0,0,0,0,0,0 +49.63,51,0,10,0,0,0,0,0,0 +49.64,51,0,10,0,0,0,0,0,0 +49.65,51,0,10,0,0,0,0,0,0 +49.66,51,0,10,0,0,0,0,0,0 +49.67,51,0,10,0,0,0,0,0,0 +49.68,51,0,10,0,0,0,0,0,0 +49.69,51,0,10,0,0,0,0,0,0 +49.7,51,0,10,0,0,0,0,0,0 +49.71,51,0,10,0,0,0,0,0,0 +49.72,51,0,10,0,0,0,0,0,0 +49.73,51,0,10,0,0,0,0,0,0 +49.74,51,0,10,0,0,0,0,0,0 +49.75,51,0,10,0,0,0,0,0,0 +49.76,51,0,10,0,0,0,0,0,0 +49.77,51,0,10,0,0,0,0,0,0 +49.78,51,0,10,0,0,0,0,0,0 +49.79,51,0,10,0,0,0,0,0,0 +49.8,51,0,10,0,0,0,0,0,0 +49.81,51,0,10,0,0,0,0,0,0 +49.82,51,0,10,0,0,0,0,0,0 +49.83,51,0,10,0,0,0,0,0,0 +49.84,51,0,10,0,0,0,0,0,0 +49.85,51,0,10,0,0,0,0,0,0 +49.86,51,0,10,0,0,0,0,0,0 +49.87,51,0,10,0,0,0,0,0,0 +49.88,51,0,10,0,0,0,0,0,0 +49.89,51,0,10,0,0,0,0,0,0 +49.9,51,0,10,0,0,0,0,0,0 +49.91,51,0,10,0,0,0,0,0,0 +49.92,51,0,10,0,0,0,0,0,0 +49.93,51,0,10,0,0,0,0,0,0 +49.94,51,0,10,0,0,0,0,0,0 +49.95,51,0,10,0,0,0,0,0,0 +49.96,51,0,10,0,0,0,0,0,0 +49.97,51,0,10,0,0,0,0,0,0 +49.98,51,0,10,0,0,0,0,0,0 +49.99,51,0,10,0,0,0,0,0,0 +50,51,0,10,0,0,0,0,0,0 +50.01,51,0,10,0,0,0,0,0,0 +50.02,51,0,10,0,0,0,0,0,0 +50.03,51,0,10,0,0,0,0,0,0 +50.04,51,0,10,0,0,0,0,0,0 +50.05,51,0,10,0,0,0,0,0,0 +50.06,51,0,10,0,0,0,0,0,0 +50.07,51,0,10,0,0,0,0,0,0 +50.08,51,0,10,0,0,0,0,0,0 +50.09,51,0,10,0,0,0,0,0,0 +50.1,51,0,10,0,0,0,0,0,0 +50.11,51,0,10,0,0,0,0,0,0 +50.12,51,0,10,0,0,0,0,0,0 +50.13,51,0,10,0,0,0,0,0,0 +50.14,51,0,10,0,0,0,0,0,0 +50.15,51,0,10,0,0,0,0,0,0 +50.16,51,0,10,0,0,0,0,0,0 +50.17,51,0,10,0,0,0,0,0,0 +50.18,51,0,10,0,0,0,0,0,0 +50.19,51,0,10,0,0,0,0,0,0 +50.2,51,0,10,0,0,0,0,0,0 +50.21,51,0,10,0,0,0,0,0,0 +50.22,51,0,10,0,0,0,0,0,0 +50.23,51,0,10,0,0,0,0,0,0 +50.24,51,0,10,0,0,0,0,0,0 +50.25,51,0,10,0,0,0,0,0,0 +50.26,51,0,10,0,0,0,0,0,0 +50.27,51,0,10,0,0,0,0,0,0 +50.28,51,0,10,0,0,0,0,0,0 +50.29,51,0,10,0,0,0,0,0,0 +50.3,51,0,10,0,0,0,0,0,0 +50.31,51,0,10,0,0,0,0,0,0 +50.32,51,0,10,0,0,0,0,0,0 +50.33,51,0,10,0,0,0,0,0,0 +50.34,51,0,10,0,0,0,0,0,0 +50.35,51,0,10,0,0,0,0,0,0 +50.36,51,0,10,0,0,0,0,0,0 +50.37,51,0,10,0,0,0,0,0,0 +50.38,51,0,10,0,0,0,0,0,0 +50.39,51,0,10,0,0,0,0,0,0 +50.4,51,0,10,0,0,0,0,0,0 +50.41,51,0,10,0,0,0,0,0,0 +50.42,51,0,10,0,0,0,0,0,0 +50.43,51,0,10,0,0,0,0,0,0 +50.44,51,0,10,0,0,0,0,0,0 +50.45,51,0,10,0,0,0,0,0,0 +50.46,51,0,10,0,0,0,0,0,0 +50.47,51,0,10,0,0,0,0,0,0 +50.48,51,0,10,0,0,0,0,0,0 +50.49,51,0,10,0,0,0,0,0,0 +50.5,51,0,10,0,0,0,0,0,0 +50.51,51,0,10,0,0,0,0,0,0 +50.52,51,0,10,0,0,0,0,0,0 +50.53,51,0,10,0,0,0,0,0,0 +50.54,51,0,10,0,0,0,0,0,0 +50.55,51,0,10,0,0,0,0,0,0 +50.56,51,0,10,0,0,0,0,0,0 +50.57,51,0,10,0,0,0,0,0,0 +50.58,51,0,10,0,0,0,0,0,0 +50.59,51,0,10,0,0,0,0,0,0 +50.6,51,0,10,0,0,0,0,0,0 +50.61,51,0,10,0,0,0,0,0,0 +50.62,51,0,10,0,0,0,0,0,0 +50.63,51,0,10,0,0,0,0,0,0 +50.64,51,0,10,0,0,0,0,0,0 +50.65,51,0,10,0,0,0,0,0,0 +50.66,51,0,10,0,0,0,0,0,0 +50.67,51,0,10,0,0,0,0,0,0 +50.68,51,0,10,0,0,0,0,0,0 +50.69,51,0,10,0,0,0,0,0,0 +50.7,51,0,10,0,0,0,0,0,0 +50.71,51,0,10,0,0,0,0,0,0 +50.72,51,0,10,0,0,0,0,0,0 +50.73,51,0,10,0,0,0,0,0,0 +50.74,51,0,10,0,0,0,0,0,0 +50.75,51,0,10,0,0,0,0,0,0 +50.76,51,0,10,0,0,0,0,0,0 +50.77,51,0,10,0,0,0,0,0,0 +50.78,51,0,10,0,0,0,0,0,0 +50.79,51,0,10,0,0,0,0,0,0 +50.8,51,0,10,0,0,0,0,0,0 +50.81,51,0,10,0,0,0,0,0,0 +50.82,51,0,10,0,0,0,0,0,0 +50.83,51,0,10,0,0,0,0,0,0 +50.84,51,0,10,0,0,0,0,0,0 +50.85,51,0,10,0,0,0,0,0,0 +50.86,51,0,10,0,0,0,0,0,0 +50.87,51,0,10,0,0,0,0,0,0 +50.88,51,0,10,0,0,0,0,0,0 +50.89,51,0,10,0,0,0,0,0,0 +50.9,51,0,10,0,0,0,0,0,0 +50.91,51,0,10,0,0,0,0,0,0 +50.92,51,0,10,0,0,0,0,0,0 +50.93,51,0,10,0,0,0,0,0,0 +50.94,51,0,10,0,0,0,0,0,0 +50.95,51,0,10,0,0,0,0,0,0 +50.96,51,0,10,0,0,0,0,0,0 +50.97,51,0,10,0,0,0,0,0,0 +50.98,51,0,10,0,0,0,0,0,0 +50.99,51,0,10,0,0,0,0,0,0 +51,51,0,10,0,0,0,0,0,0 +51.01,51,0,10,0,0,0,0,0,0 +51.02,51,0,10,0,0,0,0,0,0 +51.03,51,0,10,0,0,0,0,0,0 +51.04,51,0,10,0,0,0,0,0,0 +51.05,51,0,10,0,0,0,0,0,0 +51.06,51,0,10,0,0,0,0,0,0 +51.07,51,0,10,0,0,0,0,0,0 +51.08,51,0,10,0,0,0,0,0,0 +51.09,51,0,10,0,0,0,0,0,0 +51.1,51,0,10,0,0,0,0,0,0 +51.11,51,0,10,0,0,0,0,0,0 +51.12,51,0,10,0,0,0,0,0,0 +51.13,51,0,10,0,0,0,0,0,0 +51.14,51,0,10,0,0,0,0,0,0 +51.15,51,0,10,0,0,0,0,0,0 +51.16,51,0,10,0,0,0,0,0,0 +51.17,51,0,10,0,0,0,0,0,0 +51.18,51,0,10,0,0,0,0,0,0 +51.19,51,0,10,0,0,0,0,0,0 +51.2,51,0,10,0,0,0,0,0,0 +51.21,51,0,10,0,0,0,0,0,0 +51.22,51,0,10,0,0,0,0,0,0 +51.23,51,0,10,0,0,0,0,0,0 +51.24,51,0,10,0,0,0,0,0,0 +51.25,51,0,10,0,0,0,0,0,0 +51.26,51,0,10,0,0,0,0,0,0 +51.27,51,0,10,0,0,0,0,0,0 +51.28,51,0,10,0,0,0,0,0,0 +51.29,51,0,10,0,0,0,0,0,0 +51.3,51,0,10,0,0,0,0,0,0 +51.31,51,0,10,0,0,0,0,0,0 +51.32,51,0,10,0,0,0,0,0,0 +51.33,51,0,10,0,0,0,0,0,0 +51.34,51,0,10,0,0,0,0,0,0 +51.35,51,0,10,0,0,0,0,0,0 +51.36,51,0,10,0,0,0,0,0,0 +51.37,51,0,10,0,0,0,0,0,0 +51.38,51,0,10,0,0,0,0,0,0 +51.39,51,0,10,0,0,0,0,0,0 +51.4,51,0,10,0,0,0,0,0,0 +51.41,51,0,10,0,0,0,0,0,0 +51.42,51,0,10,0,0,0,0,0,0 +51.43,51,0,10,0,0,0,0,0,0 +51.44,51,0,10,0,0,0,0,0,0 +51.45,51,0,10,0,0,0,0,0,0 +51.46,51,0,10,0,0,0,0,0,0 +51.47,51,0,10,0,0,0,0,0,0 +51.48,51,0,10,0,0,0,0,0,0 +51.49,51,0,10,0,0,0,0,0,0 +51.5,51,0,10,0,0,0,0,0,0 +51.51,51,0,10,0,0,0,0,0,0 +51.52,51,0,10,0,0,0,0,0,0 +51.53,51,0,10,0,0,0,0,0,0 +51.54,51,0,10,0,0,0,0,0,0 +51.55,51,0,10,0,0,0,0,0,0 +51.56,51,0,10,0,0,0,0,0,0 +51.57,51,0,10,0,0,0,0,0,0 +51.58,51,0,10,0,0,0,0,0,0 +51.59,51,0,10,0,0,0,0,0,0 +51.6,51,0,10,0,0,0,0,0,0 +51.61,51,0,10,0,0,0,0,0,0 +51.62,51,0,10,0,0,0,0,0,0 +51.63,51,0,10,0,0,0,0,0,0 +51.64,51,0,10,0,0,0,0,0,0 +51.65,51,0,10,0,0,0,0,0,0 +51.66,51,0,10,0,0,0,0,0,0 +51.67,51,0,10,0,0,0,0,0,0 +51.68,51,0,10,0,0,0,0,0,0 +51.69,51,0,10,0,0,0,0,0,0 +51.7,51,0,10,0,0,0,0,0,0 +51.71,51,0,10,0,0,0,0,0,0 +51.72,51,0,10,0,0,0,0,0,0 +51.73,51,0,10,0,0,0,0,0,0 +51.74,51,0,10,0,0,0,0,0,0 +51.75,51,0,10,0,0,0,0,0,0 +51.76,51,0,10,0,0,0,0,0,0 +51.77,51,0,10,0,0,0,0,0,0 +51.78,51,0,10,0,0,0,0,0,0 +51.79,51,0,10,0,0,0,0,0,0 +51.8,51,0,10,0,0,0,0,0,0 +51.81,51,0,10,0,0,0,0,0,0 +51.82,51,0,10,0,0,0,0,0,0 +51.83,51,0,10,0,0,0,0,0,0 +51.84,51,0,10,0,0,0,0,0,0 +51.85,51,0,10,0,0,0,0,0,0 +51.86,51,0,10,0,0,0,0,0,0 +51.87,51,0,10,0,0,0,0,0,0 +51.88,51,0,10,0,0,0,0,0,0 +51.89,51,0,10,0,0,0,0,0,0 +51.9,51,0,10,0,0,0,0,0,0 +51.91,51,0,10,0,0,0,0,0,0 +51.92,51,0,10,0,0,0,0,0,0 +51.93,51,0,10,0,0,0,0,0,0 +51.94,51,0,10,0,0,0,0,0,0 +51.95,51,0,10,0,0,0,0,0,0 +51.96,51,0,10,0,0,0,0,0,0 +51.97,51,0,10,0,0,0,0,0,0 +51.98,51,0,10,0,0,0,0,0,0 +51.99,51,0,10,0,0,0,0,0,0 +52,51,0,10,0,0,0,0,0,0 +52.01,51,0,10,0,0,0,0,0,0 +52.02,51,0,10,0,0,0,0,0,0 +52.03,51,0,10,0,0,0,0,0,0 +52.04,51,0,10,0,0,0,0,0,0 +52.05,51,0,10,0,0,0,0,0,0 +52.06,51,0,10,0,0,0,0,0,0 +52.07,51,0,10,0,0,0,0,0,0 +52.08,51,0,10,0,0,0,0,0,0 +52.09,51,0,10,0,0,0,0,0,0 +52.1,51,0,10,0,0,0,0,0,0 +52.11,51,0,10,0,0,0,0,0,0 +52.12,51,0,10,0,0,0,0,0,0 +52.13,51,0,10,0,0,0,0,0,0 +52.14,51,0,10,0,0,0,0,0,0 +52.15,51,0,10,0,0,0,0,0,0 +52.16,51,0,10,0,0,0,0,0,0 +52.17,51,0,10,0,0,0,0,0,0 +52.18,51,0,10,0,0,0,0,0,0 +52.19,51,0,10,0,0,0,0,0,0 +52.2,51,0,10,0,0,0,0,0,0 +52.21,51,0,10,0,0,0,0,0,0 +52.22,51,0,10,0,0,0,0,0,0 +52.23,51,0,10,0,0,0,0,0,0 +52.24,51,0,10,0,0,0,0,0,0 +52.25,51,0,10,0,0,0,0,0,0 +52.26,51,0,10,0,0,0,0,0,0 +52.27,51,0,10,0,0,0,0,0,0 +52.28,51,0,10,0,0,0,0,0,0 +52.29,51,0,10,0,0,0,0,0,0 +52.3,51,0,10,0,0,0,0,0,0 +52.31,51,0,10,0,0,0,0,0,0 +52.32,51,0,10,0,0,0,0,0,0 +52.33,51,0,10,0,0,0,0,0,0 +52.34,51,0,10,0,0,0,0,0,0 +52.35,51,0,10,0,0,0,0,0,0 +52.36,51,0,10,0,0,0,0,0,0 +52.37,51,0,10,0,0,0,0,0,0 +52.38,51,0,10,0,0,0,0,0,0 +52.39,51,0,10,0,0,0,0,0,0 +52.4,51,0,10,0,0,0,0,0,0 +52.41,51,0,10,0,0,0,0,0,0 +52.42,51,0,10,0,0,0,0,0,0 +52.43,51,0,10,0,0,0,0,0,0 +52.44,51,0,10,0,0,0,0,0,0 +52.45,51,0,10,0,0,0,0,0,0 +52.46,51,0,10,0,0,0,0,0,0 +52.47,51,0,10,0,0,0,0,0,0 +52.48,51,0,10,0,0,0,0,0,0 +52.49,51,0,10,0,0,0,0,0,0 +52.5,51,0,10,0,0,0,0,0,0 +52.51,51,0,10,0,0,0,0,0,0 +52.52,51,0,10,0,0,0,0,0,0 +52.53,51,0,10,0,0,0,0,0,0 +52.54,51,0,10,0,0,0,0,0,0 +52.55,51,0,10,0,0,0,0,0,0 +52.56,51,0,10,0,0,0,0,0,0 +52.57,51,0,10,0,0,0,0,0,0 +52.58,51,0,10,0,0,0,0,0,0 +52.59,51,0,10,0,0,0,0,0,0 +52.6,51,0,10,0,0,0,0,0,0 +52.61,51,0,10,0,0,0,0,0,0 +52.62,51,0,10,0,0,0,0,0,0 +52.63,51,0,10,0,0,0,0,0,0 +52.64,51,0,10,0,0,0,0,0,0 +52.65,51,0,10,0,0,0,0,0,0 +52.66,51,0,10,0,0,0,0,0,0 +52.67,51,0,10,0,0,0,0,0,0 +52.68,51,0,10,0,0,0,0,0,0 +52.69,51,0,10,0,0,0,0,0,0 +52.7,51,0,10,0,0,0,0,0,0 +52.71,51,0,10,0,0,0,0,0,0 +52.72,51,0,10,0,0,0,0,0,0 +52.73,51,0,10,0,0,0,0,0,0 +52.74,51,0,10,0,0,0,0,0,0 +52.75,51,0,10,0,0,0,0,0,0 +52.76,51,0,10,0,0,0,0,0,0 +52.77,51,0,10,0,0,0,0,0,0 +52.78,51,0,10,0,0,0,0,0,0 +52.79,51,0,10,0,0,0,0,0,0 +52.8,51,0,10,0,0,0,0,0,0 +52.81,51,0,10,0,0,0,0,0,0 +52.82,51,0,10,0,0,0,0,0,0 +52.83,51,0,10,0,0,0,0,0,0 +52.84,51,0,10,0,0,0,0,0,0 +52.85,51,0,10,0,0,0,0,0,0 +52.86,51,0,10,0,0,0,0,0,0 +52.87,51,0,10,0,0,0,0,0,0 +52.88,51,0,10,0,0,0,0,0,0 +52.89,51,0,10,0,0,0,0,0,0 +52.9,51,0,10,0,0,0,0,0,0 +52.91,51,0,10,0,0,0,0,0,0 +52.92,51,0,10,0,0,0,0,0,0 +52.93,51,0,10,0,0,0,0,0,0 +52.94,51,0,10,0,0,0,0,0,0 +52.95,51,0,10,0,0,0,0,0,0 +52.96,51,0,10,0,0,0,0,0,0 +52.97,51,0,10,0,0,0,0,0,0 +52.98,51,0,10,0,0,0,0,0,0 +52.99,51,0,10,0,0,0,0,0,0 +53,51,0,10,0,0,0,0,0,0 +53.01,51,0,10,0,0,0,0,0,0 +53.02,51,0,10,0,0,0,0,0,0 +53.03,51,0,10,0,0,0,0,0,0 +53.04,51,0,10,0,0,0,0,0,0 +53.05,51,0,10,0,0,0,0,0,0 +53.06,51,0,10,0,0,0,0,0,0 +53.07,51,0,10,0,0,0,0,0,0 +53.08,51,0,10,0,0,0,0,0,0 +53.09,51,0,10,0,0,0,0,0,0 +53.1,51,0,10,0,0,0,0,0,0 +53.11,51,0,10,0,0,0,0,0,0 +53.12,51,0,10,0,0,0,0,0,0 +53.13,51,0,10,0,0,0,0,0,0 +53.14,51,0,10,0,0,0,0,0,0 +53.15,51,0,10,0,0,0,0,0,0 +53.16,51,0,10,0,0,0,0,0,0 +53.17,51,0,10,0,0,0,0,0,0 +53.18,51,0,10,0,0,0,0,0,0 +53.19,51,0,10,0,0,0,0,0,0 +53.2,51,0,10,0,0,0,0,0,0 +53.21,51,0,10,0,0,0,0,0,0 +53.22,51,0,10,0,0,0,0,0,0 +53.23,51,0,10,0,0,0,0,0,0 +53.24,51,0,10,0,0,0,0,0,0 +53.25,51,0,10,0,0,0,0,0,0 +53.26,51,0,10,0,0,0,0,0,0 +53.27,51,0,10,0,0,0,0,0,0 +53.28,51,0,10,0,0,0,0,0,0 +53.29,51,0,10,0,0,0,0,0,0 +53.3,51,0,10,0,0,0,0,0,0 +53.31,51,0,10,0,0,0,0,0,0 +53.32,51,0,10,0,0,0,0,0,0 +53.33,51,0,10,0,0,0,0,0,0 +53.34,51,0,10,0,0,0,0,0,0 +53.35,51,0,10,0,0,0,0,0,0 +53.36,51,0,10,0,0,0,0,0,0 +53.37,51,0,10,0,0,0,0,0,0 +53.38,51,0,10,0,0,0,0,0,0 +53.39,51,0,10,0,0,0,0,0,0 +53.4,51,0,10,0,0,0,0,0,0 +53.41,51,0,10,0,0,0,0,0,0 +53.42,51,0,10,0,0,0,0,0,0 +53.43,51,0,10,0,0,0,0,0,0 +53.44,51,0,10,0,0,0,0,0,0 +53.45,51,0,10,0,0,0,0,0,0 +53.46,51,0,10,0,0,0,0,0,0 +53.47,51,0,10,0,0,0,0,0,0 +53.48,51,0,10,0,0,0,0,0,0 +53.49,51,0,10,0,0,0,0,0,0 +53.5,51,0,10,0,0,0,0,0,0 +53.51,51,0,10,0,0,0,0,0,0 +53.52,51,0,10,0,0,0,0,0,0 +53.53,51,0,10,0,0,0,0,0,0 +53.54,51,0,10,0,0,0,0,0,0 +53.55,51,0,10,0,0,0,0,0,0 +53.56,51,0,10,0,0,0,0,0,0 +53.57,51,0,10,0,0,0,0,0,0 +53.58,51,0,10,0,0,0,0,0,0 +53.59,51,0,10,0,0,0,0,0,0 +53.6,51,0,10,0,0,0,0,0,0 +53.61,51,0,10,0,0,0,0,0,0 +53.62,51,0,10,0,0,0,0,0,0 +53.63,51,0,10,0,0,0,0,0,0 +53.64,51,0,10,0,0,0,0,0,0 +53.65,51,0,10,0,0,0,0,0,0 +53.66,51,0,10,0,0,0,0,0,0 +53.67,51,0,10,0,0,0,0,0,0 +53.68,51,0,10,0,0,0,0,0,0 +53.69,51,0,10,0,0,0,0,0,0 +53.7,51,0,10,0,0,0,0,0,0 +53.71,51,0,10,0,0,0,0,0,0 +53.72,51,0,10,0,0,0,0,0,0 +53.73,51,0,10,0,0,0,0,0,0 +53.74,51,0,10,0,0,0,0,0,0 +53.75,51,0,10,0,0,0,0,0,0 +53.76,51,0,10,0,0,0,0,0,0 +53.77,51,0,10,0,0,0,0,0,0 +53.78,51,0,10,0,0,0,0,0,0 +53.79,51,0,10,0,0,0,0,0,0 +53.8,51,0,10,0,0,0,0,0,0 +53.81,51,0,10,0,0,0,0,0,0 +53.82,51,0,10,0,0,0,0,0,0 +53.83,51,0,10,0,0,0,0,0,0 +53.84,51,0,10,0,0,0,0,0,0 +53.85,51,0,10,0,0,0,0,0,0 +53.86,51,0,10,0,0,0,0,0,0 +53.87,51,0,10,0,0,0,0,0,0 +53.88,51,0,10,0,0,0,0,0,0 +53.89,51,0,10,0,0,0,0,0,0 +53.9,51,0,10,0,0,0,0,0,0 +53.91,51,0,10,0,0,0,0,0,0 +53.92,51,0,10,0,0,0,0,0,0 +53.93,51,0,10,0,0,0,0,0,0 +53.94,51,0,10,0,0,0,0,0,0 +53.95,51,0,10,0,0,0,0,0,0 +53.96,51,0,10,0,0,0,0,0,0 +53.97,51,0,10,0,0,0,0,0,0 +53.98,51,0,10,0,0,0,0,0,0 +53.99,51,0,10,0,0,0,0,0,0 +54,51,0,10,0,0,0,0,0,0 +54.01,51,0,10,0,0,0,0,0,0 +54.02,51,0,10,0,0,0,0,0,0 +54.03,51,0,10,0,0,0,0,0,0 +54.04,51,0,10,0,0,0,0,0,0 +54.05,51,0,10,0,0,0,0,0,0 +54.06,51,0,10,0,0,0,0,0,0 +54.07,51,0,10,0,0,0,0,0,0 +54.08,51,0,10,0,0,0,0,0,0 +54.09,51,0,10,0,0,0,0,0,0 +54.1,51,0,10,0,0,0,0,0,0 +54.11,51,0,10,0,0,0,0,0,0 +54.12,51,0,10,0,0,0,0,0,0 +54.13,51,0,10,0,0,0,0,0,0 +54.14,51,0,10,0,0,0,0,0,0 +54.15,51,0,10,0,0,0,0,0,0 +54.16,51,0,10,0,0,0,0,0,0 +54.17,51,0,10,0,0,0,0,0,0 +54.18,51,0,10,0,0,0,0,0,0 +54.19,51,0,10,0,0,0,0,0,0 +54.2,51,0,10,0,0,0,0,0,0 +54.21,51,0,10,0,0,0,0,0,0 +54.22,51,0,10,0,0,0,0,0,0 +54.23,51,0,10,0,0,0,0,0,0 +54.24,51,0,10,0,0,0,0,0,0 +54.25,51,0,10,0,0,0,0,0,0 +54.26,51,0,10,0,0,0,0,0,0 +54.27,51,0,10,0,0,0,0,0,0 +54.28,51,0,10,0,0,0,0,0,0 +54.29,51,0,10,0,0,0,0,0,0 +54.3,51,0,10,0,0,0,0,0,0 +54.31,51,0,10,0,0,0,0,0,0 +54.32,51,0,10,0,0,0,0,0,0 +54.33,51,0,10,0,0,0,0,0,0 +54.34,51,0,10,0,0,0,0,0,0 +54.35,51,0,10,0,0,0,0,0,0 +54.36,51,0,10,0,0,0,0,0,0 +54.37,51,0,10,0,0,0,0,0,0 +54.38,51,0,10,0,0,0,0,0,0 +54.39,51,0,10,0,0,0,0,0,0 +54.4,51,0,10,0,0,0,0,0,0 +54.41,51,0,10,0,0,0,0,0,0 +54.42,51,0,10,0,0,0,0,0,0 +54.43,51,0,10,0,0,0,0,0,0 +54.44,51,0,10,0,0,0,0,0,0 +54.45,51,0,10,0,0,0,0,0,0 +54.46,51,0,10,0,0,0,0,0,0 +54.47,51,0,10,0,0,0,0,0,0 +54.48,51,0,10,0,0,0,0,0,0 +54.49,51,0,10,0,0,0,0,0,0 +54.5,51,0,10,0,0,0,0,0,0 +54.51,51,0,10,0,0,0,0,0,0 +54.52,51,0,10,0,0,0,0,0,0 +54.53,51,0,10,0,0,0,0,0,0 +54.54,51,0,10,0,0,0,0,0,0 +54.55,51,0,10,0,0,0,0,0,0 +54.56,51,0,10,0,0,0,0,0,0 +54.57,51,0,10,0,0,0,0,0,0 +54.58,51,0,10,0,0,0,0,0,0 +54.59,51,0,10,0,0,0,0,0,0 +54.6,51,0,10,0,0,0,0,0,0 +54.61,51,0,10,0,0,0,0,0,0 +54.62,51,0,10,0,0,0,0,0,0 +54.63,51,0,10,0,0,0,0,0,0 +54.64,51,0,10,0,0,0,0,0,0 +54.65,51,0,10,0,0,0,0,0,0 +54.66,51,0,10,0,0,0,0,0,0 +54.67,51,0,10,0,0,0,0,0,0 +54.68,51,0,10,0,0,0,0,0,0 +54.69,51,0,10,0,0,0,0,0,0 +54.7,51,0,10,0,0,0,0,0,0 +54.71,51,0,10,0,0,0,0,0,0 +54.72,51,0,10,0,0,0,0,0,0 +54.73,51,0,10,0,0,0,0,0,0 +54.74,51,0,10,0,0,0,0,0,0 +54.75,51,0,10,0,0,0,0,0,0 +54.76,51,0,10,0,0,0,0,0,0 +54.77,51,0,10,0,0,0,0,0,0 +54.78,51,0,10,0,0,0,0,0,0 +54.79,51,0,10,0,0,0,0,0,0 +54.8,51,0,10,0,0,0,0,0,0 +54.81,51,0,10,0,0,0,0,0,0 +54.82,51,0,10,0,0,0,0,0,0 +54.83,51,0,10,0,0,0,0,0,0 +54.84,51,0,10,0,0,0,0,0,0 +54.85,51,0,10,0,0,0,0,0,0 +54.86,51,0,10,0,0,0,0,0,0 +54.87,51,0,10,0,0,0,0,0,0 +54.88,51,0,10,0,0,0,0,0,0 +54.89,51,0,10,0,0,0,0,0,0 +54.9,51,0,10,0,0,0,0,0,0 +54.91,51,0,10,0,0,0,0,0,0 +54.92,51,0,10,0,0,0,0,0,0 +54.93,51,0,10,0,0,0,0,0,0 +54.94,51,0,10,0,0,0,0,0,0 +54.95,51,0,10,0,0,0,0,0,0 +54.96,51,0,10,0,0,0,0,0,0 +54.97,51,0,10,0,0,0,0,0,0 +54.98,51,0,10,0,0,0,0,0,0 +54.99,51,0,10,0,0,0,0,0,0 +55,51,0,10,0,0,0,0,0,0 +55.01,51,0,10,0,0,0,0,0,0 +55.02,51,0,10,0,0,0,0,0,0 +55.03,51,0,10,0,0,0,0,0,0 +55.04,51,0,10,0,0,0,0,0,0 +55.05,51,0,10,0,0,0,0,0,0 +55.06,51,0,10,0,0,0,0,0,0 +55.07,51,0,10,0,0,0,0,0,0 +55.08,51,0,10,0,0,0,0,0,0 +55.09,51,0,10,0,0,0,0,0,0 +55.1,51,0,10,0,0,0,0,0,0 +55.11,51,0,10,0,0,0,0,0,0 +55.12,51,0,10,0,0,0,0,0,0 +55.13,51,0,10,0,0,0,0,0,0 +55.14,51,0,10,0,0,0,0,0,0 +55.15,51,0,10,0,0,0,0,0,0 +55.16,51,0,10,0,0,0,0,0,0 +55.17,51,0,10,0,0,0,0,0,0 +55.18,51,0,10,0,0,0,0,0,0 +55.19,51,0,10,0,0,0,0,0,0 +55.2,51,0,10,0,0,0,0,0,0 +55.21,51,0,10,0,0,0,0,0,0 +55.22,51,0,10,0,0,0,0,0,0 +55.23,51,0,10,0,0,0,0,0,0 +55.24,51,0,10,0,0,0,0,0,0 +55.25,51,0,10,0,0,0,0,0,0 +55.26,51,0,10,0,0,0,0,0,0 +55.27,51,0,10,0,0,0,0,0,0 +55.28,51,0,10,0,0,0,0,0,0 +55.29,51,0,10,0,0,0,0,0,0 +55.3,51,0,10,0,0,0,0,0,0 +55.31,51,0,10,0,0,0,0,0,0 +55.32,51,0,10,0,0,0,0,0,0 +55.33,51,0,10,0,0,0,0,0,0 +55.34,51,0,10,0,0,0,0,0,0 +55.35,51,0,10,0,0,0,0,0,0 +55.36,51,0,10,0,0,0,0,0,0 +55.37,51,0,10,0,0,0,0,0,0 +55.38,51,0,10,0,0,0,0,0,0 +55.39,51,0,10,0,0,0,0,0,0 +55.4,51,0,10,0,0,0,0,0,0 +55.41,51,0,10,0,0,0,0,0,0 +55.42,51,0,10,0,0,0,0,0,0 +55.43,51,0,10,0,0,0,0,0,0 +55.44,51,0,10,0,0,0,0,0,0 +55.45,51,0,10,0,0,0,0,0,0 +55.46,51,0,10,0,0,0,0,0,0 +55.47,51,0,10,0,0,0,0,0,0 +55.48,51,0,10,0,0,0,0,0,0 +55.49,51,0,10,0,0,0,0,0,0 +55.5,51,0,10,0,0,0,0,0,0 +55.51,51,0,10,0,0,0,0,0,0 +55.52,51,0,10,0,0,0,0,0,0 +55.53,51,0,10,0,0,0,0,0,0 +55.54,51,0,10,0,0,0,0,0,0 +55.55,51,0,10,0,0,0,0,0,0 +55.56,51,0,10,0,0,0,0,0,0 +55.57,51,0,10,0,0,0,0,0,0 +55.58,51,0,10,0,0,0,0,0,0 +55.59,51,0,10,0,0,0,0,0,0 +55.6,51,0,10,0,0,0,0,0,0 +55.61,51,0,10,0,0,0,0,0,0 +55.62,51,0,10,0,0,0,0,0,0 +55.63,51,0,10,0,0,0,0,0,0 +55.64,51,0,10,0,0,0,0,0,0 +55.65,51,0,10,0,0,0,0,0,0 +55.66,51,0,10,0,0,0,0,0,0 +55.67,51,0,10,0,0,0,0,0,0 +55.68,51,0,10,0,0,0,0,0,0 +55.69,51,0,10,0,0,0,0,0,0 +55.7,51,0,10,0,0,0,0,0,0 +55.71,51,0,10,0,0,0,0,0,0 +55.72,51,0,10,0,0,0,0,0,0 +55.73,51,0,10,0,0,0,0,0,0 +55.74,51,0,10,0,0,0,0,0,0 +55.75,51,0,10,0,0,0,0,0,0 +55.76,51,0,10,0,0,0,0,0,0 +55.77,51,0,10,0,0,0,0,0,0 +55.78,51,0,10,0,0,0,0,0,0 +55.79,51,0,10,0,0,0,0,0,0 +55.8,51,0,10,0,0,0,0,0,0 +55.81,51,0,10,0,0,0,0,0,0 +55.82,51,0,10,0,0,0,0,0,0 +55.83,51,0,10,0,0,0,0,0,0 +55.84,51,0,10,0,0,0,0,0,0 +55.85,51,0,10,0,0,0,0,0,0 +55.86,51,0,10,0,0,0,0,0,0 +55.87,51,0,10,0,0,0,0,0,0 +55.88,51,0,10,0,0,0,0,0,0 +55.89,51,0,10,0,0,0,0,0,0 +55.9,51,0,10,0,0,0,0,0,0 +55.91,51,0,10,0,0,0,0,0,0 +55.92,51,0,10,0,0,0,0,0,0 +55.93,51,0,10,0,0,0,0,0,0 +55.94,51,0,10,0,0,0,0,0,0 +55.95,51,0,10,0,0,0,0,0,0 +55.96,51,0,10,0,0,0,0,0,0 +55.97,51,0,10,0,0,0,0,0,0 +55.98,51,0,10,0,0,0,0,0,0 +55.99,51,0,10,0,0,0,0,0,0 +56,51,0,10,0,0,0,0,0,0 +56.01,51,0,10,0,0,0,0,0,0 +56.02,51,0,10,0,0,0,0,0,0 +56.03,51,0,10,0,0,0,0,0,0 +56.04,51,0,10,0,0,0,0,0,0 +56.05,51,0,10,0,0,0,0,0,0 +56.06,51,0,10,0,0,0,0,0,0 +56.07,51,0,10,0,0,0,0,0,0 +56.08,51,0,10,0,0,0,0,0,0 +56.09,51,0,10,0,0,0,0,0,0 +56.1,51,0,10,0,0,0,0,0,0 +56.11,51,0,10,0,0,0,0,0,0 +56.12,51,0,10,0,0,0,0,0,0 +56.13,51,0,10,0,0,0,0,0,0 +56.14,51,0,10,0,0,0,0,0,0 +56.15,51,0,10,0,0,0,0,0,0 +56.16,51,0,10,0,0,0,0,0,0 +56.17,51,0,10,0,0,0,0,0,0 +56.18,51,0,10,0,0,0,0,0,0 +56.19,51,0,10,0,0,0,0,0,0 +56.2,51,0,10,0,0,0,0,0,0 +56.21,51,0,10,0,0,0,0,0,0 +56.22,51,0,10,0,0,0,0,0,0 +56.23,51,0,10,0,0,0,0,0,0 +56.24,51,0,10,0,0,0,0,0,0 +56.25,51,0,10,0,0,0,0,0,0 +56.26,51,0,10,0,0,0,0,0,0 +56.27,51,0,10,0,0,0,0,0,0 +56.28,51,0,10,0,0,0,0,0,0 +56.29,51,0,10,0,0,0,0,0,0 +56.3,51,0,10,0,0,0,0,0,0 +56.31,51,0,10,0,0,0,0,0,0 +56.32,51,0,10,0,0,0,0,0,0 +56.33,51,0,10,0,0,0,0,0,0 +56.34,51,0,10,0,0,0,0,0,0 +56.35,51,0,10,0,0,0,0,0,0 +56.36,51,0,10,0,0,0,0,0,0 +56.37,51,0,10,0,0,0,0,0,0 +56.38,51,0,10,0,0,0,0,0,0 +56.39,51,0,10,0,0,0,0,0,0 +56.4,51,0,10,0,0,0,0,0,0 +56.41,51,0,10,0,0,0,0,0,0 +56.42,51,0,10,0,0,0,0,0,0 +56.43,51,0,10,0,0,0,0,0,0 +56.44,51,0,10,0,0,0,0,0,0 +56.45,51,0,10,0,0,0,0,0,0 +56.46,51,0,10,0,0,0,0,0,0 +56.47,51,0,10,0,0,0,0,0,0 +56.48,51,0,10,0,0,0,0,0,0 +56.49,51,0,10,0,0,0,0,0,0 +56.5,51,0,10,0,0,0,0,0,0 +56.51,51,0,10,0,0,0,0,0,0 +56.52,51,0,10,0,0,0,0,0,0 +56.53,51,0,10,0,0,0,0,0,0 +56.54,51,0,10,0,0,0,0,0,0 +56.55,51,0,10,0,0,0,0,0,0 +56.56,51,0,10,0,0,0,0,0,0 +56.57,51,0,10,0,0,0,0,0,0 +56.58,51,0,10,0,0,0,0,0,0 +56.59,51,0,10,0,0,0,0,0,0 +56.6,51,0,10,0,0,0,0,0,0 +56.61,51,0,10,0,0,0,0,0,0 +56.62,51,0,10,0,0,0,0,0,0 +56.63,51,0,10,0,0,0,0,0,0 +56.64,51,0,10,0,0,0,0,0,0 +56.65,51,0,10,0,0,0,0,0,0 +56.66,51,0,10,0,0,0,0,0,0 +56.67,51,0,10,0,0,0,0,0,0 +56.68,51,0,10,0,0,0,0,0,0 +56.69,51,0,10,0,0,0,0,0,0 +56.7,51,0,10,0,0,0,0,0,0 +56.71,51,0,10,0,0,0,0,0,0 +56.72,51,0,10,0,0,0,0,0,0 +56.73,51,0,10,0,0,0,0,0,0 +56.74,51,0,10,0,0,0,0,0,0 +56.75,51,0,10,0,0,0,0,0,0 +56.76,51,0,10,0,0,0,0,0,0 +56.77,51,0,10,0,0,0,0,0,0 +56.78,51,0,10,0,0,0,0,0,0 +56.79,51,0,10,0,0,0,0,0,0 +56.8,51,0,10,0,0,0,0,0,0 +56.81,51,0,10,0,0,0,0,0,0 +56.82,51,0,10,0,0,0,0,0,0 +56.83,51,0,10,0,0,0,0,0,0 +56.84,51,0,10,0,0,0,0,0,0 +56.85,51,0,10,0,0,0,0,0,0 +56.86,51,0,10,0,0,0,0,0,0 +56.87,51,0,10,0,0,0,0,0,0 +56.88,51,0,10,0,0,0,0,0,0 +56.89,51,0,10,0,0,0,0,0,0 +56.9,51,0,10,0,0,0,0,0,0 +56.91,51,0,10,0,0,0,0,0,0 +56.92,51,0,10,0,0,0,0,0,0 +56.93,51,0,10,0,0,0,0,0,0 +56.94,51,0,10,0,0,0,0,0,0 +56.95,51,0,10,0,0,0,0,0,0 +56.96,51,0,10,0,0,0,0,0,0 +56.97,51,0,10,0,0,0,0,0,0 +56.98,51,0,10,0,0,0,0,0,0 +56.99,51,0,10,0,0,0,0,0,0 +57,51,0,10,0,0,0,0,0,0 +57.01,51,0,10,0,0,0,0,0,0 +57.02,51,0,10,0,0,0,0,0,0 +57.03,51,0,10,0,0,0,0,0,0 +57.04,51,0,10,0,0,0,0,0,0 +57.05,51,0,10,0,0,0,0,0,0 +57.06,51,0,10,0,0,0,0,0,0 +57.07,51,0,10,0,0,0,0,0,0 +57.08,51,0,10,0,0,0,0,0,0 +57.09,51,0,10,0,0,0,0,0,0 +57.1,51,0,10,0,0,0,0,0,0 +57.11,51,0,10,0,0,0,0,0,0 +57.12,51,0,10,0,0,0,0,0,0 +57.13,51,0,10,0,0,0,0,0,0 +57.14,51,0,10,0,0,0,0,0,0 +57.15,51,0,10,0,0,0,0,0,0 +57.16,51,0,10,0,0,0,0,0,0 +57.17,51,0,10,0,0,0,0,0,0 +57.18,51,0,10,0,0,0,0,0,0 +57.19,51,0,10,0,0,0,0,0,0 +57.2,51,0,10,0,0,0,0,0,0 +57.21,51,0,10,0,0,0,0,0,0 +57.22,51,0,10,0,0,0,0,0,0 +57.23,51,0,10,0,0,0,0,0,0 +57.24,51,0,10,0,0,0,0,0,0 +57.25,51,0,10,0,0,0,0,0,0 +57.26,51,0,10,0,0,0,0,0,0 +57.27,51,0,10,0,0,0,0,0,0 +57.28,51,0,10,0,0,0,0,0,0 +57.29,51,0,10,0,0,0,0,0,0 +57.3,51,0,10,0,0,0,0,0,0 +57.31,51,0,10,0,0,0,0,0,0 +57.32,51,0,10,0,0,0,0,0,0 +57.33,51,0,10,0,0,0,0,0,0 +57.34,51,0,10,0,0,0,0,0,0 +57.35,51,0,10,0,0,0,0,0,0 +57.36,51,0,10,0,0,0,0,0,0 +57.37,51,0,10,0,0,0,0,0,0 +57.38,51,0,10,0,0,0,0,0,0 +57.39,51,0,10,0,0,0,0,0,0 +57.4,51,0,10,0,0,0,0,0,0 +57.41,51,0,10,0,0,0,0,0,0 +57.42,51,0,10,0,0,0,0,0,0 +57.43,51,0,10,0,0,0,0,0,0 +57.44,51,0,10,0,0,0,0,0,0 +57.45,51,0,10,0,0,0,0,0,0 +57.46,51,0,10,0,0,0,0,0,0 +57.47,51,0,10,0,0,0,0,0,0 +57.48,51,0,10,0,0,0,0,0,0 +57.49,51,0,10,0,0,0,0,0,0 +57.5,51,0,10,0,0,0,0,0,0 +57.51,51,0,10,0,0,0,0,0,0 +57.52,51,0,10,0,0,0,0,0,0 +57.53,51,0,10,0,0,0,0,0,0 +57.54,51,0,10,0,0,0,0,0,0 +57.55,51,0,10,0,0,0,0,0,0 +57.56,51,0,10,0,0,0,0,0,0 +57.57,51,0,10,0,0,0,0,0,0 +57.58,51,0,10,0,0,0,0,0,0 +57.59,51,0,10,0,0,0,0,0,0 +57.6,51,0,10,0,0,0,0,0,0 +57.61,51,0,10,0,0,0,0,0,0 +57.62,51,0,10,0,0,0,0,0,0 +57.63,51,0,10,0,0,0,0,0,0 +57.64,51,0,10,0,0,0,0,0,0 +57.65,51,0,10,0,0,0,0,0,0 +57.66,51,0,10,0,0,0,0,0,0 +57.67,51,0,10,0,0,0,0,0,0 +57.68,51,0,10,0,0,0,0,0,0 +57.69,51,0,10,0,0,0,0,0,0 +57.7,51,0,10,0,0,0,0,0,0 +57.71,51,0,10,0,0,0,0,0,0 +57.72,51,0,10,0,0,0,0,0,0 +57.73,51,0,10,0,0,0,0,0,0 +57.74,51,0,10,0,0,0,0,0,0 +57.75,51,0,10,0,0,0,0,0,0 +57.76,51,0,10,0,0,0,0,0,0 +57.77,51,0,10,0,0,0,0,0,0 +57.78,51,0,10,0,0,0,0,0,0 +57.79,51,0,10,0,0,0,0,0,0 +57.8,51,0,10,0,0,0,0,0,0 +57.81,51,0,10,0,0,0,0,0,0 +57.82,51,0,10,0,0,0,0,0,0 +57.83,51,0,10,0,0,0,0,0,0 +57.84,51,0,10,0,0,0,0,0,0 +57.85,51,0,10,0,0,0,0,0,0 +57.86,51,0,10,0,0,0,0,0,0 +57.87,51,0,10,0,0,0,0,0,0 +57.88,51,0,10,0,0,0,0,0,0 +57.89,51,0,10,0,0,0,0,0,0 +57.9,51,0,10,0,0,0,0,0,0 +57.91,51,0,10,0,0,0,0,0,0 +57.92,51,0,10,0,0,0,0,0,0 +57.93,51,0,10,0,0,0,0,0,0 +57.94,51,0,10,0,0,0,0,0,0 +57.95,51,0,10,0,0,0,0,0,0 +57.96,51,0,10,0,0,0,0,0,0 +57.97,51,0,10,0,0,0,0,0,0 +57.98,51,0,10,0,0,0,0,0,0 +57.99,51,0,10,0,0,0,0,0,0 +58,51,0,10,0,0,0,0,0,0 +58.01,51,0,10,0,0,0,0,0,0 +58.02,51,0,10,0,0,0,0,0,0 +58.03,51,0,10,0,0,0,0,0,0 +58.04,51,0,10,0,0,0,0,0,0 +58.05,51,0,10,0,0,0,0,0,0 +58.06,51,0,10,0,0,0,0,0,0 +58.07,51,0,10,0,0,0,0,0,0 +58.08,51,0,10,0,0,0,0,0,0 +58.09,51,0,10,0,0,0,0,0,0 +58.1,51,0,10,0,0,0,0,0,0 +58.11,51,0,10,0,0,0,0,0,0 +58.12,51,0,10,0,0,0,0,0,0 +58.13,51,0,10,0,0,0,0,0,0 +58.14,51,0,10,0,0,0,0,0,0 +58.15,51,0,10,0,0,0,0,0,0 +58.16,51,0,10,0,0,0,0,0,0 +58.17,51,0,10,0,0,0,0,0,0 +58.18,51,0,10,0,0,0,0,0,0 +58.19,51,0,10,0,0,0,0,0,0 +58.2,51,0,10,0,0,0,0,0,0 +58.21,51,0,10,0,0,0,0,0,0 +58.22,51,0,10,0,0,0,0,0,0 +58.23,51,0,10,0,0,0,0,0,0 +58.24,51,0,10,0,0,0,0,0,0 +58.25,51,0,10,0,0,0,0,0,0 +58.26,51,0,10,0,0,0,0,0,0 +58.27,51,0,10,0,0,0,0,0,0 +58.28,51,0,10,0,0,0,0,0,0 +58.29,51,0,10,0,0,0,0,0,0 +58.3,51,0,10,0,0,0,0,0,0 +58.31,51,0,10,0,0,0,0,0,0 +58.32,51,0,10,0,0,0,0,0,0 +58.33,51,0,10,0,0,0,0,0,0 +58.34,51,0,10,0,0,0,0,0,0 +58.35,51,0,10,0,0,0,0,0,0 +58.36,51,0,10,0,0,0,0,0,0 +58.37,51,0,10,0,0,0,0,0,0 +58.38,51,0,10,0,0,0,0,0,0 +58.39,51,0,10,0,0,0,0,0,0 +58.4,51,0,10,0,0,0,0,0,0 +58.41,51,0,10,0,0,0,0,0,0 +58.42,51,0,10,0,0,0,0,0,0 +58.43,51,0,10,0,0,0,0,0,0 +58.44,51,0,10,0,0,0,0,0,0 +58.45,51,0,10,0,0,0,0,0,0 +58.46,51,0,10,0,0,0,0,0,0 +58.47,51,0,10,0,0,0,0,0,0 +58.48,51,0,10,0,0,0,0,0,0 +58.49,51,0,10,0,0,0,0,0,0 +58.5,51,0,10,0,0,0,0,0,0 +58.51,51,0,10,0,0,0,0,0,0 +58.52,51,0,10,0,0,0,0,0,0 +58.53,51,0,10,0,0,0,0,0,0 +58.54,51,0,10,0,0,0,0,0,0 +58.55,51,0,10,0,0,0,0,0,0 +58.56,51,0,10,0,0,0,0,0,0 +58.57,51,0,10,0,0,0,0,0,0 +58.58,51,0,10,0,0,0,0,0,0 +58.59,51,0,10,0,0,0,0,0,0 +58.6,51,0,10,0,0,0,0,0,0 +58.61,51,0,10,0,0,0,0,0,0 +58.62,51,0,10,0,0,0,0,0,0 +58.63,51,0,10,0,0,0,0,0,0 +58.64,51,0,10,0,0,0,0,0,0 +58.65,51,0,10,0,0,0,0,0,0 +58.66,51,0,10,0,0,0,0,0,0 +58.67,51,0,10,0,0,0,0,0,0 +58.68,51,0,10,0,0,0,0,0,0 +58.69,51,0,10,0,0,0,0,0,0 +58.7,51,0,10,0,0,0,0,0,0 +58.71,51,0,10,0,0,0,0,0,0 +58.72,51,0,10,0,0,0,0,0,0 +58.73,51,0,10,0,0,0,0,0,0 +58.74,51,0,10,0,0,0,0,0,0 +58.75,51,0,10,0,0,0,0,0,0 +58.76,51,0,10,0,0,0,0,0,0 +58.77,51,0,10,0,0,0,0,0,0 +58.78,51,0,10,0,0,0,0,0,0 +58.79,51,0,10,0,0,0,0,0,0 +58.8,51,0,10,0,0,0,0,0,0 +58.81,51,0,10,0,0,0,0,0,0 +58.82,51,0,10,0,0,0,0,0,0 +58.83,51,0,10,0,0,0,0,0,0 +58.84,51,0,10,0,0,0,0,0,0 +58.85,51,0,10,0,0,0,0,0,0 +58.86,51,0,10,0,0,0,0,0,0 +58.87,51,0,10,0,0,0,0,0,0 +58.88,51,0,10,0,0,0,0,0,0 +58.89,51,0,10,0,0,0,0,0,0 +58.9,51,0,10,0,0,0,0,0,0 +58.91,51,0,10,0,0,0,0,0,0 +58.92,51,0,10,0,0,0,0,0,0 +58.93,51,0,10,0,0,0,0,0,0 +58.94,51,0,10,0,0,0,0,0,0 +58.95,51,0,10,0,0,0,0,0,0 +58.96,51,0,10,0,0,0,0,0,0 +58.97,51,0,10,0,0,0,0,0,0 +58.98,51,0,10,0,0,0,0,0,0 +58.99,51,0,10,0,0,0,0,0,0 +59,51,0,10,0,0,0,0,0,0 +59.01,51,0,10,0,0,0,0,0,0 +59.02,51,0,10,0,0,0,0,0,0 +59.03,51,0,10,0,0,0,0,0,0 +59.04,51,0,10,0,0,0,0,0,0 +59.05,51,0,10,0,0,0,0,0,0 +59.06,51,0,10,0,0,0,0,0,0 +59.07,51,0,10,0,0,0,0,0,0 +59.08,51,0,10,0,0,0,0,0,0 +59.09,51,0,10,0,0,0,0,0,0 +59.1,51,0,10,0,0,0,0,0,0 +59.11,51,0,10,0,0,0,0,0,0 +59.12,51,0,10,0,0,0,0,0,0 +59.13,51,0,10,0,0,0,0,0,0 +59.14,51,0,10,0,0,0,0,0,0 +59.15,51,0,10,0,0,0,0,0,0 +59.16,51,0,10,0,0,0,0,0,0 +59.17,51,0,10,0,0,0,0,0,0 +59.18,51,0,10,0,0,0,0,0,0 +59.19,51,0,10,0,0,0,0,0,0 +59.2,51,0,10,0,0,0,0,0,0 +59.21,51,0,10,0,0,0,0,0,0 +59.22,51,0,10,0,0,0,0,0,0 +59.23,51,0,10,0,0,0,0,0,0 +59.24,51,0,10,0,0,0,0,0,0 +59.25,51,0,10,0,0,0,0,0,0 +59.26,51,0,10,0,0,0,0,0,0 +59.27,51,0,10,0,0,0,0,0,0 +59.28,51,0,10,0,0,0,0,0,0 +59.29,51,0,10,0,0,0,0,0,0 +59.3,51,0,10,0,0,0,0,0,0 +59.31,51,0,10,0,0,0,0,0,0 +59.32,51,0,10,0,0,0,0,0,0 +59.33,51,0,10,0,0,0,0,0,0 +59.34,51,0,10,0,0,0,0,0,0 +59.35,51,0,10,0,0,0,0,0,0 +59.36,51,0,10,0,0,0,0,0,0 +59.37,51,0,10,0,0,0,0,0,0 +59.38,51,0,10,0,0,0,0,0,0 +59.39,51,0,10,0,0,0,0,0,0 +59.4,51,0,10,0,0,0,0,0,0 +59.41,51,0,10,0,0,0,0,0,0 +59.42,51,0,10,0,0,0,0,0,0 +59.43,51,0,10,0,0,0,0,0,0 +59.44,51,0,10,0,0,0,0,0,0 +59.45,51,0,10,0,0,0,0,0,0 +59.46,51,0,10,0,0,0,0,0,0 +59.47,51,0,10,0,0,0,0,0,0 +59.48,51,0,10,0,0,0,0,0,0 +59.49,51,0,10,0,0,0,0,0,0 +59.5,51,0,10,0,0,0,0,0,0 +59.51,51,0,10,0,0,0,0,0,0 +59.52,51,0,10,0,0,0,0,0,0 +59.53,51,0,10,0,0,0,0,0,0 +59.54,51,0,10,0,0,0,0,0,0 +59.55,51,0,10,0,0,0,0,0,0 +59.56,51,0,10,0,0,0,0,0,0 +59.57,51,0,10,0,0,0,0,0,0 +59.58,51,0,10,0,0,0,0,0,0 +59.59,51,0,10,0,0,0,0,0,0 +59.6,51,0,10,0,0,0,0,0,0 +59.61,51,0,10,0,0,0,0,0,0 +59.62,51,0,10,0,0,0,0,0,0 +59.63,51,0,10,0,0,0,0,0,0 +59.64,51,0,10,0,0,0,0,0,0 +59.65,51,0,10,0,0,0,0,0,0 +59.66,51,0,10,0,0,0,0,0,0 +59.67,51,0,10,0,0,0,0,0,0 +59.68,51,0,10,0,0,0,0,0,0 +59.69,51,0,10,0,0,0,0,0,0 +59.7,51,0,10,0,0,0,0,0,0 +59.71,51,0,10,0,0,0,0,0,0 +59.72,51,0,10,0,0,0,0,0,0 +59.73,51,0,10,0,0,0,0,0,0 +59.74,51,0,10,0,0,0,0,0,0 +59.75,51,0,10,0,0,0,0,0,0 +59.76,51,0,10,0,0,0,0,0,0 +59.77,51,0,10,0,0,0,0,0,0 +59.78,51,0,10,0,0,0,0,0,0 +59.79,51,0,10,0,0,0,0,0,0 +59.8,51,0,10,0,0,0,0,0,0 +59.81,51,0,10,0,0,0,0,0,0 +59.82,51,0,10,0,0,0,0,0,0 +59.83,51,0,10,0,0,0,0,0,0 +59.84,51,0,10,0,0,0,0,0,0 +59.85,51,0,10,0,0,0,0,0,0 +59.86,51,0,10,0,0,0,0,0,0 +59.87,51,0,10,0,0,0,0,0,0 +59.88,51,0,10,0,0,0,0,0,0 +59.89,51,0,10,0,0,0,0,0,0 +59.9,51,0,10,0,0,0,0,0,0 +59.91,51,0,10,0,0,0,0,0,0 +59.92,51,0,10,0,0,0,0,0,0 +59.93,51,0,10,0,0,0,0,0,0 +59.94,51,0,10,0,0,0,0,0,0 +59.95,51,0,10,0,0,0,0,0,0 +59.96,51,0,10,0,0,0,0,0,0 +59.97,51,0,10,0,0,0,0,0,0 +59.98,51,0,10,0,0,0,0,0,0 +59.99,51,0,10,0,0,0,0,0,0 +60,51,0,10,0,0,0,0,0,0 \ No newline at end of file diff --git a/Profile_1.csv b/Profile_1.csv new file mode 100644 index 0000000..9f0df81 --- /dev/null +++ b/Profile_1.csv @@ -0,0 +1,6001 @@ +0,51,0,10,0,0,0,0,0,0 +0.01,50.9999999999,1.66948022706e-010,10.0000075253,-0.0012878866903,0.00234387636453,-0.0015050557618,-0.00252317821495,0.000421028840123,-0.00130219767196 +0.02,50.9999999998,4.99529516758e-010,10.0000225166,-0.00127774585022,0.00232542064512,-0.00149320492903,-0.00250331066995,0.00277991837682,-0.00129194414698 +0.03,50.9999999997,8.42187452819e-010,10.0000383737,-0.00182628577461,0.00248534515156,-0.00167821554274,-0.00181142938199,0.00416261735389,-0.000364590643437 +0.04,50.9999999995,1.18221628616e-009,10.0000541123,-0.00125746417006,0.00228850920631,-0.00146950326349,-0.00246357557995,0.00749769745021,-0.00127143709703 +0.05,50.9999999994,1.5756494092e-009,10.0000704542,-0.00303606843695,0.00323511774766,-0.00179887269029,-0.00191654704254,0.00711628776675,-0.00225802819234 +0.06,50.9999999991,1.97915897425e-009,10.0000876618,-0.00179586325437,0.00242997799335,-0.00164266304443,-0.00175182674699,0.011239285964,-0.000333830068512 +0.07,50.999999999,2.46218490567e-009,10.0001049128,-0.000331210766587,0.00435149234577,-0.0018075387291,-0.00137622444921,0.0161274350951,0.00125033619511 +0.08,50.999999999,2.92987618964e-009,10.000121061,-0.00121690080973,0.00221468632869,-0.00142209993241,-0.00238410539995,0.016933255597,-0.00123042299713 +0.09,50.9999999987,3.20355589846e-009,10.0001381627,-0.00396625509767,0.00162765568042,-0.00199824127742,-0.000493897734759,0.0163546729231,-0.00205381219852 +0.1,50.9999999984,3.54334544171e-009,10.000156852,-0.00298536423654,0.00314283915063,-0.00173961852644,-0.00181720931754,0.0189107354502,-0.00220676056746 +0.11,50.9999999982,3.96642785757e-009,10.0001715716,-0.00108934279102,0.00279705075506,-0.00120429807349,-0.00209414053647,0.0230551297296,-0.000175281627781 +0.12,50.9999999981,4.33084777829e-009,10.0001854509,-0.00173501821388,0.00231924367691,-0.00157155804781,-0.00163262147699,0.0253926231842,-0.000272308918657 +0.13,50.999999998,4.85701943672e-009,10.0001985956,-0.00148841192622,0.00506797357767,-0.00105737392255,-0.00216344334466,0.0297075268081,-8.84480152868e-005 +0.14,50.9999999979,5.51874085393e-009,10.0002125054,-0.000260224886017,0.00422230230992,-0.00172458289971,-0.00123715163421,0.032639661852,0.00132211086994 +0.15,50.9999999978,6.08707045556e-009,10.0002339797,-0.000853079873041,0.00375679381245,-0.0025702815795,-0.0021272233293,0.032879685825,-0.000698766543868 +0.16,50.9999999978,6.50188654822e-009,10.0002534675,-0.00113577408908,0.00206704057344,-0.00132729327025,-0.00222516503995,0.0358043718906,-0.00114839479732 +0.17,50.9999999976,6.66924671971e-009,10.0002709415,-0.00157916441884,0.000282622177928,-0.00216749633506,-0.00130273229899,0.0350028189001,-0.0012582851383 +0.18,50.9999999974,6.79347972231e-009,10.0002912369,-0.00387498753694,0.00146155420576,-0.00189158378249,-0.000315089829759,0.0375846787534,-0.00196153047373 +0.19,50.999999997,7.0692158022e-009,10.0003073472,-0.00539816263877,0.00240965834346,-0.00133048267148,-0.00242217443899,0.0394861349567,-0.00135185153218 +0.2,50.9999999966,7.45155978269e-009,10.0003221052,-0.00288395583573,0.00295828195657,-0.00162111019874,-0.00161853386754,0.0424996308172,-0.0021042253177 +0.21,50.9999999964,7.72769804195e-009,10.0003367447,-0.00220733959957,0.000918577013153,-0.00130679374413,-0.00142280576692,0.0458241085173,-0.000586684816474 +0.22,50.9999999962,7.9778921705e-009,10.0003486484,-0.000977793550131,0.00259403784159,-0.00107393891302,-0.00187559754147,0.0490029146332,-6.24928530431e-005 +0.23,50.9999999961,8.42231305623e-009,10.0003655253,-0.000872700477033,0.00364543473937,-0.00230143671827,-0.00368198128222,0.0522862226177,-0.000481979022435 +0.24,50.999999996,8.83138647482e-009,10.0003841792,-0.00161332813291,0.00209777504404,-0.00142934805457,-0.00139421093699,0.0536992976245,-0.000149266618942 +0.25,50.9999999958,9.3066521696e-009,10.0003996951,-0.00269952018263,0.00457474500725,-0.00167382753039,-0.000619818822938,0.0574684515104,0.00161210882507 +0.26,50.9999999957,9.97638796649e-009,10.0004125808,-0.00135658100517,0.00482804922539,-0.000903313096545,-0.00190516525966,0.0603730907851,4.48478094057e-005 +0.27,50.9999999956,1.06793915863e-008,10.0004263707,-0.000290471991849,0.00504181052027,-0.00185466957803,-0.00211417633874,0.0648650440095,0.000355331713413 +0.28,50.9999999956,1.13208457601e-008,10.0004434374,-0.000118253124885,0.00396392223824,-0.00155867124093,-0.000959006004212,0.0656641153657,0.00146566021961 +0.29,50.9999999955,1.1751720115e-008,10.0004582019,-0.000245442713418,0.00208536304463,-0.0013942296091,-0.0015418234708,0.0674595915779,0.000179474004899 +0.3,50.9999999955,1.21481229977e-008,10.0004771356,-0.000700967271829,0.00347995802137,-0.00239251908795,-0.00182921015431,0.0682630288754,-0.000544963669223 +0.31,50.9999999954,1.2702742549e-008,10.0004970417,-0.00192267434915,0.00430665506172,-0.00158868757608,-0.00424194219992,0.0711467072363,-0.00143254544007 +0.32,50.9999999953,1.31356909608e-008,10.0005106735,-0.000973520647787,0.00177174906295,-0.00113767994593,-0.00190728431996,0.0735466044777,-0.000984338397701 +0.33,50.9999999952,1.34303469042e-008,10.0005262452,-0.00117197654953,0.00236508999837,-0.00197665279539,0.000496158143711,0.0747440933079,-0.00229129632089 +0.34,50.999999995,1.35965889632e-008,10.0005459586,-0.00140677013746,-3.11250519673e-005,-0.00196603217797,-0.000964984034005,0.0751039410239,-0.0010839752137 +0.35,50.999999995,1.36778539316e-008,10.0005616131,-0.000619398236892,0.001172049249,-0.00116486615114,-0.00213814291379,0.0785528536525,-0.000765279703284 +0.36,50.9999999948,1.38417765128e-008,10.0005758288,-0.00369245241548,0.00112935125646,-0.00167826879263,4.25259802312e-005,0.0800446904139,-0.00177696702416 +0.37,50.9999999944,1.40923821192e-008,10.0005885914,-0.00536757052416,0.00238904056518,-0.000874257712511,-0.000434296108809,0.0829356707348,-0.00228079793781 +0.38,50.9999999939,1.44092040873e-008,10.0005984893,-0.00520548667723,0.00205899967476,-0.00110531684885,-0.002044691084,0.0843050361539,-0.00115703455763 +0.39,50.9999999934,1.46685779669e-008,10.0006175777,-0.00525015049425,0.00158249482268,-0.00271236444609,-0.00208176317412,0.0879556988575,-0.00143323138958 +0.4,50.9999999931,1.49657142826e-008,10.00063806,-0.00268113903411,0.00258916756846,-0.00138409354334,-0.00122118296755,0.089677421551,-0.00189915481817 +0.41,50.9999999928,1.53175102599e-008,10.0006550916,-0.00202308908189,0.00234989228517,-0.00202223380559,-0.00148655743762,0.0928453202017,0.000365454053776 +0.42,50.9999999927,1.55227089772e-008,10.0006704924,-0.00199438195787,0.000531006905638,-0.00105792625596,-0.00100558732193,0.0953607887876,-0.00037136079197 +0.43,50.9999999925,1.55064925152e-008,10.0006769245,-0.00121416517524,-0.000758678856686,-0.000228492826255,-0.00241771331365,0.099353711221,-0.000467660921903 +0.44,50.9999999924,1.56083000798e-008,10.0006821331,-0.000754695068346,0.00218801201467,-0.000813220592079,-0.00143851155148,0.10089848444,0.000163084696435 +0.45,50.9999999924,1.60065735015e-008,10.0006925089,0.000782598564521,0.00340357059261,-0.00126194480021,-0.00341521050427,0.10281086468,-0.00238978653587 +0.46,50.9999999924,1.64784205511e-008,10.0007089629,-0.000639461155165,0.00322095319304,-0.00202886756455,-0.00322502774723,0.106540681961,-0.000246147947983 +0.47,50.9999999923,1.67632998589e-008,10.0007318324,-0.00336353962,0.000778626230719,-0.00254502157907,-0.00181254142915,0.108676090352,-0.00101802771437 +0.48,50.999999992,1.6936628969e-008,10.0007502821,-0.00136994797096,0.00165483777831,-0.00114492806808,-0.000917389857005,0.110312646505,9.68179804842e-005 +0.49,50.9999999918,1.73464845212e-008,10.0007615316,-0.00292074161013,0.00409935281572,-0.00110496701426,-0.000978921121605,0.112870426685,0.00149611984769 +0.5,50.9999999916,1.79314534445e-008,10.0007739442,-0.0024459991806,0.00411335202211,-0.00137755671113,-0.000123130197956,0.116440689928,0.00186844694947 +0.51,50.9999999913,1.8541089363e-008,10.0007830161,-0.00343404997189,0.004445666513,-0.000436810944454,0.000839632009488,0.118362871739,0.0010755031971 +0.52,50.9999999911,1.91674529097e-008,10.0007881761,-0.00109291916306,0.00434820052085,-0.000595191444515,-0.00138860908968,0.121704218739,0.000311439458784 +0.53,50.9999999911,1.99098741638e-008,10.0008035266,0.000218818154115,0.00607506536889,-0.00247491930309,-0.0034854192318,0.124588485901,0.000402952120554 +0.54,50.9999999911,2.06662065098e-008,10.0008235747,-1.66693096571e-005,0.00454350609632,-0.00153469709323,-0.00157775262375,0.1285550615,0.000632176887767 +0.55,50.9999999911,2.12887376968e-008,10.0008410686,0.000513389114457,0.00419655630253,-0.00196407088493,-0.000113841232766,0.130295352273,0.000765113701309 +0.56,50.9999999912,2.1833179243e-008,10.0008570231,0.000165690397388,0.00344716209489,-0.00122684792336,-0.000402714744225,0.131713022393,0.00175275891894 +0.57,50.9999999912,2.23471869695e-008,10.0008663552,0.000212632954881,0.00376927893981,-0.000639571763896,-0.00113914682622,0.131739052808,0.000808954198249 +0.58,50.9999999912,2.27260754152e-008,10.0008748059,4.86416489358e-005,0.00155014718187,-0.00105055545876,-0.00096566466581,0.135867388142,0.000476826229205 +0.59,50.9999999912,2.29649840715e-008,10.000885455,4.38086452391e-006,0.00180402463605,-0.00107926153348,-0.00238450586033,0.137037081759,0.000729666853286 +0.6,50.9999999912,2.33019114335e-008,10.0009010362,-0.000396742069394,0.0029262864392,-0.00203699410484,-0.00123318380432,0.139029714976,-0.000237357919941 +0.61,50.999999991,2.37808149004e-008,10.0009188064,-0.00264603299096,0.00379730632448,-0.00151704567368,-0.000714702485329,0.140978916847,-0.00264577305136 +0.62,50.9999999908,2.43172872274e-008,10.0009324982,-0.00160830830664,0.00373452776014,-0.0012213117602,-0.00362604830493,0.144272282874,-0.00111468616581 +0.63,50.9999999908,2.48358270869e-008,10.0009397709,-0.000387620887696,0.00354554241629,-0.00023321239536,-0.000581293876659,0.145076049915,-0.00209097117553 +0.64,50.9999999907,2.51724978442e-008,10.0009447292,-0.000649013765191,0.00118116604197,-0.000758453297284,-0.00127152287997,0.149031069652,-0.000656225598467 +0.65,50.9999999907,2.54482865665e-008,10.0009425279,-0.000265653402336,0.00269078558428,0.00119871793507,7.14378710968e-005,0.15112904869,-0.000442757802588 +0.66,50.9999999906,2.57650228198e-008,10.0009444621,-0.000837328826858,0.00175605125798,-0.00158557531397,0.0011517871287,0.152587448019,-0.00195292999668 +0.67,50.9999999905,2.59273337705e-008,10.0009597781,-0.00120991214968,0.000522722668872,-0.00147761574043,0.000596325559601,0.156073875351,-8.32517806823e-005 +0.68,50.9999999904,2.59176542031e-008,10.0009749817,-0.00106198157471,-0.000658619511755,-0.00156310386378,-0.000289487504015,0.155306185272,-0.000735355364516 +0.69,50.9999999903,2.58996417946e-008,10.0009927757,-0.00102733240569,0.000405733265639,-0.00199570226245,-0.00146617272693,0.156618677431,-0.000566012995844 +0.7,50.9999999903,2.59660137108e-008,10.0010065047,-0.000264468834057,0.000526099069808,-0.000750087004187,-0.0014427788388,0.161113987437,-0.000406406329122 +0.71,50.9999999901,2.62260389406e-008,10.0010111618,-0.00320070805112,0.00312454009625,-0.000181333834809,-0.00199653743377,0.162466703135,-0.00150066049867 +0.72,50.9999999898,2.64817083556e-008,10.0010183266,-0.00332738217256,0.000464945357864,-0.00125163881291,0.00075775760022,0.164964713735,-0.00140784012502 +0.73,50.9999999894,2.66625504269e-008,10.0010306071,-0.00596261750445,0.00207399730226,-0.00120446064364,0.00182721245303,0.168058349151,-0.00071598478418 +0.74,50.9999999889,2.69318022354e-008,10.0010388083,-0.00499235944116,0.00170617894717,-0.000435776900022,0.000300803056175,0.170214583592,-0.0019014175137 +0.75,50.9999999885,2.73344584677e-008,10.0010442843,-0.00458658564571,0.00394693638219,-0.000659412931553,-0.000359224098509,0.173224272538,-0.00174425603523 +0.76,50.9999999881,2.77122922219e-008,10.0010508563,-0.00482013475415,0.00135768233735,-0.000654985203591,-0.00128972437402,0.173942838548,-0.000767400608541 +0.77,50.9999999876,2.79052712926e-008,10.00107507,-0.0048924224702,0.00135165842385,-0.00418776392707,-0.00107657585013,0.176781003611,0.000766448739576 +0.78,50.9999999872,2.80629956503e-008,10.0011072597,-0.00485465773109,0.000862721765864,-0.00225018196806,-0.00130692891914,0.179952390789,-0.00103334391551 +0.79,50.9999999868,2.83442335235e-008,10.0011251518,-0.00396177096145,0.00308573352847,-0.00132822857559,-0.0015755148907,0.183111487155,-0.00111107468114 +0.8,50.9999999865,2.86958594432e-008,10.0011363432,-0.00227550543086,0.00185093879224,-0.000910060232534,-0.000426481167563,0.184033003019,-0.00148901381913 +0.81,50.9999999863,2.89437091248e-008,10.0011445605,-0.00230576724586,0.00162876106662,-0.000733398462556,0.00105668735841,0.186482160423,0.000422846025358 +0.82,50.9999999861,2.91732013189e-008,10.0011559093,-0.00160731463856,0.00159320778955,-0.00153634966201,-0.000671988092634,0.189559791206,0.000785848577793 +0.83,50.999999986,2.93824748808e-008,10.0011677906,-0.0013973098765,0.00134490041759,-0.000839913498374,-4.58525667853e-005,0.191053655691,0.000802903717213 +0.84,50.9999999859,2.94608795675e-008,10.0011747911,-0.00156846667446,-0.000244133309392,-0.000560191279615,-0.000171150431942,0.194434149329,5.92872570229e-005 +0.85,50.9999999858,2.94065623722e-008,10.0011728451,-0.000829373980387,-0.000518456077964,0.000949390150914,0.000272744968883,0.197849104199,-0.000441171551408 +0.86,50.9999999857,2.92590697701e-008,10.0011666927,-0.000778109051745,-0.00155227479112,0.00028109298286,-0.00156340887867,0.200785961299,-2.67593479345e-005 +0.87,50.9999999856,2.91331259528e-008,10.0011665886,-3.7292580545e-005,-0.000215920675048,-0.000260266312827,-0.00115330531468,0.202377231096,-5.96812316865e-005 +0.88,50.9999999856,2.92157524661e-008,10.0011693488,-0.000308498104776,0.00137596036083,-0.000291783950195,-0.000564339571496,0.204689624055,0.00061423979538 +0.89,50.9999999857,2.94451793179e-008,10.0011667204,0.000866487355994,0.00184509111829,0.000817462593948,-0.000774090559199,0.206032612066,-0.00071346923677 +0.9,50.9999999857,2.97598725933e-008,10.0011662764,0.00123893636817,0.00257306321936,-0.00072865732556,-0.00252117097929,0.208960893831,-0.00192837791195 +0.91,50.9999999858,3.0140855981e-008,10.0011651682,0.000206245960093,0.00277577496293,0.000950307011005,-0.000459848950779,0.212590514179,-0.00106650748788 +0.92,50.9999999858,3.05075174702e-008,10.0011678353,-0.000172982511435,0.00237199010038,-0.00148372925713,-0.00231112067725,0.215049600649,0.000225514200915 +0.93,50.9999999857,3.08392134903e-008,10.0011832815,-0.00211938073208,0.0022848752492,-0.0016055129798,-0.000922906855228,0.217415236606,0.000147843142661 +0.94,50.9999999855,3.09956345646e-008,10.0012012492,-0.00288692013619,-8.87925813483e-005,-0.00198803243888,-0.000878766814172,0.219543898577,-0.000536112040499 +0.95,50.9999999853,3.10292926658e-008,10.0012171446,-0.00183025476357,0.000561337428687,-0.00119105443053,-0.000593276941966,0.220898422938,-0.00203527661786 +0.96,50.9999999852,3.11240464125e-008,10.0012259804,-0.000883187647069,0.000768963246835,-0.000576088095118,3.6252302975e-005,0.223539344266,0.000588987179335 +0.97,50.999999985,3.12557006969e-008,10.0012288725,-0.00212424143089,0.00107940465107,-2.34090974225e-006,-0.000827065613368,0.22768889377,0.00187339549151 +0.98,50.9999999848,3.15601566752e-008,10.0012315056,-0.00242384044615,0.00319502256484,-0.000524276208529,-5.41141662493e-006,0.228456013983,0.00199854257152 +0.99,50.9999999846,3.20247509619e-008,10.0012427441,-0.00148873496834,0.00332767564109,-0.00172342552808,0.000240371451552,0.230890164362,0.000741894933119 +1,50.9999999845,3.24890278231e-008,10.0012552863,-0.00193895717654,0.00319056605183,-0.000785015072624,0.000870247052024,0.234385166762,0.00238112319828 +1.01,50.9999999843,3.2931615884e-008,10.0012540495,-0.00200751807693,0.00302317448197,0.0010323796089,0.0027523175724,0.235949553536,0.000710520107688 +1.02,50.9999999841,3.33965592628e-008,10.0012480497,-0.00291686712775,0.00350442482332,0.000167581526821,0.00185287680447,0.23866623811,0.00159843297089 +1.03,50.9999999838,3.3891578212e-008,10.0012459727,-0.00266330332069,0.00344542218178,0.000247806266172,-0.000287183181808,0.24044110723,0.00171872992082 +1.04,50.9999999837,3.43783403688e-008,10.0012446284,-0.00056559547884,0.00338850311176,2.1051859529e-005,-0.0003554967497,0.244366474647,0.000844622757539 +1.05,50.9999999837,3.49505555974e-008,10.0012523504,-5.78096963212e-005,0.00464514549818,-0.00156543907505,-0.0036373165646,0.247065623663,0.000841281117881 +1.06,50.9999999837,3.5644456223e-008,10.0012694117,0.000756282678415,0.00509691224039,-0.00184682516627,-0.00243243934682,0.249609631346,0.000946388944283 +1.07,50.9999999837,3.63479232045e-008,10.0012851032,-5.3309610382e-005,0.00477945290184,-0.00129148458702,-0.000919098692018,0.250067554384,0.00157492388329 +1.08,50.9999999837,3.69409867782e-008,10.0012960344,0.000530936054723,0.00354689724842,-0.000894752123649,-0.000504905193776,0.255935096482,0.00118586723647 +1.09,50.9999999838,3.74401690101e-008,10.0013004517,0.000476046221142,0.00346140040287,1.12918939239e-005,-0.00108891176101,0.257439560126,0.00185630066003 +1.1,50.9999999839,3.79133243879e-008,10.0013069566,0.00107113531892,0.00318149173522,-0.00131227508258,0.000978873742208,0.260034276791,0.00132905757499 +1.11,50.999999984,3.83403753513e-008,10.001313694,0.00178950010935,0.00281411482397,-3.51964567449e-005,0.00216765554265,0.262922406679,0.00129038612863 +1.12,50.9999999841,3.87127344252e-008,10.001316686,0.000733577441929,0.00241364180817,-0.000563201288235,0.00070986777575,0.263810836448,0.0023269563176 +1.13,50.9999999842,3.91269359338e-008,10.0013192977,0.00135864818341,0.00340156409265,4.08551029532e-005,0.00167548911158,0.263202474093,0.00373544646067 +1.14,50.9999999843,3.95627664094e-008,10.0013189138,0.000790660839503,0.00271730293369,3.5925704002e-005,-6.69676124078e-006,0.2661957564,0.00139340512189 +1.15,50.9999999844,3.98284713674e-008,10.0013221046,0.00126856698425,0.00101307710461,-0.000674084609683,0.00065457322576,0.268693577691,0.00229458556629 +1.16,50.9999999845,3.9934798975e-008,10.0013272911,0.000636810373639,0.000479715456336,-0.000363207158089,0.000186652944165,0.27268298127,0.00107153067782 +1.17,50.9999999845,4.00343726903e-008,10.0013238638,0.000431633983725,0.000918255447244,0.00104866323229,-0.00187642978946,0.273383354185,0.0027037143415 +1.18,50.9999999846,4.0150714864e-008,10.0013205208,0.000602690429309,0.000715137191117,-0.000380062400039,-0.00121232070535,0.276211564424,0.00133462482688 +1.19,50.9999999846,4.04933398957e-008,10.0013253156,0.000522545256827,0.00409516664497,-0.000578904707708,-0.00049415770022,0.277160774454,4.29804934094e-005 +1.2,50.9999999846,4.09145860722e-008,10.0013348399,0.000211708335472,0.00181894327486,-0.00132594413863,-4.11311043446e-005,0.280563087178,0.000377853578622 +1.21,50.9999999845,4.11230833978e-008,10.0013404088,-0.00242100501033,0.00110826691821,0.00021214781777,-0.00108295110651,0.282114193158,0.000987232038499 +1.22,50.9999999843,4.13923065806e-008,10.0013433188,-0.00202744174601,0.00267150744074,-0.000794144874702,0.000497217759644,0.284871178585,-0.00202030802782 +1.23,50.9999999842,4.18111923394e-008,10.0013576053,-0.000924873245678,0.00320946325899,-0.00206315830104,-0.00116669456553,0.287910473468,0.000450894656806 +1.24,50.9999999841,4.22242919981e-008,10.0013703539,-0.00097957622161,0.00259027315699,-0.000486560128451,-0.00239426051496,0.290523434149,-0.000478967617294 +1.25,50.999999984,4.2548145819e-008,10.0013770171,-0.00104363127729,0.00195649118512,-0.000846079432755,0.000635023676737,0.292005836037,-0.00342612927402 +1.26,50.999999984,4.28572241696e-008,10.0013786806,0.000251252037414,0.00238283209373,0.000513390069156,0.000670361458311,0.293686090727,-0.00144499910203 +1.27,50.999999984,4.3030921153e-008,10.0013712554,0.000150857831465,5.57966932963e-005,0.00097164780189,-0.000371669767955,0.295748172393,-0.000567158742228 +1.28,50.999999984,4.30348954017e-008,10.0013663972,0,0,0,0,0.3,0 +1.29,50.9999999858,4.30631769815e-008,10.0013562268,0.0398870785431,0.00039706086547,0.00203406995871,0.0007261504993,0.305436170517,0.00220553251665 +1.3,50.9999999911,4.32002992609e-008,10.0013363299,0.0784982195232,0.00152807526172,0.00194532039958,0.00132309320607,0.310676589501,0.0002032142709 +1.31,51,4.32752429386e-008,10.0013220988,0.117945174841,-0.000475899188416,0.000900880378842,0.0017474053316,0.316426640968,-0.00154587750423 +1.32,51.0000000123,4.32849225504e-008,10.0013218486,0.156041403259,0.000611796654824,-0.000850823682229,0.00238357491867,0.320713599294,-0.00131721144817 +1.33,51.000000028,4.32416869267e-008,10.0013310447,0.194026095437,-0.00121880567941,-0.000988412207886,0.000124351760192,0.326920073565,0.000548149752986 +1.34,51.0000000472,4.3111919169e-008,10.0013397604,0.233783679097,-0.000603076214878,-0.000754714941456,0.00180824580457,0.332778637089,0.000542213242853 +1.35,51.00000007,4.30603687939e-008,10.0013515671,0.27349287174,-0.000120668240376,-0.00160662314206,0.00227056510897,0.336323028137,0.00157016389601 +1.36,51.0000000964,4.2925989137e-008,10.0013638605,0.312046468832,-0.0017659626761,-0.000852053897576,0.000902565195955,0.340589557473,-0.000120143865955 +1.37,51.0000001262,4.26114851302e-008,10.0013807627,0.351206162011,-0.00264953440282,-0.00252838963345,-0.00176903515057,0.343858694812,-0.000198813150423 +1.38,51.0000001595,4.23741066664e-008,10.0013998871,0.390195977161,-0.000683154179301,-0.00129650312901,-0.000293987571967,0.350480660096,3.89449777408e-005 +1.39,51.0000001963,4.2087046198e-008,10.0014013057,0.428629246639,-0.00334704775818,0.00101278405066,-0.000616960269861,0.358303500733,-0.000238115475488 +1.4,51.0000002366,4.18098736141e-008,10.0013965555,0.469073699893,-0.000544332655727,-6.27387035211e-005,-0.000290461228835,0.363554580565,0.000188298119486 +1.41,51.0000002805,4.18197368413e-008,10.0013959792,0.506494478441,0.000682807999888,0.000177994961763,0.001819281458,0.368049696766,0.00302517002145 +1.42,51.0000003277,4.20159946014e-008,10.0013926184,0.544252319836,0.00207256409012,0.000494163633088,-0.000864087368807,0.373485906726,-0.000916209575036 +1.43,51.0000003783,4.22378545885e-008,10.0013977289,0.581559023433,0.00104225193438,-0.00151626667938,0.00101771327045,0.377080864935,-0.000805643423136 +1.44,51.0000004324,4.22715933305e-008,10.0014082502,0.622240504875,-0.000568574928861,-0.000587992177782,0.00187034012019,0.38456252779,-0.000833642726365 +1.45,51.00000049,4.23905814217e-008,10.0014094374,0.658832704304,0.0022391150585,0.00035056314189,0.00425461190783,0.38983996264,-0.001862877788 +1.46,51.000000551,4.26254925169e-008,10.0014104479,0.697720128703,0.00105893273495,-0.000552664841285,0.002919927428,0.396234773669,-0.000152040910497 +1.47,51.0000006154,4.27972503389e-008,10.0014074328,0.735843217531,0.00135247105391,0.00115567552922,0.00478780013997,0.402577861749,-0.000151901076588 +1.48,51.0000006834,4.29441239979e-008,10.0014006336,0.776805245927,0.000709570099261,0.000204168069565,0.00137365048615,0.406969618574,-0.00134772716499 +1.49,51.0000007551,4.31021270881e-008,10.0014036624,0.819266855704,0.0015087233356,-0.000809930917108,-0.000105279566329,0.410618993792,0.000442158603374 +1.5,51.0000008304,4.34210478707e-008,10.0014078687,0.855325878883,0.00296878325369,-3.1318794737e-005,0.000693755786467,0.418557917983,-0.0012008192115 +1.51,51.0000009089,4.36917366357e-008,10.0014028134,0.89263408718,0.00083156715937,0.0010423699219,-0.000285743940138,0.427020095027,-0.000598577322188 +1.52,51.000000991,4.37793143326e-008,10.0013977953,0.933207188935,0.000397984928248,-3.87418995453e-005,-0.000256612034042,0.427855094456,-0.000234217309789 +1.53,51.0000010766,4.38846994369e-008,10.0014105284,0.971455395895,0.00108157527005,-0.00250787400112,-0.000246317686758,0.43359329738,0.0028257559769 +1.54,51.0000011657,4.39909700255e-008,10.0014409846,1.01124976038,0.000410416734154,-0.0035833714558,-6.3331055153e-005,0.439271869982,0.00128937851335 +1.55,51.0000012583,4.40792797818e-008,10.0014649082,1.04919644103,0.000829413134249,-0.00120133923103,-0.00113452391632,0.445207724678,-0.000596381759784 +1.56,51.0000013544,4.41340784426e-008,10.001479203,1.08940238428,-6.00642044274e-005,-0.00165764032956,-0.00031355166916,0.451021867623,-0.000520667666714 +1.57,51.0000014542,4.42183742672e-008,10.0014913491,1.13067437553,0.00124354024297,-0.000771567217593,-0.000719984642736,0.457342207957,-0.00116726775963 +1.58,51.0000015576,4.44623238098e-008,10.0014989446,1.16841013021,0.00218140327759,-0.000747537769863,-0.000602005185722,0.462759574452,-0.000608651957317 +1.59,51.0000016643,4.47408142517e-008,10.0015095746,1.20586373242,0.00172847916126,-0.0013784580424,5.249530406e-005,0.469013892518,-0.000957589407858 +1.6,51.0000017746,4.49326681274e-008,10.001518173,1.2482112549,0.00096506426076,-0.000341220259571,0.000527160992414,0.47225970078,-0.000996844620281 +1.61,51.0000018885,4.50513018029e-008,10.001510624,1.28584355807,0.000700499982026,0.00185102136156,0.00293481137485,0.478821072481,0.00168674876223 +1.62,51.0000020059,4.51554249063e-008,10.0015022509,1.32629585224,0.000761342254542,-0.000176409322365,0.00199046197339,0.483287468648,0.000904761699231 +1.63,51.0000021268,4.51821161012e-008,10.0015095795,1.36524834359,-0.000386609704232,-0.00128930733749,0.000736779769129,0.487372889712,0.00127053242617 +1.64,51.0000022513,4.52075894831e-008,10.0015209821,1.40510916401,0.000744244696878,-0.000991211354591,0.000241918977344,0.494943709894,0.00125751072669 +1.65,51.0000023794,4.53472326966e-008,10.0015336996,1.44378372605,0.00121628413029,-0.00155228794373,0.000970196766921,0.498535929888,0.00151632394326 +1.66,51.0000025109,4.54705041931e-008,10.0015429942,1.48343402793,0.000514393044328,-0.000306626023723,0.000848186958193,0.505016184842,0.00126431234113 +1.67,51.000002646,4.54154333075e-008,10.0015470209,1.52199281531,-0.00128756386445,-0.000498713037774,0.00110047375478,0.510982480097,0.000928936708282 +1.68,51.0000027846,4.52484943592e-008,10.0015497082,1.56137773029,-0.00105618496325,-3.87546377326e-005,0.000703021548037,0.516975288943,0.000510442355967 +1.69,51.0000029267,4.51156824133e-008,10.0015455011,1.59970640321,-0.000808435874842,0.000880165464137,0.00222099881067,0.524871385055,0.000642689783547 +1.7,51.0000030723,4.49646457425e-008,10.0015338054,1.64023168214,-0.00131205201242,0.00145897596003,0.00112704940386,0.528968854276,-2.69977439957e-007 +1.71,51.0000032214,4.46844334158e-008,10.0015237882,1.67749577358,-0.00262200479453,0.00054447759847,-6.93983656973e-005,0.534376853734,0.00208047570105 +1.72,51.000003374,4.43318995022e-008,10.0015171716,1.71839780623,-0.00232741500617,0.000778827959202,-0.000728971988685,0.54048432184,0.000403888701058 +1.73,51.0000035302,4.41425127884e-008,10.0015081046,1.75592840844,-0.000331490459922,0.00103458187969,0.000155526228588,0.546104620732,0.000620859396264 +1.74,51.0000036899,4.40496255494e-008,10.0015018036,1.79725348186,-0.000972605170691,0.000225617830745,-0.000338735969699,0.5506542021,0.00036071329233 +1.75,51.0000038532,4.37500984444e-008,10.0015027183,1.83611770929,-0.00323262249902,-0.000408560561454,-7.27070292154e-005,0.55698996545,0.000589407628889 +1.76,51.00000402,4.35652713139e-008,10.0015038499,1.8750971355,0.000637731584593,0.000182249360607,0.000230362228485,0.561545205522,0.00102438079442 +1.77,51.0000041903,4.36102501741e-008,10.0015031643,1.91459326907,-6.2483452494e-006,-4.51442700249e-005,0.000836594576465,0.564998163464,0.00138527427039 +1.78,51.0000043642,4.3689958514e-008,10.0014969918,1.95438698012,0.00112531806146,0.00127964507198,7.4369578689e-007,0.571466803997,-0.000313581762705 +1.79,51.0000045416,4.38358569588e-008,10.0014879637,1.99280550224,0.000923031349587,0.000525985285675,-0.000238076333871,0.577023042108,-0.00166889174826 +1.8,51.0000047225,4.403492146e-008,10.0014867254,2.03287428829,0.00187174588194,-0.000278325680299,-0.0017662042693,0.582973696225,-0.00153874396286 +1.81,51.000004907,4.43106566146e-008,10.0014812018,2.07126222787,0.00199945327505,0.00138303841194,5.54317692478e-005,0.587924804488,-0.00368457174912 +1.82,51.0000050949,4.46021449367e-008,10.0014673427,2.10995645704,0.00209291334492,0.0013887878235,0.000275250214211,0.595181927036,-0.000687127063763 +1.83,51.0000052863,4.49508005628e-008,10.0014745985,2.14892657324,0.00280205681936,-0.00283995378392,9.51099647811e-005,0.601572062098,-0.000240952504752 +1.84,51.0000054812,4.52720102262e-008,10.0014940838,2.18769208773,0.00170758420177,-0.00105709927741,-0.00159588905726,0.60621962397,0.000594641100051 +1.85,51.0000056796,4.55576029718e-008,10.0015088067,2.22648493421,0.0023020110908,-0.00188748429046,0.000449254228971,0.613025542081,0.00105248703485 +1.86,51.0000058814,4.58383053121e-008,10.0015241978,2.26386054867,0.00163892507,-0.00119073383285,-0.00022754278024,0.61716387039,0.000506716516821 +1.87,51.0000060867,4.6000157436e-008,10.0015402709,2.30329856689,0.000633406840186,-0.00202389752334,8.66968046094e-005,0.623156917744,-0.000211098089153 +1.88,51.0000062954,4.59942541007e-008,10.001558316,2.34120786843,-0.000716287041146,-0.0015851041247,-0.000203270284185,0.627871142824,-0.000187492191315 +1.89,51.0000065077,4.58684079466e-008,10.0015694933,2.38103256056,-0.00105053703301,-0.000650360570056,-0.000912635942911,0.633544039032,-0.00120438480008 +1.9,51.0000067235,4.57901833659e-008,10.001576745,2.42037939296,-4.77013117039e-005,-0.000799976949119,6.23520430199e-005,0.637804277648,-0.00169691029365 +1.91,51.0000069429,4.57803833085e-008,10.0015897785,2.46073135586,-8.98871368385e-005,-0.0018067270593,0.00125821765916,0.642061731229,-6.01377330952e-005 +1.92,51.0000071658,4.57866864348e-008,10.0015997964,2.49944131924,0.00017838022585,-0.000196861446476,0.00067201374296,0.64902380944,0.000917099978568 +1.93,51.0000073922,4.5785628034e-008,10.0016049651,2.5383275138,-0.000193239700758,-0.000836879069574,-0.000556247726543,0.654135552802,0.000993834410516 +1.94,51.0000076221,4.58079960966e-008,10.0016073243,2.57631512462,0.000507277349494,0.000365034906129,-0.000211171718382,0.661751969407,0.00219125476576 +1.95,51.0000078554,4.58115494365e-008,10.0016018134,2.6143039893,-0.000457390035801,0.000737147395526,0.00149135381876,0.665524593241,0.00108880313598 +1.96,51.0000080922,4.59671071404e-008,10.0015989715,2.65413038476,0.00264135098267,-0.000168751225428,0.000590614933361,0.671097700083,0.00230614832079 +1.97,51.0000083325,4.6457109561e-008,10.0016003701,2.69264699049,0.00423806496093,-0.000110981440759,0.000785180510329,0.675934377484,0.00283538930471 +1.98,51.0000085763,4.69578750596e-008,10.0016078238,2.7331803494,0.00279245977832,-0.00137975137775,0.000816530256538,0.682110460926,0.00103924715741 +1.99,51.0000088237,4.73973225395e-008,10.0016183005,2.77178572437,0.00337718723091,-0.000715594146894,0.00108826284283,0.687010159358,0.00412674745997 +2,51.0000090747,4.78283186232e-008,10.0016241444,2.81084498635,0.00267380590846,-0.000453191755063,0.00142653831201,0.694184073789,0.0026682218976 +2.01,51.000009329,4.80892717728e-008,10.0016252614,2.84892857206,0.000989860121873,0.000229792061236,0.00203975119839,0.698247000328,0.00249692912927 +2.02,51.0000095869,4.83396166215e-008,10.0016173507,2.88889128461,0.00252487005801,0.00135235209369,0.00328874128738,0.704327071027,0.000987365282033 +2.03,51.0000098483,4.87467722147e-008,10.0015995847,2.92713010996,0.00319141311142,0.00220085397824,0.00122031946903,0.710483789562,0.00307729621934 +2.04,51.0000101132,4.91895205393e-008,10.0015862019,2.96609679472,0.00302457611876,0.000475703178842,0.00236943297445,0.715622366064,0.00186502462026 +2.05,51.0000103816,4.96556944505e-008,10.0015824342,3.00561388297,0.00352029787154,0.000277828689854,0.00197970582329,0.721501022356,0.001470834742 +2.06,51.0000106535,5.01189803151e-008,10.0015783247,3.04446521769,0.00298402919663,0.000544077085423,0.000209505443175,0.725975845647,0.00197506804522 +2.07,51.000010929,5.040773622e-008,10.0015666888,3.08528232671,0.00106997500025,0.00178310319457,-0.000879428626708,0.732056363898,0.00107321505892 +2.08,51.0000112081,5.06937524855e-008,10.0015562459,3.12467778469,0.00294556584601,0.00030547184601,0.000121324330287,0.738479823527,0.00109070735696 +2.09,51.0000114907,5.13015021883e-008,10.0015597353,3.1634115247,0.00558696896502,-0.00100334209941,-0.00142765547582,0.74409613093,0.000238139748499 +2.1,51.0000117769,5.20000737325e-008,10.0015712164,3.20330042963,0.00422066395183,-0.00129286992134,-0.00318036302961,0.749757583006,0.00107711219232 +2.11,51.0000120665,5.24793508833e-008,10.0015847467,3.24161274165,0.00250817344916,-0.00141319245643,-0.00353426222551,0.754496133551,-0.00109965764597 +2.12,51.0000123597,5.29921207307e-008,10.0015997432,3.28222938117,0.00469088641345,-0.00158610684533,-0.00199535335683,0.760880201153,0.00117196649375 +2.13,51.0000126565,5.35312513852e-008,10.0016039289,3.32186956015,0.00287826738364,0.000748951765545,-0.00363445447904,0.765711488022,-0.00124243190804 +2.14,51.0000129568,5.40490848128e-008,10.0016053973,3.35953464804,0.0043918827943,-0.00104261709885,-0.000501880247029,0.769916734654,0.00179024790778 +2.15,51.0000132606,5.4560881383e-008,10.0016143901,3.39926366631,0.00279351256517,-0.000755958890785,0.000433025158352,0.776242603431,0.00176089991716 +2.16,51.0000135679,5.49862008524e-008,10.0016214586,3.43823375286,0.00317778286029,-0.000657735468248,-0.000107554293788,0.784362887215,0.00139093773599 +2.17,51.0000138787,5.55213437155e-008,10.0016208958,3.47634295849,0.00433538391906,0.000770297444502,-0.001238479464,0.792079422873,-0.00120246255372 +2.18,51.000014193,5.60517114207e-008,10.001615862,3.51629372219,0.00311074173415,0.000236457716554,-0.000711428406025,0.794445961322,0.00205111763457 +2.19,51.0000145109,5.65017180162e-008,10.0016185923,3.55655120543,0.00320714979131,-0.000782503430946,0.000916960110498,0.801035124464,0.00529815027254 +2.2,51.0000148323,5.6933102017e-008,10.0016279996,3.59500367045,0.0028492887859,-0.00109896009272,0.0013364895522,0.805619288451,0.00151362102456 +2.21,51.0000151572,5.73805264813e-008,10.001630683,3.6338014015,0.00343235068294,0.000562281288258,0.00198149695204,0.811594282583,0.00280979871571 +2.22,51.0000154856,5.78030982201e-008,10.0016270402,3.6738368944,0.00250036759406,0.000166267700346,0.00250540380764,0.817086028803,0.00146469605322 +2.23,51.0000158176,5.8182404246e-008,10.0016219163,3.71201406879,0.00282491937477,0.000858515374512,0.00221022581731,0.821561493523,0.00226367535583 +2.24,51.000016153,5.85345001982e-008,10.0016194917,3.75089583089,0.00211835029767,-0.000373587963914,0.00102774849574,0.826553069035,0.00249101271721 +2.25,51.0000164918,5.89227671936e-008,10.0016139325,3.78834978677,0.00333274459442,0.00148541795337,0.000554810159916,0.829887159792,0.00236086190945 +2.26,51.0000168342,5.93827158213e-008,10.0016054123,3.82963576079,0.00312472830155,0.000218617594504,0.00197350228657,0.834523317143,0.0038892493353 +2.27,51.0000171802,5.98561687869e-008,10.0016028421,3.86740019815,0.00352233940305,0.000295437211235,0.000632062751629,0.839625883078,0.00185870514262 +2.28,51.0000175296,6.02821982034e-008,10.0016003557,3.90718263261,0.002458922862,0.000201837362783,0.00027144886875,0.846095209913,0.00153695447154 +2.29,51.0000178826,6.05586893175e-008,10.0016007708,3.94712190347,0.00142288856011,-0.000284853693768,0.000507515797488,0.852919315562,0.00169256528729 +2.3,51.0000182391,6.07151075067e-008,10.0016047952,3.98577539791,0.000773152752327,-0.000520023783672,0.000912851310751,0.857171641668,0.00242788139096 +2.31,51.0000185991,6.08349657318e-008,10.0016126405,4.02412193866,0.000909603024296,-0.00104904668765,0.000479032112497,0.862872204382,0.00237176134214 +2.32,51.0000189626,6.09181485754e-008,10.0016189907,4.06325850046,0.000258246823461,-0.000220997164848,0.000425063484157,0.86973965571,0.00119457297752 +2.33,51.0000193297,6.09603728736e-008,10.0016135058,4.10343947703,0.000334563394827,0.00131798197324,-0.000692517882179,0.875389882147,0.00130137502202 +2.34,51.0000197002,6.10351477638e-008,10.0016010208,4.14116818323,0.000715242533776,0.00117902239276,-0.00165788679446,0.879018639089,0.00281650311623 +2.35,51.0000200742,6.11840404039e-008,10.0015903207,4.18019795418,0.00137514335272,0.000960987773785,0.000694239281306,0.884751488655,0.00212088661695 +2.36,51.0000204517,6.13197800222e-008,10.0015868236,4.21945409883,0.000530579997055,-0.000261554072339,-0.00101364525536,0.890425459791,0.00143716007663 +2.37,51.0000208328,6.14022484269e-008,10.0015883537,4.25950584857,0.000627239399336,-4.44666738547e-005,0.0019848901502,0.895219064158,0.000201828132985 +2.38,51.0000212174,6.17267819203e-008,10.0015909372,4.29748881282,0.00392906517031,-0.000472247212778,-0.000315349795227,0.899953280284,0.000135262218187 +2.39,51.0000216055,6.21022699071e-008,10.0015942254,4.33778128192,0.0013426175975,-0.000185385945032,0.000158751591698,0.908348737952,0.000846975949556 +2.4,51.0000219971,6.23169430925e-008,10.001601308,4.37529283506,0.00167129751961,-0.00123113747647,0.00011780925565,0.911934203471,0.000459881778427 +2.41,51.0000223921,6.24074258689e-008,10.0016017854,4.41368422093,-0.000400959974197,0.00113565439206,-0.00103891110326,0.9164142836,0.00316434475689 +2.42,51.0000227905,6.24486036051e-008,10.0015946317,4.45077498087,0.000979076882362,0.00029510364716,-0.000943878291518,0.922063919915,0.00105900671333 +2.43,51.0000231924,6.26298755339e-008,10.0015999708,4.49105103185,0.00156589952578,-0.0013629267175,0.00104787610886,0.927650697983,-0.0023539950942 +2.44,51.0000235978,6.29238074992e-008,10.0016104006,4.5292834033,0.0025607731243,-0.000723039878082,0.000616423029641,0.933399515805,-0.00195878687797 +2.45,51.0000240068,6.33783010263e-008,10.0016209252,4.5706175754,0.00382011161475,-0.00138188043919,0.00126440950008,0.938885306635,-0.00045045584748 +2.46,51.0000244194,6.38724262779e-008,10.0016378541,4.60850083096,0.00311718466195,-0.00200390413719,-0.00106735684053,0.945017421151,0.000502162281683 +2.47,51.0000248354,6.42964014068e-008,10.0016616685,4.64725735659,0.00283523539086,-0.00275896355945,0.00122108391382,0.950125057951,-0.0014634498897 +2.48,51.0000252549,6.46775878187e-008,10.0016776591,4.68656098714,0.00251645027936,-0.000439156797371,-0.00231479033496,0.956208992295,-0.000437953517391 +2.49,51.0000256779,6.48801075838e-008,10.0016810334,4.72497874533,0.000326836063322,-0.000235718410416,-0.000778265112931,0.961256293029,-0.000224535262011 +2.5,51.0000261044,6.50387992902e-008,10.0016862647,4.76461179124,0.00190112402689,-0.000810526934445,0.000694626311737,0.966270004646,-0.00339536869909 +2.51,51.0000265344,6.5372010772e-008,10.0016918263,4.80456986224,0.00277701508178,-0.000301798188877,0.00131693849262,0.970758580781,-0.00290451536455 +2.52,51.0000269681,6.57369039446e-008,10.0016906498,4.84402153372,0.00234592065491,0.000537091734696,0.000710096548311,0.9765288698,-0.00142449205208 +2.53,51.0000274052,6.59551709041e-008,10.0016901384,4.88115793815,0.000718449091126,-0.000434809579665,-0.000158558625041,0.982665035492,-0.00135416049493 +2.54,51.0000278458,6.60090038337e-008,10.001687395,4.92203599867,3.73409738863e-005,0.00098349863466,-0.000351802222955,0.98716956193,-0.000556905217253 +2.55,51.00002829,6.60437331821e-008,10.0016814699,4.96236357987,0.000450243414027,0.000201524587416,0.00074631310943,0.993985277304,-0.0010518778333 +2.56,51.0000287378,6.60758028316e-008,10.0016804622,5,0,0,0,1,0 +2.57,51.0000291887,6.60871104778e-008,10.001677858,5.03282645552,0.000158754250124,0.000520845699922,0.000168220847247,0.998721360592,0.000506565563706 +2.58,51.0000296425,6.61265011976e-008,10.001665068,5.06333330793,0.00039427367444,0.00203714591881,0.000715650284565,0.996857673494,0.00219120282949 +2.59,51.0000300991,6.62016921516e-008,10.001643873,5.0954117703,0.000661373369459,0.00220185320682,0.000990200102183,0.996203224883,0.00313125653368 +2.6,51.0000305584,6.63572437547e-008,10.0016231064,5.1253906783,0.00152250087966,0.00195147231978,0.0013020927766,0.993519595456,0.00017455489657 +2.61,51.0000310205,6.65159898144e-008,10.001599698,5.15514524639,0.000706222083106,0.00273021575939,0.0013057795607,0.993557160929,-0.00144392429618 +2.62,51.0000314854,6.65317995338e-008,10.0015814964,5.18828386301,-0.000484260761503,0.000910108259144,0.0017159046874,0.9906911499,-0.00158886656573 +2.63,51.0000319531,6.65364762259e-008,10.0015783558,5.21964407175,0.000549919398563,-0.00028199676,0.000790751380548,0.988274148572,-0.000292800886182 +2.64,51.0000324237,6.66184281026e-008,10.0015839584,5.24982632081,0.000600647890709,-0.000838519841825,0.00234157405974,0.986399611204,-0.00137453019683 +2.65,51.0000328969,6.672055753e-008,10.0016009716,5.28003610869,0.000833203070349,-0.002564114531,0.000452068711031,0.983867460345,1.62056339232e-005 +2.66,51.000033373,6.66920994494e-008,10.0016186573,5.31125724237,-0.00123274163455,-0.00097303240738,7.18506865272e-005,0.984027588452,0.00047650131716 +2.67,51.0000338518,6.65927138495e-008,10.0016290519,5.34342031079,-0.000162587207118,-0.00110589741805,0.00157349281408,0.981682491434,0.000189408314226 +2.68,51.0000343335,6.65369865131e-008,10.0016382627,5.37446105542,-0.000619799361051,-0.000736259180849,0.00174524451617,0.981307654954,0.000456235119862 +2.69,51.0000348181,6.64288447843e-008,10.0016524962,5.40580338538,-0.000898461529296,-0.00211043825535,0.00224570820283,0.979430862951,0.00136450182015 +2.7,51.0000353054,6.63548651817e-008,10.0016709739,5.43761647745,-0.000140178577578,-0.00158509142135,0.00219706360584,0.976273548979,0.00146985608585 +2.71,51.0000357956,6.61991569963e-008,10.0016926039,5.46889157331,-0.0020458937647,-0.00274092258028,0.00153556342179,0.9759182887,-0.00171810414901 +2.72,51.0000362886,6.59260602882e-008,10.0017104458,5.49961630393,-0.00178826020433,-0.000827446216767,0.000818563478085,0.971961581293,-0.000234781363278 +2.73,51.0000367843,6.56269963749e-008,10.001722955,5.53071406698,-0.00241046150222,-0.00167439255577,-0.00194845083169,0.968499731011,-0.00153521721288 +2.74,51.0000372829,6.52647994416e-008,10.0017438305,5.56222222649,-0.00267461912208,-0.00250070599254,-0.00186353708317,0.966652221609,-0.000327780334912 +2.75,51.0000377843,6.50333821417e-008,10.0017668765,5.59456933672,-0.000574374756933,-0.00210849279765,-0.00104891995449,0.96409348441,-0.000181790101947 +2.76,51.0000382886,6.49418264145e-008,10.0017837476,5.62465827103,-0.000711026089589,-0.001265743528,-0.000398989719305,0.964695689871,-0.000104351893913 +2.77,51.0000387955,6.48660676927e-008,10.0017868486,5.65520054229,-0.000352591962407,0.000645555172787,3.46002539009e-005,0.963774275342,-0.000272678228506 +2.78,51.0000393053,6.46003682952e-008,10.0017783877,5.6865377699,-0.0033777068595,0.00104661961178,-0.000732462631933,0.963940033486,-0.000395742034307 +2.79,51.000039818,6.43295099829e-008,10.0017702903,5.72162109208,-0.000425020773779,0.000572853231555,-6.30882152183e-005,0.962523969875,-0.000378791060059 +2.8,51.0000403336,6.42580831886e-008,10.0017675552,5.75042845254,-0.000577778948073,-2.58271823071e-005,-0.00041646380564,0.960612616295,1.63418735019e-005 +2.81,51.0000408519,6.42285247881e-008,10.0017629897,5.78060077525,0.000162792442678,0.000938921901359,0.00150899620974,0.958823326427,0.00262003005638 +2.82,51.0000413729,6.42861738755e-008,10.0017572052,5.81129546048,0.00064657451651,0.000217982443078,0.00168277866646,0.956529235474,0.0028388840883 +2.83,51.0000418965,6.44729418134e-008,10.0017626141,5.84057273584,0.00197556233391,-0.00129976374722,-2.4442826348e-005,0.95427402833,0.00133953109906 +2.84,51.000042423,6.47584999146e-008,10.0017664268,5.87249953126,0.00203354341571,0.000537227074504,-0.00101109037508,0.953386948411,-0.00111682519535 +2.85,51.0000429521,6.49561907989e-008,10.0017741764,5.90057146353,0.000741946582535,-0.00208715346697,0.0004145912326,0.951165685702,-0.00127390175417 +2.86,51.000043484,6.50802967239e-008,10.0017919628,5.93325246424,0.00100044406894,-0.00147012727786,0.000860210049447,0.948403409598,-0.00102058873062 +2.87,51.0000440187,6.52521646268e-008,10.0018045315,5.9651098676,0.00141250296454,-0.00104359630755,0.0013715976207,0.947071061363,-0.000917754823175 +2.88,51.0000445564,6.53090990229e-008,10.0018124433,5.99738017507,-0.000613169985323,-0.000538776816163,0.00170233668445,0.94730657543,-0.00106291772101 +2.89,51.0000450968,6.53086915577e-008,10.0018174789,6.02720622988,0.000607449352326,-0.000468342000954,0.00264898816571,0.945537150821,-5.97374369244e-005 +2.9,51.00004564,6.55080699855e-008,10.0018178064,6.05741860388,0.00219173281101,0.00040285446361,0.00407610825735,0.944005513257,-0.00210648246982 +2.91,51.0000461858,6.58479025905e-008,10.0018146505,6.08804344961,0.00257936187857,0.000228321369394,0.00506410558746,0.942561867559,-0.00209097856591 +2.92,51.0000467345,6.6103475371e-008,10.0018159954,6.11975225767,0.00100876329643,-0.000497297559464,0.00273092356279,0.941821827264,-0.000409975279475 +2.93,51.0000472861,6.60606458957e-008,10.0018195306,6.15181578997,-0.00161006955472,-0.000209755656135,0.00682612292091,0.94077360444,-0.00278155604232 +2.94,51.0000478404,6.60385258659e-008,10.0018145088,6.18132157589,0.00129951442436,0.00121411877114,0.00458829606002,0.939586418321,-0.000424165132732 +2.95,51.0000483974,6.62238936837e-008,10.0018010814,6.21355634478,0.001302965021,0.00147136235992,0.00442854782624,0.937246307182,-0.000414465785742 +2.96,51.0000489574,6.63632708216e-008,10.0017923962,6.24572983367,0.000653826278683,0.000265687271589,0.00116364619147,0.935399678124,-0.0016343209083 +2.97,51.0000495203,6.64836748948e-008,10.0017919671,6.279258136,0.00103659183916,-0.000179869910414,-0.000632627602996,0.932334323293,-0.00195023894406 +2.98,51.0000500862,6.66608020462e-008,10.0017965931,6.31163767283,0.00145019232399,-0.000745335754983,-0.000325784075741,0.930470556319,0.000141235172899 +2.99,51.0000506549,6.69151857811e-008,10.0018029813,6.34169637871,0.00212123887926,-0.000532306906379,0.00176660488345,0.930301470157,-0.000747042611191 +3,51.0000512263,6.7273367258e-008,10.0018054611,6.3711429254,0.00290746505105,3.63523274892e-005,0.000462751062322,0.929830983488,-0.00151607232914 +3.01,51.0000518003,6.74878305267e-008,10.0018043427,6.40097004925,0.000103501026997,0.000187316025157,-0.00274250675212,0.929118212312,-0.0012105781362 +3.02,51.0000523771,6.75498669386e-008,10.0017978406,6.43189736308,0.000767461765703,0.00111311700423,-0.000527248879015,0.929714663509,-0.000928160126991 +3.03,51.0000529568,6.75851941304e-008,10.0017878772,6.46516275169,-0.000271484180192,0.000879558843005,-0.000517966393942,0.923271742023,-0.00288838158444 +3.04,51.0000535393,6.7589439865e-008,10.001783304,6.49591669422,0.000331092343554,3.50811428832e-005,-0.000508617187652,0.921971165916,-0.000578129801756 +3.05,51.0000541246,6.77481564742e-008,10.0017921361,6.52656830633,0.00189721602954,-0.00180149484546,0.000268444118687,0.919718716739,-0.000284567530843 +3.06,51.0000547126,6.79553649222e-008,10.0018132984,6.55761113057,0.00101189549432,-0.00243097499859,-0.000508823055101,0.919130871817,0.00246751379776 +3.07,51.0000553035,6.80591573435e-008,10.0018435725,6.58792894135,0.000445302453827,-0.00362384046468,1.46122220285e-005,0.916020720639,0.000571325147932 +3.08,51.0000558971,6.81149463637e-008,10.0018792087,6.62085172444,0.000337949767402,-0.00350339649317,-0.00033633663823,0.916230947397,0.000916806647052 +3.09,51.0000564936,6.81011960261e-008,10.001905162,6.65032380319,-0.00053099818416,-0.00168725929885,-0.00140189309356,0.914265897741,0.000122844053442 +3.1,51.0000570928,6.81170911903e-008,10.0019191897,6.68224463447,0.000754158976468,-0.00111828830829,-0.00141802971413,0.913588305071,-0.000983283313247 +3.11,51.0000576949,6.83306505053e-008,10.0019236989,6.71509222387,0.00224411559809,0.000216455013374,0.000544531971613,0.910069275085,-0.00292019855586 +3.12,51.0000582999,6.84806561343e-008,10.0019304742,6.74589680711,-0.000138105553237,-0.00157151344672,-0.000607557681705,0.910823950993,-0.000921898907342 +3.13,51.0000589078,6.84570731321e-008,10.0019384292,6.77819404588,-0.000192988945504,-1.95033553669e-005,-0.000867324706142,0.909830706778,-0.000245998312143 +3.14,51.0000595185,6.852614397e-008,10.0019419386,6.81061502774,0.00116271170313,-0.000682364374653,-0.00102449087001,0.908565794304,-0.00158282868742 +3.15,51.0000601321,6.87671139042e-008,10.0019514682,6.84112607303,0.00222039518733,-0.00122355852272,-0.00167625374806,0.906195647299,-0.00117714220603 +3.16,51.0000607484,6.90746868702e-008,10.0019608623,6.87179701181,0.00209778754672,-0.000655258966824,-0.000917011627735,0.905404663777,-0.00103854257228 +3.17,51.0000613674,6.94140589683e-008,10.0019813055,6.90139132305,0.00266684028338,-0.00343339191894,-0.00113885336159,0.904887772856,-0.00185374048944 +3.18,51.0000619892,6.97209719338e-008,10.002004888,6.93269684341,0.00164207623937,-0.00128310327926,-0.000273011352686,0.903080484821,-0.00140180970998 +3.19,51.0000626138,6.99365062744e-008,10.0020145729,6.96529879195,0.00138392647883,-0.00065387184064,-0.00132416155834,0.900956100342,0.000609565816793 +3.2,51.0000632414,7.00974660254e-008,10.0020190562,6.99849059528,0.000875874147835,-0.000242789536333,0.000191154120934,0.89774779606,-0.00145539460957 +3.21,51.0000638719,7.01658479399e-008,10.0020154565,7.02982987927,8.41763669697e-005,0.000962721647243,0.000796939406996,0.896876562691,0.0020918881083 +3.22,51.0000645052,7.0215187102e-008,10.0020008803,7.05956912784,0.000608522678071,0.0019525280449,0.00258830428863,0.895730670738,0.00121386908578 +3.23,51.0000651412,7.03696515097e-008,10.0019915996,7.09098571175,0.00156008622732,-9.63986244021e-005,0.00243133506345,0.893075174851,0.00144169493255 +3.24,51.00006578,7.0528251032e-008,10.0019924408,7.1234676514,0.000666577759558,-7.1826678925e-005,0.00163345467244,0.891618569883,0.000417552335612 +3.25,51.0000664218,7.06155933306e-008,10.0019964337,7.15537234451,0.000559667723194,-0.000726761422352,-0.000222349405192,0.886405578115,7.89638508671e-005 +3.26,51.0000670663,7.06209714513e-008,10.0020059757,7.18586637213,-0.000484161390245,-0.00118164873395,0.000369272253446,0.887125493925,0.000768993375388 +3.27,51.0000677136,7.06587567962e-008,10.0020151594,7.21607963792,0.00101465013449,-0.000655086036429,-0.000171344112235,0.887191016625,0.000861511255252 +3.28,51.0000683637,7.0776891458e-008,10.0020228372,7.24917342194,0.000643905819836,-0.000880476790948,-0.000136088753071,0.886117817084,0.000741641988741 +3.29,51.0000690167,7.08567608882e-008,10.0020385066,7.27826949146,0.000477423984738,-0.00225338802807,-0.000554478442716,0.881367175712,0.001215920147 +3.3,51.0000696724,7.09700539476e-008,10.0020569659,7.31129421337,0.00111315806222,-0.00143847741999,0.000581688821773,0.881131540056,0.000986125518151 +3.31,51.000070331,7.11189083226e-008,10.0020694153,7.3428893992,0.000976688350741,-0.0010514017174,0.0024245314609,0.879826917535,-0.000717964666472 +3.32,51.0000709925,7.12175702808e-008,10.002075621,7.37439074464,0.000408479785227,-0.000189739539878,0.000449178798311,0.879033297987,0.000719784228855 +3.33,51.0000716568,7.12629076868e-008,10.0020744264,7.40624936124,0.000228036358947,0.000428649580277,0.00130852754299,0.876243866273,-0.00040380612137 +3.34,51.0000723239,7.11796978153e-008,10.0020741769,7.4363957614,-0.00139626431458,-0.000378750593828,0.000690965380166,0.87642109622,0.000370078908841 +3.35,51.0000729937,7.09726260081e-008,10.0020725283,7.46724656574,-0.00151092768901,0.000708483717535,-0.00100472201633,0.875043561134,-0.00236458323715 +3.36,51.0000736664,7.07818361978e-008,10.0020685644,7.49922690577,-0.00116767260441,8.42837663149e-005,0.000283012958687,0.873835408043,-6.27451306406e-005 +3.37,51.0000743419,7.06701846163e-008,10.0020713864,7.53097836825,-0.000399863707556,-0.000648673499918,0.000996763532222,0.872677412453,0.00299739851602 +3.38,51.0000750202,7.05759810389e-008,10.0020695984,7.56100180808,-0.000922710707027,0.00100627982829,0.00179049000659,0.873153007133,5.51726097741e-005 +3.39,51.0000757014,7.04713128775e-008,10.0020489519,7.59578221189,-0.000546781586132,0.00312300212473,0.00106495371151,0.872171730362,-0.000675273970588 +3.4,51.0000763855,7.0330574905e-008,10.0020253961,7.6249733164,-0.00142911403563,0.00158816628428,0.000686040385047,0.868671979331,-0.000602116838378 +3.41,51.0000770722,7.01951778156e-008,10.0020097329,7.65414740266,-0.000471798058889,0.00154447613692,-0.00146194300732,0.868674331258,0.00123376237702 +3.42,51.0000777617,6.9966277622e-008,10.0019986268,7.68568363723,-0.00274185400877,0.000676743882821,-0.000520907599246,0.865501481766,0.00146429915295 +3.43,51.000078454,6.95984969554e-008,10.0019949349,7.71817996564,-0.00242161514204,6.16371376882e-005,-0.000595031302386,0.865638012169,-0.0010271392913 +3.44,51.0000791492,6.92515006342e-008,10.0019900559,7.75003189926,-0.00245005141144,0.000914170203654,-0.00119098143697,0.86303045285,-0.00022661753421 +3.45,51.0000798471,6.90551220029e-008,10.0019779954,7.77895070715,-0.000307012980392,0.00149792848767,-0.000591057746357,0.860634133903,-0.0014510482015 +3.46,51.0000805478,6.90007094365e-008,10.0019646407,7.81100873085,-0.000456914056222,0.00117300008424,-0.00031698343443,0.86007225472,-2.39765261691e-005 +3.47,51.0000812514,6.88899784072e-008,10.0019617612,7.84430233473,-0.00109769788957,-0.000597101707121,6.81134553901e-005,0.857248748309,0.00115573833535 +3.48,51.000081958,6.87333838917e-008,10.0019629112,7.87578003366,-0.00110081595802,0.000367111995399,-0.000821745847451,0.856043339065,-0.000298452317268 +3.49,51.0000826674,6.84947073275e-008,10.0019594778,7.90831496168,-0.00225009145297,0.000319571692933,-0.000655430102677,0.855367020026,0.000598378797112 +3.5,51.0000833796,6.80948569793e-008,10.0019591998,7.93809049047,-0.00336362047738,-0.000263990436699,-0.000566217121701,0.853800605392,-8.4087667874e-005 +3.51,51.0000840945,6.7829660656e-008,10.0019595305,7.96842471554,-0.000359611875275,0.000197862312738,-0.0020071180956,0.850653576582,0.000559869119359 +3.52,51.0000848122,6.7839941237e-008,10.0019568917,8.00051614607,0.000503946415206,0.000329895445464,-0.000273648078735,0.849777348442,0.000336555810493 +3.53,51.0000855327,6.78186480687e-008,10.0019591856,8.03068790264,-0.000802892518388,-0.000788679317427,0.00184031460007,0.847768722445,0.00160948279036 +3.54,51.0000862561,6.775128733e-008,10.0019626011,8.06345850903,-0.000142820705663,0.000105577774934,0.000322084054511,0.844651809361,0.000683119599299 +3.55,51.0000869823,6.77900457938e-008,10.0019565403,8.09453251315,0.000686971366836,0.00110658440179,0.000329716758763,0.842394507528,0.00105712844177 +3.56,51.0000877113,6.79092043228e-008,10.0019438402,8.12669844946,0.00098595851002,0.00143344307704,-0.000524267040903,0.842541952872,-0.00103006612096 +3.57,51.0000884433,6.80479162927e-008,10.0019369376,8.15903152962,0.000961492481521,-5.29357486976e-005,0.000416581632844,0.839418602993,-0.00227689057361 +3.58,51.000089178,6.81720213731e-008,10.001933788,8.18856320097,0.000780884607117,0.000682859250836,-0.000773587285296,0.839519693961,-0.00239970579368 +3.59,51.0000899155,6.83397943515e-008,10.0019198376,8.22111716954,0.00157456922972,0.00210723458421,-0.00139870196902,0.839676307974,-0.00126431215524 +3.6,51.0000906559,6.85749433286e-008,10.0019098933,8.25207821641,0.00172681194844,-0.000118375755037,-0.00231221543546,0.836891851055,-0.00228388769545 +3.61,51.000091399,6.87870770264e-008,10.0019055507,8.2820826101,0.00125144547757,0.000986887009524,-0.00162308034589,0.832740457091,-0.00274065386022 +3.62,51.0000921449,6.90081084765e-008,10.0018928859,8.31391238538,0.00185173215052,0.0015460642973,-0.000501079611645,0.833264462295,-0.00444404516887 +3.63,51.0000928936,6.91764267562e-008,10.0018721265,8.34399355994,0.000511377327415,0.00260582649579,-0.00241696476806,0.831556212856,-0.00589281256333 +3.64,51.0000936451,6.9351203439e-008,10.0018513229,8.37605284394,0.00194240502936,0.00155488966896,-0.000291761381414,0.831943087821,-0.00146093017068 +3.65,51.0000943995,6.96600888269e-008,10.001849695,8.40868831438,0.00239420036909,-0.00122931346269,0.00059919971357,0.830886831452,-0.00144878862313 +3.66,51.0000951566,7.00192861845e-008,10.0018691955,8.43846918953,0.00264876131277,-0.00267077597836,-0.000482401845576,0.82975472586,-0.00102908529883 +3.67,51.0000959166,7.03066325268e-008,10.0018965654,8.47004614316,0.00138544590899,-0.00280320789988,-0.00205651787648,0.827364377512,-4.12951762563e-005 +3.68,51.0000966793,7.05158238416e-008,10.0019150057,8.5006809334,0.00155150150415,-0.000884845511743,-0.00218390108235,0.82582379071,-0.000207821381196 +3.69,51.0000974449,7.06716620325e-008,10.0019149085,8.53213505063,0.000636393181323,0.00090428193086,-0.000319045200533,0.825523087293,0.000712430072874 +3.7,51.0000982132,7.08696412238e-008,10.0019189478,8.56292000926,0.00214314120215,-0.0017121545647,-0.000149258010852,0.824051211798,0.000235694866435 +3.71,51.0000989842,7.1146266482e-008,10.0019352932,8.59208109984,0.00174054678951,-0.00155691047118,-2.52651761652e-005,0.821680746124,0.000351057659245 +3.72,51.000099758,7.13754632818e-008,10.0019481394,8.62374185311,0.00147726799032,-0.00101232814699,-0.000836555234797,0.819611043085,-0.000324405338755 +3.73,51.0001005346,7.15986348908e-008,10.0019591385,8.65575163874,0.00165595590096,-0.00118749194193,-0.00360761777843,0.818840285654,0.000573583088166 +3.74,51.000101314,7.17499874579e-008,10.001974288,8.68662610072,0.000468962569478,-0.00184241587737,-0.000532815864682,0.817025593417,-0.00105654963189 +3.75,51.0001020963,7.16868651166e-008,10.0019972545,8.71876427384,-0.00135517035759,-0.00275087305851,-0.00117504853898,0.81443392442,0.00025456699567 +3.76,51.0001028813,7.15274089665e-008,10.0020180115,8.74798163164,-0.000883518502881,-0.00140054651863,-0.00083328316821,0.813161321474,-0.00104727342122 +3.77,51.0001036691,7.14449106755e-008,10.0020300078,8.77989681807,-0.000274718432449,-0.000998710643811,-0.0024855771138,0.809155111093,-0.00222577266495 +3.78,51.0001044597,7.13384060744e-008,10.002037315,8.81125255316,-0.00122055568577,-0.000462727003884,-0.00155314904167,0.81025572066,-0.00207849571716 +3.79,51.0001052531,7.12554872872e-008,10.0020404454,8.84100779296,5.64152174001e-005,-0.000163344005435,-0.000321382922843,0.808075986918,-0.00320753026509 +3.8,51.0001060493,7.12437994322e-008,10.0020443084,8.87404561495,-0.000220507155496,-0.000609267422846,-0.000588661270473,0.805937462253,-0.00258535089789 +3.81,51.0001068484,7.12020127798e-008,10.0020567272,8.90531412937,-0.000366157609702,-0.00187448679988,-0.00163629933553,0.805028636185,-0.000657260467167 +3.82,51.0001076503,7.11570228122e-008,10.0020741643,8.93784380723,-0.00026548017166,-0.00161294157292,0.000596704130935,0.801616418811,-0.000962908024499 +3.83,51.0001084551,7.11757347363e-008,10.002087635,8.96837316769,0.000528186688269,-0.00108118832263,0.0020649698399,0.801324587485,-6.6311525166e-005 +3.84,51.0001092627,7.12133561442e-008,10.0020930409,9,0,0,0,0.8,0 +3.85,51.0001100729,7.12114010874e-008,10.0020922777,9.0264406558,-2.74480672668e-005,0.000152643506468,-0.00128900618551,0.80106934854,0.0022228860703 +3.86,51.0001108855,7.11831750021e-008,10.00209473,9.05450246518,-0.000368832735578,-0.000643093583199,-0.00121776125477,0.798065240384,9.10641191119e-005 +3.87,51.0001117006,7.11960759816e-008,10.0020892874,9.0805744106,0.000549956337457,0.00173161573797,-0.00251325280492,0.800355261268,-0.000745007648458 +3.88,51.0001125181,7.12590715548e-008,10.0020778506,9.10810634661,0.000334471505704,0.000555744432403,-0.000862185031875,0.798635154012,0.00130281416152 +3.89,51.000113338,7.1292330709e-008,10.0020736974,9.13589838343,0.000132471170131,0.000274888713857,-0.000565492790739,0.797761177409,0.00123787654266 +3.9,51.0001141604,7.12570775513e-008,10.002067699,9.16171148191,-0.000627408688561,0.000924780961699,0.00085084072,0.795361274869,0.000214692218914 +3.91,51.0001149853,7.13020362118e-008,10.0020487087,9.19089536866,0.00125860681759,0.00287328363707,0.000856829343953,0.792944067685,0.000686082983329 +3.92,51.0001158126,7.15679089508e-008,10.0020342633,9.21715414798,0.00247411952094,1.58063806437e-005,-3.93979506639e-005,0.793887878733,0.00144636709089 +3.93,51.0001166423,7.21284036056e-008,10.0020360513,9.2434572117,0.00539495773068,-0.000373421116141,0.00265769479151,0.79287729924,0.00112226912372 +3.94,51.0001174744,7.28028267298e-008,10.002037566,9.27128702432,0.00407362069023,7.05002052116e-005,0.000165667841038,0.791678053157,0.00198993776197 +3.95,51.000118309,7.32866193586e-008,10.0020508,9.29818109168,0.00271859654277,-0.00271731187496,0.000647441316501,0.791019341711,0.00365537167936 +3.96,51.0001191462,7.36676436815e-008,10.0020703933,9.32743665384,0.00263080269865,-0.00120134569188,0.000207517801981,0.790807633621,0.000208125301844 +3.97,51.0001199859,7.40140202417e-008,10.0020815652,9.35694742113,0.00223215844114,-0.00103303418653,0.000282677660998,0.78993367647,0.00226881631032 +3.98,51.0001208281,7.44022440085e-008,10.0020894317,9.38165829942,0.00321831734227,-0.000540264421126,0.000489750603003,0.788660829075,0.00330995529157 +3.99,51.0001216726,7.48216385177e-008,10.0020960226,9.40895337455,0.00266978064649,-0.000777909160481,0.00234380313931,0.786677042356,0.0038409325206 +4,51.0001225196,7.51911314643e-008,10.0021013168,9.43633383202,0.00251772321085,-0.000280937989396,0.000838526286921,0.788788240529,0.00186575941636 +4.01,51.000123369,7.55687411824e-008,10.002103879,9.46232745722,0.00278373612857,-0.000231508345538,0.00283377830018,0.786304486081,0.000178074048156 +4.02,51.0001242208,7.58266061727e-008,10.0021030417,9.49003368834,0.000836564615288,0.000398969866799,0.00146223938803,0.785804664091,0.00170879633519 +4.03,51.0001250752,7.60074919353e-008,10.0020979191,9.51867109854,0.00170298463868,0.000625552681231,0.000953349855153,0.784011017273,0.00172819231611 +4.04,51.000125932,7.62979111586e-008,10.0020871991,9.54561267151,0.00237436174245,0.00151845393915,0.00272172969176,0.784838231812,0.000213562175123 +4.05,51.0001267913,7.66918957882e-008,10.0020701442,9.57410980817,0.00315699308853,0.00189251685467,0.00405286892238,0.784378653741,0.000937002188217 +4.06,51.0001276531,7.71335551517e-008,10.0020488622,9.59946776747,0.00304369198689,0.0023638798636,0.000663808088142,0.78394844737,0.00231782279959 +4.07,51.0001285172,7.77564095678e-008,10.0020319327,9.62623786128,0.00570088430542,0.00102202765452,0.00123894577248,0.782805535622,0.00309746059144 +4.08,51.0001293837,7.83675791324e-008,10.0020236443,9.65405072284,0.00287964218526,0.000635653104104,0.0018234218083,0.782040520894,0.00111988088768 +4.09,51.0001302527,7.87666220108e-008,10.002014625,9.68129965724,0.00272272762041,0.00116819735342,0.00106424554507,0.780622159173,0.00236188297554 +4.1,51.0001311242,7.9201172451e-008,10.0020066105,9.70918408171,0.00337815112907,0.000434702655014,0.00144419487187,0.780872674208,0.000740020696586 +4.11,51.0001319982,7.96774458263e-008,10.0020048615,9.73734294394,0.00330849740287,-8.48938862092e-005,0.00118262587839,0.780277361608,0.000354522329934 +4.12,51.0001328747,8.01157206479e-008,10.0020017966,9.76365168704,0.00284466964519,0.000697875090482,-0.000315505293509,0.778300994522,0.00125858368697 +4.13,51.0001337536,8.06276938271e-008,10.0019922917,9.79085112251,0.00434318663429,0.00120310608,0.000306133364346,0.776475109209,0.00144898445145 +4.14,51.000134635,8.1003532201e-008,10.001976607,9.82008506668,0.000933402639844,0.00193382523953,-0.00139393914866,0.777335009796,0.000371060387834 +4.15,51.0001355189,8.11900713069e-008,10.001966626,9.84744805751,0.0016855162531,6.23774187395e-005,-0.00185281212711,0.777496663309,0.000696957755996 +4.16,51.0001364053,8.15104026338e-008,10.0019640485,9.87509679527,0.00281178067663,0.000453117930867,-0.000382685976931,0.776711966447,0.000402882373037 +4.17,51.0001372943,8.18328980477e-008,10.0019578722,9.90338370562,0.00171589892367,0.000782150608181,-0.00114742882978,0.774937874234,-0.000518794476497 +4.18,51.0001381856,8.23437326076e-008,10.0019582553,9.9294468059,0.00545597098667,-0.000858771974647,-0.0019211655683,0.775281770873,-0.000435355548256 +4.19,51.0001390794,8.31686470188e-008,10.0019642554,9.95638866668,0.00612542780638,-0.000341254339983,-0.00144470975536,0.774122573182,0.000886823956779 +4.2,51.0001399756,8.38964414377e-008,10.0019717186,9.98495198144,0.00409245316451,-0.00115137575668,-0.00366337290736,0.773896719971,0.000417946582734 +4.21,51.0001408744,8.44996528986e-008,10.0019837524,10.0120792332,0.00437634326294,-0.00125539675312,-0.00332809876858,0.77348380648,-0.00125577268243 +4.22,51.0001417756,8.49810864215e-008,10.0019964033,10.0388805641,0.00238274985287,-0.00127477425187,-0.00400677188852,0.771588767539,-0.00174449356839 +4.23,51.0001426792,8.53764499094e-008,10.0020078524,10.0670616536,0.00316796159331,-0.00101504581731,-0.00207951350393,0.771019177213,-0.0012860956606 +4.24,51.0001435854,8.59274811947e-008,10.0020201815,10.0951134742,0.00456825000819,-0.00145076460088,-0.00245736280511,0.770926332163,0.000541460258491 +4.25,51.0001444942,8.65299710773e-008,10.0020307443,10.1243825642,0.00389041516106,-0.000661795875417,-0.0027810534175,0.769667406849,-0.00167444572115 +4.26,51.0001454054,8.70035511052e-008,10.0020296471,10.1503699238,0.00275841816941,0.000881218049895,-0.00408596371258,0.768711116054,-0.00185860845614 +4.27,51.000146319,8.74333949193e-008,10.0020300026,10.1768299288,0.00327637985028,-0.000952301328812,-0.000989678660783,0.767795407163,-1.77826352969e-005 +4.28,51.000147235,8.79712483703e-008,10.0020393312,10.2036512823,0.0042748207711,-0.0009134267746,-0.000942889265842,0.765869859709,0.00118840104685 +4.29,51.0001481535,8.85331489364e-008,10.0020450274,10.2320846816,0.00361398950056,-0.00022580493485,0.00144072545101,0.76750053989,-0.000256815823997 +4.3,51.0001490744,8.8981400053e-008,10.0020493056,10.2589965712,0.00267923773299,-0.000629844526636,2.51635427235e-006,0.765149225508,0.0011733827434 +4.31,51.0001499978,8.93081220233e-008,10.0020530194,10.2849952167,0.00190777942021,-0.000112913064177,-0.00221267260724,0.763642156909,0.0010037193749 +4.32,51.0001509235,8.96624131565e-008,10.0020562574,10.3135829284,0.00306629521914,-0.000534697064201,-0.000527562883135,0.766223006315,0.000817750249388 +4.33,51.0001518517,9.01137087241e-008,10.0020574639,10.3384315452,0.00326967423373,0.000293401056667,-0.0012490082626,0.766718505779,-0.000321450286039 +4.34,51.0001527823,9.06476559125e-008,10.0020515456,10.3673084046,0.00422668346894,0.000890259888448,-0.00164798783861,0.766893038996,-0.00176132035316 +4.35,51.0001537155,9.12557124404e-008,10.0020413533,10.3946845514,0.00431013299817,0.00114821232857,-0.000988584221817,0.764635445363,-0.000628953208851 +4.36,51.0001546511,9.17767392392e-008,10.0020338455,10.4228754389,0.00300482847506,0.0003533442004,-0.00111043656591,0.762213074467,0.0015065895223 +4.37,51.0001555893,9.23290640611e-008,10.0020310315,10.4512281509,0.00474954174976,0.000209447603294,0.00154108716692,0.76174625329,0.00369700118491 +4.38,51.00015653,9.28884543267e-008,10.0020333277,10.4787491928,0.00310402372325,-0.000668692907201,0.000528452165348,0.761755734631,0.00476795184743 +4.39,51.0001574731,9.33363751797e-008,10.0020406407,10.5049420108,0.0031845656272,-0.000793904877604,-0.0027524221977,0.760587899467,0.00407739809844 +4.4,51.0001584186,9.37590050008e-008,10.0020495514,10.5328179284,0.00274894990887,-0.000988225529076,0.000958481821785,0.759293395641,0.000997752286615 +4.41,51.0001593665,9.41862415507e-008,10.002051071,10.5585914432,0.00324924170993,0.000684300982522,0.00200046485476,0.759520655986,-0.000349017471271 +4.42,51.0001603169,9.46552067105e-008,10.0020442998,10.5872319301,0.00333479899693,0.0006699398918,0.00161398943636,0.758221886796,0.00230825966493 +4.43,51.0001612698,9.51699229103e-008,10.0020317901,10.6143663917,0.00389156370646,0.00183201034133,0.00220299424308,0.759019383387,0.00324847090691 +4.44,51.0001622252,9.56184547591e-008,10.0020212758,10.6428836936,0.00240560309908,0.000270850343787,0.00214839650669,0.756667130038,0.000977486689606 +4.45,51.0001631832,9.61307048821e-008,10.0020300868,10.6716781433,0.00478613678273,-0.00203305348383,0.000616828694001,0.754487540992,0.00251180207051 +4.46,51.0001641436,9.66662705709e-008,10.0020354519,10.6966771386,0.00273294207082,0.000960022057851,0.0018637187311,0.754096091781,0.00179079567938 +4.47,51.0001651063,9.70958019097e-008,10.0020239761,10.7230872897,0.00329746651503,0.0013351502565,0.00124419470005,0.752657942744,0.00139892531115 +4.48,51.0001660714,9.74752045827e-008,10.0020186761,10.7511751713,0.00202916018475,-0.000275157240676,0.000691741624263,0.752041164315,0.00203246272793 +4.49,51.000167039,9.7907734144e-008,10.0020119476,10.7773849469,0.00404334170202,0.00162085198256,-0.000480860130846,0.748121798765,0.0040357902462 +4.5,51.000168009,9.8426960595e-008,10.0019959395,10.8042453978,0.00324634167253,0.0015807727165,0.000229303503172,0.748328752094,0.00191664160734 +4.51,51.0001689815,9.88589799577e-008,10.0019765683,10.8334559285,0.00281899705076,0.00229346140747,0.000747996261594,0.746788742083,0.00496850364581 +4.52,51.0001699565,9.92763813587e-008,10.0019635465,10.8611476424,0.00304111257069,0.000310896397539,0.00165849584456,0.745918406468,0.00345935872035 +4.53,51.0001709341,9.97289244374e-008,10.0019541329,10.8896689322,0.00331236872619,0.00157183039596,0.00317980947432,0.745006275742,0.00208592781474 +4.54,51.0001719141,1.00209986926e-007,10.0019443506,10.9145283504,0.00344151086322,0.000384640054168,0.000327556524353,0.743974469426,0.00144314421483 +4.55,51.0001728965,1.00655739335e-007,10.001938634,10.9429319462,0.0028166325262,0.000758677383498,0.00197062988526,0.744934582017,0.000634465124079 +4.56,51.0001738813,1.0102594569e-007,10.0019334008,10.9699270555,0.00238088151319,0.000287964245614,-2.25571437918e-005,0.743397293283,0.00113572323092 +4.57,51.0001748685,1.01281506741e-007,10.0019311834,10.9947010996,0.00120706913065,0.000155503071417,-0.000376435024152,0.743999300806,0.00291831745522 +4.58,51.0001758582,1.01463472104e-007,10.0019314149,11.025482597,0.00134763440233,-0.000201802771039,0.00022400999968,0.743174895955,0.00130566373384 +4.59,51.0001768505,1.01765237389e-007,10.0019240166,11.0517796938,0.00288900059829,0.00168146023316,0.00328135462857,0.740144476477,0.000480920863216 +4.6,51.0001778451,1.02020922089e-007,10.0019178096,11.079752362,0.000700685785577,-0.000440048821045,0.000639845727677,0.740380719083,0.00205530952467 +4.61,51.0001788422,1.02090636775e-007,10.0019296763,11.1042330282,0.000278073809243,-0.0019332905224,1.56247165054e-005,0.738901684024,0.00395385508188 +4.62,51.0001798417,1.02170269012e-007,10.0019442035,11.1337151734,0.000839923248576,-0.000972147685128,0.000216526744156,0.739034778819,0.00201351916301 +4.63,51.0001808437,1.02213488996e-007,10.0019518188,11.1610468538,-0.000233136142584,-0.000550918298636,0.00108383286837,0.737696934614,0.00228050940028 +4.64,51.0001818482,1.02210512971e-007,10.0019553093,11.1884680058,0.000191354238771,-0.000147174122424,0.00017305833055,0.73885572717,0.000850660485564 +4.65,51.0001828552,1.02260617038e-007,10.0019443491,11.2178917478,0.000512081925913,0.002339199299,-0.00113625614708,0.737981450806,-0.00141648824244 +4.66,51.0001838648,1.02316355476e-007,10.0019257095,11.244265253,0.000270458001165,0.00138872905556,-0.000934022821052,0.73745945063,0.000971792217224 +4.67,51.0001848767,1.02477153116e-007,10.0019153101,11.2705269691,0.00198706074706,0.000691147060723,0.000205488173822,0.737192293221,0.00357905062754 +4.68,51.000185891,1.02665264144e-007,10.0019056209,11.2976102298,0.000653924331143,0.00124669351498,-0.0018888915186,0.734041704594,0.0025012499986 +4.69,51.0001869077,1.02853457321e-007,10.0018919993,11.323507282,0.00198821399414,0.00147763204555,-0.00179894567002,0.732267477323,0.00100076028967 +4.7,51.0001879268,1.03088852178e-007,10.0018794832,11.3522562713,0.00131661234112,0.0010255829359,0.000473734771901,0.732728051183,0.00181996318648 +4.71,51.0001889485,1.03069820019e-007,10.0018755671,11.3795974046,-0.00158381431596,-0.000242368470893,-0.00155655148299,0.732953902685,0.00172225112771 +4.72,51.0001899726,1.02990830163e-007,10.0018777791,11.4071286866,0.00047483617648,-0.000200034870322,-0.00122364955003,0.731355519341,0.00115056633333 +4.73,51.0001909993,1.03006408167e-007,10.0018772896,11.4367187843,-0.000256128773601,0.000297946632457,-0.000789611572364,0.730295867045,0.0012347939666 +4.74,51.0001920286,1.03029069517e-007,10.00187573,11.4627967069,0.000574282769794,1.39765680608e-005,0.00178538607027,0.729102620731,-7.04359231502e-005 +4.75,51.0001930602,1.03142549936e-007,10.0018794674,11.4916429085,0.00101892550105,-0.000761468024552,5.33775509258e-005,0.725378790415,-0.0034403401635 +4.76,51.0001940943,1.03491410051e-007,10.0018853592,11.5163959418,0.0038788957318,-0.000416879930964,-0.000504353660431,0.726790333879,-0.000122672150783 +4.77,51.0001951308,1.03880033533e-007,10.001891701,11.544336326,0.00157718319368,-0.000851495178108,0.000315155132453,0.726921544661,-0.000420945483052 +4.78,51.0001961697,1.04084629056e-007,10.001896624,11.5723046815,0.00129523535001,-0.00013309462332,-1.97520587733e-005,0.72813928857,0.000603371267751 +4.79,51.0001972112,1.04261542971e-007,10.0018975087,11.5991454064,0.0011885472201,-4.38442006866e-005,-4.93431628037e-005,0.726496136984,-8.50153478774e-006 +4.8,51.000198255,1.04462066502e-007,10.0019036375,11.6254325053,0.00162670246315,-0.00118192211486,-5.01941800881e-005,0.724678251111,0.000230606783787 +4.81,51.0001993012,1.04572083198e-007,10.0019051624,11.6519354662,-8.21233235092e-005,0.00087694348044,0.000666411373069,0.725756150095,-3.93188933333e-005 +4.82,51.0002003498,1.04534696448e-007,10.0018948687,11.6794401618,-0.00044276783963,0.00118179379357,-0.00119641432426,0.722111828263,0.00294939944941 +4.83,51.0002014009,1.04617019521e-007,10.0018881347,11.7069143261,0.00159854234059,0.000165011980049,-0.00234415349576,0.721764490279,0.000469224823001 +4.84,51.0002024543,1.04797837866e-007,10.0018856188,11.7321471923,0.000940056207957,0.000338167088569,-0.00109088129779,0.7207149616,0.000858391093017 +4.85,51.0002035102,1.04891743219e-007,10.0018812891,11.7598911067,0.000378327643231,0.000527778509521,-0.000113044333887,0.722071663394,0.000204726652418 +4.86,51.0002045685,1.05027645085e-007,10.0018852649,11.7880395139,0.00152966604241,-0.00132293923619,0.000911373317317,0.71925523669,-0.00254028102734 +4.87,51.0002056293,1.05361778469e-007,10.0019002743,11.8149044056,0.00316139812124,-0.00167894698828,0.000950953090139,0.719575096246,-0.0027281641892 +4.88,51.0002066926,1.05766972875e-007,10.0019120997,11.841888156,0.00252732683195,-0.000686128356875,0.000490420452837,0.717957551535,-0.00213074312395 +4.89,51.0002077582,1.06171282574e-007,10.0019208961,11.8680428499,0.00314897715419,-0.00107314629079,0.00108337856385,0.715653198868,-0.00222767355479 +4.9,51.0002088264,1.06665490511e-007,10.001933002,11.8988385987,0.00378945251343,-0.00134804487809,0.00114890713801,0.716396839388,-0.000608082406295 +4.91,51.0002098971,1.07225222837e-007,10.0019444329,11.9239126933,0.0040689062944,-0.000938127114179,-0.000917388120159,0.716589874427,-0.00120598480794 +4.92,51.0002109702,1.07735085873e-007,10.0019589892,11.9523381249,0.00308931275166,-0.00197314453619,-0.00117235898787,0.715482450926,0.000358865410033 +4.93,51.0002120457,1.08070655324e-007,10.0019739054,11.9770289628,0.00162191245704,-0.00101008848616,0.0011108484242,0.713768201757,0.0012062313955 +4.94,51.0002131236,1.08386340729e-007,10.0019926122,12.0067109211,0.0028101506716,-0.00273127991855,0.00112658198121,0.713543584749,-0.00159241707418 +4.95,51.0002142042,1.08750896579e-007,10.0020148673,12.0351233472,0.00230802864543,-0.0017197411015,-0.000162925100491,0.71127162592,-0.00190548316929 +4.96,51.0002152872,1.0909294465e-007,10.0020255388,12.0616308223,0.00249415275113,-0.000414549116566,-0.00239879205283,0.712581016115,-0.000552591014711 +4.97,51.0002163726,1.09302239017e-007,10.0020267969,12.087706489,0.000444233943418,0.000162938292634,-0.00150598941856,0.711080666943,-1.43523458633e-005 +4.98,51.0002174604,1.09355770845e-007,10.0020270531,12.1156648511,0.000307325726122,-0.000214186689711,-0.000851766616067,0.710581813871,-0.000324843072166 +4.99,51.0002185506,1.09347465009e-007,10.002031234,12.1423779037,-0.000423935435707,-0.000621997977296,-0.00144775781446,0.708375961968,-0.000846763148049 +5,51.0002196434,1.09451490534e-007,10.0020383044,12.1709141676,0.00188440088072,-0.000792071173841,0.000631625023334,0.708549022511,-0.00348134682208 +5.01,51.0002207386,1.09815153906e-007,10.0020482759,12.1972194043,0.00322124776065,-0.00120223064601,-0.00182871164473,0.707529953187,-0.00189031824379 +5.02,51.0002218363,1.10241403476e-007,10.0020557191,12.2264885092,0.00276307912664,-0.000286418388373,0.00126443741895,0.705991095668,-0.00297616380037 +5.03,51.0002229367,1.10569129856e-007,10.0020627064,12.255954899,0.00183803224154,-0.00111102893792,0.00147470894785,0.706330840847,-0.000486109698256 +5.04,51.0002240395,1.10866348923e-007,10.0020655145,12.2815564513,0.0023347718908,0.000549395575099,0.000668095689376,0.70471488171,-0.00148181080074 +5.05,51.0002251447,1.11218646741e-007,10.0020574787,12.3082704389,0.00261130970913,0.00105776751703,-6.92605341292e-006,0.704583437258,-0.00142596171137 +5.06,51.0002262522,1.11455222098e-007,10.0020543178,12.3343091264,0.000710087518043,-0.000425581699362,-0.000190059269242,0.703804544425,-0.00139714955642 +5.07,51.0002273622,1.11558778313e-007,10.0020549134,12.3631328441,0.000743788830094,0.000306455669185,0.000952101199077,0.70254584403,-0.000300657118138 +5.08,51.0002284748,1.11614019314e-007,10.0020484329,12.3908034575,3.17665918313e-005,0.000989650554862,-0.000372802652423,0.701262567885,-0.000585564591583 +5.09,51.0002295898,1.1150689735e-007,10.0020340414,12.4181962394,-0.00153570413638,0.00188865284685,0.000958390517429,0.699909956155,-0.000697839012159 +5.1,51.0002307073,1.11429383991e-007,10.0020235751,12.4467473093,0.000447456222999,0.000204600547517,0.000735812894696,0.701031780281,-0.00106620752047 +5.11,51.0002318274,1.11446766167e-007,10.0020283221,12.4744827822,-0.000203419366098,-0.00115401176967,0.000741325009048,0.699329979872,4.1262151259e-005 +5.12,51.0002329499,1.11432277079e-007,10.0020340922,12.5,0,0,0,0.7,0 +5.13,51.0002340746,1.1149566377e-007,10.0020413652,12.524440357,0.000889916620802,-0.00145459484003,-0.00169142596822,0.699826348368,-0.000334084792946 +5.14,51.0002352015,1.11569383369e-007,10.002046015,12.54847504,0.000145068716564,0.000524639286432,0.000165234064107,0.698756551278,0.000529306104481 +5.15,51.0002363304,1.1156490089e-007,10.0020341596,12.5702572347,-0.000208000417335,0.00184642900545,-0.000126957879104,0.699938150015,0.00254347816019 +5.16,51.0002374614,1.11576219125e-007,10.0020147038,12.5946304768,0.00036690260732,0.00204473309183,0.000709676718285,0.696928054867,0.00223668391104 +5.17,51.0002385947,1.11666743303e-007,10.0019955877,12.6210999256,0.000904010290916,0.00177848856489,0.00154906469234,0.695755244852,0.00226470706062 +5.18,51.0002397302,1.11775317586e-007,10.0019756291,12.6423575236,0.000620316768779,0.00221323396635,0.000981239752763,0.696308796943,0.003199478156 +5.19,51.0002408676,1.11921362714e-007,10.0019441426,12.6652318795,0.00143008159784,0.00408405716176,-0.000567204602026,0.696027710801,0.0036473808573 +5.2,51.0002420071,1.12127769175e-007,10.0019138891,12.6879850161,0.00146775874542,0.00196664666581,0.00129014564404,0.693660358202,0.00026551705967 +5.21,51.0002431487,1.12405471689e-007,10.0018966128,12.7109779683,0.00243104131876,0.00148861371361,0.00290681390768,0.692956654096,0.000915718748064 +5.22,51.0002442922,1.12624057765e-007,10.0018754238,12.7333881686,0.000637794415306,0.00274918369192,0.001290845645,0.693733114361,-0.00133022159231 +5.23,51.0002454378,1.12584533766e-007,10.001839037,12.7557454342,-0.00119269092927,0.00452818404015,0.00196987307641,0.691943904143,-0.00244843211513 +5.24,51.0002465856,1.12459239633e-007,10.0018117317,12.7821753697,-0.000566373962863,0.00093286977818,0.00169798398856,0.690902294019,-0.00145242332108 +5.25,51.0002477357,1.1229313364e-007,10.0018082025,12.8059756684,-0.00176566827432,-0.000227033359597,0.000258522241215,0.690270869807,-0.000209428683589 +5.26,51.0002488878,1.12199715127e-007,10.0018106149,12.8291841629,0.000454120663643,-0.000255441654461,0.000769843898568,0.688520483378,-0.000133617100757 +5.27,51.0002500421,1.1237626208e-007,10.0018116763,12.8525664072,0.00202450711972,4.31588758744e-005,0.00189380202232,0.687289569594,0.00121258455704 +5.28,51.0002511984,1.12555447519e-007,10.0018155014,12.8750149964,0.000491163622229,-0.000808171149783,0.00231767979462,0.686681136696,-0.00119260587063 +5.29,51.0002523567,1.12757693865e-007,10.0018303066,12.8970258537,0.00234827019678,-0.00215287765255,0.00153233598216,0.686113467844,-0.00125070637744 +5.3,51.0002535171,1.12975529796e-007,10.0018537209,12.9208733688,0.000710033268309,-0.00252997225245,0.000425187662774,0.684184176524,0.000220870500897 +5.31,51.0002546795,1.13004628275e-007,10.0018717269,12.9429237533,-0.000301505709488,-0.00107122382899,0.00146432975809,0.683988653541,0.00207329829999 +5.32,51.000255844,1.12885599462e-007,10.0018817585,12.9677430869,-0.00136959697015,-0.000935096542328,4.19828551322e-005,0.684379495318,0.000703906724908 +5.33,51.0002570108,1.12761836842e-007,10.0018904624,12.9916015446,-0.000367965887446,-0.000805699627507,-0.00135887908155,0.681987087892,0.00259615491864 +5.34,51.0002581796,1.12713324079e-007,10.0018998118,13.0155547397,-0.000313128076278,-0.00106416796649,0.00154063819954,0.682069588986,0.000439554262748 +5.35,51.0002593507,1.1269343315e-007,10.0019122718,13.0393895631,3.38697918558e-005,-0.00142784508775,0.00177083205869,0.682517321668,0.000771003050542 +5.36,51.0002605238,1.12640001254e-007,10.0019228647,13.0622440688,-0.000784025763771,-0.000690736142787,0.0017094031185,0.681729943193,0.000729121609158 +5.37,51.000261699,1.1249586635e-007,10.0019430488,13.0850778557,-0.0012395531553,-0.00334607912095,0.00485256371008,0.68379894174,-0.00157772668659 +5.38,51.0002628763,1.12330908182e-007,10.0019700848,13.1092349832,-0.00107637346558,-0.00206112163079,0.00220688002202,0.679888341876,0.00166012885022 +5.39,51.0002640557,1.12171316875e-007,10.0019874728,13.1335853098,-0.00116420518613,-0.00141647021106,0.00183910229226,0.678696187965,0.00103778739594 +5.4,51.0002652373,1.12064761541e-007,10.002002215,13.1566966597,-0.000331776047418,-0.00153198121028,0.00215524864189,0.676766218591,0.0017882236567 +5.41,51.000266421,1.12055134313e-007,10.0020132876,13.1794387416,0.000196614785657,-0.000682523834993,0.00226048537636,0.675860069462,0.00174499443008 +5.42,51.0002676068,1.11908792535e-007,10.0020301203,13.20362034,-0.0022511767681,-0.0026840187827,0.0014907616747,0.676446148999,-0.00137699603739 +5.43,51.0002687947,1.11649536182e-007,10.0020567707,13.2269751709,-0.00138864673699,-0.00264607310427,0.00282214726277,0.674039209033,-0.000219502509446 +5.44,51.0002699847,1.11407655684e-007,10.0020738349,13.2499936551,-0.00200722874129,-0.000766748832684,0.000770774947855,0.672524632278,0.000129067289115 +5.45,51.0002711768,1.11136398231e-007,10.0020869328,13.2738473846,-0.00180108372191,-0.00185284657569,0.000224072507111,0.671929755798,-0.00024789454562 +5.46,51.000272371,1.10819847993e-007,10.0021042466,13.2967400026,-0.00264311557274,-0.00160990158518,-0.00199922614506,0.669097972682,-0.00114862801971 +5.47,51.0002735672,1.1034681911e-007,10.0021261324,13.3188631294,-0.00399796165465,-0.00276726166696,-0.00337928272585,0.666235664357,5.81717791024e-005 +5.48,51.0002747655,1.09854000078e-007,10.0021521308,13.3438967466,-0.00292095872616,-0.00243242143545,-0.00191729917968,0.667285653967,8.15493990304e-005 +5.49,51.000275966,1.09407014328e-007,10.0021720843,13.3662719993,-0.00335448625751,-0.00155827345315,0.000491904666442,0.666336423486,0.00271773869162 +5.5,51.0002771686,1.09108649439e-007,10.0021900577,13.3918924413,-0.000834399894573,-0.00203641465405,-0.00110566883414,0.664762107455,0.000250280172769 +5.51,51.0002783734,1.09125029844e-007,10.0022132743,13.4138305114,0.00106437213728,-0.00260690199847,0.000113441510807,0.666193203561,0.000768455381869 +5.52,51.0002795802,1.0913070209e-007,10.0022322582,13.43762996,-0.000984736760788,-0.00118987179789,-0.000458725382092,0.665399503602,0.000350458921578 +5.53,51.0002807892,1.09154604764e-007,10.002242826,13.4606942909,0.00132031767862,-0.00092370010074,0.00253542866344,0.665394228106,0.00209291917447 +5.54,51.0002820002,1.09203063101e-007,10.0022438184,13.4838208157,-0.000639988167166,0.000725220489397,-2.81221920256e-005,0.664513279759,0.00020487312776 +5.55,51.0002832132,1.09045814275e-007,10.0022345073,13.5058403921,-0.00156770234247,0.00113701317411,-0.000453503529016,0.6632746409,-0.00100986487638 +5.56,51.0002844284,1.08672118525e-007,10.0022231718,13.5308066278,-0.00367878859782,0.00113007851489,-0.000798171860999,0.66471422859,0.000104549862733 +5.57,51.0002856457,1.08171712028e-007,10.0022067121,13.5553084956,-0.00334665413897,0.00216187062877,-0.000458920759748,0.661803477318,0.00189607515069 +5.58,51.0002868654,1.07880643931e-007,10.0021926022,13.5815385344,-0.000739788045658,0.000660105721172,-0.000131784227424,0.663333355666,0.000144241377756 +5.59,51.0002880872,1.07859914197e-007,10.0021872467,13.6038749048,0.000448753538296,0.000410979727743,-0.000557872559834,0.663889478453,-0.000956307088421 +5.6,51.000289311,1.07827329048e-007,10.0021848658,13.6259944793,-0.000906231753511,6.52188938174e-005,-0.000488146600985,0.661457192773,0.000562114852091 +5.61,51.000290537,1.07870247912e-007,10.002183075,13.6502162489,0.00150878982623,0.000292933741756,-0.000840444992434,0.66157851897,0.000722111651003 +5.62,51.0002917649,1.07964941226e-007,10.0021764415,13.6718153864,-0.000179345896321,0.00103376156399,0.00143432663126,0.659703093592,0.00318854357575 +5.63,51.000292995,1.07921250656e-007,10.0021708138,13.696719637,-0.000434046517787,9.17845969302e-005,0.00277856150556,0.661283288738,0.00351449712327 +5.64,51.0002942271,1.07911044012e-007,10.0021687718,13.7181586561,0.000290750643951,0.000316615692213,0.00160512230484,0.657444193325,0.00343013814844 +5.65,51.0002954613,1.07969451309e-007,10.0021605458,13.7418729897,0.000529256766771,0.00132858687547,9.74323857068e-005,0.65523039308,0.00490425980994 +5.66,51.0002966975,1.08121544657e-007,10.0021598895,13.7630845159,0.00160605292779,-0.00119733691158,-0.000105085971108,0.655224176867,0.00195352569997 +5.67,51.0002979357,1.08409786259e-007,10.0021653729,13.7867521293,0.00244070575307,0.000100650752013,-5.1003091022e-005,0.653411916965,0.00365153597297 +5.68,51.0002991761,1.08701182941e-007,10.0021616525,13.8106598958,0.00165034847603,0.000643447496649,-0.00109472030298,0.654372287635,-0.000480090053663 +5.69,51.0003004185,1.08900076905e-007,10.0021541351,13.8338077647,0.00114201677388,0.000860021390136,-0.00153685972537,0.653521557523,-0.000909971953797 +5.7,51.000301663,1.09005998512e-007,10.0021597207,13.8543804125,0.000345066109296,-0.00197713945832,0.00032797452156,0.652186215613,-0.000614426071709 +5.71,51.0003029094,1.09007635233e-007,10.0021709853,13.8788499325,-0.000322087411522,-0.000275782348695,-0.000937861520191,0.64950025668,-0.00209712015448 +5.72,51.000304158,1.09026709368e-007,10.0021791458,13.9027099977,0.000589878062142,-0.00135631968271,0.000770606555267,0.649459130195,-0.000338372507379 +5.73,51.0003054088,1.09105643735e-007,10.0021827753,13.9259914556,0.00051831826829,0.000630415795846,0.000151766022356,0.649341266646,-0.000226042739949 +5.74,51.0003066617,1.09212953357e-007,10.0021842532,13.9502159855,0.000988251424187,-0.000925995125887,0.00127900734338,0.648161972647,-0.000212798059161 +5.75,51.0003079167,1.09233660993e-007,10.0021964183,13.9739031343,-0.000697527271338,-0.00150701925499,-0.000119941182444,0.648754804324,-0.000155636320863 +5.76,51.0003091739,1.09109109637e-007,10.0022060403,13.9981348774,-0.00105110705924,-0.000417382047997,0.00160675962399,0.6484326774,-0.000335220416224 +5.77,51.0003104332,1.09059687543e-007,10.0022135426,14.0207313224,0.000357247336621,-0.00108307181411,0.00395889472861,0.648189071182,0.0011141094424 +5.78,51.0003116945,1.09096232677e-007,10.0022206737,14.0436095167,0.000155826744848,-0.000343153646283,0.00255042432212,0.646698443478,0.000690700408639 +5.79,51.0003129579,1.09142794834e-007,10.0022224795,14.0660468183,0.000497880942882,-1.80135809476e-005,0.00506512324673,0.646982585817,-0.00037165160422 +5.8,51.0003142233,1.09301227222e-007,10.0022199104,14.0894704751,0.00172642466997,0.000531836404787,0.00397455763062,0.6452019966,-0.00133330408348 +5.81,51.0003154909,1.09640784862e-007,10.0022075304,14.1129434086,0.00304078205819,0.00194416179663,0.00508207563702,0.64562054932,-0.00150092125609 +5.82,51.0003167605,1.10006977684e-007,10.0021960041,14.1357439053,0.00210036820397,0.000361096897076,0.00495956817759,0.643793541589,-0.0012950596388 +5.83,51.0003180322,1.10273148135e-007,10.0021937903,14.1603073974,0.00163652165704,8.16636639557e-005,0.00567482358063,0.643768582509,0.000734972541287 +5.84,51.0003193061,1.10426473514e-007,10.0021951857,14.1831012978,0.000516084088269,-0.000360728445277,0.00262339936978,0.64308869198,0.00040868418841 +5.85,51.000320582,1.10417239971e-007,10.0021953082,14.2048470325,-0.000645718041823,0.000336230819601,0.0065183271931,0.642228724968,0.00123027679257 +5.86,51.00032186,1.10220497913e-007,10.002193974,14.2308134145,-0.00211643429643,-6.93929554414e-005,0.00671561194476,0.642075659842,-0.00194015603366 +5.87,51.0003231402,1.09954410994e-007,10.0021869251,14.2527662066,-0.00161928242169,0.00147916909485,0.00685209542546,0.64357290558,-0.00219807200919 +5.88,51.0003244224,1.09894592578e-007,10.0021727379,14.2759677849,0.000779464149085,0.00135827505834,0.00447479830073,0.64092366441,0.000439975416703 +5.89,51.0003257067,1.09908475154e-007,10.0021609312,14.2995902678,-0.000584560274602,0.00100306784098,0.00557524492707,0.640821211692,0.000301326571661 +5.9,51.0003269932,1.0992162872e-007,10.0021478193,14.3238511383,0.000769229212163,0.00161931223363,0.00431206328381,0.638618743957,0.000472415304468 +5.91,51.0003282818,1.1003669244e-007,10.0021342639,14.3474510717,0.000846203126771,0.00109176212733,0.0028553103648,0.637931235192,-0.000360217673203 +5.92,51.0003295726,1.10104544635e-007,10.0021267179,14.3716732116,0.000106404936287,0.000417430731797,0.0010441748659,0.636807305586,-0.000724699277316 +5.93,51.0003308656,1.10076004863e-007,10.00212157,14.3969719972,-0.00050708784772,0.000612149247808,0.00122837823891,0.632566421998,0.000414386150405 +5.94,51.0003321608,1.1007375386e-007,10.0021186309,14.4208500984,0.000475484963206,-2.43328637013e-005,-0.000755085711707,0.633777141442,-0.0010178767723 +5.95,51.000333458,1.10167003417e-007,10.0021185342,14.4431345433,0.000833688193585,4.36834556253e-005,-0.00124449381202,0.634644232928,0.000579690333255 +5.96,51.0003347575,1.10288738051e-007,10.0021212458,14.4688782196,0.00087539991448,-0.000586005121765,-0.000451228967593,0.631948565155,0.00109633788543 +5.97,51.0003360591,1.10494637884e-007,10.0021330835,14.4913772603,0.00201532178471,-0.00178153041413,0.000860995360161,0.629290826746,0.000864226074192 +5.98,51.0003373627,1.10747360122e-007,10.002143837,14.5145855099,0.00153276093619,-0.000369182686656,0.00163817320846,0.63181466968,0.000230800642116 +5.99,51.0003386684,1.11021486658e-007,10.002143716,14.5357032646,0.00231582634645,0.000393391799389,0.00104425930976,0.632124561328,0.000434890518484 +6,51.0003399761,1.11350639598e-007,10.0021407327,14.5596806411,0.00230530157442,0.000203270133718,0.000331332604189,0.631379373697,-0.000515488535058 +6.01,51.0003412859,1.11589213057e-007,10.0021391178,14.5832925339,0.00104413972177,0.000119714314799,-0.00166223974462,0.631731044632,-0.000135741661167 +6.02,51.0003425977,1.11627091432e-007,10.002136729,14.6051563494,-0.000512347983194,0.000358027417892,-0.00287691199339,0.630701793207,-0.000187253801343 +6.03,51.0003439116,1.1158969277e-007,10.0021260755,14.6274424046,-1.27088134179e-005,0.00177268595828,-0.00285493050057,0.632089997927,0.00113213220412 +6.04,51.0003452275,1.11598611808e-007,10.0021107739,14.6517322477,0.00013792722195,0.00128762198347,-0.00066464090343,0.631333435091,0.000117904748639 +6.05,51.0003465456,1.11521421316e-007,10.0021016159,14.6761881887,-0.00122163949315,0.000543986348346,0.000604613711242,0.626693765023,-0.00108266711032 +6.06,51.000347866,1.11369254149e-007,10.0020936067,14.7006462207,-0.000914704257506,0.00105785740875,-0.000658345201498,0.624925704291,-0.00181957616804 +6.07,51.0003491884,1.11207034178e-007,10.0020845712,14.7241374932,-0.0013627752832,0.000749234378841,-4.40179604897e-005,0.623824160245,-0.000706185380895 +6.08,51.000350513,1.11086759644e-007,10.0020797392,14.7470487477,-0.000325813267322,0.000217173295133,-0.000651982778349,0.623660318871,0.000513416155422 +6.09,51.0003518396,1.11182010757e-007,10.0020799585,14.7701805165,0.00166308662181,-0.000261032025164,-0.000436805835176,0.623440979456,0.000585666876154 +6.1,51.0003531684,1.11387838711e-007,10.0020893417,14.7933489442,0.0012266248851,-0.00161560910671,0.00012209174485,0.621443060381,0.000829718967111 +6.11,51.0003544992,1.11556316396e-007,10.0021119136,14.8167625596,0.00113870926945,-0.0028987680546,0.000531521157799,0.621750485554,0.00395987458262 +6.12,51.0003558321,1.11660759807e-007,10.0021376139,14.8400403529,0.000327618816328,-0.00224129567333,-0.000658162212078,0.620890406146,0.00360454083649 +6.13,51.000357167,1.11676299866e-007,10.0021539088,14.861233158,-0.000109444926302,-0.00101768081177,0.000100725856107,0.620683325362,0.00233520922777 +6.14,51.000358504,1.11650507923e-007,10.002176149,14.8860067481,-0.000252659757727,-0.00343036755291,-0.000137713718088,0.617815445654,0.00173109272744 +6.15,51.0003598432,1.11728014176e-007,10.00221797,14.9109908026,0.00134080483105,-0.0049338235118,0.000629831598601,0.619000256955,0.00115004373657 +6.16,51.0003611846,1.11796899133e-007,10.0022591697,14.9345781157,-0.000373697977714,-0.0033061299949,-0.000491649361486,0.618060863099,0.00209931476733 +6.17,51.000362528,1.1162214759e-007,10.0022797157,14.955973912,-0.00207971725698,-0.000803067501585,-0.00275284283185,0.618734549061,0.00334947278464 +6.18,51.0003638734,1.11384527939e-007,10.0022911621,14.9796987789,-0.00125633146284,-0.00148619921408,-0.00156019259996,0.61613100413,0.00132809271449 +6.19,51.000365221,1.11217897722e-007,10.0022952618,15.0025314263,-0.00108306471426,0.00066625885142,-0.00123007184885,0.615641108529,0.000819243578052 +6.2,51.0003665706,1.11141831726e-007,10.0022964976,15.0272681946,1.51401642326e-005,-0.000913434637012,-0.00157931600367,0.615488602146,0.000244705888579 +6.21,51.0003679225,1.11181332054e-007,10.0023072215,15.0517573853,0.000539422583971,-0.00123134249157,-0.00207421549138,0.611969424836,-0.00332690176938 +6.22,51.0003692766,1.11325984045e-007,10.0023112527,15.0757643685,0.0014914112523,0.000425102271158,0.000380258898935,0.612004762847,-0.00166946881326 +6.23,51.0003706328,1.11527830009e-007,10.0023143292,15.0991882319,0.00134239422758,-0.00104039322901,-0.00121229614005,0.612187629343,-0.000372547270696 +6.24,51.0003719911,1.11559020611e-007,10.0023263265,15.1222175362,-0.000904495432592,-0.00135907260243,-0.00077481753752,0.612794629441,0.000351571376032 +6.25,51.0003733514,1.11445804956e-007,10.0023187466,15.1459242823,-0.000684989540965,0.00287504950761,0.000477034993865,0.612757448251,0.000637742829313 +6.26,51.000374714,1.11327705277e-007,10.0023033877,15.1701633594,-0.000973064358421,0.000196731075428,-0.0010375713451,0.611836575912,0.00105021251201 +6.27,51.0003760787,1.1117380402e-007,10.0022914354,15.1945848399,-0.00118762375098,0.00219372459274,-0.00229711262029,0.612368797098,0.00116465571883 +6.28,51.0003774456,1.11115491669e-007,10.0022827785,15.2182329257,0.00036895075665,-0.000462336357353,-0.00119772429211,0.610606854125,-0.000263877322496 +6.29,51.0003788146,1.11145242433e-007,10.0022956995,15.2422589242,4.87334188473e-005,-0.00212187123408,-0.0018634511616,0.610491402886,-0.000195227122369 +6.3,51.0003801857,1.11249354979e-007,10.0023113076,15.2643925555,0.00141294870729,-0.000999736918911,-0.0018524739533,0.608271897807,0.000164549699674 +6.31,51.0003815589,1.11437213043e-007,10.0023186296,15.2887840869,0.0012244737993,-0.000464675467024,0.00023957634737,0.60859236299,-0.000765638271596 +6.32,51.0003829342,1.11615363237e-007,10.0023230912,15.3107120787,0.00127665553312,-0.000427643776513,-0.00109621861611,0.607516104971,0.000325889874196 +6.33,51.0003843115,1.11766259738e-007,10.0023339048,15.3332156223,0.000841847115877,-0.00173507415792,-0.00167906911589,0.605874827479,0.000683210533865 +6.34,51.0003856908,1.11956713888e-007,10.0023585901,15.3559549744,0.00183202273622,-0.00320198314212,-0.00132104713311,0.607034404736,-0.000466567502195 +6.35,51.0003870722,1.12281550106e-007,10.0023895739,15.3798323029,0.00272849612876,-0.00299477824535,-6.07212428314e-005,0.607507385054,0.000239105496908 +6.36,51.0003884557,1.12532419737e-007,10.0024097873,15.4029090792,0.000793573158648,-0.00104790091594,-0.000458191907341,0.605262307388,8.10381803895e-006 +6.37,51.0003898413,1.12592980514e-007,10.0024190616,15.4257221679,5.66662460636e-005,-0.000806963745423,-0.000824218880456,0.604122662652,0.000890977404935 +6.38,51.000391229,1.12634179033e-007,10.0024251708,15.4511596122,0.00052173786455,-0.000414875890814,-0.00151232889614,0.603173113596,0.00204221988559 +6.39,51.000392619,1.12780456772e-007,10.0024237597,15.4757743137,0.00153191955808,0.000697102539788,-0.00026493059872,0.601896223894,0.00270472672443 +6.4,51.0003940112,1.12889572212e-007,10.0024202742,15.5,0,0,0,0.6,0 +6.41,51.0003954054,1.12888394668e-007,10.0024213092,15.5198383021,-1.65320509654e-005,-0.000206993591499,0.00133994461491,0.597691352102,-0.000526511182291 +6.42,51.0003968013,1.12831800928e-007,10.0024163355,15.5391281996,-0.000778012247305,0.00120171759707,0.000608772069199,0.599093575945,0.0035245421771 +6.43,51.0003981989,1.12760049939e-007,10.0024044291,15.5562480105,-0.000229331289735,0.00117956185989,0.000927092421002,0.596327213719,0.0018027971092 +6.44,51.0003995981,1.1272662184e-007,10.0023875927,15.5766563637,-0.000239980402643,0.00218773040822,0.00240312373397,0.597912493305,0.0026237826138 +6.45,51.0004009992,1.12729786294e-007,10.0023770194,15.5971122632,0.000284407549626,-7.30809008519e-005,0.00244869715952,0.598929689736,0.00518559056016 +6.46,51.0004024021,1.12801703444e-007,10.0023767098,15.6158618631,0.00072526868017,0.000135010152414,0.00224914129193,0.595221806731,0.0028288679198 +6.47,51.0004038066,1.12855688272e-007,10.0023711823,15.6358027988,3.26478715112e-005,0.000970496811162,0.000719954365934,0.594214763181,0.000982642627296 +6.48,51.000405213,1.12847005132e-007,10.0023655508,15.6561327183,-0.000154554254036,0.000155788511387,0.00145424768406,0.593730011076,0.00178198478209 +6.49,51.0004066213,1.1280498762e-007,10.0023646659,15.6764505035,-0.000435347877052,2.12041323409e-005,0.00199581220823,0.591666177906,0.00137634584049 +6.5,51.0004080313,1.12756329917e-007,10.0023670745,15.695826327,-0.000247778756841,-0.000502939818546,-0.000398569610431,0.588481828622,0.00142065575657 +6.51,51.000409443,1.12752462847e-007,10.0023826646,15.7142706418,0.00019348727716,-0.00261508037426,0.0012646186826,0.589148478134,0.00321913434337 +6.52,51.0004108564,1.12675220766e-007,10.0024005481,15.7341092702,-0.00127792233672,-0.000961620716651,0.000196038831348,0.589166553745,0.00208794474032 +6.53,51.0004122716,1.1248525062e-007,10.0024120849,15.7533657041,-0.00138915086022,-0.00134573029914,-2.18829532897e-005,0.591768578697,0.00042216630393 +6.54,51.0004136885,1.12403012532e-007,10.0024210078,15.7721114515,0.000234574721572,-0.000438851605634,-0.000341590751193,0.589196885758,0.00215772207941 +6.55,51.0004151072,1.12403462562e-007,10.0024172718,15.7925970533,-0.000228256552039,0.00118605544848,0.00100410567843,0.588358167975,0.00143404024908 +6.56,51.0004165276,1.12378480026e-007,10.0024146817,15.8129941511,-0.000122484059517,-0.000668035946657,-0.000303348608888,0.588088495531,0.00201511227212 +6.57,51.0004179498,1.12271341238e-007,10.0024271237,15.829070627,-0.00138168360829,-0.00182035682451,-0.000329034460676,0.586801653546,0.00126942423381 +6.58,51.0004193736,1.12153319081e-007,10.0024464491,15.8498791362,-0.000275280361055,-0.00204474077029,-0.000718751515393,0.583302663473,0.0024666498896 +6.59,51.0004207993,1.12177295059e-007,10.0024575425,15.8726220041,0.000611889441777,-0.000173925351704,0.00341940222054,0.582931691366,0.00237725639486 +6.6,51.0004222269,1.12247527873e-007,10.0024645802,15.8906927736,0.000374139249987,-0.00123362374871,0.000420402532235,0.58303183713,0.00221411471998 +6.61,51.0004236562,1.12261394936e-007,10.0024809555,15.9104619726,-0.000179453582723,-0.0020414314721,0.000817911977731,0.583270579421,0.00199248477311 +6.62,51.0004250873,1.12266516333e-007,10.0024954144,15.930076875,0.000251355072068,-0.000850341632621,0.00226623195451,0.581692023923,0.000487283994585 +6.63,51.0004265201,1.12288745233e-007,10.0025063734,15.9505056842,6.07259919578e-005,-0.00134146207112,0.00151271808407,0.580856987555,0.000529624738005 +6.64,51.0004279547,1.12271476583e-007,10.0025130431,15.969367136,-0.000303167959885,7.52695839279e-006,0.000293866075052,0.580863213688,0.00190229234914 +6.65,51.0004293911,1.12206000864e-007,10.0025121357,15.9899737254,-0.000616073690749,0.000173940994418,0.00190520941658,0.580308650932,-4.3556801995e-005 +6.66,51.0004308293,1.12128647316e-007,10.0025081554,16.0090146681,-0.000469925852604,0.000622122492043,0.00115620160288,0.578038591287,0.000755961458137 +6.67,51.0004322691,1.11950059162e-007,10.0025105864,16.0267634533,-0.00203734952104,-0.00110833087579,0.000830494215494,0.579689048793,0.00210840805276 +6.68,51.0004337107,1.11656750143e-007,10.0025170735,16.0469499838,-0.00208054099257,-0.000189071268567,0.000541626223187,0.578180630548,0.00150710594757 +6.69,51.000435154,1.1126694813e-007,10.0025242476,16.0664134079,-0.00339205565554,-0.00124575011599,0.000645029292505,0.57604917531,0.000294057653065 +6.7,51.000436599,1.1086995366e-007,10.0025260045,16.0855897037,-0.00218151883344,0.000894369456291,-0.00115107439017,0.576767904775,-0.0012502967392 +6.71,51.0004380459,1.10530042674e-007,10.0025272769,16.1066841764,-0.00259063614062,-0.00114886125912,-0.00226396628766,0.575488507026,0.00130798095208 +6.72,51.0004394946,1.1021555584e-007,10.0025316893,16.1253589593,-0.00182457821528,0.000266375918565,0.000139647367987,0.575524560998,0.00102880082654 +6.73,51.0004409449,1.09886650762e-007,10.0025431705,16.1441278031,-0.00279305983617,-0.00256260888921,0.00157163154463,0.574291530712,0.00217556028109 +6.74,51.000442397,1.09613409955e-007,10.0025583354,16.1648993373,-0.00104308378487,-0.000470374934178,0.000856384724662,0.574331374722,0.00406620393243 +6.75,51.0004438508,1.09425620905e-007,10.0025599397,16.182383432,-0.00159336626148,0.000149531380296,0.00118499817328,0.574294357823,0.00111730485347 +6.76,51.0004453064,1.09201565299e-007,10.0025532881,16.2027116927,-0.00155224525078,0.00118078480752,0.00165309798217,0.574771778715,0.00110123748541 +6.77,51.0004467638,1.08962431807e-007,10.00253735,16.2243851676,-0.00180505096736,0.0020068249666,0.000460839176116,0.573780902313,0.00123581675105 +6.78,51.0004482231,1.08751049781e-007,10.0025108473,16.2452810121,-0.00116263059633,0.00329371351745,0.000930548470227,0.573755311258,0.000348050364271 +6.79,51.0004496842,1.08531095112e-007,10.0024823121,16.2638361318,-0.00192540581841,0.00241332676913,-0.000391366869803,0.572571707444,-0.000464212856391 +6.8,51.000451147,1.08249268449e-007,10.0024614701,16.2822610321,-0.00203127751227,0.0017550840905,0.000554621926907,0.57022036954,0.000398466955705 +6.81,51.0004526115,1.0799630337e-007,10.0024440265,16.3029674133,-0.00152020577327,0.00173363960826,-0.00151645739342,0.569795876109,0.00119078810512 +6.82,51.0004540777,1.07812500789e-007,10.0024268203,16.3192240339,-0.00106027600197,0.00170760035664,-0.00159037468232,0.57018753078,0.00221160563033 +6.83,51.0004555456,1.075230035e-007,10.0024158694,16.3406428344,-0.00300409805795,0.000482569033814,-0.000227058009485,0.569626155889,0.00173372227527 +6.84,51.0004570152,1.0707278942e-007,10.0024092762,16.358549184,-0.00331664641829,0.000836074516034,-0.000646352491106,0.566979490602,0.00241940186548 +6.85,51.0004584865,1.06592953032e-007,10.0024004983,16.3777607644,-0.00341997785616,0.000919509189395,0.00128396789522,0.569509572137,0.00145314093175 +6.86,51.0004599597,1.06136901403e-007,10.0023948149,16.398834428,-0.002982722018,0.000217174184398,-0.000717489411106,0.567080830318,-9.47771195464e-005 +6.87,51.0004614346,1.05736236651e-007,10.0023844286,16.418055085,-0.00264237809937,0.00186007335719,-0.00219728196522,0.565039490053,0.00194197158456 +6.88,51.0004629113,1.05334521221e-007,10.0023697987,16.4384752772,-0.00299747275384,0.00106591366386,-0.00131045276255,0.564438080312,0.000683004096774 +6.89,51.0004643897,1.05037384524e-007,10.0023653569,16.4560971837,-0.00117415343601,-0.000177565330875,-0.000198282904458,0.56238216177,0.00190421563686 +6.9,51.0004658698,1.04893867012e-007,10.0023580154,16.4751830006,-0.000840748789232,0.00164587836138,-0.000707542288798,0.562006570678,-0.000564167111295 +6.91,51.0004673516,1.04765079842e-007,10.0023312846,16.4946833801,-0.000967347950585,0.00370027970127,-0.00108845809398,0.560469476203,0.000625519118268 +6.92,51.0004688352,1.04626590303e-007,10.0023061974,16.5150299399,-0.000976964331502,0.00131715637144,-0.000430481193732,0.561409500809,0.000840164023266 +6.93,51.0004703207,1.04382631819e-007,10.0022982272,16.5359731613,-0.00244807023804,0.000276878044047,0.000684310811671,0.560945989431,0.00194616792744 +6.94,51.000471808,1.04094006349e-007,10.0022991265,16.5561124593,-0.00160406263129,-0.000456739006427,-4.23975207729e-005,0.558550803711,0.00199713834401 +6.95,51.0004732971,1.03914754689e-007,10.0022969476,16.5762377085,-0.000912525800766,0.000892527596845,-0.000337972282938,0.559223080448,-4.06905493918e-005 +6.96,51.000474788,1.03736255722e-007,10.0022899666,16.5953790738,-0.00159349516618,0.000503681109586,-0.000929270040475,0.557310203781,0.000520207150618 +6.97,51.0004762806,1.03425453066e-007,10.0022856649,16.6153382416,-0.00276999196661,0.000356644652103,-0.000853207747253,0.55769733469,0.000950140085513 +6.98,51.0004777751,1.03033764548e-007,10.00228162,16.6357029174,-0.00272908512757,0.000452347220615,-0.000759967512562,0.556598694055,0.00139429772422 +6.99,51.0004792713,1.0263980861e-007,10.0022794128,16.6547169358,-0.00280182502792,-1.09060899599e-005,-0.00219681933267,0.555213605172,0.000312795017121 +7,51.0004807692,1.02167512949e-007,10.0022801423,16.6732673617,-0.00382892861842,-0.000135008495522,-0.000667767748447,0.554997088735,0.000689090718463 +7.01,51.0004822688,1.01736047434e-007,10.0022787627,16.6917539959,-0.00222859362177,0.000410934807152,-0.00138656723823,0.55269794256,0.00156544774185 +7.02,51.0004837701,1.0151952639e-007,10.0022750928,16.7113905023,-0.000811234482754,0.00032305066741,-0.0021056819392,0.551814869238,0.00131030696492 +7.03,51.0004852731,1.01225538553e-007,10.0022717888,16.7301150423,-0.00331618164144,0.000337734222786,-0.000475218478755,0.549173583293,-0.000441242180553 +7.04,51.0004867779,1.00994035088e-007,10.0022678437,16.7512708484,6.60093412882e-005,0.000451290213631,-0.000369225139202,0.550903450412,0.00106425311528 +7.05,51.0004882845,1.00991975266e-007,10.0022735643,16.7698949499,-9.49280288834e-005,-0.00159541119644,-0.00108780408459,0.549745026313,0.00264705048521 +7.06,51.0004897928,1.00897806628e-007,10.0022848968,16.7892315205,-0.00122714405875,-0.000671078135764,0.00174772432274,0.548859633729,0.00231443955437 +7.07,51.0004913029,1.00686882398e-007,10.0022876603,16.8101031101,-0.0017341075729,0.000118372794918,0.000733202002814,0.548184408625,0.000910721517251 +7.08,51.0004928148,1.00523948597e-007,10.0022859715,16.8297910425,-0.000553386712461,0.000219385370092,0.000232480560323,0.545707529958,0.00136533582253 +7.09,51.0004943285,1.00331146649e-007,10.0022859152,16.8493155741,-0.00215343857676,-0.000208127594587,0.000178833336439,0.543147123231,0.00199367656242 +7.1,51.0004958439,1.00198423985e-007,10.0022808729,16.8686539622,0.000290090893597,0.00121659841045,0.000243100047714,0.543415037439,0.00171660412423 +7.11,51.0004973611,1.00292335754e-007,10.0022692253,16.8886972941,0.00102837469857,0.0011129074499,0.00315882486503,0.543569597093,0.000640402412944 +7.12,51.0004988801,1.00408518599e-007,10.0022559625,16.908608814,0.000602763570341,0.00153966349919,-0.000607896968812,0.543527292096,-0.000393330979275 +7.13,51.000500401,1.00511335555e-007,10.002246089,16.9296149786,0.000840725488165,0.000435026158551,-0.00017568188918,0.539857454522,-0.00146881442472 +7.14,51.0005019236,1.00613384639e-007,10.0022436664,16.9487308097,0.000591983075402,4.94910869464e-005,0.000335938488074,0.540368751531,-0.0016628959727 +7.15,51.0005034479,1.00682487954e-007,10.0022463037,16.9661878067,0.000378186406518,-0.000576932868878,-0.000214752281179,0.538493326395,-0.00150754409985 +7.16,51.0005049739,1.00739701712e-007,10.0022452809,16.9860513966,0.000425060734558,0.000781492499974,-0.000851243646926,0.540434651812,-0.00180845173355 +7.17,51.0005065016,1.0083875125e-007,10.0022285042,17.0057690459,0.000965535817788,0.00257384101704,-0.00141472948142,0.54075253908,-0.00200578771434 +7.18,51.0005080312,1.00995308227e-007,10.0022046246,17.0263942807,0.00123243089072,0.00220207424684,-0.00147337154751,0.540556075138,-0.000695798635877 +7.19,51.0005095626,1.01241784246e-007,10.0021919119,17.0480870577,0.00222794549433,0.000340475571815,-0.0019346274872,0.540296422439,-0.000407056065663 +7.2,51.0005110958,1.01500079025e-007,10.0021903461,17.0651442432,0.001398359143,-2.73296789122e-005,-0.00238389823081,0.537736427533,-0.00173811471686 +7.21,51.0005126307,1.01673045451e-007,10.0021842536,17.0849751,0.00102998623067,0.00124584374598,0.000876343623097,0.535434941248,-0.00184863047681 +7.22,51.0005141672,1.01813127227e-007,10.0021726537,17.1029375525,0.000936678205687,0.00107413949914,-0.00169177635811,0.533549842883,-0.0022176214224 +7.23,51.0005157055,1.01956084026e-007,10.0021612373,17.1222251819,0.00107034978778,0.00120914078214,0.000803685341732,0.532507926203,-0.0015671799146 +7.24,51.0005172455,1.02142772909e-007,10.0021470439,17.1425562433,0.0015506504122,0.00162952320041,-0.000566788840717,0.5340386574,-0.00394375327183 +7.25,51.0005187873,1.02338094258e-007,10.002131631,17.1617350606,0.00119154435997,0.00145306907747,-0.00355657279768,0.532567326656,-0.00583611981899 +7.26,51.0005203307,1.02438919463e-007,10.0021109382,17.1804263334,0.000223981122655,0.00268549181239,-0.00247968721399,0.532295217275,-0.00541526120706 +7.27,51.000521876,1.02620917097e-007,10.0020857553,17.2007506839,0.0023311564612,0.00235108253686,-0.00128228753899,0.532741393706,-0.0038519597993 +7.28,51.000523423,1.02905818935e-007,10.0020658461,17.2202745329,0.00166869435816,0.00163076139906,-0.000351497044209,0.532646901553,-0.00100611935519 +7.29,51.0005249718,1.03188728706e-007,10.0020526776,17.2401383289,0.00230318886652,0.00100293859738,-0.000649027380624,0.53138994527,-0.000337127791469 +7.3,51.0005265224,1.03504793813e-007,10.0020534491,17.2606989189,0.00213417523145,-0.00115723531909,0.000542450833913,0.531555454497,-0.00101671834842 +7.31,51.0005280748,1.03697855688e-007,10.0020754087,17.2791233684,0.000576297366735,-0.00323470278685,-0.000147872431238,0.53132713377,0.000496097044109 +7.32,51.0005296289,1.03910024267e-007,10.0021045947,17.2982687096,0.0024024217087,-0.00260249142126,-0.000536163942094,0.530388158219,-0.000619755564893 +7.33,51.0005311847,1.04166510182e-007,10.0021258973,17.3183937515,0.00119848600583,-0.00165803026949,-0.00216355117202,0.528994336223,-0.000481843598662 +7.34,51.0005327423,1.04333987307e-007,10.0021478811,17.3376345788,0.00115279183848,-0.00273871692929,-0.00210729318986,0.527962619184,0.000345294016909 +7.35,51.0005343016,1.04412271309e-007,10.0021715699,17.3565121505,-5.37316767126e-005,-0.00199904921842,-0.00338353436168,0.52810141046,0.000264244702311 +7.36,51.0005358627,1.04503357942e-007,10.0021856859,17.3760582846,0.0013325329672,-0.00082414812766,-0.00223168961259,0.526386841695,0.000156027271197 +7.37,51.0005374255,1.04738642088e-007,10.0021903851,17.3967398038,0.00197071421194,-0.000115693428912,-0.000316771686054,0.526807833731,-0.000508872027891 +7.38,51.0005389901,1.0490971957e-007,10.0021861576,17.4153013174,0.000431110177933,0.000961185728441,-0.000363846947633,0.526050947591,0.00105353818449 +7.39,51.0005405564,1.05073163995e-007,10.0021861517,17.4346866791,0.00186355057066,-0.000960007365891,-0.00246024154679,0.524542641208,0.00188513055593 +7.4,51.0005421245,1.05344906085e-007,10.002199247,17.4538751916,0.00195154373232,-0.00165904435362,-0.000191072974812,0.52454388141,0.000554062437278 +7.41,51.0005436943,1.05650808223e-007,10.0022238484,17.4736068737,0.00234313680253,-0.00326124262401,0.000699493982811,0.523427036069,0.00156971050414 +7.42,51.0005452657,1.0592900911e-007,10.0022476926,17.4908251977,0.00156263485324,-0.0015075938466,-6.40933569852e-005,0.52213822505,0.000646684689313 +7.43,51.0005468389,1.06172230717e-007,10.0022547189,17.5112065147,0.00185204879998,0.000102344608291,0.000362892010508,0.521788167567,0.000938218402425 +7.44,51.0005484138,1.06397674264e-007,10.0022590412,17.5302748665,0.00131304158761,-0.000966805108924,-0.000872396632477,0.520033331324,-5.1518849462e-005 +7.45,51.0005499905,1.0654799815e-007,10.0022739594,17.5512847793,0.000797414348542,-0.00201684642303,-0.000806540402743,0.519788861494,0.000624883783076 +7.46,51.000551569,1.06712024449e-007,10.0022897725,17.5700735677,0.00150541503181,-0.00114576249037,-0.00364047239297,0.519227383206,0.000823729036683 +7.47,51.0005531493,1.06774976956e-007,10.0022958392,17.5898350228,-0.000621600144138,-6.75833495838e-005,-0.00533088911925,0.519141294123,0.000117813682782 +7.48,51.0005547312,1.06754356909e-007,10.0023051995,17.6087369452,0.000332107233886,-0.00180448001232,-0.000562683696082,0.517377500283,-0.00082914422415 +7.49,51.000556315,1.06693076796e-007,10.0023284751,17.629809183,-0.00119244260592,-0.0028506394018,-0.000851950875448,0.516936808579,-3.00800668089e-005 +7.5,51.0005579006,1.06502841829e-007,10.002356312,17.6486640339,-0.00147834015962,-0.00271673077996,-0.00120192958724,0.5147506406,0.000459231862637 +7.51,51.0005594879,1.06295726427e-007,10.0023722432,17.6676904818,-0.00142943352217,-0.000469512837512,-0.000130426644487,0.513482857647,0.000266366788291 +7.52,51.0005610768,1.06123180713e-007,10.0023814417,17.6856703072,-0.000993002771356,-0.00137019782659,-0.00085717743333,0.513442846967,-0.000865349095026 +7.53,51.0005626674,1.06063859781e-007,10.0023990724,17.7057906617,0.000160173162346,-0.00215594632564,-0.0028008511074,0.510695361432,-0.0022497883236 +7.54,51.0005642599,1.0604887736e-007,10.002414713,17.7253744092,-0.000370517167367,-0.000972155538276,-0.00250648459578,0.5094014459,-0.00206658887952 +7.55,51.0005658541,1.05862236616e-007,10.0024212067,17.745728174,-0.00224980442244,-0.000326588932152,-0.0019074945262,0.509637479527,-0.00407289469971 +7.56,51.0005674501,1.05609200396e-007,10.0024250395,17.7645190598,-0.00130266888713,-0.000439965484854,-0.00157106974051,0.51046686478,-0.00194205247251 +7.57,51.0005690478,1.05432741193e-007,10.0024310333,17.7837580858,-0.00117470998313,-0.000758800735924,-0.00147307462058,0.509947844796,-0.00415977313261 +7.58,51.0005706472,1.05348213105e-007,10.0024355492,17.8020632152,-1.20124503989e-005,-0.00014437607291,-0.000336316838543,0.508251940352,-0.00309382756121 +7.59,51.0005722483,1.05139895038e-007,10.002425896,17.822685461,-0.0029126450499,0.00207501536513,-0.000261178872356,0.506346127021,-0.00466498967289 +7.6,51.0005738513,1.04912827087e-007,10.0024184914,17.8428899527,-0.000275249289734,-0.000594093076826,-0.000600608403033,0.506078225,-0.00249438873479 +7.61,51.0005754561,1.04978918992e-007,10.0024347181,17.8631455653,0.00120313890011,-0.00265126490382,-0.000530228482884,0.505298385772,0.000335716854788 +7.62,51.0005770626,1.05035611271e-007,10.00245729,17.8819473827,-0.000407214210381,-0.00186310604036,-0.00164525968495,0.505134208246,-0.000589038844842 +7.63,51.000578671,1.05025177094e-007,10.0024704915,17.903235974,0.000260724780296,-0.000777191018545,-0.00202145833144,0.503806991171,0.000144766560123 +7.64,51.0005802811,1.05022888783e-007,10.0024824042,17.9222659761,-0.000292851238779,-0.00160535439991,0.000590730564655,0.501686800185,-0.000917426942949 +7.65,51.000581893,1.05017683943e-007,10.0024939255,17.9419472504,0.000219778498585,-0.000698899125912,0.00211000112005,0.499629715216,-0.000236917724559 +7.66,51.0005835066,1.05069985368e-007,10.002502807,17.9605842521,0.000514501154709,-0.00107739473612,0.00206198305676,0.501359778172,-4.3570984391e-005 +7.67,51.0005851219,1.05199169211e-007,10.0025161134,17.9793002261,0.00129916004475,-0.00158389536071,-0.000124063411766,0.499582754125,-0.000286122462905 +7.68,51.000586739,1.05291706058e-007,10.0025240329,18,0,0,0,0.5,0 +7.69,51.0005883577,1.05303438574e-007,10.0025130565,18.0153883019,0.000164717250337,0.00219527954039,-0.00134865726407,0.498807242649,0.00156616772591 +7.7,51.0005899777,1.05310957678e-007,10.0025012954,18.0303285438,-5.91536951543e-005,0.000156942838353,-0.00129981464839,0.497912455348,0.00219112884017 +7.71,51.0005915992,1.05339649388e-007,10.0025071927,18.0465466497,0.000461967485353,-0.00133640710126,-0.00131725364726,0.495339315511,-0.000421902038619 +7.72,51.0005932221,1.05341766538e-007,10.0025170472,18.0622782411,-0.000432243991353,-0.000634494919428,-0.00123937818053,0.491751454,2.75496588669e-005 +7.73,51.0005948463,1.05173467261e-007,10.0025179846,18.0763753005,-0.00193057318729,0.000447014459487,-0.00406234523127,0.491885668107,-0.00146456993998 +7.74,51.0005964719,1.05068353365e-007,10.002507027,18.0922380745,0.000454839453795,0.00174451373363,-0.00254567819356,0.490884581691,-0.000840279338825 +7.75,51.0005980989,1.05113839057e-007,10.002500631,18.1072601247,0.000183751340142,-0.000465316401657,-0.00307649148749,0.48609162791,0.00123722436692 +7.76,51.0005997272,1.05141717812e-007,10.0025000928,18.1236578984,0.000207648994154,0.000572941759945,-0.000905418883391,0.486007581243,0.00117578524103 +7.77,51.0006013571,1.05132321192e-007,10.0024968309,18.1397144134,-0.000339571666841,7.94449379946e-005,-0.000953182545124,0.485389332199,0.00063906418992 +7.78,51.0006029883,1.05106278109e-007,10.0024949518,18.1553378232,-2.60569693067e-005,0.000296385373285,-0.000619535105134,0.481976711447,0.00107909039204 +7.79,51.000604621,1.05102044672e-007,10.0024977385,18.1705996123,-3.33778306232e-005,-0.00085373786509,0.00010610201687,0.480166607583,-0.000989486262551 +7.8,51.000606255,1.05041427992e-007,10.0024972543,18.1850388096,-0.000817642455886,0.000950576953012,0.000785989942726,0.476419915715,2.41488381739e-005 +7.81,51.0006078904,1.0479559012e-007,10.0024883792,18.2020365276,-0.00263376741129,0.000824441455281,-0.000597042161167,0.473528739457,0.00134927940206 +7.82,51.0006095273,1.0468183149e-007,10.0024697401,18.2181105843,0.00103666742238,0.00290337896027,0.0007811701038,0.470845815339,0.000463782372464 +7.83,51.0006111655,1.04791313709e-007,10.0024447879,18.2328322103,0.000500394328635,0.00208707455025,0.000358070014189,0.468939210019,0.00246453980599 +7.84,51.0006128051,1.04985116445e-007,10.0024341015,18.2482572516,0.00222047449784,5.02010357282e-005,-0.000125865653697,0.468632733194,0.0011923092499 +7.85,51.0006144462,1.0534202675e-007,10.0024362559,18.2653442844,0.00279032215141,-0.000481086691152,0.00140269903955,0.46861597719,0.000346782531276 +7.86,51.0006160887,1.05904724951e-007,10.002440335,18.2784482033,0.0051096070797,-0.000334727129171,0.0025604186256,0.464465260509,0.000836454052613 +7.87,51.0006177324,1.06535391933e-007,10.0024439777,18.2945976432,0.00374456088328,-0.000393810459869,0.0029296825321,0.461109996547,-0.000113251537401 +7.88,51.0006193776,1.07069684059e-007,10.0024453793,18.3101659038,0.00375656441136,0.000113493524069,5.7583212247e-005,0.460109121233,0.00167236546074 +7.89,51.0006210242,1.07421677545e-007,10.0024541517,18.3256384559,0.00118520254356,-0.00186797347682,-0.000271690805007,0.457576029442,0.00304018743356 +7.9,51.0006226721,1.07674896688e-007,10.0024768416,18.3409478591,0.00236983463601,-0.00267001922422,0.00052854822483,0.456293516595,0.003306042148 +7.91,51.0006243214,1.07978626433e-007,10.0024963856,18.3556819213,0.00189433944346,-0.00123877542121,-0.00122027275587,0.455114995315,0.00186711383774 +7.92,51.0006259722,1.08273844449e-007,10.0025083282,18.3740913092,0.00225033516401,-0.00114975370925,7.78162474313e-005,0.452924915312,-0.000172961459641 +7.93,51.0006276246,1.08509780363e-007,10.0025170324,18.3894353645,0.00106205604986,-0.000591077998971,-6.79784194123e-005,0.450825271023,0.00186675254566 +7.94,51.0006292784,1.08715063205e-007,10.0025248735,18.4074899644,0.00181998527861,-0.00097714287201,0.000142167643569,0.448894064969,0.00185597231871 +7.95,51.0006309336,1.09153126466e-007,10.0025358259,18.419690783,0.00433014571493,-0.00121333827632,-0.00101522245314,0.446530056875,0.00265378053267 +7.96,51.00063259,1.09659173805e-007,10.002544293,18.4360887307,0.00277443855185,-0.000480073774726,0.000338432122695,0.444464324382,0.00286535406983 +7.97,51.0006342479,1.10006810089e-007,10.0025491535,18.4513952313,0.00210615459545,-0.000492023436724,0.00241846347982,0.441623259008,0.00481528389619 +7.98,51.0006359072,1.10313116718e-007,10.0025551807,18.4672716938,0.00219419622819,-0.000713419182197,0.00218167619613,0.439323644471,0.00336457406874 +7.99,51.0006375679,1.10547403494e-007,10.0025645805,18.4833532266,0.00109504143783,-0.00116654884845,0.000978477178818,0.439134460327,0.00357671870758 +8,51.0006392301,1.10768601151e-007,10.002571474,18.4985400392,0.00201043316466,-0.000212148679227,0.000665590880855,0.438277949451,0.00135764373438 +8.01,51.0006408936,1.11028462046e-007,10.0025737902,18.5157592758,0.001637848624,-0.000251096276793,0.00209678808747,0.435576076118,-1.14413071259e-005 +8.02,51.0006425586,1.11305012261e-007,10.0025758378,18.5284215523,0.0022447404545,-0.000158419703484,0.00265003443124,0.432637301811,-0.000361798863949 +8.03,51.0006442247,1.11597081521e-007,10.0025818811,18.5433508001,0.0018557260106,-0.00105024834766,0.00387578042286,0.432932350066,0.00124361150291 +8.04,51.0006458923,1.11748198728e-007,10.0025847506,18.5600156714,0.000265863313328,0.000476357840739,0.00126768705621,0.428980586628,0.00113716619296 +8.05,51.0006475614,1.11861890435e-007,10.0025816624,18.5762548677,0.00133029573716,0.000141275817697,0.00152633686868,0.426877728577,0.000398585629169 +8.06,51.0006492319,1.12035037439e-007,10.0025774198,18.5925409696,0.00110057770884,0.000707239987056,0.000747989060453,0.424030046617,0.00112480494376 +8.07,51.0006509039,1.12181976636e-007,10.002569106,18.6073788733,0.000962354767401,0.000955522111915,0.00178001253597,0.420529757951,0.000739607711751 +8.08,51.0006525772,1.1237447856e-007,10.0025563062,18.6233704305,0.00174024918472,0.00160444057686,0.00250556043418,0.421700367964,-0.000421582427355 +8.09,51.0006542519,1.12640499042e-007,10.0025406203,18.6385469113,0.00199450821627,0.00153273569055,0.00250022928818,0.419520913674,-0.00172235797769 +8.1,51.0006559281,1.12960006711e-007,10.0025230427,18.6557554551,0.00249117490292,0.00198280282427,0.00382589120192,0.418083896701,0.000270100355613 +8.11,51.0006576056,1.13331476147e-007,10.0025003224,18.6690287372,0.00272401796341,0.00256124245169,0.0014319666108,0.415455270255,-0.000421768234701 +8.12,51.0006592845,1.13692617008e-007,10.0024752239,18.6850013023,0.00234616817339,0.00245846516509,0.000426021904802,0.414496797137,0.00161916373686 +8.13,51.0006609648,1.1407631568e-007,10.00245337,18.7029172702,0.00304071494299,0.00191231791531,0.000825162746613,0.411698453326,0.00143928272022 +8.14,51.0006626466,1.14647023398e-007,10.0024382038,18.7156592841,0.00497165486403,0.0011209122879,0.000990351126257,0.410196992197,0.00236704429859 +8.15,51.0006643297,1.15268186731e-007,10.0024247372,18.7337677631,0.00374907910862,0.00157240691165,0.00124574662797,0.408666241862,0.00165115066452 +8.16,51.0006660143,1.15686139369e-007,10.002413181,18.7473600336,0.00211870711598,0.000738837069358,0.0015640186992,0.406275084276,0.000357707364704 +8.17,51.0006677001,1.15934611337e-007,10.0024050553,18.7617853978,0.00136967937654,0.000886300229775,0.000892652331768,0.403453144398,-0.000415212879035 +8.18,51.0006693874,1.16169648212e-007,10.0023942454,18.778496856,0.00193008692325,0.00127568065056,0.000794033973092,0.401699829362,0.00156795222244 +8.19,51.0006710761,1.16444711889e-007,10.0023868273,18.7957974064,0.00193162974523,0.000207948694304,0.000654090175046,0.400928252914,-0.000982893221706 +8.2,51.0006727663,1.16764201969e-007,10.0023830551,18.8102691684,0.00255380480402,0.000546485284039,0.00116317483701,0.398793451205,-8.56672866377e-005 +8.21,51.0006744578,1.17191136502e-007,10.0023755641,18.8253850837,0.00344008032438,0.000951708858698,0.00167353230922,0.397882819122,-0.00326277179913 +8.22,51.0006761508,1.17610851389e-007,10.0023706496,18.8423159186,0.00245244544993,3.11880747013e-005,0.000890797380648,0.395041245413,-0.000502922883414 +8.23,51.0006778452,1.18037902024e-007,10.0023741422,18.857781017,0.00354306922866,-0.00072970484175,-0.000466884731246,0.392581090264,-0.000659716809298 +8.24,51.0006795409,1.18429656644e-007,10.0023736995,18.8725125496,0.00195691206436,0.000818256383278,-0.000618142254125,0.389907985134,0.000369381243498 +8.25,51.0006812381,1.18582752384e-007,10.0023732541,18.8885045897,0.00019245298216,-0.000729191379991,0.000184468487211,0.388999926039,0.00213201577191 +8.26,51.0006829366,1.18840326705e-007,10.0023702612,18.903599873,0.00342372342557,0.00132778670468,-7.31205914717e-006,0.384925206628,0.000528024777853 +8.27,51.0006846367,1.19136893787e-007,10.0023631465,18.9215918231,0.000739886035122,9.51516392985e-005,-0.00232813330616,0.383916568258,0.000687000264523 +8.28,51.0006863382,1.19188329202e-007,10.0023523567,18.9367217051,-1.77661967608e-005,0.00206280519609,-0.00171819303503,0.382628214023,-0.000581656515885 +8.29,51.0006880411,1.19276654695e-007,10.0023388682,18.9524558658,0.00125779869385,0.000634888706654,-0.000887832251172,0.379344266959,-0.00214268737128 +8.3,51.0006897454,1.19416293676e-007,10.0023347155,18.9679725839,0.000702641788612,0.000195656707189,-0.00218787447636,0.379632974344,-0.000287516377846 +8.31,51.0006914511,1.19566107601e-007,10.0023155341,18.9834057439,0.00140064818494,0.00364061701184,-0.00204960218879,0.377224637296,-0.000754284512452 +8.32,51.0006931582,1.19793885176e-007,10.0022943776,18.9995092096,0.00179720058425,0.000590696551205,-0.000728556789063,0.37569138429,-0.000613348990928 +8.33,51.0006948668,1.19924903777e-007,10.0022873864,19.0149536281,4.2215184033e-005,0.000807540561053,-0.00170345289204,0.375053324691,-0.000101199645238 +8.34,51.0006965768,1.19975606161e-007,10.0022787285,19.0316840079,0.000669613203408,0.000924028560404,-0.00150410810479,0.370760398884,-0.00156678307059 +8.35,51.0006982882,1.200971252e-007,10.0022727514,19.0480097372,0.00103643474095,0.000271403063404,-0.00400418962826,0.370536341419,-0.00358403484522 +8.36,51.000700001,1.20482785204e-007,10.0022749573,19.0616349961,0.00437797963852,-0.00071259469054,-0.00228865330619,0.367947402331,-0.00151510137247 +8.37,51.0007017151,1.21108785196e-007,10.0022823153,19.0761058978,0.00441065083633,-0.000758991936558,-0.00302736620972,0.36446134846,-0.00177431431088 +8.38,51.0007034306,1.21780211203e-007,10.0022870641,19.0924647449,0.00501573083034,-0.000190777723991,-0.00182300595613,0.363631311447,-0.000224679097559 +8.39,51.0007051475,1.22642711659e-007,10.0022983351,19.1081362418,0.00709321055084,-0.00206341161305,-0.00158001487676,0.360603774102,-0.00210333039194 +8.4,51.0007068659,1.23358148272e-007,10.0023136351,19.1249159476,0.00295105056059,-0.000996599808803,-0.00405247757101,0.360248565044,-0.000725313701727 +8.41,51.0007085856,1.23745266339e-007,10.0023244533,19.1398743933,0.00248383313383,-0.00116703138515,-0.00240640087339,0.359087769717,-0.00200645903086 +8.42,51.0007103068,1.24150347119e-007,10.00233577,19.1559310873,0.00320323503113,-0.00109632147336,-0.00372801189511,0.35667875836,-0.00243079019702 +8.43,51.0007120294,1.24611696114e-007,10.002343087,19.1712191956,0.00327380169822,-0.000367068506964,-0.00484457017133,0.353356741737,-0.00125594301517 +8.44,51.0007137534,1.24928786298e-007,10.0023504793,19.1866203061,0.00117793599317,-0.00111139964022,-0.00441749347793,0.351626826227,-0.0029512683131 +8.45,51.0007154788,1.25117905605e-007,10.002364216,19.2020758324,0.0014771745985,-0.0016359434792,-0.00118634552725,0.349769292517,-0.0026951368027 +8.46,51.0007172056,1.25360695964e-007,10.0023766326,19.2186892836,0.00193144210572,-0.00084737187377,-0.00250104355622,0.347900342709,-0.00252462763543 +8.47,51.0007189338,1.25687150809e-007,10.0023878762,19.2337499638,0.00265176870785,-0.00140133745263,-0.00379630618296,0.344453952668,-0.00155712092191 +8.48,51.0007206634,1.26111087653e-007,10.0024012768,19.2506289921,0.00330002489272,-0.00127879132546,-0.00288970132028,0.344650604466,-0.000728828946465 +8.49,51.0007223947,1.26646798422e-007,10.0024120983,19.2685564072,0.00422100058401,-0.000885501128099,-0.00255158835002,0.342246948701,-0.00294695523575 +8.5,51.0007241274,1.27131969758e-007,10.0024189534,19.28378597,0.0025904844177,-0.000485523268109,-0.00322420039555,0.34023478596,-0.00297649215623 +8.51,51.0007258614,1.27505493242e-007,10.0024140936,19.2972851179,0.00265353828849,0.00145747137887,-0.0053707075972,0.337850790921,-0.00262162265992 +8.52,51.0007275967,1.27796128029e-007,10.0024014973,19.3136612176,0.00142678179816,0.00106178998909,-0.00453991915351,0.336121601972,-0.00319241212134 +8.53,51.0007293335,1.28046677346e-007,10.0023923936,19.3281205,0.0020907646543,0.000758953364548,-0.00251797462942,0.335387028403,-0.000768321579488 +8.54,51.0007310716,1.28331861928e-007,10.002392436,19.3440091105,0.00191303785114,-0.000767430057732,-0.00145444256459,0.332048999889,-0.00138334353062 +8.55,51.0007328111,1.287371702e-007,10.0024005162,19.3594653477,0.00377722136319,-0.000848607086411,-0.000971313691729,0.330905894716,-0.00020055800935 +8.56,51.0007345519,1.29211337528e-007,10.0024083805,19.374718352,0.00287977314408,-0.000724256171636,-0.00141846163252,0.326966559242,-0.000208917078598 +8.57,51.0007362942,1.29623616402e-007,10.0024169617,19.390102626,0.00290834830252,-0.000991984434004,-0.0010310004136,0.326637158462,-0.0030967488383 +8.58,51.0007380379,1.29986566963e-007,10.0024220833,19.4070396393,0.00218723624566,-3.23350000006e-005,0.000954344621455,0.325440346231,-0.00168589117957 +8.59,51.0007397831,1.30333319096e-007,10.0024248039,19.4224202877,0.00268093293853,-0.000511778364388,-0.00173828992078,0.322560980776,0.000349271738479 +8.6,51.0007415296,1.30611231978e-007,10.0024295231,19.4378394168,0.0012207788502,-0.000432075259901,-0.000494672938164,0.319932138657,-0.0002874498423 +8.61,51.0007432776,1.3078032526e-007,10.0024377109,19.4534477655,0.00115317812073,-0.00120546734947,-0.00261044024451,0.317557498266,0.00204072229688 +8.62,51.0007450269,1.3089221042e-007,10.0024432924,19.4677259503,0.000417614909537,8.91555344443e-005,-0.00272067036255,0.315268176865,-0.000488870440923 +8.63,51.0007467775,1.31016846029e-007,10.0024436236,19.483006925,0.00133218581478,-0.000155382730226,-0.00400493116202,0.317245788503,-0.00126850825659 +8.64,51.0007485296,1.31221742596e-007,10.0024460421,19.5002015499,0.00154442508058,-0.000328329133694,-0.00104636910133,0.314692133079,-0.000706596796559 +8.65,51.0007502831,1.31496626514e-007,10.002446337,19.5152088123,0.00231476130733,0.000269356428985,-0.000901126973849,0.312410770376,-0.00200070314224 +8.66,51.0007520379,1.31783738472e-007,10.0024424699,19.5289380547,0.00171609846728,0.000504068319061,-0.00177862294367,0.312030739351,-0.00187755456211 +8.67,51.0007537941,1.32037994719e-007,10.0024332168,19.5457397633,0.00185348896315,0.00134654630292,-0.000278573306281,0.309262139534,-0.000892430192821 +8.68,51.0007555518,1.32358158939e-007,10.0024209579,19.561702802,0.0026414020746,0.00110522648273,-0.00218841098256,0.309048379375,-0.00334918185936 +8.69,51.0007573109,1.32892597627e-007,10.0024077236,19.5771804193,0.00486175858335,0.00154163166166,-0.000511087667821,0.306389033567,-0.00274075300846 +8.7,51.0007590713,1.3343072197e-007,10.0023931781,19.5929668367,0.00269314597595,0.00136747825473,-0.00153981582865,0.30363389255,-0.00224857194517 +8.71,51.0007608332,1.33728459506e-007,10.0023849402,19.6082628721,0.00148688901759,0.000280096982982,-0.00306631059034,0.297543055985,-0.00225150521123 +8.72,51.0007625965,1.3393096385e-007,10.0023806552,19.6250456122,0.00135613582495,0.000576909458449,-0.00167247663562,0.298054628462,-0.000144786444145 +8.73,51.0007643613,1.34285205448e-007,10.002384803,19.6401589354,0.00361717778948,-0.00140647127888,-0.00146441008025,0.296879156518,0.0026055114295 +8.74,51.0007661275,1.34761461999e-007,10.0023896488,19.6572862121,0.00306914347176,0.000437312193229,0.000968238634328,0.294430914093,0.00201386798834 +8.75,51.0007678951,1.35037927676e-007,10.0023844171,19.6725519405,0.000812248349267,0.000609015110854,0.000996743210375,0.292388081136,0.00247255122129 +8.76,51.0007696642,1.35194927254e-007,10.0023835547,19.688695142,0.00139191981736,-0.00043652898538,-5.5204830121e-005,0.291283502241,0.00305306142074 +8.77,51.0007714347,1.35373067692e-007,10.0023842879,19.7042172177,0.00110905168262,0.000289885206535,-0.000284560459719,0.289947251204,0.00189387143985 +8.78,51.0007732065,1.35554686672e-007,10.0023856257,19.7187758479,0.00144075609342,-0.000557441623898,-0.00334688765605,0.286958773884,0.00233075044162 +8.79,51.0007749799,1.35738410594e-007,10.0023902473,19.7369802669,0.00113860356395,-0.000366880000484,-0.00100330294966,0.285683650518,4.19219878556e-005 +8.8,51.0007767546,1.35888847923e-007,10.002395819,19.7505396535,0.000973434747214,-0.000747462943484,0.000353207900556,0.282507376866,-0.000780652600324 +8.81,51.0007785306,1.36121165685e-007,10.002395717,19.765209807,0.00228814928897,0.000767872236472,0.00202076297417,0.283045746725,-0.00262479332754 +8.82,51.000780308,1.36386860148e-007,10.0023872308,19.7802010563,0.00144202092039,0.0009293629,0.00138438247065,0.279577744019,-0.00215917958833 +8.83,51.0007820867,1.36627001993e-007,10.0023737503,19.7955107984,0.0019294076948,0.0017667428788,0.00148681079906,0.278071558989,-0.00152687929 +8.84,51.0007838668,1.36870979619e-007,10.0023603201,19.8127294311,0.0014958725795,0.000919301141163,0.000987098589376,0.275122081636,0.000466340317746 +8.85,51.0007856485,1.37102163711e-007,10.0023498089,19.8275903006,0.0017497950171,0.00118292848908,0.00140664719096,0.274371960036,-0.000461035647102 +8.86,51.0007874315,1.37370746994e-007,10.0023334659,19.8437517807,0.00202093166114,0.00208567092258,0.00156529493322,0.272762685035,0.0013747943296 +8.87,51.0007892159,1.37750213656e-007,10.0023195855,19.8599150559,0.00330652206964,0.000690407106634,-8.7933648335e-005,0.270517714754,0.000247861315294 +8.88,51.0007910018,1.380215792e-007,10.0023134894,19.8761569705,0.000503265425877,0.000528810256921,0.00149988873395,0.267253538493,-0.000927947117828 +8.89,51.0007927892,1.3835621657e-007,10.002314393,19.8915244322,0.00419481512727,-0.000709532814956,0.00170775762381,0.263916838303,-0.00203831036031 +8.9,51.000794578,1.38858157518e-007,10.0023267947,19.9088393081,0.00285209348164,-0.00177079423881,-4.2487541619e-005,0.261917056255,0.000574611032955 +8.91,51.0007963682,1.39165424493e-007,10.0023319534,19.9227320325,0.00146172514752,0.000739047162962,-0.000232420943955,0.259861854167,0.00111005824053 +8.92,51.0007981597,1.3932418708e-007,10.0023221253,19.9377261914,0.000767193141845,0.00122658063476,0.0011935940326,0.258368713851,-0.000178152588299 +8.93,51.0007999526,1.39406419587e-007,10.0023162111,19.9530877632,0.000387295040252,-4.37473327999e-005,0.00209019378302,0.257299171751,0.00085907644595 +8.94,51.0008017468,1.39526604006e-007,10.0023083998,19.9680242304,0.00130001195817,0.0016060081653,0.000563261538667,0.253773671622,-0.000601780186657 +8.95,51.0008035425,1.39733800979e-007,10.0022923529,19.9850065224,0.00160889166596,0.00160337041234,-0.000920332804299,0.251291684784,0.000260073906044 +8.96,51.0008053396,1.39848399994e-007,10.0022843361,20,0,0,0,0.25,0 +8.97,51.0008071374,1.39965263188e-007,10.0022848936,20.0010324975,0.00164067907267,-0.000111501042156,0.000422305199678,0.248350472575,0.00043317899825 +8.98,51.0008089352,1.40227851967e-007,10.0022777113,19.9988843877,0.00204588714516,0.00154795989136,-0.00116179329223,0.243331277642,0.00203508474839 +8.99,51.0008107328,1.4045215095e-007,10.0022591081,19.9976544022,0.00110311652696,0.00217267867389,0.000655626179831,0.242507678268,-0.000725097901458 +9,51.0008125304,1.40621939126e-007,10.0022424455,19.9984194506,0.00128059274355,0.00115983129341,-0.000440821195329,0.240788874164,-5.23066603417e-005 +9.01,51.0008143281,1.40697453872e-007,10.0022198721,19.9990603424,-0.00022041763551,0.00335485075554,0.00114419537919,0.238683042596,0.00126783306814 +9.02,51.0008161258,1.40744787827e-007,10.0021954755,20.0003045933,0.000884953749669,0.00152447065249,8.86800259737e-005,0.236499507345,0.00303131260825 +9.03,51.0008179236,1.40849518537e-007,10.0021934693,19.999307038,0.000585393256893,-0.00112322885546,0.0014256271536,0.23477752806,0.00100873105404 +9.04,51.0008197213,1.4097232857e-007,10.0022031162,20.0006709193,0.00113877489749,-0.000806143689325,0.00100998807182,0.232879814923,0.00155392491292 +9.05,51.0008215192,1.41095924156e-007,10.0022100745,20.0002146827,0.000596421849421,-0.000585512995938,0.00110410288015,0.230185125391,0.00130578557148 +9.06,51.000823317,1.41241099286e-007,10.0022124683,20.0018668212,0.00144173668088,0.000106740977212,0.00254211016446,0.22921832739,0.000212251237438 +9.07,51.0008251149,1.41446942862e-007,10.0022067762,19.9992124934,0.0014481648406,0.00103167900433,0.00158936393342,0.226197496649,-0.00206706518458 +9.08,51.0008269126,1.41664243404e-007,10.0022087603,19.9994008514,0.00160258444579,-0.00142849869647,-0.000299334322632,0.225437164266,-0.000398775132351 +9.09,51.0008287103,1.41912233353e-007,10.0022300071,19.9993991155,0.00187902274396,-0.00282086804359,0.00164862900296,0.223284231461,-0.00330407053683 +9.1,51.0008305081,1.42117972456e-007,10.002251124,20.0004790593,0.00100941173666,-0.00140251069902,0.00135454750115,0.22364792005,-0.00117569699298 +9.11,51.0008323059,1.42348818422e-007,10.0022756393,20.0015041397,0.00223150552942,-0.00350053664972,-0.000298659207679,0.22320284814,-0.00192411792665 +9.12,51.0008341038,1.42550884809e-007,10.0023042483,20.0001487806,0.000605366351539,-0.00222127316879,-0.000627831065022,0.219361274508,-0.000642681656015 +9.13,51.0008359015,1.42631934787e-007,10.0023208984,19.9977981568,0.000532519046298,-0.00110874591448,-0.00212233174294,0.21833298305,0.000892023030338 +9.14,51.000837699,1.42631634104e-007,10.0023399511,19.9975974367,-0.000536740403114,-0.00270178367487,-0.000970900482503,0.217213925223,0.00117166979841 +9.15,51.0008394966,1.42475530089e-007,10.0023576556,19.9975494776,-0.00165485135747,-0.000839132296363,-0.00148721801444,0.2140100222,0.00066069481248 +9.16,51.0008412943,1.42331696688e-007,10.002378887,20.0010535462,-0.000364469503552,-0.00340713884921,-0.000359646995792,0.213640163564,-0.000409226692849 +9.17,51.0008430922,1.42221349655e-007,10.0024075019,20.0003644328,-0.00118472594318,-0.00231583102714,0.00065327854316,0.210052819208,0.000569450117658 +9.18,51.0008448899,1.42223050339e-007,10.0024284406,20.0000252551,0.00120860232029,-0.0018719251769,0.00270850609598,0.207860387279,-0.00120221233335 +9.19,51.0008466876,1.42375924848e-007,10.0024489931,19.9982396348,0.000937649121757,-0.00223856361896,0.00325083624638,0.204698429475,-0.00118758705926 +9.2,51.0008484854,1.42375187078e-007,10.0024818933,20.0006725353,-0.000948006864529,-0.00434148356299,7.78056579626e-005,0.205347273077,0.000403933558234 +9.21,51.0008502831,1.42339181693e-007,10.0025216483,19.9980171843,0.000442516394145,-0.00360951872,3.14897313895e-005,0.202265195005,-0.000189683767705 +9.22,51.0008520807,1.42275332583e-007,10.0025706098,19.9978278135,-0.00133891321298,-0.00618277459623,-0.00053560689033,0.20111888121,0.00233423634557 +9.23,51.0008538783,1.42069115818e-007,10.002633865,19.9990361697,-0.00155622582213,-0.00646827634527,-0.00157725421203,0.198307066018,0.0012580057 +9.24,51.0008556761,1.41905177158e-007,10.0026940548,19.9999845708,-0.000745358145758,-0.00556968109084,-0.0003238963998,0.198502619198,0.000425657656821 +9.25,51.0008574738,1.41764396536e-007,10.0027451349,20.00000638,-0.00123110309928,-0.00464633954465,0.000918104825302,0.197128999057,0.000892437961359 +9.26,51.0008592716,1.41549441705e-007,10.0027958491,19.9999908632,-0.00178671190903,-0.00549650103624,0.00055421818729,0.194415418185,0.000724405124212 +9.27,51.0008610694,1.41387810616e-007,10.0028463188,19.9999621959,-0.000482475138998,-0.00459742139589,-0.000869796437532,0.195142270275,-0.0019052665175 +9.28,51.0008628672,1.41258673736e-007,10.0028965099,20.0000866273,-0.00133051589979,-0.00544080619191,-0.000345747887648,0.192824853934,-0.000673686560383 +9.29,51.000864665,1.41101147572e-007,10.0029372341,20.00132501,-0.000881040685416,-0.00270403722243,-0.00142979482853,0.18940360202,-0.00143201538856 +9.3,51.0008664629,1.40968724747e-007,10.0029672667,20.0021849814,-0.00097808258476,-0.00330248210237,-0.0016442539024,0.189201220762,-0.00290907805827 +9.31,51.0008682608,1.40812316762e-007,10.0029957544,19.9991847522,-0.0012177753757,-0.00239505509375,-0.00129586427595,0.186760129987,-0.000324382381389 +9.32,51.0008700586,1.40640956574e-007,10.0030307347,20.0012330986,-0.00118800088162,-0.00460100167769,-0.00143121211349,0.185929863778,-0.000489040368475 +9.33,51.0008718565,1.40573431245e-007,10.0030830728,20.0024009761,0.000239992858062,-0.0058666215193,-0.000860982488945,0.187356421534,0.00138060443231 +9.34,51.0008736544,1.40630435561e-007,10.0031406391,20.0001694268,0.000560307492161,-0.00564663300441,-0.000280892655737,0.182913349561,0.00214997527197 +9.35,51.0008754522,1.40692497625e-007,10.0031998442,20.0004254681,0.000311000058046,-0.00619439141079,-0.00233145402097,0.180626702522,0.00113515583899 +9.36,51.00087725,1.40661860523e-007,10.0032580118,19.9999272995,-0.000741123295872,-0.00543913588204,-0.00236446388528,0.177013404127,0.00110393187315 +9.37,51.0008790477,1.40647174129e-007,10.0033086895,19.9988892771,0.00053493669569,-0.00469639428929,-0.00330907914914,0.175598132352,-0.000174079548181 +9.38,51.0008808454,1.40729785752e-007,10.0033599527,19.9984989637,0.000624871995008,-0.00555624668335,-0.00226370957382,0.172489820049,-0.000364800605653 +9.39,51.0008826431,1.40900745053e-007,10.0034167398,19.9994664664,0.00177527542356,-0.00580117721534,-0.0012145001996,0.171864253682,6.50600065615e-005 +9.4,51.0008844408,1.41026125414e-007,10.0034775274,19.9999225651,-1.50240301249e-005,-0.00635634512489,1.97793309807e-005,0.170201037101,0.000486159521281 +9.41,51.0008862386,1.40961197208e-007,10.0035353768,19.9998396095,-0.000896521886359,-0.00521353174751,-0.00105937965079,0.167635991874,0.00058640568303 +9.42,51.0008880364,1.40691933802e-007,10.0036013062,19.9999383104,-0.00288374505932,-0.00797234586357,-0.00199969846103,0.167677531795,0.000420204692635 +9.43,51.0008898341,1.40270722747e-007,10.0036748017,19.9994859484,-0.00302975876869,-0.00672676078871,-0.00373084150519,0.165895390567,0.000127421390486 +9.44,51.0008916319,1.39998404986e-007,10.0037498258,20.0001442045,-0.00079338893899,-0.00827806159488,-0.00165598806519,0.163329791644,-0.000119722871626 +9.45,51.0008934297,1.39822472029e-007,10.0038423609,20.00024867,-0.00167658452787,-0.0102289550738,-0.00121101310033,0.162906953341,-0.00170624868534 +9.46,51.0008952276,1.39596731744e-007,10.0039341463,20.0024089142,-0.00149264826119,-0.00812812942399,-0.00121114162465,0.15952078254,-3.73800823136e-006 +9.47,51.0008970255,1.39416919862e-007,10.0040133281,20.0000444865,-0.00103178236888,-0.00770821597138,0.000871280080609,0.157052179436,-0.00177772805855 +9.48,51.0008988233,1.39298515451e-007,10.0040956699,20.0011614489,-0.000630531089906,-0.00876014882027,0.00137466448086,0.155578179419,-0.00127721066786 +9.49,51.0009006212,1.39204224715e-007,10.0041746426,20.0015398982,-0.000693243522587,-0.00703439132256,8.38771916351e-005,0.151165783825,-0.00283199944024 +9.5,51.0009024192,1.39143863648e-007,10.0042592328,20.0026822625,-0.000154182730769,-0.00988364274477,-0.000346535575602,0.149104992295,-0.00461535767809 +9.51,51.0009042172,1.39295223922e-007,10.0043563318,20.0026956223,0.0022791726943,-0.0095361614959,-0.000710962779216,0.149091432023,-0.00441126648235 +9.52,51.0009060151,1.39652554517e-007,10.0044534481,20.0001099079,0.00273749312787,-0.00988710398306,-0.000893458324077,0.147767178952,-0.00126593243524 +9.53,51.0009078129,1.4000009385e-007,10.0045399994,20.0000792278,0.00214171021332,-0.00742315775094,-0.00167755036442,0.146184862785,-0.00459379201761 +9.54,51.0009096107,1.40185943537e-007,10.004630464,20.0007249042,0.000467486217638,-0.0106697685621,-6.31410683141e-005,0.145149032927,-0.00153244853739 +9.55,51.0009114085,1.40160788133e-007,10.0047307051,20.0009641115,-0.000820650022768,-0.00937843681639,0.000383096032765,0.141819478567,-0.00218423397445 +9.56,51.0009132064,1.401178083e-007,10.0048290943,20.0013678717,0.000217244001859,-0.0102994173392,-0.000387239796662,0.143617420028,-0.00047637455646 +9.57,51.0009150044,1.40126975361e-007,10.0049322158,20.0029928313,-8.85450419605e-005,-0.0103248828902,0.000976732955376,0.143078158236,-0.00108786907772 +9.58,51.0009168023,1.40130801516e-007,10.0050366313,20.0008832086,0.000142261499832,-0.0105582162484,-0.000406022437814,0.139224911635,-0.00105649012888 +9.59,51.0009186001,1.40177357188e-007,10.0051478091,19.9996329869,0.000511346632762,-0.0116773354417,-0.00256200254228,0.137434317894,-0.00157878689768 +9.6,51.0009203979,1.40257380452e-007,10.0052664175,19.9998449196,0.000612122370772,-0.0120443434945,-0.00039606499222,0.134657668954,-0.000785624580178 +9.61,51.0009221957,1.40307327363e-007,10.0053792817,19.9997136406,8.90962882527e-005,-0.0105284959618,0.000166284258282,0.133143409755,-0.00281216943335 +9.62,51.0009239934,1.40237815138e-007,10.0054835918,19.9990224925,-0.001064997788,-0.0103335272311,0.000331349023818,0.13298621113,-0.00102379302718 +9.63,51.000925791,1.40042383513e-007,10.0055835502,19.9982710701,-0.00167872117852,-0.009658147977,0.000307201643324,0.128873237482,-0.00148684984705 +9.64,51.0009275887,1.39823521982e-007,10.0056837246,19.9992018002,-0.00139393667623,-0.0103767262498,-0.00152066821063,0.12659253249,0.00199668254569 +9.65,51.0009293864,1.39707264153e-007,10.0057889672,19.9983923864,-0.000238239253653,-0.0106718027876,-0.00202317267348,0.124491101885,0.00112112599103 +9.66,51.000931184,1.39738664623e-007,10.005901034,19.9993505766,0.000679079131879,-0.0117415573952,-0.00265759891925,0.123495837699,-0.000451734850593 +9.67,51.0009329817,1.39825423018e-007,10.0060113249,19.9978848525,0.000538945945398,-0.0103166141253,-0.00137143830911,0.121869355806,-0.000550964035898 +9.68,51.0009347792,1.39867536627e-007,10.0061224902,19.9972580548,5.22986271285e-005,-0.0119164516186,-0.0013935182584,0.119696952212,-3.08113504509e-005 +9.69,51.0009365768,1.39999823748e-007,10.0062358812,19.9983155339,0.00180491662329,-0.0107617509909,-0.000715457114954,0.118549152149,-0.00134540782972 +9.7,51.0009383744,1.40094357996e-007,10.0063500644,19.9976765812,-0.000477724309713,-0.0120748895295,-0.000404872831619,0.118304297199,-0.000652718560925 +9.71,51.000940172,1.40028885166e-007,10.0064772304,19.9978022234,-0.000441466699524,-0.0133583196027,0.000269155112209,0.114396381336,-0.00319853081297 +9.72,51.0009419696,1.4004767909e-007,10.0066153903,19.9984996005,0.000705319717351,-0.0142736566071,0.000630353282464,0.112738513687,-0.00336596901056 +9.73,51.0009437672,1.40160331332e-007,10.0067599387,19.9978030761,0.000876235859846,-0.0146360232736,0.000645327479671,0.113122690499,-0.00221908990841 +9.74,51.0009455648,1.4039146819e-007,10.0069080074,19.9980391042,0.00236875742407,-0.0149777136911,0.000680741518165,0.110309016435,-0.00352209494229 +9.75,51.0009473624,1.4080257511e-007,10.0070610148,19.9977067508,0.00340288438474,-0.0156237667153,0.000696123481106,0.107920713585,-0.000837209015013 +9.76,51.00094916,1.41170776279e-007,10.0072107984,19.9976974667,0.00176639176267,-0.0143329443916,0.000231017343741,0.105942114917,-0.00289291664692 +9.77,51.0009509576,1.41367512903e-007,10.0073570721,19.9987331738,0.000995646994908,-0.0149217999687,-0.000444802323905,0.103495066282,-0.00229564464438 +9.78,51.0009527552,1.41610787281e-007,10.0075070211,19.9965267727,0.00241974771279,-0.0150680116574,0.00083478391764,0.100888405442,-0.00295808984764 +9.79,51.0009545526,1.41887395672e-007,10.0076560382,19.9960917276,0.00146363211583,-0.0147353982208,0.00246582394176,0.100216177571,-0.00147534303072 +9.8,51.0009563502,1.42211882708e-007,10.00780817,19.9999971335,0.00309192869992,-0.0156909595766,0.000911120954676,0.0988826891546,-0.00130674146902 +9.81,51.0009581479,1.42748486738e-007,10.0079613709,19.9984329646,0.00444159939261,-0.0149492191351,0.000194683552063,0.0965360466935,-0.000627065226183 +9.82,51.0009599455,1.43307254292e-007,10.0081142624,19.9977458402,0.00340308810878,-0.0156290911446,-0.00114436584061,0.0963263673865,-0.00187288664054 +9.83,51.0009617432,1.43809761283e-007,10.0082680897,19.9993786159,0.00365174197636,-0.0151363592418,-0.00185601308014,0.0952021073722,-0.00180767506627 +9.84,51.0009635409,1.44244751382e-007,10.0084288323,19.9988458838,0.00245520019393,-0.0170121578985,-0.00138852824544,0.0924695870775,-0.000276279192442 +9.85,51.0009653385,1.44407968457e-007,10.0085943683,19.9983481944,-0.000163752129845,-0.0160950453306,-0.000272152553474,0.088723369565,0.0012227056718 +9.86,51.000967136,1.44468922743e-007,10.0087568293,19.9962113338,0.0010195055272,-0.0163971511803,0.00090548762951,0.0880059811013,0.000602844023148 +9.87,51.0009689335,1.44793950083e-007,10.0089295965,19.9968853782,0.00354363951298,-0.0181563043556,0.00234712823081,0.0878556161991,-0.00160779577009 +9.88,51.0009707311,1.45205872568e-007,10.00911271,19.9985679041,0.00223944936964,-0.0184663919446,0.000932029649397,0.0850320072853,-0.00216404721641 +9.89,51.0009725289,1.45631476665e-007,10.009296513,20.0019466162,0.00373571899441,-0.0182942113991,-0.000544745509202,0.0810782927036,-0.000412450248545 +9.9,51.0009743267,1.46023573574e-007,10.0094769986,19.9996549422,0.00176903297135,-0.0178029024594,-0.000346668969428,0.0800106916492,-0.00244535608139 +9.91,51.0009761244,1.46454567555e-007,10.0096533709,19.9982282493,0.00428180492492,-0.0174715566821,-0.000257529778777,0.0809482980538,-0.00329436083539 +9.92,51.0009779221,1.469010773e-007,10.0098249575,19.9988370294,0.00198686270494,-0.0168457598064,-0.00257172745889,0.0785707250367,-0.00106070669669 +9.93,51.0009797197,1.47147369766e-007,10.0099950837,19.9982990233,0.0014709017949,-0.0171794906336,-0.00467010429988,0.0753825324505,0.000979587716006 +9.94,51.0009815173,1.47249907302e-007,10.0101640628,19.9975873081,-3.1350474884e-005,-0.0166163217291,-0.00166811636174,0.0743210190573,-0.000490710797718 +9.95,51.0009833148,1.47111042844e-007,10.010330064,19.9957535813,-0.00191820386393,-0.0165839080699,-0.00128400848571,0.0726910557543,-0.00114685000082 +9.96,51.0009851123,1.46964684929e-007,10.010499691,19.9982202823,-0.000136553064293,-0.0173414960433,-0.00100308509637,0.071072809178,-0.000769444293896 +9.97,51.0009869099,1.46984746898e-007,10.0106783152,19.9982138672,0.000418208258009,-0.0183833526331,0.00046114356174,0.0682793873275,-0.00100877675042 +9.98,51.0009887075,1.46954980345e-007,10.0108607188,19.9976079469,-0.000836108598234,-0.0180973566628,-0.00158826783188,0.0661176004675,-0.00125960713965 +9.99,51.0009905051,1.46847938234e-007,10.0110382416,19.998639433,-0.000666683309016,-0.0174072116377,8.08839327606e-005,0.0650893742714,-0.0037995849134 +10,51.0009923028,1.46907574581e-007,10.0112183551,19.9988188229,0.00150393334608,-0.0186154791912,0.000501923468789,0.0635413042025,-0.00386243358356 +10.01,51.0009941005,1.47140034707e-007,10.0114019081,19.9992087584,0.00175963428213,-0.018095133721,-0.00331016350752,0.060975500342,-0.00285113902025 +10.02,51.0009958981,1.4746997525e-007,10.0115892522,19.9977986716,0.00287248585389,-0.0193736879953,-0.0019476047364,0.0597728780707,-0.00223964777515 +10.03,51.0009976958,1.47862436568e-007,10.0117720108,19.9993966247,0.00263737933837,-0.0171780336158,0.00209620875123,0.0575521045758,-0.00179859621567 +10.04,51.0009994935,1.48224521434e-007,10.0119519306,19.9997423886,0.00244602284777,-0.0188059250695,0.00115635279016,0.0554846637444,-0.00329373610161 +10.05,51.0010012913,1.48603090199e-007,10.012149782,20.0007932517,0.002868800807,-0.0207643492101,3.70414756732e-005,0.0555708660993,-0.00084989672947 +10.06,51.0010030892,1.48918027305e-007,10.0123534967,20.0018833904,0.00155268159055,-0.0199785849509,0.00137743278194,0.0530750521157,-0.000771924769371 +10.07,51.0010048871,1.49183037552e-007,10.0125521779,20.0004837896,0.00216786470732,-0.0197576676965,0.000247401804988,0.0506683996777,-0.00198974033661 +10.08,51.0010066849,1.49485688361e-007,10.0127442973,20.0001595548,0.0020811268677,-0.0186662097698,0.000581627986346,0.0487097361705,-0.00173586864173 +10.09,51.0010084826,1.49782762462e-007,10.012927962,19.9977377289,0.00208957173225,-0.0180667285295,0.000701659977567,0.0474854801558,-0.00212872535921 +10.1,51.0010102802,1.50101792405e-007,10.0131108251,19.9995481544,0.00238937031392,-0.0185058871597,-8.25852935644e-005,0.045828934911,-0.00164826232224 +10.11,51.0010120779,1.50468785926e-007,10.0132992222,19.9983360001,0.00276294433395,-0.0191735408465,-0.0011014938604,0.0436699317078,-0.00081695812826 +10.12,51.0010138755,1.50702615911e-007,10.0134967764,19.998261454,0.000519853750718,-0.020337285708,-0.000254910046515,0.0423006852697,-0.00158769293717 +10.13,51.0010156731,1.50694119517e-007,10.0137045703,19.9983102122,-0.000639136728245,-0.0212214941006,0.0015189744854,0.0406862636742,-0.00114642283337 +10.14,51.0010174708,1.5069028199e-007,10.0139104442,19.9997597837,0.000585260690656,-0.0199532976714,0.000898058884683,0.0382926280672,-0.000459443268761 +10.15,51.0010192686,1.50754504983e-007,10.0141104542,20.0007556924,0.000316381990472,-0.0200486980594,-0.00179684564107,0.0366842446039,-0.000965258450944 +10.16,51.0010210665,1.5077026979e-007,10.0143087885,20.0001050092,-9.50559197187e-005,-0.0196181521176,-0.000416036503938,0.0342599951148,-0.000712593512078 +10.17,51.0010228643,1.50907652312e-007,10.0145087036,20.0003417605,0.00202380333085,-0.0203648813766,0.00161961203806,0.0329452222174,-0.00204773068894 +10.18,51.0010246621,1.50935643999e-007,10.014705864,20.0001724032,-0.00163082102004,-0.0190671991575,0.000925965128792,0.0301580265772,-0.000793110702527 +10.19,51.0010264599,1.50876524304e-007,10.0149003561,20.0018621621,0.000800824911707,-0.0198312186229,0.00149531808744,0.0277870520409,0.000434960582503 +10.2,51.0010282578,1.50960921268e-007,10.0151050087,20.0013980851,0.000384044967224,-0.0210993007887,0.000714195968938,0.0285304938963,-0.00112972198071 +10.21,51.0010300557,1.50797290318e-007,10.0153170505,20.0013397284,-0.00268130022414,-0.0213090628657,0.00195112657851,0.0284343728789,-0.00267302634102 +10.22,51.0010318537,1.50589556577e-007,10.0155376257,20.0018081701,-0.000235124993986,-0.0228059624378,0.000730516546169,0.0240793366796,9.504921139e-006 +10.23,51.0010336515,1.505739593e-007,10.0157643413,19.9987849243,1.61509822341e-005,-0.0225371655434,0.00134387775467,0.0248410564125,0.00130278282008 +10.24,51.0010354492,1.50575109717e-007,10.0159870271,20,0,-0.022,0,0.022,0 +10.25,51.001037247,1.50744256296e-007,10.0162154025,20.0011934489,0.00237469018291,-0.0236750835187,-0.00306480456839,0.0236236031769,-0.000944435959596 +10.26,51.0010390449,1.50977960495e-007,10.0164530496,20.0010319996,0.000906340168603,-0.0238543232455,-0.00171653158734,0.0236789627837,-0.000328846973944 +10.27,51.0010408428,1.51106762587e-007,10.0166874178,20.0011419577,0.000901943788758,-0.0230193269094,-0.00114357817096,0.0224031201814,0.000179472390518 +10.28,51.0010426407,1.51183679809e-007,10.0169138885,20.0016583251,0.000177915812167,-0.0222748175246,0.000115022825857,0.0244617801099,0.000539781742486 +10.29,51.0010444385,1.51280919655e-007,10.0171316348,19.9995313089,0.00118725795352,-0.0212744411765,-0.0021586365767,0.0274672810843,0.00277255099871 +10.3,51.0010462363,1.51354180601e-007,10.0173447708,20.0000321624,-0.000158729773931,-0.0213527562111,-0.000202274736479,0.0274959932623,0.0025591916172 +10.31,51.001048034,1.51281370085e-007,10.0175590624,19.9990933602,-0.000863474624482,-0.0215055562223,-0.000333111718243,0.0271393360136,0.00287180282207 +10.32,51.0010498318,1.51250679124e-007,10.0177743611,20.000997047,0.000432596798525,-0.0215541805302,0.000609254241785,0.0263385125299,0.00225763518705 +10.33,51.0010516298,1.51230289585e-007,10.0179837371,20.0031923528,-0.000718850420583,-0.0203210298783,0.0002311388241,0.0285845186379,0.00338607301882 +10.34,51.0010534279,1.51249327485e-007,10.018196443,20.0040581383,0.000986128029922,-0.0222201534627,0.00142353659671,0.0270183169299,0.00229089615563 +10.35,51.001055226,1.51393211177e-007,10.0184229537,20.0031256762,0.00103388956623,-0.0230819710457,0.000528795333262,0.0263095990725,0.00197935694175 +10.36,51.001057024,1.51518057519e-007,10.0186492892,20.0019073789,0.000718858055587,-0.0221851364667,0.000830606038013,0.0294244834368,0.00323090507002 +10.37,51.0010588219,1.51651392592e-007,10.0188652034,20.0006102218,0.00115306478852,-0.0209977068495,-0.00169408915017,0.029795416791,0.00180213175475 +10.38,51.0010606197,1.51843576191e-007,10.0190737622,20.0013733773,0.00154504643245,-0.0207140416768,-0.000742943935901,0.0309960117105,0.00368404559032 +10.39,51.0010624176,1.52093592584e-007,10.0192854926,20.0010696544,0.00196499300219,-0.0216320413937,0.00141891900933,0.0303647798907,0.00231998617162 +10.4,51.0010642155,1.52347462521e-007,10.0195098087,20.0007181564,0.00159914712783,-0.0232311805782,0.00108930069104,0.0304812735272,0.000307419611695 +10.41,51.0010660133,1.52478506752e-007,10.019746087,19.9996289736,0.000240613800566,-0.0240244806863,-0.000827210292049,0.0331182591861,0.00148823841978 +10.42,51.001067811,1.52679334431e-007,10.0199867541,20.0003027511,0.00257885324897,-0.0241089419359,0.00268086333556,0.0316301838369,0.000962859119092 +10.43,51.0010696087,1.53005826963e-007,10.0202275434,19.9980407293,0.00200485214767,-0.0240489193415,0.00377928859702,0.0329177788601,0.00118885025556 +10.44,51.0010714064,1.53205758236e-007,10.0204640285,19.999304594,0.000802029893316,-0.0232481003631,0.00103978945375,0.0342592585176,-0.00127784340228 +10.45,51.0010732041,1.53218277478e-007,10.0206965677,19.9986190936,-0.000626269299296,-0.0232597320668,-0.000731096715026,0.0338465926774,-0.00171144044705 +10.46,51.0010750017,1.53101582986e-007,10.0209222105,19.9982535022,-0.00101203190346,-0.0218688284203,0.00169371126604,0.0343226627156,-0.0023908161061 +10.47,51.0010767994,1.53081331726e-007,10.021154283,19.9996700925,0.000727719722656,-0.0245456766899,0.000793365899747,0.0334321232971,-0.00160788748704 +10.48,51.0010785972,1.53106862204e-007,10.0214063307,20.0012750802,-0.000369291389253,-0.0258638710878,0.00139671655906,0.0351336670069,-0.00138956949304 +10.49,51.0010803951,1.52939708601e-007,10.0216631239,20.0006942261,-0.00197741676064,-0.0254947677241,0.000279688946117,0.0361621304608,-0.00241468085031 +10.5,51.001082193,1.52688300325e-007,10.0219277153,20.0016670214,-0.00155216215291,-0.0274235026311,-6.78508074097e-005,0.0363548572103,-0.000141337036547 +10.51,51.0010839909,1.52401339834e-007,10.0221987311,20.0006921342,-0.00247654237261,-0.0267796628634,-0.00181559492206,0.0364688329035,-0.00298524463924 +10.52,51.0010857887,1.52273662464e-007,10.0224718876,20.0014671584,0.000684050332853,-0.0278516393315,0.000418365230818,0.0364570851969,-6.02876347124e-005 +10.53,51.0010875866,1.52512048007e-007,10.0227494132,20.0008165631,0.00266269900247,-0.0276534756043,0.00264276052035,0.0371620240904,-0.00149582684076 +10.54,51.0010893845,1.52863460418e-007,10.0230274444,20.0014410452,0.00227086033673,-0.0279527672067,0.00151721773544,0.0370787858287,0.00129115184209 +10.55,51.0010911824,1.53053902435e-007,10.0233117065,20.0007236436,0.000402798692958,-0.0288996554309,0.00159772520673,0.037913937136,-0.000186527336003 +10.56,51.0010929802,1.53136295789e-007,10.0236022239,20.000481277,0.000753940387039,-0.0292038256378,0.00191598988862,0.0383229673462,-0.00110880076658 +10.57,51.001094778,1.53297353044e-007,10.0238985506,19.9998809666,0.00150717903352,-0.0300615156487,0.00049255784,0.0367178223083,-0.000239651410811 +10.58,51.0010965757,1.53591859971e-007,10.0242035995,19.9990837769,0.0026274705094,-0.030948260546,0.00110554045703,0.0396079129089,-0.00116166345439 +10.59,51.0010983734,1.53930612142e-007,10.0245140633,19.9990739897,0.00212834789887,-0.0311444972276,0.00250357520074,0.0405831533861,-0.000602441741203 +10.6,51.0011001711,1.54153844181e-007,10.0248284112,19.9995229345,0.00100565712872,-0.0317250835514,-2.67134814765e-005,0.0395312360046,0.000315151242955 +10.61,51.0011019688,1.54283138976e-007,10.0251403291,19.998317281,0.000809541621022,-0.0306584942345,0.000852695225588,0.0417809323851,0.00274057972896 +10.62,51.0011037664,1.54341552693e-007,10.0254469519,19.9981649615,1.05416987224e-005,-0.0306660635335,0.00098732299471,0.0411883274375,0.00217281686105 +10.63,51.0011055641,1.543375804e-007,10.0257583536,19.9993780568,-6.63096148826e-005,-0.0316142858668,0.00141540238294,0.04326679798,0.00378100148332 +10.64,51.0011073618,1.54258698855e-007,10.0260710734,19.9995759377,-0.00104112601414,-0.0309296646523,-0.000460129527368,0.04343178363,0.000808663104974 +10.65,51.0011091596,1.54168828074e-007,10.0263868739,20.0009629501,-0.000220589944492,-0.0322304382516,-0.00160464768366,0.0455968830089,0.00353788468596 +10.66,51.0011109574,1.54151472318e-007,10.0267040261,20.0000260379,-2.30713836351e-005,-0.031199996143,-0.00188609708317,0.0428919906194,0.00270614911771 +10.67,51.0011127552,1.54152979312e-007,10.0270194311,20.0005307441,4.42284051219e-005,-0.0318810111591,-0.000317743136988,0.0441870820229,-0.000557960075802 +10.68,51.0011145531,1.54159562182e-007,10.0273381271,20.0005708756,4.8189975334e-005,-0.0318581928875,0.000988314578793,0.0448271061297,0.000554786280821 +10.69,51.001116351,1.54065074808e-007,10.0276654134,20.0016799475,-0.00137471907422,-0.0335990623834,0.000955387530139,0.0464918973725,-0.00113786615245 +10.7,51.0011181489,1.53996473588e-007,10.0279965167,20.0009973415,0.000411611391269,-0.0326215984143,0.00119340281882,0.0471274532271,0.000891472887619 +10.71,51.0011199466,1.5414755299e-007,10.0283182954,19.9988567606,0.00170942553169,-0.0317341292478,0.00294142483626,0.0475473307768,0.000565058810092 +10.72,51.0011217444,1.54241544319e-007,10.0286383871,20.0004434898,-0.000389860616556,-0.0322842178748,0.0011068682595,0.0481926891678,0.000854829265239 +10.73,51.0011235422,1.54181129372e-007,10.0289678652,19.9997644036,-0.000458318032063,-0.0336113958028,0.00383822027737,0.050545003119,-2.11684874885e-005 +10.74,51.0011253399,1.54089437479e-007,10.0293126186,19.9998689193,-0.000828964460277,-0.0353392892585,0.00422492323196,0.0521143021306,-0.00144678121151 +10.75,51.0011271377,1.53923777584e-007,10.0296667075,19.9997858341,-0.00149677084927,-0.0354784865663,0.00239159351779,0.0517170445151,0.000778195162267 +10.76,51.0011289355,1.53770910652e-007,10.0300163702,20.0006176893,-0.000649361222759,-0.0344540601738,0.00155413392477,0.0500563166825,0.00179631214431 +10.77,51.0011307333,1.53630846695e-007,10.0303704453,20.0011684076,-0.00131702699742,-0.0363609653312,0.00199268821543,0.0527282617049,-0.00127875197013 +10.78,51.0011325312,1.53485696398e-007,10.0307232958,20.0015596585,-0.000720769395509,-0.0342091371596,0.00116125057588,0.0507167771877,0.00117920850903 +10.79,51.0011343291,1.53478316907e-007,10.0310639752,20.0010022069,0.000617167109,-0.0339267377003,0.00093879678542,0.0509123490983,0.00200026926829 +10.8,51.001136127,1.53531400387e-007,10.0314072308,20.0012626509,0.000128083291,-0.0347243765643,0.00145229130639,0.0506394222289,0.00193488258879 +10.81,51.0011379249,1.53565939498e-007,10.0317538349,20.0017127408,0.000356818684206,-0.0345964568943,0.000908301578348,0.0504552629531,0.000372432164494 +10.82,51.0011397228,1.53639285226e-007,10.0320981905,20.0005963754,0.000672897671876,-0.0342746475945,0.00153242242174,0.0515858875155,0.00189689118117 +10.83,51.0011415207,1.5367897869e-007,10.0324443026,20.001621645,-0.000115632642453,-0.0349477831199,-0.0005289586442,0.0526328539984,-0.000522339703431 +10.84,51.0011433186,1.53545488085e-007,10.0328024209,20.0013696163,-0.00175847033408,-0.0366758709477,0.00073759310095,0.054024581468,-0.00121986146729 +10.85,51.0011451165,1.53517022605e-007,10.0331700884,20.0014326991,0.00135883735777,-0.0368576314917,0.00128296782692,0.0551846119748,0.000615757494189 +10.86,51.0011469144,1.53551164163e-007,10.0335395648,20.0013160897,-0.000879516755173,-0.0370376536748,0.0020438730699,0.0534702559173,-5.71301203404e-005 +10.87,51.0011487123,1.53517123734e-007,10.0338986921,20.0005474353,0.000401615964373,-0.0347877966748,-0.000205111764245,0.0537356364677,0.000786380094973 +10.88,51.0011505101,1.5344019211e-007,10.0342504214,20.0009262164,-0.00148167521167,-0.0355580578087,-3.26048641402e-005,0.0538082935781,0.000296677497227 +10.89,51.001152308,1.53230831826e-007,10.0346058302,20.0008155064,-0.00145757780115,-0.0355237123404,-0.00180120485647,0.0539222983152,0.000446292245212 +10.9,51.0011541058,1.53037324888e-007,10.0349686682,20.0013715884,-0.00125910664449,-0.0370438839572,-0.000604412924012,0.0550660315137,-7.50465185068e-005 +10.91,51.0011559037,1.52943146149e-007,10.0353370095,20.0001966899,-6.3088379309e-005,-0.0366243743216,-0.000421538396271,0.054629303525,-0.00202590699959 +10.92,51.0011577015,1.52790160077e-007,10.0357061347,20.000855849,-0.00208471494752,-0.0372006673722,-0.00285281719531,0.0540868628135,-0.000970542173595 +10.93,51.0011594994,1.52485245133e-007,10.036081228,20.0022083995,-0.00219604933998,-0.0378180000652,-0.0022430865588,0.0567785633268,-0.000228333067091 +10.94,51.0011612973,1.52084995554e-007,10.0364641068,19.9995706183,-0.00342313748163,-0.0387577558595,-0.00425797939523,0.0530771689045,0.000241495444223 +10.95,51.0011630951,1.51784833053e-007,10.036850507,20.0007125017,-0.000790906005243,-0.0385222750165,-0.00617030100003,0.0549158177504,0.000413975752295 +10.96,51.0011648929,1.51562554317e-007,10.0372372316,20.001195878,-0.00232971100534,-0.0388226440335,-0.00282110146818,0.0559797729298,0.000270110883156 +10.97,51.0011666908,1.51058519292e-007,10.037620214,20.0002613988,-0.00474654037211,-0.0377738376986,-4.21067562258e-005,0.0575797415757,-8.15498649897e-005 +10.98,51.0011684886,1.50524774311e-007,10.0380008243,20.0001627733,-0.00274681498889,-0.0383482244567,-0.000437003241183,0.0568831568644,0.00291153799475 +10.99,51.0011702864,1.50300712932e-007,10.0383878927,20.000496004,-0.000398828607081,-0.0390654539295,-0.00173808492561,0.0545493891375,0.000209363980748 +11,51.0011720843,1.50257324883e-007,10.0387793504,20.0023748578,-0.00021030507815,-0.0392260940631,-0.00205968236089,0.0571614552488,0.000449317294902 +11.01,51.0011738822,1.50268702339e-007,10.0391701018,20.0001407317,0.000370035486407,-0.0389241910472,-0.000358925579505,0.0602908356272,0.000492771889804 +11.02,51.00117568,1.50416497481e-007,10.0395657043,20.0009045704,0.0017048905015,-0.040196309813,-0.000865677635067,0.0604451657705,0.000972730323006 +11.03,51.0011774779,1.50583203957e-007,10.0399766889,20.0015052011,0.000635535494425,-0.0420005997756,-0.00235561372704,0.0601276819946,0.0017999776893 +11.04,51.0011792758,1.50605124051e-007,10.0403825869,20.0012956616,-0.000327794848763,-0.0391790080179,-0.00146295014709,0.0615040802274,0.000559971681718 +11.05,51.0011810737,1.50575955812e-007,10.040773471,20.0017000002,-8.17039383069e-005,-0.0389978147889,0.000643200888653,0.0618730922055,0.00104934350955 +11.06,51.0011828716,1.50712144421e-007,10.0411650229,20.0009516351,0.00199368313844,-0.0393125647262,0.00150609827932,0.0633514191469,0.00230766975361 +11.07,51.0011846695,1.50863849721e-007,10.0415463399,20.0010502408,0.000136137995362,-0.0369508314419,0.00231952788916,0.0647481181959,0.000255788538111 +11.08,51.0011864673,1.50877093983e-007,10.0419214109,20.0006698024,4.98008404614e-005,-0.0380633725416,-0.00108255819528,0.0643230852161,0.000424861525907 +11.09,51.0011882651,1.50903816565e-007,10.0422982819,20.0002089468,0.000325362811515,-0.0373108169378,-0.00184939829525,0.0656537085392,-0.000862029707571 +11.1,51.0011900629,1.50865628702e-007,10.0426750925,19.9992810213,-0.000861489787046,-0.0380513082624,-0.00153304515139,0.0649370607727,-0.000784638659232 +11.11,51.0011918606,1.50730866799e-007,10.0430503281,20.0002595068,-0.00103045926367,-0.0369958043988,-0.00248575409948,0.0667703058984,-0.000482918837564 +11.12,51.0011936585,1.50446903862e-007,10.043427597,20.0008388995,-0.00295615249459,-0.0384579713271,-0.0019028191025,0.068229262878,0.000335013898887 +11.13,51.0011954563,1.50147601935e-007,10.0438073079,20.0011607707,-0.00124580628118,-0.0374842118203,0.000864358738453,0.0665650272833,0.000514657517679 +11.14,51.0011972543,1.49873127482e-007,10.0441838585,20.0019324098,-0.00260759448794,-0.0378259076187,-0.00158867362037,0.0671711260214,0.00213177700585 +11.15,51.0011990522,1.49549600572e-007,10.0445690931,20.0017971486,-0.00193446323051,-0.0392210261842,-0.000945640163217,0.0687156828752,0.00156622460795 +11.16,51.0012008503,1.4941292835e-007,10.0449638353,20.0047540912,1.5695153172e-005,-0.0397274009318,-0.00128664270717,0.070553618785,0.000385181051917 +11.17,51.0012026484,1.49372465266e-007,10.0453643359,20.0026260731,-0.00058376425963,-0.0403727258428,-0.0016568806507,0.0713382253026,0.00168116926577 +11.18,51.0012044464,1.49417830837e-007,10.0457680808,20.0036821041,0.00122066028493,-0.0403762553308,-0.0017378366587,0.0729623559875,-0.000710129595257 +11.19,51.0012062445,1.49505141176e-007,10.0461787663,20.00210413,5.10652406635e-006,-0.041760839799,-0.00220897550221,0.0721227918922,0.000237281374882 +11.2,51.0012080425,1.49497106887e-007,10.0465931792,20.0023933212,-0.000117901459081,-0.0411217445702,-0.00169321631898,0.0723826847227,0.000813530164259 +11.21,51.0012098404,1.49542899445e-007,10.0470004495,20.0013282622,0.000760791990015,-0.0403323239925,-0.000931242420918,0.0716775140211,-0.000216863903504 +11.22,51.0012116384,1.49761881823e-007,10.04740858,20.0032067333,0.00231354366846,-0.0412937581277,-0.00207062032955,0.0743566253351,0.000978764782172 +11.23,51.0012134364,1.50044677887e-007,10.0478248822,20.0017199644,0.00165668449605,-0.0419666985812,-0.000865324318198,0.0732056046697,0.00345454513933 +11.24,51.0012152343,1.50208399283e-007,10.048239479,20.0013975134,0.000641831493714,-0.040952658711,0.000179045675018,0.0743338143727,0.00345043452592 +11.25,51.0012170322,1.50342670869e-007,10.048660829,20.0018699676,0.00124323287708,-0.0433173311124,-0.000120168730088,0.0753711801739,0.0041754341162 +11.26,51.0012188302,1.50459970177e-007,10.0490888875,20.0028934065,0.00040355442005,-0.0422943640836,0.00149817493019,0.0777666239343,0.00378162589245 +11.27,51.0012206282,1.50674503607e-007,10.0495158327,20.0023962234,0.00260832101245,-0.0430946751387,0.00157509193709,0.0770573489536,0.00392419754182 +11.28,51.0012224262,1.50941833587e-007,10.0499436523,20.0009240682,0.00114477512959,-0.0424692613938,0.000299630110346,0.0757801429371,0.00370250473662 +11.29,51.0012242241,1.51048677402e-007,10.0503709167,20.0017751063,0.000355225336108,-0.0429836204137,-0.000649632126884,0.0763865583555,0.00354690768551 +11.3,51.001226022,1.51173679658e-007,10.0507951199,20.0012300444,0.00139970480021,-0.0418570186161,-0.00123316542791,0.0754189571081,0.00518186421713 +11.31,51.0012278198,1.51411513588e-007,10.0512186152,19.9998642535,0.00193929028032,-0.0428420325018,-0.00208650816066,0.0783633436233,0.00542782292019 +11.32,51.0012296175,1.51727216688e-007,10.0516567387,19.9990332131,0.00249292450903,-0.0447826708086,-0.00146078940385,0.0772653553112,0.00223636792616 +11.33,51.0012314152,1.52155543943e-007,10.0521036759,19.9978777465,0.0035204415833,-0.044604765175,-0.00100313654857,0.077206063259,0.00324753938619 +11.34,51.0012332128,1.52644492704e-007,10.0525461218,19.999292469,0.00334400088211,-0.0438844115505,-0.00143181214289,0.0773057098252,0.00393961601816 +11.35,51.0012350105,1.53170662537e-007,10.0529937058,19.9986378046,0.00404299481907,-0.0456323918763,-0.00180633086442,0.0786763179909,0.0032669459372 +11.36,51.0012368082,1.53641705701e-007,10.0534405745,19.9997918781,0.00257006715287,-0.0437413432114,-0.00250063497397,0.0801186949103,-0.000186772189467 +11.37,51.001238606,1.54055648501e-007,10.053879776,19.9996218448,0.00324135200419,-0.0440989548343,-0.00371312213256,0.0818348528405,-0.000779382598114 +11.38,51.0012404037,1.54434553083e-007,10.0543198932,19.9995313896,0.00207815899851,-0.0439244977234,-0.00296788001549,0.0811205792133,-0.000611416270597 +11.39,51.0012422014,1.54719346283e-007,10.0547652099,19.9981089218,0.0019201048578,-0.0451388386703,-0.00184793564921,0.0809921803715,-0.00134228923987 +11.4,51.0012439989,1.54948543157e-007,10.055226711,19.9966956799,0.00129763188173,-0.0471613869773,-0.00112815138768,0.0816378517191,-0.000310632569506 +11.41,51.0012457964,1.55205578649e-007,10.055698049,19.9975867691,0.00231093613526,-0.0471062075058,-0.00190602216784,0.0822978418696,-0.000914330301601 +11.42,51.001247594,1.55416263156e-007,10.0561628788,19.9977568424,0.000646901908714,-0.0458597582732,-0.00241909304856,0.0808045072014,-0.00178808883327 +11.43,51.0012493916,1.55496370991e-007,10.0566242772,19.9981906564,0.00047774646725,-0.0464199151975,-0.000912193007713,0.0805158285193,0.00164877694333 +11.44,51.0012511892,1.55642607265e-007,10.0570930769,19.9982085501,0.00157529093018,-0.0473400240127,-0.000735730592223,0.0826159951323,-2.41033671687e-005 +11.45,51.0012529868,1.55912410502e-007,10.0575652269,19.9970563229,0.00221252520024,-0.0470899822657,-0.00188233246603,0.0830605232426,-0.000919947565163 +11.46,51.0012547843,1.56178286435e-007,10.0580294419,19.9980816505,0.00152015468413,-0.0457530169397,-0.00137967674426,0.0843507459988,9.34642192647e-005 +11.47,51.0012565819,1.5636193492e-007,10.058487077,19.9983561017,0.00105811921933,-0.0457739895791,0.000645193477786,0.0856039105615,0.00169712643295 +11.48,51.0012583796,1.56580226232e-007,10.0589544927,19.998897823,0.00200651138783,-0.0477091562669,-0.000277541042356,0.0850240664155,0.000111946719056 +11.49,51.0012601772,1.56739317391e-007,10.0594385209,19.9979403415,0.000226997678577,-0.049096495853,-0.00121130472096,0.0853528441034,0.00078665867119 +11.5,51.0012619749,1.5677950165e-007,10.059927453,19.9991766144,0.000337156240103,-0.0486899088015,-0.00170159518731,0.0874695125087,0.000174346276358 +11.51,51.0012637727,1.56845179444e-007,10.0604145789,20.0017436563,0.000584905898213,-0.0487352829783,-0.00288831349208,0.0873393557621,0.00323976682 +11.52,51.0012655706,1.56886841853e-007,10.0608982553,20,0,-0.048,0,0.089,0 +11.53,51.0012673683,1.56965316449e-007,10.0613745906,19.9990153833,0.00110171861112,-0.0472670615351,0.00161582462763,0.0894953107017,-4.02747702896e-005 +11.54,51.001269166,1.57142937249e-007,10.0618567089,19.9991298024,0.00139193084806,-0.0491565863606,0.00237724072375,0.0909975293666,0.00144409203962 +11.55,51.0012709637,1.57286441923e-007,10.0623500287,19.9999301348,0.000622756299989,-0.049507380084,0.00133808637384,0.0931982996141,0.00217674472559 +11.56,51.0012727614,1.57414429726e-007,10.0628421034,19.9985413542,0.00117408670849,-0.0489075647873,0.00099387593638,0.0917480372466,0.00101544518686 +11.57,51.001274559,1.57552459936e-007,10.0633266972,19.9969942047,0.000763743334151,-0.0480111959244,0.00337178278047,0.0903340132802,0.00175192988523 +11.58,51.0012763565,1.57713684586e-007,10.0638121198,19.9975120133,0.00149971735872,-0.0490733213164,0.00353368048011,0.09427331517,-5.21446450048e-005 +11.59,51.0012781541,1.57966769628e-007,10.0642981279,19.9978715977,0.0020533871042,-0.0481283001784,0.000702323294917,0.0939457417905,-0.00214309867474 +11.6,51.0012799517,1.58306193119e-007,10.0647838413,19.9974690276,0.00271183753801,-0.0490143679252,0.00246822048313,0.0947338615378,-0.00101903494327 +11.61,51.0012817492,1.58726332413e-007,10.0652717603,19.9979092763,0.00318656988039,-0.048569443064,0.00205416039269,0.097060274296,-0.00277230157834 +11.62,51.0012835468,1.59238922615e-007,10.0657550722,19.9974753185,0.00400977137843,-0.0480929391279,0.00360084410866,0.0973935498418,-0.00119188993489 +11.63,51.0012853443,1.5980174318e-007,10.066236653,19.9964401912,0.00389176221084,-0.0482232205032,0.00367076166461,0.0983548513247,-0.00235237356162 +11.64,51.0012871418,1.60296408921e-007,10.0667286037,19.9968091727,0.00305293397641,-0.0501669006219,0.00350344226835,0.097807677695,-0.000991266136598 +11.65,51.0012889392,1.60628072233e-007,10.0672321984,19.9958734942,0.0016033433182,-0.0505520469537,0.00504267939177,0.0982279838283,-0.000291983379908 +11.66,51.0012907367,1.60925526263e-007,10.0677396448,19.9979060222,0.00257266388168,-0.0509372304495,0.00424380329051,0.100023854199,0.00103352822449 +11.67,51.0012925343,1.61171402175e-007,10.0682462853,19.9966595494,0.00087922934667,-0.0503908738292,0.0014524850372,0.102770596574,-0.000424845670091 +11.68,51.0012943318,1.61336300283e-007,10.0687575923,19.9972332801,0.0014358027651,-0.0518705191533,0.00121748469879,0.101585099255,0.000702002052606 +11.69,51.0012961293,1.61430986508e-007,10.0692709535,19.9962162021,-0.00010648702857,-0.0508017337953,0.00314142829181,0.104151055045,-0.000517183857895 +11.7,51.0012979267,1.61441748548e-007,10.0697832845,19.9955123722,0.000257577087207,-0.0516644564829,0.00513751814124,0.102966267828,0.00151835683776 +11.71,51.0012997241,1.6148518062e-007,10.070294386,19.9967565476,0.000352172963196,-0.0505558507881,0.00545113395672,0.10279933788,0.00139462535444 +11.72,51.0013015216,1.61422684754e-007,10.0708099702,19.9980121117,-0.0012295627152,-0.0525609768525,0.00535990851202,0.105054338286,-0.00165731380747 +11.73,51.0013033192,1.61278703526e-007,10.0713330244,19.9982618038,-0.000791813453467,-0.0520498779192,0.00786845912337,0.105156722909,-0.00274456063699 +11.74,51.0013051168,1.6116896424e-007,10.0718507904,19.9964982612,-0.000748834388262,-0.0515033113967,0.00552149761185,0.108792719609,-0.00192046760201 +11.75,51.0013069142,1.61116439341e-007,10.0723715137,19.9963681727,1.1428735146e-005,-0.0526413631093,0.00333490772883,0.109806037971,-0.00123469364192 +11.76,51.0013087117,1.61233605685e-007,10.0728952961,19.996233197,0.00163348863472,-0.0521151020277,0.00316930610624,0.108384614023,0.000712342004885 +11.77,51.0013105091,1.61464416713e-007,10.0734150254,19.9962982496,0.00160690488135,-0.0518307669536,0.00291295868968,0.107857613354,0.000520906232949 +11.78,51.0013123066,1.61596899374e-007,10.0739389853,19.9963890373,0.000253040663234,-0.0529612058396,0.0042948583517,0.11052329689,0.00056845534084 +11.79,51.001314104,1.61776627204e-007,10.0744712354,19.9966907855,0.00227018729888,-0.0534888225303,0.00324107050471,0.109807850384,-0.000372873997958 +11.8,51.0013159016,1.62051614715e-007,10.0750028588,19.9971832653,0.0015904066022,-0.0528358580414,0.00305678232756,0.110561964739,0.000734306254643 +11.81,51.001317699,1.62260570207e-007,10.0755390938,19.9963205169,0.00134315304312,-0.0544111430852,0.00296334824479,0.111827236089,-0.0014273701898 +11.82,51.0013194965,1.6247383867e-007,10.0760804211,19.9973165562,0.001650956969,-0.0538543047422,0.00162513502768,0.112115591558,-0.000103564542031 +11.83,51.0013212941,1.62663426823e-007,10.0766186446,19.9992131733,0.00101070131049,-0.0537903982746,0.00109745014351,0.111933085177,0.000407407020173 +11.84,51.0013230918,1.6279914981e-007,10.0771626942,19.9980720535,0.000894735230717,-0.0550195327322,-0.000160894852095,0.113232797536,-0.000473283965148 +11.85,51.0013248895,1.62947865574e-007,10.0777162722,20.0002909829,0.00119310888976,-0.055696060226,-0.000334042047637,0.114979787148,0.00131703142082 +11.86,51.0013266873,1.63051712815e-007,10.0782713311,19.9999041966,0.000264818898912,-0.0553157108107,4.84141400407e-005,0.111233049532,0.000660563643569 +11.87,51.0013284851,1.63027286371e-007,10.078822362,20.0001978574,-0.000607745553454,-0.0548904680444,-0.00169579973744,0.114198368291,0.000209965032603 +11.88,51.0013302829,1.63071678116e-007,10.0793790297,20.0003156552,0.00123096816204,-0.0564430895167,-0.00190994419145,0.11468490456,-0.00077693709814 +11.89,51.0013320806,1.63324423995e-007,10.079940678,19.9977975696,0.00231737062496,-0.0558865525298,-0.00143238718651,0.114497981209,-0.00120225357902 +11.9,51.0013338782,1.63601514628e-007,10.0805044406,19.9991334576,0.00157274784462,-0.0568659697919,-0.00237424667264,0.117793131631,0.000815392188415 +11.91,51.001335676,1.63874214726e-007,10.0810777863,20.0013856458,0.00225573105673,-0.0578031837513,-0.00231082520994,0.117707743782,0.00143578245096 +11.92,51.0013374739,1.64148716094e-007,10.081656735,20.0014104914,0.00159803601771,-0.0579865549638,-0.00155587620909,0.117338599442,0.00132680192159 +11.93,51.0013392718,1.64303508989e-007,10.0822432319,20.0005308793,0.000575125250101,-0.0593128153715,0.00109112573831,0.116112699618,0.000399321378161 +11.94,51.0013410696,1.64538327968e-007,10.0828381608,20.0004428896,0.00272153434014,-0.0596729768507,-0.000218546262212,0.116921996618,0.00108945229135 +11.95,51.0013428673,1.64900336525e-007,10.0834362056,19.998616361,0.00236075906771,-0.0599359714805,0.000394006691486,0.119505948071,0.000674276106363 +11.96,51.0013446651,1.6522680275e-007,10.0840296431,20.0001844966,0.00222254994381,-0.0587515257177,0.000583737205212,0.121686975136,0.000450789040266 +11.97,51.0013464628,1.65570926868e-007,10.084615541,19.9995771535,0.00260866071685,-0.0584280515223,-0.000520085504972,0.124236256536,0.000556206846709 +11.98,51.0013482605,1.65969658423e-007,10.0852000804,19.9978356087,0.00298919180627,-0.0584798478261,1.49289256388e-005,0.124238002368,0.000649641097629 +11.99,51.0013500581,1.66382618275e-007,10.0857865331,19.9989268615,0.00280841371197,-0.0588106819933,-0.00293073173019,0.124957863829,-0.000756945208316 +12,51.0013518558,1.6679365863e-007,10.0863763908,19.9983463427,0.00296224348644,-0.0591608660863,-0.000672892160804,0.125733950322,-0.000305975774918 +12.01,51.0013536533,1.67156217198e-007,10.0869673927,19.996812076,0.00212777044929,-0.059039502598,-0.00218757790265,0.125682852975,0.000920423278127 +12.02,51.0013554509,1.67427774153e-007,10.0875612668,19.998491593,0.00168465808599,-0.0597353184998,-0.00264135889049,0.128326756842,6.85332799698e-005 +12.03,51.0013572486,1.67682102538e-007,10.0881619247,19.9995838053,0.00188589583779,-0.060396262156,-0.00211535132799,0.127484302238,-0.000303139615018 +12.04,51.0013590462,1.67824393414e-007,10.0887638455,19.9968887659,0.000111746833226,-0.0599879019912,-0.00383092552014,0.129538641001,1.178332079e-005 +12.05,51.0013608437,1.67801765916e-007,10.0893630429,19.9976919509,-0.000429417600225,-0.059851575685,-0.00323426023263,0.132444582774,0.000207822226187 +12.06,51.0013626412,1.67813557578e-007,10.0899576215,19.9957081785,0.000594962455202,-0.0590641400453,-0.00378383840819,0.133167981306,0.00132593150725 +12.07,51.0013644386,1.67879125888e-007,10.0905445228,19.9950358521,0.000325560640535,-0.0583161170095,-0.00239080276284,0.135370097514,0.000165509963882 +12.08,51.001366236,1.67954254077e-007,10.0911363039,19.9965313791,0.00072917494277,-0.0600401006146,-0.00156844319192,0.134652554054,0.000306466232765 +12.09,51.0013680334,1.67996765681e-007,10.0917443878,19.9957237448,-0.000132348350876,-0.0615766838002,-0.000869790860002,0.133530129003,-0.00147205501828 +12.1,51.0013698309,1.67941266311e-007,10.0923586444,19.9975206776,-0.00064681532013,-0.0612746328442,-0.000274082958124,0.13225401957,-0.000899343445193 +12.11,51.0013716284,1.67771322266e-007,10.0929720576,19.9974014287,-0.00173905358667,-0.0614080120302,-0.0016486576273,0.132721809267,-9.86602828931e-005 +12.12,51.001373426,1.67622071195e-007,10.0935853559,19.9985120671,-0.000356303632286,-0.0612516583783,-0.00151193625174,0.132727094423,-0.00164149032192 +12.13,51.0013752237,1.67417394628e-007,10.0941950877,19.9984966168,-0.00251717991129,-0.0606946906804,0.000947351347433,0.132303049861,-0.00125714505269 +12.14,51.0013770213,1.67179632378e-007,10.094808817,19.998536697,-0.000820798205778,-0.0620511780027,-0.000872503391606,0.133866685961,-0.000533337353779 +12.15,51.001378819,1.67067387718e-007,10.095430418,19.9988254232,-0.000755020504025,-0.0622690213721,0.000274958781645,0.132821726209,-0.000167180361103 +12.16,51.0013806166,1.67027835426e-007,10.0960571338,19.997981309,0.000199740262298,-0.0630741356809,-0.00145536259034,0.135943980171,0.000681026363534 +12.17,51.0013824142,1.67292664544e-007,10.0966892064,19.9972408943,0.00351823294569,-0.0633403852657,-0.00207721721149,0.137431236181,0.00118633015071 +12.18,51.0013842117,1.67697992037e-007,10.0973261245,19.9976464353,0.00217221660363,-0.0640432375957,-0.00121508002804,0.13796577634,0.000748039265263 +12.19,51.0013860093,1.68124051568e-007,10.0979654952,19.9981226752,0.00380929264212,-0.0638308957561,0.000715346827467,0.137111516541,-0.000612603274048 +12.2,51.0013878069,1.68517852346e-007,10.0986140932,19.9973482205,0.00171933131912,-0.0658887112717,-0.000631076828892,0.138208992849,0.000986853537217 +12.21,51.0013896044,1.6868390611e-007,10.0992756259,19.9963130115,0.000611920515854,-0.0664178219352,0.000167520111197,0.139557612946,0.00127564222855 +12.22,51.0013914019,1.68842527863e-007,10.0999460288,19.9972951933,0.00161499215567,-0.0676627668141,-0.000196541796818,0.140757553607,0.00411177133372 +12.23,51.0013931994,1.69106097261e-007,10.1006194093,19.9968319821,0.00208529486143,-0.0670133205602,-0.00105315341959,0.142230472982,0.00277672498453 +12.24,51.0013949969,1.693107233e-007,10.1012919568,19.9971063441,0.000787478154746,-0.0674961910273,-0.00136111954757,0.142138609783,0.00375119976859 +12.25,51.0013967943,1.69414105435e-007,10.1019691944,19.9944997619,0.000663917752202,-0.0679513173315,-0.00100379405768,0.143977306603,0.00351042254438 +12.26,51.0013985916,1.69485185922e-007,10.1026427683,19.9948325066,0.000333990864315,-0.0667634727602,-0.000577125860261,0.144172664584,0.00247663034086 +12.27,51.0014003889,1.69522670406e-007,10.1033199255,19.9955821157,0.00019225889586,-0.0686679639859,-0.000187455641423,0.143633745903,0.001828918812 +12.28,51.0014021863,1.69548783937e-007,10.1040116006,19.9961394542,0.00017435248509,-0.0696670560959,-0.000790459815331,0.14354592046,0.00186727602153 +12.29,51.0014039839,1.69539871557e-007,10.1047161942,19.9995831201,-0.000299474577075,-0.0712516658148,-0.000780898559059,0.146755322296,0.00197292875646 +12.3,51.0014057816,1.69643290971e-007,10.1054307596,19.9976568662,0.00175139352606,-0.0716614086493,2.19112048269e-006,0.146971867346,0.00128098921165 +12.31,51.0014075792,1.69812319869e-007,10.1061384288,19.9987203569,0.000621625699194,-0.0698724315684,-0.000118560717746,0.148921011622,0.00261030802855 +12.32,51.0014093768,1.69858055803e-007,10.106840414,19.9977775367,2.04671695014e-005,-0.0705246117269,-0.00109418422048,0.148273609074,0.00222502242341 +12.33,51.0014111743,1.69787732882e-007,10.1075475175,19.9969987137,-0.00100773993999,-0.0708960832489,-0.00197080824065,0.149937722629,0.00325099624167 +12.34,51.0014129718,1.69594721256e-007,10.1082445601,19.9957066904,-0.00170197565757,-0.0685124458281,-0.00333027207172,0.15118843062,0.00346994262172 +12.35,51.0014147692,1.69389451943e-007,10.1089356075,19.995641242,-0.00117982713619,-0.0696970375943,-0.00205921348143,0.148901500106,0.00415117997297 +12.36,51.0014165666,1.69241662125e-007,10.1096325251,19.9959649148,-0.000895013411222,-0.0696864741351,-0.0021125162207,0.150826021273,0.00144332473257 +12.37,51.0014183639,1.69066676888e-007,10.110322354,19.9946688989,-0.00156162705426,-0.0682793138912,-3.00999661729e-005,0.153270015005,0.000421565339261 +12.38,51.0014201613,1.68902863508e-007,10.1110038752,19.9953309197,-0.000738170210445,-0.0680249126641,-0.00175728985046,0.152577261257,0.000929237777126 +12.39,51.0014219587,1.68903004219e-007,10.1116867435,19.9969905011,0.00074014564091,-0.0685487596777,-0.000970971062529,0.15536093375,0.000512179186186 +12.4,51.0014237562,1.68980199663e-007,10.1123799648,19.9966010455,0.000343611120245,-0.070095502747,-0.00208142838616,0.154665890458,0.000349462268647 +12.41,51.0014255537,1.69016183391e-007,10.1130923035,19.9965869012,0.000161569035419,-0.0723722252676,-0.002950360314,0.153566246831,-0.00107234209309 +12.42,51.0014273512,1.69088341654e-007,10.1138086862,19.9976235937,0.000851469992182,-0.070904307196,-0.00255122225475,0.153387848732,-0.00322738320831 +12.43,51.0014291488,1.69280386142e-007,10.1145170027,19.9991191321,0.00184466688269,-0.0707590014688,-0.000990018139719,0.154798070491,-0.0035343532305 +12.44,51.0014309465,1.69539070475e-007,10.1152194915,19.9981639343,0.00178703511271,-0.0697387590278,-7.164224531e-005,0.155664322328,-0.0015751880712 +12.45,51.0014327441,1.69710257614e-007,10.1159173695,19.9994078208,0.000616282661454,-0.0698368448226,-0.00250504817806,0.155387093781,-0.000177937752995 +12.46,51.0014345418,1.69869660512e-007,10.1166250295,19.9981211552,0.00162159454019,-0.0716951511225,-0.00163909166517,0.158088324408,-0.000283504347638 +12.47,51.0014363394,1.70006451173e-007,10.1173381535,19.9980081396,0.000298826618375,-0.070929647908,-0.00206359689433,0.160481871697,0.00173102816295 +12.48,51.001438137,1.69982027137e-007,10.1180553254,19.9976838169,-0.000641718667782,-0.0725047270904,-0.00117650744352,0.160936460091,0.000435376480088 +12.49,51.0014399346,1.6983756161e-007,10.1187723659,19.9987094721,-0.00138645070063,-0.0709033885354,0.000212077308122,0.1634773151,0.000944132509946 +12.5,51.0014417322,1.69707561537e-007,10.1194706904,19.9979239205,-0.000438636323955,-0.0687615015748,0.00010045070699,0.163140414486,0.000716310114366 +12.51,51.0014435299,1.69671069909e-007,10.1201691712,19.9991203583,-7.36741092637e-005,-0.070934665323,-0.000510293134196,0.163867049251,0.00150567769519 +12.52,51.0014453276,1.69612889004e-007,10.1208834981,19.9986963551,-0.000743134689211,-0.0719307166015,-0.00138905001285,0.164460677731,0.00112354197806 +12.53,51.0014471253,1.69528439851e-007,10.1215884788,20.0003605616,-0.000442457228934,-0.0690654118865,-0.000928556637272,0.165563667076,0.00156742044558 +12.54,51.0014489231,1.69427537886e-007,10.1222859289,19.9996511931,-0.000974117629566,-0.0704246196787,-0.00262348566891,0.167234034502,0.00123274736588 +12.55,51.0014507209,1.69363709165e-007,10.1229959706,20.0018789214,7.80185204218e-005,-0.0715837032667,-0.00178866047608,0.167024068501,-0.000269145415424 +12.56,51.0014525188,1.69409584681e-007,10.123721747,19.9998326363,0.00056603333026,-0.0735715772233,-0.00149899172161,0.167713227113,-0.000201023494454 +12.57,51.0014543165,1.69366422694e-007,10.124458684,19.9998954926,-0.00117198956484,-0.0738158268721,-0.00117905912568,0.168409245345,-0.000715676461334 +12.58,51.0014561143,1.69299281934e-007,10.1252063732,20.0003919922,0.000229392444657,-0.0757220086945,-0.00213961297198,0.169838911458,-0.000137611113331 +12.59,51.0014579122,1.69410917929e-007,10.1259568751,20.000994368,0.00133787844165,-0.0743783818298,-0.00298783819076,0.168892426604,0.000446566096232 +12.6,51.0014597099,1.69618556524e-007,10.1267042209,19.999058981,0.0015771841853,-0.0750907709739,-0.00210353014455,0.169860541963,0.000216927889709 +12.61,51.0014615076,1.69920900862e-007,10.1274551364,19.9984990867,0.00266746333224,-0.075092336671,-0.000856155867378,0.169423319011,0.000360347714807 +12.62,51.0014633053,1.70208650384e-007,10.1282058311,19.9999838698,0.00137228572951,-0.0750466061165,1.36257752452e-005,0.172422142731,-0.000718497900565 +12.63,51.001465103,1.7031830165e-007,10.1289538345,19.9979556409,0.000167121126437,-0.074554068292,0.000117878298821,0.174075711464,-0.000132004220997 +12.64,51.0014669006,1.70430499963e-007,10.1297041072,19.9984452191,0.00140804391553,-0.0755004710205,-0.00129706356911,0.173587020296,0.000367792426224 +12.65,51.0014686982,1.70642692831e-007,10.1304622403,19.9981227868,0.00157095612121,-0.0761261523764,-0.00176231178593,0.174207272342,0.000855826292164 +12.66,51.0014704958,1.7082274465e-007,10.1312293651,19.9974821202,0.000956811950487,-0.0772987979964,-0.00185480844977,0.174186878388,0.000719875266889 +12.67,51.0014722934,1.70921807717e-007,10.1320009642,19.9975890877,0.000433945726211,-0.0770210335853,-0.000894768949832,0.177127880742,0.00104983625924 +12.68,51.0014740909,1.71090230733e-007,10.1327823524,19.9967548297,0.00193056402303,-0.0792566035751,-0.00147168084786,0.17758759123,-0.000435140588174 +12.69,51.0014758884,1.71377591526e-007,10.1335730339,19.9979534799,0.00210372651682,-0.0788796898936,-0.000174784016556,0.180297953937,0.00160800638384 +12.7,51.001477686,1.71727637907e-007,10.1343651338,19.9971655157,0.00281061386776,-0.0795402952728,-0.000186249338456,0.180301707132,0.000265294591926 +12.71,51.0014794835,1.72079849885e-007,10.1351575159,19.9977442965,0.00213412939832,-0.0789361221689,1.92980828723e-005,0.17935328081,0.00088663198252 +12.72,51.0014812811,1.7229306828e-007,10.1359426181,19.9967756494,0.000859267349853,-0.0780843145379,-0.000558614383841,0.18029776505,2.9055094053e-005 +12.73,51.0014830785,1.72414380684e-007,10.1367226465,19.9954089538,0.000843850894038,-0.0779213758171,-0.000897860592064,0.181934949079,0.000574098844062 +12.74,51.0014848759,1.72482033675e-007,10.1375039248,19.9961220956,0.000105936889467,-0.0783342739619,-0.000899535737831,0.181399255899,0.000906690861942 +12.75,51.0014866734,1.72486602543e-007,10.1382963017,19.9970896833,-4.17940402846e-005,-0.0801411173041,-0.00184284665344,0.180605937542,0.00165766507393 +12.76,51.0014884709,1.72523128432e-007,10.1390891727,19.9980928973,0.000554584960152,-0.0784330827018,-0.00156254013439,0.182690842427,0.00205269552359 +12.77,51.0014902686,1.72731340642e-007,10.1398675504,19.9992495955,0.0023685287765,-0.0772424428275,-0.00210150295834,0.184073037125,0.00260010826927 +12.78,51.0014920663,1.7301033785e-007,10.1406428226,19.9992409562,0.00154834310588,-0.0778120008657,-0.000290036217845,0.183655088309,0.00270996454343 +12.79,51.001493864,1.7307730496e-007,10.1414258824,19.9983988685,-0.000608184627787,-0.0787999568328,0.000535447237347,0.184581840873,0.00280285040688 +12.8,51.0014956617,1.73033984211e-007,10.1422148821,20,0,-0.079,0,0.184,0 +12.81,51.0014974595,1.72990910216e-007,10.1430042082,20.0009559414,-0.000604720370297,-0.0788652117711,0.000304042430201,0.184488007287,-0.00203111229748 +12.82,51.0014992573,1.72946585184e-007,10.1437966357,20.0002871951,-1.75634469229e-005,-0.0796202950011,0.00181446375771,0.184052235689,-0.000543140137216 +12.83,51.0015010552,1.72769602699e-007,10.1445907965,20.0008958407,-0.00246711220971,-0.0792118523485,0.00312779699007,0.184453822107,-0.000334212723403 +12.84,51.001502853,1.72538306807e-007,10.1453799802,20.0000259856,-0.00078007503922,-0.0786248852221,0.0015578103548,0.187815343119,0.00349128426725 +12.85,51.0015046508,1.72463696873e-007,10.1461763047,19.9999548215,-0.00026738159365,-0.0806400194886,0.00363036822099,0.187864155701,0.0028048552307 +12.86,51.0015064484,1.72428095805e-007,10.1469748065,19.9975946895,-0.000232425477608,-0.0790603423689,0.00235064984941,0.187409864481,0.00175291024443 +12.87,51.0015082461,1.72506138651e-007,10.1477734399,19.9992795912,0.00132807699778,-0.0806663473429,0.00302274095327,0.188624439035,0.00199179698646 +12.88,51.0015100437,1.72583349498e-007,10.1485690991,19.9984519357,-0.000244105986474,-0.0784654752301,0.00430120030518,0.191356027654,0.0025572667941 +12.89,51.0015118413,1.72403772011e-007,10.1493619305,19.9978529349,-0.00227700059374,-0.080100821778,0.00663269152228,0.19553518508,0.00475372536108 +12.9,51.001513639,1.72261473019e-007,10.1501681326,19.9993567282,0.000279250569837,-0.0811395879488,0.00482129287353,0.194734107672,0.00510244578554 +12.91,51.0015154366,1.72200005678e-007,10.1509859014,19.9970713931,-0.00114219672653,-0.0824141770101,0.00263149112436,0.194779953319,0.00413042738938 +12.92,51.0015172342,1.72169867252e-007,10.1518046963,19.9985552211,0.000719080304424,-0.0813447983051,0.00509625614874,0.193387108255,0.00272909419025 +12.93,51.0015190318,1.72277573322e-007,10.1526124788,19.9983854234,0.000793015942154,-0.0802117042973,0.00338763629296,0.192796158233,0.00107580481007 +12.94,51.0015208295,1.72335870797e-007,10.1534181504,19.9989450498,2.54280998072e-005,-0.0809226130559,0.00404158836554,0.194740948293,0.000866239942816 +12.95,51.0015226272,1.72289225246e-007,10.1542267665,19.9991385196,-0.000680289572007,-0.0808006029392,0.00382616529969,0.196885538737,0.00334250739158 +12.96,51.0015244249,1.72229171888e-007,10.1550415226,19.9997238623,-0.000162805421698,-0.0821506227653,0.00525040082647,0.196617079775,0.00164895314268 +12.97,51.0015262227,1.72186353609e-007,10.1558688446,20.0001753021,-0.000438324567198,-0.0833137710985,0.00440418055587,0.197661743066,0.000320151769377 +12.98,51.0015280205,1.7212346103e-007,10.156698906,20.0004905405,-0.000444630440671,-0.0826985085539,0.00626648449344,0.196914130192,0.00122668524616 +12.99,51.0015298183,1.72066495991e-007,10.1575334818,20.0006256201,-0.000355107239939,-0.0842166598077,0.00769628102037,0.195600966669,0.00192788950473 +13,51.0015316161,1.72022817968e-007,10.1583727449,20.0003152569,-0.000258092716417,-0.0836359539144,0.00434662181758,0.196090664495,0.00125436620731 +13.01,51.001533414,1.7204792931e-007,10.1592217796,20.0026201284,0.000610633228734,-0.086170987216,0.00429378493979,0.197819335563,0.00310414428442 +13.02,51.0015352119,1.72104398417e-007,10.1600834415,19.9992084647,0.000182141921627,-0.0861613958797,0.00648432925341,0.199118197595,0.00303621583918 +13.03,51.0015370096,1.72104738492e-007,10.1609409145,19.9989966538,-0.000177367573537,-0.0853332112224,0.00370552030572,0.20209524365,0.00200781053654 +13.04,51.0015388073,1.72000197079e-007,10.1617921868,19.9994959861,-0.00129029908821,-0.0849212376317,0.00589026854496,0.201497156793,0.0018883972812 +13.05,51.001540605,1.71910088071e-007,10.162643704,19.9987135521,2.5250295217e-005,-0.0853822076536,0.00579449253426,0.204517444473,2.4017760849e-005 +13.06,51.0015424027,1.71811982818e-007,10.1634992083,19.999201313,-0.00140255900767,-0.0857186486238,0.00614686590312,0.206460065332,0.000205989889885 +13.07,51.0015442004,1.71701194294e-007,10.1643545145,19.998904026,-0.000152811299813,-0.085342591632,0.00702175866253,0.206509978602,0.00156001434088 +13.08,51.001545998,1.71705989753e-007,10.1652073528,19.9983959534,0.000220135178164,-0.0852250713399,0.00630167724802,0.206249255981,0.00192491671044 +13.09,51.0015477957,1.71628549473e-007,10.1660599568,19.9997763705,-0.00130732628904,-0.0852957339052,0.007996011697,0.205365746901,0.000180120114318 +13.1,51.0015495935,1.71518068401e-007,10.1669065028,19.9993304482,-0.000243727491405,-0.0840134656954,0.00812189282044,0.207771421785,0.00118460592518 +13.11,51.0015513913,1.71469978818e-007,10.167754653,20.0008162055,-0.000431406495466,-0.0856165768646,0.00841682058539,0.210233131057,-0.000730555348161 +13.12,51.0015531891,1.71429349909e-007,10.1686141402,20.000176439,-0.000138986394842,-0.0862808585001,0.00728895767592,0.209862632928,0.0017490489933 +13.13,51.0015549868,1.71390262229e-007,10.1694733735,19.9988327527,-0.00040976901651,-0.0855657983156,0.00709508725179,0.210955694781,-0.000344515145359 +13.14,51.0015567844,1.71261408678e-007,10.1703404349,19.9967018079,-0.00139921733957,-0.0878464807875,0.00773779096693,0.21093667453,0.000986732000066 +13.15,51.0015585818,1.71174150968e-007,10.1712325716,19.994796949,0.000174198655521,-0.0905808636471,0.00715240463043,0.208187749564,0.00152464478539 +13.16,51.0015603792,1.71165628559e-007,10.1721278968,19.9979592101,-0.000293845488296,-0.0884841661429,0.00782259305502,0.209798568044,0.00216732870093 +13.17,51.001562177,1.71266331773e-007,10.1730117017,20.000925039,0.00170762659848,-0.0882768242464,0.0112175651857,0.211292479553,0.00377373033971 +13.18,51.0015639748,1.71430154366e-007,10.1738882191,20.001150971,0.000592292918579,-0.0870266521339,0.0124352659338,0.211788479524,0.00206130625126 +13.19,51.0015657727,1.7137563025e-007,10.1747535812,20.0002297227,-0.00135776160412,-0.0860457714609,0.0115642121509,0.21244503554,7.98070817644e-005 +13.2,51.0015675704,1.71304097794e-007,10.1756263083,19.9996706335,0.000353511330831,-0.0884996519405,0.00991078538826,0.214249508876,0.00188153562145 +13.21,51.0015693681,1.71306370817e-007,10.1765175291,19.9972240625,-0.000321600151883,-0.0897445106938,0.0102695904157,0.216043893869,0.00169077859769 +13.22,51.0015711657,1.71269138114e-007,10.1774148555,19.9998887254,-0.000201112897837,-0.0897207610735,0.0107828139765,0.216849134754,0.00164327671966 +13.23,51.0015729635,1.7131363348e-007,10.1783143227,19.9996288498,0.000825787035532,-0.0901726857135,0.0128575313397,0.219494012987,0.00105095271079 +13.24,51.0015747612,1.71388741761e-007,10.179209901,19.9999525208,0.000228664360997,-0.0889429726436,0.0127056530961,0.217631462844,0.0001214469862 +13.25,51.0015765591,1.71367938611e-007,10.1800993628,20.00141366,-0.000520721485838,-0.0889493891922,0.0121589794245,0.218376884543,-0.000365019932849 +13.26,51.001578357,1.71333483538e-007,10.1809933468,20.000830223,3.70038849288e-005,-0.0898473944917,0.0124266583685,0.219157310064,0.000147158774692 +13.27,51.0015801548,1.71304840857e-007,10.1818898308,20.0013665724,-0.00043912079569,-0.0894494212776,0.012809585589,0.218854042037,0.000841505375009 +13.28,51.0015819527,1.71250204641e-007,10.1827816365,20.0001405678,-0.000327921462872,-0.0889117068718,0.0116823255023,0.221524419784,0.0015031974309 +13.29,51.0015837506,1.7123195741e-007,10.1836746351,20.0022300284,7.17471234906e-005,-0.0896880123326,0.013956045157,0.224876121042,0.00242509859606 +13.3,51.0015855485,1.71191348518e-007,10.1845688681,20.0011960502,-0.000641858589694,-0.0891585942454,0.0137681879866,0.223330740616,-0.00045928067516 +13.31,51.0015873464,1.71065187354e-007,10.1854622558,20.0021855875,-0.00112932795596,-0.0895189469928,0.013872868655,0.223107083271,-0.00020109114813 +13.32,51.0015891443,1.70949362795e-007,10.1863554691,20.0006858859,-0.000496742147507,-0.0891237141573,0.0134936993157,0.223421564558,0.000323608630047 +13.33,51.0015909422,1.70747463687e-007,10.1872487515,20.0005160669,-0.00233773515276,-0.0895327702327,0.0140112926918,0.227305803963,0.00250986076119 +13.34,51.0015927399,1.7043384391e-007,10.1881527527,19.9988835641,-0.0020651972119,-0.0912674689347,0.0136425110711,0.227432905651,0.00165942626974 +13.35,51.0015945376,1.70210846662e-007,10.189065606,19.9990951278,-0.00106547832824,-0.09130318971,0.0125272125977,0.225185297342,0.000505486272184 +13.36,51.0015963353,1.69984699419e-007,10.1899759295,19.9995189876,-0.00210942007939,-0.0907615107371,0.0138281622216,0.228285370993,0.00104149520963 +13.37,51.0015981331,1.69571252972e-007,10.1908815103,19.9996436472,-0.00369498594492,-0.0903546349803,0.0126093535345,0.230137847687,0.00173599696017 +13.38,51.0015999308,1.69064314167e-007,10.1917944409,19.9994313047,-0.00342196613832,-0.0922314909941,0.0144060844337,0.228514799343,-0.0001881820398 +13.39,51.0016017285,1.68671657286e-007,10.1927086556,19.9984841697,-0.0020905732085,-0.0906114406067,0.0129029376866,0.229839870423,0.000119591459913 +13.4,51.0016035261,1.68365153179e-007,10.1936142361,19.9990564935,-0.00221246071218,-0.0905046728314,0.0130844998938,0.231594412395,-0.00174916538699 +13.41,51.0016053238,1.67919382389e-007,10.1945278585,19.9991702552,-0.0040457482389,-0.0922197936257,0.0106183425947,0.23160869783,-0.0013985355482 +13.42,51.0016071216,1.67444396787e-007,10.1954537634,20.0005998592,-0.00262260941532,-0.0929612049564,0.0124461271391,0.232675898233,0.000792483349362 +13.43,51.0016089194,1.6719347958e-007,10.1963830195,19.9990691897,-0.000900035515783,-0.0928900126705,0.0140018549805,0.233914944493,0.000358835043447 +13.44,51.0016107171,1.6699705503e-007,10.1973072659,19.9997235351,-0.00185758288593,-0.0919592691883,0.0153242599376,0.235072835792,0.000496674268898 +13.45,51.0016125148,1.66648378383e-007,10.1982285881,19.999871974,-0.0030375134825,-0.092305158377,0.0147102489086,0.236206630301,0.000459899199924 +13.46,51.0016143126,1.66230643522e-007,10.1991661216,19.9989412719,-0.00282709590277,-0.0952015554057,0.0172307632571,0.236200689093,0.00162680476852 +13.47,51.0016161103,1.65863472767e-007,10.2001117818,19.9991280158,-0.00232764022183,-0.0939304658222,0.0159050921515,0.236709025141,0.00197873429814 +13.48,51.001617908,1.65620878958e-007,10.2010490472,20.0001616991,-0.00107815124743,-0.0935226228602,0.0169900355799,0.23860141669,0.00350081946494 +13.49,51.0016197057,1.65439649142e-007,10.2019897751,19.9980692294,-0.00146614670895,-0.0946229508309,0.0189687480701,0.240643758642,0.00212932766647 +13.5,51.0016215033,1.65219149345e-007,10.2029294699,19.9980946868,-0.00162946512,-0.0933160179553,0.0177931681713,0.240925283379,0.000535291431049 +13.51,51.0016233009,1.65091254947e-007,10.203858288,19.9987210177,-0.000166053105804,-0.0924475952283,0.0186568332559,0.241224648146,0.000268031827029 +13.52,51.0016250986,1.64966216115e-007,10.2047840163,19.9988718405,-0.00158937550526,-0.0926980659377,0.018735787123,0.243763587858,0.000502595108059 +13.53,51.0016268963,1.64742684465e-007,10.2057039421,20.0000795123,-0.00154880035024,-0.0912871044212,0.017705242496,0.245027758247,-0.000455777482544 +13.54,51.0016286942,1.64501072039e-007,10.2066218043,20.0009942084,-0.0018432126178,-0.0922853271882,0.0180180474597,0.245133595043,0.000620545418777 +13.55,51.0016304921,1.64398158305e-007,10.2075451478,20.0013046862,0.00039839985487,-0.0923833768358,0.0178554327405,0.24609885586,-0.00120056007943 +13.56,51.00163229,1.64340930577e-007,10.2084641234,20.0023389459,-0.00120182364272,-0.091411740047,0.0189622758966,0.247468887575,-0.00028384992293 +13.57,51.0016340879,1.64176081153e-007,10.2093803602,20.0013638333,-0.00111250815193,-0.0918356145005,0.0208325593619,0.248178907631,-0.000499649868501 +13.58,51.0016358858,1.63956825916e-007,10.2103030654,20.0013429586,-0.00196563026076,-0.0927054282049,0.0181148796994,0.248646167348,-0.00111274209852 +13.59,51.0016376837,1.63575791059e-007,10.2112276635,20.0014537642,-0.00338374244997,-0.092214188926,0.0176265369188,0.248386568936,-0.00141974338783 +13.6,51.0016394816,1.63187141503e-007,10.2121576193,20.0002167519,-0.00207253335057,-0.0937769722931,0.0195353876389,0.248655713032,-0.000266691241347 +13.61,51.0016412794,1.62919291252e-007,10.2130990153,20.0009064224,-0.00168783318105,-0.0945022322576,0.0205387209723,0.25051981202,0.00045630723469 +13.62,51.0016430773,1.62687771077e-007,10.214042585,20.0013720261,-0.00156249300752,-0.0942117181849,0.0179388274614,0.250592103188,0.000509000953138 +13.63,51.0016448751,1.625000332e-007,10.2149868427,19.9995481931,-0.00107317065371,-0.0946398219086,0.0179014034135,0.252018795731,0.00013364488098 +13.64,51.0016466728,1.62344982571e-007,10.2159332972,19.9980775397,-0.00110359463218,-0.0946510588461,0.0183394293153,0.253344641447,0.00151318952342 +13.65,51.0016484704,1.62121716089e-007,10.216898384,19.9974155473,-0.00203085705185,-0.0983663088377,0.0190483225012,0.256207443582,0.00253045647321 +13.66,51.001650268,1.61759918e-007,10.2178716625,19.9999452332,-0.00304844808412,-0.0962893915785,0.0201772651309,0.255144150143,0.00101867721343 +13.67,51.0016520657,1.61335071607e-007,10.2188431735,19.9969099611,-0.00291599578013,-0.0980128056953,0.0188664930658,0.254859627428,0.00220728962983 +13.68,51.0016538632,1.6088788896e-007,10.2198149834,19.9983004758,-0.00336202784042,-0.0963491875059,0.0202324897921,0.254858368443,0.00168772784872 +13.69,51.0016556608,1.60262275404e-007,10.220773895,19.9984437802,-0.00542099748938,-0.0954331213102,0.021276575301,0.258288463153,0.000694718143637 +13.7,51.0016574585,1.5962922808e-007,10.2217344559,19.9979609492,-0.00346639067424,-0.0966790542421,0.0226373293212,0.259749333565,0.000704837960067 +13.71,51.001659256,1.59155594601e-007,10.2227052905,19.9970511323,-0.00318297698414,-0.0974878717672,0.0198172189146,0.257871535848,-0.00147587925209 +13.72,51.0016610536,1.58713033307e-007,10.2236817033,19.9994835057,-0.00303016623204,-0.0977946906567,0.0211103911577,0.259681475334,-0.000859709046157 +13.73,51.0016628513,1.58235259e-007,10.224655301,19.9968324882,-0.00367733420813,-0.0969248449857,0.0205284693044,0.261551856222,-0.00121488912252 +13.74,51.0016646488,1.57781653861e-007,10.2256227507,19.9991530557,-0.00269085370937,-0.0965650928935,0.0201051177464,0.260001018656,0.00116041070302 +13.75,51.0016664466,1.57408717282e-007,10.2265863219,20.0005580392,-0.0025448235781,-0.0961491429553,0.0197642464691,0.259673725927,0.00106076148294 +13.76,51.0016682444,1.57010413876e-007,10.2275559303,20.0000221409,-0.0030469797598,-0.0977725539964,0.0214664660919,0.261760492503,-0.000115185739687 +13.77,51.0016700422,1.56647185809e-007,10.2285473978,19.999172169,-0.00205239879511,-0.100520929453,0.0225651047427,0.263648158008,0.00155186081273 +13.78,51.0016718398,1.56413759064e-007,10.2295471491,19.9980929404,-0.00122469183793,-0.0994293344007,0.0230531550928,0.262065457548,0.00108939684547 +13.79,51.0016736374,1.56233028321e-007,10.2305414168,19.9971845208,-0.00131259667471,-0.0994242171346,0.0222365610291,0.262664287152,0.000510638502107 +13.8,51.0016754349,1.56075972477e-007,10.2315286339,19.9976276503,-0.000892318587106,-0.098019192118,0.0230184148512,0.264050750044,-0.00139561485761 +13.81,51.0016772325,1.55989682044e-007,10.2325110873,19.9982060738,-0.000319117312005,-0.0984714893512,0.0239022281431,0.266162136216,-0.000673994465346 +13.82,51.0016790301,1.55894300496e-007,10.2334853352,19.9975769227,-0.00101994914442,-0.0963780921876,0.0231120181888,0.264874539156,-0.000222557582973 +13.83,51.0016808277,1.55694697077e-007,10.2344563186,19.9979598709,-0.00178229343023,-0.0978185932187,0.0243091617277,0.265260397864,-0.00038829352185 +13.84,51.0016826253,1.55494335212e-007,10.2354412842,19.9983723755,-0.00103059692129,-0.099174516927,0.0242445142319,0.268175447349,-2.45416329001e-005 +13.85,51.0016844229,1.55397235476e-007,10.2364301544,19.9990634694,-0.000332591138942,-0.0985995276087,0.0273370641455,0.26809767897,0.00191577038406 +13.86,51.0016862207,1.55195275548e-007,10.2374262925,19.9997644899,-0.00250273422379,-0.100628096664,0.0258338253801,0.270072819559,0.00106483331635 +13.87,51.0016880184,1.5499332945e-007,10.2384401125,19.9993889081,-0.000332396956464,-0.102135895157,0.0248907339227,0.270527107739,0.00046078622281 +13.88,51.0016898162,1.5485142845e-007,10.239459667,20.0003526809,-0.00165975801299,-0.101775015124,0.0255816361905,0.270038517426,0.00109917477799 +13.89,51.0016916141,1.54618116506e-007,10.2404713261,20.0026557747,-0.00161571951298,-0.10055679578,0.0263148630134,0.272009143742,0.00034518025283 +13.9,51.001693412,1.54433989191e-007,10.2414783053,20.0009268231,-0.000969252578426,-0.10083904993,0.0257605805711,0.27307167775,-0.000955283070337 +13.91,51.0016952099,1.54287830811e-007,10.2424858245,20.0005905679,-0.00108267174124,-0.10066479313,0.0248822497601,0.273671854774,0.000542715764895 +13.92,51.0016970077,1.54093093572e-007,10.2434973545,20.0005170814,-0.0016512533398,-0.101641197827,0.0256438019564,0.273519684671,-0.000411014325253 +13.93,51.0016988056,1.53887462533e-007,10.2445114298,20.0015448583,-0.00123561020057,-0.101173874692,0.0247145961602,0.27396014892,-0.000731149398396 +13.94,51.0017006035,1.53597956249e-007,10.2455283069,20.0009251422,-0.00282878153619,-0.102201535694,0.0261943833924,0.276267699168,2.28965471753e-006 +13.95,51.0017024014,1.53193560412e-007,10.2465441279,20.0019549988,-0.00284854963222,-0.100962661354,0.0260724298665,0.277575365125,-0.00168014610369 +13.96,51.0017041993,1.52792004884e-007,10.2475615369,20.001738711,-0.0027889060931,-0.102519134535,0.0267621427699,0.27752994212,0.0004298183385 +13.97,51.0017059972,1.52367243021e-007,10.2485897188,20.0006961583,-0.00317434416278,-0.103117254446,0.0275581941819,0.27726700328,-0.000972279378502 +13.98,51.0017077951,1.51937226418e-007,10.2496222835,20.0012016224,-0.00286267738941,-0.103395689256,0.0257998100926,0.278505736824,-0.000668313323527 +13.99,51.0017095929,1.51619875847e-007,10.2506591482,20.000769238,-0.00159262074136,-0.10397724784,0.0257743066145,0.280093643665,2.00068545874e-005 +14,51.0017113907,1.51229291274e-007,10.2516986999,20.0002009413,-0.00389081237587,-0.103933093071,0.0278033808196,0.280650103974,-0.000308646577113 +14.01,51.0017131884,1.50842572807e-007,10.2527378895,19.9980891325,-0.00153834420611,-0.103904829445,0.0267454841926,0.281430123681,-0.000428379178035 +14.02,51.0017149861,1.50569772616e-007,10.2537764159,19.9991364685,-0.00229150877518,-0.103800451178,0.0275591004726,0.280711841387,0.000551081491344 +14.03,51.0017167838,1.50317794847e-007,10.2548235511,19.9990939427,-0.00124601728468,-0.105626585702,0.0273214691992,0.282274723805,0.00115469588582 +14.04,51.0017185815,1.50166702011e-007,10.2558731922,19.9992218679,-0.000875181032123,-0.104301636727,0.0273145049144,0.282189651652,0.000279311759493 +14.05,51.0017203792,1.49999455289e-007,10.2569119944,19.9993504001,-0.00147280223968,-0.103458796448,0.0273026193749,0.283247541984,-0.00213866803785 +14.06,51.0017221769,1.49653707834e-007,10.2579527896,19.9983953009,-0.00338115958677,-0.104700254581,0.0294194875176,0.281909249294,-0.00148886634091 +14.07,51.0017239745,1.49248470916e-007,10.2590046597,19.9988443779,-0.00230797694131,-0.105673762041,0.0292010912116,0.284077399902,-0.00237522182633 +14.08,51.0017257723,1.49084073828e-007,10.2600580285,20,0,-0.105,0.03,0.286,0 +14.09,51.0017275699,1.50869254454e-007,10.2611226143,19.9978033986,0.0250622163466,-0.107917142395,0.0284626445669,0.285609345689,0.0709888557863 +14.1,51.0017293674,1.5620454304e-007,10.2622007576,19.9959877085,0.049840094026,-0.107711525,0.0302131519118,0.287136942313,0.143786926324 +14.11,51.0017311648,1.65001162485e-007,10.2632787079,19.9952535531,0.073655961668,-0.107878528585,0.0316472863388,0.286939549006,0.213493108711 +14.12,51.0017329621,1.77278706288e-007,10.2643553606,19.9926878861,0.0987089093923,-0.10745201553,0.0339804111763,0.288546916142,0.285658444348 +14.13,51.0017347592,1.93136754468e-007,10.2654337635,19.9921498633,0.123922780638,-0.108228560451,0.0337379624034,0.288342412709,0.354814123862 +14.14,51.0017365562,2.12520264262e-007,10.2665115432,19.9909230827,0.148202977274,-0.10732738819,0.0338976197136,0.290167057451,0.426458855265 +14.15,51.001738353,2.35449929504e-007,10.2675759725,19.9885942476,0.173707366128,-0.105558475175,0.0340222958613,0.290931414713,0.497984499252 +14.16,51.0017401498,2.62025270621e-007,10.2686432209,19.9879746221,0.199384729531,-0.107891199205,0.0343286291283,0.289985545197,0.569117598525 +14.17,51.0017419464,2.92096617608e-007,10.2697235967,19.9879928443,0.222787892377,-0.108183959262,0.0342643853971,0.291604431801,0.640015915266 +14.18,51.001743743,3.25615566636e-007,10.2708094342,19.9848627607,0.247785709063,-0.10898353576,0.0352067127616,0.289720504882,0.711950068219 +14.19,51.0017455395,3.62901561223e-007,10.2718959612,19.9860236092,0.275673545777,-0.108321868366,0.0342453173829,0.290366032781,0.782107216057 +14.2,51.0017473358,4.03923182634e-007,10.2729786887,19.9815647558,0.300230269929,-0.108223633346,0.0362027103301,0.292283785503,0.853877124735 +14.21,51.0017491319,4.48410740541e-007,10.2740578219,19.980810865,0.324331911812,-0.107603005066,0.0361206654881,0.292688933592,0.924177897475 +14.22,51.0017509279,4.96512461208e-007,10.2751407976,19.9789716948,0.35096958513,-0.108992147897,0.0400501660046,0.29473371157,0.995005051978 +14.23,51.0017527237,5.48285415661e-007,10.2762267311,19.9777746507,0.375872445012,-0.108194537417,0.0393966979179,0.294001452563,1.06332092557 +14.24,51.0017545194,6.03589629194e-007,10.2773138548,19.9762468217,0.400545005398,-0.109230215438,0.037215175028,0.296986772985,1.13617544754 +14.25,51.001756315,6.62445934419e-007,10.2784088683,19.9763825484,0.425740331085,-0.109772481134,0.0375290115399,0.296432653919,1.20609556705 +14.26,51.0017581106,7.24880765577e-007,10.2795127291,19.9746165933,0.450783998712,-0.110999676369,0.0385791209648,0.295612301824,1.27730409305 +14.27,51.001759906,7.90885671014e-007,10.2806254827,19.9727928141,0.475860667524,-0.111551035794,0.0369657350381,0.298376932351,1.34907129112 +14.28,51.0017617013,8.6043443498e-007,10.281743488,19.9710960314,0.500536287695,-0.112050035031,0.0400224721993,0.298418965245,1.41931414045 +14.29,51.0017634963,9.33526521532e-007,10.2828595266,19.9680501617,0.52560542857,-0.111157687059,0.0394365655407,0.299618155481,1.48837268315 +14.3,51.0017652911,1.01016495634e-006,10.2839820215,19.9659166354,0.550323522422,-0.113341282577,0.0404035122872,0.298838906522,1.56167362128 +14.31,51.0017670858,1.09041437957e-006,10.2851180104,19.9652157245,0.576300144269,-0.11385650625,0.0393012455025,0.301303700201,1.63253549613 +14.32,51.0017688804,1.1742287192e-006,10.2862505314,19.9631438323,0.600371428146,-0.112647680799,0.0406987517787,0.303075598352,1.7035768426 +14.33,51.0017706748,1.26151727207e-006,10.2873775567,19.9619420304,0.625074662119,-0.112757396273,0.0379888892737,0.30256231297,1.7751456481 +14.34,51.0017724691,1.35240590108e-006,10.2884989445,19.9602250886,0.650912934625,-0.111520155872,0.0410669968014,0.305688852033,1.84558363558 +14.35,51.0017742632,1.44693027293e-006,10.2896218701,19.9577844621,0.676116890377,-0.113064956358,0.0426642205948,0.306963090949,1.91909917625 +14.36,51.0017760572,1.54503523437e-006,10.2907499786,19.9582139304,0.701180861094,-0.112556746233,0.0419400855925,0.307787754504,1.98909775361 +14.37,51.0017778512,1.64675337313e-006,10.2918848417,19.9578822779,0.726842312824,-0.114415873382,0.0414371986094,0.308661827032,2.05863552854 +14.38,51.0017796451,1.75210400161e-006,10.2930323369,19.9572703144,0.752177407094,-0.115083168498,0.04241056051,0.309823468218,2.13159062514 +14.39,51.0017814389,1.8609870034e-006,10.2941915542,19.9528186864,0.776433318239,-0.11676030339,0.0437653798497,0.30892427595,2.20198341966 +14.4,51.0017832324,1.97337249345e-006,10.2953559347,19.9516911069,0.801348852139,-0.116115797339,0.0428930206236,0.309558839724,2.27246369544 +14.41,51.0017850257,2.08932560392e-006,10.296508545,19.9490076734,0.826519151145,-0.114406257521,0.0446143959949,0.307034302816,2.34290633617 +14.42,51.0017868189,2.20881405545e-006,10.2976581135,19.9488855707,0.850981510622,-0.115507447505,0.0470849933347,0.309552719852,2.41455730863 +14.43,51.001788612,2.3317866575e-006,10.2988137206,19.9469405314,0.875433140713,-0.115613958004,0.0483121588812,0.309165125237,2.48501144912 +14.44,51.0017904048,2.45831419403e-006,10.2999735102,19.9442116302,0.900889233993,-0.116343975342,0.0454486042107,0.309962987899,2.55639244664 +14.45,51.0017921974,2.58845466445e-006,10.3011444425,19.9405786365,0.926155114927,-0.117842472295,0.0456379229265,0.308969133322,2.62694495705 +14.46,51.0017939899,2.72216623767e-006,10.3023180238,19.9408628666,0.95102393697,-0.116873797649,0.0488757967677,0.311216437632,2.6992470171 +14.47,51.0017957823,2.85940338858e-006,10.3034734107,19.9390598697,0.9756506861,-0.114203582391,0.0492282958428,0.312992244856,2.7664207055 +14.48,51.0017975745,3.00023633325e-006,10.3046300198,19.938557535,1.00150526899,-0.117118238821,0.0484370534425,0.315042535242,2.8390745727 +14.49,51.0017993666,3.14479646119e-006,10.3058061272,19.9337053933,1.02797659376,-0.118103226509,0.046308162076,0.314272565946,2.91009913705 +14.5,51.0018011585,3.29289259245e-006,10.3069864409,19.9350999593,1.05114719433,-0.117959516534,0.0463790003427,0.315866570911,2.97938633511 +14.51,51.0018029503,3.44427176381e-006,10.30816737,19.9327474289,1.0740671611,-0.118226299564,0.046708583239,0.316149964328,3.05070471932 +14.52,51.001804742,3.59914359858e-006,10.309345461,19.9311548391,1.10018066249,-0.11739191739,0.0483876167836,0.317889827942,3.12201132268 +14.53,51.0018065335,3.7577732895e-006,10.3105242151,19.9298813727,1.12682367021,-0.11835889916,0.0494913764443,0.31790861676,3.19319238686 +14.54,51.0018083249,3.92011465824e-006,10.3117079654,19.9288427967,1.15228886923,-0.118391150256,0.0505167473158,0.320631370785,3.26577875304 +14.55,51.0018101162,4.0859472484e-006,10.3128937385,19.9270720608,1.17583688276,-0.118763479371,0.0512813201046,0.324664162911,3.33927523676 +14.56,51.0018119074,4.25529423542e-006,10.3140864374,19.9257302527,1.20162743852,-0.119776294984,0.0523792686678,0.322832245045,3.41082872244 +14.57,51.0018136984,4.4283140883e-006,10.3152894047,19.9229752223,1.22740019637,-0.120817171633,0.0527016614798,0.3241062055,3.48141824111 +14.58,51.0018154892,4.60494072094e-006,10.3164988353,19.9229576557,1.25226296443,-0.121068941376,0.0530134691886,0.323870655175,3.55370184296 +14.59,51.00181728,4.78510623356e-006,10.3177143143,19.9217061136,1.27708247297,-0.122026863115,0.0535400475275,0.325116942904,3.62375300764 +14.6,51.0018190707,4.96882129251e-006,10.3189439183,19.9208818527,1.30209498219,-0.123893938883,0.0551366782603,0.326331530815,3.69522638136 +14.61,51.0018208613,5.15602478261e-006,10.320185677,19.9190746726,1.32605649034,-0.124457796182,0.0558372564002,0.328598641031,3.7655297551 +14.62,51.0018226517,5.34667889065e-006,10.3214411471,19.9166699092,1.35053813572,-0.126636229941,0.0553780858524,0.3283985765,3.83894332571 +14.63,51.0018244419,5.54093484307e-006,10.3227172413,19.9143458333,1.37662270955,-0.128582599108,0.0558561974491,0.328774601358,3.90874793722 +14.64,51.0018262319,5.7388824568e-006,10.3239934985,19.9131788574,1.40236529146,-0.126668842166,0.0559215251987,0.329754967362,3.98003160205 +14.65,51.0018280218,5.94028798056e-006,10.3252566788,19.9107281838,1.42516822566,-0.125967218309,0.056303375215,0.329626614161,4.05112173018 +14.66,51.0018298115,6.14516933466e-006,10.3265184609,19.9106675063,1.45116238715,-0.126389204605,0.055225868826,0.330656511779,4.12237364297 +14.67,51.0018316012,6.35373207732e-006,10.3277883183,19.9095162515,1.47685115063,-0.12758226798,0.0586263180412,0.332370179167,4.19327426263 +14.68,51.0018333907,6.56585315254e-006,10.3290669032,19.9072719406,1.50111772438,-0.128134714855,0.0562138576653,0.331920161152,4.26540490954 +14.69,51.0018351802,6.78143413823e-006,10.3303532009,19.9069021438,1.52542473581,-0.129124834849,0.0548707467475,0.332422415592,4.33493703763 +14.7,51.0018369694,7.00049077101e-006,10.3316391245,19.9035131193,1.54991223226,-0.128059870734,0.0558693473507,0.334354318841,4.40752798918 +14.71,51.0018387584,7.22328452356e-006,10.3329181306,19.9017328697,1.57789005604,-0.127741366073,0.0570746319649,0.332967597876,4.47570574285 +14.72,51.0018405473,7.44973860836e-006,10.3341945864,19.9004228604,1.6012995283,-0.127549793234,0.057952922957,0.334935116489,4.54962390071 +14.73,51.001842336,7.67958367919e-006,10.3354611399,19.8970322032,1.62549599562,-0.125760903005,0.0611403212822,0.334558808288,4.61994537142 +14.74,51.0018441246,7.91303579674e-006,10.3367274752,19.8984679866,1.65193874094,-0.127506162126,0.0607995717408,0.337651474938,4.69116313037 +14.75,51.0018459131,8.15010682734e-006,10.3379978387,19.8960037106,1.67630179569,-0.126566532519,0.0609860168674,0.336350631792,4.76335713635 +14.76,51.0018477015,8.39062978126e-006,10.3392661419,19.8943931072,1.7004001683,-0.127094106559,0.0616842273364,0.339189955211,4.83492966954 +14.77,51.0018494896,8.63474040714e-006,10.3405423428,19.8908229328,1.72666899444,-0.128146077285,0.0599188058043,0.339857155722,4.90535332899 +14.78,51.0018512776,8.88251465604e-006,10.3418314738,19.8911420759,1.75183364009,-0.129680123244,0.0605195635944,0.339977015241,4.97796539087 +14.79,51.0018530655,9.13382895991e-006,10.3431249826,19.8886532946,1.77636769072,-0.129021630534,0.0638966273869,0.341406325719,5.0469929969 +14.8,51.0018548532,9.38871112218e-006,10.3444253107,19.8876941954,1.80192266465,-0.131043983822,0.0637204630236,0.342273621855,5.1188384517 +14.81,51.0018566408,9.64739067351e-006,10.3457456796,19.8862851236,1.82967909229,-0.133029804734,0.064986317596,0.344711030825,5.19090229226 +14.82,51.0018584283,9.90965970925e-006,10.3470773837,19.8847894845,1.85231528911,-0.133311005683,0.0655427608384,0.343452142926,5.26205822872 +14.83,51.0018602155,1.01752064453e-005,10.3484073521,19.8807109976,1.87569457715,-0.132682681336,0.0652808162318,0.34457087728,5.33284146694 +14.84,51.0018620025,1.04442591778e-005,10.3497318764,19.8793714155,1.90153581856,-0.132222180496,0.0657109043558,0.34445869832,5.40333933186 +14.85,51.0018637894,1.07169566427e-005,10.3510530038,19.8778153859,1.92686281673,-0.132003304216,0.0669433800818,0.344101153214,5.47325833366 +14.86,51.0018655762,1.09932363149e-005,10.3523694057,19.8771163395,1.9518262639,-0.131277065631,0.0670696205805,0.34640400725,5.54583499453 +14.87,51.0018673628,1.12731178782e-005,10.3536829265,19.8753712037,1.9774296007,-0.131427104045,0.0658373651599,0.346285443726,5.61618593397 +14.88,51.0018691493,1.15565226408e-005,10.3550051172,19.8735482983,2.00128828809,-0.133011038939,0.0667660627947,0.34694453742,5.68704938623 +14.89,51.0018709357,1.18434583477e-005,10.3563334806,19.8725677462,2.02700035493,-0.13266162816,0.066509848512,0.347326157144,5.75796158191 +14.9,51.001872722,1.21339189197e-005,10.3576704182,19.8719218181,2.05077369225,-0.134725903843,0.0677636498816,0.348995434002,5.82992991781 +14.91,51.0018745081,1.24279490319e-005,10.3590193755,19.8689464793,2.07711294819,-0.13506553792,0.0672757651449,0.350954416992,5.90103793844 +14.92,51.0018762941,1.2725591169e-005,10.3603673014,19.8680742135,2.10148272433,-0.134519643501,0.0658614487486,0.350729322127,5.97233289202 +14.93,51.00187808,1.30266581002e-005,10.3617043425,19.867777174,2.12519344567,-0.132888583983,0.0665076442445,0.3532392117,6.04275852017 +14.94,51.0018798657,1.33311351182e-005,10.3630393169,19.8651992756,2.14935674055,-0.134106287951,0.0651027628795,0.352938599457,6.11383110562 +14.95,51.0018816513,1.3639264893e-005,10.3643832164,19.8639322085,2.17647430147,-0.134673629613,0.0704376202567,0.353911014901,6.18346024379 +14.96,51.0018834368,1.39510241955e-005,10.3657391246,19.861464805,2.20031147932,-0.136508008204,0.0708026991599,0.353470172029,6.25508827667 +14.97,51.0018852221,1.4266085715e-005,10.3671030952,19.8605636003,2.22283392601,-0.136286111583,0.0702036645921,0.355134353169,6.32608148215 +14.98,51.0018870073,1.45846002361e-005,10.3684756207,19.8599006498,2.24878796088,-0.138218991184,0.0714451628378,0.355324846737,6.39809146978 +14.99,51.0018887924,1.49067660014e-005,10.3698542879,19.8576962033,2.27409353057,-0.137514431445,0.0727372125537,0.354948471601,6.46836373762 +15,51.0018905773,1.52324729982e-005,10.3712356095,19.8561191077,2.29850309472,-0.138749906153,0.0720269149832,0.355434045171,6.54078491067 +15.01,51.001892362,1.55616954325e-005,10.3726147105,19.8537580127,2.32344653983,-0.137070280387,0.0743710014186,0.354928422788,6.61085728926 +15.02,51.0018941466,1.5894482947e-005,10.3739858994,19.8525091626,2.34855303275,-0.137167511801,0.0740301487831,0.356461628631,6.68279617455 +15.03,51.001895931,1.62308663737e-005,10.3753608074,19.8490847934,2.37392932462,-0.137814078107,0.0734627905202,0.359111954046,6.7547562536 +15.04,51.0018977151,1.65708424846e-005,10.3767435429,19.8478525951,2.3989904949,-0.13873302038,0.0742351288515,0.358716984364,6.82386858762 +15.05,51.0018994991,1.69144071913e-005,10.3781343724,19.8457487358,2.42430938619,-0.139432883502,0.073110806737,0.359028811486,6.893756569 +15.06,51.001901283,1.72616156366e-005,10.3795324548,19.8453365566,2.45014470223,-0.14018359247,0.0732231860346,0.358264865242,6.96468827734 +15.07,51.0019030668,1.76123854845e-005,10.3809332356,19.8444711454,2.47430767516,-0.139972571689,0.0752051537897,0.357955144093,7.03516289399 +15.08,51.0019048505,1.79666791294e-005,10.3823314216,19.8422839111,2.4996150433,-0.139664625273,0.0744492834034,0.359266316122,7.10707560574 +15.09,51.0019066341,1.83245319059e-005,10.3837288624,19.8403816966,2.52427407444,-0.139823545561,0.0766849003576,0.361520078201,7.17675370556 +15.1,51.0019084175,1.86858124191e-005,10.3851263996,19.8400012829,2.54773678744,-0.139683882257,0.0759800043302,0.361797716162,7.24727342888 +15.11,51.0019102007,1.90505778639e-005,10.3865132567,19.8373013643,2.57319877457,-0.137687543042,0.0777996381538,0.362606579888,7.32090910263 +15.12,51.0019119838,1.94189723727e-005,10.3879040048,19.8361557758,2.59868495437,-0.1404620824,0.0772481599731,0.364922467827,7.39160840006 +15.13,51.0019137669,1.97908904672e-005,10.3893152629,19.8361444751,2.62266613041,-0.141789522963,0.0786262543132,0.366051510443,7.46073978427 +15.14,51.0019155498,2.01663792761e-005,10.3907314392,19.8327584088,2.64881394467,-0.141445741242,0.0782778859502,0.366698814256,7.53159480835 +15.15,51.0019173325,2.05455236919e-005,10.3921449809,19.8318793346,2.67398692215,-0.141262606536,0.0805703692348,0.366621531608,7.60439104947 +15.16,51.001919115,2.09283125273e-005,10.3935587747,19.8284271452,2.6999776736,-0.141496140169,0.0803463745895,0.367298276224,7.67486488288 +15.17,51.0019208973,2.13146170169e-005,10.394974784,19.8271734872,2.72334291312,-0.141705723611,0.0816053888152,0.36959624128,7.74497042005 +15.18,51.0019226795,2.17042764946e-005,10.3963830205,19.826412998,2.7470780724,-0.139941572322,0.0813532434129,0.367687829306,7.81549784973 +15.19,51.0019244617,2.20975734022e-005,10.3977916911,19.8260566943,2.77440850225,-0.14179256281,0.0807019512965,0.367765907025,7.88748445205 +15.2,51.0019262437,2.24946197736e-005,10.3992170315,19.8239810967,2.79971649955,-0.143275504354,0.0819455447394,0.369715293698,7.95987257962 +15.21,51.0019280256,2.28953119409e-005,10.4006497155,19.8227714123,2.82559153422,-0.143261300977,0.07918807705,0.370400514142,8.0322462812 +15.22,51.0019298074,2.32996710162e-005,10.4020960095,19.8216003163,2.85119591914,-0.145997499771,0.0829476555168,0.371230820882,8.10490681416 +15.23,51.0019315891,2.37075856095e-005,10.403546928,19.8195097974,2.87550714905,-0.144186207302,0.0816318708907,0.375614371405,8.17470326379 +15.24,51.0019333705,2.41189470994e-005,10.4049972299,19.8177657407,2.89958659742,-0.145874164498,0.0827643551719,0.373362009769,8.24618618742 +15.25,51.0019351519,2.45338681113e-005,10.4064506344,19.8173142826,2.92547896745,-0.144806747636,0.0835744311819,0.377078138283,8.31772367833 +15.26,51.0019369332,2.49523983037e-005,10.4079019336,19.816417939,2.9502555678,-0.145453073067,0.0833198873826,0.374330159107,8.38912412178 +15.27,51.0019387145,2.53745159361e-005,10.409362892,19.816636672,2.97584271918,-0.146738621118,0.0833889895738,0.375287099454,8.46033673723 +15.28,51.0019404956,2.58001557407e-005,10.4108313154,19.8128115481,2.99970302318,-0.146946060039,0.0868638071359,0.374505334534,8.53026605723 +15.29,51.0019422765,2.62291450996e-005,10.4122973653,19.8108924766,3.02286679095,-0.146263913715,0.0894339346846,0.374989486904,8.60228723902 +15.3,51.0019440572,2.66617325773e-005,10.413762207,19.8098564294,3.05021668431,-0.146704428355,0.0893148085485,0.374743615978,8.6731506954 +15.31,51.0019458378,2.70981030274e-005,10.4152314056,19.8072757582,3.07597560194,-0.147135293423,0.0912714242747,0.378048439911,8.74437617147 +15.32,51.0019476182,2.75380560755e-005,10.4167058208,19.8058570381,3.10051243836,-0.147747747556,0.0901985213424,0.378769045347,8.8155481711 +15.33,51.0019493984,2.79816069162e-005,10.4181925017,19.8041678403,3.12648467287,-0.149588423253,0.0893144665176,0.381326740593,8.88408411815 +15.34,51.0019511785,2.84287752537e-005,10.4196850392,19.8019366191,3.15129812865,-0.148919071771,0.0889442057311,0.379287387712,8.95750974858 +15.35,51.0019529584,2.8879429841e-005,10.4211775189,19.8003558831,3.17542778808,-0.149576872485,0.0900962252254,0.38208811559,9.02872874314 +15.36,51.0019547382,2.93335534945e-005,10.4226654032,19.8,3.2,-0.148,0.09,0.382,9.1 +15.37,51.0019565178,2.97909054557e-005,10.4241398245,19.7944037227,3.22074965604,-0.146884247463,0.0897708308479,0.384967491944,9.17123835104 +15.38,51.0019582968,3.0251383493e-005,10.4256057373,19.7872709705,3.24388663599,-0.146298325093,0.0888189764358,0.38428081477,9.24220075131 +15.39,51.0019600752,3.0715046229e-005,10.4270699493,19.7831107555,3.26545929176,-0.146544060323,0.0914513825052,0.385312907565,9.31250728646 +15.4,51.0019618531,3.11818073623e-005,10.4285468209,19.774093881,3.28738468379,-0.148830266429,0.0890354527513,0.386859599589,9.38346029601 +15.41,51.0019636302,3.16516885193e-005,10.4300462367,19.766104981,3.30926095096,-0.151052885013,0.0886088881825,0.386224358579,9.45307790975 +15.42,51.0019654068,3.212472114e-005,10.4315555872,19.7621946555,3.33162772371,-0.150817221002,0.0891856474522,0.387760031873,9.52148184871 +15.43,51.0019671829,3.26009052898e-005,10.4330577531,19.7559210797,3.35350490588,-0.149615956059,0.090397345563,0.387877764793,9.59198486636 +15.44,51.0019689585,3.30801400892e-005,10.4345588774,19.7498089155,3.37445543097,-0.150608913454,0.0894311566188,0.387645742482,9.66256588399 +15.45,51.0019707334,3.35622656593e-005,10.4360640336,19.7421374548,3.39408807626,-0.150422315436,0.0874039989983,0.388130795606,9.73334373166 +15.46,51.0019725077,3.40473988479e-005,10.4375662502,19.7357886435,3.41667902052,-0.150021008709,0.0867758232679,0.39125352871,9.80170834797 +15.47,51.0019742815,3.45359559866e-005,10.4390664843,19.7302060116,3.4421565274,-0.150025815562,0.0874649152216,0.39251767327,9.87130098612 +15.48,51.0019760547,3.50277973845e-005,10.440562699,19.7235340861,3.4627863519,-0.149217114068,0.0884601240055,0.393726014414,9.94296722216 +15.49,51.0019778274,3.55227548366e-005,10.4420587252,19.7170829069,3.48590243051,-0.149988145325,0.0869759746165,0.394183899642,10.0151046822 +15.5,51.0019795994,3.60208073248e-005,10.4435682687,19.7104388049,3.50623718253,-0.151920548837,0.0880969444114,0.392406632753,10.0856793094 +15.51,51.0019813709,3.65218288595e-005,10.4450844013,19.7051391812,3.52758449267,-0.151305968155,0.0898605642517,0.392016188139,10.1570104595 +15.52,51.0019831419,3.70259664429e-005,10.4465978106,19.6987192472,3.54998299892,-0.151375895309,0.0904356507153,0.395796158207,10.2262524539 +15.53,51.0019849123,3.75332995489e-005,10.4481108788,19.69247682,3.57244603902,-0.151237743547,0.09106514841,0.398031701148,10.2968885786 +15.54,51.0019866822,3.8043708023e-005,10.4496288825,19.6866584308,3.593157697,-0.152362996765,0.0905555207534,0.398651481284,10.3663503164 +15.55,51.0019884515,3.85572021074e-005,10.4511544492,19.6794803525,3.61576452433,-0.152750346642,0.0900611980986,0.400232709249,10.4382487833 +15.56,51.0019902202,3.9073832871e-005,10.4526813993,19.6741645092,3.63719313044,-0.152639660963,0.0910568018932,0.398712432652,10.5074249262 +15.57,51.0019919884,3.95934671617e-005,10.4542115096,19.6681942122,3.65793064138,-0.153382401841,0.0920361598537,0.399560560091,10.576355286 +15.58,51.0019937561,4.01162152787e-005,10.4557498385,19.6613089669,3.68090772832,-0.154283388835,0.091950072715,0.400375900909,10.6459909331 +15.59,51.0019955232,4.06422613612e-005,10.457288289,19.6561708861,3.70423035846,-0.153406707459,0.0924591801533,0.400919765791,10.7193392314 +15.6,51.0019972897,4.11713659284e-005,10.458820186,19.6476308328,3.72384538243,-0.15297267865,0.0927975943407,0.400102781161,10.7876391518 +15.61,51.0019990555,4.1703341144e-005,10.4603443884,19.6428804452,3.74453098235,-0.151867804499,0.0918019494474,0.400530912291,10.8577913054 +15.62,51.0020008209,4.22383013449e-005,10.4618716895,19.6365112194,3.76575117622,-0.153592418781,0.0915821959366,0.400685177023,10.9295988659 +15.63,51.0020025857,4.2776364461e-005,10.4633956249,19.6297202606,3.78809238301,-0.151194661547,0.0910973703665,0.402050353337,10.9985145223 +15.64,51.00200435,4.33178033727e-005,10.4649116336,19.6244679447,3.81314352979,-0.15200708591,0.0931280419014,0.401475825026,11.0693479525 +15.65,51.0020061137,4.3862528582e-005,10.4664378858,19.6178195258,3.83422827674,-0.153243344806,0.0926763148187,0.402989772668,11.1420644409 +15.66,51.0020078768,4.4410329942e-005,10.4679706875,19.6110722393,3.85632917544,-0.153316994954,0.0928725755116,0.403042791826,11.2119832935 +15.67,51.0020096393,4.49613913766e-005,10.4695173626,19.6043466555,3.8799960192,-0.156018024629,0.0895569051231,0.40453073296,11.282932589 +15.68,51.0020114013,4.55156896832e-005,10.4710766901,19.5983799492,3.90177117435,-0.155847473102,0.0925562735436,0.406209887122,11.3513456465 +15.69,51.0020131627,4.60731647952e-005,10.4726430381,19.59233063,3.92459474262,-0.157422131521,0.0923030667697,0.408010131978,11.4217942453 +15.7,51.0020149236,4.66337948482e-005,10.4742145106,19.5873496506,3.94606294075,-0.156872365462,0.0942524719367,0.409666703239,11.4911347033 +15.71,51.002016684,4.71976455602e-005,10.4757841457,19.5819820054,3.96980911709,-0.157054651993,0.0936643554141,0.409466577059,11.5607970761 +15.72,51.0020184438,4.77647758267e-005,10.477355517,19.5723362381,3.99210414442,-0.157219610534,0.0955778252226,0.408989558678,11.6322589584 +15.73,51.0020202029,4.83350237547e-005,10.4789321768,19.5674639645,4.01357750997,-0.158112358689,0.0967111028992,0.408683753493,11.7030240723 +15.74,51.0020219615,4.89082888014e-005,10.4805116001,19.5603683466,4.03446101696,-0.157772298498,0.0961147228289,0.409107866836,11.7719438364 +15.75,51.0020237195,4.94844327447e-005,10.4820891837,19.5555301645,4.05399388822,-0.157744413152,0.0936371848715,0.411019461514,11.8418228589 +15.76,51.002025477,5.00636918949e-005,10.4836666987,19.5478192758,4.07819493923,-0.157758599148,0.0934102572089,0.411580563643,11.914364037 +15.77,51.0020272339,5.06460621618e-005,10.4852442237,19.5420756074,4.09767038689,-0.157746404454,0.0932169440192,0.412362725098,11.9846284813 +15.78,51.0020289902,5.12313636219e-005,10.4868341241,19.5351744965,4.1193454961,-0.160233670783,0.0932486168915,0.412521043972,12.0563664425 +15.79,51.0020307459,5.18199020902e-005,10.4884310668,19.5281891659,4.14311426084,-0.159154865793,0.0932059843687,0.415346430112,12.127036377 +15.8,51.002032501,5.2411639293e-005,10.4900344877,19.5223665683,4.16425204693,-0.161529321164,0.0942164896211,0.414712103246,12.1972668808 +15.81,51.0020342555,5.30064061059e-005,10.4916546856,19.5144295092,4.18564647865,-0.162510245101,0.0940496036606,0.4149745023,12.2655146706 +15.82,51.0020360094,5.36042534023e-005,10.4932701952,19.5089832991,4.20749847048,-0.160591681994,0.0926353023403,0.417007154086,12.3364625361 +15.83,51.0020377628,5.42053068387e-005,10.494878219,19.5046875965,4.23065698373,-0.161013075043,0.0932940058939,0.415360815825,12.404827824 +15.84,51.0020395158,5.48094999865e-005,10.4964882657,19.4992753556,4.25157638494,-0.160996264916,0.0941010250434,0.418290646204,12.4750570444 +15.85,51.0020412683,5.54167059621e-005,10.4980916361,19.4933733807,4.27295358363,-0.159677824197,0.0941162636515,0.420396253839,12.5464287844 +15.86,51.0020430202,5.60269416501e-005,10.4996946812,19.4865020795,4.29411002457,-0.160931193839,0.0941228640764,0.419664574035,12.617731342 +15.87,51.0020447717,5.66401807211e-005,10.5013054036,19.4817125582,4.31511758079,-0.161213274911,0.0932875216044,0.420645081061,12.6866851485 +15.88,51.0020465226,5.72565881343e-005,10.5029205243,19.476439348,4.33858987254,-0.161810863346,0.0945006438392,0.421206940101,12.7583551453 +15.89,51.0020482729,5.7876375361e-005,10.5045472802,19.4679268225,4.36256625906,-0.163540327766,0.09358011717,0.422557517931,12.8272344402 +15.9,51.0020500226,5.84994557425e-005,10.5061776852,19.4605228352,4.38482195171,-0.162540663384,0.0935108874423,0.422316504128,12.8997875371 +15.91,51.0020517716,5.91255267287e-005,10.5077903508,19.4542015585,4.40455084951,-0.159992465631,0.0929852899733,0.421575296929,12.9700948717 +15.92,51.00205352,5.97546012565e-005,10.5094018182,19.4488034515,4.42698816329,-0.162301003516,0.095032175718,0.423724343755,13.0406336942 +15.93,51.002055268,6.03867741733e-005,10.5110302019,19.4427603125,4.44804861094,-0.163375751988,0.0956764353271,0.42450567201,13.1128645914 +15.94,51.0020570154,6.10220138438e-005,10.5126611135,19.4359926207,4.47004179808,-0.162806557812,0.097279840775,0.424356850501,13.1832182076 +15.95,51.0020587621,6.16603324724e-005,10.5142889824,19.4292935549,4.49127357946,-0.162767234917,0.096680747501,0.424558620003,13.2541191935 +15.96,51.0020605084,6.23017717287e-005,10.5159204264,19.4237517518,4.51385175845,-0.163521558191,0.0972106871911,0.425530808085,13.3224020814 +15.97,51.0020622541,6.29464461596e-005,10.5175603946,19.4181272203,4.53669165554,-0.164472086185,0.0950694687101,0.42774895682,13.3928892663 +15.98,51.0020639993,6.3594156654e-005,10.5192050965,19.4117159532,4.5564745224,-0.164468292491,0.0961751218736,0.428815196062,13.4632488096 +15.99,51.002065744,6.42448646995e-005,10.5208505103,19.4074301008,4.5787737432,-0.164614469217,0.0945367855059,0.430381164036,13.5337236151 +16,51.0020674881,6.4898752306e-005,10.5224936202,19.3987854344,4.60111183287,-0.164007496955,0.0960298692754,0.431432257306,13.6016643182 +16.01,51.0020692317,6.55556745716e-005,10.5241391318,19.3944745804,4.62137677997,-0.165094825442,0.0966926057307,0.430863397883,13.6718093249 +16.02,51.0020709747,6.62156846554e-005,10.5257873062,19.3878873396,4.64446116707,-0.164540049186,0.0976287001819,0.432203956093,13.7409298168 +16.03,51.0020727171,6.68788914122e-005,10.5274291916,19.3806836382,4.66625431364,-0.163837042271,0.0974011980886,0.433342640671,13.810506004 +16.04,51.0020744589,6.75452557564e-005,10.5290730817,19.3724322847,4.68878997764,-0.164940977247,0.0983495802255,0.432738753907,13.8812140428 +16.05,51.0020761999,6.82148548991e-005,10.5307207487,19.365185145,4.71166708327,-0.164592422364,0.0999450679498,0.435241650437,13.9520829602 +16.06,51.0020779404,6.88875406906e-005,10.5323753429,19.3592442011,4.73212288194,-0.166326410525,0.0997429599169,0.436507374283,14.0234540367 +16.07,51.0020796804,6.95631190685e-005,10.5340425772,19.3554797004,4.75227555296,-0.167120446563,0.0989201022767,0.435947803341,14.0938344888 +16.08,51.0020814199,7.02416985588e-005,10.5357046464,19.347791741,4.77425493798,-0.16529340897,0.0973025002501,0.436029182965,14.163982175 +16.09,51.0020831587,7.09234357602e-005,10.5373581853,19.3417441521,4.7966060867,-0.165414354569,0.0989207584021,0.435300982191,14.2347145062 +16.1,51.0020848971,7.16083631412e-005,10.5390158675,19.3359136059,4.81904128915,-0.166122095627,0.0977287837624,0.437399897034,14.303878178 +16.11,51.0020866349,7.22963297438e-005,10.540672501,19.3307808457,4.83927314781,-0.165204594902,0.0969630599067,0.437262159497,14.374837138 +16.12,51.0020883723,7.29873943435e-005,10.5423287726,19.3240823764,4.86253348986,-0.166049736091,0.097118069654,0.438025787195,14.4452389809 +16.13,51.002090109,7.36816384019e-005,10.5439912392,19.3181750993,4.88390898202,-0.166443577572,0.0962885827597,0.439052191977,14.5157057573 +16.14,51.0020918452,7.43789869751e-005,10.5456549324,19.3108029487,4.90611718566,-0.1662950586,0.0983177268294,0.43799907065,14.5854883673 +16.15,51.0020935808,7.5079563011e-005,10.5473098008,19.3056315654,4.92921873407,-0.164678630495,0.100196608272,0.44093144021,14.6543352442 +16.16,51.0020953158,7.57833088176e-005,10.5489638927,19.2986771745,4.95061699882,-0.166139744768,0.0992109084274,0.442643252783,14.7249617607 +16.17,51.0020970502,7.64900573675e-005,10.5506234439,19.2914488661,4.97137366044,-0.165770506229,0.100535369929,0.44484293057,14.7941736047 +16.18,51.0020987841,7.71999383897e-005,10.5522858217,19.2857363239,4.99459317659,-0.166705054288,0.0993732109813,0.443937370614,14.8642955688 +16.19,51.0021005174,7.79129310631e-005,10.5539427399,19.2814724924,5.01505752865,-0.164678570847,0.100156802106,0.444911862005,14.9355497355 +16.2,51.0021022503,7.8629073476e-005,10.5555998757,19.2748275363,5.03881176202,-0.166748591788,0.100866506595,0.445973925761,15.0069226107 +16.21,51.0021039826,7.934848814e-005,10.5572643931,19.2675606517,5.06099604122,-0.166154901742,0.101129885773,0.447255121252,15.0760475266 +16.22,51.0021057142,8.00710337517e-005,10.5589284864,19.259983487,5.08276652382,-0.166663756794,0.0986402157036,0.446818871435,15.1468653257 +16.23,51.0021074452,8.07965862864e-005,10.5605933694,19.2547691387,5.10320962815,-0.166312837986,0.0986256778698,0.449804762641,15.2183103982 +16.24,51.0021091757,8.15252262694e-005,10.5622612343,19.2478387207,5.12611059277,-0.167260138714,0.0978019046973,0.449333970438,15.2895408412 +16.25,51.0021109056,8.22570580454e-005,10.5639310667,19.242663411,5.14801858396,-0.166706336724,0.100248411776,0.449808700022,15.3603773332 +16.26,51.0021126351,8.29920536574e-005,10.5656060978,19.2376373572,5.17052705828,-0.168299890597,0.0983686792389,0.450009198748,15.4299955438 +16.27,51.002114364,8.373028241e-005,10.5672939034,19.2289818355,5.1934080084,-0.169261226479,0.0997017104763,0.450326383675,15.5013370111 +16.28,51.0021160921,8.4471763068e-005,10.568988134,19.2222620397,5.21617991694,-0.169584900858,0.0987015013184,0.451981309739,15.5715578889 +16.29,51.0021178198,8.52163089104e-005,10.5706762532,19.218363764,5.23643950264,-0.168038940327,0.0972133299239,0.45349227253,15.6402724731 +16.3,51.0021195471,8.5963882032e-005,10.572364583,19.2122531873,5.25867925993,-0.169627010868,0.0991245305199,0.453924131525,15.7114765788 +16.31,51.0021212737,8.67144607565e-005,10.5740615378,19.205057363,5.27863453095,-0.169763949416,0.0997109842867,0.454706824483,15.7797996378 +16.32,51.0021229997,8.7468037713e-005,10.5757651285,19.1977281264,5.30077080668,-0.170954185344,0.099610436291,0.455006546059,15.8508177191 +16.33,51.002124725,8.82246543347e-005,10.5774707621,19.1896233106,5.32130775036,-0.170172534001,0.0979248496695,0.456033109548,15.9195693403 +16.34,51.0021264497,8.89843319675e-005,10.5791781264,19.1840361592,5.34374369768,-0.171300326817,0.0991067036234,0.455658178301,15.9906793824 +16.35,51.0021281738,8.974711267e-005,10.5808932187,19.1777444299,5.36487109457,-0.171718139364,0.0973049785592,0.457831327085,16.0622335948 +16.36,51.0021298975,9.05130476559e-005,10.5826088322,19.172630286,5.38802602397,-0.17140455103,0.0991757189645,0.457378435386,16.1332971311 +16.37,51.0021316206,9.12822007532e-005,10.58433025,19.1673475481,5.41004949438,-0.172879018144,0.0990608974525,0.458938369445,16.2027966595 +16.38,51.0021333433,9.20544683261e-005,10.5860594745,19.161813505,5.43174948553,-0.17296588762,0.0992034088663,0.460080431059,16.2713808693 +16.39,51.0021350654,9.28297989196e-005,10.5877875362,19.1551207522,5.4530505819,-0.172646452643,0.0997592262929,0.460865908269,16.3433493636 +16.4,51.002136787,9.36082881972e-005,10.5895163733,19.1481679356,5.47609357933,-0.173120955664,0.0998801272281,0.46141920147,16.4129126788 +16.41,51.0021385079,9.43900449322e-005,10.5912555715,19.141519092,5.49892173317,-0.174718697226,0.0986979174497,0.464079470932,16.4808935787 +16.42,51.0021402282,9.51749791637e-005,10.5929952117,19.1351665195,5.52070177359,-0.173209336723,0.1005581184,0.463982141508,16.5503701578 +16.43,51.0021419479,9.59630642702e-005,10.5947352565,19.1287794988,5.543156188,-0.174799626591,0.100043544139,0.464532566215,16.6225040226 +16.44,51.0021436672,9.67541933939e-005,10.596482372,19.123980023,5.56343605746,-0.17462346214,0.0999430171714,0.464614139919,16.6937645903 +16.45,51.002145386,9.75482080384e-005,10.5982355318,19.1185676951,5.58366535115,-0.176008501756,0.0984615065709,0.466317900822,16.7651244734 +16.46,51.0021471042,9.8345414736e-005,10.5999949641,19.11132779,5.60824859998,-0.17587795969,0.0987529687593,0.46562755689,16.83424238 +16.47,51.0021488218,9.91458076533e-005,10.6017541007,19.1037342225,5.62839599311,-0.175949359663,0.10216767163,0.466109027016,16.9053008584 +16.48,51.0021505387,9.99492019555e-005,10.6035079655,19.0979419912,5.65038436155,-0.174823603099,0.0987693449363,0.466428023881,16.9759060616 +16.49,51.0021522551,0.00010075565054,10.6052661518,19.0909719738,5.67127436967,-0.176813656632,0.100320978241,0.467144840705,17.0442055214 +16.5,51.0021539709,0.000101565087809,10.6070345434,19.0858166999,5.69234182121,-0.176864655496,0.0997395893774,0.468993536906,17.1183032797 +16.51,51.0021556863,0.000102377664932,10.6087964073,19.0800280547,5.71535407513,-0.175508133192,0.0975570015913,0.468925121417,17.1877933053 +16.52,51.002157401,0.000103193586589,10.6105504544,19.0727946518,5.73929501039,-0.175301282045,0.0997154425309,0.468392389616,17.2573338723 +16.53,51.0021591153,0.000104012528149,10.6123061083,19.0695845262,5.75774979789,-0.17582949337,0.0957166108892,0.469229966971,17.329403629 +16.54,51.0021608291,0.000104834392907,10.6140703933,19.0626692705,5.78033309174,-0.177027521744,0.0975622549837,0.470857323366,17.3981274314 +16.55,51.0021625424,0.00010565932511,10.6158352954,19.0572422215,5.80081294168,-0.175952893152,0.0953511863615,0.47207688853,17.4655949559 +16.56,51.0021642551,0.000106487317714,10.6175928272,19.0496818211,5.82329735825,-0.175553472821,0.0983398289547,0.473042541252,17.5374933582 +16.57,51.0021659673,0.000107318545436,10.6193525674,19.0452514916,5.84623003829,-0.176394550831,0.0982487483233,0.474617748437,17.6071109147 +16.58,51.0021676789,0.000108152978388,10.6211219151,19.0372986504,5.86829484188,-0.177474993944,0.0993378234384,0.473232166308,17.6765669109 +16.59,51.0021693897,0.000108990482995,10.6229002798,19.0289162472,5.88935227749,-0.178197960093,0.0978215190322,0.474651379756,17.7469949964 +16.6,51.0021711,0.000109831062427,10.6246833088,19.0246980371,5.91146160372,-0.178407830577,0.098205414913,0.476994445814,17.8190566655 +16.61,51.0021728099,0.000110674926152,10.6264503998,19.0194455424,5.93545970555,-0.175010366543,0.0974652441943,0.478827311561,17.8897711857 +16.62,51.0021745192,0.000111521953968,10.628202734,19.0120138657,5.95588152886,-0.175456474906,0.0985113209004,0.478059680886,17.9592244809 +16.63,51.0021762279,0.000112372016924,10.6299558164,19.0066862584,5.97806932509,-0.175160002179,0.0974217650048,0.480380396566,18.0296031715 +16.64,51.0021779361,0.000113225222499,10.6317266164,19,6,-0.179,0.1,0.48,18.1 +16.65,51.0021796436,0.000114081542283,10.6335248036,18.9919079666,6.02178896398,-0.1806374444,0.0985685760391,0.482478156325,18.1693701177 +16.66,51.0021813503,0.000114941078026,10.6353242823,18.9810617499,6.04514809586,-0.179258301356,0.0991699701971,0.482763368281,18.2380025658 +16.67,51.0021830561,0.000115803970919,10.6371174068,18.9730785225,6.06891921944,-0.179366594843,0.098748523636,0.483388144255,18.3068397953 +16.68,51.0021847612,0.00011667024947,10.6389123246,18.9634094611,6.09267857514,-0.179616958723,0.0995141812845,0.481871870353,18.3740273988 +16.69,51.0021864654,0.0001175400068,10.6407077995,18.9548485577,6.11775699156,-0.179478031302,0.0997236385811,0.484087010293,18.4420337471 +16.7,51.0021881688,0.000118413131227,10.6425089133,18.9453525218,6.13994847793,-0.180744729587,0.0971589660612,0.485049240768,18.5095005634 +16.71,51.0021898713,0.000119289612296,10.6443296457,18.9356359391,6.16488009411,-0.183401740271,0.099520164663,0.486444979885,18.5785575573 +16.72,51.0021915729,0.000120169672355,10.6461576738,18.9245951121,6.19019310409,-0.182203872707,0.0990193686834,0.485861729559,18.6490599133 +16.73,51.0021932736,0.000121053234409,10.6479806822,18.9135458023,6.214043791,-0.182397820555,0.0982547915845,0.484011544244,18.718240261 +16.74,51.0021949733,0.000121940139759,10.6498062984,18.9046833452,6.23712885655,-0.182725415319,0.09842552208,0.485777103568,18.7862911168 +16.75,51.0021966721,0.000122830347472,10.6516332761,18.8938461096,6.26040486267,-0.182670117358,0.0967800753321,0.486878532362,18.8536623601 +16.76,51.0021983701,0.000123723939256,10.6534597884,18.8866595237,6.2846370178,-0.182632346473,0.0997747486338,0.488348494435,18.9253311684 +16.77,51.0022000674,0.000124621134115,10.6552909312,18.8760780695,6.31098760723,-0.183596215783,0.100433890892,0.488165491272,18.9947534813 +16.78,51.0022017637,0.000125521817925,10.6571338129,18.867948352,6.33361757878,-0.184980125729,0.100162606013,0.48872238497,19.0609429336 +16.79,51.0022034594,0.000126425689311,10.6589822096,18.8606041161,6.35573718537,-0.18469921954,0.100129206374,0.490845400503,19.1317430738 +16.8,51.0022051543,0.000127332606619,10.660827648,18.8503453892,6.37637850005,-0.184388459291,0.0978350096192,0.491768603791,19.1998113667 +16.81,51.0022068483,0.00012824265706,10.6626803378,18.8394247885,6.39972244606,-0.18614949224,0.0996956365729,0.494243437208,19.2679193914 +16.82,51.0022085413,0.000129156015193,10.6645362554,18.8309211663,6.42281436388,-0.185034036234,0.099625952617,0.494009236343,19.3360206378 +16.83,51.0022102336,0.000130072780265,10.6663892976,18.8219430825,6.44755164731,-0.185574406103,0.0985469962255,0.493836360272,19.4046056717 +16.84,51.0022119251,0.000130992937554,10.668244362,18.8125951917,6.47043684704,-0.185438471688,0.0984492078954,0.495001652866,19.4730867231 +16.85,51.0022136158,0.00013191637961,10.6701051589,18.805159775,6.49366568037,-0.186720909461,0.0983830260862,0.495023872642,19.5420867411 +16.86,51.0022153056,0.000132843167665,10.6719646853,18.7935006314,6.51741049497,-0.185184364088,0.0974775159193,0.495081064122,19.6117519867 +16.87,51.0022169945,0.000133773315641,10.6738166278,18.7835933075,6.540834771,-0.185204137142,0.0964626146722,0.497284988846,19.6817370885 +16.88,51.0022186826,0.0001347066553,10.6756746677,18.7745190733,6.56221771052,-0.186403840588,0.0980494589128,0.496752576492,19.7475470778 +16.89,51.0022203698,0.000135643249777,10.6775432735,18.7665403755,6.58652832399,-0.187317321617,0.0989671834693,0.499264089144,19.8169211239 +16.9,51.0022220562,0.000136583206542,10.6794168778,18.755591931,6.60942003038,-0.187403529793,0.101425473164,0.498296470662,19.8852936257 +16.91,51.0022237417,0.00013752655236,10.6812884669,18.7466444156,6.634106391,-0.186914295285,0.101279641394,0.498046259632,19.9560008004 +16.92,51.0022254265,0.000138473271511,10.6831584889,18.7378227136,6.65677737915,-0.187090103554,0.100255641435,0.499828948733,20.0229545513 +16.93,51.0022271104,0.000139423250883,10.685033986,18.7289988323,6.67987579996,-0.188009320467,0.10003533045,0.500503520532,20.0921766848 +16.94,51.0022287934,0.000140376622539,10.6869146287,18.7185007252,6.70440078701,-0.1881192145,0.0991052451083,0.499783986571,20.1614124744 +16.95,51.0022304756,0.000141333466321,10.6887982812,18.7096052367,6.72862011333,-0.188611280907,0.0969162243693,0.500913733686,20.229651276 +16.96,51.002232157,0.000142293697254,10.6906836966,18.7009970849,6.75195212446,-0.188471813739,0.100156716271,0.503382066249,20.2997311828 +16.97,51.0022338377,0.000143257345313,10.6925697858,18.693797785,6.77659225552,-0.188746017733,0.101077535592,0.503186545441,20.3675400454 +16.98,51.0022355177,0.000144224399948,10.6944562842,18.6845418314,6.79977618141,-0.188553668908,0.100639695541,0.504379838363,20.4350034729 +16.99,51.0022371968,0.000145194659322,10.6963426654,18.6747090181,6.82158272713,-0.188722567473,0.0988739014771,0.507039289053,20.505218326 +17,51.002238875,0.000146168143529,10.6982294224,18.6653887256,6.8450487465,-0.188628836414,0.100111949796,0.505769103502,20.5724643524 +17.01,51.0022405523,0.000147144968902,10.7001076009,18.654462436,6.86848848102,-0.187006868481,0.0979898196733,0.506697146211,20.6410885076 +17.02,51.0022422287,0.000148125139743,10.7019784402,18.6445052049,6.89201488163,-0.187160987134,0.0981103088945,0.506786536342,20.7103096383 +17.03,51.0022439042,0.000149108678464,10.7038528908,18.6353308224,6.91576926166,-0.187729128503,0.0983198943674,0.510931583609,20.7818353466 +17.04,51.0022455789,0.000150095470778,10.7057316955,18.626498636,6.9376912064,-0.18803181389,0.0990859636384,0.508458775273,20.8472292653 +17.05,51.0022472527,0.000151085393332,10.7076089405,18.6155418111,6.95971382228,-0.187417191032,0.0998257682576,0.510402903337,20.9176109995 +17.06,51.0022489257,0.000152078704159,10.7094900755,18.6065752498,6.98525827051,-0.188809795881,0.101252774463,0.511125629584,20.9871437722 +17.07,51.0022505978,0.000153075458346,10.7113764617,18.5983262325,7.00805424795,-0.188467449137,0.101201138687,0.509780033511,21.0557359624 +17.08,51.0022522691,0.000154075540851,10.7132728556,18.5880811917,7.03198362497,-0.190811324669,0.102461172828,0.511189028949,21.1240191667 +17.09,51.0022539396,0.000155079189676,10.7151782741,18.578641464,7.05812089131,-0.190272388538,0.102693103103,0.511021207045,21.1936416661 +17.1,51.0022556092,0.000156086312267,10.7170864743,18.5691547603,7.08075088974,-0.191367647064,0.103089168001,0.513447351655,21.2626923686 +17.11,51.0022572779,0.000157096724618,10.7190007989,18.5593481395,7.10430493698,-0.191497277711,0.103674539007,0.512373568104,21.3306952115 +17.12,51.0022589457,0.000158110414022,10.7209168775,18.550025096,7.12675652278,-0.191718441516,0.10278688636,0.512909444061,21.400174426 +17.13,51.0022606128,0.000159127400261,10.7228376422,18.5408306952,7.15058829823,-0.192434482929,0.104462632213,0.516286899822,21.467613152 +17.14,51.0022622789,0.000160147729514,10.7247621211,18.5310267014,7.1736881792,-0.192461315145,0.103319213879,0.515981471161,21.5347770106 +17.15,51.0022639443,0.000161171336645,10.7266886263,18.5220031774,7.19660550901,-0.192839714316,0.105666995212,0.515804025816,21.6031287783 +17.16,51.0022656088,0.00016219823339,10.7286127089,18.5135810461,7.2198701484,-0.191976811077,0.105449425214,0.518186086809,21.6736782847 +17.17,51.0022672725,0.000163228463251,10.7305439558,18.5041225836,7.24339819585,-0.194272573393,0.104364092344,0.519063312296,21.7434021005 +17.18,51.0022689354,0.000164262069257,10.7324799757,18.4945790259,7.26726692635,-0.192931399808,0.102901656972,0.518708149233,21.813203864 +17.19,51.0022705974,0.000165298935854,10.7344209972,18.4839347159,7.2891726958,-0.195272908666,0.103724918384,0.517468493146,21.8811626508 +17.2,51.0022722585,0.000166339039423,10.736363996,18.4756154864,7.31270985352,-0.19332684207,0.104290140255,0.519480734994,21.9500575589 +17.21,51.0022739188,0.00016738246398,10.7382987737,18.4657929901,7.33579510414,-0.193628703503,0.102797280578,0.521356841751,22.019585503 +17.22,51.0022755783,0.000168429224702,10.7402397941,18.4568411665,7.35954533405,-0.194575379526,0.102319239249,0.520507522483,22.0898761475 +17.23,51.002277237,0.00016947934474,10.7421906067,18.4482040314,7.38295558945,-0.195587140447,0.100905893847,0.520653373505,22.1579577901 +17.24,51.0022788948,0.000170532753364,10.744137322,18.4367366827,7.4057128521,-0.193755902008,0.102353875431,0.521619628961,22.2248369712 +17.25,51.0022805516,0.000171589552922,10.7460761794,18.428459255,7.43055995178,-0.194015594972,0.10264200857,0.524483940624,22.2926580358 +17.26,51.0022822077,0.000172649758607,10.7480186353,18.4176349888,7.45353050426,-0.194475585639,0.101214480932,0.526998668478,22.3615477498 +17.27,51.0022838628,0.000173713257501,10.7499632078,18.4095154662,7.47679237206,-0.194438904542,0.103858000804,0.527196612829,22.4306096763 +17.28,51.0022855173,0.000174780112496,10.7519110207,18.4004469451,7.50064582479,-0.195123677409,0.104317909293,0.527846440934,22.4996000777 +17.29,51.0022871708,0.000175850384207,10.7538569322,18.3903738682,7.52475868128,-0.194058614836,0.10406958007,0.529334660773,22.5677396443 +17.3,51.0022888235,0.000176924051772,10.7558022309,18.3810715389,7.54831924227,-0.195001137213,0.104608017721,0.52896650611,22.6357963878 +17.31,51.0022904752,0.000178001041743,10.7577593207,18.3690202626,7.57140096484,-0.196416822311,0.105084629572,0.528955954587,22.7049562729 +17.32,51.002292126,0.000179081330053,10.7597176127,18.3604181127,7.59462366069,-0.195241570689,0.103875388051,0.531987902965,22.7734099528 +17.33,51.0022937759,0.00018016490893,10.7616771345,18.3501204056,7.61759627622,-0.196662792393,0.104695562874,0.532534317744,22.8434804535 +17.34,51.002295425,0.000181251838578,10.7636348197,18.3428371527,7.64166413245,-0.194874238071,0.105520303988,0.532620731028,22.9118854936 +17.35,51.0022970734,0.000182342228196,10.7655834308,18.3334379309,7.66616981484,-0.194847985893,0.106959549835,0.533690673849,22.9807698233 +17.36,51.002298721,0.000183436014922,10.7675356242,18.3244175228,7.68935512682,-0.195590703258,0.103755332612,0.535808398748,23.0469191583 +17.37,51.0023003678,0.000184533246707,10.7694918844,18.315822996,7.71453398449,-0.1956613325,0.104782042487,0.538002257437,23.1178497697 +17.38,51.0023020137,0.000185633977633,10.7714483383,18.3055124715,7.73847856459,-0.195629443446,0.105577522227,0.53655048082,23.1850180036 +17.39,51.0023036588,0.000186737998268,10.7734056464,18.2974094832,7.76071723186,-0.195832175232,0.106469585821,0.536298007582,23.2534187888 +17.4,51.0023053031,0.000187845205417,10.775366201,18.2869162203,7.78321303324,-0.196278742219,0.104693660366,0.537196767682,23.3230006011 +17.41,51.0023069464,0.000188955654514,10.7773279807,18.2759749874,7.80622997813,-0.196077198696,0.101652233345,0.536487219367,23.3899732817 +17.42,51.0023085888,0.000190069358675,10.779297573,18.2678295871,7.82890985754,-0.197841268857,0.103312031905,0.534507358996,23.4604880842 +17.43,51.0023102305,0.000191186305444,10.7812787806,18.2590563077,7.85175197416,-0.19840024063,0.103936644016,0.536579887763,23.5312299544 +17.44,51.0023118714,0.000192306583885,10.7832608798,18.2502296586,7.87568218561,-0.198019601748,0.10485073216,0.538420359353,23.6000852194 +17.45,51.0023135114,0.000193430229455,10.7852495614,18.241045051,7.89902209222,-0.199716721119,0.102643810532,0.540249091042,23.6684027852 +17.46,51.0023151507,0.000194557377067,10.7872505356,18.2309603132,7.92484630884,-0.200478127852,0.105203665015,0.540646315288,23.7403259337 +17.47,51.002316789,0.000195688088391,10.7892504319,18.2228318889,7.9490519941,-0.199501127321,0.108135051397,0.539229064209,23.8088629477 +17.48,51.0023184267,0.000196822101665,10.791243485,18.2137049213,7.97120135578,-0.199109489746,0.10778118003,0.541599500743,23.8772247067 +17.49,51.0023200634,0.000197959252553,10.7932432284,18.2036791806,7.99309997155,-0.200839185651,0.107928630953,0.541337261726,23.9486933037 +17.5,51.0023216993,0.000199099583667,10.795244489,18.1945879811,8.01584754191,-0.199412932195,0.107954550906,0.542958095665,24.0151738063 +17.51,51.0023233344,0.000200243224735,10.7972412815,18.1852123228,8.03956738687,-0.199945580973,0.104236790722,0.543952602133,24.0846126766 +17.52,51.0023249686,0.00020139024808,10.7992456775,18.176348514,8.06333029464,-0.200933621657,0.107047469166,0.54525494465,24.1532447329 +17.53,51.0023266021,0.000202540614388,10.8012504632,18.1681401056,8.08649820235,-0.200023516266,0.107724904349,0.544664984505,24.2207290056 +17.54,51.0023282348,0.000203694301534,10.8032539926,18.1574879211,8.10995050776,-0.200682352831,0.106962979837,0.547320121492,24.2895759594 +17.55,51.0023298664,0.000204851357907,10.805263257,18.1467292758,8.1337977287,-0.201170537324,0.106171929645,0.545813794706,24.3581118025 +17.56,51.0023314972,0.000206011778895,10.8072791338,18.1376638827,8.15718529343,-0.202004825028,0.104045518941,0.547733072052,24.4275032548 +17.57,51.0023331272,0.000207175542079,10.8092998058,18.1293706846,8.18071775702,-0.202129576303,0.106045525507,0.547743374823,24.4952333237 +17.58,51.0023347565,0.000208342624728,10.8113219008,18.1214856331,8.20378622216,-0.202289408771,0.106533969948,0.549859376565,24.5627048428 +17.59,51.002336385,0.000209513007071,10.8133465207,18.1116432112,8.22704111161,-0.202634572781,0.109058334266,0.550383327888,24.6304704973 +17.6,51.0023380125,0.000210686718638,10.8153754192,18.1006623511,8.2505241346,-0.203145137081,0.108035347098,0.550084530793,24.6993726846 +17.61,51.0023396391,0.000211863853267,10.8174091625,18.0905375287,8.27509642257,-0.203603519003,0.109450273973,0.55070344295,24.7657323739 +17.62,51.0023412648,0.000213044422534,10.8194377048,18.080949836,8.2987419304,-0.202104947267,0.109847768472,0.554024328531,24.8350189603 +17.63,51.0023428897,0.000214228194634,10.8214556169,18.072047744,8.32005994239,-0.201477469883,0.110626601383,0.552760134846,24.9042631009 +17.64,51.0023445137,0.000215415247452,10.8234750973,18.0615584167,8.34479888329,-0.20241860197,0.109356254269,0.553957753705,24.9729749905 +17.65,51.0023461368,0.000216605796595,10.8255040832,18.0525267974,8.3691437355,-0.203378578657,0.11070290141,0.556051596284,25.0417905599 +17.66,51.0023477591,0.000217799721444,10.8275312579,18.0424854902,8.39218935132,-0.202056367358,0.109603548898,0.555852996555,25.1110977072 +17.67,51.0023493805,0.000218996946297,10.8295502474,18.0338842878,8.41547142499,-0.201741527123,0.107091441319,0.556326313658,25.1807843289 +17.68,51.0023510012,0.00022019748126,10.8315758498,18.0253214543,8.43865889747,-0.203378954462,0.109248702988,0.556304947081,25.2505813432 +17.69,51.002352621,0.000221401365008,10.8336084257,18.0151166691,8.46248393018,-0.203136222068,0.10965708865,0.556881379129,25.3178024468 +17.7,51.0023542399,0.000222608607833,10.8356420591,18.0057996552,8.48581590117,-0.20359047248,0.10981311789,0.558956253361,25.3871443837 +17.71,51.0023558579,0.000223819146306,10.8376773038,17.9935045462,8.5087504419,-0.203458450281,0.111407348017,0.560013403148,25.4567547755 +17.72,51.002357475,0.000225033045083,10.8397104104,17.9875784667,8.53299011907,-0.203162875413,0.110116631932,0.560748406239,25.5264706301 +17.73,51.0023590916,0.000226250349024,10.8417523161,17.9792896795,8.55655443256,-0.20521827559,0.109636256437,0.561611010204,25.5933800544 +17.74,51.0023607072,0.000227471085531,10.8438035739,17.9693590733,8.58117879074,-0.205033284596,0.108608269651,0.561904863838,25.6628341135 +17.75,51.0023623221,0.000228695169373,10.8458584231,17.9595688819,8.60354656581,-0.205936548955,0.108645848485,0.561717170877,25.7322029192 +17.76,51.002363936,0.000229922394528,10.847916456,17.9512183193,8.62527861535,-0.205670026812,0.110340958333,0.562042115456,25.7991487215 +17.77,51.0023655493,0.000231152972078,10.84998179,17.9426709309,8.65060973367,-0.207396781535,0.11157413872,0.561436414575,25.8681601641 +17.78,51.0023671616,0.000232387153573,10.8520556915,17.9322031124,8.67587324631,-0.207383515251,0.110693693523,0.562106843145,25.9355287747 +17.79,51.0023687732,0.000233624906119,10.854140286,17.9248112552,8.70074257046,-0.209535383771,0.10998631717,0.564603832741,26.0057329151 +17.8,51.002370384,0.000234865904015,10.8562325625,17.9151353197,8.72143360592,-0.208919922041,0.109088314658,0.563508488977,26.0756321125 +17.81,51.002371994,0.000236110033021,10.858312813,17.9054823946,8.74469913966,-0.207130162297,0.109193920103,0.565397700476,26.1452570893 +17.82,51.002373603,0.000237357403982,10.8603828899,17.8946453755,8.76694631885,-0.206885226006,0.109043247556,0.564854714768,26.2136579761 +17.83,51.0023752111,0.000238608016486,10.8624442357,17.8860405398,8.79020603718,-0.205383924075,0.110022181892,0.565376808702,26.2830461788 +17.84,51.0023768184,0.000239861920511,10.8645055195,17.8752568658,8.8131548681,-0.2068728379,0.110614128832,0.566763002332,26.3498601817 +17.85,51.0023784247,0.000241119089088,10.8665695375,17.8656095523,8.83603596698,-0.20593077842,0.111862864322,0.56818481383,26.4202152953 +17.86,51.0023800302,0.000242379571599,10.868642283,17.856235769,8.85967805126,-0.208618311234,0.111655594882,0.569094888112,26.4883878272 +17.87,51.0023816349,0.000243643456083,10.8707280937,17.847581336,8.88379511313,-0.208543835191,0.111086551395,0.567485161324,26.5561894702 +17.88,51.0023832387,0.000244910746574,10.8728080314,17.8367895676,8.90749384944,-0.207443701102,0.110273528938,0.568970815862,26.624417387 +17.89,51.0023848417,0.00024618143063,10.8748796697,17.8280353781,8.93143621307,-0.206883963879,0.109758925382,0.570760613528,26.6938358838 +17.9,51.0023864438,0.000247455477683,10.876953697,17.819389191,8.95470581041,-0.207921484221,0.108934800895,0.569890256904,26.7627696575 +17.91,51.0023880452,0.000248732794905,10.8790397524,17.8095183375,8.977344992,-0.209289599762,0.108705004647,0.569962492909,26.831131936 +17.92,51.0023896456,0.00025001333852,10.8811362004,17.8,9,-0.21,0.11,0.572,26.9 +17.93,51.0023912451,0.000251297125734,10.8832379202,17.787935478,9.0228807424,-0.210343953723,0.110898821401,0.570844330923,26.9741871757 +17.94,51.0023928435,0.000252584034234,10.8853419908,17.7760349206,9.04381861466,-0.210470183175,0.110272243715,0.573652696498,27.0457579544 +17.95,51.0023944408,0.00025387399312,10.8874447926,17.7628685284,9.06570400532,-0.210090163649,0.109997486667,0.571337055941,27.118020372 +17.96,51.0023960368,0.000255166985289,10.8895410904,17.7488892339,9.08640175832,-0.209169404374,0.108538083739,0.571935725488,27.1926846355 +17.97,51.0023976316,0.000256462850893,10.8916340185,17.7353404906,9.10604307429,-0.209416207215,0.110219708933,0.573650453093,27.264369883 +17.98,51.0023992253,0.000257761653763,10.8937256163,17.7226616716,9.12763692329,-0.208903367724,0.110205441727,0.574414350037,27.3352492283 +17.99,51.0024008177,0.000259063461686,10.895807424,17.7090234386,9.14822991686,-0.207458170319,0.109050158095,0.575953099278,27.4098062745 +18,51.0024024091,0.000260368286671,10.8978960894,17.6984291431,9.16999233509,-0.210274897238,0.108958932867,0.575997769855,27.4812467949 +18.01,51.0024039994,0.000261676110637,10.8999881573,17.6861332538,9.19033148711,-0.208138679845,0.110536654953,0.577422729627,27.5546311285 +18.02,51.0024055887,0.000262986832105,10.9020710435,17.674072458,9.2106692603,-0.208438559909,0.110393887957,0.57719416221,27.62789171 +18.03,51.0024071769,0.000264300568301,10.9041669684,17.6625800925,9.23265412378,-0.210746434676,0.110491662436,0.576671308459,27.6994453866 +18.04,51.002408764,0.000265617387653,10.9062738387,17.6503191321,9.25395256727,-0.210627622145,0.109188311119,0.578312850881,27.7749799649 +18.05,51.0024103499,0.000266937177065,10.9083841012,17.6361108855,9.27434966203,-0.211424876535,0.109684648844,0.578941110621,27.8478544585 +18.06,51.0024119347,0.00026825994956,10.9105093956,17.6243239999,9.29583094237,-0.213634003786,0.110375196762,0.579893095519,27.9182821587 +18.07,51.0024135183,0.000269585858388,10.9126409016,17.611230106,9.31837948231,-0.212667188578,0.109404718108,0.582033983855,27.991372205 +18.08,51.0024151009,0.000270914811055,10.9147726155,17.6006903044,9.3385622596,-0.213675600752,0.109809496196,0.581297606304,28.064152128 +18.09,51.0024166824,0.000272246574751,10.9169222704,17.5870918024,9.35784242083,-0.216255384912,0.109002851061,0.579106553072,28.1367561519 +18.1,51.0024182627,0.000273581304237,10.9190726156,17.5752364909,9.38019784214,-0.213813652191,0.10975354952,0.581905140695,28.209228764 +18.11,51.002419842,0.000274919153591,10.9212154405,17.5622086444,9.40164108843,-0.214751330285,0.110572715504,0.582824369773,28.2816828426 +18.12,51.0024214201,0.000276260067579,10.9233565976,17.5518910525,9.42322109256,-0.213480080351,0.111041495319,0.584240566616,28.3534600051 +18.13,51.0024229972,0.000277603957681,10.9254854968,17.5376623495,9.44342159606,-0.21229976156,0.110333209392,0.582772046173,28.4221932047 +18.14,51.0024245731,0.000278950852663,10.9276115647,17.5242391478,9.46540545631,-0.212913824457,0.109938687604,0.584521959797,28.4965054641 +18.15,51.0024261477,0.000280300737067,10.9297530795,17.5119835619,9.48538895042,-0.215389134107,0.108309949325,0.587325732385,28.5719098953 +18.16,51.0024277213,0.000281653636894,10.9319086886,17.499429929,9.5077378115,-0.215732684291,0.107899927863,0.587063851337,28.6434985295 +18.17,51.0024292937,0.000283009791733,10.9340685829,17.4850259903,9.53108487187,-0.216246170795,0.109141908768,0.586287999396,28.7167049894 +18.18,51.0024308649,0.000284368970686,10.9362372324,17.4744306162,9.55019218538,-0.217483735771,0.109697829704,0.588213142455,28.7859180095 +18.19,51.0024324352,0.000285731054404,10.9384088672,17.4638389014,9.57186372424,-0.216843214273,0.109857712104,0.589811282938,28.8592999342 +18.2,51.0024340044,0.000287096080602,10.9405752036,17.4505129831,9.59150050996,-0.216424060559,0.109253686718,0.591879054966,28.9333711584 +18.21,51.0024355724,0.00028846410458,10.942739349,17.437479382,9.61394838529,-0.216405031228,0.108504987808,0.593358389688,29.0066923128 +18.22,51.0024371394,0.000289835220032,10.944915778,17.4265404867,9.63490053934,-0.218880768643,0.107450418525,0.594736206979,29.0779475128 +18.23,51.0024387052,0.000291209232673,10.9471042019,17.4123797786,9.65462085937,-0.218803999057,0.103745541907,0.594577389645,29.15267209 +18.24,51.0024402698,0.000292586133906,10.9492880228,17.4001875507,9.67545233575,-0.217960187295,0.106971185183,0.594196857269,29.2245537245 +18.25,51.0024418333,0.000293966026236,10.9514637144,17.3870597262,9.6966116933,-0.217178142417,0.107016618289,0.594159317658,29.2973935449 +18.26,51.0024433956,0.000295348917801,10.9536356369,17.3728393501,9.71755742403,-0.217206342174,0.10532662302,0.596470789734,29.3714132046 +18.27,51.0024449566,0.000296734809214,10.9558175194,17.3605954883,9.73872537999,-0.219170167162,0.104369267526,0.597613745388,29.4444342127 +18.28,51.0024465166,0.000298123628888,10.9580091605,17.3476410531,9.75866610016,-0.219158062067,0.106327992796,0.59865395583,29.5170176267 +18.29,51.0024480753,0.000299515307813,10.9601964904,17.333157787,9.77886526592,-0.218307914203,0.106226409642,0.600610050866,29.5876754329 +18.3,51.0024496329,0.00030090991152,10.9623763005,17.3225955171,9.79972592479,-0.217654092821,0.10566161378,0.598752276729,29.6618314271 +18.31,51.0024511895,0.000302307556065,10.9645635514,17.3113541565,9.82155439658,-0.219796092873,0.105781269203,0.601233643373,29.7326868603 +18.32,51.0024527451,0.00030370829695,10.9667654358,17.3011020088,9.84319424223,-0.220580781507,0.106639123314,0.601684642016,29.806086281 +18.33,51.0024542998,0.000305112077795,10.9689694245,17.2902410047,9.86423119411,-0.220216974344,0.106990699585,0.601824830082,29.8782568685 +18.34,51.0024558533,0.000306518804638,10.9711697502,17.2754153186,9.88455192137,-0.219848155818,0.107501987369,0.601399521582,29.9523897332 +18.35,51.0024574056,0.000307928601629,10.9733571577,17.2620990815,9.90733178706,-0.217633340777,0.108529189624,0.602353890902,30.0242326048 +18.36,51.0024589567,0.000309341573525,10.975544139,17.250078564,9.92912318522,-0.219762932101,0.109407153437,0.602509313576,30.0959428461 +18.37,51.0024605067,0.00031075760829,10.9777386661,17.2355650371,9.95033018911,-0.219142475463,0.110500767426,0.600061607559,30.1682304119 +18.38,51.0024620554,0.000312176628181,10.9799368197,17.2232953668,9.9710301676,-0.220488252676,0.109799422103,0.602649579695,30.2412822468 +18.39,51.0024636031,0.000313598566241,10.982149513,17.2126248314,9.99129716982,-0.22205040065,0.109519357459,0.60417788629,30.3157062169 +18.4,51.0024651498,0.00031502337441,10.9843745143,17.2007306905,10.0113224472,-0.222949854753,0.10647633003,0.606600647219,30.3881985428 +18.41,51.0024666953,0.000316451119088,10.9865996422,17.1876199647,10.0325216027,-0.222075739426,0.106402970547,0.606059972989,30.4615084803 +18.42,51.0024682397,0.00031788196724,10.9888229038,17.1730777626,10.054890906,-0.222576572043,0.106279952619,0.60682079307,30.5329297008 +18.43,51.0024697828,0.000319315822446,10.991057263,17.16053033,10.0747364096,-0.224295259412,0.106451644761,0.610662980178,30.6070454833 +18.44,51.0024713247,0.000320752555186,10.9933062818,17.147890815,10.095287412,-0.225508510052,0.105562794513,0.608976703198,30.6807783963 +18.45,51.0024728657,0.000322192221124,10.9955628294,17.1369802156,10.1159143623,-0.225801005768,0.10598094797,0.611019101136,30.75221905 +18.46,51.0024744055,0.00032363487601,10.9978225979,17.1241015943,10.137248035,-0.226152693934,0.104371085707,0.609467111928,30.825026941 +18.47,51.0024759443,0.000325080733933,11.0000833888,17.1129715656,10.1608805436,-0.226005482383,0.103928215745,0.611629581286,30.8955968459 +18.48,51.002477482,0.000326529654043,11.0023414801,17.1000524185,10.1802368383,-0.225612780812,0.105474382034,0.612964889031,30.9695193684 +18.49,51.0024790186,0.000327981412838,11.0046078467,17.0890771025,10.2007316274,-0.22766054131,0.105158731817,0.613782538169,31.040413641 +18.5,51.0024805541,0.00032943614146,11.00687139,17.0750766508,10.2219290289,-0.225048121399,0.106566321775,0.614893492813,31.1153109241 +18.51,51.0024820883,0.00033089388901,11.0091186153,17.0615109093,10.2431131178,-0.224396942636,0.108085643048,0.613661279624,31.1887285467 +18.52,51.0024836214,0.000332354601412,11.0113718849,17.0500635572,10.2635513557,-0.226256965023,0.106052373652,0.615482135863,31.2604676666 +18.53,51.0024851535,0.000333818245909,11.0136343028,17.038348459,10.2842755697,-0.226226614579,0.107848839967,0.619924831496,31.3323774058 +18.54,51.0024866845,0.000335284987737,11.0158940187,17.025037313,10.3070335281,-0.225716567516,0.104478297543,0.619511211876,31.4031627704 +18.55,51.0024882143,0.000336754801779,11.0181515307,17.0127993758,10.3274051253,-0.225785830962,0.104882423109,0.620673564939,31.4766812542 +18.56,51.002489743,0.000338227559843,11.020415053,17.0001641675,10.3483634229,-0.226918634445,0.104852284608,0.620496019457,31.5497191257 +18.57,51.0024912706,0.000339703267111,11.0226859188,16.9888525936,10.3688077572,-0.227254537442,0.10311509315,0.619541278849,31.6212432736 +18.58,51.0024927971,0.000341182010825,11.0249448943,16.9764049733,10.3909908337,-0.224540547608,0.103618176182,0.620376991466,31.6942855723 +18.59,51.0024943226,0.0003426639311,11.0271886304,16.9637505416,10.4134022051,-0.224206671741,0.102488642067,0.623041646048,31.7663969019 +18.6,51.0024958469,0.000344148848892,11.0294371521,16.9522673678,10.4330717274,-0.225497674621,0.103253655624,0.623476834131,31.838133285 +18.61,51.0024973701,0.000345636624476,11.0316970411,16.9380823431,10.4535215179,-0.226480135152,0.101689928436,0.622832061498,31.9129326493 +18.62,51.002498892,0.000347127387417,11.0339541865,16.9242695618,10.4750099702,-0.224948929745,0.103451983766,0.624337967279,31.986042756 +18.63,51.0025004128,0.000348621232507,11.0362071877,16.9123087945,10.4967905428,-0.225651316093,0.103741055206,0.625187754902,32.0595845912 +18.64,51.0025019325,0.000350118084149,11.0384730121,16.9013203313,10.5172176803,-0.227513558462,0.103166574444,0.626809924992,32.1312028734 +18.65,51.0025034513,0.000351617909706,11.0407542532,16.891179358,10.5385400752,-0.228734668412,0.104158795232,0.629348968755,32.2062060156 +18.66,51.002504969,0.000353120841411,11.0430436159,16.8774906319,10.5608236096,-0.229137860437,0.103586742584,0.63153870667,32.2783972936 +18.67,51.0025064854,0.000354626761897,11.0453307264,16.8628867979,10.5804982968,-0.228284253009,0.101544448328,0.63087989571,32.35278007 +18.68,51.0025080007,0.00035613570963,11.0476185305,16.8502615057,10.6033218598,-0.229276554055,0.104016770933,0.63039785862,32.4244914398 +18.69,51.0025095148,0.000357647764251,11.0499190247,16.8386903925,10.624114591,-0.230822300916,0.103105665158,0.632131494066,32.4975128653 +18.7,51.0025110278,0.000359162805544,11.0522240512,16.8255199701,10.645250488,-0.230182994594,0.101816148084,0.631413435503,32.5688013958 +18.71,51.0025125396,0.000360680859443,11.0545175397,16.8116939982,10.6664072749,-0.228514701156,0.100416107073,0.632660408989,32.6408449948 +18.72,51.0025140503,0.000362201842829,11.0568090453,16.8000242247,10.6863763002,-0.229786421198,0.101633076735,0.631102361031,32.7140949472 +18.73,51.0025155598,0.000363725735482,11.0591055898,16.7874101901,10.7072491982,-0.229522479277,0.100468611149,0.632298816068,32.7842436076 +18.74,51.0025170682,0.000365252723462,11.061400214,16.7739886255,10.7298302958,-0.229402361738,0.100538399986,0.632989313178,32.8581417112 +18.75,51.0025185755,0.000366782661554,11.0636970034,16.7614245596,10.7486645447,-0.229955516846,0.101683564536,0.634519126032,32.9302995206 +18.76,51.0025200816,0.000368315610485,11.0659998855,16.7486007352,10.7720981667,-0.230620896265,0.101433708077,0.633183224798,33.0032757655 +18.77,51.0025215865,0.000369851825444,11.068305091,16.7370993634,10.7945149793,-0.230420217596,0.102012429552,0.632929735729,33.0765056499 +18.78,51.0025230905,0.000371391126781,11.0706133147,16.7245706611,10.8154265057,-0.23122450893,0.102332855967,0.635859882353,33.1490304015 +18.79,51.0025245933,0.000372933323436,11.0729158283,16.7129135901,10.8351610713,-0.229278217186,0.102638638119,0.638692889112,33.2224136587 +18.8,51.002526095,0.000374478396998,11.0752229112,16.7000291829,10.8558141418,-0.232138358972,0.103417074013,0.637498889695,33.2947762764 +18.81,51.0025275956,0.00037602642872,11.0775407502,16.6878925459,10.8766893798,-0.231429450045,0.104937873683,0.638971075949,33.3679870936 +18.82,51.0025290951,0.000377577402085,11.0798546686,16.6749486505,10.8971105796,-0.231354227728,0.102187853547,0.638236068391,33.4402012979 +18.83,51.0025305934,0.000379131142874,11.0821771419,16.661326335,10.9155399869,-0.233140427257,0.0990322739021,0.639979998948,33.5110491223 +18.84,51.0025320905,0.000380687746544,11.0845152026,16.6500497745,10.937301292,-0.234471723977,0.101097473252,0.641579832235,33.5853598723 +18.85,51.0025335866,0.0003822473881,11.0868476373,16.6371839769,10.9581875402,-0.232015206093,0.0984456843371,0.6411260068,33.6590241388 +18.86,51.0025350815,0.000383810023688,11.0891756374,16.6245998356,10.9793332139,-0.233584821035,0.0992162687234,0.643099914929,33.7303918644 +18.87,51.0025365754,0.000385375821733,11.0915206589,16.613435615,11.0025839198,-0.235419479527,0.100829967661,0.643515144426,33.802159313 +18.88,51.0025380682,0.000386944783512,11.0938752303,16.6002605148,11.0237475193,-0.235494803974,0.101141060679,0.643836539929,33.8754694955 +18.89,51.0025395598,0.000388516872104,11.0962396462,16.588003267,11.0464799127,-0.237388370482,0.101944375092,0.644351509375,33.9466704265 +18.9,51.0025410503,0.00039009190222,11.09861561,16.5753674035,11.0650422593,-0.237804379586,0.10143597416,0.646715925548,34.0192077451 +18.91,51.0025425398,0.000391669666384,11.1009854129,16.5657316348,11.0848619604,-0.236156197626,0.100935888986,0.646378902269,34.091604767 +18.92,51.0025440283,0.000393250448086,11.103346505,16.5525300708,11.1074041312,-0.236062236069,0.101285784151,0.64663197867,34.1662350311 +18.93,51.0025455155,0.000394834321404,11.105703245,16.5379345505,11.1282638329,-0.235285751983,0.103203067578,0.64795251685,34.2368671577 +18.94,51.0025470015,0.000396421231986,11.1080596787,16.5251680662,11.1500429327,-0.236001004749,0.103218144372,0.647465599489,34.3097858164 +18.95,51.0025484864,0.000398011365321,11.1104222537,16.5128913609,11.1735066859,-0.236513994905,0.10352685678,0.647797063417,34.3833621999 +18.96,51.0025499702,0.000399604531674,11.1127918818,16.5012874518,11.1926221195,-0.237411619731,0.103571467287,0.649293823394,34.4556111092 +18.97,51.0025514529,0.000401200550038,11.1151621802,16.4889773528,11.2135447841,-0.23664805437,0.101304543886,0.649000536021,34.5265554096 +18.98,51.0025529346,0.000402799568371,11.1175256432,16.4766683242,11.2347373427,-0.236044544366,0.102130618514,0.648183651722,34.5993810958 +18.99,51.0025544151,0.000404401476901,11.1198854601,16.464637259,11.2541189502,-0.23591884277,0.101155177097,0.648567914848,34.6724053683 +19,51.0025558945,0.000406006428266,11.1222613167,16.4528131117,11.2774543391,-0.239252477921,0.101550144262,0.649425084115,34.742922513 +19.01,51.0025573729,0.000407614646724,11.1246538457,16.4398566431,11.2999842805,-0.239253322485,0.101920990165,0.651505879077,34.8156314699 +19.02,51.0025588501,0.000409226042949,11.1270464307,16.4278288946,11.3220656301,-0.239263678805,0.101035655574,0.652713747766,34.8884513796 +19.03,51.0025603262,0.000410840708573,11.1294411964,16.4142157091,11.3458819611,-0.239689445565,0.0995220608187,0.653892928599,34.9624110637 +19.04,51.002561801,0.00041245841128,11.1318395101,16.4002456033,11.3647018861,-0.239973303425,0.100703098544,0.654691718617,35.036921489 +19.05,51.0025632747,0.00041407905529,11.1342424104,16.3895824478,11.3871735603,-0.240606750055,0.10016065088,0.654516776691,35.1098603013 +19.06,51.0025647473,0.000415702661297,11.1366347843,16.3752173463,11.4062840388,-0.237868039326,0.0997689450193,0.656411626373,35.1789184048 +19.07,51.0025662188,0.000417329054211,11.1390232545,16.3639794078,11.4262976195,-0.23982599736,0.100994415796,0.658093313595,35.2525442866 +19.08,51.0025676891,0.000418958332304,11.1414297511,16.3508654458,11.4467877504,-0.24147333227,0.101233292831,0.658678020437,35.3273045237 +19.09,51.0025691583,0.000420590717998,11.1438386214,16.3384406773,11.4699238348,-0.240300719732,0.10152768972,0.660421561796,35.3989569775 +19.1,51.0025706264,0.000422226016374,11.1462428284,16.3261070762,11.4876775497,-0.240540682657,0.101529468447,0.658650689999,35.4719775137 +19.11,51.0025720934,0.000423864060668,11.1486473427,16.3150136852,11.5084724835,-0.240362177794,0.101806499406,0.662734433846,35.5459978059 +19.12,51.0025735594,0.000425505183331,11.1510582553,16.3015132596,11.5308933793,-0.241820345313,0.100609071133,0.663750855383,35.6190101485 +19.13,51.0025750241,0.000427149390281,11.1534690451,16.2892205755,11.5517713954,-0.240337601923,0.101411345977,0.664721428895,35.6928183777 +19.14,51.0025764879,0.000428796579887,11.1558817555,16.2781406423,11.5727655259,-0.242204492997,0.101822982401,0.666513817514,35.7637234294 +19.15,51.0025779504,0.000430446747878,11.1583011652,16.2621549762,11.5935835844,-0.241677432666,0.103783436559,0.663241223618,35.8368266998 +19.16,51.0025794116,0.000432099936749,11.1607235349,16.2510334428,11.615174268,-0.242796508488,0.100290165523,0.665962794835,35.9090795837 +19.17,51.0025808718,0.000433756185765,11.163155936,16.2369887253,11.6365435792,-0.24368370866,0.0998788760961,0.665703842909,35.9808298076 +19.18,51.0025823308,0.00043541546551,11.1655957261,16.2247856442,11.6577212887,-0.244274309814,0.0979841239342,0.667474425017,36.0538820623 +19.19,51.0025837887,0.000437077648843,11.1680296781,16.2128091752,11.6773056868,-0.242516095888,0.0991888918787,0.669509601067,36.1279813324 +19.2,51.0025852454,0.000438742843793,11.1704672586,16.2,11.7,-0.245,0.1,0.668,36.2 +19.21,51.0025867009,0.00044041107889,11.1729222695,16.1834952235,11.7199849128,-0.246002182071,0.101086474509,0.669629532521,36.266070737 +19.22,51.0025881549,0.000442082059935,11.175372439,16.1670537979,11.7385490383,-0.244031720335,0.100790535735,0.669792891879,36.3354611798 +19.23,51.0025896074,0.000443755522418,11.1778098956,16.150261203,11.7548205559,-0.243459607394,0.0993629416568,0.671323018745,36.4045371408 +19.24,51.0025910583,0.000445431685898,11.1802491153,16.1335477267,11.7764670087,-0.244384319471,0.101183786985,0.672942844331,36.4747372808 +19.25,51.0025925079,0.000447110808726,11.1826902204,16.1182859772,11.7963654481,-0.243836710455,0.101589531236,0.67196153981,36.543585059 +19.26,51.0025939559,0.000448792671042,11.1851306865,16.0999813812,11.8149253497,-0.244256508084,0.101387826089,0.67213702176,36.6117619486 +19.27,51.0025954025,0.000450477248945,11.1875748768,16.0856540519,11.8344882508,-0.244581550568,0.101046836825,0.673058483039,36.6826388698 +19.28,51.0025968476,0.000452164630338,11.1900253978,16.0680971881,11.8542821986,-0.245522654224,0.0997881427197,0.673163467846,36.7527332056 +19.29,51.0025982912,0.00045385493649,11.1924817924,16.0518146949,11.8755475415,-0.245756258525,0.10104041746,0.672766907085,36.8206228463 +19.3,51.0025997333,0.000455548108168,11.1949424002,16.0344728512,11.8945099605,-0.246365298629,0.0995138247414,0.674369188318,36.8893453737 +19.31,51.0026011739,0.000457243980472,11.1974090828,16.0188863834,11.9134603046,-0.246971218486,0.0992155058596,0.674965922865,36.9571400607 +19.32,51.0026026131,0.000458942701324,11.199883852,16.0026161182,11.9344993433,-0.247982621104,0.0991075849801,0.67668107521,37.0252602375 +19.33,51.0026040508,0.000460644291217,11.2023580982,15.9850152184,11.9537373951,-0.246866638018,0.100327524661,0.676419961012,37.0930842166 +19.34,51.0026054869,0.000462348654333,11.2048279577,15.968335471,11.9734312745,-0.247105245701,0.100621932075,0.678361744394,37.1626487329 +19.35,51.0026069215,0.000464055895364,11.2072999103,15.9510315195,11.9941390663,-0.24728527385,0.100172684368,0.677739140281,37.2326779669 +19.36,51.0026083546,0.000465765884937,11.2097825999,15.9348937502,12.0120166916,-0.249252651061,0.10082803861,0.679496491878,37.3006566102 +19.37,51.0026097863,0.00046747853996,11.2122772303,15.9199867021,12.0315579878,-0.249673435149,0.102282497626,0.678386461542,37.3696601225 +19.38,51.0026112166,0.00046919410303,11.2147688251,15.9031363062,12.052841374,-0.2486455183,0.101734286238,0.681655842892,37.4368297383 +19.39,51.0026126453,0.000470912532184,11.2172679361,15.8854705047,12.0717935527,-0.251176692763,0.101704837385,0.681815845996,37.5056519809 +19.4,51.0026140725,0.000472633581949,11.2197763507,15.8696824304,12.0896307975,-0.250506224706,0.102273057006,0.68471813902,37.5750101522 +19.41,51.0026154982,0.000474357291484,11.2222848051,15.8519075802,12.1091327316,-0.251184652729,0.102483571123,0.687283904793,37.643587736 +19.42,51.0026169225,0.000476083786809,11.2248024145,15.8369931495,12.1287391195,-0.252337222646,0.103175271434,0.684117374234,37.7099520646 +19.43,51.0026183453,0.000477813120841,11.2273312438,15.8209942388,12.1489839692,-0.253428635636,0.103523390992,0.685589662485,37.7760868943 +19.44,51.0026197667,0.000479545319767,11.2298673876,15.8048756034,12.1689579703,-0.253800127518,0.103764656089,0.685766657663,37.847272351 +19.45,51.0026211867,0.000481280430316,11.2324099641,15.7896579638,12.189858834,-0.254715180119,0.104743349934,0.6879760808,37.9166538019 +19.46,51.0026226052,0.000483018336246,11.2349570904,15.7713641558,12.2082009508,-0.254710062052,0.104007816771,0.689457985552,37.9859069547 +19.47,51.0026240222,0.000484759040412,11.2375166819,15.7557027651,12.2291418869,-0.257208238859,0.103722448139,0.689053427415,38.0548778833 +19.48,51.0026254377,0.000486502634099,11.2400807197,15.7387852608,12.2487655368,-0.255599320336,0.104271417294,0.689951462566,38.1220916743 +19.49,51.0026268516,0.000488249029314,11.242633959,15.7212035592,12.2684711411,-0.255048548827,0.104772461465,0.691896487735,38.1920870312 +19.5,51.0026282641,0.000489998281398,11.2451931664,15.7056379842,12.2888717282,-0.256792941227,0.104514985741,0.690870310793,38.2622642848 +19.51,51.0026296751,0.000491750420993,11.2477614497,15.6894699845,12.3090074979,-0.25686370488,0.1056540169,0.692117513598,38.3313589875 +19.52,51.0026310847,0.000493505227226,11.2503260166,15.672813777,12.3263073,-0.256049686771,0.104278066088,0.692198863202,38.3976963018 +19.53,51.0026324928,0.000495262659795,11.2528817594,15.6571259201,12.3458772879,-0.255098864805,0.103902751344,0.69090204464,38.465167065 +19.54,51.0026338995,0.000497022820672,11.2554431843,15.641034561,12.3646086197,-0.257186110215,0.103830432905,0.693058965645,38.5357812985 +19.55,51.0026353047,0.00049878569921,11.2580102825,15.6241123628,12.3840291749,-0.256233533202,0.104709725061,0.694187717756,38.6052699012 +19.56,51.0026367083,0.000500551462397,11.2605808496,15.6060132367,12.4051047848,-0.257879889771,0.105338205631,0.693759455882,38.6726065779 +19.57,51.0026381104,0.000502320066231,11.2631590388,15.5900510817,12.4239076045,-0.257757951501,0.106327376263,0.696085244494,38.7405232317 +19.58,51.002639511,0.000504091385167,11.2657383028,15.5727632685,12.4432207336,-0.258094844201,0.10719743214,0.696394379089,38.8115770493 +19.59,51.0026409101,0.000505865516957,11.2683173199,15.55849577,12.463395852,-0.257708582638,0.107242713438,0.696536600307,38.8796424031 +19.6,51.002642308,0.000507642547942,11.2709038527,15.5438537513,12.4839210946,-0.259597973424,0.105870915637,0.698368041749,38.9492333755 +19.61,51.0026437045,0.000509422642135,11.273502702,15.5267614399,12.5063987854,-0.260171895794,0.107103222718,0.69891133729,39.0172752594 +19.62,51.0026450994,0.000511205615677,11.2761005805,15.5094746592,12.5243428297,-0.259403800849,0.105382664719,0.699328550365,39.0874007763 +19.63,51.0026464927,0.000512991171333,11.278705338,15.4916263276,12.5426477416,-0.261547698976,0.105109491286,0.701394029278,39.1562050477 +19.64,51.0026478845,0.000514779436223,11.2813162327,15.4759726117,12.5623763828,-0.260631240726,0.104271801811,0.702426022136,39.2236426795 +19.65,51.0026492749,0.000516570387023,11.2839188204,15.4598246296,12.5803538469,-0.259886291512,0.103009705946,0.704300351564,39.2948969933 +19.66,51.0026506639,0.000518364138745,11.2865216822,15.4447904642,12.6016971011,-0.26068607669,0.103788341056,0.704608913199,39.3611956157 +19.67,51.0026520514,0.000520160716806,11.2891329857,15.4264745708,12.6200314235,-0.2615746177,0.104878840256,0.704019562437,39.43126502 +19.68,51.0026534374,0.000521959992846,11.291756406,15.411442809,12.6395726237,-0.263109443214,0.104484012375,0.705183543982,39.5002147362 +19.69,51.002654822,0.000523762096211,11.2943819701,15.3949962354,12.6597228183,-0.262003381409,0.104534702292,0.70330657717,39.5700317155 +19.7,51.002656205,0.000525566796234,11.2970056865,15.3781301964,12.6760257358,-0.262739898513,0.105828574551,0.704744477547,39.6392014457 +19.71,51.0026575865,0.000527373972714,11.2996316247,15.3595786721,12.6944884699,-0.262447731274,0.105428580815,0.7057246225,39.7081127087 +19.72,51.0026589664,0.00052918401669,11.3022618112,15.3431784127,12.7162810578,-0.26358957223,0.107234401219,0.70733424016,39.7760693086 +19.73,51.0026603449,0.000530997133435,11.3049004317,15.3271697912,12.7376255964,-0.26413452419,0.109621140047,0.709130185257,39.8446183334 +19.74,51.0026617219,0.000532813213187,11.3075505858,15.311037534,12.7578772562,-0.265896293273,0.108904228305,0.710491026335,39.9113463934 +19.75,51.0026630976,0.000534632103404,11.3102062606,15.2966495069,12.7770802814,-0.265238676502,0.107705926424,0.710634596517,39.9779561639 +19.76,51.0026644718,0.000536453683932,11.3128662237,15.2799051368,12.7956451305,-0.266753948729,0.107717316208,0.710974568499,40.0482778666 +19.77,51.0026658447,0.000538278042868,11.3155342834,15.2671161423,12.8160849291,-0.266857991528,0.106631662694,0.711774323354,40.1161643961 +19.78,51.0026672163,0.000540105291596,11.3182042201,15.2504689258,12.8362134645,-0.267129336051,0.106468727534,0.710328004995,40.1875171882 +19.79,51.0026685864,0.000541935124428,11.3208793879,15.2323026874,12.8523618001,-0.267904231067,0.106677518427,0.711316584136,40.2544300654 +19.8,51.0026699548,0.000543767600381,11.323554837,15.2153623287,12.8733188429,-0.267185594978,0.106894990558,0.712567555018,40.322972007 +19.81,51.0026713217,0.000545602958344,11.3262282239,15.198496223,12.8928208817,-0.267491773683,0.10589746187,0.715171833987,40.3897270701 +19.82,51.0026726871,0.000547441278506,11.3289026918,15.1811207127,12.9149036793,-0.267401817068,0.107212316233,0.7168123125,40.4596107269 +19.83,51.002674051,0.000549282489642,11.3315761322,15.1641328875,12.933405811,-0.267286262341,0.105574059259,0.71758274078,40.5280517454 +19.84,51.0026754134,0.000551126320517,11.3342491815,15.1489145696,12.9516808015,-0.267323588059,0.105126305037,0.71774189056,40.5993321056 +19.85,51.0026767744,0.000552972935872,11.3369174301,15.1333338977,12.9724956839,-0.266326129556,0.106774904295,0.716614164693,40.6673540318 +19.86,51.0026781339,0.000554822297685,11.3395900852,15.1155616404,12.990236905,-0.268204886753,0.10325611468,0.717860849051,40.7388601246 +19.87,51.0026794919,0.000556674268465,11.3422717097,15.0997417814,13.0091215734,-0.26812001335,0.103599601323,0.721308511103,40.8080339494 +19.88,51.0026808484,0.000558528915448,11.3449532562,15.0820350021,13.0278067172,-0.268189285716,0.106486289103,0.720106486735,40.8748775507 +19.89,51.0026822034,0.000560386268745,11.3476376875,15.0657424649,13.0471140835,-0.268696991399,0.108890302891,0.722376031253,40.9444822793 +19.9,51.0026835568,0.00056224627085,11.3503246947,15.0473863522,13.0649919282,-0.268704439924,0.107098583464,0.72178367451,41.0117091361 +19.91,51.0026849087,0.00056410888128,11.3530241878,15.0323835939,13.0837309533,-0.271194186731,0.105634624654,0.720777917281,41.0821767604 +19.92,51.0026862593,0.000565974401831,11.3557302067,15.01703813,13.1058456434,-0.270009595765,0.107607693338,0.723472579011,41.1495742664 +19.93,51.0026876085,0.000567842916995,11.3584319128,15.0014381051,13.1257708372,-0.270331622918,0.108344998132,0.725349806043,41.218644318 +19.94,51.0026889561,0.000569714254888,11.3611415661,14.9842167918,13.1454724691,-0.271599020222,0.10930010848,0.723986308238,41.2868226586 +19.95,51.0026903023,0.000571588473133,11.3638600428,14.9678242754,13.1662066192,-0.272096320901,0.107420031379,0.725102207201,41.3562759151 +19.96,51.002691647,0.000573465385243,11.3665798273,14.9507959484,13.1832902167,-0.271860592119,0.107478883571,0.725131672455,41.4240595528 +19.97,51.0026929902,0.00057534490244,11.3693066441,14.9349579444,13.2027780383,-0.273502766919,0.107752952784,0.725501978371,41.4922553938 +19.98,51.002694332,0.000577227214919,11.372032748,14.9190125113,13.2225317064,-0.271718014961,0.10937622182,0.727410597336,41.5590072996 +19.99,51.0026956722,0.000579112430438,11.3747555196,14.9018815548,13.2435323459,-0.272836299746,0.107724855869,0.728805306873,41.6288009441 +20,51.0026970111,0.000581000583786,11.3774870704,14.8863769781,13.2637743875,-0.273473850381,0.110025447841,0.729169678345,41.6964321756 +20.01,51.0026983484,0.000582891574338,11.3802295934,14.8697335422,13.2833623937,-0.2750307507,0.106934111876,0.730724695402,41.7649259349 +20.02,51.0026996843,0.000584785366317,11.3829722525,14.8539519905,13.3031021528,-0.273501072778,0.106441547349,0.729911025562,41.8349311948 +20.03,51.0027010187,0.000586682050854,11.3857246852,14.8356014307,13.3239695174,-0.276985469756,0.107659458119,0.731448120291,41.9047283854 +20.04,51.0027023516,0.000588581597873,11.3884862485,14.8197269806,13.3432870688,-0.275327194919,0.108032292605,0.732015554368,41.9730304107 +20.05,51.002703683,0.00059048390953,11.3912407631,14.8036205989,13.3627808003,-0.275575727155,0.109216138922,0.731853900379,42.0420186974 +20.06,51.002705013,0.000592388987652,11.3939870373,14.7885100106,13.3821240267,-0.273679108407,0.112304292577,0.73310193195,42.1109591869 +20.07,51.0027063416,0.000594296863785,11.3967388324,14.7728728501,13.4020605929,-0.276679919786,0.111172694823,0.733712431111,42.1768624271 +20.08,51.0027076688,0.0005962075095,11.3995015049,14.7560408513,13.4210047346,-0.275854567728,0.1115926231,0.734341642196,42.2469517716 +20.09,51.0027089945,0.000598120943929,11.4022720265,14.7408299936,13.4412098691,-0.278249751258,0.11358515687,0.736129511098,42.3205961101 +20.1,51.0027103188,0.000600037191686,11.405055078,14.7242767913,13.460499577,-0.278360559735,0.11070149827,0.737734995628,42.3868833356 +20.11,51.0027116416,0.000601955983987,11.4078305284,14.7090423303,13.4769313267,-0.276729511801,0.111064261004,0.738470502082,42.4562957417 +20.12,51.0027129631,0.000603877465754,11.4106047878,14.6925520068,13.4982555222,-0.278122363343,0.112270076061,0.738546332722,42.5244490322 +20.13,51.002714283,0.000605801919101,11.4133983835,14.6763499986,13.5186478198,-0.280596793887,0.11097312767,0.739797778807,42.5942239849 +20.14,51.0027156015,0.000607729199482,11.4161936126,14.6583374828,13.5379427697,-0.278449013956,0.111368231568,0.739446831362,42.6607189412 +20.15,51.0027169184,0.000609659186446,11.4189809576,14.642158071,13.5566440912,-0.279019981342,0.110586151355,0.740987314376,42.729468851 +20.16,51.0027182338,0.000611591950447,11.4217655831,14.6251983249,13.5769280963,-0.277905123896,0.111930644234,0.740795318932,42.7984605375 +20.17,51.0027195476,0.000613527484636,11.4245398636,14.6082977942,13.5955333086,-0.27695098332,0.112023671064,0.74383467157,42.8652178644 +20.18,51.0027208599,0.000615465802642,11.4273138846,14.5899615759,13.6160086056,-0.277853210523,0.11227886271,0.742878213995,42.9355554054 +20.19,51.0027221707,0.00061740699835,11.4300936141,14.5733989352,13.6359318638,-0.278092693857,0.111134339403,0.743822901392,43.0055136049 +20.2,51.00272348,0.000619350998627,11.4328782773,14.5589570783,13.6553804686,-0.27883993702,0.111722803923,0.744528819827,43.0735235931 +20.21,51.0027247879,0.000621297889969,11.4356691405,14.540453362,13.6765180176,-0.279332703319,0.110081197997,0.745732541557,43.1447973035 +20.22,51.0027260942,0.000623247591137,11.4384660798,14.5249300009,13.694826107,-0.280055158574,0.110932081841,0.745676967701,43.2118426219 +20.23,51.0027273992,0.000625200062164,11.441272098,14.5111172264,13.7154025975,-0.281148489978,0.109805364023,0.748374968054,43.2794570473 +20.24,51.0027287027,0.000627155156627,11.4440866728,14.4920405316,13.7316550808,-0.281766471303,0.112006852139,0.747614872341,43.3485596117 +20.25,51.0027300047,0.000629112856459,11.4469114431,14.4771422461,13.7519779323,-0.283187589322,0.114346833252,0.74891318882,43.418615284 +20.26,51.0027313053,0.00063107325695,11.4497433723,14.4592743667,13.7695681548,-0.283198247563,0.114008923155,0.749307601823,43.4864886064 +20.27,51.0027326043,0.000633036287218,11.4525746638,14.4443591207,13.7888959263,-0.283060051052,0.115067482812,0.750163438284,43.5570806565 +20.28,51.002733902,0.000635002187917,11.4554023522,14.4279090151,13.8098646166,-0.282477619001,0.113616194039,0.750221117293,43.6246633106 +20.29,51.0027351982,0.000636970976252,11.458234023,14.4118738361,13.8294339338,-0.283856542093,0.111705607851,0.749595425435,43.6944399234 +20.3,51.0027364929,0.00063894252865,11.4610689086,14.3960900006,13.8486678023,-0.283120587256,0.111149475998,0.751919884907,43.76164522 +20.31,51.0027377861,0.000640916950833,11.4638969305,14.3780615914,13.8697213336,-0.282483779689,0.112439339019,0.750044099845,43.8292817206 +20.32,51.0027390779,0.000642894126925,11.4667255374,14.3626243943,13.8873284288,-0.283237609181,0.11275847162,0.752802786496,43.8993856096 +20.33,51.0027403681,0.000644874049643,11.469565218,14.3450861834,13.9082797376,-0.284698517693,0.115274443155,0.754092046743,43.9662860779 +20.34,51.0027416569,0.000646856906507,11.4724113701,14.3300462224,13.9285193525,-0.284531906307,0.115022306647,0.754795164676,44.035538197 +20.35,51.0027429443,0.000648842380067,11.4752562027,14.3133970445,13.9450140929,-0.284434603757,0.11551240906,0.755223898911,44.104640821 +20.36,51.0027442302,0.000650830376519,11.4780972847,14.297061942,13.9639367925,-0.283781791955,0.114556846222,0.755315120113,44.1742805416 +20.37,51.0027455146,0.000652821069569,11.480945525,14.2807450973,13.9828701511,-0.285866270375,0.113336638378,0.753886274673,44.2432729746 +20.38,51.0027467976,0.000654814719045,11.4838003232,14.2659367778,14.0054405028,-0.285093379287,0.115354385665,0.756251296654,44.3129963375 +20.39,51.0027480792,0.000656811330887,11.4866556929,14.2498253366,14.0244572476,-0.285980546275,0.115773902719,0.75857009874,44.37958291 +20.4,51.0027493593,0.000658810696256,11.4895201407,14.2326577777,14.0440957873,-0.28690902932,0.114801450031,0.760301889587,44.4489193796 +20.41,51.002750638,0.000660812793884,11.4923885101,14.2162725437,14.0628139204,-0.286764837476,0.115492352016,0.763635080875,44.5150722981 +20.42,51.0027519151,0.000662817456379,11.4952606661,14.1997844979,14.0801025065,-0.287666359264,0.116266567125,0.763512919647,44.5848637998 +20.43,51.0027531908,0.000664824796799,11.4981403912,14.1841789666,14.1004078396,-0.288278677319,0.114526525679,0.762104428804,44.6544758373 +20.44,51.0027544651,0.000666835094681,11.5010303388,14.1674380164,14.1216207462,-0.289710826703,0.115274143577,0.762465034525,44.7250340557 +20.45,51.0027557377,0.000668848316125,11.5039316741,14.1495589577,14.1414501831,-0.290556237946,0.115163331026,0.765662657263,44.7939609545 +20.46,51.0027570088,0.000670864338685,11.5068344033,14.1315998474,14.1609440866,-0.289989597676,0.11611569127,0.766533905335,44.8638150582 +20.47,51.0027582784,0.000672883037627,11.5097376799,14.1150218683,14.1790224155,-0.290665731662,0.115489465144,0.766238618574,44.9325542705 +20.48,51.0027595465,0.000674904518634,11.5126410086,14.1,14.2,-0.29,0.115,0.767,45 +20.49,51.002760813,0.000676928543403,11.5155419233,14.0799339604,14.2147328197,-0.290182941285,0.113080969087,0.769637143654,45.0686431302 +20.5,51.002762078,0.000678954853713,11.5184524979,14.0652414768,14.2320853413,-0.291931988865,0.111779454883,0.76956409859,45.1396759285 +20.51,51.0027633415,0.000680983314622,11.5213669915,14.0488775187,14.2449237324,-0.290966722616,0.112886426684,0.770035429092,45.2091203787 +20.52,51.0027646035,0.000683013787328,11.5242836658,14.0291280553,14.2603276425,-0.292368133939,0.112971987315,0.770559953609,45.2809118819 +20.53,51.0027658637,0.000685046347431,11.5271979798,14.0113380183,14.2742273698,-0.290494668523,0.113100502245,0.769508361423,45.3512737015 +20.54,51.0027671224,0.000687081023611,11.5301094033,13.9932860412,14.2900338973,-0.291790042949,0.113389200182,0.77022460642,45.4220405657 +20.55,51.0027683794,0.000689117762889,11.5330351401,13.9738354567,14.3031898936,-0.29335731701,0.113845392261,0.773005913694,45.4906473151 +20.56,51.0027696347,0.000691156566984,11.5359584389,13.9578504365,14.3190205205,-0.291302438911,0.11449206063,0.773223761761,45.5630212394 +20.57,51.0027708884,0.000693197522522,11.5388633113,13.9367297658,14.3333926612,-0.289672030372,0.113885431784,0.774579942054,45.6336262963 +20.58,51.0027721404,0.000695240666346,11.5417644663,13.9197714481,14.3497405138,-0.29055896791,0.112062660679,0.777169758148,45.7058743731 +20.59,51.0027733908,0.000697286098806,11.5446701943,13.9014351421,14.3655214211,-0.29058663446,0.112881282579,0.777422764815,45.7773876883 +20.6,51.0027746397,0.000699333551779,11.5475775984,13.8843203295,14.3781051773,-0.290894188291,0.11386328197,0.778138965739,45.8462813781 +20.61,51.002775887,0.000701382987732,11.5504780404,13.8680759355,14.3933591806,-0.289194224789,0.112882373524,0.780694665902,45.9165732541 +20.62,51.0027771326,0.000703434489875,11.553380531,13.8474295552,14.4071110836,-0.291303893649,0.113576704439,0.778722803904,45.9872143537 +20.63,51.0027783765,0.000705488096663,11.5562924283,13.8291179911,14.4229049506,-0.291075549568,0.11388369976,0.778276981221,46.0577943379 +20.64,51.0027796189,0.000707543912163,11.5592058531,13.8133812699,14.4381178062,-0.291609423304,0.11436332985,0.778862475833,46.1272205505 +20.65,51.0027808598,0.000709601847768,11.5621179605,13.7958911486,14.4526677783,-0.290812062967,0.11382208466,0.780987777023,46.1972206667 +20.66,51.0027820992,0.000711661817744,11.5650251868,13.7796246036,14.4666770102,-0.290633177999,0.113829473883,0.782048977354,46.2689693527 +20.67,51.002783337,0.000713723926882,11.5679395594,13.7621630052,14.4826981246,-0.292241350589,0.113514451133,0.782507958147,46.3390783942 +20.68,51.0027845733,0.000715788273859,11.5708647122,13.744538417,14.4980926398,-0.29278920693,0.114866131107,0.781423271059,46.4084945403 +20.69,51.002785808,0.00071785471992,11.5737979003,13.7265489557,14.5121658324,-0.293848412896,0.115143405753,0.782155187334,46.4785213779 +20.7,51.002787041,0.000719923285774,11.576736682,13.7076539827,14.5278510525,-0.293907929859,0.113815649294,0.781655048614,46.5488033655 +20.71,51.0027882722,0.000721993944755,11.5796818236,13.6877284572,14.5415498987,-0.29512039249,0.115347008092,0.782731830885,46.620276637 +20.72,51.0027895018,0.000724066697685,11.5826237656,13.6704837133,14.5572466721,-0.293268000627,0.11396171945,0.785710428391,46.690675278 +20.73,51.0027907298,0.00072614167582,11.5855529348,13.6520046238,14.5727881722,-0.292565846256,0.111626510378,0.787012154295,46.7606613159 +20.74,51.0027919561,0.000728218801275,11.5884774514,13.6332345841,14.58739153,-0.292337476357,0.111281283713,0.787021857158,46.8298668691 +20.75,51.0027931808,0.000730298054135,11.5914022154,13.6158028794,14.6026534507,-0.292615312299,0.11030675382,0.786713329777,46.9004106329 +20.76,51.0027944039,0.000732379451306,11.5943268455,13.5980457675,14.6174941628,-0.292310716531,0.112076688378,0.78916294749,46.9723691473 +20.77,51.0027956254,0.000734463009664,11.5972514467,13.5793138724,14.6329929835,-0.292609520281,0.111976261549,0.78955118921,47.04315893 +20.78,51.0027968453,0.000736548714325,11.6001819224,13.5617900724,14.6476247606,-0.293485621595,0.114082810774,0.789472211083,47.1116254523 +20.79,51.0027980636,0.000738636544835,11.6031167879,13.5452230808,14.6628364088,-0.293487482295,0.112902857477,0.788815612167,47.1818368997 +20.8,51.0027992802,0.000740726465675,11.6060609337,13.5254866023,14.6769695659,-0.295341666126,0.113597451907,0.790529200133,47.2502332502 +20.81,51.0028004953,0.000742818379148,11.6090163696,13.5096155383,14.6908096575,-0.29574552858,0.11195410917,0.792521915929,47.3210145031 +20.82,51.0028017087,0.000744912312241,11.6119770566,13.4884454474,14.7053216838,-0.296391871581,0.111525200375,0.794106681205,47.3920344334 +20.83,51.0028029203,0.000747008439245,11.6149397227,13.4695471615,14.7216085921,-0.296141336949,0.115044711289,0.795145092064,47.4632044407 +20.84,51.0028041304,0.000749106849195,11.6179040956,13.4531672528,14.7373705744,-0.296733238177,0.114877533454,0.793559101269,47.5321294185 +20.85,51.0028053388,0.000751207271666,11.6208733516,13.4338505716,14.7498610446,-0.297117976976,0.116455995536,0.794235513111,47.6007583459 +20.86,51.0028065455,0.000753309769641,11.6238435921,13.4149532589,14.7665072245,-0.29693012093,0.115820218166,0.795787191705,47.672975774 +20.87,51.0028077506,0.000755414553268,11.626812738,13.3980196879,14.7819479042,-0.296899046167,0.114943975534,0.796663169141,47.7414005102 +20.88,51.0028089541,0.000757521367606,11.6297791642,13.3802651514,14.7950150534,-0.296386207298,0.112924978474,0.798069166775,47.8111294448 +20.89,51.002810156,0.000759629893003,11.6327539891,13.3601533028,14.805968214,-0.298578767933,0.111818756648,0.798665948413,47.8799345108 +20.9,51.0028113561,0.000761740433051,11.6357301567,13.3436276788,14.8232974054,-0.296654744348,0.110998351756,0.798596996347,47.9513162122 +20.91,51.0028125547,0.000763853140138,11.6386828019,13.324336038,14.8363899067,-0.293874308048,0.111842251932,0.797981887367,48.0221100008 +20.92,51.0028137517,0.000765967936137,11.6416297772,13.3073101153,14.8526222939,-0.295520746048,0.113267419188,0.800013561798,48.0912572009 +20.93,51.002814947,0.00076808498102,11.6445898511,13.289485475,14.8679605845,-0.296494037038,0.111907390834,0.797397755235,48.1629375777 +20.94,51.0028161409,0.000770204266219,11.6475645938,13.2727747335,14.8840726967,-0.298454499664,0.112211333273,0.800063517792,48.232660494 +20.95,51.0028173331,0.000772325694131,11.6505476444,13.2551049471,14.8980407544,-0.298155617875,0.111859474631,0.79948877492,48.304452744 +20.96,51.0028185239,0.000774449160291,11.6535385705,13.238427749,14.9126863368,-0.300029599409,0.112658943383,0.802705556915,48.3734991764 +20.97,51.002819713,0.000776574592895,11.6565420522,13.2187517772,14.9256463313,-0.300666749854,0.110122481658,0.802742283752,48.4442424479 +20.98,51.0028209004,0.00077870202734,11.659544973,13.2018949228,14.9407888626,-0.299917401392,0.111386175221,0.804674515782,48.5130944295 +20.99,51.0028220863,0.000780831635375,11.6625539061,13.1830617543,14.9561599825,-0.301869225809,0.113583475423,0.807282952744,48.5845024606 +21,51.0028232706,0.000782963390093,11.6655737674,13.166915746,14.9709247684,-0.302103041646,0.110882894919,0.805807737944,48.6559881377 +21.01,51.0028244533,0.000785097229262,11.668600758,13.1486740669,14.985422233,-0.303295065182,0.109653727233,0.807074165297,48.7249221622 +21.02,51.0028256344,0.000787233118976,11.6716258138,13.1299888867,14.9997110393,-0.301716107225,0.108979410255,0.80686220905,48.7937645945 +21.03,51.0028268139,0.000789371238151,11.6746393287,13.1145338675,15.0167202299,-0.300986860761,0.109267592428,0.807654295997,48.8671638803 +21.04,51.0028279919,0.000791511698852,11.6776594879,13.0948119387,15.0325822832,-0.30304498904,0.111057629859,0.807790956756,48.9373099159 +21.05,51.0028291681,0.000793654429353,11.6806871548,13.0750057162,15.0485845568,-0.30248837696,0.11160819722,0.808820993821,49.0053469914 +21.06,51.0028303426,0.000795799417188,11.6837151153,13.0582093713,15.0642715831,-0.30310373066,0.1131262846,0.809436391063,49.0764947411 +21.07,51.0028315157,0.000797946493952,11.6867478121,13.0417821736,15.0779096753,-0.303435630296,0.112176164583,0.809046657384,49.1480133676 +21.08,51.0028326871,0.000800095659196,11.6897832899,13.0228818813,15.0935903956,-0.303659927609,0.111845001266,0.810293648214,49.2199020842 +21.09,51.0028338569,0.000802246938411,11.6928248863,13.003294264,15.1075863347,-0.304659344868,0.112260750064,0.810233491178,49.2875829884 +21.1,51.002835025,0.000804400200951,11.6958725016,12.9862125075,15.1214329851,-0.30486372118,0.111769768188,0.812069294934,49.3590447695 +21.11,51.0028361914,0.00080655564085,11.6989275952,12.967377625,15.1381528911,-0.306155004893,0.111339854895,0.812079713561,49.4263917522 +21.12,51.0028373563,0.000808713222154,11.7019854942,12.9500181688,15.151494778,-0.305424796733,0.111932292321,0.813418820557,49.4987428605 +21.13,51.0028385195,0.000810872788789,11.7050379007,12.9312837846,15.1660236353,-0.30505650126,0.108939795304,0.814101320386,49.5718180621 +21.14,51.0028396811,0.00081303452547,11.7080958802,12.9134658862,15.1819586678,-0.306539392091,0.110353119723,0.812754170932,49.6402323743 +21.15,51.002840841,0.000815198384735,11.7111642041,12.8938884239,15.1958212191,-0.30712539453,0.110829647323,0.815092532751,49.7099526139 +21.16,51.0028419992,0.000817364440191,11.7142382463,12.8767167244,15.2127896105,-0.307683042335,0.110810361791,0.816584756946,49.7799307267 +21.17,51.0028431559,0.000819532755631,11.7173100225,12.8588562073,15.2275477121,-0.30667219116,0.110707397589,0.816006905062,49.8505695431 +21.18,51.0028443109,0.000821703151909,11.7203840643,12.840754965,15.242001139,-0.308136184363,0.112052655986,0.818500492836,49.9211103128 +21.19,51.0028454644,0.000823875505261,11.7234657419,12.8245094598,15.2550217513,-0.308199325593,0.110663082655,0.819523376243,49.9905953341 +21.2,51.0028466164,0.000826049895034,11.7265516069,12.8052519377,15.2705890994,-0.308973676034,0.109366626755,0.818389070867,50.0626482702 +21.21,51.0028477666,0.000828226507046,11.7296289354,12.7872209194,15.2862183673,-0.306492014915,0.109881896556,0.820610950342,50.1339095405 +21.22,51.0028489152,0.00083040522148,11.7327022154,12.7680943121,15.3001036351,-0.308163992064,0.110090294913,0.821579262661,50.2056940631 +21.23,51.0028500621,0.000832585992032,11.7357937918,12.7517772017,15.3150828454,-0.31015129761,0.108126882636,0.8208040977,50.2735669557 +21.24,51.0028512075,0.000834768822061,11.7388866907,12.7319900205,15.3290152863,-0.30842846671,0.110069182133,0.821927153126,50.3457466646 +21.25,51.0028523511,0.000836953684563,11.7419712495,12.7135227663,15.3436153844,-0.30848330134,0.109319346323,0.823511778801,50.4181964765 +21.26,51.0028534932,0.000839140657982,11.745061834,12.6972511436,15.3586490862,-0.30963359439,0.110341520972,0.824946119081,50.4879752137 +21.27,51.0028546338,0.000841329762274,11.7481515015,12.6804775025,15.3735293259,-0.308299900097,0.108680611039,0.826238794678,50.56053369 +21.28,51.0028557728,0.00084352091352,11.7512390303,12.6614970524,15.387384921,-0.309205878522,0.108310248513,0.826051600144,50.6256232397 +21.29,51.0028569101,0.00084571412894,11.7543417181,12.6435125119,15.4025069059,-0.311331664358,0.107616943957,0.827729224008,50.695928328 +21.3,51.0028580459,0.0008479095192,11.7574521942,12.6269320927,15.4179161083,-0.310763557468,0.107009989808,0.829157194936,50.7689728257 +21.31,51.0028591801,0.000850107007306,11.7605543957,12.6093893965,15.4319571923,-0.309676746567,0.107423162144,0.828800144444,50.8413538013 +21.32,51.0028603127,0.000852306625873,11.7636527295,12.5900432084,15.447824278,-0.309990020706,0.106572799859,0.827392797959,50.9087614545 +21.33,51.0028614436,0.000854508506902,11.7667533475,12.5732182668,15.4637184723,-0.310133574506,0.10722836228,0.827896589624,50.9750103545 +21.34,51.002862573,0.000856712509117,11.7698586551,12.5545959425,15.477602229,-0.310927941069,0.107985413256,0.829628384775,51.0461177097 +21.35,51.0028637007,0.000858918545574,11.7729697716,12.5368933813,15.4922758497,-0.31129536408,0.109598360288,0.830810170058,51.1184326083 +21.36,51.0028648268,0.000861126698706,11.7760820586,12.5186841018,15.5073168417,-0.311162028144,0.109135730423,0.831208904295,51.1878508205 +21.37,51.0028659513,0.000863336899435,11.7791973724,12.5003710437,15.5210207165,-0.311900734938,0.108221332084,0.832369327081,51.2572411452 +21.38,51.0028670742,0.0008655491152,11.7823226751,12.4838412016,15.5356045838,-0.313159802987,0.108947062825,0.833814190951,51.3267785325 +21.39,51.0028681954,0.000867763383491,11.7854465228,12.4631816647,15.5498347698,-0.311609741293,0.106991027135,0.835316024824,51.3979411507 +21.4,51.002869315,0.000869979895417,11.7885667677,12.4472066235,15.5671015655,-0.312439244364,0.109029337565,0.835390242218,51.4694282359 +21.41,51.0028704331,0.000872198799145,11.7916911319,12.4304541128,15.5834118202,-0.312433585375,0.109343657198,0.835474025712,51.5391507839 +21.42,51.0028715495,0.000874419911712,11.7948123432,12.4091140705,15.5981100308,-0.311808680544,0.110621619034,0.83675061518,51.6097221862 +21.43,51.0028726641,0.000876643035389,11.7979318532,12.3916725966,15.6116444604,-0.31209332867,0.11056010592,0.835451261766,51.6814597367 +21.44,51.0028737773,0.000878868125923,11.8010553983,12.3747488275,15.6257213958,-0.312615674518,0.108631321908,0.838336468984,51.7506323211 +21.45,51.0028748888,0.000881095196292,11.8041900475,12.3573617449,15.639438037,-0.314314176602,0.110426374249,0.838576323836,51.8204740669 +21.46,51.0028759987,0.000883324378177,11.8073326172,12.3381177691,15.6553635896,-0.314199757793,0.111206933377,0.841629278348,51.8903766878 +21.47,51.0028771069,0.000885555860359,11.810487404,12.3179197621,15.6717304567,-0.316757607413,0.110819315624,0.842072874379,51.961547491 +21.48,51.0028782134,0.00088778943253,11.8136521148,12.3022703127,15.6847035943,-0.316184556595,0.111437895782,0.844139072772,52.0295714395 +21.49,51.0028793185,0.00089002485726,11.8168230033,12.2842074249,15.6977372147,-0.317993145448,0.110349396422,0.844022524669,52.0998563931 +21.5,51.0028804219,0.000892262350813,11.8199958724,12.2662352554,15.7137464391,-0.31658065925,0.109448825519,0.84468231057,52.1724167803 +21.51,51.0028815236,0.00089450218219,11.8231659423,12.2470539361,15.7305564825,-0.317433317136,0.107394499609,0.843719450235,52.2430455447 +21.52,51.0028826238,0.000896744190322,11.8263321745,12.2311151384,15.7443044999,-0.315813138204,0.108455625377,0.84396207815,52.3140552617 +21.53,51.0028837224,0.00089898824239,11.8294887684,12.2134283027,15.759249943,-0.315505629803,0.10843098315,0.847783084499,52.3814636174 +21.54,51.0028848195,0.000901234363292,11.8326561813,12.1957138846,15.7733474853,-0.317976948708,0.108738439119,0.847574518585,52.451600562 +21.55,51.0028859149,0.000903482550792,11.8358279323,12.1775799234,15.7882615572,-0.316373253095,0.109826770042,0.847783172862,52.5218005002 +21.56,51.0028870087,0.000905732897158,11.8389902087,12.1601531633,15.8036543941,-0.316082025884,0.10775126093,0.846503529481,52.5946788869 +21.57,51.002888101,0.000907985448594,11.8421480556,12.142203531,15.8192171411,-0.315487363739,0.106793220303,0.846550946519,52.6636730126 +21.58,51.0028891916,0.000910240211727,11.8453057751,12.1236437396,15.8347029818,-0.316056531771,0.107373066591,0.847639596804,52.7361203121 +21.59,51.0028902806,0.000912497176925,11.8484732391,12.1057047577,15.8501305296,-0.317436265925,0.108299173433,0.848392339253,52.8054286206 +21.6,51.002891368,0.000914756223677,11.8516459758,12.0879522115,15.8639245491,-0.317111075982,0.107730820563,0.848307165348,52.8766752898 +21.61,51.0028924537,0.000917017251271,11.8548195994,12.0701439967,15.8779382253,-0.317613654376,0.108800142449,0.847043292399,52.9439675585 +21.62,51.0028935379,0.000919280411551,11.857993868,12.0524503292,15.8938639357,-0.317240061659,0.107031090286,0.849063501485,53.0157332038 +21.63,51.0028946205,0.0009215457107,11.8611638397,12.0351119737,15.9079644295,-0.31675427453,0.106602993469,0.848306298602,53.0860518979 +21.64,51.0028957014,0.000923813148758,11.8643334869,12.0153819917,15.9238906658,-0.317175157706,0.10749947058,0.85113462146,53.1578780272 +21.65,51.0028967807,0.000926082883628,11.8675107096,11.9984402437,15.9402079499,-0.318269397563,0.105697223175,0.851788683163,53.2286743412 +21.66,51.0028978584,0.000928354678723,11.8706925826,11.9804552892,15.9528127867,-0.318105198578,0.105282348965,0.853122083356,53.2960791607 +21.67,51.0028989346,0.000930628329198,11.8738782761,11.9631583909,15.9662543382,-0.319033494216,0.10776212677,0.854209381893,53.3661681921 +21.68,51.0029000091,0.000932903979044,11.8770738945,11.9442512884,15.9808806002,-0.320090191752,0.106393160161,0.855454306238,53.4360020034 +21.69,51.0029010819,0.000935181874844,11.8802805836,11.9251146215,15.9977838502,-0.32124762364,0.106339979029,0.856277415106,53.5074568589 +21.7,51.0029021531,0.000937462109087,11.883489466,11.908362399,16.0137085591,-0.320528857643,0.106782794338,0.857554832158,53.5784579868 +21.71,51.0029032228,0.000939744424429,11.8866954075,11.8924017595,16.0269990282,-0.320659434586,0.107909757666,0.857424772899,53.6494553176 +21.72,51.0029042909,0.000942028696723,11.8899035336,11.8722938175,16.0411808561,-0.320965785173,0.107387959032,0.856780971513,53.7184054636 +21.73,51.0029053572,0.000944315139658,11.8931117532,11.8530984233,16.0574712671,-0.320678138126,0.106112171849,0.856025494924,53.7895239027 +21.74,51.0029064219,0.000946603790243,11.896310008,11.835573191,16.07217264,-0.31897283352,0.104983233649,0.857986847477,53.8598693382 +21.75,51.002907485,0.000948894475816,11.8995075958,11.8185684682,16.0860390859,-0.320544723118,0.104078700255,0.856264638911,53.9299154765 +21.76,51.0029085465,0.00095118714363,11.9027103194,11.8,16.1,-0.32,0.105,0.859,54 +21.77,51.0029096063,0.000953481697795,11.9059220701,11.7796106655,16.1125202408,-0.322350142883,0.104669952687,0.859418600446,54.070111677 +21.78,51.0029106641,0.000955778255472,11.9091350209,11.7577162621,16.1281259462,-0.320239999185,0.103074640557,0.860017259324,54.1392167504 +21.79,51.0029117201,0.000958076857039,11.9123487537,11.7373284563,16.1412130586,-0.322506569825,0.106292875117,0.860595857471,54.2090286581 +21.8,51.0029127742,0.000960377474539,11.9155714591,11.7160993163,16.1564262662,-0.322034515455,0.104114673038,0.86206424711,54.2777625472 +21.81,51.0029138264,0.000962680214351,11.9187963053,11.6947488632,16.1710068221,-0.322934715726,0.104563227514,0.863815620154,54.3462291371 +21.82,51.0029148766,0.000964985041153,11.9220204256,11.6727513899,16.1857241333,-0.321889350473,0.104140788115,0.862530773708,54.4148788223 +21.83,51.002915925,0.00096729186538,11.9252419419,11.6519584341,16.199047323,-0.322413911817,0.102863018167,0.862564761179,54.4839726551 +21.84,51.0029169714,0.000969600547398,11.9284677114,11.6312375211,16.2118043556,-0.322739988177,0.101552749865,0.862891587584,54.5550013227 +21.85,51.002918016,0.000971911013386,11.9316999566,11.6116766743,16.2240911916,-0.323709048297,0.103017289333,0.86466419665,54.626605025 +21.86,51.0029190589,0.000974223473237,11.9349366602,11.5904170437,16.23979487,-0.323631665523,0.10200572105,0.866486542684,54.6948106674 +21.87,51.0029200997,0.000976538097689,11.9381712807,11.567946303,16.2544786075,-0.323292441226,0.0989989769318,0.865042723246,54.7655011814 +21.88,51.0029211385,0.000978854636528,11.9414119717,11.5456062347,16.2666696307,-0.324845765971,0.099834068763,0.863688402849,54.8343476315 +21.89,51.0029221754,0.000981173188294,11.9446617531,11.5243715932,16.2827367339,-0.325110504401,0.0978851387509,0.863980008095,54.903378486 +21.9,51.0029232104,0.000983493929353,11.9479117288,11.5045750902,16.297403711,-0.324884629781,0.0977649877072,0.866430306282,54.9735872474 +21.91,51.0029242436,0.000985816776499,11.9511582516,11.4842069376,16.3123026987,-0.324419937994,0.0978791706736,0.867907448667,55.0408070646 +21.92,51.002925275,0.000988141515828,11.954407648,11.4628854387,16.3239667548,-0.325459343451,0.100957427788,0.868397516049,55.1125105181 +21.93,51.0029263044,0.000990467964897,11.9576564479,11.4411051004,16.3363044901,-0.324300637773,0.103153065644,0.869285080558,55.1805678753 +21.94,51.0029273318,0.000992796243606,11.9609013755,11.4197779316,16.3496517743,-0.324684881769,0.103579663049,0.870900739282,55.2512259929 +21.95,51.0029283574,0.000995126516716,11.9641543568,11.3981789403,16.3643025365,-0.325911370136,0.104958777481,0.868914904077,55.3208276348 +21.96,51.002929381,0.000997458934065,11.9674115817,11.3775062782,16.3797533485,-0.32553361318,0.103028007113,0.871107409158,55.3932862164 +21.97,51.0029304028,0.000999793559273,11.9706749913,11.35613769,16.395297266,-0.327148317267,0.101374715378,0.871799084314,55.4618050327 +21.98,51.0029314226,0.00100213035353,11.9739433589,11.3356664811,16.4102031837,-0.326525187306,0.101570165977,0.869676896018,55.529651178 +21.99,51.0029324407,0.00100446914573,11.977210355,11.315331581,16.4233450416,-0.326874044447,0.100250072487,0.871690280056,55.5978657793 +22,51.0029334569,0.00100680995315,11.9804795261,11.295372307,16.438493556,-0.326960172093,0.101091809091,0.873192216717,55.6689582669 +22.01,51.0029344712,0.00100915284795,11.983751476,11.2733134924,16.4526484423,-0.32742980491,0.102267910475,0.874508839877,55.7383735945 +22.02,51.0029354836,0.00101149778589,11.9870232881,11.2509651531,16.4671757454,-0.32693261373,0.102635806421,0.877224851683,55.8080688571 +22.03,51.002936494,0.00101384474645,11.9902912227,11.230487868,16.4810427179,-0.326654301222,0.104410972091,0.875899913063,55.8758472299 +22.04,51.0029375025,0.0010161938039,11.9935668896,11.2095559639,16.4966124492,-0.328479077149,0.101972294915,0.878282436413,55.9476159511 +22.05,51.0029385092,0.00101854500597,11.9968539804,11.1887868311,16.511149878,-0.328939101757,0.0989692123141,0.877923062731,56.0181408297 +22.06,51.002939514,0.00102089813368,12.0001514645,11.1679835667,16.523644943,-0.330557711765,0.100325599372,0.878868207224,56.087510334 +22.07,51.002940517,0.00102325311061,12.0034553274,11.1474108379,16.5371100259,-0.330214858666,0.100928996118,0.880026079412,56.157049592 +22.08,51.002941518,0.00102561002073,12.006746454,11.1256009993,16.5507834615,-0.328010464661,0.101061503501,0.881147860044,56.2253374636 +22.09,51.0029425171,0.00102796898795,12.0100304705,11.1041181649,16.5659883384,-0.328792830199,0.102905658195,0.879807271011,56.2961024241 +22.1,51.0029435144,0.00103032997449,12.0133149527,11.08383231,16.5791314012,-0.328103616085,0.103010895086,0.882420126609,56.364893971 +22.11,51.0029445097,0.00103269299895,12.0165915495,11.0631322485,16.5945973141,-0.327215753289,0.102383366537,0.883076087757,56.4339445152 +22.12,51.0029455032,0.00103505817303,12.0198710919,11.040910917,16.6093086371,-0.328692710676,0.103717033026,0.884801708138,56.5052194328 +22.13,51.0029464947,0.00103742538708,12.0231458389,11.0207188005,16.6232348762,-0.326256696786,0.103377946244,0.884524694377,56.5746437971 +22.14,51.0029474844,0.0010397944706,12.026410149,10.9988364949,16.6355529408,-0.326605322045,0.104373703185,0.887101661774,56.6422346872 +22.15,51.0029484721,0.00104216546861,12.0296784798,10.9774015347,16.6501111555,-0.327060837671,0.101625897194,0.888273974037,56.7140947551 +22.16,51.0029494579,0.00104453846227,12.032953745,10.9562830286,16.6635684525,-0.327992207798,0.100814857649,0.887579883381,56.7814708958 +22.17,51.0029504418,0.00104691340132,12.0362227395,10.9359091142,16.6774210722,-0.325806685492,0.099476503769,0.890327047761,56.8489110615 +22.18,51.0029514239,0.00104929036179,12.0394893429,10.9136491452,16.6919458633,-0.327513996848,0.0998912580981,0.889813761291,56.9192511402 +22.19,51.0029524039,0.00105166935038,12.0427629145,10.8919451108,16.7058926347,-0.327200331566,0.101479203916,0.888795801822,56.9884131413 +22.2,51.002953382,0.00105405025624,12.0460415604,10.8705481918,16.7188608595,-0.328528832826,0.100050851791,0.890000368112,57.0583956668 +22.21,51.0029543582,0.00105643304845,12.0493248465,10.8502731728,16.7323739722,-0.328128399907,0.0995365767592,0.89232493084,57.1287956207 +22.22,51.0029553326,0.00105881783042,12.0526042269,10.8293536495,16.7467937389,-0.327747673616,0.0989413833918,0.892736867825,57.1977645222 +22.23,51.0029563051,0.0010612043133,12.0558877247,10.809381432,16.7562517254,-0.328951890203,0.100862409088,0.894438231061,57.266216347 +22.24,51.0029572758,0.0010635926608,12.0591799051,10.7877600143,16.7729698945,-0.329484185197,0.0993675589376,0.895099079392,57.3376495905 +22.25,51.0029582444,0.00106598314202,12.0624636828,10.7634332968,16.7862057382,-0.327271361894,0.103046152144,0.896085515727,57.4089904715 +22.26,51.0029592111,0.00106837574688,12.0657439635,10.7459088577,16.8027820895,-0.328784770343,0.101977977328,0.894338098385,57.4768963697 +22.27,51.0029601761,0.00107077057014,12.0690318039,10.7239651442,16.8173486196,-0.328783318568,0.100118236876,0.895090753876,57.5488361454 +22.28,51.0029611392,0.0010731672982,12.0723227246,10.7045074689,16.8295221501,-0.329400810795,0.0993681855177,0.89584745171,57.6175806248 +22.29,51.0029621004,0.00107556583435,12.0756276813,10.6815040991,16.842731215,-0.331590530186,0.0997211250336,0.895431832241,57.6855437969 +22.3,51.0029630596,0.00107796642025,12.0789409853,10.6621991798,16.8582971302,-0.331070274014,0.0998544595239,0.898295263151,57.756082208 +22.31,51.0029640172,0.00108036924499,12.0822502226,10.6426502728,16.874160937,-0.330777176479,0.0981321612092,0.898240543867,57.8251783492 +22.32,51.002964973,0.00108277421044,12.0855633634,10.6229830945,16.8883491374,-0.331850993415,0.0993566975289,0.901036453648,57.8939683 +22.33,51.0029659268,0.00108518120208,12.0888883822,10.6001799589,16.9026052002,-0.333152758916,0.0989562645126,0.902328268564,57.9656243611 +22.34,51.0029668787,0.00108759015281,12.0922179993,10.5786820486,16.9158515268,-0.332770662979,0.0988297001344,0.902724314753,58.0343314238 +22.35,51.0029678286,0.00109000124486,12.0955475354,10.5576767022,16.9326658773,-0.333136563203,0.0963216867856,0.903881976979,58.1050004334 +22.36,51.0029687768,0.00109241446724,12.0988784609,10.5375650517,16.9457578002,-0.33304853712,0.0985919846754,0.905251700025,58.1710072605 +22.37,51.0029697229,0.00109482951361,12.1022109111,10.5134896708,16.9582715954,-0.333441492197,0.0979858802033,0.90514460509,58.2428056431 +22.38,51.0029706671,0.00109724647519,12.1055516558,10.4938140497,16.9726440953,-0.334707466241,0.0979640863809,0.905315390517,58.311021807 +22.39,51.0029716093,0.00109966540884,12.108899882,10.4719130748,16.9859561927,-0.334937768019,0.0971788407538,0.905955173659,58.3798809029 +22.4,51.0029725498,0.00110208633553,12.1122462844,10.451930213,17.0006229361,-0.334342715666,0.0983230861131,0.906478537934,58.4506651914 +22.41,51.0029734884,0.00110450929469,12.1155808973,10.4327201255,17.0144887562,-0.33257985824,0.0987011201544,0.908364146753,58.5165606264 +22.42,51.0029744251,0.00110693431823,12.1189129348,10.4086921261,17.0296034784,-0.333827639742,0.0989283005601,0.90667662182,58.5887019329 +22.43,51.0029753598,0.00110936147499,12.1222585865,10.3883151479,17.0444355894,-0.335302707439,0.0980616818781,0.905628695303,58.6594776225 +22.44,51.0029762927,0.00111179074415,12.1256104172,10.3683975694,17.0592580789,-0.33506341853,0.0976321632005,0.910258987721,58.7289646972 +22.45,51.0029772239,0.00111422192253,12.1289604345,10.3491699968,17.0712379031,-0.334940052379,0.0993015035331,0.909234971085,58.7998047787 +22.46,51.002978153,0.00111665505592,12.1323151883,10.3247377727,17.0867030686,-0.336010703637,0.0986806997609,0.910011221643,58.8705076131 +22.47,51.0029790801,0.00111909029841,12.1356779672,10.3028255108,17.1008462409,-0.336545071703,0.0988295755276,0.912575903236,58.9399391922 +22.48,51.0029800053,0.00112152747041,12.1390370476,10.2822422938,17.1137900644,-0.33527100842,0.0995683103031,0.912042685933,59.0095706381 +22.49,51.0029809286,0.00112396664967,12.1423926987,10.2616918389,17.1290248033,-0.335859215365,0.101810428505,0.915557066572,59.0785644293 +22.5,51.0029818501,0.00112640787356,12.1457615449,10.2405417201,17.1424933146,-0.337910025475,0.0991123364469,0.913983306321,59.1493627733 +22.51,51.0029827697,0.00112885099015,12.1491432487,10.2198254115,17.155595157,-0.338430737551,0.0972043156177,0.914326165751,59.2206282172 +22.52,51.0029836874,0.00113129604872,12.1525212094,10.1993921312,17.169755485,-0.337161403099,0.100573920656,0.917282004669,59.2880361006 +22.53,51.0029846032,0.00113374310064,12.1558977011,10.1764804507,17.1835783129,-0.338136937777,0.101142364622,0.917591509002,59.3597777456 +22.54,51.0029855171,0.00113619231139,12.1592795661,10.1567219202,17.2000621004,-0.338236058807,0.100494078212,0.917475984275,59.4272458078 +22.55,51.0029864291,0.00113864375024,12.1626612646,10.1354182366,17.2148571265,-0.338103633266,0.099954556544,0.917993182742,59.4956899631 +22.56,51.0029873391,0.00114109708664,12.1660412077,10.1130767371,17.2267004033,-0.337884989716,0.0990618569344,0.917102032846,59.5660912506 +22.57,51.0029882472,0.00114355215559,12.1694205548,10.0917219534,17.2391792585,-0.337984443356,0.099425588365,0.91736688881,59.6355722761 +22.58,51.0029891535,0.00114600917009,12.1728038455,10.0717547473,17.2540127023,-0.338673693389,0.0979558352461,0.918611702851,59.7050027892 +22.59,51.0029900579,0.00114846834693,12.1761890628,10.0512906074,17.269534869,-0.338369753356,0.0980114544707,0.91872485716,59.7741903557 +22.6,51.0029909604,0.00115092959996,12.1795700187,10.0290366575,17.2831590306,-0.337821436245,0.0972155424941,0.918547356191,59.8457048813 +22.61,51.0029918609,0.00115339294354,12.1829548532,10.0077086809,17.2988826266,-0.339145461842,0.0961297807457,0.920831288493,59.9154297338 +22.62,51.0029927595,0.00115585832734,12.1863459845,9.98549783872,17.3118004649,-0.339080794784,0.0962054403104,0.922394997293,59.9850179756 +22.63,51.0029936561,0.00115832579634,12.1897401348,9.96359572988,17.3281552975,-0.339749269761,0.0952794662001,0.923320887697,60.0513874158 +22.64,51.0029945508,0.00116079530656,12.19314536,9.9424937705,17.340455948,-0.341295777744,0.0966743996162,0.922200263568,60.1208936562 +22.65,51.0029954435,0.00116326670834,12.1965651102,9.91995982894,17.3547094177,-0.342654263592,0.0958382967766,0.922350098829,60.1934489847 +22.66,51.0029963342,0.00116574018509,12.1999853426,9.89916527601,17.3695853139,-0.341392216763,0.0969752930205,0.923044226103,60.2609719632 +22.67,51.0029972232,0.00116821561059,12.2033943028,9.88049107287,17.3820664056,-0.340399813321,0.0959505764428,0.922696752041,60.330157878 +22.68,51.0029981104,0.00117069302531,12.2068010329,9.85840697066,17.397510722,-0.340946207792,0.0963898579752,0.924047127256,60.4007311754 +22.69,51.0029989956,0.00117317256051,12.210214269,9.83714333071,17.4118345514,-0.341701005753,0.0955183195254,0.924603138732,60.4706677285 +22.7,51.0029998789,0.0011756541473,12.2136376167,9.81557927833,17.4263115648,-0.342968532771,0.0958585798027,0.926320990009,60.5391256409 +22.71,51.0030007603,0.00117813767599,12.2170544717,9.79578297566,17.4390954838,-0.340402468397,0.0952758471067,0.93021213714,60.6059691847 +22.72,51.0030016399,0.00118062310154,12.2204632432,9.77456032395,17.4529404859,-0.341351828759,0.0950075162421,0.928666621516,60.6747390584 +22.73,51.0030025175,0.00118311056014,12.2238775459,9.75291795925,17.4676359623,-0.341508715415,0.0939322319248,0.929922075003,60.7446094103 +22.74,51.0030033933,0.00118560006834,12.2272950084,9.73221726273,17.4817136196,-0.341983785035,0.0936382696325,0.931286034033,60.8132135836 +22.75,51.0030042671,0.00118809156668,12.2307107674,9.71067412894,17.4955741146,-0.341168027001,0.0962563955287,0.93030566724,60.8831254146 +22.76,51.003005139,0.00119058498396,12.2341270259,9.68995377969,17.5086522754,-0.342083672578,0.0942267522986,0.931475014993,60.9524486855 +22.77,51.0030060091,0.00119308026931,12.2375591573,9.66856830924,17.5217986931,-0.344342593754,0.0965600303918,0.930766190583,61.0221347719 +22.78,51.0030068772,0.00119557754519,12.240998732,9.64635828402,17.5365960701,-0.343572358178,0.0951899372139,0.932249870738,61.0907849481 +22.79,51.0030077433,0.00119807681297,12.2444433102,9.62471251919,17.5497617267,-0.345343266613,0.0967547792486,0.932952426109,61.1607965055 +22.8,51.0030086075,0.00120057803821,12.2478993727,9.60277201428,17.5640754459,-0.345869251138,0.0957529620244,0.933798796673,61.2308837404 +22.81,51.0030094698,0.00120308131124,12.2513592495,9.5829496087,17.5785092702,-0.346106108583,0.0944727388622,0.934190773235,61.2990911432 +22.82,51.0030103302,0.00120558665824,12.2548202222,9.56149007567,17.593190599,-0.34608841632,0.0948183317932,0.935362041411,61.3693471782 +22.83,51.0030111887,0.00120809395861,12.2582894163,9.53893014217,17.6059312855,-0.347750420572,0.093949259058,0.935995762021,61.4395098729 +22.84,51.0030120453,0.00121060314224,12.26175375,9.51948712109,17.6196284136,-0.345116311741,0.0941485014615,0.93477196133,61.5075405553 +22.85,51.0030129,0.00121311427876,12.2652052454,9.49807842012,17.6333466585,-0.345182769303,0.0960731806614,0.933076343408,61.5785358391 +22.86,51.0030137528,0.00121562740502,12.2686609133,9.47774790718,17.647561107,-0.345950813319,0.0954986420513,0.935386537235,61.6500445566 +22.87,51.0030146037,0.00121814257762,12.2721147109,9.45435970572,17.6620738224,-0.344808703606,0.0932167261412,0.936711015111,61.71738103 +22.88,51.0030154527,0.0012206598302,12.2755744808,9.43559277305,17.6767605003,-0.347145266787,0.0955183450158,0.938389958435,61.7874388119 +22.89,51.0030162999,0.00122317913618,12.2790484494,9.41320509437,17.6909002884,-0.347648465561,0.0962199008834,0.939224299319,61.8563791468 +22.9,51.0030171451,0.00122570048935,12.2825225396,9.39226751798,17.7054995834,-0.347169569693,0.094214983691,0.939737741133,61.9256101033 +22.91,51.0030179885,0.00122822368871,12.2859873317,9.37263220162,17.716817768,-0.345788856795,0.0937970936838,0.940848613905,61.9948741769 +22.92,51.00301883,0.00123074884055,12.2894468108,9.35111981772,17.7329090617,-0.34610694902,0.0945608799618,0.941931218476,62.0656906507 +22.93,51.0030196696,0.00123327612575,12.2929098333,9.33095426785,17.7467667948,-0.346497561539,0.094510907723,0.943589996473,62.1357725083 +22.94,51.0030205074,0.00123580537984,12.2963743325,9.30922124104,17.7605488751,-0.346402266313,0.0964289907328,0.944087637626,62.2063614485 +22.95,51.0030213433,0.00123833667342,12.2998562671,9.28921807335,17.7753978136,-0.34998467159,0.094795810254,0.945045990947,62.2749380808 +22.96,51.0030221773,0.00124087003634,12.3033492494,9.26758993447,17.7895991161,-0.348611777654,0.0953494967617,0.944411048067,62.3438434044 +22.97,51.0030230094,0.00124340536499,12.306832197,9.24638758475,17.8029932733,-0.347977740918,0.0950670370721,0.946922621823,62.4127764919 +22.98,51.0030238396,0.00124594256866,12.310323453,9.22445942506,17.8159214512,-0.350273461893,0.0942589736321,0.945643080342,62.4835852519 +22.99,51.0030246679,0.00124848156041,12.3138356826,9.20463988574,17.8280947033,-0.352172462891,0.0936011840198,0.945947518629,62.5538090521 +23,51.0030254943,0.0012510225618,12.317347251,9.1835226701,17.8441334586,-0.350141219495,0.0936119237147,0.948663003334,62.6220400751 +23.01,51.003026319,0.00125356574571,12.3208495454,9.16448469457,17.8587338301,-0.350317644106,0.0929109919159,0.9492574347,62.6934569331 +23.02,51.0030271418,0.00125611094906,12.3243534383,9.14391668411,17.8724830571,-0.350460938325,0.0922684459589,0.949436101175,62.7641726312 +23.03,51.0030279628,0.00125865800145,12.3278567041,9.12294457013,17.8846910852,-0.350192222187,0.0954871580544,0.950611922645,62.8330347727 +23.04,51.0030287818,0.00126120701396,12.3313576652,9.1,17.9,-0.35,0.095,0.952,62.9 +23.05,51.0030295988,0.00126375786099,12.3348575489,9.07708977213,17.9104447433,-0.349976753504,0.0974117301266,0.951876867624,62.971080935 +23.06,51.0030304137,0.00126631012193,12.3383550904,9.05373442531,17.9198485976,-0.349531528165,0.0968729396681,0.953339936011,63.0405740842 +23.07,51.0030312264,0.00126886357917,12.3418562133,9.02983005496,17.9272387789,-0.350693065274,0.0977596158364,0.95385551255,63.11118279 +23.08,51.0030320372,0.00127141839252,12.3453681062,9.00856788649,17.9388856889,-0.35168551962,0.0978914708047,0.955686779986,63.18267281 +23.09,51.0030328459,0.00127397473387,12.348881987,8.9848968729,17.9486893766,-0.351090627918,0.0984653459078,0.957013440125,63.2518609775 +23.1,51.0030336526,0.00127653235585,12.352398944,8.9640872609,17.9568633934,-0.352300779974,0.0971094314952,0.958732175543,63.3240198217 +23.11,51.0030344572,0.00127909133295,12.3559185972,8.93850824054,17.9677128635,-0.351629847706,0.0976225842105,0.959715670167,63.3935808439 +23.12,51.0030352597,0.00128165168475,12.3594365736,8.91741752237,17.9761616029,-0.351965431307,0.0970223360982,0.958126538486,63.4634728811 +23.13,51.0030360603,0.00128421331842,12.3629568706,8.89450586499,17.9857080831,-0.352093981558,0.0969066241745,0.957374180461,63.5342217213 +23.14,51.0030368587,0.00128677625828,12.3664740082,8.87058941487,17.9944981386,-0.351333529074,0.0996573579828,0.957557139829,63.6048237248 +23.15,51.003037655,0.00128934059267,12.369989599,8.84738658475,18.0052847905,-0.351784631752,0.1003045155,0.962115412587,63.6761499022 +23.16,51.0030384493,0.00129190631491,12.3735118227,8.82582626554,18.0139809917,-0.352660121096,0.100076370723,0.962341067029,63.7436340092 +23.17,51.0030392418,0.00129447335496,12.377045097,8.80605116552,18.0237845578,-0.353994731306,0.10061574395,0.963572367747,63.8115568494 +23.18,51.0030400322,0.00129704176987,12.3805749685,8.78090489195,18.0332815405,-0.351979566588,0.0975021285781,0.962858118959,63.8821574141 +23.19,51.0030408205,0.00129961172231,12.3840962789,8.75729121509,18.045368807,-0.352282523992,0.0986068522909,0.960919039761,63.9535137072 +23.2,51.0030416067,0.00130218305707,12.3876233421,8.73522136392,18.05268687,-0.353130100965,0.0995251408067,0.964490864016,64.0238958368 +23.21,51.0030423909,0.00130475566549,12.3911559498,8.71280136384,18.0632486312,-0.353391454286,0.0997223101612,0.965724550135,64.093417936 +23.22,51.003043173,0.00130732964314,12.3946876553,8.69038065471,18.0719084814,-0.352949642734,0.0993681957566,0.967661902084,64.1627569292 +23.23,51.0030439531,0.00130990490038,12.3982227934,8.66711523182,18.0812117037,-0.354077961367,0.101545422467,0.967582122599,64.2337149583 +23.24,51.0030447312,0.00131248155168,12.4017568712,8.64466573896,18.091478562,-0.352737605428,0.101171994513,0.96883980294,64.3049516998 +23.25,51.0030455073,0.00131505951506,12.4052811194,8.62194563538,18.0996310864,-0.352112027843,0.0993514611958,0.969099827169,64.3740808661 +23.26,51.0030462812,0.00131763880546,12.4088073413,8.59834965365,18.1101074319,-0.353132353433,0.10149902711,0.970645729733,64.4444055751 +23.27,51.0030470531,0.0013202195094,12.4123418109,8.57575325796,18.1194746162,-0.353761577471,0.101792125639,0.971604872161,64.5140550992 +23.28,51.003047823,0.001322801489,12.4158873213,8.5534376772,18.1280154827,-0.355340500182,0.101588822754,0.970943181413,64.5863810415 +23.29,51.0030485908,0.00132538465733,12.4194440675,8.53119835738,18.1361621914,-0.356008742658,0.101976223993,0.970277239909,64.6562260005 +23.3,51.0030493566,0.00132796905782,12.4230040618,8.50722104076,18.1453127711,-0.355990113143,0.103385174918,0.972208112856,64.7276946832 +23.31,51.0030501203,0.00133055473067,12.4265620652,8.4844415098,18.1540238885,-0.355610574494,0.104556364869,0.972825673015,64.7983471744 +23.32,51.003050882,0.00133314180799,12.4301233169,8.46397261081,18.1650289707,-0.356639763269,0.102843413857,0.974848608537,64.8696345538 +23.33,51.0030516417,0.00133573023747,12.4336903408,8.43930481664,18.1730057426,-0.356765009426,0.0998187340681,0.975582766197,64.9391829965 +23.34,51.0030523993,0.00133831988174,12.4372559552,8.4174451801,18.1820824152,-0.356357873279,0.100309210644,0.978439976221,65.0087905388 +23.35,51.0030531549,0.00134091082874,12.4408293005,8.39438794164,18.1912938252,-0.358311184413,0.0987797708534,0.976605290465,65.0800774691 +23.36,51.0030539085,0.00134350315081,12.4444113663,8.37273795281,18.2013858677,-0.358101985233,0.100331325346,0.978099104212,65.1505317455 +23.37,51.0030546601,0.00134609682371,12.447994824,8.3487238108,18.2102571393,-0.358589545009,0.100431748824,0.980207571264,65.2202371371 +23.38,51.0030554095,0.00134869172217,12.45157426,8.32643991688,18.2185904569,-0.357297666505,0.102512383979,0.981509685311,65.2899269185 +23.39,51.0030561569,0.0013512877879,12.4551449342,8.30275986654,18.2266435476,-0.356837158898,0.103440383657,0.98298324074,65.364082552 +23.4,51.0030569022,0.00135388521499,12.4587212442,8.28045512907,18.2377014001,-0.358424855823,0.104765588869,0.981169523404,65.4325768182 +23.41,51.0030576455,0.00135648410153,12.4623046619,8.25688297101,18.2471317746,-0.358258671747,0.104148989242,0.982383433852,65.5019531453 +23.42,51.0030583868,0.00135908433023,12.4658838588,8.23641834655,18.256542875,-0.357580716758,0.105336319725,0.981847218766,65.5730674457 +23.43,51.0030591262,0.00136168586531,12.4694715686,8.21510435195,18.2654710863,-0.359961233979,0.105180078104,0.981264495966,65.642028221 +23.44,51.0030598636,0.00136428862314,12.4730706263,8.19239295266,18.2737080184,-0.359850309452,0.105502209321,0.984946844482,65.7106298655 +23.45,51.0030605989,0.00136689265279,12.4766611382,8.16873061688,18.2833251848,-0.358252070136,0.107044493197,0.98559741995,65.7820484205 +23.46,51.0030613323,0.00136949804904,12.4802504169,8.14736168683,18.2928926467,-0.359603677149,0.108267874973,0.985893854414,65.8501569776 +23.47,51.0030620635,0.00137210469087,12.4838447357,8.12295281716,18.3008107732,-0.359260074729,0.106440334884,0.987868027693,65.9206079074 +23.48,51.0030627927,0.00137471267117,12.487437644,8.10031718628,18.3116825049,-0.359321577256,0.106178028502,0.990374476424,65.9915954296 +23.49,51.0030635198,0.00137732210131,12.4910347988,8.07910529137,18.3211640537,-0.360109394564,0.107769794507,0.992177768625,66.0629252699 +23.5,51.003064245,0.00137993292103,12.4946389663,8.05490613983,18.3311896471,-0.360724095599,0.104248553659,0.992232420096,66.1328955626 +23.51,51.003064968,0.00138254510264,12.4982473352,8.031445352,18.3402826318,-0.360949698413,0.102377025692,0.994958756739,66.2030142105 +23.52,51.0030656889,0.00138515873521,12.5018543952,8.00949020613,18.351558586,-0.360462301147,0.104340067077,0.991655621458,66.2754569572 +23.53,51.0030664078,0.00138777387513,12.5054595249,7.98591694986,18.3614432262,-0.360563630178,0.104830613274,0.992622958404,66.3461299956 +23.54,51.0030671247,0.00139039034857,12.5090645552,7.9642743008,18.3702788813,-0.360442432703,0.104340834701,0.991973246099,66.4158798804 +23.55,51.0030678396,0.00139300815692,12.5126659446,7.94167107143,18.3801829901,-0.359835449071,0.107086329026,0.996038992746,66.4875632388 +23.56,51.0030685524,0.00139562720425,12.5162743085,7.91908413052,18.3876718961,-0.361837338219,0.105979849403,0.995483554944,66.5565417885 +23.57,51.0030692632,0.00139824756739,12.5198930983,7.89657960936,18.3986545489,-0.361920610536,0.106245941538,0.995026996375,66.6281868856 +23.58,51.003069972,0.00140086940962,12.5235158484,7.87410492071,18.4084359218,-0.36262942154,0.105183176597,0.995612733748,66.6962148181 +23.59,51.0030706789,0.00140349262944,12.5271498965,7.85302785911,18.4179934145,-0.364180186214,0.105226430192,0.995570806605,66.7657444262 +23.6,51.0030713837,0.00140611713625,12.530782002,7.82931644258,18.4265030202,-0.362240923681,0.10525600346,0.997211473413,66.8379363573 +23.61,51.0030720865,0.00140874290251,12.5344123283,7.806440976,18.4356738067,-0.363824332829,0.105158442904,0.996812829046,66.9072494353 +23.62,51.0030727871,0.00141136998658,12.5380518534,7.78317273622,18.4450026457,-0.364080675355,0.105419684418,0.999321370072,66.9763890398 +23.63,51.0030734858,0.0014139985297,12.5416989056,7.76243653191,18.456156374,-0.365329767748,0.103624209062,0.997213962125,67.046472801 +23.64,51.0030741825,0.00141662843015,12.5453444959,7.73888781759,18.4640573287,-0.363788303642,0.104338586241,1.00045435085,67.1183272044 +23.65,51.0030748772,0.00141925952507,12.5489837255,7.71851678443,18.4729243823,-0.364057618056,0.103733110459,1.00142128552,67.1890851465 +23.66,51.00307557,0.00142189190979,12.552623958,7.69550347678,18.4821639521,-0.363988863804,0.104068016398,1.00111646978,67.2594525349 +23.67,51.0030762607,0.00142452560667,12.5562697619,7.67145797593,18.4913447659,-0.365171928323,0.104392068758,1.00129964776,67.3276222567 +23.68,51.0030769492,0.0014271606307,12.5599230339,7.64908139902,18.5007948651,-0.365482464892,0.103066786443,1.00326080745,67.3991862029 +23.69,51.0030776359,0.00142979698027,12.5635693516,7.62814199477,18.5099529218,-0.363781085411,0.103193135033,1.00636171595,67.4716174232 +23.7,51.0030783206,0.00143243468651,12.5672203744,7.6060193705,18.5198401178,-0.366423459016,0.103150754288,1.00585242237,67.5415908772 +23.71,51.0030790033,0.00143507365715,12.5708823693,7.58386240572,18.5277028045,-0.365975521697,0.102278538547,1.00539621861,67.6139932809 +23.72,51.0030796839,0.00143771389707,12.5745437847,7.56035162618,18.5376587069,-0.366307576231,0.103790325516,1.00295031006,67.6815487684 +23.73,51.0030803625,0.00144035542873,12.5782044678,7.53805816891,18.5458364682,-0.365829027201,0.102717759327,1.00477180261,67.750737524 +23.74,51.0030810391,0.00144299823365,12.5818643469,7.51536432909,18.5555330215,-0.366146800095,0.102303226679,1.00676025413,67.8217125288 +23.75,51.0030817136,0.00144564245665,12.5855287353,7.49358096911,18.5657438134,-0.366730872535,0.103079562466,1.00751740786,67.8909231698 +23.76,51.0030823862,0.00144828814604,12.5892022091,7.47020116891,18.5761186143,-0.367963888197,0.102346197266,1.00809141571,67.9613399856 +23.77,51.0030830566,0.00145093536976,12.5928843343,7.44710820923,18.5872832272,-0.368461150775,0.104038672373,1.00810688568,68.0312208916 +23.78,51.0030837249,0.00145358400628,12.5965649991,7.42240212536,18.5959518958,-0.36767181784,0.103080869312,1.00874911767,68.1015290281 +23.79,51.0030843912,0.00145623391206,12.6002499969,7.40145213889,18.6051013826,-0.36932773776,0.103188947134,1.01174329496,68.1731976895 +23.8,51.0030850554,0.00145888510021,12.6039412141,7.37845705543,18.6139541521,-0.368915701732,0.102396124866,1.0128888934,68.2441610328 +23.81,51.0030857178,0.00146153774841,12.6076302275,7.3583250478,18.6255979075,-0.368886988591,0.100578059296,1.01302203823,68.314787161 +23.82,51.0030863782,0.00146419178067,12.6113252494,7.33542828569,18.6333840144,-0.370117382321,0.102716661369,1.01364813086,68.385395782 +23.83,51.0030870366,0.00146684705713,12.6150254153,7.31315991833,18.6430642429,-0.369915807753,0.104224896464,1.01413574944,68.4583553104 +23.84,51.0030876929,0.00146950362216,12.6187278205,7.29017217329,18.6514731984,-0.370565220164,0.10372872541,1.01412361183,68.5259011605 +23.85,51.0030883471,0.00147216141022,12.6224423293,7.26673321894,18.6602334965,-0.372336537302,0.106210974425,1.01491821393,68.5958473747 +23.86,51.0030889993,0.00147482046083,12.6261647917,7.24401160328,18.6691971667,-0.372155947202,0.106632842398,1.01374233731,68.6655880389 +23.87,51.0030896495,0.00147748079518,12.6298864606,7.22107369231,18.6782549174,-0.372177842774,0.105141702499,1.01313196439,68.7371142071 +23.88,51.0030902975,0.00148014261784,12.6336112527,7.1986426556,18.6900904548,-0.372780575311,0.105580285438,1.01539625962,68.8068925288 +23.89,51.0030909436,0.00148280591135,12.6373472484,7.17592497371,18.6989032746,-0.374418559118,0.106063111461,1.01684391073,68.8768714926 +23.9,51.0030915875,0.00148547051458,12.6410858814,7.15153516901,18.7084765586,-0.373308036571,0.106449953432,1.01882483638,68.9470917116 +23.91,51.0030922295,0.00148813637627,12.6448154406,7.13104449377,18.7165696975,-0.372603805648,0.107387998946,1.0218232491,69.017225251 +23.92,51.0030928694,0.00149080356352,12.6485403999,7.10782234672,18.7270852285,-0.372388057438,0.106896798986,1.02185048876,69.0874825835 +23.93,51.0030935073,0.00149347220994,12.6522701333,7.08498988885,18.7370540886,-0.373558623984,0.108985998406,1.02288687769,69.1585405651 +23.94,51.0030941431,0.00149614221929,12.6559995717,7.06193404569,18.7462182183,-0.372329049872,0.106050091316,1.02524439547,69.2282023603 +23.95,51.0030947768,0.00149881349671,12.6597237949,7.0366097464,18.7548556537,-0.372515590144,0.105219776399,1.02568139133,69.2972727388 +23.96,51.0030954083,0.00150148613665,12.6634495994,7.01491154291,18.7653456285,-0.372645312806,0.106842220787,1.02609076661,69.3689101535 +23.97,51.0030960379,0.00150416017164,12.6671763713,6.99267726502,18.7744396778,-0.372709078544,0.103348249497,1.02856499895,69.4386940407 +23.98,51.0030966655,0.00150683552916,12.6709061198,6.97072183772,18.7839117295,-0.373240613603,0.104153675172,1.02765525338,69.5081179261 +23.99,51.003097291,0.00150951230026,12.6746412385,6.94833537522,18.7942838443,-0.373783126365,0.105484797358,1.02970999133,69.577374028 +24,51.0030979146,0.00151219041772,12.6783794305,6.92486036096,18.8028124383,-0.373855264326,0.106668629782,1.02927596519,69.6491832545 +24.01,51.003098536,0.00151486963324,12.6821208192,6.9028366973,18.8096984907,-0.374422474059,0.106573969867,1.02819873866,69.7206790468 +24.02,51.0030991554,0.00151755012473,12.6858629234,6.87804513633,18.8207248443,-0.373998367468,0.10541105908,1.03006949315,69.7910240125 +24.03,51.0030997728,0.00152023198566,12.689607584,6.85789986809,18.8289231051,-0.374933767253,0.102936812775,1.03037538622,69.8604358537 +24.04,51.0031003882,0.00152291515044,12.6933570461,6.83444369534,18.839028611,-0.37495865,0.105214393133,1.03355802233,69.9307864815 +24.05,51.0031010016,0.00152559971189,12.6971105025,6.81372834906,18.8485300808,-0.375732630403,0.104824786519,1.03476301882,70.0016608853 +24.06,51.003101613,0.0015282856231,12.700868586,6.7902549497,18.8579767278,-0.375884060286,0.105997515736,1.03356019304,70.0710291675 +24.07,51.0031022223,0.00153097291332,12.7046258804,6.76573183713,18.8678890988,-0.375574816924,0.10472840604,1.03496432098,70.1413159028 +24.08,51.0031028294,0.00153366141258,12.7083824553,6.74227895236,18.8749494579,-0.375740166751,0.104539056585,1.03645915711,70.2119584494 +24.09,51.0031034344,0.00153635109464,12.7121368247,6.7192543721,18.8844936877,-0.375133716934,0.104383555191,1.03817107278,70.2844555809 +24.1,51.0031040374,0.00153904207358,12.7158918348,6.6978011794,18.8931551725,-0.375868307075,0.105392836913,1.04020972419,70.3527688473 +24.11,51.0031046384,0.00154173442379,12.7196420313,6.67358964124,18.9037440949,-0.37417098594,0.106147034995,1.03938519825,70.4233761307 +24.12,51.0031052372,0.00154442818238,12.7233896129,6.6505364491,18.9129264316,-0.375345338065,0.105100373778,1.04177774803,70.4945013155 +24.13,51.003105834,0.00154712328881,12.7271362902,6.62811014782,18.9226655609,-0.373990122247,0.105444713543,1.04349643425,70.5639317571 +24.14,51.0031064288,0.00154981971147,12.7308805497,6.6045831647,18.9314039088,-0.374861781659,0.106750524464,1.04482448955,70.6339552529 +24.15,51.0031070215,0.00155251743499,12.7346198005,6.58333818273,18.9409273115,-0.372988364661,0.109036278442,1.04488727523,70.7043139131 +24.16,51.0031076122,0.00155521652267,12.7383689934,6.56079773375,18.9505544022,-0.376850231894,0.107829999075,1.0449515714,70.7747105682 +24.17,51.0031082009,0.00155791686755,12.7421439096,6.53684838389,18.9585762656,-0.378133004541,0.106778461686,1.04384500579,70.8423249569 +24.18,51.0031087875,0.00156061848647,12.7459278311,6.51470914151,18.968439758,-0.37865128171,0.108785766448,1.04467377166,70.9135464059 +24.19,51.0031093721,0.00156332135969,12.7497149385,6.49260533716,18.9761844471,-0.378770199445,0.109683792746,1.04367478878,70.9862818595 +24.2,51.0031099548,0.00156602553168,12.7535018579,6.47122511634,18.9866721701,-0.378613697384,0.10963858939,1.04424228754,71.0547334764 +24.21,51.0031105354,0.00156873098056,12.757286108,6.44774326833,18.9941098844,-0.378236321194,0.107774770739,1.04467893937,71.1257223029 +24.22,51.003111114,0.00157143768705,12.7610723474,6.42582490943,19.0043268109,-0.3790115432,0.108521129761,1.04555470255,71.1961485186 +24.23,51.0031116907,0.00157414591887,12.7648631637,6.4057536201,19.0155228414,-0.379151719109,0.109306394309,1.04682467584,71.2648914316 +24.24,51.0031122654,0.00157685558459,12.7686545205,6.38165458991,19.0244564399,-0.379119656178,0.108914966177,1.04640461301,71.3352200475 +24.25,51.0031128381,0.00157956652369,12.7724436112,6.35978573024,19.0333989652,-0.37869847728,0.109908139691,1.04590939824,71.4053550237 +24.26,51.0031134087,0.00158227864428,12.7762312394,6.33635818163,19.0410424427,-0.37882715511,0.111631368817,1.04682519376,71.4762187517 +24.27,51.0031139772,0.00158499199699,12.7800140992,6.31250469926,19.050695725,-0.377744818774,0.110763763495,1.04694378233,71.5484332523 +24.28,51.0031145436,0.00158770680594,12.7838050639,6.29111730394,19.0614857034,-0.380448109062,0.110068629118,1.04923345517,71.6175569184 +24.29,51.0031151081,0.00159042308478,12.7876164455,6.26776938068,19.0713304219,-0.381828208099,0.109786795346,1.04883863398,71.6873219116 +24.3,51.0031156705,0.00159314070371,12.7914302386,6.24612507216,19.0802983602,-0.380930419061,0.111473206332,1.04903312073,71.7585374343 +24.31,51.003116231,0.00159585954276,12.7952426175,6.22339256438,19.0884587681,-0.381545356633,0.110454583057,1.05062650237,71.8300118909 +24.32,51.0031167893,0.00159857978523,12.7990603443,6.2,19.1,-0.382,0.11,1.053,71.9 +24.33,51.0031173455,0.00160130126901,12.8028849106,6.17471463324,19.1058845236,-0.382913261372,0.110674073111,1.0552083203,71.9744310726 +24.34,51.0031178995,0.00160402365722,12.806712142,6.15079054327,19.1126966136,-0.382533032955,0.109121030339,1.0551738807,72.0442659448 +24.35,51.0031184513,0.0016067468128,12.8105445244,6.12788160427,19.1166570009,-0.383943443988,0.110181209479,1.05632526662,72.1168074971 +24.36,51.003119001,0.00160947054057,12.814381755,6.10272704224,19.1207287182,-0.383502668655,0.109726052482,1.05639504555,72.187588295 +24.37,51.0031195485,0.00161219493248,12.8182111724,6.07829067816,19.125980395,-0.382380809494,0.109909878516,1.0562285014,72.2592138147 +24.38,51.0031200938,0.00161492010906,12.822040862,6.0547342401,19.1317439152,-0.383557110185,0.111399364297,1.05622741044,72.3299882935 +24.39,51.003120637,0.0016176458709,12.8258824356,6.03052697762,19.1341961024,-0.384757610555,0.113876167806,1.05663384476,72.4017868826 +24.4,51.0031211779,0.00162037215191,12.8297356322,6.00549074329,19.1390320748,-0.385881709071,0.1097958256,1.05801151144,72.4753483913 +24.41,51.0031217166,0.00162309911484,12.8335906915,5.98032279011,19.1437688852,-0.385130152586,0.11163691168,1.05857011913,72.5461229234 +24.42,51.0031222531,0.00162582666695,12.8374497303,5.95598649229,19.1473027849,-0.386677603104,0.1103373075,1.06004675623,72.619397821 +24.43,51.0031227874,0.00162855485858,12.841322551,5.93274615549,19.1527465554,-0.387886538596,0.109609585364,1.06138697139,72.6921199363 +24.44,51.0031233196,0.00163128378971,12.8452029303,5.90849963205,19.1576839775,-0.388189331353,0.109716130551,1.06193332158,72.7659945912 +24.45,51.0031238496,0.00163401339333,12.849082132,5.88390331529,19.1621868098,-0.387650997273,0.107849075172,1.06281038694,72.8388529631 +24.46,51.0031243774,0.00163674369849,12.8529594203,5.85956737876,19.1675324012,-0.387806668469,0.108602403888,1.06409286565,72.9084201859 +24.47,51.003124903,0.00163947481797,12.856842927,5.83445096764,19.1736182649,-0.388894670693,0.10825141982,1.06437276526,72.9795333999 +24.48,51.0031254264,0.00164220651306,12.860730182,5.81137269871,19.1756127054,-0.388556322306,0.108037322719,1.06468762714,73.0531553017 +24.49,51.0031259477,0.00164493872841,12.8646197472,5.78633922809,19.1809217165,-0.389356721103,0.108104846258,1.06589862704,73.1254221636 +24.5,51.0031264666,0.00164767160302,12.8685129219,5.76029707455,19.1848672659,-0.38927823198,0.108137533168,1.06721294865,73.1966751655 +24.51,51.0031269833,0.0016504050057,12.8724079962,5.73621475661,19.1883346816,-0.389736610363,0.109692370793,1.06779107981,73.2685164063 +24.52,51.0031274979,0.00165313905292,12.8762984651,5.71216077719,19.19391546,-0.388357170779,0.108307086325,1.06809493132,73.3394020143 +24.53,51.0031280103,0.00165587375146,12.8801881934,5.69007523767,19.1974777425,-0.389588494857,0.108456096012,1.06877659558,73.4102127384 +24.54,51.0031285207,0.00165860910795,12.8840887781,5.6644413442,19.203151849,-0.390528445375,0.108439641503,1.06824263733,73.4825149438 +24.55,51.0031290288,0.00166134530174,12.888004268,5.64178273999,19.209231998,-0.392569537092,0.108087332763,1.07028745396,73.5516964842 +24.56,51.0031295348,0.00166408216232,12.8919260873,5.61652964068,19.2125120635,-0.391794320855,0.107579522289,1.06884143658,73.6263139421 +24.57,51.0031300386,0.00166681956024,12.8958459226,5.59349034895,19.2167751881,-0.392172740814,0.107264114862,1.06937486821,73.698819862 +24.58,51.0031305404,0.00166955759245,12.8997750149,5.5715042645,19.2214163574,-0.393645713944,0.107331968505,1.0727374631,73.7701802359 +24.59,51.0031310401,0.00167229629448,12.9037174916,5.54577035571,19.2261779981,-0.394849627856,0.108682883192,1.07061660432,73.8417725591 +24.6,51.0031315375,0.00167503581065,12.9076633509,5.52110896853,19.2328453464,-0.394322240148,0.107857943144,1.07364063284,73.9132489374 +24.61,51.0031320327,0.00167777602218,12.9116060107,5.49754452212,19.2359396386,-0.39420972308,0.108915536043,1.07282830015,73.987788665 +24.62,51.0031325258,0.00168051682129,12.9155410596,5.47370341714,19.2410936996,-0.392800046437,0.107480076265,1.07627640181,74.0583388973 +24.63,51.0031330167,0.00168325838066,12.9194717156,5.44799597299,19.2466121887,-0.39333115111,0.106979188757,1.07390876191,74.127676977 +24.64,51.0031335053,0.00168600056525,12.9234069664,5.42429155495,19.249870662,-0.393719009966,0.106247337722,1.07631562395,74.2017142527 +24.65,51.0031339918,0.00168874319744,12.9273467915,5.39870879029,19.2528954005,-0.39424601918,0.10609574994,1.07841638707,74.2738423302 +24.66,51.003134476,0.00169148642443,12.9312898079,5.37504368988,19.2582205759,-0.394357264858,0.105113598661,1.0786663622,74.3465008675 +24.67,51.003134958,0.00169423026577,12.9352274815,5.34953569347,19.2615195895,-0.393177455177,0.104192728076,1.07935011523,74.4166482836 +24.68,51.0031354378,0.00169697472571,12.9391545709,5.32528262458,19.2669044611,-0.392240410807,0.10349701979,1.08060369488,74.4904804549 +24.69,51.0031359153,0.001699719951,12.9430709556,5.30036731092,19.2722636748,-0.391036531283,0.104595526617,1.07998779947,74.5619341157 +24.7,51.0031363907,0.00170246588153,12.9469945972,5.2767481341,19.2768047305,-0.393691785943,0.10451096334,1.07900338905,74.6349223333 +24.71,51.0031368639,0.00170521248052,12.9509295126,5.25141822081,19.281647512,-0.393291303855,0.105422033199,1.0813845763,74.7044356674 +24.72,51.0031373349,0.00170795976785,12.9548657092,5.22860276488,19.2864676652,-0.393948005854,0.10420054556,1.08161453491,74.7759751191 +24.73,51.0031378038,0.00171070776922,12.9587975959,5.20332427418,19.2916713559,-0.392429333815,0.103873541374,1.08443225518,74.8475090623 +24.74,51.0031382704,0.00171345639116,12.9627237807,5.1788377069,19.2951791725,-0.39280762898,0.106025846774,1.08474515333,74.9187140007 +24.75,51.0031387347,0.00171620566557,12.9666573953,5.15219617268,19.3008308944,-0.393915296127,0.104755091044,1.08250096837,74.9935859821 +24.76,51.0031391969,0.00171895566669,12.9705910718,5.13103068565,19.3053807503,-0.392820011123,0.104041541849,1.08473902428,75.0629823142 +24.77,51.0031396571,0.00172170631757,12.9745155925,5.10836814567,19.3099521308,-0.39208411332,0.104348989543,1.08605169896,75.1343257081 +24.78,51.0031401152,0.00172445774179,12.9784440662,5.08422122499,19.3162371871,-0.393610641507,0.104570745597,1.08820932146,75.2063258967 +24.79,51.0031405711,0.00172720983309,12.9823912646,5.05929041716,19.3193166887,-0.395829036038,0.104690483438,1.08978123715,75.276376306 +24.8,51.0031410248,0.0017299625642,12.9863475307,5.03536272735,19.3252187735,-0.395424167946,0.103203173233,1.08820090286,75.3499238208 +24.81,51.0031414762,0.00173271605838,12.990310821,5.00965263089,19.3300287676,-0.397233907103,0.102696546957,1.08788918135,75.4176722967 +24.82,51.0031419255,0.00173547020764,12.9942868289,4.98687954102,19.3344148523,-0.397967673837,0.102077126264,1.08778788392,75.4922626575 +24.83,51.0031423727,0.00173822491374,12.9982671957,4.96334182809,19.3378457075,-0.398105689336,0.102232044147,1.0889703922,75.5624981703 +24.84,51.0031428178,0.00174098033703,13.0022415569,4.9394471914,19.3444828742,-0.396766539135,0.102219149283,1.08829611051,75.6338682574 +24.85,51.0031432608,0.00174373658047,13.006206084,4.91700810185,19.3493591115,-0.396138890673,0.103750440574,1.08904371858,75.7045708749 +24.86,51.0031437017,0.0017464935627,13.0101712186,4.8924736878,19.354854192,-0.396888016778,0.103523238358,1.09039295696,75.7773219284 +24.87,51.0031441404,0.00174925115993,13.0141347574,4.86771399434,19.3579924041,-0.395819739809,0.104177188549,1.09115585598,75.8501154545 +24.88,51.0031445768,0.0017520094211,13.0180945288,4.84304944793,19.3641746812,-0.396134557707,0.104184499212,1.09194583349,75.9230417346 +24.89,51.003145011,0.00175476837827,13.0220596054,4.81874759337,19.3677630704,-0.396880747048,0.102924184231,1.09194098446,75.9969829879 +24.9,51.0031454432,0.0017575279201,13.0260265062,4.79582429234,19.3723820497,-0.396499426872,0.101493978239,1.09235522963,76.068199626 +24.91,51.0031458732,0.00176028816051,13.0299942762,4.7716957438,19.3775697675,-0.397054570228,0.101316680923,1.09352856756,76.1403099793 +24.92,51.0031463009,0.00176304914057,13.0339726717,4.74606858471,19.3827654825,-0.398624516542,0.102102819711,1.09574308495,76.2118547004 +24.93,51.0031467265,0.00176581070507,13.0379554555,4.72216945486,19.3857740975,-0.397932258944,0.102132649346,1.09796006748,76.2837659309 +24.94,51.0031471498,0.00176857284339,13.0419357458,4.69748652712,19.3908208355,-0.398125796698,0.101421199442,1.09882325693,76.3576298739 +24.95,51.0031475709,0.00177133567221,13.0459221254,4.67170667331,19.3954674484,-0.399150112546,0.102904821384,1.0968703429,76.4292283484 +24.96,51.0031479898,0.00177409910208,13.0499177142,4.64869316236,19.3992584112,-0.39996765925,0.102051173852,1.09996447001,76.5000948633 +24.97,51.0031484066,0.00177686316084,13.0539147748,4.62388413819,19.4042957356,-0.399444464679,0.104486883717,1.10008960471,76.5719175731 +24.98,51.0031488212,0.00177962783459,13.0579051627,4.60124977554,19.4078918001,-0.398633104065,0.103182643563,1.10319194971,76.6443642604 +24.99,51.0031492337,0.00178239305497,13.0618837125,4.57597529245,19.4119694296,-0.39707685496,0.103309912176,1.10512219223,76.7147848492 +25,51.0031496439,0.00178515901092,13.0658528868,4.55199518187,19.4182177354,-0.396758000474,0.102813901922,1.10354167378,76.787897079 +25.01,51.003150052,0.00178792575679,13.0698205831,4.52653171722,19.4230586168,-0.396781259383,0.100410804699,1.10301602895,76.8584855968 +25.02,51.0031504579,0.00179069319671,13.0738004791,4.50472257763,19.4279608185,-0.399197947592,0.10194604304,1.10495493324,76.9324470876 +25.03,51.0031508617,0.0017934613215,13.0777957014,4.48054431882,19.4326728838,-0.399846522307,0.0989735326675,1.10610203451,77.00235623 +25.04,51.0031512633,0.00179623006664,13.081797238,4.45582953231,19.4366694789,-0.400460782241,0.100810171121,1.10623518641,77.0758255929 +25.05,51.0031516628,0.00179899954967,13.0857929101,4.4318625486,19.4430315146,-0.398673638129,0.101531889109,1.10552166437,77.1459533747 +25.06,51.0031520601,0.00180176972217,13.0897755896,4.4090246968,19.4463482773,-0.397862260896,0.101013549456,1.10802480044,77.2200301124 +25.07,51.0031524553,0.00180454050273,13.0937661815,4.38424413173,19.4515675567,-0.400256135163,0.0997968213402,1.10844004409,77.2934299512 +25.08,51.0031528483,0.00180731191346,13.0977649035,4.35984628623,19.4551947378,-0.399488252058,0.0990615053839,1.11038179256,77.3634560804 +25.09,51.0031532392,0.00181008400604,13.1017602649,4.3372742397,19.4611394944,-0.399584033467,0.0998638823467,1.11186429577,77.4345416682 +25.1,51.003153628,0.00181285684161,13.1057627557,4.31360497249,19.4656249949,-0.400914119016,0.0996392155362,1.11085845125,77.5057148286 +25.11,51.0031540146,0.00181563036454,13.1097716967,4.28762862577,19.4707885909,-0.400874093963,0.0989471662434,1.11240104282,77.5779335376 +25.12,51.0031543989,0.00181840459026,13.1137919111,4.26308964536,19.4754911307,-0.403168776343,0.0996717692501,1.11223423455,77.6495435916 +25.13,51.003154781,0.00182117939961,13.1178221524,4.23894828706,19.4789814743,-0.402879495505,0.0995293844447,1.11446945061,77.7212928195 +25.14,51.003155161,0.00182395475319,13.121854949,4.21468345963,19.4831312287,-0.403679809362,0.0997345868056,1.11361687747,77.7927895796 +25.15,51.0031555387,0.00182673063636,13.1258940358,4.18990047581,19.4864157251,-0.404137556939,0.0982056381998,1.11415475472,77.8656231565 +25.16,51.0031559143,0.00182950728739,13.1299439875,4.16671091716,19.4939107317,-0.405852774554,0.0985169179188,1.11573316827,77.937128286 +25.17,51.0031562878,0.0018322847612,13.1340126054,4.14419691023,19.4979660533,-0.407870817526,0.0967489817268,1.11442103415,78.0082638915 +25.18,51.0031566592,0.00183506298201,13.1380758392,4.11884425086,19.5043973386,-0.404775931059,0.0974115776595,1.11547330811,78.0814731043 +25.19,51.0031570283,0.00183784201782,13.142120226,4.093646067,19.5094073108,-0.404101438197,0.097362444498,1.11679551643,78.1563169782 +25.2,51.0031573952,0.00184062173873,13.1461695087,4.06843982184,19.5140147653,-0.405755103573,0.0980387706652,1.11712804816,78.2250041071 +25.21,51.0031577597,0.00184340210255,13.1502316841,4.04177854581,19.5184326549,-0.406679975901,0.0964743416015,1.11567902476,78.2964274796 +25.22,51.003158122,0.00184618321207,13.1542952013,4.01941088553,19.5244831654,-0.40602345264,0.0990290299019,1.1173774499,78.368908168 +25.23,51.0031584822,0.00184896508445,13.1583443634,3.99560012283,19.5291416874,-0.403808969898,0.0997066831226,1.12136592023,78.4425041343 +25.24,51.0031588403,0.00185174753261,13.1623946307,3.97242662661,19.5325661087,-0.406244505456,0.099641696504,1.12106289831,78.5115899634 +25.25,51.0031591962,0.00185453050268,13.1664519732,3.94665762703,19.5364683881,-0.405223988832,0.0999611927418,1.12094327832,78.5823116524 +25.26,51.0031595499,0.00185731405495,13.1705081869,3.92192935563,19.5407390651,-0.406018751001,0.0994888339871,1.12340309174,78.6559370981 +25.27,51.0031599013,0.001860098135,13.174568223,3.89805146596,19.5438774636,-0.405988460942,0.0990838414791,1.12226407962,78.7265155016 +25.28,51.0031602507,0.00186288297149,13.178634325,3.8739498918,19.5513581088,-0.4072319371,0.0978167770787,1.12360102526,78.8001975358 +25.29,51.0031605977,0.00186566870122,13.182712804,3.84869858707,19.5564169372,-0.408463871082,0.0969062221656,1.12661549632,78.8731684053 +25.3,51.0031609426,0.00186845511059,13.1867957454,3.82515841746,19.5608991419,-0.408124401826,0.0970944138214,1.12490790199,78.9444462107 +25.31,51.0031612853,0.00187124208217,13.190878551,3.79994319367,19.5643093127,-0.408436730465,0.0997739430915,1.12485326769,79.0140775777 +25.32,51.0031616258,0.00187402967804,13.1949685538,3.77604870877,19.5696631187,-0.409563830816,0.0967448021171,1.12557413273,79.0880709007 +25.33,51.0031619642,0.00187681796625,13.1990626113,3.75298357533,19.574028435,-0.409247665083,0.0972773437687,1.12795932063,79.1608977949 +25.34,51.0031623004,0.00187960688525,13.2031566139,3.72768663427,19.5785183734,-0.409552849775,0.0974477265765,1.12920175977,79.2321615028 +25.35,51.0031626344,0.00188239656491,13.2072653542,3.70232756037,19.5847066799,-0.412195221593,0.0976274890612,1.12901115813,79.3035934359 +25.36,51.0031629661,0.00188518701921,13.2113866064,3.67838333422,19.5893931127,-0.412055203135,0.096613699638,1.13034809495,79.374437167 +25.37,51.0031632957,0.00188797810689,13.2155055416,3.65403772086,19.5935980658,-0.411731842175,0.096504552193,1.13201679671,79.4479414639 +25.38,51.0031636231,0.00189076987494,13.2196239262,3.63111294232,19.5989443961,-0.411945072824,0.0976534814288,1.13374508235,79.520240955 +25.39,51.0031639484,0.00189356232446,13.2237452855,3.6080061393,19.6031647329,-0.412326791341,0.0978927162281,1.13431330429,79.5923527857 +25.4,51.0031642716,0.00189635549238,13.2278712818,3.5818559361,19.6090294044,-0.412872461573,0.0973849010664,1.13443546023,79.6626588842 +25.41,51.0031645925,0.00189914943134,13.231994256,3.55847694825,19.6139888618,-0.411722394252,0.0977882569372,1.13414397441,79.734628783 +25.42,51.0031649113,0.00190194399015,13.2361155434,3.53396567486,19.6177310409,-0.412535071839,0.0973333334473,1.1341736586,79.8070408626 +25.43,51.0031652278,0.00190473901905,13.2402451343,3.50859765596,19.6205879551,-0.413383122785,0.097500085815,1.13321301992,79.8790095947 +25.44,51.0031655421,0.00190753462518,13.2443718002,3.48452798576,19.6258342998,-0.411950047578,0.0964983059401,1.13580476753,79.9499439268 +25.45,51.0031658542,0.001910331,13.2484879004,3.45983303294,19.6313790478,-0.411269994552,0.0968204357277,1.13532600003,80.0221235119 +25.46,51.0031661641,0.00191312804176,13.2526045198,3.43469224815,19.6351970043,-0.412053892227,0.0959019446914,1.13812857625,80.0942496116 +25.47,51.0031664718,0.00191592562008,13.2567268053,3.41154061916,19.6389114437,-0.412403190543,0.0951086647425,1.13799603103,80.1657889705 +25.48,51.0031667773,0.00191872381389,13.2608524891,3.38693634785,19.6438372112,-0.412733573742,0.0956431545051,1.13827950776,80.2383428447 +25.49,51.0031670807,0.00192152280209,13.2649918546,3.36345056616,19.6500635665,-0.415139525759,0.0947261878423,1.13849583301,80.3100909937 +25.5,51.003167382,0.00192432244782,13.2691415882,3.33943489352,19.6530676012,-0.414807200454,0.094442728549,1.13817281409,80.3828544599 +25.51,51.0031676812,0.00192712265373,13.2732916921,3.31770691331,19.6579276097,-0.415213575197,0.0947327128557,1.1387264581,80.4563737919 +25.52,51.0031679782,0.00192992357017,13.2774345897,3.29196906549,19.6630421012,-0.413365949222,0.0944659200276,1.14094434367,80.5270101314 +25.53,51.0031682731,0.00193272530923,13.2815690993,3.26919157616,19.6694759428,-0.413535971882,0.0924170049376,1.14223295707,80.5998229855 +25.54,51.0031685659,0.00193552784555,13.2856989896,3.24465672165,19.6742341659,-0.412442092718,0.0936698421632,1.14301316306,80.6713181852 +25.55,51.0031688565,0.0019383309962,13.2898260891,3.22011547272,19.6781002425,-0.412977797772,0.0937059061923,1.14366482589,80.742697959 +25.56,51.0031691448,0.00194113475647,13.2939573702,3.1961790403,19.6827921012,-0.413278434126,0.0952241938632,1.14328183893,80.8151886825 +25.57,51.003169431,0.00194393909385,13.2980965282,3.17204674277,19.6862017576,-0.414553166942,0.0959361638524,1.14192156314,80.8864145531 +25.58,51.003169715,0.00194674394565,13.3022419599,3.14686791058,19.6900136944,-0.414533173463,0.0957925622779,1.14489521618,80.9590422094 +25.59,51.0031699968,0.00194954947903,13.3063906504,3.1226404955,19.6957699983,-0.415204909442,0.0952985238158,1.14628202576,81.0311589108 +25.6,51.0031702765,0.00195235572378,13.3105416749,3.1,19.7,-0.415,0.095,1.145,81.1 +25.61,51.0031705541,0.00195516245188,13.3146968633,3.07703736943,19.7025555265,-0.416037683959,0.0956660696805,1.1437811608,81.1692831146 +25.62,51.0031708296,0.0019579694729,13.3188529435,3.05252276116,19.7041118044,-0.41517834819,0.0940489758687,1.14618999423,81.2370236272 +25.63,51.0031711029,0.00196077671305,13.323008652,3.02749931074,19.7056317006,-0.415963354343,0.0944924709613,1.14758149309,81.3057841161 +25.64,51.0031713739,0.00196358433101,13.3271697016,3.00342083454,19.709415486,-0.416246567839,0.0943043306347,1.14645620957,81.3775663388 +25.65,51.0031716428,0.00196639237469,13.3313262024,2.97948674147,19.7116080901,-0.415053588026,0.0951888214531,1.14651782272,81.4476608559 +25.66,51.0031719096,0.00196920057987,13.3354822266,2.95559629993,19.711682462,-0.416151261605,0.0943625973055,1.14755978293,81.5168300057 +25.67,51.0031721741,0.00197200891929,13.3396334982,2.93085844945,19.7134924094,-0.414103045436,0.0923509957035,1.15031488361,81.5895850489 +25.68,51.0031724365,0.00197481771486,13.3437834006,2.90629326458,19.7180860239,-0.415877430898,0.0915375441087,1.15162329088,81.6597102421 +25.69,51.0031726966,0.00197762702571,13.3479483355,2.88157745041,19.7207260449,-0.417109562676,0.0888559753802,1.15245524029,81.729544543 +25.7,51.0031729546,0.00198043670906,13.3521249118,2.85778892023,19.7233152421,-0.418205701583,0.0923550354134,1.1523740904,81.7980785525 +25.71,51.0031732103,0.00198324678101,13.3563164729,2.83257383423,19.7261811513,-0.420106506361,0.0909309026148,1.15327320498,81.8686001194 +25.72,51.0031734638,0.00198605719143,13.3605017012,2.80699560798,19.7280667229,-0.416939160882,0.0898202504803,1.15262178612,81.936081347 +25.73,51.0031737151,0.0019888679649,13.3646741086,2.78396269429,19.7312776912,-0.41754232349,0.0888598569654,1.15176773287,82.0048557467 +25.74,51.0031739643,0.00199167918551,13.3688561118,2.76024732949,19.7343437501,-0.418858302275,0.0892372750226,1.15453834762,82.0753749732 +25.75,51.0031742113,0.00199449076729,13.373037074,2.73625443536,19.7363478514,-0.417334133316,0.088609508863,1.15613627485,82.1441053165 +25.76,51.0031744561,0.00199730257306,13.3772085975,2.71098649375,19.7374880919,-0.416970566581,0.089260667813,1.15797192318,82.2149951825 +25.77,51.0031746987,0.00200011459905,13.3813885228,2.6876323769,19.7394392364,-0.41901450739,0.087669905582,1.16038795179,82.2844515588 +25.78,51.0031749392,0.00200292681621,13.3855781906,2.66195431276,19.740171722,-0.418919049548,0.0903370924686,1.16285306755,82.3562463805 +25.79,51.0031751774,0.0020057394523,13.3897744982,2.63805204193,19.7453201137,-0.420342460088,0.0894761188018,1.16264769264,82.4264053732 +25.8,51.0031754135,0.00200855260645,13.3939775652,2.61502492579,19.7474444979,-0.420270952138,0.0872706272583,1.16275397708,82.4956498404 +25.81,51.0031756474,0.00201136612067,13.3981838821,2.58894965246,19.750374839,-0.420992426268,0.0864449930226,1.16299372118,82.5656545206 +25.82,51.003175879,0.00201417986962,13.4023981376,2.5643064105,19.7507395753,-0.421858677618,0.0838257589476,1.16350180967,82.6337325615 +25.83,51.0031761085,0.00201699399495,13.4066117223,2.54165598155,19.7556584599,-0.420858255608,0.0843225503257,1.16180650859,82.7008280724 +25.84,51.0031763358,0.00201980858884,13.4108215257,2.51735705825,19.7573173771,-0.421102435332,0.0850354574105,1.16281095155,82.7713859678 +25.85,51.003176561,0.00202262362482,13.415031125,2.49184611384,19.7618646439,-0.420817409161,0.082381505227,1.16364401698,82.8384810345 +25.86,51.0031767839,0.00202543900205,13.4192366244,2.46875408031,19.7621078375,-0.420282477743,0.0820717709932,1.16292198847,82.9087874179 +25.87,51.0031770048,0.00202825454307,13.4234320033,2.44552880522,19.7641639709,-0.418793310541,0.0812722734466,1.16277759966,82.978826134 +25.88,51.0031772235,0.0020310703654,13.4276325025,2.42088052642,19.7660567744,-0.421306522921,0.0814706565042,1.16556876547,83.0476325925 +25.89,51.0031774401,0.00203388650219,13.4318428178,2.39809225852,19.7685784836,-0.420756541823,0.0811886190681,1.16890311753,83.1191284235 +25.9,51.0031776545,0.0020367029247,13.4360540888,2.37264081603,19.7700675814,-0.421497649223,0.0800001668768,1.16841534285,83.1891635994 +25.91,51.0031778667,0.00203951953054,13.4402706985,2.34885066713,19.7711520729,-0.421824289434,0.0787137099437,1.16724485258,83.2606265859 +25.92,51.0031780768,0.00204233650921,13.444495624,2.32479297849,19.7753015903,-0.423160805468,0.0801693358421,1.16884887083,83.3265247846 +25.93,51.0031782847,0.00204515395928,13.4487430066,2.30065156698,19.7777696303,-0.426315725405,0.0784266693121,1.17117231555,83.396484388 +25.94,51.0031784904,0.00204797172571,13.4529977707,2.27681123805,19.7797425959,-0.42463709022,0.07806804901,1.17059552106,83.4642507227 +25.95,51.0031786939,0.00205078982711,13.457243034,2.25132515181,19.7824721264,-0.42441556238,0.077978475812,1.17041131123,83.5341216967 +25.96,51.0031788953,0.00205360826405,13.4614867866,2.2286932962,19.7844528147,-0.424334964095,0.078675286386,1.17054989513,83.6042119956 +25.97,51.0031790945,0.00205642702582,13.4657294787,2.20350278015,19.7870322465,-0.424203456038,0.080957722323,1.16785377234,83.6755767882 +25.98,51.0031792915,0.00205924612994,13.4699813272,2.18039519562,19.7892588626,-0.426166251768,0.0788500163514,1.16993871855,83.7439679393 +25.99,51.0031794864,0.0020620656229,13.4742401252,2.15570692379,19.7924908367,-0.42559335028,0.0770506354909,1.17161802008,83.8124684457 +26,51.0031796791,0.00206488545876,13.4784975854,2.13165165219,19.7940724019,-0.425898682293,0.0742452905871,1.17113040331,83.8823491555 +26.01,51.0031798697,0.00206770565597,13.4827723086,2.11034969867,19.7975637153,-0.429045953632,0.0765008869909,1.17050921376,83.9524665017 +26.02,51.0031800583,0.00207052625104,13.4870612726,2.08552334342,19.7996576526,-0.428746852013,0.0729373871478,1.17356106132,84.0232536731 +26.03,51.0031802447,0.00207334717368,13.4913459454,2.06121784536,19.8021622152,-0.428187709408,0.0735153741406,1.17385431329,84.0935811777 +26.04,51.0031804287,0.00207616840178,13.4956321359,2.03367849949,19.803945686,-0.429050397096,0.0738728648999,1.17556191029,84.1622404841 +26.05,51.0031806105,0.00207899001531,13.4999235069,2.01021561609,19.8075730051,-0.429223786672,0.0697501643778,1.17801387128,84.2321565599 +26.06,51.00318079,0.00208181193921,13.5042123025,1.98503350834,19.8083027013,-0.428535348858,0.0698389893907,1.17924094329,84.3002668183 +26.07,51.0031809674,0.00208463404763,13.5084884461,1.96122807818,19.8101633764,-0.426693367815,0.0720677226203,1.18069683026,84.3683100682 +26.08,51.0031811426,0.00208745641276,13.5127640955,1.93709966041,19.8119062945,-0.428436511686,0.0707686710684,1.17934484337,84.4392021445 +26.09,51.0031813156,0.00209027919172,13.51704875,1.91093952636,19.8159729568,-0.428494381501,0.0687994959354,1.18114095443,84.5083069658 +26.1,51.0031814863,0.00209310240037,13.521337275,1.88788404617,19.8179383686,-0.429210618127,0.0694178284962,1.18306711799,84.5763925044 +26.11,51.0031816549,0.00209592595522,13.5256325186,1.86447955127,19.8208330134,-0.429838099249,0.0694946683771,1.18452811413,84.6456265882 +26.12,51.0031818214,0.00209874974434,13.5299310101,1.83993862683,19.821227084,-0.429860195516,0.0685151353035,1.18571172579,84.715629216 +26.13,51.0031819857,0.0021015738328,13.5342407238,1.8153605674,19.8250351803,-0.432082552885,0.0687573897036,1.18545585074,84.78517962 +26.14,51.0031821478,0.00210439834625,13.5385501229,1.79120815958,19.8271933565,-0.429797274943,0.0681349615014,1.186463626,84.8560379799 +26.15,51.0031823077,0.00210722318649,13.5428514412,1.7664656782,19.8296225931,-0.430466371174,0.066537703836,1.18704178892,84.9239217583 +26.16,51.0031824654,0.00211004838927,13.5471537375,1.7422669068,19.8322828277,-0.42999289107,0.0661598135253,1.18690489032,84.9954576218 +26.17,51.003182621,0.00211287390067,13.5514548686,1.71915667363,19.8339552234,-0.430233342985,0.0677897688777,1.18718680655,85.0627085032 +26.18,51.0031827744,0.00211569963925,13.5557579188,1.69521414364,19.835471891,-0.430376690054,0.0665990814128,1.18672336818,85.1327675646 +26.19,51.0031829258,0.00211852556404,13.5600648586,1.67168433599,19.8365692367,-0.431011277418,0.0660795688742,1.18888683985,85.2028159328 +26.2,51.0031830749,0.00212135190056,13.5643669528,1.64633504106,19.8412520145,-0.429407558263,0.0654698959747,1.18983103001,85.2728267899 +26.21,51.0031832218,0.00212417863202,13.5686640352,1.62149118464,19.8421134702,-0.430008915417,0.0666360214921,1.19060345331,85.3409628041 +26.22,51.0031833665,0.00212700568609,13.5729706988,1.59938761816,19.8457808602,-0.431323805851,0.0645097571781,1.19299472622,85.4099663681 +26.23,51.0031835093,0.00212983328079,13.5772783139,1.57692717898,19.8497030717,-0.430199219253,0.0613808714901,1.19164168812,85.4807036633 +26.24,51.0031836498,0.00213266123229,13.5815908161,1.55031467141,19.850789805,-0.432301223906,0.0621268277071,1.19332621503,85.5515007119 +26.25,51.003183788,0.00213548926111,13.5859122533,1.52366899779,19.8507884539,-0.4319862093,0.0610509132047,1.19535875958,85.6190993667 +26.26,51.0031839239,0.00213831760662,13.5902316809,1.5005378049,19.8552355471,-0.431899300141,0.0606778907215,1.19512126382,85.6884618872 +26.27,51.0031840576,0.00214114638798,13.5945550003,1.47486700023,19.8569070993,-0.432764592001,0.0628384050343,1.19520873778,85.7596338609 +26.28,51.0031841891,0.00214397543483,13.5988912889,1.44997367984,19.8589626235,-0.434493119032,0.0600655278751,1.19580423051,85.8288478738 +26.29,51.0031843184,0.00214680490975,13.6032385896,1.42616818043,19.8629164333,-0.434967027774,0.0606346708524,1.19492441612,85.8984238213 +26.3,51.0031844454,0.00214963483271,13.6076011279,1.39963564064,19.8652525642,-0.43754063831,0.0582250749771,1.19375729249,85.968440526 +26.31,51.0031845701,0.00215246516659,13.6119734937,1.37638557334,19.8686848905,-0.436932516822,0.0564476534766,1.19463675899,86.037865971 +26.32,51.0031846929,0.0021552958031,13.6163369417,1.35436472152,19.8695010448,-0.435757077225,0.0576401968401,1.19607009791,86.1081379494 +26.33,51.0031848136,0.00215812680737,13.6206978882,1.3309826969,19.8738476867,-0.436432226621,0.06048426424,1.19780471622,86.1748311485 +26.34,51.0031849322,0.00216095829018,13.6250593637,1.30889737019,19.8762190416,-0.435862871747,0.0597801024093,1.19826599636,86.2487990905 +26.35,51.0031850488,0.00216379001969,13.6294122236,1.28570636366,19.8773109006,-0.434709101367,0.0577885270054,1.19826806474,86.3182696254 +26.36,51.0031851633,0.00216662200573,13.6337603982,1.260690122,19.8798202327,-0.434925836054,0.0597427365958,1.19946398327,86.3861414059 +26.37,51.0031852755,0.00216945418152,13.6381115342,1.23667013625,19.8799747727,-0.435301349338,0.0578345084302,1.19883757072,86.4540219277 +26.38,51.0031853855,0.00217228655438,13.6424593314,1.21133569343,19.8825867029,-0.4342580918,0.0576166162515,1.20082252623,86.5232146462 +26.39,51.0031854933,0.00217511921304,13.6468117708,1.1867591634,19.8839869366,-0.436229801507,0.056490281394,1.20029941182,86.5935242139 +26.4,51.0031855989,0.00217795232957,13.6511780454,1.16234342403,19.8890145006,-0.437025108698,0.0547081229273,1.20332898651,86.6640711142 +26.41,51.0031857022,0.00218078585891,13.6555585197,1.1370630496,19.8897821119,-0.439069746981,0.0533318755775,1.20326541772,86.7331711905 +26.42,51.0031858033,0.00218361967613,13.6599467839,1.11146367282,19.8930559139,-0.43858310387,0.0538118613933,1.20582535844,86.8029350966 +26.43,51.0031859021,0.00218645391389,13.6643267006,1.0874551059,19.8956857387,-0.437400221302,0.0546134929434,1.20708653655,86.8725708455 +26.44,51.0031859989,0.00218928849619,13.6687080641,1.06569515551,19.8978929259,-0.438872490669,0.0530700183926,1.20733258627,86.9419423342 +26.45,51.0031860936,0.00219212353257,13.673102466,1.04115839825,19.9020601803,-0.440007884376,0.0529696094327,1.20939407274,87.0111984472 +26.46,51.0031861861,0.00219495897807,13.6775006932,1.01700209966,19.9036363506,-0.439637551728,0.0538896691943,1.21067945144,87.0804047497 +26.47,51.0031862765,0.00219779476778,13.6819012699,0.99364681749,19.906892372,-0.440477795556,0.0536765016592,1.21121598273,87.1478246985 +26.48,51.0031863647,0.00220063085092,13.6862972638,0.968892590454,19.9077557526,-0.438720975077,0.0524827243891,1.20951888824,87.2185299834 +26.49,51.0031864508,0.00220346711762,13.6906834117,0.947852726349,19.9094690453,-0.43850861462,0.0524247922161,1.21095494379,87.2861687719 +26.5,51.0031865348,0.0022063036669,13.6950711574,0.921920549382,19.9117228915,-0.439040528045,0.050680984156,1.21096629688,87.3570982559 +26.51,51.0031866166,0.00220914063597,13.6994698541,0.898299024407,19.9153623119,-0.440698814805,0.0479968136758,1.21082709568,87.4288216676 +26.52,51.0031866963,0.00221197798075,13.7038746066,0.872903932197,19.9169971416,-0.440251669763,0.0496935965384,1.21244870934,87.4966651741 +26.53,51.0031867737,0.00221481548675,13.7082783622,0.850482819902,19.9176256549,-0.44049946396,0.0489872507029,1.21194067797,87.5659703427 +26.54,51.003186849,0.0022176532948,13.7126816937,0.825007101297,19.9212375416,-0.440166832968,0.0488214571974,1.21284742825,87.6364142602 +26.55,51.0031869221,0.00222049153121,13.7170839162,0.800493592534,19.9236390207,-0.440277661066,0.0477213546768,1.21486663315,87.7078951214 +26.56,51.0031869929,0.0022233301115,13.7214850158,0.775347916485,19.9260652657,-0.439942254981,0.0464391305491,1.21621979294,87.7761306917 +26.57,51.0031870615,0.00222616899368,13.7258910347,0.751392373202,19.9278770418,-0.44126153716,0.0461989445992,1.21767048202,87.8446092185 +26.58,51.0031871281,0.0022290082403,13.7303025009,0.72900419683,19.931181459,-0.441031696861,0.0474577836423,1.22027348114,87.9161073323 +26.59,51.0031871924,0.00223184792433,13.7347084528,0.703806272406,19.9340176169,-0.440158685283,0.0470496076692,1.21896884575,87.9848142761 +26.6,51.0031872546,0.0022346878935,13.7391133233,0.679537038393,19.935184378,-0.440815415192,0.0460148599104,1.21943008765,88.0522776925 +26.61,51.0031873147,0.00223752807865,13.7435206961,0.656172305462,19.9370497477,-0.440659143503,0.0455662718545,1.2213020066,88.12262257 +26.62,51.0031873726,0.00224036856506,13.7479314363,0.632093395532,19.9394134334,-0.441488904358,0.0448644740173,1.21990841724,88.1915906215 +26.63,51.0031874282,0.00224320937166,13.752343735,0.606389198174,19.9415449568,-0.440970823309,0.0430912430769,1.22104807142,88.260051359 +26.64,51.0031874816,0.0022460505593,13.7567556231,0.582160513681,19.9447625439,-0.441406807942,0.0432302381164,1.22092488547,88.3311700608 +26.65,51.0031875329,0.00224889202455,13.7611691934,0.558601156866,19.9454423008,-0.441307254076,0.0416671712304,1.2234215668,88.3997270958 +26.66,51.003187582,0.00225173369463,13.7655863747,0.533557514441,19.9476380756,-0.442129000437,0.042492764931,1.22551111182,88.4724110524 +26.67,51.0031876288,0.00225457566327,13.7700166769,0.508389575272,19.9496334982,-0.443931433791,0.0409865013917,1.22726961578,88.5412819658 +26.68,51.0031876734,0.00225741798728,13.7744572182,0.48349183139,19.9526271383,-0.444176835558,0.0408689167488,1.22634020045,88.6106153573 +26.69,51.0031877158,0.00226026077739,13.7789014849,0.460091904099,19.9561767772,-0.444676488409,0.0396644912767,1.22822016814,88.6801828615 +26.7,51.0031877561,0.00226310397468,13.7833474958,0.435270214827,19.9583433819,-0.444525692752,0.0384985517138,1.22479457908,88.7485161568 +26.71,51.0031877941,0.00226594750012,13.7877867407,0.411228761532,19.9607834721,-0.443323300874,0.0385683236569,1.2264133492,88.8198382053 +26.72,51.00318783,0.00226879128716,13.792224843,0.387260894438,19.9620159649,-0.444297150198,0.0385444347762,1.22859663967,88.8881069052 +26.73,51.0031878637,0.00227163527355,13.7966709393,0.362879243225,19.9635820158,-0.444922116852,0.0397269479898,1.22966655274,88.9584042368 +26.74,51.0031878952,0.00227447948296,13.801116567,0.338952373762,19.9651469238,-0.44420341086,0.0360705595275,1.2311511033,89.0278561464 +26.75,51.0031879245,0.00227732398312,13.8055662871,0.311667067656,19.9676637834,-0.445740611878,0.0358009026028,1.23094883119,89.0987495786 +26.76,51.0031879515,0.0022801688387,13.8100269571,0.29030685102,19.9701364683,-0.446393403293,0.0366122238652,1.2302300419,89.1649867069 +26.77,51.0031879765,0.00228301411087,13.8144878183,0.264842797869,19.9735120167,-0.445778819296,0.0349305111448,1.23042917072,89.2331777385 +26.78,51.0031879992,0.00228585981384,13.8189421448,0.240926535841,19.976184386,-0.445086489324,0.0338540105566,1.23225709992,89.3043492199 +26.79,51.0031880197,0.0022887058928,13.8233916664,0.215342942549,19.9787904164,-0.444817826699,0.0327490509719,1.23361542079,89.3733381232 +26.8,51.0031880381,0.00229155229904,13.8278422198,0.193065679372,19.9807790232,-0.445292857968,0.0327805062023,1.23471362884,89.4415352025 +26.81,51.0031880544,0.00229439892882,13.8323002668,0.17060482543,19.9819285611,-0.446316548846,0.0313982442694,1.23551707617,89.5117250207 +26.82,51.0031880686,0.00229724576398,13.8367684552,0.144746260836,19.9836622604,-0.447321115181,0.0290592823417,1.23542990122,89.5809405718 +26.83,51.0031880807,0.00230009287837,13.8412329905,0.123443699408,19.9858486552,-0.445585949131,0.0288030661903,1.23667646145,89.6509521586 +26.84,51.0031880906,0.00230294043011,13.8457027985,0.0977426845954,19.989801924,-0.448375662931,0.0296320003246,1.23719908856,89.7221863302 +26.85,51.0031880983,0.00230578859362,13.8501818831,0.073236433265,19.9944371779,-0.447441241959,0.029975847273,1.23814280824,89.7916094481 +26.86,51.0031881037,0.0023086372158,13.8546621773,0.0477788348459,19.9962410226,-0.448617607064,0.0299326616045,1.23914012176,89.8608074213 +26.87,51.003188107,0.00231148606888,13.8591446272,0.0247412571021,19.9976786204,-0.447872365396,0.030424278525,1.24348630385,89.9300696597 +26.88,51.0031881081,0.00231433518971,13.863623989,0,20,-0.448,0.03,1.241,90 +26.89,51.0031881081,0.00231718438543,13.8681103936,0.000679525927927,19.9987299365,-0.449280924461,0.027967767157,1.24119759394,89.9996620101 +26.9,51.0031881082,0.00232003349503,13.8725996964,0.000144119188846,19.9987910447,-0.448579627769,0.0286879305325,1.24277555757,89.9999709855 +26.91,51.0031881081,0.00232288262662,13.8770877762,-0.00161642736921,19.9990386813,-0.449036335141,0.0295947839954,1.24319513273,89.9977144948 +26.92,51.003188108,0.00232573177113,13.8815915067,-0.000790902688881,19.9989724375,-0.451709763379,0.0305103864425,1.24341137942,90.0011456516 +26.93,51.0031881079,0.00232858092197,13.8861105236,-0.000373571821715,19.9991275611,-0.452093610969,0.0315611747272,1.24432590606,90.0023026858 +26.94,51.0031881079,0.00233143010631,13.8906243537,-0.000608478579333,19.9994428685,-0.450672412377,0.0284866568984,1.24456147853,90.0015053416 +26.95,51.0031881079,0.00233427932746,13.8951257455,-6.46800959258e-005,19.999644213,-0.449605943229,0.0274847116987,1.24638111983,90.0033198483 +26.96,51.0031881079,0.00233712863554,13.8996262667,0.000420884960747,20.0006633327,-0.450498307996,0.0288735418884,1.24709563314,90.0030351873 +26.97,51.0031881079,0.00233997792027,13.9041376658,1.05919576637e-005,19.9993164716,-0.451781517931,0.0304517797497,1.24754111655,90.0018907714 +26.98,51.0031881078,0.0023428271753,13.9086557353,-0.00167590449577,20.0002463125,-0.451832374548,0.0301541959401,1.24977973815,90.001671456 +26.99,51.0031881076,0.00234567643846,13.9131691243,-0.00227048243782,19.9994306681,-0.45084543071,0.0283357351921,1.25146933113,90.0018992506 +27,51.0031881075,0.00234852568791,13.9176771474,-0.00165476693323,20.0000539694,-0.450759180253,0.0282805576029,1.25070302594,90.0000851803 +27.01,51.0031881073,0.00235137513676,13.9221761028,-0.00154704765332,20.0022298665,-0.44903191052,0.0299109135437,1.25341935108,90.0025883293 +27.02,51.0031881072,0.00235422468778,13.9266718849,-0.00103275578564,20.0014883567,-0.450124496107,0.028446164249,1.25164415377,89.9998256813 +27.03,51.0031881073,0.0023570741684,13.9311812732,0.00243072115623,20.0012416435,-0.451753165882,0.0291737460667,1.25569627891,89.9985428316 +27.04,51.0031881073,0.00235992354557,13.9356930825,-0.000886252732076,20.0000360095,-0.450608705398,0.0278270596776,1.25482485654,90.0000680051 +27.05,51.0031881073,0.00236277276185,13.9401912285,-2.98670995897e-005,19.9989830839,-0.449020481839,0.0262911619042,1.25399162008,90.0009303339 +27.06,51.0031881073,0.00236562197896,13.9446834883,0.000317099255214,20.0000475599,-0.449431482463,0.0260984566121,1.25673078999,89.9991173931 +27.07,51.0031881074,0.00236847127555,13.9491827409,0.000881868849353,20.0000989612,-0.450419036081,0.0247346101511,1.25466913599,90.0001573656 +27.08,51.0031881075,0.00237132054909,13.9536881533,0.00122747561418,19.9997241229,-0.450663443811,0.0257132031374,1.25747838985,90.0002014765 +27.09,51.0031881076,0.0023741698654,13.9581978922,0.00272797875845,20.000699251,-0.451284343588,0.0237271860706,1.25839906427,89.9985262027 +27.1,51.0031881078,0.00237701933931,13.9627092901,0.00153363364973,20.0019367106,-0.45099523204,0.0248525299797,1.25908541373,89.9983881315 +27.11,51.003188108,0.00237986902004,13.9672255822,0.0025507840688,20.0036027989,-0.452263184101,0.0235976911195,1.26029832158,89.9983855415 +27.12,51.0031881082,0.00238271858472,13.9717381848,0.00256357356293,20.0003074624,-0.450257333832,0.0252613146973,1.2610972085,89.9993126022 +27.13,51.0031881085,0.00238556791473,13.976236558,0.00280930497455,20.0003083887,-0.449417310773,0.0251200451178,1.26201230906,89.9993966357 +27.14,51.0031881087,0.00238841724903,13.9807382193,0.00158414121489,20.0003677531,-0.450914946867,0.0264335397241,1.26244899161,89.9991045628 +27.15,51.0031881088,0.00239126650935,13.9852495534,0.00208796460019,19.9992698185,-0.451351875399,0.0220851404174,1.26415910776,89.9985055709 +27.16,51.003188109,0.00239411570683,13.9897664053,0.00155894678683,19.9994856063,-0.452018499152,0.0230178016231,1.26355801439,89.9984992311 +27.17,51.0031881091,0.00239696479945,13.9942902868,0.00130550575042,19.9977978121,-0.452757798566,0.0217294383825,1.26364043407,89.99793592 +27.18,51.0031881093,0.00239981378899,13.9988128807,0.00166543258442,19.9980384694,-0.451760998454,0.0218314004041,1.26394017904,89.9981999903 +27.19,51.0031881093,0.00240266286228,14.0033398242,-0.00042847196241,19.9989735283,-0.453627694084,0.0217062759772,1.26557911838,89.9995807549 +27.2,51.0031881093,0.00240551202689,14.0078757503,0.000424100551652,19.9993206538,-0.453557520402,0.0230421926857,1.26485108619,89.999360803 +27.21,51.0031881094,0.00240836119298,14.012412117,0.00137914983661,19.9989941473,-0.453715833096,0.024027534469,1.2676264335,90.0008910809 +27.22,51.0031881095,0.00241121038439,14.0169532788,0.00110945127059,19.9996763292,-0.454516518948,0.0233474675806,1.26735694823,90.000091562 +27.23,51.0031881096,0.00241405968936,14.0215036038,0.00152797929175,20.000588263,-0.45554847922,0.0217434889066,1.26895486231,89.9989121338 +27.24,51.0031881098,0.00241690900119,14.0260536449,0.00157073519084,19.9997726447,-0.454459743456,0.0200495156312,1.26807100246,90.0001520163 +27.25,51.0031881099,0.00241975828137,14.0306056802,0.000660554238919,20.0001440981,-0.455947310388,0.0168795946245,1.2695432576,89.9997306763 +27.26,51.0031881099,0.00242260759434,14.0351610247,-0.00025741756214,20.0002329423,-0.455121585761,0.0193140331448,1.27013945806,89.9997844207 +27.27,51.0031881098,0.00242545695035,14.0397086399,-0.00191393343636,20.0007482759,-0.454401459502,0.0213434251049,1.2702540905,90.0010975876 +27.28,51.0031881096,0.00242830630212,14.04425748,-0.00173239070419,20.0001734936,-0.455366561279,0.0190540006082,1.27210706684,90.0011717259 +27.29,51.0031881095,0.00243115552441,14.0488244307,-0.00209869878969,19.9989306684,-0.458023580617,0.018603453054,1.27230007995,89.9999797101 +27.3,51.0031881093,0.00243400467859,14.0534111264,-0.00239870282473,19.9992172065,-0.459315549852,0.0190648353557,1.27561163204,90.0021967534 +27.31,51.0031881091,0.00243685372771,14.05799984,-0.000378017726399,19.9974559733,-0.458427182626,0.0205385354738,1.27547800956,90.0018193327 +27.32,51.0031881091,0.00243970270229,14.0625793378,0.000126663289425,19.9981705907,-0.457472371174,0.0194957195469,1.27519010166,90.0006927347 +27.33,51.003188109,0.00244255171221,14.0671521854,-0.00371031043123,19.9979523006,-0.457097159877,0.0179653626493,1.27458926191,90.0027799451 +27.34,51.0031881087,0.0024454007295,14.0717348189,-0.0029129285865,19.9982740183,-0.459429523872,0.0174868890433,1.27554734201,90.0018891076 +27.35,51.0031881083,0.00244824972252,14.0763248392,-0.00450863751232,19.9976116345,-0.458574545506,0.0182104644625,1.27538390599,90.0015739908 +27.36,51.0031881081,0.0024510986817,14.0809077102,-0.00152673365637,19.9977989615,-0.457999644263,0.0181548273311,1.27618784608,90.0013773064 +27.37,51.0031881079,0.00245394759142,14.0854910773,-0.00225204274225,19.9969172448,-0.458673791396,0.018836599308,1.27737916448,90.0020758358 +27.38,51.0031881077,0.0024567963524,14.0900710329,-0.0013877490224,19.9957109671,-0.457317316648,0.0185008544016,1.28025970385,90.0003920572 +27.39,51.0031881076,0.00245964499196,14.0946536214,-0.00106744496249,19.995212769,-0.459200393254,0.0180209604296,1.2817591958,90.0006549991 +27.4,51.0031881075,0.00246249376869,14.0992436083,-0.00187489976188,19.9976365492,-0.458796988161,0.0191635499833,1.28236233732,90.0004099376 +27.41,51.0031881073,0.00246534275379,14.1038316901,-0.00228915909123,19.9981381136,-0.458819361078,0.0145129907795,1.28112387915,89.9991753667 +27.42,51.0031881071,0.00246819175701,14.1084249846,-0.00278903642643,19.9978909382,-0.459839544267,0.0156453811382,1.28112630266,89.9982369809 +27.43,51.0031881069,0.00247104083998,14.1130242761,-0.000582656883866,19.9992576612,-0.460018759178,0.0138513741406,1.28263096693,89.9979707515 +27.44,51.0031881069,0.00247388993176,14.1176262704,-0.000360982762558,19.9980147242,-0.460380101738,0.0162404949428,1.28357800521,89.9988609116 +27.45,51.0031881068,0.00247673886055,14.1222298405,-0.000854006542956,19.9969694441,-0.460333908697,0.0170862084852,1.28362399684,89.9968934814 +27.46,51.0031881066,0.00247958774116,14.12683023,-0.00301632007659,19.9973385315,-0.459743994648,0.0149605146511,1.28609014916,89.998513492 +27.47,51.0031881065,0.00248243669635,14.1314200474,-0.00131204579882,19.9980163808,-0.458219486059,0.0131817577469,1.28766806139,90.0000995639 +27.48,51.0031881064,0.00248528571975,14.1360092347,-0.000700072323325,19.9982959872,-0.459617981137,0.0138391046546,1.28518107465,90.0008965524 +27.49,51.0031881063,0.00248813489442,14.1406042205,-0.000976893447024,20.000140165,-0.459379173773,0.0132337041562,1.28557662561,90.0009581988 +27.5,51.0031881063,0.00249098407742,14.1451982952,0.000700591430467,19.9984129926,-0.45943576978,0.0128001749388,1.28549554498,90.0008046638 +27.51,51.0031881063,0.00249383316328,14.1498040457,0.000924144150873,19.9987765392,-0.461714324701,0.0133123545037,1.28499377598,90.0000483215 +27.52,51.0031881064,0.00249668221131,14.1544190819,0.000160373337873,19.9978818117,-0.461292919402,0.0138043361231,1.28822407461,89.9996364771 +27.53,51.0031881064,0.00249953132545,14.159035758,-0.000678788953581,19.9997047519,-0.462042299128,0.0127053391626,1.28822720901,90.0006548084 +27.54,51.0031881063,0.00250238050838,14.1636673447,-0.000693918319541,19.998847368,-0.46427503344,0.0142049163354,1.29075350317,90.0013112842 +27.55,51.0031881061,0.00250522978414,14.1683102135,-0.00292209983624,20.0010082435,-0.464298734274,0.0136791792661,1.29140128065,89.9999743667 +27.56,51.0031881059,0.0025080791168,14.1729487931,-0.00177746670305,19.9996460502,-0.463417176968,0.013994908247,1.28981256577,90.0008565807 +27.57,51.0031881057,0.00251092826992,14.177587756,-0.0025262683626,19.9984877482,-0.464375405997,0.0143242853383,1.29010280993,90.0015984329 +27.58,51.0031881055,0.0025137774147,14.182227862,-0.00269020605813,19.9995291206,-0.463645798283,0.0124802557448,1.29105315844,90.0002855829 +27.59,51.0031881052,0.00251662670126,14.1868666363,-0.00329387207237,20.0004780196,-0.464109064142,0.0129028258924,1.29095500347,90.0000995385 +27.6,51.003188105,0.00251947601568,14.1914995542,-0.00225139628787,19.999920374,-0.462474511848,0.0125640511285,1.29308138439,89.9983870901 +27.61,51.0031881047,0.00252232539752,14.1961290588,-0.00322011234866,20.0014245171,-0.463426415049,0.0137035217834,1.29410612379,89.9989873351 +27.62,51.0031881045,0.00252517481812,14.2007619936,-0.00167729256832,20.0004645506,-0.463160547662,0.012749805982,1.29583453362,89.9991164711 +27.63,51.0031881043,0.00252802409976,14.2053891645,-0.00289686277088,19.9994736525,-0.462273616314,0.0090363169967,1.29662672106,89.9992245466 +27.64,51.0031881041,0.0025308733294,14.210007037,-0.00231076339441,19.999734694,-0.46130088908,0.0112615375892,1.29518869962,89.9995756685 +27.65,51.0031881039,0.0025337225179,14.2146259644,-0.00287595420879,19.9988960483,-0.462484587103,0.0114732576501,1.29812115291,90.0007357211 +27.66,51.0031881036,0.00253657165002,14.219253263,-0.00193213496099,19.998943325,-0.462975128692,0.0117606226896,1.29621632139,89.9994176931 +27.67,51.0031881035,0.00253942081258,14.2238970843,-0.000383891451054,19.999323246,-0.465789142432,0.0121913598432,1.29884184769,89.9989418612 +27.68,51.0031881034,0.00254227002661,14.228548854,-0.00152395010667,19.9996659967,-0.464564790981,0.0109979167553,1.29977313393,89.9997892055 +27.69,51.0031881033,0.00254511929138,14.2331946403,-0.00182212336599,20.0000356157,-0.464592482541,0.0148559593027,1.30151439161,89.9994483703 +27.7,51.0031881032,0.0025479686038,14.2378387205,-0.000837175915235,20.0003349777,-0.464223540244,0.0133924082305,1.30033712861,90.001737278 +27.71,51.0031881031,0.00255081788578,14.2424878322,-0.000815208599228,19.9996084052,-0.465598808605,0.0123196781874,1.30265557083,90.0009365292 +27.72,51.0031881031,0.00255366701112,14.2471482555,-0.000140475209529,19.9981358099,-0.46648584788,0.0111911110266,1.30295403226,90.0008941015 +27.73,51.0031881031,0.0025565160479,14.2518149142,0.000299400575783,19.9983653463,-0.466845890362,0.0113843987657,1.30387829532,89.9989917223 +27.74,51.0031881031,0.00255936523722,14.2564902805,-0.00052037681575,20.0002771225,-0.468227384954,0.00954996113069,1.3040500835,90.000297815 +27.75,51.003188103,0.00256221455351,14.2611670728,-0.00114754890636,20.0001478968,-0.467131061525,0.0100904227825,1.30309579748,90.0015989656 +27.76,51.0031881029,0.00256506377317,14.2658432293,0.000439076251273,19.9989207367,-0.468100243502,0.00954280495996,1.30420325624,90.0009439641 +27.77,51.003188103,0.00256791292171,14.270521144,0.000931624545233,19.9991494051,-0.467482699415,0.00987265324139,1.30479527012,90.0028672502 +27.78,51.0031881032,0.00257076207132,14.2751941363,0.00273785028368,19.9989357504,-0.46711576274,0.00957797334436,1.30681564561,90.0001977301 +27.79,51.0031881035,0.00257361114208,14.2798656097,0.00419477850772,19.998042485,-0.467178917899,0.0084122142883,1.30794724522,89.9983005877 +27.8,51.0031881037,0.00257646025681,14.2845396631,0.00100457894438,19.9995531926,-0.467631755471,0.00832563246364,1.30851994268,89.9989050273 +27.81,51.0031881038,0.00257930933075,14.2892217556,0.00137642601168,19.9974697102,-0.468786746004,0.00688161670722,1.30742539431,89.9979374057 +27.82,51.0031881039,0.00258215839454,14.2939041455,0.000664003924414,19.9994107487,-0.467691237252,0.00674924321417,1.30976188276,90.0004107867 +27.83,51.003188104,0.0025850076721,14.2985911522,0.000588612358456,20.000470859,-0.469710087453,0.00609185175987,1.31034077876,90.0001748481 +27.84,51.003188104,0.00258785690709,14.3032842095,0.000586197666652,19.9988131424,-0.46890138053,0.00681273697195,1.31025147572,89.9994648171 +27.85,51.0031881041,0.0025907060044,14.3079780386,0.00186787527679,19.9985380301,-0.46986444581,0.00761260525687,1.31038846588,90.000121234 +27.86,51.0031881043,0.00259355512925,14.3126706998,0.00160965481277,19.9991997608,-0.468667795976,0.00518547273726,1.31133370303,89.9991524425 +27.87,51.0031881044,0.00259640433348,14.3173648187,0.00161873946882,19.9996524595,-0.470155977161,0.00389993118659,1.31269154996,90.0008378514 +27.88,51.0031881046,0.00259925342215,14.3220652446,0.000985618882661,19.9975775647,-0.469929195559,0.00596720153102,1.31428301634,89.9998936421 +27.89,51.0031881046,0.00260210228968,14.3267655894,0.000587402332421,19.9965479596,-0.470139776772,0.00513258655021,1.31453021411,89.9968767943 +27.9,51.0031881047,0.00260495115373,14.3314609086,0.00201115575841,19.9975287719,-0.4689240598,0.0051471895666,1.31623244536,89.9982189669 +27.91,51.0031881049,0.00260780001235,14.3361632124,0.00138231251834,19.9964716461,-0.47153670078,0.00457786023022,1.31652677647,89.9998240182 +27.92,51.003188105,0.00261064887315,14.3408744673,0.00179054817297,19.9975593907,-0.470714271562,0.00513884403156,1.31682878541,90.0003366919 +27.93,51.0031881052,0.00261349779334,14.3455779952,0.000677497516363,19.997305567,-0.469991312793,0.00708356562594,1.31509802528,89.9994847857 +27.94,51.0031881052,0.00261634668401,14.3502856824,0.000743675706957,19.9971449279,-0.471546130054,0.00523683700506,1.31720760963,89.9989423547 +27.95,51.0031881054,0.00261919562242,14.3549982299,0.0024081464867,19.9979757905,-0.470963374354,0.00196234312082,1.31913817854,89.9978482603 +27.96,51.0031881055,0.00262204458096,14.3597133383,0.0012448200861,19.9974275699,-0.472058303445,0.0027803944773,1.31908810623,89.9992540813 +27.97,51.0031881056,0.00262489349753,14.3644308707,0.000795922782755,19.9973865763,-0.47144817763,0.00239716871148,1.31919239494,89.999421427 +27.98,51.0031881057,0.00262774250249,14.3691524796,0.000808115890424,19.9986686018,-0.47287360061,0.00205683256078,1.32131777613,89.999950162 +27.99,51.0031881057,0.0026305915481,14.373876607,0.000139219103768,19.9979571442,-0.47195186869,-0.0017866062439,1.32223269401,89.9992066304 +28,51.0031881057,0.00263344042793,14.3786016822,0.000235499442007,19.9963413855,-0.473063184422,0.00338784832737,1.3225159995,89.9996292691 +28.01,51.0031881057,0.00263628932862,14.383329083,-0.00110653058882,19.9982500283,-0.472416972239,0.00515886554545,1.32492261626,89.9993810407 +28.02,51.0031881056,0.00263913839482,14.3880575112,-0.00188062908809,19.9986648289,-0.473268659377,0.00163189326189,1.32393778227,89.9995172971 +28.03,51.0031881055,0.00264198750394,14.3927965478,0.000696679078509,19.9988526408,-0.474538670559,0.00205063427094,1.32396802231,90.0016545135 +28.04,51.0031881055,0.00264483655733,14.3975362313,-0.000837612910748,19.9978826396,-0.473398019691,0.00174745110344,1.32386126303,90.0005045183 +28.05,51.0031881055,0.00264768558365,14.4022722247,1.91757274058e-005,19.998472481,-0.473800660916,-0.000596928828509,1.32373063438,90.0006479028 +28.06,51.0031881054,0.00265053468237,14.4070185174,-0.000884458484887,19.9988991064,-0.475457892797,0.000811761391584,1.32606590851,90.0011158932 +28.07,51.0031881053,0.00265338383241,14.411772172,-0.00180234187084,19.9991929275,-0.475273009836,0.000328911257168,1.32323971265,90.0030099643 +28.08,51.0031881052,0.00265623300679,14.4165203704,-0.000760853006675,19.9992409179,-0.474366682403,0.000106738668307,1.32662259941,90.0002482696 +28.09,51.0031881052,0.00265908211299,14.4212691355,4.83621741144e-005,19.9982357543,-0.475386334975,-0.00226360187348,1.32506175148,89.9987941685 +28.1,51.0031881051,0.00266193117455,14.4260148551,-0.000636640549036,19.998614272,-0.473757580705,-0.000603205309638,1.3283222528,89.9978380504 +28.11,51.0031881051,0.00266478032869,14.4307569216,-0.000484745436712,19.9995354796,-0.47465571383,0.00142404673787,1.32677529807,89.9969875228 +28.12,51.003188105,0.00266762934482,14.435506364,-0.00159605953276,19.9966768899,-0.475232777419,0.000815604394599,1.32762572317,89.9984956126 +28.13,51.0031881048,0.00267047816957,14.4402649949,-0.00191571770783,19.9968486827,-0.476493395415,0.000468996751574,1.32742111833,89.9970953608 +28.14,51.0031881047,0.00267332706869,14.445029662,-0.00115130229941,19.9977210478,-0.47644002346,-0.000100850349923,1.33043563684,89.9976170176 +28.15,51.0031881047,0.00267617604601,14.4497953528,0.000166997913252,19.9979465589,-0.476698153014,-0.00161709026594,1.32978040768,89.9983801535 +28.16,51.0031881047,0.00267902518567,14.4545588436,0,20,-0.476,0,1.333,90 +28.17,51.0031881047,0.00268187438046,14.4593347869,0.000305980395803,19.9987206754,-0.479188666534,-0.00155217010974,1.33210395004,90.0010625068 +28.18,51.0031881047,0.00268472357824,14.4641262105,-0.000640708553882,20.0000419112,-0.479096051876,-0.0019741198543,1.33339160949,89.9999009824 +28.19,51.0031881046,0.00268757289771,14.4689228593,-0.0013559940919,20.0004291092,-0.480233698693,-0.00191288853478,1.33331276083,89.9994853685 +28.2,51.0031881045,0.00269042219991,14.4737193745,-0.0009005058473,19.9997994838,-0.479069343962,-0.000660376930598,1.33570146992,90.0016111795 +28.21,51.0031881044,0.00269327138426,14.4785037418,-0.000152720720208,19.9987746651,-0.477804124697,-0.000857509958804,1.33742695982,89.999829314 +28.22,51.0031881044,0.00269612048281,14.4832898388,-7.87684335822e-005,19.9985950463,-0.479415257027,0.000336993075182,1.33628634042,90.0002294884 +28.23,51.0031881044,0.00269896949652,14.4880871034,-0.000613498780562,19.9975835402,-0.480037666962,0.000116400034872,1.33707802431,90.0004993594 +28.24,51.0031881043,0.00270181851254,14.49288313,-0.00108854263953,19.9986276889,-0.479167653453,0.00223335349153,1.33867597136,90.0013069506 +28.25,51.0031881042,0.00270466759133,14.4976738509,-0.000595212620308,19.9984646282,-0.478976534382,0.00093608258617,1.33778402618,90.0016784563 +28.26,51.0031881042,0.0027075166839,14.5024693491,-7.06726285974e-005,19.998821255,-0.480123107855,0.00155414029742,1.33925373173,89.9993747567 +28.27,51.0031881042,0.00271036568503,14.5072686157,0.000211475530488,19.997180919,-0.479730207222,0.000574354479802,1.33967975342,90.0001096565 +28.28,51.0031881042,0.00271321463344,14.512064271,0.000258439507291,19.9980811465,-0.479400845074,0.0012770331864,1.34186064028,89.9999316146 +28.29,51.0031881042,0.00271606364598,14.5168514513,-0.000932903002729,19.9980812959,-0.478035219174,0.00235111404254,1.34281082633,89.9987817616 +28.3,51.0031881041,0.002718912693,14.5216306816,-0.000514502724979,19.9985652302,-0.47781084154,0.000964944912882,1.34340726134,90.0003693852 +28.31,51.0031881041,0.00272176174947,14.5264152295,-0.00133163608674,19.9982139764,-0.479098733048,-0.00129774692903,1.34283917938,90.0018875726 +28.32,51.003188104,0.00272461085274,14.5312123355,0.000421764544291,19.9992222885,-0.480322475051,0.000834513758699,1.34324365563,90.000414611 +28.33,51.0031881041,0.00272746002628,14.5360114616,0.00171462582064,19.9992003991,-0.479502735003,0.000616728315166,1.34479097069,89.9999350973 +28.34,51.0031881043,0.00273030908462,14.540812946,0.00199587957443,19.9976051462,-0.480794144588,0.000333505606342,1.34564480604,90.0002250543 +28.35,51.0031881045,0.00273315807129,14.5456249955,0.00272531290568,19.9981943835,-0.481615755604,-0.00189926873745,1.34424591725,90.0005172371 +28.36,51.0031881046,0.00273600705637,14.5504419374,0.000421688793807,19.9975826578,-0.481772630567,0.000839068549609,1.34454314293,90.0010713338 +28.37,51.0031881047,0.00273885606021,14.5552647959,0.00116409818788,19.9984579842,-0.482799079172,-0.00115292441159,1.34424197724,90.0025306358 +28.38,51.0031881049,0.00274170526832,14.5600852407,0.00313843011698,20.0004501894,-0.481289872653,-0.000559091250334,1.34597093463,90.0001406082 +28.39,51.0031881051,0.00274455461265,14.5648968363,0.00155307590189,20.0003703725,-0.481029243164,-0.00118225895268,1.3462406791,90.0021194299 +28.4,51.0031881052,0.00274740392395,14.5697088352,0.000235469460388,19.9999866084,-0.481370547114,0.000961537275678,1.34867095116,90.0008226434 +28.41,51.0031881052,0.00275025308647,14.5745277591,0.00012193495768,19.9982816993,-0.482414225307,0.00196072439272,1.34800767839,89.9996558451 +28.42,51.0031881053,0.00275310218355,14.5793444744,0.00103747146902,19.9990679451,-0.480928828314,0.000442728012478,1.34985836306,90.0000355427 +28.43,51.0031881053,0.00275595131524,14.5841581923,7.48293831279e-005,19.9987676008,-0.481814765832,0.00255604520904,1.35149235885,90.0001474362 +28.44,51.0031881053,0.00275880056214,14.5889797506,0.000754194029513,20.0006853133,-0.482496880626,0.00393546410779,1.35268540484,89.9997748237 +28.45,51.0031881054,0.00276164993788,14.5938012853,0.00141475757599,20.000576401,-0.481810077946,0.00294676771866,1.35493396744,89.9994443549 +28.46,51.0031881055,0.00276449930525,14.5986197266,0.00111304270912,20.000567868,-0.481878179627,0.00284523159991,1.35273540964,89.9970028239 +28.47,51.0031881057,0.00276734876957,14.6034368808,0.00158664033469,20.0019374424,-0.481552655604,0.00177813212173,1.35439421,89.9975449871 +28.48,51.0031881058,0.00277019820911,14.6082601079,0.00114110656244,20.0002201233,-0.483092767129,0.000226944288739,1.35650299386,89.9987694724 +28.49,51.003188106,0.00277304752954,14.6130882804,0.00294468044122,20.0002652653,-0.482541720049,0.000148440304613,1.35548222565,89.9984267742 +28.5,51.0031881062,0.00277589686244,14.6179200587,0.00283272609039,20.0003951439,-0.483813942306,0.000104016379484,1.3567311386,89.9976017185 +28.51,51.0031881066,0.00277874615441,14.6227610408,0.00462820507279,19.9996908083,-0.484382479702,0.000790445105072,1.3547264543,89.9965132186 +28.52,51.0031881069,0.00278159544805,14.6276090534,0.00262266374615,20.0004185064,-0.485220047022,0.000717361383164,1.35669305031,89.997722371 +28.53,51.0031881071,0.0027844448615,14.6324625517,0.00209957443601,20.0013729216,-0.485479603215,-0.00161376550864,1.35794015323,90.0018614905 +28.54,51.0031881073,0.00278729427897,14.6373197013,0.00235477737459,20.0004748701,-0.485950315927,-0.00133278896478,1.36023994464,89.9984016956 +28.55,51.0031881076,0.00279014359996,14.6421781089,0.00352141241327,20.0000185794,-0.485731206069,-0.000991977268368,1.360805534,89.9987287541 +28.56,51.0031881078,0.0027929928964,14.647039906,0.0022138875175,20.0001301851,-0.486628224645,0.00128718377521,1.36106424134,89.9975566715 +28.57,51.003188108,0.0027958421009,14.6519053287,0.00199319632571,19.9987279417,-0.486456318473,0.000958430784127,1.36234445438,89.9979706273 +28.58,51.0031881081,0.00279869130888,14.6567671843,0.000723910652403,20.0001790209,-0.485914786154,0.000264512695465,1.36304569538,89.9955273408 +28.59,51.0031881081,0.00280154062125,14.6616266187,-0.000890293628635,20.0001936069,-0.485972100516,-0.00126985991015,1.36312296317,89.9962830027 +28.6,51.0031881081,0.0028043899121,14.6664978657,0.000146277173963,19.9998768096,-0.488277291153,0.000794695020752,1.36304871023,89.9977404055 +28.61,51.0031881081,0.0028072391227,14.6713836814,0.000584243604907,19.9990670886,-0.48888585968,-0.00115172814701,1.36517231466,89.9961550956 +28.62,51.0031881082,0.00281008840142,14.6762729678,0.00100125910928,20.0008331263,-0.488971424306,-0.000744336185171,1.36629576771,89.9975144069 +28.63,51.0031881084,0.0028129377551,14.6811566902,0.00307033259432,20.0001194224,-0.487773045195,6.43823733272e-005,1.36632806512,89.9955014547 +28.64,51.0031881085,0.00281578704117,14.6860352629,0.000485259656196,19.999884105,-0.487941508336,0.0002164056698,1.36884992967,89.9974678799 +28.65,51.0031881085,0.00281863632372,14.6909143174,-0.00179046618862,20.000069889,-0.48786938597,-0.00228799081313,1.36641879526,89.9987835191 +28.66,51.0031881084,0.00282148558367,14.695794815,0.000839350508472,19.9995670339,-0.488230133291,-0.00293022125643,1.36911890809,89.997948812 +28.67,51.0031881085,0.00282433485645,14.7006743124,-0.000467992110246,20.0002499413,-0.487669338741,-0.0015524957993,1.37049818165,89.9964845842 +28.68,51.0031881085,0.0028271841875,14.7055485181,0.000678301550469,20.0003850013,-0.487171802371,-0.000288878149901,1.37302771096,89.997298926 +28.69,51.0031881085,0.00283003361097,14.7104176923,-0.000407000134469,20.0015475871,-0.486663043451,2.1343739111e-005,1.37500449738,89.9987119229 +28.7,51.0031881085,0.00283288304753,14.7152954851,-0.000206432119279,20.0005686519,-0.488895512338,0.000871581222332,1.37508421368,89.9997265932 +28.71,51.0031881086,0.00283573249464,14.7201841087,0.00268878011711,20.0016959379,-0.488829216551,-0.000486062391033,1.37704917068,89.9985388269 +28.72,51.0031881088,0.00283858194487,14.7250710859,0.0017789290129,20.0006123175,-0.488566211693,-0.000289318201194,1.37669114104,89.9986372971 +28.73,51.003188109,0.00284143134639,14.7299616382,0.00237519840297,20.0010120957,-0.489544251893,-0.00263296871758,1.3768173042,89.9974553928 +28.74,51.0031881092,0.00284428079357,14.7348623807,0.00300316933447,20.0012534641,-0.490604248323,-0.0012289696055,1.37834747737,89.9970871986 +28.75,51.0031881095,0.00284713011668,14.7397645672,0.00268633816864,19.9992702795,-0.48983305392,-0.0016339159537,1.37767968965,89.9988844859 +28.76,51.0031881098,0.0028499794622,14.7446709847,0.0039470985637,20.0015682532,-0.49145045292,-0.000692372126091,1.38029138236,89.9989544217 +28.77,51.00318811,0.00285282903961,14.7495865457,0.00249526289309,20.0025255056,-0.491661745422,-0.00289300402917,1.38026578262,89.9980028611 +28.78,51.0031881102,0.00285567856256,14.7545113869,0.00105136341294,20.0008038592,-0.493306497293,0.000225682792383,1.3801744539,89.9982593428 +28.79,51.0031881103,0.002858528014,14.7594464195,0.00201198692905,20.0015216881,-0.49370001389,-0.00099418874032,1.38224017541,89.9987992358 +28.8,51.0031881105,0.00286137745798,14.7643791241,0.00147967667628,20.000699088,-0.492840900722,-0.00108344085491,1.38159128148,89.9976517451 +28.81,51.0031881106,0.00286422688844,14.7693113558,0.000359411279516,20.0013319046,-0.493605435178,-0.000301576658711,1.38001072399,89.9963274469 +28.82,51.0031881106,0.00286707632958,14.7742359343,0.000352136030912,20.0008490819,-0.491310270384,0.000201170095199,1.37984900838,89.9970065124 +28.83,51.0031881107,0.00286992575495,14.7791529031,0.00158450813068,20.0011106133,-0.492083500006,0.00078061833749,1.38201705616,89.9967120727 +28.84,51.0031881108,0.00287277514058,14.7840762725,0.00178592610191,20.0002911362,-0.492590369849,0.00223500301379,1.38314968922,89.9975696114 +28.85,51.003188111,0.00287562437982,14.7889991348,0.00119138704801,19.9990555286,-0.49198208584,0.00204037461478,1.38073856455,89.9958286852 +28.86,51.0031881111,0.00287847357855,14.7939234241,0.00139677953253,19.9997224612,-0.492875789829,0.00302540413906,1.38354435841,89.9969358784 +28.87,51.0031881111,0.00288132280644,14.7988468002,-0.000820775273221,19.9994648903,-0.491799429551,0.00243593697325,1.38316436216,89.9981222574 +28.88,51.0031881111,0.00288417206536,14.803774721,0.000223771155981,20.0001582493,-0.493784716648,-0.000274914952618,1.38512448488,89.9972290025 +28.89,51.0031881111,0.00288702136184,14.8087189005,-0.000907185475148,19.9999920027,-0.495051190669,-0.000173004818576,1.38506384721,89.9990011407 +28.9,51.0031881109,0.0028898706758,14.8136714671,-0.00185332971809,20.0004038251,-0.495462123082,-0.000522360657961,1.38491289411,89.9966936395 +28.91,51.0031881108,0.00289271989273,14.8186253252,-0.00188251855247,19.9986299044,-0.495309505033,-0.00089297352982,1.38654736713,89.997807567 +28.92,51.0031881107,0.00289556909887,14.8235752345,-1.32068290839e-005,20.000252342,-0.494672357917,0.00227874876201,1.38794246222,89.9979078261 +28.93,51.0031881106,0.00289841850015,14.828514709,-0.00142218418048,20.0013693241,-0.493222529123,0.00280822222554,1.38644884216,89.9948357472 +28.94,51.0031881106,0.00290126787339,14.8334417269,-0.000260310949114,19.999858786,-0.49218105214,0.00219448341591,1.39050053325,89.9939936411 +28.95,51.0031881106,0.00290411710303,14.8383707063,0.00120456462716,19.9993534464,-0.493614838461,0.00247760595094,1.39037921914,89.9951952825 +28.96,51.0031881107,0.00290696639209,14.8433151536,0.000793247227401,20.0006930638,-0.49527461805,0.000966476594357,1.39333308744,89.9955596348 +28.97,51.0031881106,0.00290981581942,14.8482717261,-0.0021605669011,20.0012944464,-0.496039889842,7.66946313751e-005,1.39408172961,89.9968833706 +28.98,51.0031881104,0.0029126653501,14.8532341182,-0.00250300168455,20.0021440834,-0.496438515219,-0.00159917919331,1.39334538195,89.9954963257 +28.99,51.0031881102,0.00291551479722,14.8582017537,-0.00158795367716,20.0001213021,-0.497088583878,-0.0011040771558,1.39606068341,89.993320729 +29,51.0031881102,0.00291836411257,14.8631695652,0.000447457139081,20.0002943789,-0.496473714725,-0.00196510534781,1.39572165072,89.9936956503 +29.01,51.0031881101,0.00292121347727,14.8681378852,-0.00125548609989,20.0008141174,-0.497190290963,-0.000520742437544,1.39862428428,89.9940353701 +29.02,51.0031881101,0.00292406269236,14.8731084337,-0.000349180454606,19.9981940405,-0.496919407235,-0.00207228687267,1.39678730794,89.9939261611 +29.03,51.00318811,0.00292691172609,14.8780731574,-0.000442395261742,19.9982680513,-0.496025337387,-0.00165269866893,1.3979315993,89.9944184471 +29.04,51.00318811,0.00292976083768,14.8830346038,-0.000385877419753,19.9992872368,-0.496263934542,-0.000830017749328,1.39930943536,89.994144891 +29.05,51.0031881099,0.0029326100214,14.8880065412,-0.000952459840509,19.9992805439,-0.498123552999,-0.000232671370704,1.39924798773,89.9937668936 +29.06,51.0031881099,0.0029354593207,14.8929842081,-0.000103451051178,20.0009099394,-0.497409825792,-0.000163022509823,1.40011048798,89.9942380817 +29.07,51.0031881099,0.00293830871895,14.8979551592,0.000399571353781,20.0006698206,-0.496780405446,-3.9374869001e-005,1.40208162912,89.9970784817 +29.08,51.0031881099,0.0029411581489,14.9029271662,0.000413865725689,20.0013548333,-0.497620986369,0.000425583940463,1.40361550581,89.9957365744 +29.09,51.00318811,0.0029440075079,14.9079055463,0.00143570276542,19.9996738368,-0.498055036959,0.000402877369861,1.40534843027,89.9959842558 +29.1,51.0031881101,0.00294685676202,14.9128866826,0.000199022613696,19.9998825417,-0.498172224965,0.000753392308032,1.40843056174,89.9981451847 +29.11,51.0031881102,0.00294970612122,14.9178725657,0.00141431922793,20.001148975,-0.499004390061,0.00283805475103,1.40718923047,89.9992917935 +29.12,51.0031881102,0.00295255553528,14.9228644074,0.000413107369866,20.0006527923,-0.499363950059,0.00141457645004,1.40738090768,89.9986107969 +29.13,51.0031881102,0.00295540511251,14.9278534777,-0.00113267925117,20.0034396935,-0.498450107738,0.000233012786805,1.40859034983,90.0001221408 +29.14,51.0031881101,0.00295825474334,14.9328486469,-0.000786030200322,20.001405245,-0.500583736188,0.00130020484084,1.40943713194,89.9981124421 +29.15,51.0031881101,0.0029611041809,14.937860586,-0.000459407164783,20.0007264437,-0.501804086249,0.00173250103661,1.41112337383,89.997770796 +29.16,51.0031881101,0.00296395360723,14.9428746785,0.000752296003289,20.0012477079,-0.501014415412,0.00117524812842,1.40998384542,89.9993081705 +29.17,51.0031881101,0.0029668030343,14.9478853454,-0.000757005602731,20.000736788,-0.501118953592,0.0013360004114,1.40914187778,90.0005578157 +29.18,51.0031881101,0.00296965244706,14.9529016964,0.00105664674349,20.0010469113,-0.502151246632,0.00126506204611,1.41201239695,89.9982714617 +29.19,51.0031881101,0.00297250189733,14.9579189759,3.38478799922e-005,20.0012635086,-0.501304653981,0.00308982044342,1.41508536069,89.9962972192 +29.2,51.0031881102,0.00297535134706,14.9629464853,0.00178827860099,20.0010391154,-0.50419723188,0.00242492835775,1.41400924867,89.998656962 +29.21,51.0031881105,0.00297820069772,14.9679890775,0.00378801051261,19.9998728756,-0.504321200087,0.00127489952283,1.41554995023,89.9981399084 +29.22,51.0031881107,0.00298104997295,14.9730353835,0.00153699130961,19.9999803184,-0.50493999866,0.00268874207641,1.41705862269,89.9978724623 +29.23,51.0031881108,0.00298389921138,14.978093474,0.000546802579036,19.9993561792,-0.506678105857,0.00216532535925,1.41877167201,89.9967786264 +29.24,51.0031881109,0.00298674841144,14.9831633512,0.000688120735885,19.9994416587,-0.5072973419,0.00179280710739,1.41764082196,90.0001981595 +29.25,51.0031881109,0.00298959769799,14.9882499092,-0.000635525613872,20.0005703703,-0.510014248631,0.00207551905529,1.41747617475,89.9988386575 +29.26,51.0031881108,0.00299244706034,14.9933470935,-8.00623133779e-005,20.0005059274,-0.509422620547,0.00183415428293,1.41879911062,89.9989148975 +29.27,51.0031881109,0.00299529649206,14.9984360625,0.00198441635035,20.0015441415,-0.508371169832,0.000849670639883,1.41972063307,89.9985711566 +29.28,51.003188111,0.00299814597522,15.0035163572,0.000308854542499,20.0012282042,-0.507687773086,0.00146271761133,1.42056174043,89.9991106889 +29.29,51.0031881111,0.00300099537659,15.0085877778,0.000735216810523,20.0003959407,-0.506596337865,0.00140134420552,1.41894393308,90.0001504157 +29.3,51.0031881111,0.00300384462001,15.0136565847,-0.000585926241205,19.9990108333,-0.50716505871,0.00140780320638,1.42121565104,89.9991129436 +29.31,51.003188111,0.0030066937512,15.0187288742,-0.00159824882875,19.998820427,-0.507292831557,0.00183639856796,1.42324220234,89.9977437296 +29.32,51.003188111,0.00300954295176,15.0238041681,0.000909289031006,19.9999846896,-0.507765954486,-0.000106467603804,1.42302781246,89.9992769829 +29.33,51.0031881111,0.00301239230793,15.0288841882,0.00234976815538,20.0010049757,-0.508238063929,0.00068499081983,1.42440937333,89.9975010342 +29.34,51.0031881113,0.00301524171171,15.0339710682,0.00131392706008,20.000653148,-0.509137927342,0.00285721719018,1.42552374365,89.9990897291 +29.35,51.0031881114,0.00301809108115,15.0390634658,0.00124291564276,20.0005230251,-0.509341593027,0.00275623134974,1.42577188158,89.9985471912 +29.36,51.0031881115,0.00302094039691,15.0441595201,0.000625508966142,19.9998994166,-0.509869283698,7.99239314656e-006,1.42585598944,90.0001325026 +29.37,51.0031881116,0.00302378956917,15.0492660145,0.00137589742288,19.9985085666,-0.511429581852,0.000830189266082,1.42726619982,89.9977515444 +29.38,51.0031881117,0.00302663869062,15.054378354,0.001811604962,19.9991861229,-0.511038313173,-0.00177188294587,1.42714050769,89.9985767573 +29.39,51.0031881118,0.00302948784762,15.0594863834,0.00108374806412,19.9990077876,-0.51056758085,-0.00363226238014,1.42938855805,90.0015074962 +29.4,51.0031881119,0.00303233696667,15.0645899826,-2.15267334491e-005,19.9986533142,-0.510152258539,-0.00121004676388,1.42985467474,90.0000798354 +29.41,51.0031881119,0.00303518617411,15.0697014645,0.000505113761499,20.0002486803,-0.512144113664,-0.00016257001405,1.43077184938,89.997249012 +29.42,51.0031881119,0.00303803559222,15.0748122484,-0.000245883487212,20.0016108329,-0.510012663359,-0.000441526570882,1.42925021758,89.9971697156 +29.43,51.0031881119,0.00304088504111,15.0799175616,-0.000763589563774,20.0006808946,-0.511049981432,8.63243104561e-005,1.43043231901,89.9997813464 +29.44,51.0031881118,0.00304373437526,15.0850228115,0,20,-0.51,0,1.432,90 +29.45,51.0031881118,0.00304658357873,15.0901189679,-0.00151436064328,19.9988464054,-0.509231284675,0.00141520639142,1.4323012918,89.9991882701 +29.46,51.0031881116,0.0030494327264,15.0952073166,-0.00182154997663,19.9992167724,-0.50843845029,0.00268666274632,1.43299767799,89.9992218441 +29.47,51.0031881115,0.00305228198611,15.1003014556,-0.000208428050776,20.0004191483,-0.510389342403,0.00145865861421,1.43385653779,90.0005636168 +29.48,51.0031881116,0.00305513135003,15.1054054575,0.00118334057641,20.0006798229,-0.51041104993,0.00184517762614,1.43746433084,89.9993399765 +29.49,51.0031881116,0.00305798058747,15.1105042558,0.000127706557696,19.9986435764,-0.509348606673,0.00374714120796,1.43730466464,89.9996597616 +29.5,51.0031881116,0.00306082978098,15.1155994926,0.000288171762285,20.0000631828,-0.509698760842,0.00153088717391,1.43753747389,90.0004343559 +29.51,51.0031881117,0.00306367895686,15.1206970542,0.00110269088101,19.9983960501,-0.509813555985,0.00161904758523,1.440139886,90.0018193116 +29.52,51.0031881118,0.00306652806995,15.1257983904,0.000246675566169,19.9991818605,-0.510453675402,0.00172836206417,1.4417507835,90.0009072626 +29.53,51.0031881118,0.00306937731019,15.1309101295,-0.000142647524196,20.0001810019,-0.511894141215,-0.00018077939453,1.44175077279,89.9995853058 +29.54,51.0031881117,0.00307222664226,15.1360282651,-0.00175439162468,20.0004709918,-0.511732986647,-0.000537795046725,1.44379197021,90.0002312955 +29.55,51.0031881116,0.00307507597476,15.1411560573,-0.00026490379369,20.0001871275,-0.513825444465,-0.000768945849695,1.44350479638,89.9999093768 +29.56,51.0031881116,0.00307792532043,15.1462926563,0.000133858667323,20.0006559426,-0.513494373125,-0.000437772835378,1.44528581592,90.0017437308 +29.57,51.0031881115,0.00308077458148,15.1514254063,-0.00127691033124,19.9989991957,-0.513055618696,0.0023461141264,1.44562325513,90.0019692563 +29.58,51.0031881114,0.00308362381079,15.1565560005,-0.000785815468377,20.0002102983,-0.513063220935,0.00243855537827,1.4480891126,89.9996717103 +29.59,51.0031881114,0.00308647321379,15.1616852055,-0.000117758141572,20.0014377074,-0.512777771892,0.00287392409504,1.45009883014,89.9982577493 +29.6,51.0031881114,0.00308932265777,15.1668256589,-0.000175807459674,20.0007855774,-0.515312914742,0.0017616554362,1.45033039493,90.0004175386 +29.61,51.0031881113,0.00309217213465,15.1719869655,-0.00148756123827,20.0018997118,-0.516948411155,0.00197614466484,1.45134368314,90.0006322292 +29.62,51.0031881112,0.00309502180933,15.177159338,-1.57720570655e-005,20.0035623102,-0.517526076173,0.00252677442979,1.45414179009,90.0013817526 +29.63,51.0031881112,0.00309787147025,15.1823340287,-0.00043141351502,20.0017066329,-0.517412072089,0.000671867364813,1.45322074008,89.997581417 +29.64,51.0031881112,0.00310072096423,15.1875112622,5.76960268085e-005,20.0012188121,-0.518034617641,0.00258248209343,1.45425688839,90.0014380625 +29.65,51.0031881112,0.0031035704547,15.1926828348,-0.000279031832602,20.0016572087,-0.516279914431,0.00255214346126,1.45423771757,90.0004199459 +29.66,51.0031881111,0.00310641983116,15.1978524026,-0.00245168367629,19.9996184053,-0.517633633814,0.00181980190807,1.45674960894,90.0011216741 +29.67,51.0031881109,0.00310926915668,15.2030269133,-0.00235768447139,20.0009421008,-0.51726851034,0.000357879905867,1.45740756777,90.0006672136 +29.68,51.0031881107,0.00311211854356,15.2082002582,-0.00222215854142,20.0004799518,-0.517400473493,0.00174915445324,1.45801141617,90.0005199125 +29.69,51.0031881105,0.00311496781271,15.2133784293,-0.00183959559888,19.9992892633,-0.518233739258,0.00267670800222,1.46089372134,90.0005985016 +29.7,51.0031881103,0.0031178171066,15.2185566426,-0.00220908096526,20.0008272551,-0.517408937732,0.00248089460046,1.45902785726,89.9993392878 +29.71,51.0031881101,0.00312066657185,15.2237323392,-0.00150365108835,20.0016949827,-0.517730366338,0.000680055158647,1.46074252259,89.9994642509 +29.72,51.00318811,0.00312351603593,15.2289055412,-0.00133902008946,20.0008110074,-0.516910039667,0.00210639952034,1.46270469749,90.0008163221 +29.73,51.0031881099,0.00312636556965,15.2340740883,-0.00118041435945,20.0026724893,-0.516799377661,0.00267064337237,1.46419945808,90.0007527933 +29.74,51.0031881098,0.00312921514779,15.2392445223,-0.00151504869458,20.0014346493,-0.5172874186,0.000373408520935,1.46396012016,90.000067635 +29.75,51.0031881096,0.00313206467335,15.2444194181,-0.00176839673444,20.0019344308,-0.51769174895,0.000180004638272,1.46673019413,90.0018049621 +29.76,51.0031881095,0.00313491411906,15.2496033703,-0.00176884693673,20.0003136418,-0.519098694013,0.000801370576965,1.46599320005,89.9998314607 +29.77,51.0031881093,0.00313776358045,15.2547907416,-0.00253655725366,20.0021546601,-0.518375570316,-0.000650995097438,1.46378527228,90.0001791782 +29.78,51.0031881091,0.00314061309401,15.2599775026,-0.00118029183342,20.0010460138,-0.518976623753,4.44207154723e-005,1.46774880597,89.9996440298 +29.79,51.003188109,0.00314346258747,15.2651722985,-0.00121390019011,20.0018726512,-0.519982554498,-0.00178026980196,1.46786465571,90.0004934686 +29.8,51.0031881089,0.00314631199501,15.2703785525,-0.000257112716314,19.9998396562,-0.521268239956,0.000797486506308,1.47079206902,90.0005127392 +29.81,51.0031881089,0.00314916128244,15.275594891,-0.000892725567065,20.0001866293,-0.521999464836,-0.000811748728864,1.47326926355,89.9997852928 +29.82,51.0031881088,0.00315201066672,15.2808140644,-0.00166334434112,20.0011992173,-0.521835214553,-0.000191133809162,1.47412503821,90.0005211333 +29.83,51.0031881085,0.00315486000508,15.2860261989,-0.00323731197565,19.9995421517,-0.520591678222,-0.00190615720526,1.47428301557,90.0007601964 +29.84,51.0031881083,0.0031577093,15.2912367406,-0.000966502966804,20.0005892986,-0.521516660653,-0.00210618578431,1.47527392954,90.0007164603 +29.85,51.0031881083,0.00316055874525,15.2964485118,0.000245139964644,20.0016526949,-0.520837585181,-0.00102349061829,1.47597984927,89.9997878717 +29.86,51.0031881083,0.00316340810011,15.3016532644,0.000305564795278,19.9993203251,-0.520112941654,-0.00196072586715,1.47915780531,90.0000424619 +29.87,51.0031881083,0.00316625724148,15.3068626428,-0.000835981930554,19.9986556326,-0.521762726606,-0.00292020435414,1.47919477441,89.9994675926 +29.88,51.0031881082,0.00316910632469,15.3120792463,-0.00070322641134,19.9985039251,-0.521557986141,-0.00386634281099,1.48023117926,90.0000154208 +29.89,51.0031881082,0.00317195546696,15.3172979527,-0.000173153023785,19.9994847275,-0.522183281176,-0.00194681230939,1.48366999472,89.9995671739 +29.9,51.0031881082,0.00317480476151,15.3225206324,-0.000401186290133,20.0006417911,-0.522352668323,0.000967778987398,1.4825775809,89.9985449324 +29.91,51.0031881081,0.00317765407782,15.3277525534,-0.00189641252896,19.9997901616,-0.52403153988,0.00154976074134,1.48307838442,89.9974169934 +29.92,51.0031881079,0.00318050331274,15.3329947831,-0.00129948265547,19.9994992741,-0.524414387433,0.000832122311787,1.48351072422,89.9990733387 +29.93,51.0031881078,0.00318335248566,15.3382488663,-0.000658942568871,19.9989197406,-0.526402260828,0.00221205419111,1.48523680311,89.9984199815 +29.94,51.0031881078,0.00318620148353,15.3435029768,-0.000631580202402,19.9970420259,-0.524419831332,-0.000267647834826,1.48654889156,89.9989669176 +29.95,51.0031881078,0.0031890503993,15.3487589942,0.00177317874829,19.9977670785,-0.526783651736,-0.00224183264976,1.48851540919,89.9989534157 +29.96,51.0031881079,0.00319189938447,15.3540258127,0.000274576511346,19.9980163659,-0.526580051452,0.000473114832029,1.48811337132,89.9998772787 +29.97,51.003188108,0.00319474833507,15.3592937532,0.000825537388662,19.997281651,-0.527008053621,0.000550864836743,1.48985292865,89.9987567219 +29.98,51.003188108,0.00319759730887,15.3645593077,-0.000360762783197,19.9983422407,-0.526102832232,0.00126442896913,1.48911098238,89.99904992 +29.99,51.003188108,0.00320044641037,15.3698172446,-8.93863947562e-005,19.9990745061,-0.525484558859,0.0022430763386,1.4914093771,89.9995759648 +30,51.003188108,0.00320329547127,15.3750824957,-0.000368751192884,19.99777211,-0.527565647459,5.33958198457e-005,1.49097054214,90.0003714665 +30.01,51.0031881079,0.00320614446199,15.3803546729,-0.000549851322216,19.9980894846,-0.526869802485,0.00424825849761,1.49217180701,89.9983823521 +30.02,51.0031881078,0.00320899345014,15.3856195887,-0.00116073903254,19.9977358602,-0.526113362212,0.0018967466765,1.49183890595,89.9993442186 +30.03,51.0031881078,0.00321184229031,15.3908863155,-5.59933296718e-005,19.9960122029,-0.527231997077,0.000371917379443,1.49213565883,89.9994066142 +30.04,51.0031881077,0.00321469113951,15.3961546652,-0.000840481901,19.9978626583,-0.526437934145,0.0010551584622,1.49474609799,90.0001834773 +30.05,51.0031881077,0.00321754002857,15.401420816,-0.000510066947113,19.996571918,-0.526792223347,0.000388423101674,1.49703903738,89.9989589049 +30.06,51.0031881075,0.00322038894589,15.4066913363,-0.002695743966,19.9982592553,-0.52731184097,-1.29353795491e-005,1.4987704096,90.0010439298 +30.07,51.0031881073,0.00322323783413,15.4119676751,-0.00324662643355,19.9961638051,-0.527955925019,0.00198565668467,1.50042091195,90.0003702303 +30.08,51.003188107,0.00322608672817,15.4172497454,-0.00235883505694,19.9983407307,-0.528458123763,0.000258667372965,1.49974942612,89.9990566373 +30.09,51.0031881068,0.0032289357912,15.4225455167,-0.00283562137716,19.9985361207,-0.530696137404,-0.000152077870084,1.50046988309,89.9984437006 +30.1,51.0031881065,0.00323178487839,15.427845924,-0.00289358714279,19.9986799271,-0.529385327404,-0.00136639032029,1.50143523944,89.9978449921 +30.11,51.0031881063,0.00323463403052,15.433142701,-0.00224057136865,19.9994478815,-0.529970067275,-0.000841874656456,1.50147399357,89.9961834729 +30.12,51.0031881061,0.00323748324359,15.4384443682,-0.00173665918714,19.9995355483,-0.530363376891,-0.0017547466015,1.50204527939,89.9976770739 +30.13,51.003188106,0.00324033242903,15.4437485431,-0.00031536992695,19.9990599106,-0.530471603547,-0.00313024626246,1.50243520768,89.9957318906 +30.14,51.003188106,0.00324318155629,15.4490527996,-0.00103296322457,19.9987188263,-0.530379696629,-0.000273514425198,1.50310954444,89.997052064 +30.15,51.0031881058,0.00324603079273,15.454361928,-0.00255373790193,20.0005927135,-0.531445990645,-0.00168279966644,1.50530173624,89.9967984623 +30.16,51.0031881056,0.00324888005251,15.4596706534,-0.00165109028423,19.9990464996,-0.530299090733,-0.00153012039028,1.50579470266,89.9978651492 +30.17,51.0031881055,0.00325172922185,15.4649707972,-0.00127882390194,19.9993231299,-0.529729669172,-0.00232516246512,1.50859690131,89.995086114 +30.18,51.0031881053,0.00325457836834,15.4702728723,-0.00198419756011,19.9987258359,-0.53068535154,0.000204760985076,1.50942245093,89.9964436225 +30.19,51.0031881052,0.00325742734408,15.4755816041,-0.000421068501892,19.9969259317,-0.531061000602,-0.00183893277698,1.50804059262,89.9969126712 +30.2,51.0031881052,0.00326027621176,15.4808907742,-0.000795504087718,19.997208854,-0.530773028756,-0.00100087062109,1.51107407509,89.9958637192 +30.21,51.0031881051,0.00326312529696,15.4861953614,-0.000969376703586,19.999979675,-0.530144411044,-0.000115912313709,1.51214578424,89.9959640556 +30.22,51.003188105,0.00326597441651,15.4914911037,-0.00192631556984,19.9976911463,-0.52900403006,0.000318027623732,1.51325692501,89.9983997664 +30.23,51.0031881048,0.00326882344501,15.4967860047,-0.00188846492842,19.9987014805,-0.529976178834,-0.00121856975199,1.51640087986,89.9991539692 +30.24,51.0031881046,0.00327167250959,15.5020959151,-0.0015027968587,19.9981976312,-0.532005909937,-0.000734186135789,1.51694679915,89.9979994373 +30.25,51.0031881046,0.0032745215621,15.5074234677,0.000470442327376,19.99853211,-0.533504592963,0.000757067714767,1.51669898337,89.9959752795 +30.26,51.0031881046,0.00327737054348,15.5127587941,5.50096539323e-005,19.9971991123,-0.533560691019,0.000143172625505,1.51944982796,89.996031195 +30.27,51.0031881046,0.00328021943475,15.5180984757,-0.000944347510027,19.9972672013,-0.534375625359,9.40630659335e-005,1.52219202959,89.9952903383 +30.28,51.0031881045,0.00328306840923,15.523437575,-0.00176194945055,19.9983672317,-0.533444249817,-0.000705931316256,1.52147111797,89.9957865925 +30.29,51.0031881043,0.0032859174183,15.5287714421,-0.00274422856724,19.9977527158,-0.53332915598,-0.000440639414098,1.52393256015,89.9952558524 +30.3,51.0031881041,0.00328876644112,15.5341055301,-0.00107191652138,19.9985605143,-0.53348845563,0.0010858163895,1.52276782152,89.9974832071 +30.31,51.0031881039,0.00329161551433,15.5394413082,-0.00204830119991,19.9984599488,-0.53366716168,0.000382523954603,1.52368510657,89.9972345312 +30.32,51.0031881037,0.00329446465955,15.5447793907,-0.00295499872292,19.9995715709,-0.533949329783,0.000361086165392,1.52481855233,89.9968574139 +30.33,51.0031881035,0.00329731383932,15.5501143337,-0.00304776831693,19.9989449863,-0.533039286661,0.001842329921,1.52636257744,89.9959640644 +30.34,51.0031881032,0.00330016290408,15.5554514614,-0.00263954948951,19.9979571156,-0.534386253744,0.00111936481231,1.52849050358,89.9958633245 +30.35,51.003188103,0.00330301203234,15.5607950285,-0.00107462624304,19.9998363636,-0.534327153175,-0.001560696842,1.52855078567,89.9965660746 +30.36,51.0031881029,0.00330586107195,15.5661309115,-0.00183093148662,19.99671258,-0.532849442974,0.000366483831186,1.5279560778,89.9952911277 +30.37,51.0031881028,0.00330871003027,15.5714599831,-0.000855022146211,19.998695386,-0.532964883501,0.000623391281471,1.52903086663,89.9936905492 +30.38,51.0031881027,0.00331155915605,15.5767994464,-0.000618127981176,19.999063315,-0.534927773982,-0.000785543863993,1.52940814171,89.9961781035 +30.39,51.0031881027,0.00331440830789,15.5821535055,0.000451255289388,19.9990613843,-0.535884052559,9.61800991335e-005,1.53049314852,89.9980425189 +30.4,51.0031881027,0.00331725748311,15.5875161161,-0.00112461840041,19.9993916174,-0.536638056045,-4.26859998851e-005,1.53273151458,89.9974666045 +30.41,51.0031881026,0.00332010668954,15.5928842029,-0.000771481107008,19.9994994343,-0.536979311265,-0.0025352718642,1.53348387288,89.9965009372 +30.42,51.0031881025,0.00332295595974,15.5982533554,-0.00076519560781,20.0002869572,-0.536851193187,-0.00330088926814,1.53479072122,89.9987406795 +30.43,51.0031881024,0.00332580527108,15.6036338298,-0.00205073475399,20.0000769905,-0.539243674885,-0.00274058246553,1.53589181413,90.0002247945 +30.44,51.0031881023,0.00332865462691,15.6090291218,-0.000367184454524,20.0009116473,-0.539814732501,-4.20463801302e-005,1.53699501415,90.0003015859 +30.45,51.0031881022,0.00333150399201,15.6144244512,-0.00178302123707,20.0002070466,-0.539251146429,-0.002165396236,1.53925239759,89.999041093 +30.46,51.0031881021,0.00333435330949,15.6198118608,-0.000888596182187,20.0002431823,-0.538230780551,-0.00185856658503,1.54275255087,89.998998409 +30.47,51.003188102,0.00333720258105,15.62519973,-0.000866878186069,19.9995624556,-0.539343047182,-0.00213988653378,1.54252727696,89.9988760069 +30.48,51.0031881019,0.00334005178848,15.6305971756,-0.0010635456431,19.9993429358,-0.540146078266,-0.00122681788259,1.54187417543,89.9993817061 +30.49,51.0031881018,0.00334290095591,15.6359962228,-0.000686608081361,19.999000955,-0.539663367575,-0.00134146385495,1.54460592302,89.9996108225 +30.5,51.0031881018,0.00334575018835,15.6413910697,5.41034418905e-005,20.000255611,-0.539306001923,-0.000917477451403,1.54696429014,89.9998195705 +30.51,51.0031881018,0.00334859947429,15.6467935716,0.00109827533191,19.9997520721,-0.541194380772,-0.000152413450507,1.54577867411,90.001400168 +30.52,51.0031881019,0.00335144874576,15.6522004418,0.000726867080973,20.0000525165,-0.540179667873,-0.00167275682947,1.54559029716,90.0001203874 +30.53,51.0031881021,0.00335429811086,15.6576044129,0.00353202357736,20.0010664929,-0.540614550635,-0.000154943410043,1.54675089871,89.9999984335 +30.54,51.0031881024,0.00335714751923,15.6630159485,0.00251470728773,20.000659973,-0.541692556444,-0.00210439021709,1.5479212237,90.0002333763 +30.55,51.0031881026,0.00335999687284,15.6684405612,0.0022679635126,20.0002978801,-0.543229995346,0.000862929401143,1.54754335431,89.9989322988 +30.56,51.0031881027,0.00336284614672,15.6738673479,0.000258690557612,19.9995405821,-0.542127335884,0.000869691766228,1.54851344497,89.9990630697 +30.57,51.0031881028,0.00336569541141,15.6792844453,0.00111752357746,20.000168985,-0.541292141779,0.00321717689847,1.55152311438,89.9989179412 +30.58,51.0031881028,0.00336854454675,15.6846992686,-9.12737919939e-005,19.997724655,-0.54167253008,0.00293908373615,1.55037158353,89.9999846249 +30.59,51.0031881028,0.00337139354687,15.6901087912,4.95190995307e-005,19.9982707037,-0.540231996679,0.000401062349054,1.54881754911,90.0016290752 +30.6,51.0031881028,0.00337424271581,15.6955216532,0.000441786243119,20.0000948535,-0.542340385239,0.00231922202123,1.5514996988,89.9997484547 +30.61,51.0031881029,0.0033770920084,15.7009505672,4.80601787911e-005,20.0000065033,-0.543442418486,0.00191370332623,1.55653647106,90.0009046624 +30.62,51.0031881028,0.0033799413565,15.7063827722,-0.000569777791901,20.0008740763,-0.542998590826,0.0037751021686,1.55617850893,89.9998743042 +30.63,51.0031881028,0.00338279068976,15.7118200401,-0.00114538335521,19.9997983531,-0.544454983259,0.00300411149452,1.55969664497,89.9999845714 +30.64,51.0031881027,0.00338563999148,15.7172615069,-0.000419390642006,20.0004312178,-0.543838385478,0.00220146365754,1.55827310056,89.9999466773 +30.65,51.0031881027,0.00338848941532,15.7227094092,-1.4185900416e-005,20.0015128649,-0.545742067717,0.000343644217985,1.5602406843,89.9985084986 +30.66,51.0031881027,0.00339133890986,15.7281676516,-0.000539481301238,20.0014237575,-0.545906401694,0.000816673253954,1.562204782,89.9973829978 +30.67,51.0031881026,0.00339418845563,15.7336289745,-0.00123742281271,20.0022320885,-0.546358194899,0.00193138473483,1.55997954912,90.0004680958 +30.68,51.0031881025,0.00339703798956,15.7390880875,-0.00120159526275,20.0012575184,-0.545464390732,-5.43231113757e-005,1.56153941532,89.9997090017 +30.69,51.0031881023,0.00339988735928,15.7445455247,-0.00232903012944,19.9999269918,-0.546023059961,0.00125767652905,1.56274936247,90.0004262165 +30.7,51.0031881021,0.00340273666846,15.7500073877,-0.00121322408145,20.000407483,-0.546349531966,0.000596960804211,1.56571412939,89.9998283697 +30.71,51.003188102,0.00340558588631,15.7554650889,-0.000954874562942,19.9986450187,-0.545190709111,-0.000144173990978,1.5655588676,90.0018684871 +30.72,51.003188102,0.00340843507514,15.7609160424,0,20,-0.545,0,1.567,90 +30.73,51.003188102,0.003411284381,15.7663674561,0.000695106028418,20.0002881183,-0.545282739454,-0.00161573984165,1.56988210868,90.000730792 +30.74,51.0031881021,0.00341413360546,15.7718146186,0.00067270023226,19.9988572836,-0.544149755323,-0.000323385859521,1.57097636292,90.0008998461 +30.75,51.0031881021,0.00341698279462,15.7772586745,-0.00153470132319,19.9997923967,-0.544661420314,-0.00134675005028,1.5732737553,90.0025777575 +30.76,51.003188102,0.00341983207242,15.7827011283,-0.000191074344632,20.0001018912,-0.543829340813,-0.00136945697909,1.57129855673,90.0015237414 +30.77,51.003188102,0.00342268135215,15.7881423895,5.77075463783e-005,19.9998194192,-0.544422911586,3.67906430584e-005,1.57246976907,90.0018854443 +30.78,51.0031881021,0.0034255306091,15.793586207,0.0019176882353,19.9997821746,-0.544340583903,0.00116873238289,1.57333952051,90.0014917715 +30.79,51.0031881022,0.00342837987802,15.7990398007,0.000531559873855,19.9999875623,-0.546378142935,-0.00125417095278,1.576179394,90.0022145953 +30.8,51.0031881022,0.00343122914929,15.8045061529,-0.00083020870645,19.9998151943,-0.546892297869,-0.00134141407844,1.57589508351,90.0021062761 +30.81,51.003188102,0.00343407833226,15.8099789006,-0.00244744336728,19.9987478189,-0.547657240672,-0.00048174124034,1.57672930936,90.0014945761 +30.82,51.0031881018,0.00343692751407,15.8154640889,-0.00255013114401,19.9997990891,-0.549380424313,-0.00186219535461,1.57626871348,90.0013853849 +30.83,51.0031881016,0.00343977686996,15.8209427748,-0.00125031164355,20.0011916123,-0.546356768079,-0.000912212843831,1.57702099223,90.0022890011 +30.84,51.0031881016,0.00344262625963,15.82642161,-0.000191479062672,20.0002734894,-0.549410268162,-0.00137965279234,1.57881325775,89.9994508189 +30.85,51.0031881015,0.00344547574093,15.8319133123,-0.00184311080359,20.0024779326,-0.548930191964,8.43521066393e-005,1.58007200304,89.9988988433 +30.86,51.0031881014,0.00344832522115,15.8374003358,-0.000196077270901,20.0002582992,-0.548474511079,-0.000262171388956,1.57993986165,89.9996153316 +30.87,51.0031881014,0.00345117448512,15.8428904338,0.000448144877544,19.9994421965,-0.549545079412,0.000295612313184,1.58230013011,90.0012570789 +30.88,51.0031881014,0.00345402368201,15.8483868241,-3.92638277618e-005,19.9993164519,-0.549732976334,-0.00132257704063,1.58071671032,89.9998578442 +30.89,51.0031881014,0.00345687274369,15.8538869924,-0.00105426559614,19.9975442789,-0.550300692366,-0.00253620582485,1.58299242533,90.0000716426 +30.9,51.0031881012,0.00345972164441,15.8593875553,-0.00144174692803,19.9970567248,-0.549811886176,-0.00344395136852,1.58221063443,90.0002971869 +30.91,51.0031881011,0.00346257045911,15.8648810537,-0.00227229427452,19.9963368096,-0.548887789272,-0.00315259906646,1.58501942591,89.9994604752 +30.92,51.0031881009,0.00346541932358,15.8703738731,-0.00152158070533,19.9977552967,-0.549676087309,-0.0041663438064,1.58634223851,89.9983232983 +30.93,51.0031881008,0.00346826825877,15.8758732962,-0.000833013670545,19.9973298581,-0.550208536973,-0.00579335006925,1.58707814316,89.998668509 +30.94,51.0031881007,0.00347111744935,15.8813740709,-0.000835234968696,20.0013404312,-0.549946402022,-0.00357146856014,1.58861525405,89.9975774315 +30.95,51.0031881006,0.00347396696141,15.8868741597,-0.00141080671955,20.001843254,-0.550071358043,-0.00382521188184,1.58853940094,89.9965793647 +30.96,51.0031881005,0.00347681638355,15.8923715325,-0.0012381829049,20.0000778833,-0.549403208389,-0.00267047648371,1.59083246617,89.9989051625 +30.97,51.0031881004,0.00347966582259,15.8978659558,-8.46480913879e-006,20.0020806563,-0.549481453446,-0.00370949083757,1.59023181341,89.9989409821 +30.98,51.0031881004,0.00348251534879,15.9033655618,-0.00142038449326,20.0013015895,-0.550439747506,-0.00424884258016,1.59229922238,90.0007041175 +30.99,51.0031881003,0.00348536468931,15.9088696747,-0.00139594379512,19.9994739748,-0.550382835473,-0.00448756226585,1.59302171237,90.0003736677 +31,51.0031881001,0.00348821391888,15.9143847772,-0.00179550893036,19.9997439691,-0.552637658878,-0.00322208949267,1.59153082647,90.0009402398 +31.01,51.0031881001,0.0034910630951,15.9199094156,0.0010385266011,19.9987250422,-0.552290027896,-0.00380905838243,1.5925246185,89.9997880394 +31.02,51.0031881001,0.00349391223249,15.9254323087,-0.000826155054116,19.9991989068,-0.552288586056,-0.00155268635979,1.59214925283,90.0019328849 +31.03,51.0031881,0.00349676143811,15.9309480561,-0.000652892088215,19.9996829775,-0.550860881919,-0.000530079259665,1.59381878978,89.9996003327 +31.04,51.0031880999,0.00349961067978,15.9364654806,-0.000977111401455,19.9997050407,-0.55262402107,-0.0010718166036,1.59693809388,90.0008363743 +31.05,51.0031880999,0.00350245990621,15.9419970825,2.72866679248e-005,19.9994690572,-0.553696366523,-0.00196119888749,1.59671013581,90.0008428951 +31.06,51.0031880999,0.00350530917329,15.9475293212,-0.000950560984262,20.0002757084,-0.552751377168,-0.000536535616317,1.6001825078,90.001133994 +31.07,51.0031880998,0.00350815844599,15.9530531428,-0.000743414650849,19.9995478842,-0.552012935605,0.000175896850512,1.60118139604,89.9992404564 +31.08,51.0031880997,0.00351100763457,15.9585839182,-0.000499972617303,19.999094994,-0.554142138246,-0.00114037998036,1.60181115891,90.0002572269 +31.09,51.0031880997,0.00351385675584,15.964127196,-0.00106726204399,19.998602864,-0.554513431995,-0.00253039216406,1.60111255149,90.0015491358 +31.1,51.0031880995,0.00351670592799,15.9696737382,-0.00140907337729,19.999809449,-0.554794995983,-0.00172891934262,1.60440125786,90.0018171888 +31.11,51.0031880995,0.00351955518464,15.9752250213,-0.000319796028133,19.9997890123,-0.555461635594,-0.00180507739635,1.60478317349,90.0019237484 +31.12,51.0031880994,0.00352240440825,15.9807770786,-0.000455939087356,19.9993456827,-0.554949818164,-0.000827532255397,1.60388985224,90.0006548267 +31.13,51.0031880994,0.00352525360189,15.986323807,-0.00148602776428,19.9993684303,-0.554395867038,-0.000750011319218,1.60475582216,89.9981182807 +31.14,51.0031880993,0.00352810271327,15.9918755767,-0.000157258510446,19.9981908212,-0.555958066902,5.7608997697e-005,1.60574685066,89.9992466816 +31.15,51.0031880993,0.00353095190604,15.9974339151,-0.000260330308959,20.0005109772,-0.555709616347,0.00177834558959,1.60720827597,89.9986077184 +31.16,51.0031880992,0.00353380117607,16.002998086,-0.000773526212024,19.9992755358,-0.557124561756,-0.00012269484842,1.60757106246,89.9985438237 +31.17,51.0031880992,0.00353665045816,16.0085717577,0.000709304093619,20.0006804198,-0.55760978476,-0.00141974172901,1.60837815444,89.999253646 +31.18,51.0031880993,0.00353949984214,16.0141423736,0.000357370597199,20.0007057935,-0.556513388241,0.00029219588243,1.60912379832,90.001553617 +31.19,51.0031880992,0.00354234924138,16.019714485,-0.00127085975114,20.0008948396,-0.557908902142,0.00133735475826,1.60816615919,90.0013760135 +31.2,51.0031880991,0.0035451984784,16.0252857539,-0.00191370510514,19.9984284451,-0.556344867292,0.000536393362408,1.60931568467,89.9995150324 +31.21,51.0031880989,0.00354804755416,16.0308441655,-0.00185488302952,19.9986309811,-0.555337455468,0.000847958354564,1.60925700691,89.9994417402 +31.22,51.0031880988,0.00355089654396,16.0363983803,-0.000395115081014,19.9972216726,-0.555505501001,-0.00055346823833,1.61075268678,89.999328681 +31.23,51.0031880988,0.0035537453447,16.0419588154,-0.000599140719226,19.9959769021,-0.556581520482,0.00233521219985,1.6116132337,90.0010305089 +31.24,51.0031880987,0.00355659409755,16.0475292011,-0.000495363302737,19.9965494941,-0.557495623144,-0.000867438456512,1.61191582249,90.0007977366 +31.25,51.0031880987,0.00355944285309,16.0530939828,-0.000594952350385,19.996014516,-0.555460726025,-0.00273084456025,1.61402927594,89.9999112793 +31.26,51.0031880986,0.00356229164059,16.0586481033,-0.00101734456973,19.9969983285,-0.55536337377,-0.00144648073402,1.61428986978,89.999374888 +31.27,51.0031880986,0.00356514073167,16.064200895,0.000416297596339,20.0002764403,-0.555194961754,0.000576452841798,1.61447731122,89.9986540382 +31.28,51.0031880986,0.00356799004776,16.0697590764,-6.82858686965e-007,20.0001571029,-0.556441305993,0.000489974093427,1.61472421245,89.9998698132 +31.29,51.0031880986,0.00357083922557,16.0753210828,-0.000535485109415,19.9983352168,-0.555959990669,0.000536348128747,1.61645387734,90.0026294785 +31.3,51.0031880985,0.00357368834584,16.0808905982,-0.000380124215502,19.9993494775,-0.557943072749,-5.59696966496e-005,1.61724703107,90.0022477966 +31.31,51.0031880984,0.00357653751338,16.0864691666,-0.00103830222458,19.9989986975,-0.557770618238,-8.80775622415e-005,1.61809073977,90.0007297585 +31.32,51.0031880984,0.00357938669577,16.0920494309,-0.000858433083538,19.9995580038,-0.558282230757,4.60742887895e-005,1.61830892121,90.0018281443 +31.33,51.0031880983,0.00358223596145,16.0976438674,-0.000958562752711,20.0001680743,-0.560605067487,-0.00277880455093,1.62095031102,90.0012520887 +31.34,51.0031880982,0.00358508535353,16.1032531365,-0.00131503928653,20.0013324752,-0.561248768292,-0.00336381280713,1.62080573333,90.0024389349 +31.35,51.003188098,0.0035879348971,16.1088684427,-0.00168742860656,20.0022949736,-0.561812463683,-0.0018638514597,1.62205130242,90.0004595187 +31.36,51.0031880979,0.00359078443233,16.1144842236,-0.00101276803435,20.0012152579,-0.561343724625,-0.000458661094124,1.62349375847,90.0005134874 +31.37,51.0031880978,0.00359363383418,16.120098674,-0.00241628590116,20.0004225005,-0.561546354364,-0.0013534377513,1.6250335657,90.0025011029 +31.38,51.0031880976,0.00359648330235,16.1257223253,-0.000793109590178,20.0021464538,-0.563183890904,-0.00080608457542,1.6263028743,90.0006235812 +31.39,51.0031880976,0.00359933289502,16.1313499484,-0.000821964280447,20.0021703262,-0.562340747992,-0.00171861301847,1.62747872928,90.0010303029 +31.4,51.0031880975,0.00360218245748,16.1369761504,0.000494888568532,20.0017222795,-0.562899632706,0.00104910388409,1.62896831654,89.9996255343 +31.41,51.0031880976,0.0036050321002,16.1426035268,0.00112669887022,20.003297265,-0.562575653034,0.000848883609525,1.62825141558,89.9989708879 +31.42,51.0031880977,0.00360788187498,16.1482331422,0.00139622089705,20.0035760835,-0.563347427097,0.000366770654059,1.62977706134,89.9989494021 +31.43,51.0031880977,0.00361073163941,16.1538584673,-0.000848291796535,20.0031520782,-0.561717587222,0.00143286407782,1.62947187168,90.0000002192 +31.44,51.0031880976,0.00361358143251,16.1594859447,-0.00198056881337,20.0039787384,-0.563777893498,0.00218602375512,1.63030891394,90.0000727794 +31.45,51.0031880975,0.00361643124078,16.1651273261,-0.000764979451237,20.0033649242,-0.564498398441,0.00189300611334,1.63193209733,90.0019524139 +31.46,51.0031880974,0.0036192810192,16.1707744989,-0.000583864801352,20.0035597316,-0.564936149513,0.00322508472429,1.63101197974,90.0004993883 +31.47,51.0031880974,0.0036221308719,16.1764208553,-0.000577021796922,20.0044077791,-0.564335144848,0.00330519180313,1.63279633354,89.9999656615 +31.48,51.0031880973,0.00362498065274,16.182066839,-0.00141050509155,20.0025508662,-0.564861597182,0.0025344879466,1.63244496406,89.9990806475 +31.49,51.0031880972,0.00362783021555,16.1877171585,-0.00111913714264,20.0013471455,-0.565202293842,0.00159043311597,1.63378549152,89.998341121 +31.5,51.0031880971,0.0036306796103,16.1933686661,2.0290415558e-005,20.0001913651,-0.565099219696,-3.72667182189e-005,1.63536542971,89.998621165 +31.51,51.0031880971,0.00363352905422,16.1990290923,-0.000246306492403,20.002037687,-0.566986025355,-0.0006198691649,1.63675606132,89.9978160997 +31.52,51.003188097,0.0036363786626,16.204690917,-0.00142162069424,20.0025000437,-0.565378913552,-0.000358411088287,1.63693540282,90.0008238381 +31.53,51.003188097,0.00363922823976,16.2103418232,0.000836906995345,20.0015994419,-0.56480233202,-0.000382834731935,1.63924791133,89.9992403073 +31.54,51.003188097,0.00364207764475,16.215993996,-0.000896311479203,20.000083119,-0.565632226718,-0.000645940985469,1.63872643526,90.0007497774 +31.55,51.003188097,0.00364492703103,16.2216646237,-0.000172966480857,20.0013367325,-0.568493316459,-0.00129503765218,1.64305953338,90.0018949602 +31.56,51.0031880969,0.00364777640183,16.2273490153,-0.0015284447922,19.9998658558,-0.568385000907,-0.000708484820567,1.63989362511,90.0021492337 +31.57,51.0031880967,0.00365062573735,16.2330315033,-0.00209318481879,20.0008415183,-0.568112590256,-0.00160229974993,1.64184237199,90.0011640047 +31.58,51.0031880965,0.00365347520653,16.2387099247,-0.00224479781752,20.0017422481,-0.567571703777,-0.000845334050778,1.64372788223,90.0024806632 +31.59,51.0031880963,0.00365632466793,16.2443864005,-0.00317782828548,20.0007324092,-0.567723450237,-0.000550692694201,1.64539646409,90.0029217496 +31.6,51.0031880961,0.00365917407558,16.2500760761,-0.00179841782926,20.0009876618,-0.570211667008,7.09544942428e-005,1.64410242634,90.002372662 +31.61,51.0031880958,0.00366202354828,16.2557880424,-0.00347367755183,20.0016456271,-0.572181602783,0.000827791352764,1.64455282816,90.001523785 +31.62,51.0031880955,0.0036648729855,16.2615062409,-0.00346649934471,20.0004897211,-0.571458098805,-0.000190148173717,1.64537369637,90.0002819468 +31.63,51.0031880953,0.00366772248625,16.2672117655,-0.00235547678054,20.0025374345,-0.569646818463,-5.82537145381e-005,1.64615146056,90.0013541374 +31.64,51.003188095,0.00367057198412,16.2729090248,-0.00264373183911,20.0004493406,-0.569805043558,-0.00169866620148,1.64841521914,90.0008913073 +31.65,51.0031880948,0.00367342138062,16.2785971245,-0.00244491963353,20.0011143866,-0.567814897675,-0.0027012145502,1.64779781541,89.9999365755 +31.66,51.0031880947,0.00367627086731,16.2842886588,-0.00067045683644,20.0017154815,-0.570491944467,-0.00113417935526,1.64777775186,89.9989180902 +31.67,51.0031880947,0.00367912030398,16.2899982345,0.000448449046448,20.0004122178,-0.57142320015,-0.00172042122444,1.6475962239,89.9989391724 +31.68,51.0031880947,0.00368196967134,16.2957090537,0.000186279825832,20.0007425103,-0.5707406422,-0.00042137691321,1.65171645322,89.9988088057 +31.69,51.0031880948,0.00368481903117,16.3014189699,0.00149981258975,20.0003066487,-0.571242608884,0.000840098493591,1.65406438556,89.9997327056 +31.7,51.0031880949,0.00368766835431,16.3071236215,0.000553282536326,20.0002273366,-0.569687709341,-0.000500355012506,1.65483093183,89.9998420407 +31.71,51.0031880948,0.00369051761671,16.3128190949,-0.00100354938374,19.9994540005,-0.569406964886,0.00048306969521,1.65605260896,90.0008241794 +31.72,51.0031880948,0.00369336682668,16.3185221627,-4.90410790833e-005,19.9994914051,-0.571206586843,-0.00058797129508,1.65510812301,90.0008060934 +31.73,51.0031880948,0.00369621603268,16.3242331791,0.00129409049542,19.9993982939,-0.570996695547,-0.000680886113579,1.65398008358,90.0005020454 +31.74,51.003188095,0.00369906517566,16.3299469334,0.00143041519162,19.9986065889,-0.571754175775,-0.00151753047452,1.65709750102,89.9994213949 +31.75,51.0031880951,0.00370191423171,16.3356661545,0.00166620136857,19.998178063,-0.572090034887,-0.00114836159624,1.6604029287,90.0005983099 +31.76,51.0031880953,0.0037047634003,16.341389691,0.00242618261001,20.0001865083,-0.57261727207,-0.000398624947126,1.65866823104,90.0007528868 +31.77,51.0031880954,0.00370761267801,16.3471308923,0.000257185523621,19.9997100866,-0.575622974498,-0.00100176402414,1.65934031961,90.0004054455 +31.78,51.0031880954,0.00371046210418,16.3528820684,0.000182634669168,20.0022705224,-0.57461224435,-0.00141336832376,1.66102767985,89.9992936767 +31.79,51.0031880953,0.00371331167646,16.3586261141,-0.00253518219866,20.0017614363,-0.574196910072,-0.00209891505114,1.66192390084,89.9999763858 +31.8,51.0031880952,0.00371616127462,16.3643664891,-0.000952375020335,20.0026338427,-0.573878087828,-0.00157681475886,1.66179553702,90.0015082686 +31.81,51.0031880951,0.00371901078045,16.370105872,-0.0010235563272,20.0004652872,-0.573998485105,-0.00328861238331,1.66285432923,90.0024048084 +31.82,51.003188095,0.00372186013217,16.3758338414,-0.0010046741359,20.0004703681,-0.571595397935,-0.00219662893533,1.6620632008,90.0014770983 +31.83,51.0031880949,0.0037247094035,16.381551642,-0.00174915588273,19.9993368247,-0.571964732876,6.63119768102e-005,1.66311855741,90.002258451 +31.84,51.0031880948,0.00372755871365,16.3872823129,-0.000133803596355,20.0010153095,-0.57416944368,-0.000243959898053,1.66522111861,90.0016774158 +31.85,51.0031880947,0.00373040819818,16.3930191427,-0.000956050283905,20.0017849695,-0.573196509021,-0.000601188642939,1.66678607419,90.0029651388 +31.86,51.0031880947,0.00373325762345,16.3987626737,9.20350052186e-005,20.0001833848,-0.575509700012,0.000306083003642,1.66701131785,90.003569808 +31.87,51.0031880947,0.0037361069292,16.4045226461,0.000923411576686,20.0001071249,-0.576484779976,-0.000450638687686,1.66754808536,90.0025663541 +31.88,51.0031880948,0.00373895624213,16.4102811001,-0.000406679269946,20.0002841995,-0.575206013696,0.00181527174405,1.66787136732,90.0035849193 +31.89,51.0031880947,0.00374180535859,16.4160414049,-0.000173438189668,19.9973490156,-0.576854942168,0.000899463919314,1.66818826454,90.0031462972 +31.9,51.0031880947,0.00374465442799,16.4218028406,-0.00083676751281,19.9996236085,-0.575432198661,0.00112196176262,1.6690820078,90.0041474002 +31.91,51.0031880947,0.00374750375388,16.4275527064,7.94695445537e-005,20.0009497923,-0.574540955106,0.00277735720293,1.67017572528,90.0050547753 +31.92,51.0031880946,0.00375035312862,16.4333076713,-0.000109592971503,20.0003094151,-0.576452029795,0.00155768474533,1.67106306686,90.0020917831 +31.93,51.0031880947,0.00375320248254,16.4390755117,0.00197540717384,20.0006575573,-0.577116045648,0.00342688211436,1.67244676971,90.0038402636 +31.94,51.0031880948,0.00375605190395,16.4448494322,0.000534853126436,20.0012569398,-0.577668065649,-0.000677750443045,1.67429008658,90.002240463 +31.95,51.0031880949,0.00375890120906,16.4506310245,-0.000261343092449,19.9990248297,-0.578650389157,-0.00131999726321,1.67559444366,90.0036145417 +31.96,51.0031880949,0.0037617503639,16.4564139253,0.000392563572893,19.9991474343,-0.577929779815,0.00033368601299,1.6763651968,90.0022615014 +31.97,51.0031880949,0.00376459955454,16.4621825846,8.44333757936e-005,19.9995274825,-0.575802067937,-9.17974949012e-005,1.678517539,90.0019432422 +31.98,51.003188095,0.00376744877416,16.4679533022,0.00237568881671,19.9995542827,-0.578341464402,-0.00139886706212,1.67894003575,90.0023978019 +31.99,51.0031880951,0.00377029811913,16.4737396576,-0.00048036343086,20.0012871776,-0.578929606136,0.000510997299337,1.68004451332,90.0019113089 +32,51.0031880951,0.00377314749584,16.4795243056,0,20,-0.578,0,1.681,90 +32.01,51.0031880951,0.00377599681685,16.4853032131,0.000292993174947,20.0005052695,-0.577781502255,0.00192685241317,1.68189881278,89.9985564368 +32.02,51.0031880952,0.00377884602441,16.4910881047,0.00192016842713,19.9984073195,-0.579196820627,0.000131953162661,1.6802503946,89.9998585117 +32.03,51.0031880954,0.00378169514945,16.4968766784,0.00209034145122,19.9993468631,-0.578517912716,0.00119487142961,1.68292813246,89.9978391969 +32.04,51.0031880955,0.00378454436187,16.5026630257,0.00156395003392,19.999634079,-0.578751536511,0.000537264321295,1.68141020683,89.9986925085 +32.05,51.0031880956,0.00378739359238,16.5084412058,0.00111157606721,19.9996007805,-0.576884498663,0.00279816193081,1.68285696377,89.9973437499 +32.06,51.0031880957,0.00379024281829,16.5142164184,0.000591271117461,19.9995695979,-0.578158021736,-0.000221021064596,1.68236814543,89.9979822006 +32.07,51.0031880957,0.00379309213834,16.5200024754,-0.000542118416463,20.0009223417,-0.579053366052,-0.000231998234123,1.68189208331,89.9976764023 +32.08,51.0031880956,0.00379594150668,16.5257945994,-0.00142905999653,20.0002476343,-0.579371448851,0.000196577779753,1.68158351269,89.9984037444 +32.09,51.0031880955,0.00379879085822,16.5315927853,-0.00153158537152,20.0006864763,-0.580265726864,0.00183836016895,1.68221197774,89.9980401684 +32.1,51.0031880953,0.00380164028237,16.5373897759,-0.00244517729959,20.0012671123,-0.579132386108,0.00126128221148,1.68390566324,89.9989861668 +32.11,51.0031880951,0.00380448967119,16.5431839505,-0.00342855752404,20.0001904504,-0.579702528735,0.00123151470855,1.68236233293,89.9985658202 +32.12,51.0031880948,0.00380733896016,16.5489873424,-0.00215509874447,19.9998652834,-0.580975866409,0.000528390886052,1.68499064111,90.0000707483 +32.13,51.0031880947,0.00381018825701,16.5548004746,-0.000671656728041,20.0003012632,-0.581650564947,-0.00101284919261,1.68386026301,90.0007596987 +32.14,51.0031880947,0.00381303743241,16.5606181244,0.000311422945237,19.9981603268,-0.581879394587,-0.000825250046753,1.68425032419,90.0001647054 +32.15,51.0031880947,0.00381588643473,16.5664352432,-0.00018208951133,19.9978714807,-0.581544369525,-0.00132405698351,1.68492919732,89.9970009806 +32.16,51.0031880946,0.00381873544573,16.5722437743,-0.00114551408262,19.9982820842,-0.580161849134,-0.00297363536591,1.68415095783,90.0000258965 +32.17,51.0031880945,0.00382158464484,16.5780452734,-0.000964463010154,20.0005124827,-0.58013796874,-0.00389693000209,1.68469879106,90.0018266413 +32.18,51.0031880944,0.0038244338791,16.5838479247,-0.00096208061203,19.9987756053,-0.580392286873,-0.00188616050651,1.68324201108,90.0004717327 +32.19,51.0031880944,0.00382728313117,16.5896572469,0.0013337650909,20.0007624712,-0.581472150242,-0.000697952641841,1.68429271333,90.0026939834 +32.2,51.0031880945,0.00383013242438,16.5954706552,-0.000561604368106,19.9993531801,-0.581209520071,-0.00360891843876,1.68516017994,89.9993489095 +32.21,51.0031880945,0.00383298162948,16.601281616,7.63363012684e-005,19.9995255783,-0.580982640819,-0.00408843589856,1.68622549588,89.9993697702 +32.22,51.0031880945,0.00383583071878,16.6070885368,0.00053665779624,19.9977274112,-0.580401511486,-0.00490542558706,1.68484169642,90.0000213745 +32.23,51.0031880945,0.00383867980947,16.6128952959,0.000533807924938,19.9995453324,-0.580950311633,-0.00453679730905,1.6864336408,90.0016131255 +32.24,51.0031880946,0.00384152900008,16.6187068282,6.92109091322e-005,19.9991301256,-0.581356144815,-0.0052811991323,1.68542457814,90.0001367223 +32.25,51.0031880946,0.00384437817532,16.6245171117,0.000640016590242,19.99932962,-0.580700566986,-0.00796864553441,1.68546539688,90.0003865672 +32.26,51.0031880946,0.00384722731622,16.630329912,0.000392956274026,19.9986479902,-0.581859478436,-0.00664146931923,1.68627023694,90.0003170036 +32.27,51.0031880947,0.00385007632174,16.6361461938,0.00114038070021,19.9974291921,-0.581396885874,-0.00507696891277,1.68605637133,89.9994895707 +32.28,51.0031880947,0.00385292535224,16.6419622805,-0.000748171915542,19.9989985662,-0.581820451604,-0.0051431085421,1.68503636964,89.9998131186 +32.29,51.0031880947,0.00385577460292,16.6477724595,0.000693218627456,20.0005204143,-0.58021536329,-0.00480732965326,1.68800651725,89.9990585906 +32.3,51.0031880948,0.00385862394221,16.6535751039,0.000311467165557,20.000242487,-0.580313515639,-0.00379501039163,1.68778799322,89.9983735005 +32.31,51.0031880948,0.00386147311906,16.6593841,-3.26281867626e-005,19.998240043,-0.581485689445,-0.00505197326909,1.68885723904,90.0005316438 +32.32,51.0031880948,0.00386432226318,16.665200949,-0.000411901324819,19.9997831241,-0.581884122052,-0.0053114935292,1.68931905981,89.998713522 +32.33,51.0031880947,0.0038671716129,16.6710207699,-0.000871906548118,20.0011262884,-0.582080054298,-0.00505189465529,1.69247897006,89.999323713 +32.34,51.0031880946,0.00387002088419,16.6768392921,-0.0014091873578,19.9986821581,-0.581624375653,-0.00451781532056,1.69133799162,89.997638871 +32.35,51.0031880945,0.00387287005861,16.6826565372,-0.00179050205588,19.9997664105,-0.581824658644,-0.00244877419295,1.6893796812,89.9989417051 +32.36,51.0031880943,0.00387571933004,16.6884790026,-0.000890707091328,20.0000440467,-0.582668415852,-0.00621075756051,1.69025168568,89.99747434 +32.37,51.0031880943,0.00387856862252,16.6943015988,0.000710098841029,20.0000620278,-0.581850833306,-0.00749849268236,1.68976255206,89.9973658667 +32.38,51.0031880944,0.00388141781576,16.7001146101,0.00107648380905,19.9986507711,-0.580751424551,-0.00595794972795,1.69104543109,89.9984420117 +32.39,51.0031880945,0.00388426698503,16.7059263685,0.00147017166196,19.9997256066,-0.581600254043,-0.0062813025457,1.69282365681,89.9997614078 +32.4,51.0031880946,0.00388711628939,16.7117490245,0.000662550136657,20.0005473769,-0.582930937632,-0.00577902853208,1.69192674887,89.9995283919 +32.41,51.0031880947,0.00388996557605,16.7175729381,0.00174315651484,19.9994770958,-0.581851791166,-0.00722662702896,1.69315340011,89.9977611632 +32.42,51.0031880948,0.00389281488598,16.7233944308,-0.000373311998119,20.0008740285,-0.582446739726,-0.00604643264686,1.69302719838,89.9983668128 +32.43,51.0031880948,0.00389566426461,16.7292167367,0.000185331461731,20.0004416622,-0.582014447546,-0.00730328178472,1.69290394936,90.0010239029 +32.44,51.0031880947,0.00389851363703,16.7350421344,-0.00171945429912,20.0007868835,-0.583065086918,-0.0090668860085,1.69241020259,89.9988981168 +32.45,51.0031880946,0.00390136285812,16.740873098,0.000408797633417,19.9983172376,-0.583127637981,-0.0102884301351,1.69359588991,89.9987377063 +32.46,51.0031880946,0.00390421197845,16.7467028545,-0.000702780195208,19.9993723602,-0.58282366025,-0.00961220713484,1.69521534781,90.0000566943 +32.47,51.0031880946,0.00390706134823,16.7525365923,-0.00100427547116,20.0018192696,-0.583923900929,-0.0108984858321,1.69400695383,90.0017729051 +32.48,51.0031880944,0.00390991079233,16.7583756141,-0.00140217576304,20.0004156972,-0.583880453118,-0.0109667635998,1.69456380963,90.0010006423 +32.49,51.0031880942,0.00391276023987,16.7642104671,-0.00339493945681,20.0018674854,-0.583090150453,-0.00930409298697,1.69271196773,90.0018064921 +32.5,51.0031880941,0.00391560969098,16.7700430986,-0.000346463051497,20.0004660608,-0.583436143268,-0.00905103981322,1.69485779323,90.0015506392 +32.51,51.003188094,0.00391845908622,16.775899166,-0.000568474243316,20.0010829871,-0.587777339833,-0.0101963323054,1.69564863665,90.0004553061 +32.52,51.003188094,0.00392130852781,16.7817637486,0.000858505573902,20.0011169075,-0.585139189281,-0.0114615556433,1.69487754598,90.0008823548 +32.53,51.0031880941,0.00392415798922,16.7876170134,-0.000283618347215,20.0013613212,-0.5855137626,-0.0130553718578,1.69437620626,90.0014641662 +32.54,51.003188094,0.00392700752353,16.7934756323,-0.00156599371942,20.00214023,-0.586210017303,-0.0106593076985,1.69501398493,90.0019373271 +32.55,51.0031880938,0.00392985713235,16.7993315182,-0.0022503915337,20.0024074983,-0.584967169289,-0.0115589811693,1.69524700984,90.0005565696 +32.56,51.0031880936,0.0039327068063,16.80518957,-0.00205476715596,20.0030545109,-0.586643183822,-0.012190300149,1.69648816501,90.0018717099 +32.57,51.0031880934,0.00393555651868,16.8110525655,-0.00300924417284,20.0029470296,-0.585955912672,-0.0146142659534,1.69603387237,90.0029916857 +32.58,51.0031880933,0.00393840611722,16.8169083786,0.000277979541795,20.001456469,-0.58520671543,-0.0142092548361,1.69781838182,90.0002997991 +32.59,51.0031880933,0.00394125563543,16.8227679522,0.000641838533854,20.0018192772,-0.586708006481,-0.0130598053784,1.6987439619,90.0013626347 +32.6,51.0031880934,0.00394410518086,16.8286360136,0.000398425258552,20.0018385987,-0.586904278111,-0.0128288375326,1.69806949484,90.0012174098 +32.61,51.0031880934,0.00394695475235,16.8344955669,0.000125792466941,20.0021852882,-0.585006374083,-0.0118348876661,1.69583435375,90.0007009434 +32.62,51.0031880934,0.00394980418833,16.8403563523,-0.000566376577331,19.9999362421,-0.587150708799,-0.0127731670584,1.69867144182,89.9992539737 +32.63,51.0031880933,0.00395265340294,16.8462338045,-0.00168648239556,19.9990775495,-0.588339722802,-0.0118399890281,1.70009106016,89.9991378793 +32.64,51.0031880931,0.0039555026374,16.8521177553,-0.00166459080006,20.0002148902,-0.588450436867,-0.0134044983467,1.69879041741,89.99998556 +32.65,51.0031880929,0.00395835196185,16.8580049308,-0.0017508438115,20.0003409866,-0.588984674222,-0.015774636348,1.69972090663,90.0024208814 +32.66,51.0031880927,0.00396120119222,16.8638887456,-0.00353838422879,19.9988942063,-0.587778277664,-0.0156208682608,1.69963623492,89.9984506862 +32.67,51.0031880924,0.00396405033416,16.8697741763,-0.00378376465968,19.9990994602,-0.589307861124,-0.0144352827318,1.69801973309,89.9998074728 +32.68,51.0031880921,0.00396689951728,16.8756657934,-0.00289451320533,19.999472526,-0.58901556262,-0.0149697975994,1.69908055769,89.9992742333 +32.69,51.0031880919,0.00396974869114,16.8815527737,-0.00181768178396,19.9989694497,-0.588380497619,-0.0168412032427,1.70046325455,89.998964333 +32.7,51.0031880917,0.00397259781299,16.8874423905,-0.00295522013505,19.9987422953,-0.589542867307,-0.0173023059562,1.7010729605,90.0005419506 +32.71,51.0031880914,0.00397544703681,16.8933330093,-0.00252353537401,20.0004011113,-0.588580877128,-0.0172325537206,1.69971581974,90.0008068719 +32.72,51.0031880912,0.00397829635304,16.8992226075,-0.00183834160156,20.0000395971,-0.589338771113,-0.0159623488434,1.70043932282,90.0013189919 +32.73,51.0031880911,0.00398114561674,16.905126228,-0.000966525901197,19.9996637278,-0.591385323145,-0.0157271169118,1.70237898991,90.0015709927 +32.74,51.003188091,0.00398399489225,16.9110377682,-0.00089005711697,20.0002054399,-0.590922730367,-0.016607953648,1.7018185109,90.0005320253 +32.75,51.0031880909,0.00398684426089,16.9169486573,-0.000630277810267,20.000971171,-0.59125507404,-0.0178581155253,1.70168593572,89.9999908571 +32.76,51.0031880909,0.0039896936183,16.9228605281,-0.000193077751105,20.0000478034,-0.591119091982,-0.0169962255268,1.70277982654,89.99882974 +32.77,51.0031880908,0.00399254287294,16.9287669423,-0.00256111903155,19.9995284612,-0.590163760073,-0.016268904054,1.70441331082,90.0000250835 +32.78,51.0031880906,0.00399539208793,16.9346723069,-0.000654808106113,19.9994912722,-0.590909149145,-0.0169711913927,1.70338455777,90.0005117393 +32.79,51.0031880905,0.00399824129568,16.9405747113,-0.00181739281753,19.999426778,-0.589571724822,-0.016673080308,1.70312056689,89.9990656301 +32.8,51.0031880904,0.00400109058786,16.9464800356,-0.00137660233883,20.000676642,-0.591493144306,-0.0173810737501,1.70375710499,89.9997885595 +32.81,51.0031880902,0.00400394011526,16.9523960466,-0.00299847239229,20.002728942,-0.59170906299,-0.0197352784234,1.7060846036,89.9993844154 +32.82,51.00318809,0.00400678971179,16.9583205939,-0.0017944235327,20.0016471682,-0.593200378008,-0.019094066821,1.70623662847,89.9974829644 +32.83,51.0031880898,0.0040096393426,16.9642471815,-0.00160940533486,20.0032103173,-0.592117145367,-0.0197796341604,1.70860468636,89.9990600064 +32.84,51.0031880897,0.00401248896789,16.9701667697,-0.00191597360938,20.001569581,-0.591800509645,-0.0177646491632,1.70595855307,89.9966730485 +32.85,51.0031880895,0.00401533853847,16.9760812305,-0.000838847549642,20.0024423092,-0.591091635488,-0.0167988618757,1.70488316814,89.9959706722 +32.86,51.0031880894,0.00401818815155,16.9820041901,-0.00207197194368,20.0021663678,-0.593500291653,-0.0188100067172,1.7063282318,89.9985204182 +32.87,51.0031880893,0.00402103764321,16.9879401057,-0.000278158144282,20.000737661,-0.593682836428,-0.0176013812031,1.70686053611,89.9997923487 +32.88,51.0031880893,0.00402388702247,16.993875688,-0.000640425311638,20.0005886097,-0.593433619342,-0.0194413169771,1.70622905952,89.9994944909 +32.89,51.0031880892,0.00402673620267,16.9998179396,9.98393354687e-005,19.9979430941,-0.595016698526,-0.0202748080294,1.70845620422,90.0000282926 +32.9,51.0031880892,0.00402958526688,17.0057676639,0.000178269249525,19.9989602758,-0.594928151098,-0.0214536108702,1.70775207444,90.000567879 +32.91,51.0031880892,0.00403243451233,17.0117175236,-0.000178889419766,20.000487454,-0.595043803986,-0.0214756067268,1.7069492344,89.9990671846 +32.92,51.0031880892,0.00403528395192,17.0176672782,-0.000830613436379,20.001685897,-0.594907101172,-0.0216929319743,1.70688098453,89.9993992905 +32.93,51.0031880891,0.0040381334982,17.0236240077,-0.00127349262934,20.001985152,-0.596438799841,-0.0190170475375,1.70688316098,90.0002628056 +32.94,51.0031880889,0.00404098292265,17.0295816416,-0.00219315852722,19.9999756625,-0.595087993285,-0.0188090123964,1.70718170868,90.0001712739 +32.95,51.0031880888,0.00404383208243,17.0355242358,-0.0014192966288,19.9982696083,-0.5934308343,-0.0224650608545,1.70570215529,90.0002237628 +32.96,51.0031880886,0.00404668125152,17.0414617486,-0.00175436741742,20.0001064033,-0.594071728861,-0.0227381223825,1.70731995956,90.0004899821 +32.97,51.0031880885,0.00404953057761,17.0474037235,-0.00124216467443,20.0004736321,-0.594323244312,-0.0215351345547,1.70567960093,90.0008182525 +32.98,51.0031880883,0.00405237983477,17.053356196,-0.00249336242151,19.9991387838,-0.596171274534,-0.0217172723707,1.7078560304,89.9985029469 +32.99,51.0031880882,0.00405522885581,17.0593131657,-0.00095046979065,19.9971588762,-0.595222659401,-0.0221907416421,1.70970350732,90.0005505796 +33,51.0031880881,0.00405807782056,17.0652709378,-0.00141761388566,19.9983486077,-0.596331765538,-0.0228294445265,1.70952398062,90.0023142102 +33.01,51.003188088,0.00406092689842,17.0712363598,-0.000154753265588,19.9987468502,-0.596752620297,-0.022850362926,1.71057391091,90.0029465118 +33.02,51.003188088,0.00406377605853,17.0771955465,-0.000975236650804,19.999503234,-0.595084735374,-0.0255428156052,1.70927481915,90.0015177408 +33.03,51.0031880879,0.0040666253717,17.0831466997,-0.00116022927308,20.0008957714,-0.59514588962,-0.0248763149247,1.70884145012,90.0014843195 +33.04,51.0031880877,0.00406947483327,17.089097366,-0.0019776171542,20.0015865417,-0.594987376367,-0.0239151579582,1.70856134137,90.0007718127 +33.05,51.0031880876,0.00407232432638,17.0950458642,-0.00106214779676,20.0013385699,-0.59471226635,-0.0266465891872,1.70873584368,90.001644292 +33.06,51.0031880876,0.0040751735771,17.1009975509,0.00104327962049,19.9981837016,-0.595625079832,-0.0284447728925,1.70921817275,90.0025550743 +33.07,51.0031880876,0.0040780225973,17.106968023,-0.00133438742207,19.9981024947,-0.598469333727,-0.0281467285551,1.71194181626,90.00330169 +33.08,51.0031880875,0.00408087166919,17.1129450327,0.000359046365297,19.9989093678,-0.596932600346,-0.0271299120905,1.71066478316,90.0009923817 +33.09,51.0031880876,0.00408372071114,17.1189060747,0.000808230745421,19.9976822576,-0.595275800936,-0.0268175391949,1.71115746783,89.998928426 +33.1,51.0031880877,0.00408656965495,17.124862291,0.00116301980172,19.9975315901,-0.595967463893,-0.0298717640053,1.71170360235,89.9981734112 +33.11,51.0031880877,0.00408941847262,17.1308188582,0.000685623274047,19.9959114646,-0.595345965792,-0.0285568058758,1.7131072051,89.9976359939 +33.12,51.0031880878,0.00409226733493,17.1367739757,-0.00016635818607,19.9981583791,-0.595677535702,-0.0274139047047,1.71248850909,89.9997853184 +33.13,51.0031880878,0.00409511627758,17.1427251909,0.000370479891276,19.997039312,-0.594565500454,-0.0265829134485,1.7151232907,89.9992554031 +33.14,51.0031880879,0.0040979652968,17.1486811589,0.00163433473599,19.9992334315,-0.596628105851,-0.0280357686287,1.7138829703,89.9991163799 +33.15,51.003188088,0.00410081450707,17.1546436129,0.000509385932817,19.9997213214,-0.595862707246,-0.0262702233599,1.71248348955,89.9987040409 +33.16,51.003188088,0.00410366373209,17.1606120167,-8.74840997404e-005,19.9994406075,-0.597818041104,-0.0274774768062,1.71231664219,89.9982858811 +33.17,51.003188088,0.00410651292129,17.1665936122,0.0001712151619,19.9992184933,-0.598501053664,-0.0281141139091,1.71117712297,89.9992535296 +33.18,51.0031880879,0.00410936205349,17.1725793699,-0.00223886485651,19.9986404155,-0.598650499393,-0.029524564505,1.71355510966,89.9984274716 +33.19,51.0031880878,0.00411221108878,17.1785687417,-0.000428122218284,19.9978580289,-0.599223855084,-0.0301956447441,1.71380807977,89.9978421077 +33.2,51.0031880877,0.00411506014199,17.1845597103,-0.000226052554086,19.9988921141,-0.598969862017,-0.0296714519167,1.71571742973,90.0002026456 +33.21,51.0031880878,0.00411790931277,17.1905425302,0.001195240571,19.9995085372,-0.597594111214,-0.0297264201136,1.71849930998,90.0004083717 +33.22,51.0031880879,0.00412075863602,17.1965089102,0.000752475195615,20.0010325883,-0.595681890123,-0.0309424059279,1.7173695495,90.0006306708 +33.23,51.0031880879,0.00412360798379,17.2024712322,-0.000248772179211,19.9998528719,-0.596782513899,-0.0313022270838,1.71726260252,90.0005251033 +33.24,51.0031880879,0.00412645722929,17.2084363322,-0.000448179144142,19.999596784,-0.596237490626,-0.0304271125144,1.71642117284,89.999797471 +33.25,51.0031880879,0.00412930650942,17.2144059918,0.00109802536396,20.0003391933,-0.597694430074,-0.0322176284367,1.71730257171,89.9979955789 +33.26,51.003188088,0.00413215581307,17.2203747165,0.000455235974113,19.9999269527,-0.596050510039,-0.0320474517026,1.71856114254,89.9998896666 +33.27,51.003188088,0.00413500494245,17.2263411601,-0.000817460933397,19.9978927141,-0.59723821404,-0.0314036422844,1.71751323956,89.9981802278 +33.28,51.0031880879,0.00413785407703,17.2323273512,0,20,-0.6,-0.03,1.718,90 +33.29,51.003188089,0.00414070306446,17.2383288518,0.0239339150942,19.9958268622,-0.600300123939,-0.0325223867643,1.71813857157,89.9300241935 +33.3,51.0031880923,0.00414355154418,17.2443325925,0.050494733121,19.992872623,-0.60044801194,-0.0325613912935,1.71777743068,89.8584388664 +33.31,51.003188098,0.00414639943648,17.2503225456,0.0747733186976,19.98758036,-0.597542611571,-0.0342339157487,1.71510231822,89.7876982046 +33.32,51.0031881057,0.00414924693293,17.2562996559,0.0982352828937,19.9873154138,-0.597879436437,-0.0330899644682,1.715361917,89.7161400633 +33.33,51.0031881157,0.00415209419426,17.2622701666,0.123950822536,19.9842796483,-0.596222719106,-0.0316327341132,1.71431005458,89.6453401584 +33.34,51.003188128,0.00415494108909,17.2682352717,0.148838822007,19.9821701964,-0.596798297464,-0.034641378362,1.71328596733,89.5740460416 +33.35,51.0031881425,0.00415778761869,17.2742033569,0.173034053036,19.979152506,-0.596818742237,-0.0345726340584,1.71137341871,89.5036154442 +33.36,51.0031881591,0.00416063378095,17.2801667468,0.197756527032,19.9770132111,-0.595859228885,-0.0350056880462,1.70906896779,89.4303023939 +33.37,51.0031881779,0.00416347963458,17.2861220093,0.220859052694,19.9748196807,-0.595193282012,-0.0335250160651,1.70833613949,89.3597186306 +33.38,51.003188199,0.00416632521482,17.2920706301,0.247782390152,19.9731752865,-0.594530869005,-0.0359261980823,1.70858338209,89.287377491 +33.39,51.0031882224,0.0041691704199,17.2980143704,0.272562989991,19.9695530863,-0.594217193469,-0.0378936208007,1.70896379329,89.216850719 +33.4,51.003188248,0.00417201514596,17.303958497,0.296873120674,19.9664504319,-0.59460813483,-0.0396208379349,1.70684488693,89.1439130561 +33.41,51.0031882757,0.00417485942618,17.3099056118,0.320024530424,19.9632941436,-0.59481481943,-0.0400919001072,1.70771344648,89.0744140693 +33.42,51.0031883056,0.00417770342256,17.3158600645,0.345743304444,19.9624657071,-0.596075713054,-0.0383896066658,1.70553990041,89.0020387988 +33.43,51.0031883378,0.00418054729315,17.321812511,0.369745120067,19.9615281733,-0.594413590326,-0.039160230268,1.70436981577,88.9309682318 +33.44,51.0031883721,0.00418339090706,17.327753021,0.393289243994,19.958862376,-0.593688413031,-0.0400203699781,1.70225592444,88.8616099036 +33.45,51.0031884085,0.00418623409284,17.3336918452,0.417529683852,19.9555178934,-0.594076429009,-0.0424987493525,1.69808668331,88.7914447865 +33.46,51.0031884471,0.00418907691779,17.339625692,0.440826700635,19.9537967219,-0.592692928419,-0.0419149144097,1.69770501349,88.719859 +33.47,51.0031884879,0.00419191928798,17.345553326,0.466139087812,19.9491336951,-0.592833870685,-0.0420490454836,1.69888874921,88.6488878667 +33.48,51.0031885309,0.00419476124279,17.3514766508,0.490551010004,19.9479654465,-0.591831090724,-0.0428741512469,1.69676984717,88.5769786046 +33.49,51.003188576,0.00419760283927,17.3573808231,0.514757065814,19.9441032194,-0.589003360013,-0.0438303055765,1.69455535619,88.5071608168 +33.5,51.0031886234,0.00420044403398,17.3632787717,0.538300540852,19.9423251116,-0.590586360304,-0.0456495653275,1.69517055033,88.4334185967 +33.51,51.0031886729,0.00420328497805,17.3691888277,0.562853305525,19.940584564,-0.591424850583,-0.0457850789973,1.69339574296,88.3641891286 +33.52,51.0031887247,0.00420612558846,17.3750927477,0.58970072146,19.9376409257,-0.589359156959,-0.0437848593585,1.69393978676,88.2941561538 +33.53,51.0031887788,0.00420896593092,17.3809833341,0.614055001592,19.9368230532,-0.588758106988,-0.0428987753333,1.69204268147,88.2251110418 +33.54,51.003188835,0.00421180609062,17.3868727926,0.637706033759,19.9350751741,-0.589133593809,-0.0442556844326,1.69105605796,88.1526472155 +33.55,51.0031888934,0.00421464590462,17.3927639961,0.661471567694,19.9319698022,-0.589107111457,-0.0438832888771,1.68850041476,88.0816377709 +33.56,51.0031889541,0.00421748527082,17.398656172,0.688163082725,19.9287888047,-0.589328071296,-0.0456569366444,1.68891222602,88.0079054165 +33.57,51.0031890172,0.00422032423202,17.4045429943,0.71584257404,19.9262840234,-0.588036385435,-0.0461386924491,1.69013433449,87.9380363311 +33.58,51.0031890826,0.00422316270907,17.4104224649,0.739405613289,19.9219920703,-0.587857732648,-0.0468203036162,1.68833451591,87.8677743055 +33.59,51.0031891501,0.00422600056602,17.4163032486,0.763529419807,19.9175786601,-0.588299006783,-0.046172392211,1.68574591469,87.7969198941 +33.6,51.0031892198,0.00422883783353,17.4221765313,0.787733652899,19.9137170439,-0.586357539939,-0.0502444677039,1.68655699356,87.7249113472 +33.61,51.0031892917,0.00423167454126,17.4280366089,0.811264295682,19.9097201173,-0.585657982924,-0.0508485865784,1.68699492066,87.6549141766 +33.62,51.0031893657,0.00423451085205,17.4338995445,0.83539981868,19.9081446489,-0.586929140428,-0.0495138080829,1.68633110134,87.5820881207 +33.63,51.003189442,0.00423734681083,17.4397594844,0.861038129167,19.9047782543,-0.585058823195,-0.0496145774913,1.68486852622,87.5089884835 +33.64,51.0031895205,0.00424018235472,17.4456078997,0.885482962912,19.9023202257,-0.584624251963,-0.0507134593715,1.68339617483,87.4392581159 +33.65,51.0031896012,0.00424301752451,17.4514495839,0.910047432871,19.8995263693,-0.583712587246,-0.051865125874,1.68257248049,87.3671223107 +33.66,51.0031896841,0.00424585239663,17.4572880228,0.935091645589,19.8981411682,-0.583975189373,-0.0529223830957,1.68052257312,87.2969118985 +33.67,51.0031897693,0.00424868705356,17.4631168345,0.959756572378,19.8965054652,-0.581787153702,-0.0521688497952,1.67833136379,87.2252793259 +33.68,51.0031898566,0.00425152128088,17.4689390194,0.984330521306,19.8921100269,-0.582649822498,-0.0541501387585,1.67898714007,87.1544616987 +33.69,51.0031899462,0.0042543550269,17.4747579655,1.00968997618,19.889748616,-0.581139388658,-0.0542426870036,1.67635776698,87.0828902034 +33.7,51.0031900382,0.00425718836779,17.4805773766,1.03548187114,19.8864225192,-0.582742827811,-0.0553462879004,1.67630863421,87.0125304655 +33.71,51.0031901323,0.00426002123028,17.4864048975,1.05888057229,19.8830325382,-0.582761356316,-0.0552788733919,1.6759198123,86.9405947715 +33.72,51.0031902285,0.00426285372439,17.4922187885,1.08240949404,19.8812509928,-0.580016849979,-0.0573817654,1.67366510005,86.8712644599 +33.73,51.0031903269,0.00426568584341,17.4980180245,1.10531446305,19.8777666371,-0.57983035741,-0.0585070451228,1.67299950401,86.8011624746 +33.74,51.0031904274,0.00426851757122,17.5038114123,1.1310889366,19.8757589278,-0.578847190573,-0.0595266339798,1.67316829913,86.7303183105 +33.75,51.0031905302,0.00427134881243,17.5095997418,1.15654298183,19.8709354116,-0.578818716425,-0.0589544467199,1.67134903742,86.660069912 +33.76,51.0031906352,0.00427417951703,17.5153881227,1.18060146889,19.8682255263,-0.57885746156,-0.0590697570718,1.66993516114,86.5851970486 +33.77,51.0031907425,0.00427700986835,17.5211715292,1.20613191712,19.8659759313,-0.577823833768,-0.0593685817044,1.67024095175,86.5138087317 +33.78,51.003190852,0.00427983989161,17.5269535559,1.23120953758,19.8636197987,-0.578581510129,-0.0592819998482,1.66974594815,86.4436398435 +33.79,51.0031909639,0.00428266956688,17.5327394568,1.25711091376,19.8610907143,-0.578598663992,-0.0581557255548,1.66804506136,86.3705421317 +33.8,51.0031910779,0.00428549881301,17.5385198415,1.27884785958,19.8575951641,-0.577478285846,-0.0579536774864,1.66607760403,86.3010810941 +33.81,51.003191194,0.00428832765966,17.5442904296,1.30568541631,19.8554825901,-0.576639320349,-0.0583105230884,1.66513862207,86.2313730487 +33.82,51.0031913124,0.00429115620501,17.5500526243,1.32848711069,19.8533651837,-0.575799618878,-0.0592294765886,1.66312666736,86.1608570176 +33.83,51.0031914329,0.00429398433643,17.5558056921,1.35308108365,19.8496715061,-0.574813944746,-0.0593248243026,1.66285604278,86.0888036571 +33.84,51.0031915557,0.00429681202298,17.5615536918,1.37825217513,19.8471198309,-0.574785994688,-0.0613834438806,1.66220863082,86.0168795172 +33.85,51.0031916807,0.00429963916708,17.5673034489,1.40261144483,19.8420560837,-0.575165434833,-0.0610519242238,1.66000043612,85.9462229377 +33.86,51.0031918079,0.00430246589676,17.573051855,1.42801506029,19.8413019107,-0.574515779141,-0.0627337221982,1.66018247698,85.8751703995 +33.87,51.0031919373,0.00430529231772,17.5787942381,1.45059160593,19.8377220193,-0.573960848852,-0.0633123998276,1.6566876127,85.8039931725 +33.88,51.0031920688,0.00430811842587,17.5845312236,1.47610371975,19.8369105567,-0.573436240714,-0.0647937748726,1.65676221738,85.7334749379 +33.89,51.0031922026,0.00431094441843,17.5902673013,1.5001132572,19.8360989973,-0.573779305115,-0.0648270633565,1.65605737879,85.6620173956 +33.9,51.0031923386,0.00431377007641,17.5959998922,1.5257949977,19.832213542,-0.572738874661,-0.0681127629442,1.65519123886,85.5907824883 +33.91,51.0031924768,0.0043165953657,17.6017291609,1.54976221807,19.8309230044,-0.573114869658,-0.0657786215073,1.65580208544,85.5203362068 +33.92,51.0031926173,0.00431942025721,17.6074517851,1.57577361239,19.8266292121,-0.571409975034,-0.0660022383751,1.65495884578,85.4499311439 +33.93,51.0031927601,0.00432224469813,17.6131639251,1.60085454377,19.8245972082,-0.571018010317,-0.0651390483298,1.65271957435,85.3795799759 +33.94,51.0031929051,0.00432506883445,17.6188714889,1.62716107899,19.8223530021,-0.570494746568,-0.0662113863867,1.65206259933,85.3068087553 +33.95,51.0031930526,0.00432789258549,17.6245676955,1.65419942096,19.8191883491,-0.568746579119,-0.0667070678671,1.65160460018,85.2345138884 +33.96,51.0031932023,0.0043307159282,17.6302569932,1.6764918919,19.816620587,-0.569112965284,-0.0677791937701,1.65055516662,85.1633409316 +33.97,51.0031933541,0.00433353875558,17.6359400043,1.70122888072,19.8119535579,-0.567489254887,-0.0670652689141,1.64974538384,85.0929106106 +33.98,51.0031935081,0.00433636107651,17.6416179127,1.72524584504,19.8095107917,-0.568092431389,-0.0706749551669,1.65051389167,85.0226245335 +33.99,51.0031936643,0.00433918311532,17.6473015513,1.74909604701,19.8079927984,-0.568635274464,-0.0719424410392,1.6462192039,84.9533510662 +34,51.0031938226,0.0043420047659,17.652978774,1.77451231905,19.8040604701,-0.566809267871,-0.0705668741809,1.64654298048,84.8789393087 +34.01,51.0031939832,0.00434482592712,17.658640734,1.79836729204,19.8011227813,-0.56558274042,-0.0725201677831,1.64523944366,84.809017922 +34.02,51.0031941459,0.00434764669823,17.6642886371,1.82217279594,19.7985838636,-0.563997867479,-0.0738189716363,1.64477029755,84.7366322127 +34.03,51.0031943108,0.00435046705716,17.6699295523,1.84606983157,19.7953361623,-0.564185184625,-0.0747703732669,1.64164517138,84.6670394085 +34.04,51.0031944779,0.00435328703216,17.675565291,1.87080233129,19.7931939232,-0.562962553672,-0.0748284497478,1.64215896204,84.5949220922 +34.05,51.0031946471,0.00435610665683,17.6811962207,1.89520280236,19.7904179024,-0.563223384464,-0.0762171283059,1.643028356,84.5249102462 +34.06,51.0031948186,0.00435892591381,17.6868240439,1.92021471526,19.7880319622,-0.562341262582,-0.0757488316076,1.64360328367,84.4555165493 +34.07,51.0031949923,0.00436174470533,17.6924421401,1.94351941886,19.7838833684,-0.561277979283,-0.075570496876,1.64147590711,84.3819097436 +34.08,51.0031951681,0.00436456299864,17.6980558026,1.96996929535,19.7810375659,-0.561454515509,-0.0761127296693,1.63842974969,84.3099792167 +34.09,51.0031953463,0.00436738077601,17.7036621984,1.994056957,19.7766403745,-0.55982464641,-0.0754526426529,1.63737002989,84.2396119718 +34.1,51.0031955266,0.00437019806234,17.709259574,2.01759923692,19.7741438408,-0.559650460192,-0.076502892383,1.63767315211,84.1694296997 +34.11,51.0031957091,0.00437301503932,17.7148468524,2.04345940652,19.7722974332,-0.557805222487,-0.0748706093983,1.63640207853,84.0993829953 +34.12,51.0031958939,0.00437583177613,17.7204351467,2.06721944211,19.770771948,-0.559853632581,-0.0762058535105,1.63569515272,84.0280312212 +34.13,51.0031960809,0.00437864823139,17.7260366023,2.09427813056,19.7683449254,-0.560437499833,-0.07504446605,1.63544614396,83.9577300417 +34.14,51.0031962702,0.0043814642507,17.7316303991,2.1175571913,19.7646515844,-0.558321853378,-0.0773874566189,1.63164883101,83.8856921602 +34.15,51.0031964616,0.00438427986019,17.7372207648,2.14064148846,19.7625914365,-0.559751281123,-0.0772614115702,1.63040010386,83.8163636092 +34.16,51.0031966551,0.00438709511445,17.7428169026,2.16589891702,19.7596646204,-0.55947629645,-0.0772573898109,1.63035710081,83.7430441133 +34.17,51.003196851,0.0043899100046,17.7483975018,2.19064292577,19.7574796138,-0.55664353634,-0.0793163890303,1.63022310757,83.6713582994 +34.18,51.003197049,0.00439272469679,17.7539694591,2.21504595583,19.7568855458,-0.557747927859,-0.0781554268687,1.62748855327,83.6017353615 +34.19,51.0031972492,0.00439553920548,17.7595501657,2.23925555985,19.7549032853,-0.558393393909,-0.0769220623837,1.62682124286,83.5296498344 +34.2,51.0031974516,0.00439835326639,17.7651304015,2.26414601857,19.7505992032,-0.557653753926,-0.0788893293033,1.62721397224,83.4598548128 +34.21,51.0031976562,0.00440116687952,17.7707019843,2.28919427328,19.7486170505,-0.556662812244,-0.0807438413051,1.62437534736,83.3874371898 +34.22,51.003197863,0.0044039801107,17.7762682681,2.31292616426,19.7452369094,-0.556593952113,-0.0794339256294,1.62343946305,83.3169264044 +34.23,51.003198072,0.00440679294247,17.7818247707,2.3367451112,19.7430097946,-0.55470655652,-0.0798457812909,1.62170934808,83.2436720577 +34.24,51.0031982832,0.00440960531376,17.7873764319,2.36218988722,19.7387721542,-0.555625683459,-0.0814515456093,1.62127461336,83.1754743677 +34.25,51.0031984966,0.00441241726641,17.7929256259,2.38576319132,19.7371325913,-0.554213120881,-0.0830458169112,1.62052975868,83.1032025405 +34.26,51.0031987122,0.00441522885688,17.798472453,2.41158225292,19.7336875886,-0.555152292413,-0.0809057670893,1.62195134348,83.0319818425 +34.27,51.0031989301,0.004418039954,17.8040280863,2.43682074037,19.7302064842,-0.555974366774,-0.0810206367491,1.62189752787,82.9599781752 +34.28,51.0031991502,0.00442085063682,17.8095779066,2.46036502552,19.7278711286,-0.553989692169,-0.0831791527556,1.61894518918,82.8882144499 +34.29,51.0031993725,0.00442366087852,17.8151161935,2.48562930583,19.724013683,-0.55366770628,-0.0827189414384,1.61674171854,82.8184594419 +34.3,51.003199597,0.00442647069291,17.8206504254,2.50992826799,19.7218721174,-0.55317865888,-0.0819613387547,1.6160670182,82.7456349664 +34.31,51.0031998238,0.00442928015626,17.8261775807,2.53628875123,19.7190854562,-0.552252403823,-0.082596391828,1.61684587441,82.6755885967 +34.32,51.0032000529,0.00443208921704,17.8316944743,2.5600929032,19.7162204157,-0.551126323182,-0.0833088760858,1.61574835355,82.6052532216 +34.33,51.0032002841,0.00443489778832,17.8372098378,2.58459565799,19.7122132872,-0.551946368051,-0.0827914042633,1.61591379813,82.5355274476 +34.34,51.0032005176,0.00443770597578,17.8427307329,2.60922120719,19.7108321221,-0.552232653038,-0.0855241762884,1.6139248534,82.4640457862 +34.35,51.0032007531,0.00444051388184,17.8482464283,2.63212942192,19.708262555,-0.550906422631,-0.0877015988751,1.61322664351,82.3945287259 +34.36,51.0032009909,0.00444332142836,17.8537494706,2.65826441596,19.7057845116,-0.549702046994,-0.0881165789933,1.6108689647,82.3229162985 +34.37,51.0032012309,0.00444612864388,17.8592482113,2.68246486201,19.7036156993,-0.550046094962,-0.0868416417069,1.60797776211,82.2522719473 +34.38,51.0032014731,0.00444893536004,17.8647527124,2.70620687251,19.6987739401,-0.550854123392,-0.0884232849145,1.60692858297,82.1799438341 +34.39,51.0032017175,0.00445174164622,17.8702541095,2.73107830514,19.6975792922,-0.549425299912,-0.0870950589884,1.60646439805,82.1097107334 +34.4,51.0032019641,0.00445454754925,17.8757398291,2.75647440947,19.6933947568,-0.547718624337,-0.0889880303759,1.60624009918,82.0379074909 +34.41,51.003202213,0.00445735308465,17.8812209364,2.77983189966,19.6924182213,-0.548502817976,-0.0894078808656,1.60717856121,81.9694410832 +34.42,51.003202464,0.00446015820471,17.8866976057,2.80523867968,19.6875636664,-0.54683105331,-0.091610857386,1.6054154803,81.8965041838 +34.43,51.0032027172,0.004462962783,17.8921651762,2.82978154627,19.684812332,-0.546683041132,-0.0920463621871,1.60059650394,81.8256660939 +34.44,51.0032029727,0.0044657669933,17.8976315329,2.85487362251,19.6823975553,-0.546588296874,-0.0932188660475,1.60186543539,81.755863577 +34.45,51.0032032304,0.00446857075303,17.9030967595,2.8791940999,19.6784866314,-0.546457027889,-0.0949792108327,1.60075908918,81.683744256 +34.46,51.0032034904,0.00447137412055,17.9085610978,2.90482325386,19.6768914697,-0.546410625336,-0.0957621787823,1.59931056077,81.6130139684 +34.47,51.0032037526,0.00447417708175,17.9140191071,2.92819583382,19.6727820505,-0.545191248271,-0.0976276969007,1.59807699072,81.5394854566 +34.48,51.0032040168,0.00447697960423,17.9194620131,2.95194267167,19.6707323913,-0.543389954437,-0.0954441645308,1.59757609059,81.4689618983 +34.49,51.0032042833,0.00447978181106,17.9248961735,2.97606734805,19.6683506452,-0.543442109369,-0.0956468543686,1.5967243119,81.3967409033 +34.5,51.003204552,0.00448258372805,17.9303256851,3.00225201049,19.66666315,-0.542460214942,-0.0962859987247,1.59773967661,81.3258517117 +34.51,51.003204823,0.0044853852767,17.9357511233,3.02716812468,19.6631794425,-0.542627420537,-0.0958184151153,1.5987148095,81.2551495295 +34.52,51.0032050961,0.00448818640183,17.9411729142,3.05001451075,19.6607173615,-0.541730773149,-0.0988434936955,1.59755367883,81.1838101745 +34.53,51.0032053714,0.0044909871734,17.9465869623,3.07441526974,19.6582157399,-0.541078841052,-0.0968659132404,1.59574206536,81.1119265621 +34.54,51.0032056489,0.0044937875422,17.9519948798,3.10048175465,19.6550628883,-0.540504659593,-0.097329941156,1.59505089754,81.0419408498 +34.55,51.0032059287,0.00449658759765,17.9573963586,3.12548998674,19.6538163984,-0.539791105184,-0.0951437442333,1.59452674481,80.971661067 +34.56,51.0032062108,0.00449938729246,17.9627953142,3.15,19.65,-0.54,-0.098,1.593,80.9 +34.57,51.0032064949,0.00450218637157,17.9681964901,3.17167707307,19.6451725217,-0.540235180357,-0.096687510092,1.59221162316,80.8313958639 +34.58,51.0032067811,0.00450498494302,17.9735881316,3.19618390658,19.6428729475,-0.538093119886,-0.0985558618902,1.59147019548,80.7603208178 +34.59,51.0032070695,0.00450778317264,17.978974819,3.2205114227,19.6403734173,-0.539244367608,-0.0980398255774,1.58992011535,80.6909322345 +34.6,51.00320736,0.00451058085525,17.98436201,3.24313856081,19.6351935995,-0.538193824723,-0.0983249569069,1.58808401646,80.6205588125 +34.61,51.0032076525,0.00451337783877,17.9897384828,3.26539395385,19.6305589536,-0.537100742083,-0.0991009739322,1.58566773575,80.5513273188 +34.62,51.003207947,0.00451617424119,17.995117825,3.287344268,19.6270354131,-0.538767692281,-0.0981558777231,1.58505544057,80.4818999488 +34.63,51.0032082436,0.00451897015943,18.0004962696,3.31223171434,19.6237617335,-0.5369212378,-0.102445979107,1.58465901327,80.4121803353 +34.64,51.0032085424,0.00452176550661,18.0058646289,3.33499910166,19.6190181999,-0.536750623118,-0.0996726519112,1.58506936459,80.34253488 +34.65,51.0032088431,0.00452456022504,18.0112354888,3.35716105608,19.6149346861,-0.53742136259,-0.0986933783684,1.58388203217,80.2735483616 +34.66,51.003209146,0.00452735435459,18.0166092458,3.38095837812,19.6107509064,-0.537330027282,-0.0991600097554,1.58259775501,80.2047866319 +34.67,51.003209451,0.004530147962,18.0219719732,3.40566956266,19.6076045325,-0.535215460968,-0.0987886564181,1.58137762849,80.1348981481 +34.68,51.0032097582,0.00453294105856,18.0273215488,3.42993210871,19.6035788537,-0.534699655419,-0.0986428013083,1.57966614393,80.0653729232 +34.69,51.0032100676,0.0045357336733,18.032657548,3.45412630929,19.6008403014,-0.532500183212,-0.0972562267137,1.57849771428,79.9964620784 +34.7,51.0032103791,0.00453852580836,18.0379892069,3.47678987044,19.5968446271,-0.5338315857,-0.0975110881282,1.57771806239,79.9264385041 +34.71,51.0032106927,0.00454131731836,18.0433232611,3.50005701985,19.592065001,-0.532979254689,-0.101595659611,1.57833026483,79.856244763 +34.72,51.0032110084,0.00454410825462,18.0486568198,3.52402644587,19.5887900301,-0.533732485525,-0.101022838019,1.57681776293,79.7847690904 +34.73,51.0032113262,0.00454689866857,18.0539948476,3.54722382902,19.5847321623,-0.533873074962,-0.10004164949,1.57805459487,79.7152481835 +34.74,51.0032116462,0.00454968865079,18.0593290194,3.57168890257,19.5827289788,-0.532961297227,-0.100303660811,1.57599359726,79.647880953 +34.75,51.0032119682,0.00455247822087,18.0646554484,3.59342634904,19.5789460099,-0.532324490722,-0.0997049838718,1.57268946837,79.5789463238 +34.76,51.0032122923,0.00455526727131,18.0699775088,3.61763536162,19.5754336499,-0.532087590632,-0.0998157137387,1.57152379628,79.5072304381 +34.77,51.0032126185,0.00455805586101,18.0752867461,3.64125611599,19.5724776964,-0.529759874419,-0.0975095207506,1.56717734472,79.4386186149 +34.78,51.003212947,0.00456084380955,18.080592788,3.66578935684,19.5664324082,-0.531448504878,-0.0992311828117,1.56825329868,79.3678124745 +34.79,51.0032132775,0.00456363099782,18.085909769,3.68880282423,19.5618042905,-0.531947704094,-0.100217607897,1.56668256991,79.2991760106 +34.8,51.0032136101,0.00456641756325,18.0912247738,3.71155307749,19.5576883006,-0.531053254324,-0.101314640934,1.56613403442,79.229575538 +34.81,51.0032139447,0.00456920358682,18.0965371056,3.7339956905,19.5541972056,-0.531413097571,-0.104026927928,1.56337813376,79.1600399813 +34.82,51.0032142814,0.00457198902467,18.1018442205,3.75686882813,19.5494653365,-0.530009893261,-0.104663600622,1.56240646174,79.0887294698 +34.83,51.0032146202,0.00457477384017,18.1071354528,3.7812879455,19.545460015,-0.52823655392,-0.103223049922,1.56067121735,79.0192331361 +34.84,51.0032149612,0.00457755804594,18.1124312963,3.80498041135,19.5409053069,-0.530932145881,-0.10331133473,1.55740857701,78.9514255236 +34.85,51.0032153043,0.00458034162754,18.117732355,3.828983178,19.5366973643,-0.529279604607,-0.105228192145,1.55727804032,78.8838437173 +34.86,51.0032156495,0.00458312461098,18.1230319996,3.85246411546,19.5325075145,-0.530649300114,-0.102994255286,1.55646308142,78.814348645 +34.87,51.0032159969,0.00458590713186,18.1283363283,3.87639943474,19.5302036606,-0.530216439063,-0.104841165861,1.55697692121,78.7443077281 +34.88,51.0032163464,0.00458868913209,18.1336345447,3.89989444982,19.525197817,-0.529426843691,-0.10238769981,1.55528552865,78.6753851612 +34.89,51.0032166979,0.00459147048549,18.1389386809,3.92203776369,19.5211229536,-0.531400408603,-0.102762108486,1.5539763271,78.6077112406 +34.9,51.0032170516,0.00459425127617,18.1442470937,3.94696682568,19.5172978146,-0.530282145521,-0.104902154105,1.55409623598,78.5358839782 +34.91,51.0032174074,0.00459703152051,18.1495478373,3.96904105862,19.513452666,-0.529866578926,-0.101718523428,1.55038589707,78.4687709868 +34.92,51.0032177652,0.00459981137909,18.1548481789,3.99313907141,19.5118821222,-0.530201734714,-0.102649832289,1.55147543587,78.3999883779 +34.93,51.0032181253,0.00460259094012,18.1601486973,4.01846937989,19.5092751427,-0.529901948407,-0.101498924423,1.54905652756,78.3284742231 +34.94,51.0032184875,0.0046053700001,18.1654401216,4.04126763061,19.5048478985,-0.528382916642,-0.100025978574,1.54704016043,78.2607066431 +34.95,51.0032188518,0.00460814834312,18.1707244716,4.06376575995,19.4992097604,-0.528487068568,-0.0985269919035,1.54702466022,78.1907951028 +34.96,51.0032192182,0.00461092603863,18.1760026542,4.08839764658,19.4957573512,-0.527149461527,-0.100687382609,1.5463925726,78.1212496533 +34.97,51.0032195868,0.00461370316839,18.1812813051,4.11178120183,19.4912672078,-0.528580710051,-0.0986124948163,1.54462257229,78.052258457 +34.98,51.0032199574,0.00461647963277,18.1865643953,4.13462888933,19.486416058,-0.528037339891,-0.100847464353,1.54311230922,77.9848995016 +34.99,51.0032203301,0.0046192554978,18.1918387986,4.15843638932,19.4828529685,-0.52684330961,-0.101343374817,1.54342549284,77.9169559656 +35,51.003220705,0.00462203075793,18.1971018615,4.18179467335,19.4779237194,-0.525769268895,-0.101129077067,1.5417151188,77.8435612554 +35.01,51.0032210819,0.00462480536342,18.2023644851,4.20574634371,19.4736626363,-0.526755457486,-0.104506049911,1.54183648676,77.7729357431 +35.02,51.003221461,0.00462757943327,18.2076255629,4.22867599853,19.4704036553,-0.525460100133,-0.105154369918,1.53969160091,77.7051813769 +35.03,51.0032218421,0.00463035307528,18.2128774863,4.2507984175,19.4676560387,-0.524924587249,-0.105189410616,1.5390119202,77.6366583796 +35.04,51.0032222254,0.0046331261847,18.2181301409,4.27606917331,19.4629266541,-0.525606323277,-0.102651224142,1.53797591907,77.5659946844 +35.05,51.0032226108,0.00463589863239,18.2233878229,4.29918518659,19.4583659199,-0.525930092711,-0.103009268652,1.53599967582,77.4965529019 +35.06,51.0032229983,0.00463867050512,18.2286367454,4.32411774838,19.4548546528,-0.523854400346,-0.102281321626,1.53436793456,77.4256602083 +35.07,51.0032233881,0.00464144182832,18.2338680199,4.3479956965,19.4506511618,-0.522400507469,-0.100930226267,1.53580015074,77.3562812168 +35.08,51.0032237799,0.00464421259682,18.2390983796,4.36972254743,19.4470670493,-0.52367141937,-0.103350778806,1.53400504719,77.2866884133 +35.09,51.0032241737,0.00464698276179,18.244346355,4.39209411674,19.4421781501,-0.525923672152,-0.102191188032,1.53088072546,77.2175812802 +35.1,51.0032245696,0.00464975240019,18.2495925623,4.41522088567,19.4396743613,-0.523317786322,-0.104449361666,1.52948069604,77.1474055076 +35.11,51.0032249675,0.00465252170437,18.2548271459,4.43829707249,19.4374860631,-0.523598926508,-0.106321541111,1.52894716136,77.0757501328 +35.12,51.0032253675,0.00465529044924,18.2600616918,4.46241247614,19.431822017,-0.523310256486,-0.106883305037,1.52838194903,77.0089782111 +35.13,51.0032257697,0.00465805864177,18.2652949098,4.48668467023,19.4297316794,-0.52333333278,-0.106997041541,1.52893232957,76.9396545892 +35.14,51.0032261741,0.0046608262853,18.2705245424,4.51037626155,19.4241145716,-0.52259319022,-0.105190831138,1.52537422744,76.8688895312 +35.15,51.0032265806,0.00466359323672,18.2757536108,4.53472044757,19.4200150282,-0.523220489841,-0.104048854838,1.52697395568,76.7984450825 +35.16,51.0032269893,0.00466635960609,18.2809792692,4.55874819358,19.4159431277,-0.521911205148,-0.105009919365,1.52447220482,76.7285423015 +35.17,51.0032274001,0.00466912547373,18.2862015461,4.58222835156,19.41297106,-0.522544169249,-0.102677243076,1.52512706771,76.6584635187 +35.18,51.0032278131,0.00467189077259,18.2914213397,4.60516275517,19.4079581082,-0.521414551618,-0.102793087714,1.52197813178,76.5884892073 +35.19,51.003228228,0.00467465537486,18.2966343921,4.62770383846,19.4031914913,-0.521195922399,-0.104698677073,1.52030774542,76.5197991086 +35.2,51.003228645,0.00467741942461,18.3018457882,4.65043887857,19.4002012222,-0.521083298377,-0.104123607549,1.51866131033,76.4495726458 +35.21,51.0032290641,0.00468018306556,18.307055449,4.67356072568,19.397452141,-0.520848857462,-0.104252028296,1.51711677626,76.3775953108 +35.22,51.0032294852,0.00468294623158,18.3122631926,4.69657103963,19.3935336012,-0.520699862758,-0.103016213342,1.51626219813,76.3081135863 +35.23,51.0032299084,0.00468570889568,18.317465934,4.7193183051,19.3904055731,-0.519848417661,-0.103430332175,1.51476494704,76.2385991717 +35.24,51.0032303337,0.00468847101884,18.3226569734,4.74324033044,19.3859392001,-0.518359473482,-0.10292625151,1.51656505935,76.1695814239 +35.25,51.0032307612,0.00469123245557,18.3278383804,4.76738060782,19.3807687051,-0.517921919541,-0.104556978758,1.5148790407,76.1002938668 +35.26,51.0032311907,0.00469399318556,18.3330124409,4.79059522194,19.3760173031,-0.516890178557,-0.102454951266,1.5122828413,76.0310068157 +35.27,51.0032316224,0.00469675328929,18.3381775758,4.8129184352,19.3719765941,-0.516136800423,-0.103408359847,1.51136036414,75.9617406363 +35.28,51.003232056,0.00469951292997,18.3433432073,4.83636287817,19.369516335,-0.516989493104,-0.104032831048,1.5104624358,75.8918999565 +35.29,51.0032324918,0.00470227232494,18.3485181337,4.8595623437,19.3685267719,-0.517995789698,-0.102624701347,1.51099235423,75.8247923924 +35.3,51.0032329297,0.00470503122878,18.3536936509,4.88358824239,19.3626212782,-0.517107652251,-0.102993716574,1.50953825402,75.7528967771 +35.31,51.0032333697,0.00470778942737,18.3588615897,4.90602155282,19.3586256926,-0.516480118144,-0.10351200304,1.50854954161,75.6843146328 +35.32,51.0032338118,0.00471054704228,18.3640187084,4.92980391874,19.354426985,-0.514943623411,-0.104400601754,1.50632162993,75.6143851756 +35.33,51.0032342559,0.00471330412932,18.3691714996,4.95300244705,19.3512147815,-0.515614615756,-0.105165794022,1.50521372232,75.5437732117 +35.34,51.0032347023,0.00471606064953,18.3743185075,4.97745969986,19.3464691497,-0.513786965636,-0.107220242,1.50377692267,75.4762530486 +35.35,51.0032351507,0.00471881664555,18.3794542524,5.00106544457,19.3438553955,-0.513362012575,-0.107445524585,1.50286497989,75.4064421972 +35.36,51.0032356014,0.00472157206799,18.3845939754,5.02515384986,19.3384167132,-0.514582575434,-0.105370512998,1.50073753173,75.3382313141 +35.37,51.003236054,0.00472432681937,18.389736717,5.0463562383,19.3344342894,-0.513965743193,-0.106326935005,1.49968166932,75.2677947129 +35.38,51.0032365087,0.0047270810426,18.3948740358,5.07120604819,19.3310018369,-0.5134980255,-0.105269660004,1.49829593942,75.1976336689 +35.39,51.0032369657,0.00472983478036,18.4000008285,5.0954293311,19.3276185933,-0.511860512835,-0.105597548421,1.49903464097,75.1288444534 +35.4,51.0032374247,0.00473258795484,18.4051256834,5.11814601782,19.3230938989,-0.513110458371,-0.105421163431,1.49735278929,75.059156857 +35.41,51.0032378858,0.00473534063114,18.4102547326,5.13997420799,19.3206244983,-0.512699400415,-0.106265997342,1.4965701516,74.9903567754 +35.42,51.0032383488,0.00473809271586,18.4153789127,5.16210789226,19.3147885307,-0.512136618632,-0.104134465971,1.49539191472,74.9209485 +35.43,51.0032388139,0.00474084410907,18.4204981257,5.18707556122,19.3109163868,-0.511705972848,-0.106321152657,1.49413233035,74.8515755973 +35.44,51.0032392813,0.00474359500367,18.4256116517,5.21243879629,19.3077882989,-0.510999226223,-0.105732714723,1.49310889345,74.7828456058 +35.45,51.003239751,0.00474634539743,18.4307199147,5.23732836833,19.3038850066,-0.510653383696,-0.105270407258,1.49242763064,74.7131888039 +35.46,51.0032402228,0.00474909524447,18.4358342457,5.26040699259,19.3001127034,-0.512212808859,-0.106520622886,1.49095347306,74.6419362813 +35.47,51.0032406967,0.00475184460232,18.4409536264,5.2836414213,19.2970170492,-0.51166332572,-0.107072614236,1.48891182855,74.5728154152 +35.48,51.0032411727,0.00475459348895,18.446067873,5.30673336998,19.2934971526,-0.511186000325,-0.107856142339,1.48822930233,74.5035715917 +35.49,51.0032416507,0.00475734176612,18.4511817738,5.33013508101,19.2884607208,-0.51159416127,-0.10921469678,1.48690760353,74.4342659096 +35.5,51.0032421309,0.00476008941133,18.4562959819,5.35320016209,19.2846250187,-0.511247447144,-0.108126096172,1.48502358501,74.3651216486 +35.51,51.0032426131,0.00476283641249,18.4614119169,5.37612289287,19.2794187147,-0.511939569881,-0.107277184164,1.48372061269,74.2950612967 +35.52,51.0032430975,0.00476558273641,18.4665223103,5.40110658301,19.2751171592,-0.51013910746,-0.106738518991,1.48233050522,74.2242487021 +35.53,51.0032435841,0.0047683285812,18.4716390243,5.42507366579,19.272692058,-0.513203695528,-0.106244392591,1.48249501654,74.1549618282 +35.54,51.0032440728,0.00477107400513,18.476760163,5.44881617813,19.2692083685,-0.511024044642,-0.105812871271,1.47870677998,74.0854413959 +35.55,51.0032445636,0.00477381911169,18.4818673908,5.4718392496,19.2682364079,-0.510421514847,-0.105366192805,1.47740238112,74.0158502504 +35.56,51.0032450565,0.00477656379257,18.4869703432,5.4946053432,19.2632319722,-0.510168960818,-0.107000849135,1.47635918419,73.9449912577 +35.57,51.0032455515,0.00477930802102,18.4920775488,5.5194102093,19.2618845355,-0.511272145366,-0.107714680778,1.47842393032,73.875984202 +35.58,51.0032460487,0.0047820517957,18.4971913045,5.54347046954,19.2568613873,-0.511479011797,-0.108015758155,1.47583814942,73.8073766493 +35.59,51.0032465481,0.00478479488156,18.5023096503,5.56725754023,19.252214083,-0.512190149704,-0.108627099617,1.4745083761,73.7392226726 +35.6,51.0032470495,0.00478753721604,18.5074207098,5.59005151751,19.2463125138,-0.510021732527,-0.109221293335,1.4717247813,73.6694570979 +35.61,51.0032475531,0.00479027886181,18.5125042533,5.61336274583,19.2425453061,-0.506686969243,-0.109272720152,1.47239666049,73.6012079273 +35.62,51.0032480587,0.00479301993957,18.5175746389,5.63665557594,19.2383381385,-0.507390155242,-0.109423220558,1.47059596844,73.5312633259 +35.63,51.0032485664,0.00479576044892,18.52264783,5.65911682769,19.2345650901,-0.507248057799,-0.110103278179,1.47008323788,73.4607683691 +35.64,51.0032490761,0.00479850031772,18.5277155873,5.68207554037,19.2293454087,-0.506303401411,-0.109881425772,1.46703495837,73.391845464 +35.65,51.0032495879,0.0048012395784,18.5327641209,5.70576617043,19.2260275117,-0.503403325472,-0.108789422681,1.46593616245,73.3234169787 +35.66,51.0032501019,0.00480397827066,18.5378009389,5.72972768815,19.2213652181,-0.503960281939,-0.109210024103,1.46453902794,73.2534149179 +35.67,51.0032506179,0.00480671633412,18.5428456548,5.7511528385,19.217199608,-0.50498288486,-0.109741031658,1.46186216056,73.181549128 +35.68,51.0032511359,0.00480945380701,18.5478936061,5.77520099765,19.21307414,-0.504607378224,-0.10892560983,1.46290719721,73.112410172 +35.69,51.0032516561,0.0048121906905,18.5529360309,5.79876382596,19.2089248279,-0.503877587487,-0.107083074884,1.46214705296,73.0440455018 +35.7,51.0032521784,0.00481492697861,18.5579695363,5.82181066769,19.2047153299,-0.502823501204,-0.107984407007,1.46131098435,72.9749465368 +35.71,51.0032527027,0.00481766255817,18.5630037868,5.84398866393,19.1989775296,-0.504026594919,-0.107576383947,1.4602977757,72.9073576061 +35.72,51.0032532291,0.00482039759655,18.5680472659,5.86869386793,19.1971175052,-0.504669216477,-0.108499209114,1.45920303427,72.8353003199 +35.73,51.0032537577,0.00482313219989,18.5730957761,5.89233962987,19.1928695965,-0.505032824539,-0.108329715647,1.45930967795,72.7670232149 +35.74,51.0032542884,0.00482586629587,18.5781397048,5.91629641848,19.1899946581,-0.503752922894,-0.109375785268,1.45457528312,72.6952832141 +35.75,51.0032548213,0.0048285998675,18.5831671361,5.93868871826,19.1855079883,-0.50173333469,-0.108696409595,1.45308232343,72.6273122119 +35.76,51.0032553561,0.00483133290198,18.5881848576,5.96176163357,19.1824534854,-0.501810971264,-0.110496340393,1.4530429133,72.5556923821 +35.77,51.0032558931,0.00483406554117,18.5931946697,5.98524041685,19.1799581638,-0.500151445825,-0.108240328693,1.45171967219,72.4857850251 +35.78,51.0032564322,0.00483679766057,18.598197474,6.00926442754,19.17515594,-0.5004094165,-0.111318476616,1.45181468661,72.4172921301 +35.79,51.0032569734,0.00483952914096,18.603202412,6.03398645297,19.1709870992,-0.500578172124,-0.111672806964,1.44958607968,72.3483486321 +35.8,51.0032575168,0.00484226005365,18.6082083284,6.05687522395,19.1671856284,-0.500605119302,-0.11245013377,1.44792630562,72.278407155 +35.81,51.0032580623,0.00484499043145,18.613211025,6.07938219845,19.1634777338,-0.49993418794,-0.110777883436,1.44591231967,72.2085891693 +35.82,51.0032586098,0.00484772019664,18.618216353,6.10326135393,19.158584901,-0.501131417302,-0.112987462685,1.44498051727,72.1389506848 +35.83,51.0032591596,0.00485044942892,18.6232199978,6.12878235781,19.1559961013,-0.499597539477,-0.112305667066,1.44391481136,72.0676122414 +35.84,51.0032597115,0.00485317804971,18.6282229855,6.15,19.15,-0.501,-0.112,1.444,72 +35.85,51.0032602653,0.00485590566089,18.6332258478,6.17249396874,19.1418220236,-0.49957245568,-0.113187038509,1.44169542594,71.9316038166 +35.86,51.0032608212,0.0048586320656,18.6382259049,6.19574541295,19.1330625639,-0.50043897506,-0.110723870546,1.43966470562,71.8624728144 +35.87,51.003261379,0.00486135727926,18.6432298183,6.21537862309,19.1251009726,-0.500343694648,-0.109800747552,1.44032140436,71.7911990164 +35.88,51.0032619389,0.00486408114807,18.6482298379,6.24165479042,19.1141822577,-0.499660225848,-0.110973140179,1.43929344589,71.7223292317 +35.89,51.0032625009,0.00486680361069,18.6532205273,6.26417130559,19.1053596866,-0.498477660283,-0.10956708101,1.43711942242,71.6521973022 +35.9,51.003263065,0.00486952479595,18.6582047917,6.28629833313,19.0962494699,-0.498375227659,-0.110870589174,1.43379818003,71.5828772879 +35.91,51.003263631,0.00487224449173,18.6631865618,6.30764745892,19.0844489891,-0.497978786206,-0.114560528517,1.43214295789,71.5137713437 +35.92,51.003264199,0.00487496282555,18.6681592032,6.33012897345,19.0771290444,-0.496549489721,-0.111952684049,1.43121722427,71.4458271901 +35.93,51.003264769,0.00487767987489,18.6731200777,6.35189980591,19.0664163203,-0.495625406459,-0.110215050827,1.43029530534,71.3756354046 +35.94,51.003265341,0.00488039548702,18.6780776613,6.37439016502,19.0569521819,-0.495891313899,-0.109893750802,1.42975232657,71.3057980762 +35.95,51.003265915,0.0048831098444,18.6830313807,6.39760377637,19.0488008963,-0.494852568607,-0.11067064643,1.42890222685,71.2376064013 +35.96,51.0032664911,0.00488582290365,18.687978011,6.41952128089,19.0387278524,-0.494473495745,-0.109530709955,1.42733659821,71.1649630602 +35.97,51.0032670692,0.00488853456146,18.6929167605,6.44353808896,19.0291262318,-0.493276413287,-0.110207397938,1.42742181473,71.0977804106 +35.98,51.0032676493,0.00489124484985,18.6978437592,6.46369298277,19.0195026675,-0.492123319677,-0.110308685534,1.42569572215,71.0278057451 +35.99,51.0032682314,0.00489395375818,18.7027637498,6.48875995287,19.0097517405,-0.491874789548,-0.110180430362,1.42335644151,70.9563745817 +36,51.0032688157,0.00489666138039,18.707693299,6.51090862218,19.0014469072,-0.494035067932,-0.110022602709,1.42256076742,70.8875319041 +36.01,51.003269402,0.00489936775265,18.712630848,6.53370512813,18.9922036908,-0.493474724272,-0.108033750258,1.42155111501,70.8183781144 +36.02,51.0032699903,0.00490207273741,18.717553191,6.55642266778,18.9819678808,-0.490993871875,-0.10806757257,1.42080610189,70.7492018764 +36.03,51.0032705807,0.00490477636523,18.7224652928,6.57881144323,18.9731538429,-0.491426499397,-0.107268354244,1.41710904927,70.6821306268 +36.04,51.0032711731,0.00490747860546,18.7273743692,6.60217180685,18.9624874755,-0.490388773276,-0.107833031513,1.41739790917,70.6107480965 +36.05,51.0032717676,0.00491017934405,18.7322800914,6.62525976465,18.9520725989,-0.49075566494,-0.107091449651,1.41622535978,70.5397280109 +36.06,51.0032723642,0.00491287881237,18.7371928281,6.6484893762,18.9446541605,-0.49179166938,-0.107357948981,1.41369543011,70.4705874118 +36.07,51.0032729628,0.00491557700556,18.7421084963,6.67167627716,18.9341711051,-0.491341986251,-0.10820427115,1.41044296661,70.4014777342 +36.08,51.0032735635,0.00491827387958,18.7470190457,6.69403835072,18.9261344255,-0.490767878186,-0.108283992245,1.41215734723,70.3344076288 +36.09,51.0032741662,0.00492096945504,18.7519279793,6.71432598596,18.9159407248,-0.491018850489,-0.108042010256,1.41124424713,70.2638721215 +36.1,51.0032747708,0.00492366364712,18.7568363743,6.73764003898,18.9067133418,-0.490660153913,-0.107410346467,1.40960598167,70.195567761 +36.11,51.0032753773,0.00492635658987,18.7617486757,6.75851125283,18.8984012138,-0.491800115606,-0.105718213588,1.40775849379,70.1253288259 +36.12,51.003275986,0.00492904822646,18.7666674978,6.78366308829,18.8883764436,-0.491964302501,-0.106342490496,1.40737834126,70.0542810999 +36.13,51.0032765967,0.00493173847863,18.7715766046,6.80577575366,18.8789653605,-0.489857070038,-0.106555423564,1.40714543637,69.9851052566 +36.14,51.0032772095,0.00493442750068,18.7764763525,6.82837912924,18.8711068051,-0.49009250863,-0.106935661097,1.40633960429,69.9156567848 +36.15,51.0032778244,0.00493711528138,18.7813785169,6.85247219788,18.861538143,-0.490340369621,-0.104321621701,1.40305790967,69.8447564914 +36.16,51.0032784414,0.00493980166344,18.7862811985,6.87564926251,18.8514714039,-0.490195942141,-0.106153574956,1.40242360144,69.7767223465 +36.17,51.0032790605,0.00494248648727,18.7911860105,6.89924214428,18.8396622839,-0.490766465756,-0.105281977019,1.39717621926,69.707996715 +36.18,51.0032796816,0.00494516984817,18.7960991966,6.91986069544,18.8309333867,-0.491870747638,-0.106582912038,1.3970529229,69.6376120091 +36.19,51.0032803047,0.00494785196123,18.8010155756,6.9438982151,18.8221439682,-0.491405059393,-0.105548115542,1.3978331245,69.5680258262 +36.2,51.0032809299,0.00495053283041,18.8059152211,6.96581531882,18.8134706295,-0.488524036254,-0.105454905526,1.39667188522,69.4983702598 +36.21,51.003281557,0.00495321233776,18.8108046438,6.98867286746,18.8030253261,-0.489360498694,-0.106613344439,1.39602002612,69.4299273768 +36.22,51.0032821862,0.00495589053626,18.8156942299,7.01059740722,18.7950956973,-0.488556735685,-0.104258431489,1.394411489,69.359109977 +36.23,51.0032828174,0.00495856746263,18.8205750517,7.03409889211,18.7851659674,-0.487607613305,-0.102423930521,1.39127074951,69.2902705393 +36.24,51.0032834508,0.00496124308989,18.8254449923,7.05808975017,18.7768575229,-0.486380507087,-0.103412343621,1.39264806054,69.2191727782 +36.25,51.0032840863,0.00496391742232,18.8303029022,7.08021496941,18.7669880141,-0.485201474737,-0.104757140777,1.38902190327,69.1457971493 +36.26,51.0032847236,0.00496659035738,18.8351503856,7.10167098208,18.7572398479,-0.484295209633,-0.103743321495,1.38799991479,69.0761916165 +36.27,51.003285363,0.00496926194263,18.8399979284,7.12285653777,18.7480380958,-0.485213353616,-0.104714243044,1.38736379113,69.0085864429 +36.28,51.0032860043,0.00497193225754,18.8448440167,7.14605771525,18.7394055297,-0.484004293867,-0.10376053523,1.38657020311,68.9387895145 +36.29,51.0032866476,0.0049746012966,18.8496792985,7.16768289972,18.730126572,-0.483052062065,-0.104832167181,1.38788613732,68.8694528174 +36.3,51.003287293,0.00497726892283,18.8545224319,7.19161206422,18.7195708453,-0.485574624854,-0.105011965456,1.38619435039,68.8024795844 +36.31,51.0032879404,0.00497993527764,18.859379479,7.21329892527,18.7122772303,-0.485834801768,-0.105109380535,1.38377786775,68.7325546732 +36.32,51.0032885898,0.00498260038811,18.864233719,7.23686836617,18.7021015279,-0.485013196374,-0.105044678865,1.38275284404,68.6623538573 +36.33,51.0032892413,0.00498526417481,18.8690770616,7.25782533897,18.6936928864,-0.483655311079,-0.103192258119,1.37970170062,68.5938862627 +36.34,51.0032898947,0.00498792678828,18.8739184466,7.28027436238,18.6856304098,-0.484621704215,-0.103425389907,1.3787973668,68.5238459559 +36.35,51.0032905501,0.00499058826727,18.8787574658,7.30227735421,18.6777660968,-0.483182136072,-0.102165648986,1.3779001533,68.4523887092 +36.36,51.0032912076,0.00499324827102,18.883598148,7.32748892317,18.6649195448,-0.484954290528,-0.102492160918,1.37754288455,68.3813446146 +36.37,51.0032918673,0.00499590662632,18.8884458266,7.35103490383,18.6546236417,-0.484581440655,-0.0992009758513,1.37507833112,68.3133925462 +36.38,51.0032925292,0.00499856368902,18.8932857778,7.37470714329,18.6467729052,-0.483408790367,-0.101954970465,1.37596139973,68.243012178 +36.39,51.003293193,0.00500121940773,18.898114922,7.396341191,18.6357552874,-0.482420059992,-0.101630989268,1.37429107223,68.1766729511 +36.4,51.0032938589,0.00500387368891,18.9029374456,7.41919115983,18.6265915124,-0.48208465799,-0.102181687798,1.37484954645,68.1053690409 +36.41,51.0032945269,0.00500652676326,18.9077634784,7.44215698636,18.6188126709,-0.483121895235,-0.102918870048,1.37289454516,68.0354011272 +36.42,51.0032951968,0.00500917860032,18.9125848911,7.46396749356,18.6092212092,-0.481160649995,-0.102553078655,1.37314925587,67.9669758339 +36.43,51.0032958688,0.00501182907019,18.9173914432,7.48704961466,18.5996187715,-0.480149760516,-0.103307065819,1.37245016453,67.8944083138 +36.44,51.0032965428,0.00501447819623,18.922205849,7.51083853317,18.5903551848,-0.482731408747,-0.103230339885,1.37134744786,67.8265166726 +36.45,51.0032972189,0.00501712588567,18.9270277148,7.53197573136,18.5794504683,-0.481641757558,-0.105032013312,1.37066781137,67.7567960784 +36.46,51.003297897,0.00501977214354,18.9318446719,7.55448775993,18.5702573264,-0.481749660498,-0.10655790845,1.36800900522,67.6895268885 +36.47,51.0032985771,0.00502241725482,18.9366594123,7.57791337938,18.5633536323,-0.481198420033,-0.104623854721,1.36506828989,67.6227732466 +36.48,51.0032992593,0.00502506101368,18.9414654088,7.60010546693,18.5512706243,-0.480000870073,-0.102954957121,1.36444884754,67.5496941616 +36.49,51.0032999434,0.00502770315703,18.9462673402,7.62084654647,18.5406737229,-0.480385416056,-0.104030213391,1.36166780849,67.4799130039 +36.5,51.0033006295,0.00503034397131,18.9510608365,7.64478757731,18.5326118034,-0.478313846531,-0.102532215962,1.36123168263,67.4108196206 +36.51,51.0033013177,0.00503298359058,18.9558421464,7.66814428264,18.5238970652,-0.477948128289,-0.103825436281,1.36002977014,67.3418627013 +36.52,51.0033020079,0.00503562186557,18.9606190724,7.68837713606,18.5137393556,-0.477437067625,-0.103844903178,1.3603635294,67.273124919 +36.53,51.0033027,0.0050382587646,18.96539708,7.71025570714,18.5045801514,-0.478164453926,-0.104475544366,1.35937627266,67.2048539777 +36.54,51.0033033941,0.00504089433518,18.9701803818,7.73394320914,18.4950891331,-0.47849591395,-0.104424950619,1.35832685975,67.1344315658 +36.55,51.0033040903,0.00504352850977,18.9749690445,7.75578661421,18.48498206,-0.479236614929,-0.102895939216,1.3567993212,67.064289574 +36.56,51.0033047885,0.00504616126849,18.9797531217,7.77879870884,18.4752116748,-0.477578830192,-0.102088917296,1.35618744489,66.9953006185 +36.57,51.0033054886,0.00504879263345,18.9845256735,7.79923951867,18.4654151993,-0.476931536035,-0.102415939456,1.3549780992,66.9264757927 +36.58,51.0033061907,0.00505142260094,18.9892894497,7.82212537765,18.4555926621,-0.475823703665,-0.101813192397,1.35496391462,66.8542440634 +36.59,51.0033068948,0.00505405130791,18.9940371245,7.84414515711,18.4477187169,-0.473711241863,-0.101696841069,1.35377451392,66.7857076856 +36.6,51.003307601,0.00505667866453,18.9987770052,7.86937304265,18.4366351425,-0.47426490362,-0.102000680206,1.34992651518,66.7166856962 +36.61,51.0033083094,0.00505930461593,19.0035252674,7.89061264544,18.4279908568,-0.475387529865,-0.102314841277,1.34749309136,66.6422366436 +36.62,51.0033090198,0.00506192928592,19.0082797146,7.91594161693,18.4186454358,-0.475501925008,-0.10150371673,1.34922825652,66.5758267681 +36.63,51.0033097324,0.00506455257473,19.0130247316,7.93900669586,18.4086005754,-0.473501472802,-0.0997133293982,1.34828797924,66.506672528 +36.64,51.0033104471,0.0050671745687,19.0177691472,7.9634994041,18.400467103,-0.475381634979,-0.100268554566,1.34649962986,66.4375118274 +36.65,51.003311164,0.00506979529987,19.0225244797,7.98832534054,18.3908722411,-0.47568486914,-0.100484989894,1.34464883201,66.3674764376 +36.66,51.0033118831,0.00507241469325,19.0272734683,8.01044833485,18.3816858764,-0.474112849153,-0.0995396702423,1.34346019262,66.2979680535 +36.67,51.0033126041,0.00507503273546,19.0320066515,8.03273342748,18.3719030362,-0.47252379225,-0.0978235874588,1.3407485606,66.2299598672 +36.68,51.0033133271,0.00507764938885,19.0367334657,8.05343258361,18.3621884252,-0.472839051964,-0.0986510744055,1.33985525882,66.1603865569 +36.69,51.003314052,0.0050802647867,19.041458523,8.07544709954,18.3542764524,-0.472172413568,-0.0963376836195,1.33886627339,66.0898178188 +36.7,51.0033147789,0.00508287897091,19.0461679814,8.09792628143,18.3451501124,-0.469719258259,-0.0972465640971,1.33763000283,66.0205150672 +36.71,51.0033155079,0.00508549187805,19.0508673741,8.12076998791,18.3363476956,-0.470159279127,-0.0942731081492,1.33708716041,65.9476798617 +36.72,51.0033162389,0.00508810350115,19.0555728898,8.1437156988,18.3271233321,-0.47094387092,-0.0959912922312,1.3346058002,65.8805109472 +36.73,51.0033169719,0.0050907138431,19.0602723496,8.16516719335,18.3183618058,-0.468948091765,-0.0970467783372,1.33309183827,65.8098424063 +36.74,51.0033177068,0.00509332285938,19.0649641823,8.18701210677,18.3085121575,-0.469418435619,-0.0945203701889,1.32897846888,65.7410841517 +36.75,51.0033184438,0.00509593059826,19.0696603369,8.21135338417,18.3004283012,-0.469812498771,-0.0951811060406,1.32919774548,65.6711548414 +36.76,51.0033191829,0.00509853697534,19.0743586956,8.23255237139,18.2893939575,-0.469859234169,-0.0948444074593,1.32838681571,65.6024216252 +36.77,51.003319924,0.00510114175491,19.0790511673,8.25803144169,18.2780010513,-0.468635104975,-0.0949597296174,1.3276607412,65.5320934081 +36.78,51.0033206673,0.00510374514185,19.0837469248,8.27969177082,18.2698427812,-0.470516403479,-0.0947471640503,1.326735497,65.465131234 +36.79,51.0033214127,0.00510634737362,19.088451618,8.30399846452,18.261783501,-0.47042222127,-0.0966495475226,1.32573381116,65.3949354177 +36.8,51.0033221601,0.00510894819553,19.0931562835,8.32560756484,18.2500498801,-0.470510878919,-0.0974128834262,1.32597863263,65.3259091985 +36.81,51.0033229094,0.00511154759501,19.0978568622,8.34763048903,18.2418139998,-0.469604875758,-0.0955463670234,1.32377315353,65.2572022539 +36.82,51.0033236608,0.00511414566825,19.1025485455,8.37030677389,18.2314308571,-0.468731784929,-0.0971089348565,1.32225833309,65.1875047747 +36.83,51.0033244142,0.00511674233213,19.1072367742,8.3923265212,18.2220279637,-0.468913937488,-0.0970181703614,1.32217927559,65.1184580773 +36.84,51.0033251695,0.00511933775312,19.111922982,8.41357450671,18.213981982,-0.468327638882,-0.0968546447313,1.31983952787,65.0472116339 +36.85,51.0033259267,0.00512193185194,19.1166119265,8.434546987,18.2034659329,-0.469461257188,-0.0963154928524,1.32029244648,64.9784377415 +36.86,51.003326686,0.0051245245281,19.1213049395,8.45883700898,18.1940093071,-0.469141347588,-0.0963056445365,1.32050208967,64.9096130551 +36.87,51.0033274474,0.00512711583522,19.1260041618,8.48255727253,18.1842460332,-0.470703108308,-0.0962920988986,1.31745138393,64.839967015 +36.88,51.0033282109,0.00512970576993,19.1307049255,8.50400742882,18.174742131,-0.469449619565,-0.0968171867316,1.31563618739,64.7716316067 +36.89,51.0033289764,0.00513229441974,19.1353950728,8.52745463118,18.1662071516,-0.468579838354,-0.0955649601113,1.31379868016,64.7025818896 +36.9,51.0033297439,0.00513488170255,19.1400821576,8.55090676436,18.1555509028,-0.468837136618,-0.0960217252215,1.31449896002,64.6313578991 +36.91,51.0033305136,0.00513746764707,19.1447736175,8.57429557437,18.147418867,-0.469454836991,-0.0986926897969,1.31382846992,64.5612414997 +36.92,51.0033312853,0.00514005227494,19.1494623109,8.59583807796,18.137066397,-0.468283846121,-0.0972542794318,1.30976734551,64.4924514287 +36.93,51.003332059,0.00514263558657,19.1541537806,8.61890997225,18.1289402445,-0.470010101886,-0.098093143924,1.3102671486,64.4231252156 +36.94,51.0033328348,0.0051452177453,19.1588399894,8.64251798418,18.1208807271,-0.467231655907,-0.0973198413408,1.30875018957,64.3513069722 +36.95,51.0033336128,0.00514779848907,19.1635110028,8.66714929375,18.1090757568,-0.46697102644,-0.0957714885846,1.30724682224,64.2825218253 +36.96,51.0033343928,0.00515037777535,19.1681755279,8.6874087719,18.1004188433,-0.465933975673,-0.0953963669981,1.30690587201,64.2135151334 +36.97,51.0033351747,0.00515295569073,19.1728342054,8.71084203567,18.0898298383,-0.465801535098,-0.0948446046679,1.30480261732,64.1444947984 +36.98,51.0033359588,0.0051555322297,19.1774985969,8.73424339075,18.081095454,-0.467076757507,-0.0953347091625,1.30454389584,64.0726950446 +36.99,51.0033367449,0.0051581075156,19.1821665053,8.75620527492,18.0722378811,-0.466504933221,-0.0938473409588,1.30594320658,64.0061711788 +37,51.003337533,0.00516068147514,19.1868168268,8.77805287398,18.062474677,-0.463559358933,-0.0935498111515,1.30247522518,63.9358779664 +37.01,51.003338323,0.00516325411877,19.1914538347,8.80054568672,18.053763835,-0.463842229726,-0.0928699968187,1.30105202851,63.8673661611 +37.02,51.0033391151,0.0051658254351,19.1960830619,8.82229706733,18.0438405874,-0.462003201507,-0.0916531818251,1.29806338669,63.7975812277 +37.03,51.0033399091,0.00516839529478,19.2007082732,8.84503809675,18.0333140644,-0.46303905211,-0.0912704406467,1.2993921087,63.7279241224 +37.04,51.0033407052,0.00517096377402,19.2053382596,8.86865965012,18.0244606468,-0.462958245231,-0.093309143168,1.29670461762,63.6576059863 +37.05,51.0033415035,0.00517353086676,19.2099738815,8.89168283801,18.0138488517,-0.464166115913,-0.0932373304792,1.29637602567,63.5897484577 +37.06,51.0033423038,0.00517609659943,19.2146048266,8.91475448685,18.0053666823,-0.462022916123,-0.0911353688006,1.29796768795,63.5178013641 +37.07,51.003343106,0.0051786610488,19.2192188048,8.9356683666,17.9958326497,-0.460772717874,-0.0940451546589,1.29838301805,63.4449230015 +37.08,51.0033439103,0.00518122428298,19.2238257078,8.95925327573,17.9883064622,-0.460607890397,-0.0941286031714,1.29437444303,63.3768723674 +37.09,51.0033447166,0.00518378635477,19.2284282639,8.98053362894,17.9795137867,-0.459903320307,-0.0935310400532,1.29458419349,63.3087561192 +37.1,51.0033455249,0.00518634704138,19.2330266414,9.00482527345,17.9688598809,-0.45977217518,-0.0933471695522,1.29235717079,63.2386764899 +37.11,51.0033463354,0.00518890632043,19.2376223985,9.02806735814,17.9597530642,-0.459379245427,-0.0940089724102,1.29084518752,63.1697077059 +37.12,51.0033471479,0.00519146425609,19.2422192947,9.05,17.95,-0.46,-0.093,1.289,63.1 +37.13,51.0033479625,0.00519402041278,19.2468118259,9.07303855586,17.9347782656,-0.458506236805,-0.0951834784273,1.28533777499,63.0312935107 +37.14,51.0033487789,0.00519657451801,19.2514001708,9.09337849128,17.9212000128,-0.45916275666,-0.0948801245106,1.2850373847,62.9582385092 +37.15,51.0033495973,0.00519912680015,19.2559761576,9.1141976396,17.9091838227,-0.456034588735,-0.0966787217008,1.28495706386,62.8894443511 +37.16,51.0033504175,0.00520167715468,19.2605327086,9.13562093608,17.8941387678,-0.45527562049,-0.0945199745314,1.28286522262,62.8179951692 +37.17,51.0033512396,0.00520422546588,19.2650716243,9.15628024803,17.8804976855,-0.452507524217,-0.0978723149629,1.2837849545,62.7462413923 +37.18,51.0033520636,0.00520677186575,19.2696030049,9.17765656946,17.8673058177,-0.453768598286,-0.0957924416998,1.2825220025,62.6768208602 +37.19,51.0033528896,0.0052093163454,19.2741346869,9.19952018626,17.8535399035,-0.452567791218,-0.0962501149961,1.28106596056,62.6063119246 +37.2,51.0033537175,0.00521185871841,19.2786669581,9.22086346078,17.8377310184,-0.453886454829,-0.0951703611957,1.27994931589,62.5352716046 +37.21,51.0033545472,0.00521439891236,19.2832000262,9.24086382838,17.822948478,-0.452727161976,-0.0959166862761,1.27726353984,62.4654216873 +37.22,51.0033553788,0.00521693705526,19.2877321409,9.26136850114,17.8089364874,-0.453695769023,-0.0968770214369,1.27629666856,62.3967853303 +37.23,51.0033562122,0.00521947310853,19.2922617603,9.28261226298,17.7936125734,-0.452228109723,-0.0958935527926,1.27767301427,62.3268235083 +37.24,51.0033570475,0.00522200718473,19.2967778579,9.30224578497,17.7811806182,-0.45099141728,-0.0952578991597,1.27479469965,62.2566097983 +37.25,51.0033578846,0.00522453945369,19.3012850057,9.32318944025,17.7682409559,-0.450438141528,-0.094765977792,1.27493367101,62.184567415 +37.26,51.0033587236,0.00522706976639,19.3057897997,9.3449750828,17.7537168692,-0.450520657291,-0.0951117607731,1.27263661258,62.1168659948 +37.27,51.0033595646,0.00522959808537,19.3102947095,9.36594174452,17.7402514051,-0.450461302324,-0.0958683938231,1.2725109963,62.0458715862 +37.28,51.0033604075,0.00523212435169,19.3148030648,9.38867668475,17.7248996852,-0.451209753323,-0.0958291745877,1.27125090797,61.9751986384 +37.29,51.0033612524,0.00523464844747,19.3193106309,9.40924562907,17.7097796966,-0.450303483001,-0.0953159847634,1.27286098896,61.9087057247 +37.3,51.0033620992,0.00523717055435,19.3238184369,9.43322577654,17.6969777586,-0.451257716936,-0.0949798868531,1.27078207703,61.8369161419 +37.31,51.0033629482,0.00523969078179,19.3283286036,9.45539765571,17.6833944523,-0.450775613337,-0.0950556245015,1.26912948376,61.7644015118 +37.32,51.003363799,0.0052422090888,19.3328349205,9.47422711562,17.6700169715,-0.450487762624,-0.0956948725536,1.26996394025,61.6958217813 +37.33,51.0033646514,0.00524472535936,19.3373338855,9.49329651105,17.6548049848,-0.449305249058,-0.0965190134314,1.26847604561,61.6270884508 +37.34,51.0033655057,0.00524723952364,19.3418227168,9.5143133467,17.6404473372,-0.448461008859,-0.0978800998623,1.2662972546,61.5569189191 +37.35,51.0033663619,0.00524975172107,19.3463077291,9.53630080723,17.6271925219,-0.448541439295,-0.0976598946176,1.26212415043,61.4854947186 +37.36,51.00336722,0.00525226203653,19.3507918371,9.55637811964,17.6140265787,-0.448280163569,-0.0955507103109,1.26280734281,61.4153446502 +37.37,51.00336808,0.00525477035856,19.3552735684,9.5776649862,17.599206949,-0.448066096476,-0.0953009440611,1.26374105959,61.3435056008 +37.38,51.0033689419,0.00525727665395,19.3597571627,9.59949707159,17.5855749883,-0.448652764093,-0.0966047491395,1.26153310356,61.275080437 +37.39,51.0033698057,0.00525978085439,19.3642439063,9.61985226738,17.5697961712,-0.44869596713,-0.100256795803,1.26026457079,61.2040292113 +37.4,51.0033706714,0.00526228305265,19.3687215877,9.64101671429,17.5574665638,-0.446840311435,-0.0980371992666,1.2578071703,61.1330833288 +37.41,51.0033715388,0.00526478349136,19.3731906343,9.65974214426,17.5450939905,-0.446968996304,-0.0974610306957,1.25686540316,61.0620184754 +37.42,51.0033724081,0.00526728192937,19.3776454736,9.68188080751,17.5293790292,-0.44399887166,-0.0995801733308,1.25604626909,60.9918412892 +37.43,51.0033732795,0.00526977822018,19.3820797543,9.70483342048,17.5149497827,-0.442857265951,-0.0985029571352,1.25312630896,60.9234159492 +37.44,51.0033741527,0.00527227242569,19.3865145278,9.72490109913,17.500103733,-0.444097445365,-0.0985061367214,1.25148034644,60.8518056029 +37.45,51.0033750278,0.00527476455316,19.3909567306,9.74626287658,17.4857765251,-0.44434309898,-0.0998968197517,1.24940158926,60.781846295 +37.46,51.0033759049,0.00527725465971,19.3953917478,9.76697712964,17.4717323095,-0.442660357108,-0.09981353536,1.24966892678,60.7086686246 +37.47,51.0033767838,0.0052797428761,19.3998201956,9.78834575166,17.4592406897,-0.443029188213,-0.0987881291932,1.24733851815,60.6407102892 +37.48,51.0033776645,0.00528222919325,19.404242177,9.80824563017,17.4450690855,-0.441367093232,-0.0998866795757,1.24735154919,60.5692810895 +37.49,51.0033785472,0.00528471336323,19.40865365,9.83142974217,17.4290968754,-0.440927504203,-0.0995635621391,1.24658469856,60.4972835467 +37.5,51.0033794318,0.00528719536707,19.413062023,9.85037162937,17.4146590129,-0.440747102003,-0.0988844480785,1.24587348735,60.4281532603 +37.51,51.0033803182,0.00528967532266,19.4174739752,9.87183142391,17.4003417841,-0.441643337092,-0.0989529375555,1.24183803013,60.3549701771 +37.52,51.0033812065,0.00529215343974,19.4218833886,9.89223787015,17.3888483134,-0.440239335085,-0.0992772375909,1.24152971142,60.2878438665 +37.53,51.0033820966,0.00529462967466,19.4262858357,9.91360598812,17.3739183401,-0.440250095367,-0.0995532040186,1.23947252307,60.2158886561 +37.54,51.0033829887,0.00529710399864,19.4306814137,9.93542656347,17.3620208045,-0.438865510079,-0.098841449169,1.23826834766,60.1477881123 +37.55,51.0033838827,0.00529957652298,19.4350603855,9.95543751616,17.3486532938,-0.436928844035,-0.0999987181814,1.23979059007,60.0777490057 +37.56,51.0033847786,0.00530204702915,19.439437513,9.97758792624,17.3336880094,-0.438496655076,-0.0986639558071,1.23819061959,60.0070272252 +37.57,51.0033856765,0.00530451553917,19.4438160819,10.0008175964,17.3206295729,-0.437217126682,-0.0994122435246,1.23822039283,59.937355798 +37.58,51.0033865764,0.00530698194718,19.4481790536,10.0206209204,17.3041782535,-0.435377216996,-0.0985011067082,1.23801575165,59.8671248438 +37.59,51.003387478,0.00530944618523,19.4525371521,10.0414223825,17.2901657883,-0.436242472985,-0.0996940380875,1.23558058448,59.7963309325 +37.6,51.0033883816,0.0053119083867,19.4569036855,10.0624265783,17.2755870025,-0.437064212445,-0.097865603867,1.23381387754,59.7262018228 +37.61,51.0033892871,0.00531436860833,19.4612876835,10.0855229072,17.2623709121,-0.439735387769,-0.0954205536286,1.23540838925,59.6555186118 +37.62,51.0033901946,0.0053168268092,19.4656622712,10.1049800064,17.2472179189,-0.435182157181,-0.0964877372502,1.2322781891,59.5861270014 +37.63,51.0033911039,0.00531928287189,19.4700111221,10.1263257746,17.2323532495,-0.434588022929,-0.0988555678763,1.23205400729,59.5161537131 +37.64,51.003392015,0.00532173688148,19.4743537312,10.1467261761,17.2183947972,-0.433933788527,-0.0993806904393,1.22853530684,59.445055567 +37.65,51.0033929281,0.00532418884394,19.4786829101,10.1686159585,17.2036136642,-0.431901985789,-0.0993145250008,1.22915378887,59.3745967849 +37.66,51.003393843,0.00532663861141,19.4830151542,10.1877939257,17.187579883,-0.434546841719,-0.102679203137,1.2272713627,59.3026177527 +37.67,51.0033947598,0.0053290862524,19.4873664303,10.2099866349,17.1737601694,-0.435708386031,-0.102091489583,1.22890059213,59.2347460691 +37.68,51.0033956785,0.00533153193575,19.4917184972,10.2312074303,17.1600968666,-0.434704992102,-0.10075693684,1.22586332129,59.1636428641 +37.69,51.0033965991,0.00533397580459,19.4960595938,10.2532594273,17.1482862654,-0.433514329409,-0.101487517138,1.22445237246,59.0912241528 +37.7,51.0033975217,0.00533641765345,19.5003825421,10.2730316979,17.1317387932,-0.431075327881,-0.103551658808,1.22240162116,59.0240214919 +37.71,51.0033984461,0.00533885727835,19.5046908939,10.2956749533,17.11706438,-0.43059503672,-0.103165654805,1.22257342713,58.953962963 +37.72,51.0033993725,0.00534129490177,19.5090012281,10.3151376217,17.1036401454,-0.431471796486,-0.102924007475,1.22136765459,58.8821035789 +37.73,51.0034003006,0.00534373067082,19.5133148423,10.3368012262,17.0910312031,-0.431251038787,-0.104624352484,1.21932565402,58.8133719208 +37.74,51.0034012308,0.00534616458834,19.517631764,10.3586634662,17.0776465298,-0.432133308641,-0.10145324159,1.21877500939,58.7405853888 +37.75,51.0034021629,0.00534859654697,19.5219561117,10.3796489183,17.0635307823,-0.432736221534,-0.100539013669,1.21844946826,58.6708486407 +37.76,51.0034030968,0.0053510265054,19.5262749702,10.4001784311,17.0495658078,-0.431035486752,-0.101285081625,1.2160885302,58.6006099327 +37.77,51.0034040326,0.00535345464205,19.5305902705,10.4215763934,17.0379549419,-0.432024578745,-0.10147862364,1.21535933199,58.531190803 +37.78,51.0034049703,0.00535588089024,19.534909173,10.4426112484,17.0230538797,-0.431755906923,-0.100624700265,1.21359562495,58.4585252251 +37.79,51.00340591,0.00535830508353,19.5392150344,10.4635627026,17.0091065452,-0.429416375833,-0.100660974533,1.21266849909,58.388388821 +37.8,51.0034068515,0.00536072709131,19.5435171101,10.48466545,16.9923719048,-0.43099876969,-0.10127603425,1.21295216643,58.317776905 +37.81,51.0034077949,0.00536314687778,19.5478269303,10.5072599088,16.9779217588,-0.430965258584,-0.101851825737,1.2102890995,58.2488761967 +37.82,51.0034087404,0.00536556456831,19.5521226438,10.5297197465,16.9629472844,-0.428177441393,-0.101919052477,1.20960726846,58.1768882883 +37.83,51.0034096878,0.00536798012316,19.5564068002,10.5487536747,16.9479393205,-0.428653839169,-0.100335554643,1.20767772993,58.1071375306 +37.84,51.003410637,0.005370393776,19.560684621,10.5712082476,16.9362451336,-0.426910333499,-0.101712090365,1.20685247016,58.0382329137 +37.85,51.0034115881,0.00537280558502,19.5649579217,10.5912816598,16.9220541282,-0.427749792986,-0.101319775367,1.20626859632,57.9662609168 +37.86,51.0034125411,0.00537521537219,19.5692214741,10.6113027924,16.9078605138,-0.424960703076,-0.0999377399915,1.20516513365,57.8955794016 +37.87,51.0034134958,0.00537762314195,19.5734802913,10.6312188233,16.8937320395,-0.426802735243,-0.10076681863,1.20450275081,57.8272011789 +37.88,51.0034144524,0.00538002895535,19.577736819,10.6532263732,16.8803952921,-0.424502809506,-0.10006559625,1.20167034159,57.7552124217 +37.89,51.003415411,0.00538243298104,19.5819731723,10.6757771361,16.8686345697,-0.42276783261,-0.099402592285,1.19882352946,57.6858174653 +37.9,51.0034163716,0.00538483517036,19.5862062247,10.695639733,16.8546147238,-0.423842653325,-0.0998998168945,1.19899393082,57.6155031665 +37.91,51.003417334,0.00538723522073,19.5904442329,10.7175850902,16.8386060341,-0.42375899215,-0.100103056867,1.20010242051,57.5437653308 +37.92,51.0034182983,0.00538963312499,19.5946808635,10.738725889,16.8244858359,-0.423567131814,-0.099998139441,1.1974828161,57.4744664371 +37.93,51.0034192645,0.00539202914247,19.5989141557,10.759494253,16.812117791,-0.423091297875,-0.103215034824,1.19644642222,57.4042181503 +37.94,51.0034202327,0.00539442314259,19.6031377643,10.7811058551,16.796164179,-0.421630420117,-0.102407995895,1.19418165403,57.3321250989 +37.95,51.0034212027,0.00539681499867,19.6073497512,10.8026702673,16.782018009,-0.420766961715,-0.101129406125,1.19273147979,57.2612102824 +37.96,51.0034221747,0.0053992048566,19.6115528548,10.8234868916,16.768112416,-0.419853763776,-0.10172485432,1.19035689503,57.1916651464 +37.97,51.0034231486,0.00540159253091,19.6157414955,10.8454426515,16.7513623977,-0.417874380926,-0.105477452519,1.18807349159,57.1227423862 +37.98,51.0034241244,0.00540397807807,19.619923642,10.8661458915,16.738249702,-0.418554915843,-0.10284322879,1.18773328346,57.0514037802 +37.99,51.0034251021,0.00540636176715,19.6241098279,10.886284424,16.725276971,-0.418682259511,-0.101404947203,1.18816313606,56.9787469473 +38,51.0034260816,0.00540874361073,19.6283068162,10.9090118093,16.7123407694,-0.420715404657,-0.102591194678,1.18558257803,56.9086352862 +38.01,51.0034270632,0.0054111235912,19.6325137042,10.9305819262,16.6991211194,-0.420662189678,-0.104672757787,1.18337280367,56.837698709 +38.02,51.0034280466,0.0054135016688,19.6367147307,10.9507454058,16.6856263892,-0.419543102884,-0.102363281828,1.1846554983,56.7680586045 +38.03,51.003429032,0.0054158777961,19.6409125754,10.972363451,16.6717411325,-0.420025853928,-0.102440081705,1.18530673461,56.6989106057 +38.04,51.0034300192,0.00541825198856,19.6451046063,10.9934077224,16.6584634173,-0.418380312867,-0.103391549472,1.18285549229,56.6275928755 +38.05,51.0034310083,0.0054206243585,19.6492952237,11.0132831825,16.6461549418,-0.419743171047,-0.104010787241,1.1832865382,56.5553971765 +38.06,51.0034319992,0.0054229949172,19.6534821042,11.034484602,16.6330354268,-0.41763293329,-0.10504807728,1.18102679843,56.488266921 +38.07,51.0034329919,0.00542536342522,19.657659318,11.0536381916,16.6173657678,-0.417809818755,-0.103427019238,1.17844466222,56.4189703546 +38.08,51.0034339865,0.00542772976608,19.6618320853,11.0752045614,16.6026110303,-0.416743644814,-0.104009972608,1.17881771375,56.3494917076 +38.09,51.0034349829,0.00543009397284,19.6659979851,11.0952711042,16.5874053378,-0.416436315565,-0.106405285903,1.17694147287,56.2784319703 +38.1,51.0034359814,0.00543245627256,19.6701611864,11.119231471,16.5758383829,-0.416203945107,-0.104695353325,1.17563489713,56.2091448813 +38.11,51.0034369818,0.00543481676315,19.6743051076,11.1402129902,16.5620069957,-0.412580298407,-0.106717527944,1.17489790325,56.136915342 +38.12,51.003437984,0.00543717510728,19.6784294695,11.1595564347,16.5457045399,-0.412292088041,-0.105229992239,1.17452187212,56.0649173461 +38.13,51.003438988,0.0054395311858,19.6825514437,11.1788469449,16.5302005136,-0.412102741825,-0.106409252934,1.17320340919,55.9954777535 +38.14,51.003439994,0.0054418851822,19.6866773419,11.2030085613,16.5164737991,-0.413076899738,-0.104147454515,1.17319568464,55.9252575892 +38.15,51.0034410019,0.00544423712129,19.6908038031,11.2236448403,16.5013182686,-0.41221533731,-0.105034742213,1.17237844343,55.8538502389 +38.16,51.0034420117,0.0054465870122,19.6949326352,11.2445846644,16.4877196085,-0.413551088311,-0.104051510533,1.17077251679,55.7867321877 +38.17,51.0034430235,0.00544893499771,19.6990721118,11.2674339116,16.474568617,-0.414344225389,-0.101391524428,1.17063420613,55.7177826208 +38.18,51.0034440372,0.00545128112352,19.7031998596,11.286849961,16.4616113714,-0.411205329436,-0.103900046697,1.16950818345,55.6450990028 +38.19,51.0034450527,0.00545362517673,19.707312846,11.3074214976,16.4454716678,-0.411391960353,-0.103840770041,1.1671147101,55.5750434675 +38.2,51.0034460701,0.00545596698684,19.7114211665,11.3292064251,16.4301207648,-0.410272146025,-0.104041201023,1.16472943696,55.5048339003 +38.21,51.0034470894,0.00545830664305,19.7155260479,11.3511063636,16.415233469,-0.410704131392,-0.103135838552,1.1640944409,55.4336940409 +38.22,51.0034481107,0.00546064427279,19.7196241711,11.3728030992,16.4016713771,-0.408920494825,-0.103907103117,1.16580530611,55.3655685539 +38.23,51.003449134,0.00546297997977,19.7237083993,11.393443369,16.3882399007,-0.407925157624,-0.104190381568,1.16392640121,55.2960973139 +38.24,51.003450159,0.00546531377609,19.7277940527,11.4139927387,16.3748479514,-0.409205516007,-0.105247464443,1.16381385295,55.2252952578 +38.25,51.0034511861,0.00546764547825,19.7318821718,11.4369952269,16.3588401337,-0.408418302296,-0.104681936818,1.16047125491,55.1571492207 +38.26,51.003452215,0.00546997515985,19.7359570114,11.4563901197,16.346481646,-0.40654962628,-0.104588122652,1.16177655177,55.0858178483 +38.27,51.0034532458,0.00547230291663,19.7400251649,11.4785343132,16.3318177454,-0.407081067344,-0.107393078395,1.16278780795,55.0171960238 +38.28,51.0034542785,0.00547462866113,19.7440967871,11.5000002516,16.3182314549,-0.407243371017,-0.104319419281,1.16056106569,54.9434372613 +38.29,51.0034553131,0.00547695235371,19.7481636464,11.5181537044,16.3030110482,-0.406128486976,-0.102922200844,1.15422996702,54.8729924616 +38.3,51.0034563493,0.00547927402146,19.7522220046,11.5387046506,16.2898051919,-0.405543164349,-0.102501898176,1.1542805971,54.803254893 +38.31,51.0034573875,0.00548159369026,19.756277492,11.5601701315,16.2749479421,-0.40555430677,-0.102842969566,1.15266074005,54.7331802079 +38.32,51.0034584276,0.00548391138927,19.760332709,11.5822731823,16.262151554,-0.405489093835,-0.106138102265,1.15399429362,54.6622221383 +38.33,51.0034594697,0.00548622717028,19.7643923409,11.6042588054,16.2480213303,-0.406437292464,-0.107069829823,1.15025419123,54.5925589957 +38.34,51.0034605137,0.00548854096574,19.7684505431,11.6229185299,16.2342765437,-0.405203147671,-0.106692324745,1.150727467,54.5206867235 +38.35,51.0034615595,0.00549085281285,19.7724962497,11.6456070973,16.2206687873,-0.403938174987,-0.10865017965,1.15023714243,54.4491684139 +38.36,51.0034626071,0.00549316266076,19.7765390436,11.6654055139,16.2062099317,-0.404620602488,-0.10873000996,1.14949017441,54.3804533396 +38.37,51.0034636567,0.00549547040726,19.7805749286,11.6863446274,16.1911673795,-0.402556394792,-0.1071782105,1.1474018706,54.3108354419 +38.38,51.0034647081,0.00549777604107,19.7845961568,11.7081191101,16.1765500083,-0.401689242225,-0.107668175068,1.14851747576,54.241266971 +38.39,51.0034657615,0.00550007960845,19.788603977,11.7302495862,16.1621572327,-0.399874806687,-0.107620004611,1.145940938,54.1706577255 +38.4,51.0034668169,0.00550238128467,19.7926183511,11.75,16.15,-0.403,-0.107,1.144,54.1 +38.41,51.0034678739,0.00550468094838,19.7966428635,11.7700083089,16.1339039108,-0.401902485361,-0.105693656949,1.14434593558,54.0271228463 +38.42,51.0034689326,0.00550697852786,19.8006662678,11.7858559333,16.1207399003,-0.402778376007,-0.106071749007,1.14260231548,53.9535811728 +38.43,51.0034699929,0.00550927407841,19.804683196,11.8052553861,16.1054198154,-0.400607260988,-0.106202692846,1.14305601613,53.882622528 +38.44,51.0034710548,0.00551156744353,19.8086841528,11.8217752176,16.0900590133,-0.399584108208,-0.106525911298,1.1397384578,53.8104820515 +38.45,51.0034721183,0.00551385876015,19.8126680626,11.8401605015,16.0766611125,-0.397197847935,-0.107799040236,1.13772192895,53.7387795513 +38.46,51.0034731834,0.00551614772803,19.8166429928,11.8573433326,16.0570855183,-0.397788189204,-0.108111728892,1.13824136763,53.6670684483 +38.47,51.0034742501,0.00551843437783,19.8206244954,11.8759482604,16.0441179416,-0.39851232434,-0.106731808013,1.13815561312,53.5933800739 +38.48,51.0034753183,0.00552071906177,19.8246045025,11.8929905661,16.0294869586,-0.397489095217,-0.10644910708,1.13683397617,53.5247790242 +38.49,51.0034763882,0.00552300168764,19.8285769133,11.912187899,16.0152250319,-0.396993071169,-0.106602342284,1.13460672745,53.4533682115 +38.5,51.0034774598,0.00552528222314,19.8325404671,11.9300895265,16.0001403855,-0.395717680137,-0.106201586345,1.13282545461,53.3811372383 +38.51,51.003478533,0.00552756065001,19.836490375,11.9471439905,15.9856223482,-0.394263913362,-0.104541977331,1.13274605619,53.3096333079 +38.52,51.0034796076,0.00552983689115,19.8404362629,11.9641456403,15.9694552746,-0.394913671703,-0.106561515008,1.12997371952,53.2368245637 +38.53,51.0034806839,0.00553211094998,19.8443871519,11.9826598481,15.9549851364,-0.395264110123,-0.106903083718,1.12929739518,53.1667741218 +38.54,51.0034817619,0.00553438289453,19.8483335469,12.0021790209,15.9397731631,-0.394014908124,-0.107060727788,1.12786796376,53.0952119208 +38.55,51.0034828416,0.00553665280302,19.8522831021,12.0203721922,15.9264012447,-0.395896121797,-0.107730634281,1.12742699023,53.0241100745 +38.56,51.0034839228,0.00553892061369,19.8562312437,12.0369828669,15.9103220984,-0.393732205716,-0.10847764541,1.12494573153,52.9528166924 +38.57,51.0034850056,0.00554118625561,19.8601643631,12.054191681,15.8959543636,-0.39289166237,-0.10766249945,1.12319185775,52.880431443 +38.58,51.00348609,0.00554344990451,19.8640925314,12.0730610836,15.8823424287,-0.392742003953,-0.107383594186,1.12152195373,52.8082167689 +38.59,51.0034871761,0.00554571154503,19.8680265511,12.0927638745,15.8677588845,-0.394061940194,-0.107442680809,1.11998894701,52.7350510099 +38.6,51.0034882638,0.0055479710285,19.871957497,12.1080799497,15.8520598352,-0.392127237994,-0.109068410421,1.12009701792,52.6644497322 +38.61,51.003489353,0.00555022849311,19.8758759151,12.1261582167,15.8394164988,-0.391556380695,-0.109833198911,1.11973509278,52.5923309061 +38.62,51.0034904438,0.00555248379981,19.8797912438,12.1448541917,15.8217651668,-0.391509351788,-0.109524952819,1.11766653543,52.519754855 +38.63,51.0034915363,0.00555473667275,19.883696859,12.1627629392,15.8052493215,-0.389613701222,-0.111299662403,1.11691284919,52.4477141594 +38.64,51.0034926304,0.00555698753656,19.8876014123,12.1809446364,15.793559193,-0.391296948342,-0.109791097215,1.11635447073,52.3753854677 +38.65,51.0034937262,0.00555923651856,19.8915046004,12.19929997,15.7788308715,-0.389340671405,-0.109558503236,1.11341205942,52.300147659 +38.66,51.0034948235,0.00556148336314,19.8953960895,12.2157044465,15.7635522323,-0.388957159192,-0.10872938105,1.11306613949,52.2307198827 +38.67,51.0034959223,0.00556372808431,19.8992751709,12.2323721495,15.7490204632,-0.386859112348,-0.1080163158,1.11244596065,52.1600879193 +38.68,51.0034970227,0.00556597070052,19.9031493263,12.2513854089,15.7340010992,-0.387971960812,-0.108593197153,1.11198070584,52.0877948348 +38.69,51.0034981247,0.00556821115599,19.9070215171,12.2690273404,15.7186861403,-0.386466200432,-0.110098048003,1.11137214318,52.0187424629 +38.7,51.0034992284,0.00557044957873,19.910888489,12.2864421672,15.7054638785,-0.386928182898,-0.109200668376,1.10833088469,51.9453345047 +38.71,51.0035003336,0.00557268592959,19.9147565304,12.3041298983,15.6895992431,-0.386680102826,-0.108748901714,1.10833940245,51.8727519497 +38.72,51.0035014404,0.00557492004613,19.9186282897,12.3226651078,15.6740964912,-0.387671754046,-0.10870353765,1.10706101924,51.8008235838 +38.73,51.0035025488,0.00557715206718,19.9225005448,12.3393049141,15.6601811048,-0.386779267598,-0.106290099545,1.10350950706,51.7280634476 +38.74,51.0035036589,0.00557938197242,19.9263687848,12.3601187696,15.6443927749,-0.386868732071,-0.10740730215,1.10292377186,51.657337532 +38.75,51.0035047707,0.00558160982748,19.9302352844,12.3770968406,15.6313989826,-0.38643119712,-0.107669026245,1.10185905862,51.5846623872 +38.76,51.0035058841,0.00558383569082,19.9340905255,12.3956290835,15.6164311486,-0.384617009159,-0.108113737054,1.10316593617,51.5120175836 +38.77,51.0035069992,0.00558605916911,19.9379426154,12.4134921838,15.5979157113,-0.385800970468,-0.106676983343,1.099338319,51.4415271055 +38.78,51.0035081157,0.00558828048961,19.9418012421,12.4303239919,15.5861383147,-0.385924377558,-0.108301409423,1.10029872224,51.368350262 +38.79,51.0035092339,0.00559049981905,19.9456518778,12.4487682998,15.5699633006,-0.384202761149,-0.106236938367,1.09791992511,51.2946787786 +38.8,51.0035103537,0.00559271691128,19.9494930421,12.4668966274,15.554730547,-0.384030103438,-0.107891413319,1.10017379822,51.2252188692 +38.81,51.0035114752,0.00559493186899,19.9533309542,12.4843795267,15.5399971865,-0.383552310611,-0.106229977155,1.09890288308,51.1544951039 +38.82,51.0035125981,0.00559714470809,19.9571661394,12.5014824871,15.5249874686,-0.383484725398,-0.107839122718,1.09971234695,51.0813068889 +38.83,51.0035137227,0.00559935534531,19.961008053,12.5198756494,15.5090854479,-0.38489800434,-0.106670515173,1.09869603636,51.0083218706 +38.84,51.0035148489,0.00560156387135,19.9648496105,12.5389287662,15.4953488439,-0.383413489251,-0.107305645923,1.09351859935,50.9351816533 +38.85,51.0035159768,0.00560377030253,19.9686838634,12.5564077988,15.4796759419,-0.383437082222,-0.106029067751,1.09280798569,50.8606543367 +38.86,51.0035171064,0.005605974668,19.9725174543,12.5752905653,15.4663486811,-0.383281096178,-0.107115749882,1.09196367056,50.7888269189 +38.87,51.0035182376,0.00560817701614,19.9763411735,12.5943949113,15.4513548833,-0.381462757131,-0.104898760324,1.09172446307,50.7183461109 +38.88,51.0035193705,0.00561037727929,19.9801606312,12.6115326398,15.4370776697,-0.382428781996,-0.107032708301,1.0891134487,50.6475228114 +38.89,51.0035205049,0.00561257558942,19.9839872629,12.6297460018,15.4239367567,-0.38289755257,-0.105508356814,1.08925861122,50.576341787 +38.9,51.003521641,0.00561477188057,19.9878123508,12.64867571,15.4087335209,-0.382120028534,-0.106212237973,1.0882956548,50.5044146982 +38.91,51.0035227787,0.00561696595116,19.9916282028,12.6644545134,15.3927624865,-0.381050380966,-0.107022870863,1.08790531359,50.4342474751 +38.92,51.0035239179,0.0056191578205,19.9954379103,12.6827426119,15.3778306252,-0.380891104403,-0.107105994652,1.08675034251,50.3611782868 +38.93,51.0035250588,0.00562134772082,19.9992456638,12.7018674112,15.3651195339,-0.380659602501,-0.108912147288,1.08298284508,50.2905366216 +38.94,51.0035262014,0.00562353560502,20.0030597892,12.719441931,15.3495265487,-0.382165475147,-0.1075495868,1.08331856733,50.2176596513 +38.95,51.0035273455,0.00562572131962,20.0068622809,12.7380150659,15.3346609618,-0.378332856958,-0.105791128453,1.08255738123,50.1457716336 +38.96,51.0035284913,0.00562790492427,20.0106506089,12.7548851366,15.3199051861,-0.37933275056,-0.107158841161,1.08118938544,50.0723838781 +38.97,51.0035296385,0.00563008644476,20.0144431303,12.7706801291,15.3054016539,-0.379171531275,-0.10828294223,1.08134073089,50.0024197793 +38.98,51.0035307873,0.00563226586113,20.0182267788,12.7896641449,15.2903657779,-0.377558172987,-0.106816020506,1.08010719357,49.9298896708 +38.99,51.0035319378,0.00563444326168,20.0219945411,12.8078612355,15.2771018025,-0.375994282443,-0.107509909041,1.07689772337,49.8585804951 +39,51.0035330899,0.00563661860762,20.0257649063,12.8264592797,15.2615213524,-0.378078759324,-0.107231719746,1.07605379959,49.7875773603 +39.01,51.0035342437,0.00563879182307,20.0295487416,12.8459196013,15.2471921076,-0.378688303849,-0.104768572409,1.07426036072,49.7175753473 +39.02,51.0035353992,0.00564096296504,20.0333268117,12.8626519899,15.2324121096,-0.376925716913,-0.106250912103,1.07427378536,49.6441824988 +39.03,51.0035365562,0.00564313179031,20.0370897913,12.880637993,15.2146684218,-0.375670193346,-0.10578375695,1.07358864349,49.5719909405 +39.04,51.0035377148,0.0056452983401,20.0408425817,12.8983564922,15.2004668992,-0.374887892741,-0.107785086431,1.07132791792,49.498030249 +39.05,51.0035388752,0.00564746284808,20.0445815903,12.9197749986,15.1860037487,-0.372913818039,-0.108676922613,1.06807111468,49.4271921416 +39.06,51.0035400372,0.00564962524229,20.0483097257,12.9350293452,15.1707918745,-0.372713264712,-0.108318624692,1.06700388232,49.353011448 +39.07,51.0035412008,0.00565178534311,20.0520377982,12.9530698774,15.1538073767,-0.37290125044,-0.10710356994,1.06797547018,49.2830928752 +39.08,51.0035423659,0.00565394327042,20.055770188,12.9712986959,15.1402781938,-0.373576704058,-0.108549166647,1.06613358628,49.2111361174 +39.09,51.0035435327,0.00565609917251,20.0594963726,12.9898727673,15.1253755782,-0.371660219891,-0.11043374629,1.06583084781,49.1402168725 +39.1,51.0035447011,0.00565825295018,20.0632116753,13.0067372076,15.1104537365,-0.371400320982,-0.107828098007,1.06423512135,49.068135156 +39.11,51.0035458711,0.00566040462271,20.0669312554,13.0238522013,15.0958218815,-0.372515698134,-0.107905172346,1.06245250584,48.9964036886 +39.12,51.0035470425,0.00566255428871,20.0706529483,13.0409987913,15.0822843339,-0.371822871487,-0.107357840953,1.06077964244,48.9229822685 +39.13,51.0035482155,0.00566470187242,20.0743705459,13.0576424934,15.0665888521,-0.371696646434,-0.106514085698,1.05933664754,48.8510971164 +39.14,51.0035493901,0.00566684728771,20.0780814147,13.0773973462,15.0518421411,-0.370477127154,-0.106526893837,1.06007821401,48.7784093581 +39.15,51.0035505664,0.00566899056252,20.0817804144,13.093456093,15.0365389768,-0.36932280291,-0.107567292689,1.05810334118,48.7065607621 +39.16,51.0035517442,0.00567113170525,20.0854749795,13.1124702428,15.0219102577,-0.369590213791,-0.105815061476,1.05736013157,48.6369736116 +39.17,51.0035529238,0.00567327075624,20.0891790439,13.1328823529,15.0071731833,-0.371222669726,-0.103966629495,1.05641849343,48.5644716653 +39.18,51.003554105,0.00567540773655,20.092875058,13.1505634542,14.9928403636,-0.367980146164,-0.105928003694,1.05447513575,48.4925494013 +39.19,51.003555288,0.00567754258092,20.0965496408,13.1699617895,14.9771870486,-0.366936415944,-0.107043823749,1.052972575,48.4223092808 +39.2,51.0035564727,0.00567967537956,20.1002275515,13.1882821453,14.9641205936,-0.368645730887,-0.107458025011,1.05327936015,48.3496508095 +39.21,51.0035576589,0.00568180609728,20.1039011928,13.2057060576,14.947973216,-0.366082522392,-0.107398707228,1.05122007883,48.2775065282 +39.22,51.0035588468,0.00568393490834,20.1075715846,13.2235505437,14.9373532719,-0.367995847194,-0.106383941446,1.05079543865,48.2052031293 +39.23,51.0035600361,0.00568606193362,20.1112492694,13.2396909823,14.9229028193,-0.367541095875,-0.107314622701,1.05058057874,48.1336842794 +39.24,51.0035612271,0.00568818672931,20.1149169946,13.2586244729,14.9060523037,-0.366003946186,-0.108262722961,1.04818543469,48.062839082 +39.25,51.0035624197,0.0056903092875,20.1185799562,13.2770594675,14.8914910733,-0.366588387162,-0.108057225463,1.0484337296,47.9905286217 +39.26,51.0035636139,0.00569242964181,20.1222475184,13.2931368512,14.8751122031,-0.366924038249,-0.108694119911,1.04722369656,47.9191537892 +39.27,51.0035648097,0.0056945477432,20.1258991954,13.3124295621,14.8598628157,-0.363411380441,-0.107709140259,1.04853794658,47.8470209306 +39.28,51.0035660071,0.00569666374212,20.1295401712,13.3298438451,14.8455958318,-0.364783773936,-0.109690032902,1.04522847238,47.7741018569 +39.29,51.0035672061,0.00569877763901,20.133184699,13.3472326204,14.8303528522,-0.364121788284,-0.110616897386,1.04751293002,47.7025718268 +39.3,51.0035684067,0.00570088930869,20.1368193831,13.3660565729,14.8143282834,-0.362815018658,-0.111110352284,1.04407558477,47.6328666065 +39.31,51.003569609,0.00570299882706,20.1404498682,13.3843883864,14.8001509808,-0.363282001567,-0.109446101622,1.0422938454,47.5609080528 +39.32,51.0035708129,0.00570510635797,20.1440782332,13.4033831173,14.786426525,-0.362390997773,-0.11048994069,1.04135692936,47.4866756648 +39.33,51.0035720186,0.00570721173704,20.1477089239,13.4223521647,14.7699416789,-0.363747146517,-0.108981114139,1.03819515746,47.4151503325 +39.34,51.0035732258,0.00570931491432,20.1513379383,13.4374279337,14.7555158349,-0.36205573272,-0.109557665006,1.03774036156,47.344255505 +39.35,51.0035744345,0.00571141602953,20.1549532581,13.4554102343,14.7409927448,-0.361008237295,-0.110081716247,1.03739973011,47.2739734832 +39.36,51.0035756448,0.00571351502892,20.1585701331,13.4747568818,14.7258120226,-0.36236675217,-0.110110716403,1.03587712606,47.200715657 +39.37,51.0035768569,0.00571561193288,20.1621887185,13.4930663816,14.7115752157,-0.361350339854,-0.109762545953,1.03403511951,47.1289890895 +39.38,51.0035780705,0.00571770676438,20.1657956547,13.510671018,14.6967172046,-0.360036884301,-0.110218250002,1.03097294221,47.0580430722 +39.39,51.0035792858,0.00571979944167,20.1694030638,13.5293165537,14.6813324275,-0.361444945426,-0.108967511895,1.03028441709,46.9860097993 +39.4,51.0035805027,0.00572188977245,20.1730080365,13.5461656889,14.6637751096,-0.359549595342,-0.109082601259,1.02938362555,46.9147232382 +39.41,51.0035817212,0.00572397772719,20.1766034776,13.5636057275,14.6479755223,-0.35953861922,-0.108548450227,1.02912284486,46.8423424155 +39.42,51.0035829411,0.00572606348927,20.1801913388,13.5799748745,14.6329928312,-0.358033622039,-0.109640818511,1.02733655346,46.771144937 +39.43,51.0035841626,0.00572814715862,20.1837673458,13.5974126527,14.6185959172,-0.357167783571,-0.110348261112,1.02973218753,46.7005974347 +39.44,51.0035853857,0.00573022887251,20.187342943,13.6159353249,14.6055404066,-0.357951656932,-0.107993221624,1.02591895408,46.6266119728 +39.45,51.0035866104,0.00573230856733,20.1909232709,13.6341740991,14.5902504317,-0.358113918983,-0.108279621633,1.02539364879,46.5550860952 +39.46,51.0035878368,0.00573438627478,20.1945002045,13.6522874133,14.5776399327,-0.357272802829,-0.105764706313,1.02468768214,46.4826714334 +39.47,51.0035890648,0.0057364620254,20.1980698723,13.6716253207,14.5627787074,-0.356660759612,-0.106298233937,1.02347374036,46.4092556363 +39.48,51.0035902945,0.0057385357108,20.20164223,13.6885158659,14.54864658,-0.357810765848,-0.106639841571,1.02302130618,46.3369099293 +39.49,51.0035915259,0.00574060732177,20.2052244058,13.7088956479,14.5336561061,-0.358624397323,-0.107338821404,1.02154901504,46.2658708519 +39.5,51.0035927589,0.00574267679282,20.2087971745,13.7264885487,14.5186045926,-0.355929343014,-0.107996366968,1.02013765932,46.1910301357 +39.51,51.0035939935,0.00574474411737,20.2123446333,13.7430182612,14.5035217589,-0.353562423338,-0.107959617679,1.01711942611,46.1194942555 +39.52,51.0035952297,0.00574680925654,20.2158935495,13.7621048884,14.4879244292,-0.356220809177,-0.1081432007,1.01745041426,46.0488622742 +39.53,51.0035964676,0.00574887222538,20.2194563025,13.7812382316,14.4730526487,-0.356329802279,-0.106247979672,1.01761217688,45.9773133981 +39.54,51.0035977073,0.00575093314239,20.2230134568,13.8016766037,14.4591192153,-0.355101045912,-0.10938707773,1.01522295208,45.9042592396 +39.55,51.0035989488,0.00575299208532,20.2265676042,13.8206676749,14.4453387507,-0.35572844665,-0.10942697476,1.01127320148,45.834848465 +39.56,51.0036001919,0.00575504895426,20.2301169894,13.8373900971,14.4300027382,-0.354148584372,-0.109708236407,1.01074941668,45.7631224675 +39.57,51.0036014365,0.00575710359971,20.233668004,13.85422523,14.4141235298,-0.356054334964,-0.10822860874,1.00966576724,45.6891341934 +39.58,51.0036026826,0.00575915588764,20.237216774,13.8715845686,14.3969060612,-0.353699673324,-0.10965766903,1.00871077878,45.6175457805 +39.59,51.0036039303,0.0057612058895,20.2407440355,13.889206541,14.3820297004,-0.351752624225,-0.110102493739,1.00672015756,45.5455495264 +39.6,51.0036051796,0.00576325387638,20.2442615848,13.9070049197,14.3686180915,-0.351757231172,-0.109598420415,1.00693453262,45.473598158 +39.61,51.0036064305,0.00576529984213,20.2477760349,13.9254882885,14.3536552443,-0.35113279979,-0.109881540478,1.00854134344,45.3999172375 +39.62,51.003607683,0.00576734368926,20.251285897,13.9424995239,14.3388751178,-0.350839603814,-0.110754172619,1.00651159455,45.3278636569 +39.63,51.0036089371,0.0057693854801,20.2547961048,13.961064094,14.3247873251,-0.351201963389,-0.109770192228,1.00441731615,45.2566647161 +39.64,51.0036101928,0.00577142533616,20.2582997438,13.9774847234,14.3117129028,-0.349525841135,-0.109597541772,1.00512485602,45.1852577496 +39.65,51.00361145,0.00577346321771,20.2617845097,13.9954666592,14.2970675054,-0.347427338256,-0.109484356735,1.00526866735,45.1114936171 +39.66,51.0036127088,0.00577549890941,20.2652625788,14.012857608,14.280970022,-0.348186480345,-0.111394022262,1.00286806726,45.041209204 +39.67,51.0036139693,0.00577753239186,20.2687417265,14.0320850739,14.2660520557,-0.34764306722,-0.112952004254,1.00092821942,44.9700022083 +39.68,51.0036152314,0.00577956366828,20.2722149419,14.05,14.25,-0.347,-0.112,1,44.9 +39.69,51.0036164951,0.00578159241878,20.2756743746,14.0659473465,14.2305912221,-0.344886542728,-0.110973746775,0.997041170533,44.8286049823 +39.7,51.0036177603,0.00578361836882,20.2791233765,14.0851836183,14.210684895,-0.34491384756,-0.110349427226,0.995899491173,44.7617614903 +39.71,51.0036190271,0.00578564140434,20.2825814917,14.1019789114,14.1896751915,-0.346709180911,-0.11086455066,0.995232480096,44.6934071477 +39.72,51.0036202955,0.00578766142045,20.2860435571,14.1181756511,14.1682961286,-0.345703910821,-0.113866243324,0.994173392571,44.6270071473 +39.73,51.0036215653,0.00578967828244,20.2895018325,14.1351994385,14.1453953371,-0.345951162397,-0.112906682856,0.993101469073,44.5589530654 +39.74,51.0036228367,0.00579169220647,20.29295424,14.1531200822,14.1270508095,-0.344530343481,-0.113520783165,0.994648271663,44.4899205362 +39.75,51.0036241095,0.00579370329507,20.296399233,14.1672981226,14.1055894773,-0.344468256112,-0.111441951377,0.991208898517,44.4191011786 +39.76,51.0036253839,0.0057957114315,20.2998391289,14.1861775931,14.0856059658,-0.343510921911,-0.110632121869,0.990473464335,44.3505037017 +39.77,51.0036266599,0.00579771656997,20.3032804235,14.204469226,14.0635020114,-0.344747995423,-0.108473745395,0.990281953359,44.2813437985 +39.78,51.0036279374,0.00579971880059,20.3067188132,14.220649346,14.0447833447,-0.342929933657,-0.108226134565,0.989770225893,44.2138479944 +39.79,51.0036292164,0.005801718152,20.3101411569,14.2362033347,14.0230816255,-0.341538804569,-0.110019467439,0.989860204113,44.1440384978 +39.8,51.0036304968,0.00580371449374,20.3135580943,14.2530575235,14.0025312019,-0.341848688246,-0.110015880476,0.98620508619,44.0748144154 +39.81,51.0036317789,0.00580570793327,20.3169835773,14.2721873305,13.9823383178,-0.343247907986,-0.109465548618,0.983120986026,44.0081808527 +39.82,51.0036330625,0.00580769842446,20.3204160655,14.2888190553,13.9611402395,-0.343249741116,-0.11147786577,0.982226546001,43.9390216038 +39.83,51.0036343478,0.0058096860859,20.3238416111,14.3071712671,13.9426121563,-0.34185938021,-0.110382273379,0.980237717213,43.8696735313 +39.84,51.0036356346,0.00581167103945,20.3272557903,14.3242378816,13.9231249421,-0.340976456213,-0.10950282357,0.981948424771,43.800158674 +39.85,51.0036369229,0.00581365320962,20.3306580467,14.3407679685,13.9035368325,-0.339474819119,-0.109424310401,0.98066685423,43.7315001029 +39.86,51.0036382128,0.00581563251595,20.3340564697,14.3594021469,13.8829201485,-0.340209789429,-0.108763545259,0.980852868843,43.6629682898 +39.87,51.0036395043,0.00581760892706,20.337463174,14.3765572946,13.8628917312,-0.341131067908,-0.108223698461,0.980095227628,43.5940779699 +39.88,51.0036407974,0.00581958245841,20.3408707718,14.3929451237,13.8424917929,-0.340388492797,-0.107806461395,0.976516588078,43.5248861945 +39.89,51.0036420919,0.00582155308879,20.3442776605,14.4099277082,13.8221658605,-0.34098924656,-0.109764206202,0.975887638099,43.4561442337 +39.9,51.003643388,0.00582352091295,20.3476815923,14.4273168974,13.8030959555,-0.339797099539,-0.10968456498,0.974659704081,43.3880790151 +39.91,51.0036446856,0.00582548586232,20.3510770785,14.4444292532,13.7818073388,-0.33930014875,-0.109497213218,0.972905570495,43.3178477253 +39.92,51.0036459847,0.00582744774542,20.3544659426,14.4610528606,13.7600495655,-0.338472676821,-0.109623739272,0.971716386375,43.249602217 +39.93,51.0036472854,0.0058294064307,20.3578484534,14.4797041513,13.7369140132,-0.338029485241,-0.110918667659,0.970778176875,43.1818338255 +39.94,51.0036485877,0.00583136222098,20.3612337317,14.4959791468,13.7194073996,-0.339026157685,-0.109347696543,0.969113909331,43.1115376221 +39.95,51.0036498915,0.00583331533666,20.3646112315,14.5127654319,13.699365886,-0.336473801991,-0.107998742158,0.965959843618,43.0407848187 +39.96,51.0036511969,0.00583526557627,20.367974364,14.5307980038,13.6790310802,-0.33615271179,-0.10772245399,0.968049745336,42.9720290921 +39.97,51.0036525037,0.00583721309324,20.3713334791,14.5467959606,13.6611433136,-0.335670310653,-0.1075893528,0.966840934875,42.9049272214 +39.98,51.0036538121,0.00583915782297,20.3746927422,14.5644313374,13.6399017322,-0.336182302638,-0.109371846425,0.966471671913,42.8355623007 +39.99,51.0036551221,0.00584109969781,20.3780591105,14.5818731566,13.6210643855,-0.337091355137,-0.107241579787,0.966001201687,42.7692721838 +40,51.0036564336,0.00584303873138,20.3814232231,14.5996910509,13.6000137863,-0.335731159337,-0.107069280937,0.963863260425,42.6969330964 +40.01,51.0036577469,0.00584497481372,20.3847750446,14.6195620679,13.5796328723,-0.334633155733,-0.106651332606,0.962477714953,42.6282913895 +40.02,51.0036590616,0.0058469080082,20.3881292073,14.6338119051,13.5594718051,-0.336199365719,-0.110158643386,0.962445494522,42.5591664199 +40.03,51.0036603779,0.00584883826124,20.3914770069,14.6531165186,13.5383388094,-0.333360567756,-0.110606717511,0.961667180896,42.4896454459 +40.04,51.0036616958,0.00585076563722,20.3948117147,14.6687946436,13.5190815767,-0.333580993861,-0.110649234396,0.958659041722,42.4229112439 +40.05,51.0036630151,0.00585269008557,20.3981501728,14.684870991,13.4972385352,-0.334110627973,-0.109433550087,0.955739967557,42.3536885078 +40.06,51.0036643358,0.00585461173718,20.4015006095,14.701208374,13.4798189538,-0.335976696902,-0.10942935011,0.957223353491,42.2864479986 +40.07,51.003665658,0.00585653068751,20.4048491822,14.7183653753,13.4593158162,-0.333737842999,-0.109465724354,0.954344549381,42.2176500241 +40.08,51.0036669819,0.0058584467307,20.40818402,14.736098214,13.4390065177,-0.333229728129,-0.109054542108,0.954818004608,42.1484895881 +40.09,51.0036683073,0.00586035984864,20.4115123433,14.7540600383,13.4182488721,-0.332434924181,-0.109136999642,0.95141566118,42.0803771644 +40.1,51.0036696342,0.00586227007199,20.4148364657,14.7707561224,13.3983702617,-0.332389566428,-0.107868722275,0.951683567659,42.0112174389 +40.11,51.0036709628,0.00586417729991,20.4181482989,14.7900825925,13.376196753,-0.3299770709,-0.105741102033,0.95258543885,41.9441741007 +40.12,51.003672293,0.00586608162252,20.4214452055,14.8064098243,13.3575835006,-0.329404253743,-0.104778595104,0.94995881627,41.8738974926 +40.13,51.0036736248,0.005867983248,20.4247412123,14.8240734095,13.3383323547,-0.329797098074,-0.10427515517,0.950551118872,41.8046714762 +40.14,51.0036749581,0.00586988201044,20.4280467796,14.841536954,13.3173900793,-0.331316371185,-0.105908219341,0.947596532471,41.7335402969 +40.15,51.0036762928,0.00587177785597,20.431351142,14.8572603511,13.2973826526,-0.329556109686,-0.105397620697,0.947699282539,41.6654457613 +40.16,51.0036776292,0.00587367076777,20.4346459342,14.8754692453,13.2762042336,-0.329402325191,-0.105486317548,0.945252960596,41.5973692056 +40.17,51.0036789671,0.00587556065557,20.4379480756,14.8922650049,13.2549295612,-0.331025941747,-0.104850987215,0.943783588903,41.531408029 +40.18,51.0036803065,0.00587744769946,20.4412567493,14.9110226777,13.2362793806,-0.330708814784,-0.103491810261,0.944068046538,41.4647531083 +40.19,51.0036816476,0.00587933205066,20.4445635327,14.9279823847,13.2171275681,-0.330647858399,-0.106775813727,0.94427542661,41.3964819604 +40.2,51.0036829903,0.00588121349275,20.4478654266,14.9452337656,13.195439101,-0.329730929325,-0.106373495345,0.942700748108,41.3247798979 +40.21,51.0036843345,0.00588309178333,20.4511608848,14.9635216827,13.1728844371,-0.329360702991,-0.105479972056,0.941023835465,41.2539248294 +40.22,51.0036856803,0.00588496696121,20.4544427443,14.9807635948,13.1517408632,-0.327011187455,-0.106008759095,0.940463471602,41.1879318681 +40.23,51.0036870277,0.00588683916905,20.4577200574,14.9985126221,13.1311888462,-0.328451442827,-0.105004574158,0.93899955421,41.1175779815 +40.24,51.0036883767,0.00588870861269,20.4609988913,15.0150375614,13.1129350713,-0.32731534506,-0.104800970522,0.937566519282,41.0498247228 +40.25,51.0036897272,0.00589057545821,20.4642745486,15.0334712931,13.0947144382,-0.327816105461,-0.105914988893,0.936604883111,40.9788946419 +40.26,51.0036910792,0.00589243947316,20.4675571345,15.0495998433,13.0731973815,-0.328701081667,-0.106095945396,0.935845182407,40.9133392396 +40.27,51.0036924328,0.00589430047206,20.470826138,15.0658470063,13.0523730883,-0.325099604117,-0.106107673989,0.933920274048,40.8432032434 +40.28,51.0036937878,0.00589615856223,20.474078959,15.0823516177,13.0323623439,-0.3254646078,-0.105698867982,0.932521452002,40.7735737601 +40.29,51.0036951442,0.00589801377752,20.4773323871,15.0989373167,13.0120136325,-0.325221016826,-0.107260049121,0.932510079486,40.7034421108 +40.3,51.0036965023,0.00589986604179,20.4805832266,15.116936496,12.9909336779,-0.324946881249,-0.106478974679,0.931089152056,40.6360632341 +40.31,51.0036978619,0.00590171538749,20.4838302918,15.1344420834,12.9710407172,-0.324466144181,-0.104831455223,0.929386895842,40.5680019945 +40.32,51.003699223,0.0059035618949,20.4870663391,15.1507410401,12.9510876955,-0.322743329867,-0.105132508284,0.927924373652,40.4987944847 +40.33,51.0037005856,0.00590540544352,20.4902873023,15.1663725367,12.929503045,-0.32144929407,-0.106027153684,0.927479191131,40.4279469099 +40.34,51.0037019497,0.00590724603426,20.4934980512,15.1846047995,12.9095629203,-0.320700495355,-0.105037507938,0.92799094333,40.3592913757 +40.35,51.0037033154,0.00590908384452,20.4967059913,15.2022388114,12.8904686053,-0.320887519462,-0.105434214522,0.927603449737,40.2911946685 +40.36,51.0037046826,0.00591091883011,20.499912999,15.2170328714,12.8699082298,-0.320514028621,-0.104780342776,0.924061702795,40.2233684809 +40.37,51.0037060512,0.00591275094312,20.5031245574,15.2340362482,12.8501412197,-0.321797654788,-0.104799461125,0.922666319734,40.157640998 +40.38,51.0037074214,0.00591458019215,20.5063318698,15.2512345209,12.8297015005,-0.319664818019,-0.105922892567,0.922033607232,40.0870662446 +40.39,51.0037087932,0.00591640650779,20.5095279469,15.2709324889,12.8089603473,-0.319550596915,-0.106787138458,0.921438330222,40.0173218519 +40.4,51.0037101666,0.00591822992564,20.5127223167,15.2875569541,12.7890201179,-0.319323367245,-0.10533245453,0.919766742707,39.9488157969 +40.41,51.0037115414,0.00592005052651,20.5159149095,15.3026511269,12.7694136674,-0.319195199735,-0.107100426659,0.918311411819,39.8816645924 +40.42,51.0037129178,0.0059218683499,20.5191045227,15.319817528,12.7500276794,-0.318727439608,-0.10697208694,0.917997681477,39.8138290714 +40.43,51.0037142956,0.00592368315447,20.5222954055,15.3365612458,12.7270334101,-0.31944912056,-0.105968699623,0.914760051062,39.7448469098 +40.44,51.003715675,0.00592549498,20.5254844571,15.355058457,12.7082057814,-0.318361200926,-0.10611922958,0.914969324661,39.674613954 +40.45,51.0037170561,0.00592730402889,20.5286678564,15.373374425,12.6880530713,-0.318318646618,-0.106170996535,0.914125841903,39.6057376523 +40.46,51.0037184388,0.00592911026034,20.5318512788,15.3920099726,12.6686522844,-0.318365838393,-0.107243973881,0.914694542054,39.5359679435 +40.47,51.0037198231,0.00593091352011,20.5350282731,15.4084952997,12.6463347688,-0.317033022809,-0.105644507852,0.913710105703,39.4663795122 +40.48,51.0037212088,0.00593271365442,20.5382029138,15.423697568,12.6247747802,-0.317895125781,-0.105040512249,0.910961663381,39.3988100721 +40.49,51.003722596,0.00593451084998,20.5413780748,15.4405853624,12.6050784751,-0.317137066033,-0.104549016633,0.912376216741,39.3306560169 +40.5,51.0037239848,0.00593630521001,20.5445548979,15.4595635726,12.5849676442,-0.318227549863,-0.102698557619,0.9092871969,39.2626053086 +40.51,51.0037253752,0.00593809660758,20.5477303326,15.4754102848,12.5634893404,-0.316859389271,-0.10445684592,0.907176119855,39.1926354293 +40.52,51.003726767,0.00593988497498,20.5509003771,15.4924599834,12.5424278792,-0.317149514167,-0.1030344942,0.906708826943,39.1242181951 +40.53,51.0037281605,0.00594167044858,20.5540762311,15.5119317208,12.5228643674,-0.318021280091,-0.102795438621,0.906409290241,39.0562059827 +40.54,51.0037295555,0.00594345301579,20.5572459506,15.5283090276,12.5016256633,-0.315922623719,-0.101973961027,0.904591880444,38.9885498093 +40.55,51.0037309522,0.00594523278826,20.5603989618,15.5464130969,12.4836300117,-0.31467961708,-0.101600778414,0.901421565549,38.9201327733 +40.56,51.0037323503,0.00594700977122,20.5635436174,15.5626232121,12.4624643661,-0.314251497732,-0.103423276284,0.901676776493,38.8498720276 +40.57,51.00373375,0.00594878379808,20.5666892867,15.5801253232,12.4421302466,-0.314882365346,-0.106453832457,0.900273909439,38.7823905612 +40.58,51.0037351513,0.00595055493574,20.5698364071,15.5973523232,12.4219036959,-0.314541726887,-0.105331888956,0.898078301675,38.7133882046 +40.59,51.0037365541,0.00595232315524,20.5729745883,15.6141057007,12.4011631988,-0.313094499593,-0.103770516395,0.89840443063,38.6426650071 +40.6,51.0037379584,0.00595408846165,20.5761036462,15.6323327779,12.3810075769,-0.312717078114,-0.105886047293,0.897429978187,38.5743330653 +40.61,51.0037393642,0.00595585094152,20.5792271213,15.646052462,12.361482217,-0.311977947873,-0.104211634441,0.894774558114,38.5049734099 +40.62,51.0037407715,0.00595761063792,20.5823419689,15.6650686589,12.3419311207,-0.310991576611,-0.104594210756,0.892581410165,38.4357091301 +40.63,51.0037421803,0.00595936747914,20.5854553835,15.6818538734,12.3213993583,-0.311691344751,-0.104013750774,0.893841987418,38.3662913026 +40.64,51.0037435908,0.00596112129139,20.5885671238,15.7003957519,12.2994082284,-0.310656712166,-0.104273104639,0.892367313856,38.2995525832 +40.65,51.0037450029,0.00596287212763,20.5916714894,15.71769665,12.2796200337,-0.310216398427,-0.101768150368,0.891904284297,38.2314935511 +40.66,51.0037464164,0.0059646201731,20.594777716,15.7336218312,12.2602295497,-0.311028926742,-0.101755159588,0.890683791143,38.1601926157 +40.67,51.0037478314,0.00596636539118,20.5978857188,15.7506521981,12.2399269418,-0.310571626843,-0.101635646092,0.887911409946,38.093243852 +40.68,51.0037492481,0.00596810776779,20.600987445,15.7693461603,12.2203391771,-0.309773621419,-0.10200532258,0.888414126116,38.0231842989 +40.69,51.0037506663,0.00596984711702,20.6040851244,15.7858735867,12.1974263485,-0.309762249806,-0.10012194786,0.88665610598,37.9555533664 +40.7,51.0037520861,0.00597158335803,20.6071768737,15.8034612725,12.17670393,-0.308587624932,-0.101513246651,0.885870077391,37.886026487 +40.71,51.0037535074,0.00597331667742,20.6102515193,15.8197618161,12.156410593,-0.30634149925,-0.101080597206,0.885446571822,37.8174388742 +40.72,51.0037549302,0.00597504706155,20.6133174574,15.8378904602,12.1354966422,-0.306846119194,-0.102466835973,0.882988515633,37.7494057718 +40.73,51.0037563545,0.00597677458527,20.616389601,15.8526791054,12.116254264,-0.30758258349,-0.10296389486,0.882216234342,37.6787787141 +40.74,51.0037577804,0.00597849917449,20.6194667234,15.8723379057,12.0943000134,-0.307841903678,-0.103685070301,0.878586887233,37.612137769 +40.75,51.0037592079,0.00598022084146,20.6225446694,15.8901646351,12.075229582,-0.307747292263,-0.101610972692,0.879421508643,37.541521143 +40.76,51.0037606371,0.00598193983299,20.6256133074,15.9082938763,12.0567403776,-0.305980318653,-0.101665349497,0.877979126254,37.475600696 +40.77,51.0037620678,0.00598365594078,20.6286653984,15.9243356679,12.034745678,-0.304437880664,-0.0997494661711,0.877963881026,37.4041679475 +40.78,51.0037635,0.00598536912001,20.6317164818,15.9429467253,12.0156271349,-0.305778791705,-0.101243858927,0.87732514538,37.3359268326 +40.79,51.0037649339,0.00598707947374,20.6347765486,15.9606918481,11.9950792757,-0.306234574469,-0.10105512628,0.875345165534,37.2664141823 +40.8,51.0037663693,0.00598878694319,20.6378358144,15.9765434565,11.9751356871,-0.305618580813,-0.102214338099,0.876084153267,37.1990028664 +40.81,51.0037678063,0.00599049155318,20.6408815905,15.994867474,11.954936117,-0.303536649061,-0.1023701704,0.876655382961,37.1289199734 +40.82,51.0037692447,0.00599219321333,20.6439212023,16.0109225126,11.9337238327,-0.304385695033,-0.101521462598,0.876444561595,37.058895349 +40.83,51.0037706847,0.00599389181272,20.6469602167,16.0272901518,11.9119670668,-0.30341720055,-0.100707447161,0.872662998498,36.9905922552 +40.84,51.0037721261,0.00599558736044,20.6499982954,16.045198757,11.8908824314,-0.304198522884,-0.100745273973,0.873349617407,36.9224264149 +40.85,51.0037735693,0.00599727989816,20.6530492435,16.0651697453,11.8697107602,-0.305991111337,-0.101547356675,0.868218419094,36.8559111052 +40.86,51.0037750141,0.00599896959912,20.6560978098,16.0803575159,11.851057777,-0.303722147003,-0.102483341902,0.868968343604,36.7857780166 +40.87,51.0037764604,0.00600065670401,20.6591415214,16.0989952093,11.8332653975,-0.305020177975,-0.10335626003,0.868416931194,36.7174001004 +40.88,51.0037779082,0.00600234103677,20.6621869503,16.1143808558,11.8121406961,-0.30406560245,-0.101733750488,0.866356166365,36.6500757991 +40.89,51.0037793574,0.00600402231764,20.6652300767,16.130284951,11.790420781,-0.304559666272,-0.101999713553,0.865339744475,36.5810027403 +40.9,51.0037808081,0.00600570072783,20.6682719866,16.1472660872,11.7718401455,-0.303822319756,-0.101842589523,0.866581006143,36.512742262 +40.91,51.0037822603,0.00600737635286,20.6713089661,16.1646767237,11.7513207903,-0.303573573441,-0.100546559149,0.866902741982,36.4461486053 +40.92,51.003783714,0.00600904908332,20.6743376689,16.1800712671,11.7312040615,-0.302166985549,-0.100888255762,0.864479471255,36.3763359299 +40.93,51.0037851692,0.00601071883392,20.6773529405,16.1974778469,11.70948768,-0.300887329484,-0.100933701626,0.862385315619,36.307510217 +40.94,51.0037866259,0.00601238558912,20.6803661492,16.2142575781,11.689152403,-0.301754425598,-0.101512508372,0.861211401534,36.2388147064 +40.95,51.0037880842,0.00601404944238,20.6833871129,16.2325680148,11.6687483962,-0.302438302015,-0.101194968886,0.859801883488,36.1693199106 +40.96,51.0037895442,0.00601571050675,20.6863993044,16.25,11.65,-0.3,-0.102,0.859,36.1 +40.97,51.0037910054,0.00601736867789,20.6894004783,16.262458984,11.6281311748,-0.300234786585,-0.103605069172,0.857557805683,36.0290519585 +40.98,51.0037924677,0.00601902383437,20.6923971431,16.2729024265,11.6076782138,-0.299098178836,-0.104027347981,0.858739974583,35.957725273 +40.99,51.003793931,0.00602067612358,20.695384077,16.2863607726,11.5878785314,-0.298288589338,-0.103960079203,0.855005829769,35.8884878814 +41,51.0037953957,0.00602232558475,20.6983743322,16.301178409,11.5679761295,-0.299762463967,-0.105437179252,0.855769760447,35.8178402141 +41.01,51.0037968615,0.00602397198074,20.7013629627,16.3132980507,11.5448474672,-0.297963633312,-0.106956403062,0.854618629601,35.7452020616 +41.02,51.0037983285,0.00602561522712,20.7043413431,16.327782917,11.5237599147,-0.297712435269,-0.104438524518,0.853343921878,35.6763668071 +41.03,51.0037997967,0.00602725541957,20.7073209256,16.3393205624,11.5019743521,-0.298204071741,-0.103918109433,0.852906507942,35.6074463789 +41.04,51.003801266,0.00602889264517,20.7103020914,16.3510019197,11.4821092189,-0.298029084143,-0.104461280955,0.850971277324,35.5372404531 +41.05,51.0038027363,0.00603052711961,20.7132660681,16.3635902614,11.463351622,-0.294766254919,-0.103410127414,0.849376368421,35.4665700365 +41.06,51.0038042078,0.00603215852004,20.7162152536,16.3761803488,11.4389543403,-0.295070856278,-0.104441083092,0.847022516067,35.3966844155 +41.07,51.0038056803,0.00603378670845,20.7191600261,16.3877469858,11.4182591369,-0.293883645728,-0.103832991671,0.845277420479,35.3268132313 +41.08,51.003807154,0.00603541195869,20.7221058517,16.4010968379,11.3977062619,-0.295281468256,-0.104260702223,0.844841591992,35.2565334225 +41.09,51.0038086288,0.00603703408026,20.7250655478,16.4131377975,11.3743368049,-0.296657746348,-0.102673248002,0.844578098419,35.1846924762 +41.1,51.0038101047,0.00603865307485,20.7280276564,16.4246147195,11.3538076523,-0.295763979868,-0.103912827211,0.844725730195,35.1142223147 +41.11,51.0038115817,0.00604026915594,20.7309782594,16.4380963621,11.3334351945,-0.294356605653,-0.103958293974,0.843722324451,35.0452096416 +41.12,51.0038130599,0.00604188230057,20.7339131641,16.4515981654,11.3125836733,-0.29262433932,-0.10337447591,0.842046409191,34.9756783818 +41.13,51.0038145392,0.00604349245466,20.73683174,16.4629096917,11.291451887,-0.291090844184,-0.10411484243,0.841174736365,34.905644945 +41.14,51.0038160195,0.00604509956839,20.7397367401,16.4734459609,11.2699012081,-0.289909168332,-0.104089421824,0.840505420413,34.8353655815 +41.15,51.0038175008,0.00604670363942,20.7426418186,16.4854494785,11.2487363685,-0.291106531175,-0.104961660349,0.842783920996,34.7647495048 +41.16,51.0038189833,0.00604830481083,20.7455459079,16.4994561093,11.2291944548,-0.289711343421,-0.106020509996,0.840198067436,34.6966958011 +41.17,51.003820467,0.00604990306417,20.7484292502,16.5121071494,11.2077704203,-0.286957106928,-0.108156990078,0.838815770017,34.6267643907 +41.18,51.0038219518,0.0060514983775,20.751307307,16.5240882694,11.1879207562,-0.288654247522,-0.105310205164,0.837553905032,34.5572912592 +41.19,51.0038234377,0.00605309061032,20.7541956256,16.537741323,11.1645241617,-0.289009486931,-0.103326872507,0.833466637675,34.4887275576 +41.2,51.0038249248,0.0060546796754,20.7570800583,16.5499419229,11.1434499064,-0.287877038904,-0.10443652284,0.835372936884,34.4152670918 +41.21,51.0038264131,0.0060562658583,20.7599505128,16.5646301228,11.124062227,-0.286213875172,-0.103650977553,0.833061735788,34.3443061419 +41.22,51.0038279027,0.00605784906366,20.7628070438,16.576665995,11.1016493038,-0.285092312953,-0.105525748353,0.835031467976,34.2746411106 +41.23,51.0038293932,0.00605942905446,20.7656655671,16.5874749521,11.0789341279,-0.286612351648,-0.106681896142,0.831450259625,34.2055269663 +41.24,51.0038308847,0.00606100596073,20.7685292149,16.5989880808,11.0583466009,-0.286117219364,-0.104939734506,0.830162436906,34.134364353 +41.25,51.0038323774,0.00606257986394,20.7713823541,16.6124974846,11.0367751484,-0.284510603854,-0.106023032463,0.829266552455,34.0652910377 +41.26,51.0038338712,0.00606415082806,20.7742289276,16.6236449828,11.017085862,-0.284804112834,-0.104741056253,0.826819445152,33.99402648 +41.27,51.0038353661,0.00606571898485,20.7770703827,16.6380080822,10.9973639081,-0.283486903063,-0.104361614956,0.825928169191,33.9238628696 +41.28,51.0038368623,0.00606728416118,20.7799090834,16.6508767277,10.9752441117,-0.284253224121,-0.10436974323,0.824507770693,33.8525348354 +41.29,51.0038383595,0.00606884626375,20.7827456568,16.6632739166,10.9542125836,-0.283061461791,-0.105761424612,0.825668948516,33.7812714943 +41.3,51.003839858,0.00607040533864,20.7855728196,16.6763550725,10.9327394779,-0.282371101335,-0.105019305487,0.823735902812,33.7116170944 +41.31,51.0038413575,0.00607196133745,20.7883860072,16.6886592113,10.9110286687,-0.280266409009,-0.105385486847,0.821991316561,33.6421348341 +41.32,51.0038428583,0.00607351427006,20.7911928765,16.7030569936,10.8896941039,-0.281107453918,-0.105120233332,0.821899934072,33.5724479232 +41.33,51.0038443604,0.00607506420938,20.7940065918,16.7171538593,10.8690069462,-0.28163561024,-0.106045998349,0.822054015925,33.5005064732 +41.34,51.0038458636,0.00607661122581,20.7968229242,16.7285638613,10.8486606124,-0.281630864059,-0.105543573149,0.819461745793,33.4316391075 +41.35,51.0038473679,0.00607815536548,20.7996365969,16.7423524919,10.8286211375,-0.28110368779,-0.104146563867,0.815882823412,33.3608678827 +41.36,51.0038488733,0.00607969653763,20.8024475851,16.7539077392,10.8070005217,-0.281093957951,-0.104300210243,0.815479889634,33.2901373964 +41.37,51.0038503799,0.00608123459155,20.8052609808,16.7671664749,10.7848455887,-0.281585173178,-0.105868472182,0.812956311021,33.21980603 +41.38,51.0038518876,0.00608276958383,20.8080742487,16.778886744,10.7640191084,-0.281068401468,-0.104131252664,0.813314636838,33.1492463768 +41.39,51.0038533963,0.00608430159874,20.8108811665,16.7885396778,10.7430473729,-0.280315157355,-0.105641702178,0.81158839146,33.0806471228 +41.4,51.003854906,0.00608583066683,20.813682958,16.8029602372,10.7226497226,-0.280043155982,-0.105567326191,0.809917329047,33.0086105072 +41.41,51.0038564169,0.00608735685838,20.8164851067,16.8133829904,10.702664677,-0.280386567005,-0.105719309492,0.808257194769,32.9399027746 +41.42,51.0038579288,0.00608887996162,20.8192878938,16.8260031778,10.6792939629,-0.280170856164,-0.104144284461,0.808096942247,32.8691659215 +41.43,51.0038594418,0.00609039990453,20.8220775249,16.8381422648,10.6582981161,-0.27775536663,-0.102953402098,0.807561726716,32.7983012521 +41.44,51.003860956,0.00609191690145,20.8248524702,16.8517269,10.6379361304,-0.277233701852,-0.10563789017,0.808178370682,32.7286467054 +41.45,51.0038624713,0.00609343090569,20.8276234065,16.8625937299,10.6162849748,-0.276953560595,-0.107421414177,0.807688453527,32.6603818372 +41.46,51.0038639876,0.00609494195288,20.8303854083,16.8762162766,10.5964230246,-0.275446785032,-0.108081416309,0.806582927515,32.5877148861 +41.47,51.0038655051,0.0060964501617,20.8331414803,16.8878544257,10.576438249,-0.275767620213,-0.107189875464,0.805810620147,32.5188599572 +41.48,51.0038670237,0.00609795534664,20.8358909867,16.900414703,10.5539717765,-0.274133652684,-0.108534960042,0.803695461306,32.4460025821 +41.49,51.0038685434,0.00609945756188,20.8386353849,16.9120610824,10.534747644,-0.274746002376,-0.110658642584,0.80354609558,32.3771477552 +41.5,51.0038700642,0.00610095680014,20.8413757486,16.9259514644,10.5121790913,-0.273326726177,-0.109617807003,0.800489764854,32.3056284887 +41.51,51.0038715863,0.00610245296715,20.8441183338,16.9391609121,10.4916315665,-0.275190313221,-0.109114315705,0.800462119139,32.2366475443 +41.52,51.0038731095,0.00610394612719,20.8468539722,16.9511628186,10.4699651975,-0.27193736796,-0.107956189512,0.800042213496,32.1666691459 +41.53,51.0038746337,0.00610543630583,20.8495705467,16.9635466294,10.4497767759,-0.271377542595,-0.106991725284,0.798566502879,32.0976124189 +41.54,51.0038761591,0.00610692352436,20.8522831915,16.9753993897,10.4284094122,-0.271151409261,-0.108164933408,0.797533286145,32.0265410714 +41.55,51.0038776855,0.00610840766963,20.855001328,16.9869129275,10.4066322086,-0.272475894586,-0.106302447264,0.797800701894,31.9548444835 +41.56,51.0038792131,0.00610988879303,20.8577184212,17.0008440558,10.3859865834,-0.270942748126,-0.106166701251,0.794557138947,31.8840897365 +41.57,51.0038807418,0.00611136692884,20.8604292765,17.014049159,10.3646906175,-0.271228302094,-0.105473557725,0.791497987934,31.8139753642 +41.58,51.0038822718,0.0061128420841,20.8631347172,17.0272455303,10.3441436257,-0.269859846377,-0.107454971616,0.79100337096,31.7433833267 +41.59,51.0038838028,0.00611431420991,20.8658360969,17.0375338518,10.3221612165,-0.270416087766,-0.1074955165,0.788751761524,31.6746210831 +41.6,51.0038853349,0.00611578327833,20.8685413237,17.0504775179,10.3012221769,-0.270629267759,-0.106868694253,0.789819789854,31.60086182 +41.61,51.0038868681,0.00611724939323,20.8712465203,17.0628048015,10.280697795,-0.270410055327,-0.106192087564,0.790251985331,31.5298931592 +41.62,51.0038884025,0.00611871242987,20.8739483124,17.07757492,10.2580076626,-0.269948367764,-0.108620354058,0.788915336579,31.4607252158 +41.63,51.0038899381,0.00612017232712,20.8766522638,17.0886238049,10.2366250332,-0.270841916284,-0.108156480882,0.787491299535,31.3922057931 +41.64,51.0038914746,0.00612162919398,20.8793540231,17.0993732952,10.2154650829,-0.269509948316,-0.10915757992,0.787602932784,31.3208272889 +41.65,51.0038930122,0.00612308306174,20.8820407067,17.1100907258,10.1945218729,-0.267826754564,-0.107601141186,0.787673192005,31.2499943355 +41.66,51.0038945508,0.00612453402553,20.8847207137,17.1234434754,10.1746973853,-0.268174651235,-0.105746386074,0.785744174571,31.181079439 +41.67,51.0038960905,0.00612598217902,20.8874003857,17.1361099591,10.1550689578,-0.267759752198,-0.106434084951,0.78253278107,31.1116381101 +41.68,51.0038976315,0.00612742739115,20.8900775934,17.1500320328,10.1334047617,-0.267681790014,-0.106021880976,0.781261014705,31.0390865596 +41.69,51.0038991737,0.00612886953002,20.8927572598,17.1626560169,10.1119245499,-0.268251489525,-0.10499865519,0.780275840465,30.9678338204 +41.7,51.0039007169,0.00613030849448,20.8954334261,17.1736838177,10.088840626,-0.266981766364,-0.104551735961,0.779040257476,30.8967976298 +41.71,51.0039022611,0.00613174437963,20.8981060972,17.183993441,10.0686951582,-0.267552454844,-0.104980680559,0.776931850623,30.8271761748 +41.72,51.0039038063,0.00613317738641,20.9007724052,17.1977549711,10.0484322,-0.265709147869,-0.105295830399,0.777694766998,30.7580972007 +41.73,51.0039053529,0.00613460752971,20.9034205993,17.2122828544,10.0284958741,-0.263929664995,-0.106105416113,0.775611685995,30.6865405337 +41.74,51.0039069006,0.00613603470876,20.9060632141,17.2237898663,10.0068182738,-0.264593310657,-0.106280390098,0.775673575363,30.6156040797 +41.75,51.0039084493,0.00613745889817,20.9087091514,17.2350659782,9.98652532548,-0.264594141661,-0.107234713505,0.775110803714,30.5438968418 +41.76,51.0039099992,0.00613887995426,20.9113471007,17.2490037959,9.96283081712,-0.262995709339,-0.108407704226,0.774182403926,30.4744151571 +41.77,51.0039115501,0.00614029766848,20.9139724776,17.2589864791,9.93961023468,-0.262079677672,-0.108706073664,0.772693046498,30.402348789 +41.78,51.0039131021,0.0061417120988,20.9166033935,17.2718604134,9.91672937183,-0.264103507526,-0.109622243119,0.771882016493,30.3323023659 +41.79,51.0039146553,0.00614312346175,20.9192275153,17.2872992883,9.89654877156,-0.26072084343,-0.11060509858,0.767396480999,30.2621453858 +41.8,51.0039162097,0.00614453199499,20.9218365931,17.2983032555,9.87700395729,-0.261094721492,-0.110550965079,0.768915895356,30.1927662101 +41.81,51.0039177653,0.00614593765286,20.924434305,17.311619478,9.8561825585,-0.258447655761,-0.108723367458,0.768397645387,30.1233521936 +41.82,51.0039193218,0.00614734017921,20.9270126909,17.3219800808,9.83304185277,-0.257229522743,-0.10981538197,0.765403617305,30.0526421415 +41.83,51.0039208795,0.00614873962849,20.9295791343,17.3346479025,9.8129846443,-0.256059164607,-0.108927161957,0.763992853557,29.9801846146 +41.84,51.0039224383,0.00615013616991,20.9321483861,17.3479226242,9.79221963405,-0.257791198294,-0.108498531782,0.764538122665,29.9108714844 +41.85,51.0039239982,0.00615152983999,20.9347253587,17.3595022318,9.77267487034,-0.25760332222,-0.108768531261,0.763888035197,29.8406962723 +41.86,51.0039255592,0.00615292053852,20.937301774,17.37306645,9.75050331876,-0.257679726835,-0.109966877204,0.759025147031,29.771634004 +41.87,51.0039271214,0.00615430814069,20.9398829707,17.3866715221,9.72920624752,-0.258559608152,-0.110063111605,0.759779103395,29.7016508135 +41.88,51.0039286849,0.00615569282645,20.9424685458,17.3993241746,9.70956082504,-0.258555427012,-0.109771251832,0.758793740517,29.6304390631 +41.89,51.0039302495,0.00615707455732,20.9450618825,17.4132942102,9.68772392261,-0.260111906588,-0.111193365124,0.758474705378,29.5600675734 +41.9,51.0039318153,0.00615845321906,20.9476483009,17.4246228543,9.66647427683,-0.257171782774,-0.110231427541,0.755321828573,29.4913134559 +41.91,51.0039333822,0.00615982897408,20.9502212086,17.4387112048,9.64691772266,-0.257409746849,-0.108008300254,0.756233158719,29.4210539165 +41.92,51.0039349503,0.00616120170821,20.9527980623,17.4509141224,9.6240652533,-0.257961001859,-0.109540275857,0.755641441497,29.3494420311 +41.93,51.0039365195,0.00616257119061,20.9553738382,17.4630424951,9.60126787616,-0.257194168764,-0.109982952078,0.754294178497,29.2791954746 +41.94,51.0039380897,0.00616393753205,20.957947376,17.4742066167,9.57997064195,-0.257513389855,-0.112185054649,0.752780999263,29.2092674454 +41.95,51.0039396611,0.00616530088191,20.9605184061,17.4888227879,9.55927032449,-0.256692628857,-0.111549353833,0.751847703406,29.1372156631 +41.96,51.0039412336,0.00616666124629,20.9630802656,17.5003182284,9.5380585673,-0.255679278944,-0.111029678154,0.751816062221,29.0672015698 +41.97,51.0039428072,0.0061680185343,20.9656462631,17.5104619381,9.51608240872,-0.257520223543,-0.111970804337,0.75156280282,28.9982748493 +41.98,51.0039443818,0.00616937285311,20.968216596,17.524453526,9.4963750813,-0.256546340912,-0.10894069502,0.751527330112,28.9276917437 +41.99,51.0039459577,0.00617072417284,20.9707752518,17.5382461647,9.47397964821,-0.255184829496,-0.110332389273,0.750519832399,28.8580075729 +42,51.0039475347,0.00617207248018,20.9733296529,17.5512759838,9.45408526127,-0.2556953943,-0.111749592592,0.747154946241,28.7882595636 +42.01,51.003949113,0.0061734177702,20.9758876546,17.5640557852,9.43162072129,-0.255904944099,-0.114701958934,0.745847375255,28.7180936732 +42.02,51.0039506923,0.00617476002878,20.9784461926,17.5760027708,9.41152811996,-0.255802655387,-0.113087077346,0.745524204523,28.6462757309 +42.03,51.0039522729,0.00617609922398,20.9810026797,17.5906896733,9.38861516547,-0.255494768327,-0.112432315625,0.743852194181,28.5759550949 +42.04,51.0039538545,0.00617743537288,20.9835458482,17.6002860567,9.36876232041,-0.253138934981,-0.113869711391,0.742415079205,28.504200306 +42.05,51.0039554373,0.00617876873824,20.9860712062,17.6153816629,9.34953806853,-0.251932654249,-0.112811437688,0.741500543483,28.4352921012 +42.06,51.0039570212,0.00618009925108,20.9885874941,17.6277995037,9.32871690507,-0.251324926068,-0.113689846286,0.740309997081,28.3666817346 +42.07,51.0039586062,0.00618142682119,20.9910919403,17.6379735613,9.30822637415,-0.249564316391,-0.11304387339,0.740002148582,28.2962988872 +42.08,51.0039601923,0.00618275145707,20.9936012534,17.651046041,9.28752435248,-0.252298291898,-0.112008125922,0.737549488769,28.225909913 +42.09,51.0039617794,0.00618407322574,20.9961167261,17.6612012233,9.26797478384,-0.250796248545,-0.112255126459,0.735689158489,28.1539785736 +42.1,51.0039633675,0.00618539207017,20.9986239919,17.6742082846,9.24647202018,-0.250656917369,-0.111565875628,0.735682356763,28.0830291313 +42.11,51.0039649569,0.00618670797982,21.0011292685,17.6894009234,9.22677474915,-0.250398407328,-0.110649031148,0.734828559955,28.0142269902 +42.12,51.0039665474,0.00618802094278,21.0036321981,17.7003804058,9.20510444052,-0.25018750862,-0.110156105316,0.733400584933,27.9432590238 +42.13,51.0039681391,0.00618933078406,21.0061332454,17.7137917191,9.18295088045,-0.250021954893,-0.108892852639,0.731023552168,27.8734289185 +42.14,51.003969732,0.00619063753268,21.0086305284,17.7269216742,9.1616879268,-0.249434645807,-0.1112145424,0.730113682183,27.8038597931 +42.15,51.003971326,0.00619194139979,21.0111193355,17.7402807836,9.14249839517,-0.248326771001,-0.111488388042,0.728508921682,27.7352150097 +42.16,51.0039729212,0.00619324231974,21.0136038402,17.750989848,9.12031404122,-0.248574180671,-0.111654022785,0.728463503942,27.6648306525 +42.17,51.0039745174,0.00619454015502,21.0160880782,17.7640120756,9.09919393689,-0.248273402976,-0.109633283094,0.728741675619,27.5918622849 +42.18,51.0039761146,0.00619583492313,21.0185718894,17.7743706969,9.07725537438,-0.248488835481,-0.111346591054,0.725506177835,27.5215936995 +42.19,51.0039777129,0.00619712657208,21.0210507016,17.7874462589,9.05540531097,-0.247273604214,-0.111662248619,0.725580083071,27.4521569228 +42.2,51.0039793124,0.00619841514323,21.0235251118,17.8002574065,9.03404741894,-0.247608449344,-0.111945889998,0.72444481252,27.3821376234 +42.21,51.0039809129,0.00619970076188,21.0259996123,17.811357973,9.01395633274,-0.247291640577,-0.112069459221,0.72251234223,27.310793651 +42.22,51.0039825145,0.00620098350739,21.0284751453,17.8243909901,8.99371271904,-0.247814970608,-0.112484120359,0.721558062075,27.2385667489 +42.23,51.0039841173,0.00620226323718,21.0309400365,17.83707836,8.97161979299,-0.245163254626,-0.111970064369,0.722633987775,27.1695513086 +42.24,51.0039857212,0.00620353985321,21.0333958527,17.85,8.95,-0.246,-0.112,0.72,27.1 +42.25,51.0039873262,0.00620481323486,21.0358567847,17.8590614443,8.92621373414,-0.246186399601,-0.112362430788,0.720670852947,27.0293422017 +42.26,51.0039889318,0.00620608336803,21.0383103616,17.8664221497,8.90439596325,-0.244528966976,-0.114665429949,0.7176421689,26.9589930588 +42.27,51.0039905382,0.00620735034985,21.040752386,17.8747211236,8.88197331991,-0.243875927692,-0.113294826184,0.715490181085,26.8856657463 +42.28,51.0039921453,0.00620861418335,21.0431963113,17.8837607852,8.86019810164,-0.244909120255,-0.112925038463,0.713254688518,26.8133252281 +42.29,51.0039937532,0.00620987480306,21.0456400678,17.8907876432,8.83685622129,-0.243842182063,-0.112322006608,0.711802649965,26.7421357844 +42.3,51.0039953618,0.00621113212682,21.0480812406,17.8993398567,8.8139277588,-0.244392385143,-0.112121443795,0.712552719408,26.6689633249 +42.31,51.0039969711,0.00621238623685,21.0505302204,17.9075480647,8.79173997381,-0.245403563239,-0.112615410508,0.709833295009,26.5970673098 +42.32,51.0039985812,0.00621363727216,21.0529764747,17.9173246911,8.7707632561,-0.243847295397,-0.11181366226,0.711004612674,26.5248592949 +42.33,51.0040001922,0.00621488525124,21.0554065415,17.9268644,8.74883469537,-0.24216607153,-0.111844576723,0.708399126072,26.4524154425 +42.34,51.004001804,0.00621612999815,21.0578260404,17.9346207079,8.72538846359,-0.241733706671,-0.111589559395,0.707386429861,26.3814159685 +42.35,51.0040034165,0.00621737137693,21.06024084,17.9430462966,8.70155078905,-0.241226211834,-0.112147237676,0.706284009342,26.3106799716 +42.36,51.0040050297,0.00621860950184,21.0626574458,17.9516759995,8.67970899647,-0.242094962323,-0.10991723393,0.706839686706,26.2378745954 +42.37,51.0040066439,0.00621984446324,21.0650657789,17.9621637022,8.65713954906,-0.239571646769,-0.109642752974,0.706468538572,26.1653799749 +42.38,51.0040082588,0.00622107606871,21.067468914,17.9705870282,8.63259671463,-0.241055366002,-0.110979740194,0.704822239185,26.0932774739 +42.39,51.0040098745,0.0062223044858,21.0698908312,17.977388366,8.61237921371,-0.243328080443,-0.110663775213,0.704544644813,26.0243962382 +42.4,51.0040114909,0.00622352972838,21.0723111065,17.98648604,8.58803116869,-0.240726978892,-0.111949129026,0.70064760288,25.9512482672 +42.41,51.004013108,0.00622475164788,21.0747111907,17.994643972,8.56572797659,-0.239289867323,-0.113608160264,0.701979486902,25.8803373299 +42.42,51.0040147259,0.00622597039728,21.077093353,18.0036115555,8.54352754243,-0.237142580222,-0.111106792157,0.699829151426,25.8084273947 +42.43,51.0040163447,0.00622718587031,21.0794699128,18.0136257751,8.51973260768,-0.238169398114,-0.11230108608,0.697496620386,25.7375855663 +42.44,51.0040179642,0.00622839804902,21.0818493189,18.0196414821,8.49727991617,-0.23771181982,-0.110571326733,0.697757132816,25.6661297745 +42.45,51.0040195843,0.00622960706235,21.0842251457,18.0267437738,8.47529534578,-0.237453532177,-0.11191785303,0.696037009644,25.5940785404 +42.46,51.0040212052,0.00623081285928,21.0866053953,18.0384809056,8.45212623239,-0.238596387815,-0.112207671943,0.693941636926,25.5199205243 +42.47,51.0040228271,0.00623201527451,21.0889736756,18.0476065222,8.42782132532,-0.235059666276,-0.112041761255,0.694923602803,25.4487622695 +42.48,51.0040244496,0.00623321439877,21.091327828,18.0538502583,8.40592577924,-0.235770819364,-0.109938305378,0.692024361423,25.3780180904 +42.49,51.0040260728,0.0062344104116,21.0936860013,18.062418283,8.38414135945,-0.235863832767,-0.109618402126,0.691056180172,25.306655542 +42.5,51.0040276968,0.00623560318102,21.096038935,18.070539538,8.36039298321,-0.234722916443,-0.11036107412,0.690568656169,25.2363857595 +42.51,51.0040293216,0.00623679252693,21.0983895524,18.079803494,8.33608022547,-0.235400559999,-0.10979052893,0.689531903614,25.1642848305 +42.52,51.0040309472,0.00623797866031,21.1007404075,18.0894244492,8.31529379091,-0.234770471942,-0.109011832404,0.688962665521,25.0920823539 +42.53,51.0040325736,0.00623916168267,21.1030799946,18.0976564525,8.29240611182,-0.233146949296,-0.109960809887,0.686147173836,25.0223225996 +42.54,51.0040342008,0.00624034148158,21.1054073996,18.107807342,8.27004113653,-0.232334040098,-0.110345675269,0.687215010189,24.9505586874 +42.55,51.0040358289,0.00624151799982,21.1077225535,18.1174941208,8.24635039174,-0.230696731275,-0.110613640331,0.685857426545,24.8739361752 +42.56,51.0040374578,0.00624269122162,21.1100367235,18.1239834258,8.2237638375,-0.232137280972,-0.110388970728,0.683987484726,24.8015660943 +42.57,51.0040390873,0.00624386111353,21.1123545569,18.1326415423,8.19960369148,-0.231429388969,-0.110208490204,0.682235062833,24.7281409021 +42.58,51.0040407176,0.00624502779921,21.1146775055,18.1411554191,8.17875292826,-0.233160329257,-0.110755208217,0.682624777661,24.6577890398 +42.59,51.0040423488,0.0062461913727,21.1170000298,18.1519450716,8.15591325581,-0.231344544571,-0.107818446787,0.682168935404,24.5873046609 +42.6,51.0040439808,0.00624735176042,21.1193142,18.1597315338,8.13402923656,-0.231489484816,-0.111035095298,0.68101241766,24.5167513947 +42.61,51.0040456136,0.00624850901967,21.1216219682,18.1700827092,8.11199418705,-0.230064153878,-0.112067545233,0.678814618279,24.4479154953 +42.62,51.0040472472,0.00624966299569,21.1239187886,18.1773453715,8.08793742647,-0.229299936364,-0.110294855894,0.677615036239,24.3750502275 +42.63,51.0040488815,0.00625081354403,21.1262122938,18.1861514087,8.06387466626,-0.22940109877,-0.111530002084,0.673072869078,24.3017623478 +42.64,51.0040505166,0.00625196093921,21.1285018516,18.1931557173,8.04367161811,-0.228510472952,-0.110818151112,0.673167358826,24.2283757379 +42.65,51.0040521524,0.00625310527669,21.1307902422,18.2035008372,8.02094907771,-0.229167630523,-0.108743671094,0.673117764898,24.1553742996 +42.66,51.0040537891,0.00625424646294,21.1330738368,18.2114873096,7.99943291826,-0.227551289201,-0.109835521623,0.670630819562,24.0805424951 +42.67,51.0040554264,0.00625538441281,21.1353419834,18.2202022324,7.97551506341,-0.226078042866,-0.109730013044,0.669871321589,24.0097796589 +42.68,51.0040570646,0.00625651906824,21.1376085882,18.2280215192,7.95318378088,-0.227242918213,-0.10875140358,0.669322283785,23.9375677075 +42.69,51.0040587035,0.00625765038255,21.1398798806,18.2368028529,7.92861069219,-0.227015557644,-0.108569214836,0.667122133735,23.8680762021 +42.7,51.0040603431,0.00625877845867,21.1421474964,18.2454754919,7.90772450747,-0.226507603673,-0.10681138948,0.667463738139,23.7958004633 +42.71,51.0040619836,0.00625990352312,21.144408665,18.2532122176,7.88633103796,-0.225726109434,-0.106935126411,0.666645715755,23.721531603 +42.72,51.0040636247,0.00626102537555,21.1466636532,18.2624227463,7.86263260544,-0.225271530186,-0.106946952278,0.664822141447,23.6511365327 +42.73,51.0040652667,0.00626214395217,21.1489172444,18.2712986566,7.84034351658,-0.225446722663,-0.107303744436,0.66504901732,23.5801406651 +42.74,51.0040669095,0.00626325922154,21.1511690156,18.2792662221,7.81620358621,-0.224907499429,-0.10753428355,0.662942233304,23.5064447146 +42.75,51.0040685529,0.00626437124259,21.1534137221,18.2879807556,7.79474198617,-0.224033816345,-0.109336464019,0.663313005908,23.4339533442 +42.76,51.0040701973,0.00626548001907,21.1556592104,18.2978929139,7.77065455938,-0.225063829927,-0.106481485741,0.661346766245,23.3618999591 +42.77,51.0040718423,0.00626658537419,21.1579006316,18.3036200047,7.74671131825,-0.223220421493,-0.106583526112,0.65938300923,23.2915329907 +42.78,51.004073488,0.00626768745955,21.1601287889,18.3123899109,7.72475185122,-0.222411030682,-0.108110454364,0.65980826919,23.2189804345 +42.79,51.0040751345,0.00626878643283,21.1623517584,18.3212245065,7.70302232999,-0.222182873651,-0.106311233845,0.657504729798,23.1482124987 +42.8,51.0040767818,0.00626988235265,21.1645733618,18.3315714035,7.68188575283,-0.222137796202,-0.105745076866,0.656842155655,23.0763853769 +42.81,51.00407843,0.00627097525053,21.1667893963,18.3396370592,7.66059880933,-0.221069111864,-0.106963106221,0.654068932946,23.0037574774 +42.82,51.0040800789,0.00627206502682,21.1689998889,18.3499754267,7.63806311347,-0.221029399662,-0.105103690166,0.65388560822,22.9320257821 +42.83,51.0040817287,0.0062731515929,21.1712055503,18.3572222956,7.61553224134,-0.220102894209,-0.104116313683,0.653277409107,22.8617342598 +42.84,51.0040833791,0.00627423492254,21.1734025736,18.3637919183,7.59262842996,-0.21930175728,-0.103498661262,0.65212186676,22.7885150416 +42.85,51.0040850303,0.00627531492362,21.1755925872,18.3740787183,7.56880414782,-0.218700967329,-0.102940788091,0.65115091464,22.7174808126 +42.86,51.0040866822,0.00627639160537,21.1777785104,18.3815069783,7.54602996549,-0.218483667855,-0.103233107308,0.647782182417,22.6461704493 +42.87,51.004088335,0.00627746503661,21.1799517377,18.3917092715,7.52317177045,-0.216161799226,-0.101813012259,0.647733366754,22.5751545804 +42.88,51.0040899886,0.00627853518716,21.1821220631,18.3997397431,7.4999740068,-0.217903276152,-0.104834824253,0.647627058706,22.5012608909 +42.89,51.004091643,0.0062796019999,21.1843076222,18.410142046,7.4763138802,-0.219208555275,-0.105632434068,0.6465697389,22.4287703233 +42.9,51.0040932981,0.00628066550628,21.1864961602,18.4175091944,7.45355775389,-0.218499040685,-0.102712704845,0.644826582629,22.3570204939 +42.91,51.0040949541,0.00628172586224,21.188669802,18.4267081775,7.43208653125,-0.216229318174,-0.103032325147,0.646866004661,22.2860939758 +42.92,51.0040966107,0.00628278306919,21.190837358,18.4334217525,7.40935041237,-0.217281884325,-0.101605078649,0.644839206212,22.2128409719 +42.93,51.004098268,0.00628383712507,21.19301862,18.4403754036,7.3878502314,-0.218970515992,-0.102850913494,0.643169154427,22.1424615105 +42.94,51.004099926,0.00628488806338,21.1952071576,18.4483802793,7.36558438543,-0.218736996394,-0.101665629334,0.642242471314,22.0699296323 +42.95,51.0041015848,0.00628593574007,21.1973820172,18.4595578947,7.34206191019,-0.21623492531,-0.100355663647,0.640272280684,21.9968858937 +42.96,51.0041032444,0.00628698005745,21.1995484979,18.4678873638,7.31842462893,-0.217061208025,-0.100719982109,0.641268338779,21.923871438 +42.97,51.0041049049,0.00628802102403,21.2017254724,18.4763657018,7.29502179636,-0.218333705192,-0.0994563601431,0.638462437764,21.8513953993 +42.98,51.0041065661,0.0062890586356,21.2039059763,18.4849810099,7.27132535521,-0.217767059327,-0.101481414401,0.638111459747,21.7800742488 +42.99,51.0041082281,0.00629009300712,21.2060720161,18.494063231,7.24953629656,-0.215440903708,-0.101309347927,0.635507456431,21.7097856827 +43,51.0041098908,0.00629112423559,21.2082254798,18.5021653743,7.22720168553,-0.215251835578,-0.102054918237,0.635730914719,21.6385524932 +43.01,51.0041115543,0.00629215234907,21.2103788405,18.5100902336,7.20580640075,-0.215420318927,-0.103923689522,0.634001776786,21.5650611006 +43.02,51.0041132185,0.00629317737654,21.2125309509,18.5181405889,7.18387883483,-0.215001755913,-0.10378217708,0.631727723455,21.4950991148 +43.03,51.0041148836,0.00629419910291,21.2146736738,18.5298663554,7.159463841,-0.213542815724,-0.10490356841,0.630643024491,21.4245595589 +43.04,51.0041165496,0.00629521752516,21.2168027821,18.5373583251,7.13749395815,-0.21227883943,-0.102393984244,0.628930020442,21.352026689 +43.05,51.0041182162,0.00629623271657,21.2189158567,18.5443332328,7.11410778408,-0.210336098838,-0.100464343955,0.629391189299,21.2803426716 +43.06,51.0041198836,0.00629724468916,21.2210218802,18.5548280233,7.09230650714,-0.210868593478,-0.102091559403,0.629710695862,21.2053529019 +43.07,51.0041215519,0.00629825362306,21.2231416869,18.5644117078,7.07144920784,-0.213092751276,-0.101135470226,0.627490822832,21.1317185847 +43.08,51.004123221,0.00629925927775,21.2252683366,18.5722701391,7.04627115536,-0.212237174832,-0.101457036367,0.626461799019,21.0614077037 +43.09,51.0041248908,0.00630026148149,21.2273865948,18.5814562457,7.02300327509,-0.211414468163,-0.100074218922,0.625363003282,20.9892068189 +43.1,51.0041265615,0.00630126046417,21.2294913208,18.5892927118,7.0010523332,-0.209530741667,-0.100041638376,0.623630122367,20.9175254991 +43.11,51.0041282329,0.00630225623803,21.2315810338,18.5990378339,6.97795621135,-0.208411851709,-0.100833198701,0.622085642441,20.8486901158 +43.12,51.0041299051,0.00630324882494,21.2336637769,18.6070224856,6.95631227595,-0.208136776905,-0.101790080421,0.619310148057,20.776321743 +43.13,51.0041315781,0.00630423821436,21.235741379,18.6181769675,6.93306841584,-0.207383635573,-0.1010119336,0.618395201336,20.7041857178 +43.14,51.004133252,0.00630522442893,21.2378104941,18.6242293872,6.9117421288,-0.206439377209,-0.10242105398,0.616317234166,20.6312337259 +43.15,51.0041349264,0.006306207669,21.2398751015,18.6307884091,6.89131093633,-0.206482104934,-0.102369572106,0.615175162995,20.5595756249 +43.16,51.0041366015,0.00630718772874,21.241937041,18.6408261296,6.86709507544,-0.20590580769,-0.101514140625,0.614365553523,20.4895988826 +43.17,51.0041382775,0.00630816441941,21.2439915893,18.6505627587,6.84401419965,-0.205003848565,-0.101668032978,0.612907137712,20.416958036 +43.18,51.0041399544,0.00630913792558,21.2460475226,18.6580436816,6.82238972916,-0.206182804293,-0.100260966715,0.612077965043,20.3448250483 +43.19,51.0041416319,0.00631010831613,21.2481135804,18.6662987485,6.80027538819,-0.207028751117,-0.0999831653233,0.610013486071,20.2726758401 +43.2,51.0041433102,0.00631107540582,21.2501724985,18.6754476693,6.77605085461,-0.204754876799,-0.100502252518,0.608952460209,20.2019895747 +43.21,51.0041449892,0.00631203907661,21.2522182207,18.6831867394,6.75227910714,-0.204389559771,-0.0996723269789,0.607134673337,20.1294546316 +43.22,51.0041466691,0.00631299946219,21.2542609421,18.6927959884,6.72993163674,-0.204154717642,-0.0991058635649,0.604648256331,20.0551997006 +43.23,51.0041483497,0.00631395670689,21.2563026084,18.7003279942,6.70818579158,-0.204178554414,-0.098511064731,0.60599592501,19.9818466188 +43.24,51.0041500311,0.00631491080259,21.2583368931,18.7102588548,6.68572445299,-0.202678387374,-0.10054784866,0.603628134488,19.9128832031 +43.25,51.0041517133,0.00631586155606,21.2603613349,18.7181901618,6.66126604429,-0.202209965953,-0.100850272722,0.601281875699,19.8423586811 +43.26,51.0041533963,0.00631680903051,21.262377834,18.7280770332,6.63969205274,-0.201089862694,-0.10064887841,0.599830600676,19.7691197544 +43.27,51.00415508,0.00631775338562,21.2643790007,18.7350200074,6.6174752267,-0.199143461561,-0.0980944422185,0.599401834812,19.6989456988 +43.28,51.0041567645,0.00631869459177,21.266376758,18.7435035851,6.59548539496,-0.200408008319,-0.0994253342305,0.599618592606,19.6268637409 +43.29,51.0041584496,0.00631963279216,21.268375185,18.7508704832,6.57527895652,-0.199277387091,-0.0999858960387,0.597663970666,19.5526844571 +43.3,51.0041601356,0.00632056787145,21.2703735695,18.761718371,6.55166978493,-0.200399510625,-0.100900514568,0.59723232338,19.4835779121 +43.31,51.0041618224,0.00632149950267,21.2723783148,18.769971437,6.52687344169,-0.200549546162,-0.102561897468,0.596602115939,19.4095265084 +43.32,51.0041635101,0.00632242774833,21.2743767254,18.7788899503,6.50414172763,-0.199132574089,-0.10098832171,0.595525392644,19.3369005888 +43.33,51.0041651984,0.00632335272107,21.2763676717,18.7870868355,6.48092667403,-0.199056701861,-0.0992862145966,0.594947956432,19.2644890328 +43.34,51.0041668876,0.00632427436785,21.2783577459,18.7967495859,6.45745038503,-0.198958132176,-0.0981814768377,0.593572360252,19.1929074774 +43.35,51.0041685776,0.00632519280708,21.2803585849,18.8057722024,6.43589749197,-0.201209665853,-0.0992213452385,0.592773940163,19.1204767326 +43.36,51.0041702684,0.00632610800474,21.2823591937,18.8129990173,6.41194375293,-0.198912092161,-0.0992233763792,0.591776953669,19.0486591458 +43.37,51.0041719598,0.00632701994936,21.284347401,18.8210425334,6.39022973408,-0.1987293589,-0.0986683778338,0.590805829793,18.9774236026 +43.38,51.004173652,0.0063279288146,21.2863358817,18.8290188843,6.36871410882,-0.198966786497,-0.098949490444,0.589559731608,18.9060318585 +43.39,51.0041753448,0.00632883457532,21.2883168716,18.8361031092,6.34664696074,-0.197231203,-0.0984505997894,0.589002002314,18.8341846698 +43.4,51.0041770385,0.00632973718697,21.2902887541,18.8474231957,6.32450592361,-0.197145282949,-0.0981796080672,0.587796817731,18.7629508436 +43.41,51.0041787331,0.0063306364348,21.2922594195,18.8583683469,6.29942418239,-0.196987806004,-0.0958135136774,0.584889154615,18.6897651031 +43.42,51.0041804287,0.00633153234591,21.2942252241,18.8666190901,6.2776634986,-0.196173122341,-0.0967255776717,0.584626427543,18.6198660316 +43.43,51.0041821248,0.00633242510244,21.2961864081,18.8717070882,6.25513859853,-0.196063673749,-0.0948793111949,0.582721574685,18.5476651419 +43.44,51.0041838216,0.00633331458573,21.2981436102,18.881667682,6.23171243248,-0.195376735377,-0.0969203092381,0.580942295229,18.4747340348 +43.45,51.0041855192,0.00633420096624,21.3000948719,18.8891126117,6.21158031266,-0.194875611968,-0.0970654820963,0.578856513964,18.4041724241 +43.46,51.0041872175,0.00633508422373,21.3020391817,18.8976288216,6.18786994943,-0.193986350779,-0.0978690293537,0.577146487711,18.3317703311 +43.47,51.0041889165,0.00633596421763,21.3039717,18.9061122424,6.16576458587,-0.192517303513,-0.0986341859562,0.576588992014,18.2587840125 +43.48,51.0041906164,0.00633684097531,21.3058901781,18.9152601232,6.14243842819,-0.191178308622,-0.0986709004862,0.576067509335,18.1880336238 +43.49,51.0041923171,0.0063377144579,21.3078032149,18.9256480913,6.11978732411,-0.191429063715,-0.0980069016767,0.573580829448,18.1170152817 +43.5,51.0041940187,0.00633858464479,21.3097185975,18.9334119343,6.09617197998,-0.191647460669,-0.0992483668123,0.57130496984,18.0439976193 +43.51,51.0041957209,0.00633945150955,21.3116328332,18.9417249827,6.07314977146,-0.191199667296,-0.0978996913397,0.569542164444,17.9716652845 +43.52,51.004197424,0.00634031508535,21.3135388315,18.95,6.05,-0.19,-0.098,0.571,17.9 +43.53,51.0041991276,0.00634117551956,21.3154465187,18.9558627049,6.02904677229,-0.191537443224,-0.0977324687849,0.571396722534,17.8291561298 +43.54,51.0042008319,0.00634203272677,21.3173609299,18.9631742559,6.00469800747,-0.191344787951,-0.0980694705337,0.568473623291,17.7615075333 +43.55,51.0042025367,0.0063428866571,21.3192648927,18.9695573225,5.9830442713,-0.189447773075,-0.09774192937,0.567870071163,17.6906214594 +43.56,51.0042042421,0.00634373758022,21.321153278,18.974843443,5.96248147948,-0.18822928932,-0.0994042058843,0.566127305014,17.6220084631 +43.57,51.0042059481,0.0063445854907,21.3230432927,18.982540735,5.94075148764,-0.189773652946,-0.0986995251463,0.566742113998,17.5515193963 +43.58,51.0042076546,0.00634543021457,21.3249396135,18.9880192276,5.91774635849,-0.189490505028,-0.0959253945448,0.563760926006,17.4832162272 +43.59,51.0042093617,0.00634627178248,21.3268357065,18.9943473808,5.89644687862,-0.189728101869,-0.0978724789476,0.562984793175,17.4142048697 +43.6,51.0042110694,0.00634711031524,21.3287244125,19.000353678,5.87513733271,-0.188013095726,-0.0978430198439,0.562284338489,17.3433459727 +43.61,51.0042127776,0.00634794560549,21.3306065765,19.0067418036,5.850927237,-0.188419708435,-0.095108543636,0.560847630345,17.2710100782 +43.62,51.0042144863,0.00634877781552,21.3324882148,19.0125668153,5.8318956552,-0.187907941064,-0.0971338885884,0.561090734378,17.203208419 +43.63,51.0042161956,0.00634960711457,21.3343603371,19.0189738543,5.81006175295,-0.186516512781,-0.0976411370212,0.55940076677,17.1318298632 +43.64,51.0042179055,0.00635043334314,21.3362222057,19.0241329324,5.78879073305,-0.185857220879,-0.0972957512082,0.556860910777,17.0632539605 +43.65,51.0042196159,0.00635125634884,21.3380800826,19.0319230955,5.76481779829,-0.185718160963,-0.0967520164487,0.554978612214,16.9925720944 +43.66,51.0042213268,0.00635207618475,21.3399355556,19.036903567,5.7442916893,-0.18537642729,-0.0983129443766,0.553949921093,16.9237436497 +43.67,51.0042230384,0.006352892933,21.3417903105,19.0444146562,5.721471938,-0.18557456334,-0.0988376584008,0.554378861937,16.8551181678 +43.68,51.0042247505,0.00635370647112,21.3436416691,19.0497462445,5.69922648855,-0.184697148718,-0.0993626358993,0.551331770343,16.7861681737 +43.69,51.0042264631,0.00635451678908,21.3454923109,19.0552117738,5.67626598008,-0.185431205688,-0.098953073454,0.552299049424,16.7164565063 +43.7,51.0042281763,0.00635532386342,21.3473427712,19.0637489881,5.65369109116,-0.184660853906,-0.0976375196514,0.550159402254,16.6491677323 +43.71,51.0042298902,0.00635612784974,21.3491911151,19.0699714724,5.63291488049,-0.185007934331,-0.0974406770243,0.549323684525,16.5792938094 +43.72,51.0042316047,0.00635692883582,21.3510340454,19.0760529479,5.61157253622,-0.1835781162,-0.0983885111547,0.549036771133,16.5087692311 +43.73,51.0042333196,0.00635772691311,21.3528677754,19.0816416893,5.5920799008,-0.183167888811,-0.100569219618,0.548794291026,16.4414011827 +43.74,51.0042350351,0.00635852191751,21.3546947825,19.0871457976,5.56843404034,-0.182233536971,-0.101134678494,0.544647974539,16.3708556015 +43.75,51.0042367511,0.00635931376611,21.3565127968,19.0920394273,5.54777740935,-0.181369328136,-0.10061788308,0.543204429714,16.2988355315 +43.76,51.0042384675,0.00636010236426,21.358333551,19.0983693197,5.52280283015,-0.182781506783,-0.100039009883,0.540348676987,16.231097908 +43.77,51.0042401844,0.00636088766648,21.3601575531,19.1027336271,5.50150769336,-0.182018907628,-0.100899454055,0.539470727282,16.1600162604 +43.78,51.0042419019,0.00636166999436,21.3619778521,19.1106982686,5.48104769994,-0.182040890281,-0.101727363116,0.537695305078,16.0915246189 +43.79,51.00424362,0.0063624493241,21.3637989269,19.1162442592,5.45941858386,-0.182174071552,-0.101623844412,0.535997149478,16.021404614 +43.8,51.0042453387,0.00636322557976,21.3656138455,19.1244653561,5.4378924437,-0.180809660728,-0.10158693738,0.53720062611,15.9531292367 +43.81,51.0042470581,0.00636399884777,21.3674212974,19.1312858466,5.41747659849,-0.180680700558,-0.100887343031,0.534570240661,15.8821012863 +43.82,51.004248778,0.00636476905823,21.3692213989,19.1376607939,5.39496919807,-0.179339614009,-0.101212177634,0.53573279134,15.8117449103 +43.83,51.0042504985,0.00636553594704,21.3710168734,19.1432872013,5.37084599416,-0.179755285476,-0.0997977437699,0.534429605006,15.7444083208 +43.84,51.0042522196,0.00636629954787,21.3728125182,19.1499028854,5.34881102077,-0.179373664534,-0.0978733437403,0.533277881566,15.6748442202 +43.85,51.0042539412,0.00636705994567,21.3746037673,19.1545097381,5.32588058764,-0.178876165547,-0.0970556400035,0.532614989694,15.6054533168 +43.86,51.0042556633,0.00636781710347,21.3763841962,19.1616861375,5.30332652263,-0.177209603923,-0.0954171291045,0.53122046892,15.5342974338 +43.87,51.0042573859,0.00636857107534,21.3781580511,19.1664316069,5.28115517331,-0.177561372271,-0.0957497228838,0.531143042074,15.4638746349 +43.88,51.0042591091,0.00636932187912,21.3799288004,19.1739225592,5.25885157348,-0.176588492987,-0.0947299549204,0.529891150489,15.3963514078 +43.89,51.0042608329,0.00637006945482,21.3816926767,19.1804253465,5.23583807961,-0.176186777905,-0.0930499413355,0.527102949507,15.3286872549 +43.9,51.0042625572,0.00637081395529,21.3834576588,19.1858871583,5.21568010234,-0.176809626422,-0.0930902637086,0.524960338129,15.2573489061 +43.91,51.0042642821,0.00637155550452,21.3852209336,19.1914732057,5.19440740002,-0.175845335692,-0.0967865282408,0.524520682341,15.1888022771 +43.92,51.0042660075,0.00637229403551,21.3869772928,19.1987780866,5.17330868093,-0.175426514534,-0.0947604572974,0.524207866054,15.1212033441 +43.93,51.0042677335,0.00637302947844,21.3887242082,19.2049944875,5.15105592366,-0.173956567442,-0.0931792672612,0.523265522494,15.0526282937 +43.94,51.0042694601,0.00637376190975,21.3904741704,19.2109730888,5.13103036508,-0.176035863689,-0.0961531722526,0.521954564055,14.9811180168 +43.95,51.0042711873,0.00637449140682,21.3922363705,19.2187644787,5.10986374385,-0.176404167037,-0.0964720091339,0.519334232114,14.9119342217 +43.96,51.0042729151,0.00637521784682,21.3939904283,19.2240654703,5.08811404938,-0.174407378796,-0.0956971448739,0.516887398604,14.8403600184 +43.97,51.0042746434,0.00637594124601,21.3957251572,19.2299116122,5.06717550738,-0.172538416461,-0.0959729108767,0.515694413877,14.7708843487 +43.98,51.0042763723,0.00637666146247,21.3974566037,19.2372941606,5.04343367395,-0.173750881004,-0.0967566615846,0.515955805486,14.6999704761 +43.99,51.0042781018,0.00637737855297,21.3991873942,19.2445083401,5.02329187206,-0.172407214335,-0.09513434786,0.516060080611,14.6314508677 +44,51.004279832,0.00637809260368,21.4009135885,19.2508984771,5.00075995498,-0.172831653718,-0.0956543482012,0.514512764992,14.5624588201 +44.01,51.0042815626,0.00637880351467,21.4026416169,19.2558707388,4.97921510229,-0.172774009898,-0.0957687941834,0.514642882866,14.4925639168 +44.02,51.0042832938,0.0063795113151,21.4043669666,19.2624032529,4.95709260792,-0.172295931603,-0.094217670037,0.512884410997,14.423270004 +44.03,51.0042850256,0.00638021614128,21.4060864605,19.2693546133,4.93746145279,-0.171602852438,-0.0941069070068,0.514412810939,14.3527993971 +44.04,51.0042867579,0.00638091788343,21.4077984417,19.273618504,4.91379767761,-0.170793385491,-0.0935891973118,0.512655445647,14.284361123 +44.05,51.0042884907,0.00638161636905,21.4094986698,19.2810964842,4.89174503828,-0.169252234481,-0.0935662475361,0.510432139228,14.2129877187 +44.06,51.0042902241,0.0063823117236,21.4111924795,19.2867048093,4.86984241678,-0.169509718051,-0.0915534548629,0.508385529872,14.1435353522 +44.07,51.004291958,0.00638300401298,21.4128893874,19.2930499942,4.84871505693,-0.169871858987,-0.0924632311043,0.507307526718,14.0742865902 +44.08,51.0042936926,0.00638369329259,21.4145903924,19.2993364957,4.8275899147,-0.170329139045,-0.0937315552594,0.507823076067,14.0066999298 +44.09,51.0042954277,0.00638437960993,21.4162905007,19.3068674783,4.80712948413,-0.169692522182,-0.0967550399131,0.506234117834,13.9386745016 +44.1,51.0042971634,0.00638506284395,21.4179878824,19.3121309533,4.78430511011,-0.169783808721,-0.0964740610808,0.50451872523,13.8686206648 +44.11,51.0042988996,0.00638574285575,21.4196871296,19.318503752,4.76189459312,-0.170065634429,-0.0960548434224,0.503252769969,13.7981572679 +44.12,51.0043006364,0.00638641963875,21.4213894431,19.3248912794,4.73897794176,-0.170397063797,-0.0948570972434,0.502518892568,13.7293860255 +44.13,51.0043023738,0.00638709315597,21.4230853807,19.3320935875,4.7160483565,-0.168790461631,-0.0951648183246,0.501373589278,13.6597312323 +44.14,51.0043041118,0.00638776351349,21.4247745773,19.337882141,4.69462079124,-0.169048855765,-0.0939931237177,0.5007317876,13.5903211399 +44.15,51.0043058504,0.00638843073155,21.4264571822,19.3438920755,4.67197544714,-0.16747213304,-0.0922842570206,0.500269205358,13.5208403873 +44.16,51.0043075894,0.00638909480475,21.4281237384,19.3496358928,4.65047199349,-0.165839106828,-0.0936000395555,0.498908591077,13.4500048679 +44.17,51.004309329,0.00638975577426,21.4297798981,19.3552339716,4.62840450817,-0.165392820808,-0.0910880748117,0.497214434514,13.3809849894 +44.18,51.0043110691,0.00639041370799,21.4314349428,19.3617166488,4.607854637,-0.165616117434,-0.0914953080819,0.494623024889,13.3121656847 +44.19,51.0043128098,0.00639106872757,21.433089194,19.3690097509,4.58749442604,-0.165234119305,-0.0906292156536,0.495200653934,13.2418220777 +44.2,51.0043145511,0.0063917205645,21.4347349723,19.3749943844,4.56317546647,-0.163921548388,-0.0911294944118,0.494290903332,13.172353088 +44.21,51.0043162931,0.00639236922704,21.4363655173,19.3825176082,4.54293099553,-0.162187450952,-0.0938246409885,0.493683099256,13.1051289963 +44.22,51.0043180356,0.0063930148724,21.4379865962,19.3878579133,4.52081914595,-0.162028330659,-0.0914964461818,0.492001887325,13.0327994886 +44.23,51.0043197786,0.00639365736402,21.4396036035,19.3935328477,4.49865764572,-0.161373127619,-0.091140868445,0.492441560185,12.9657961542 +44.24,51.0043215221,0.00639429678471,21.4412229688,19.3992001722,4.47770823562,-0.162499933114,-0.0899022029131,0.49078253055,12.8954702626 +44.25,51.0043232661,0.0063949331545,21.4428360737,19.4056556029,4.45582783859,-0.160121053846,-0.0872272277781,0.489027633429,12.8265102108 +44.26,51.0043250108,0.00639556639743,21.4444319718,19.4125716461,4.43381224133,-0.159058564291,-0.0899807129153,0.487560539633,12.7562904833 +44.27,51.004326756,0.00639619644431,21.4460155639,19.4176939669,4.41096038139,-0.157659856976,-0.0893454187551,0.488912233169,12.686940269 +44.28,51.0043285017,0.00639682324977,21.4475958724,19.4242529309,4.38830807255,-0.158401834618,-0.0887243791953,0.487192529875,12.6152772297 +44.29,51.004330248,0.00639744681473,21.4491887,19.4298002603,4.36546894984,-0.160163683985,-0.0892422040049,0.487996536717,12.5470926392 +44.3,51.0043319948,0.00639806729785,21.4507787784,19.4363815612,4.3450440539,-0.157851995312,-0.0912116084061,0.485419864983,12.478533154 +44.31,51.0043337422,0.00639868473917,21.4523569394,19.441449045,4.32276696632,-0.15778020638,-0.0921588320363,0.484543388099,12.4067043941 +44.32,51.00433549,0.00639929902023,21.4539347305,19.4488266455,4.30067911746,-0.157778010507,-0.0917620711718,0.481780797172,12.3373051511 +44.33,51.0043372386,0.00639991001853,21.4555053928,19.4561704357,4.27668253493,-0.156354456674,-0.0917029199008,0.483436834176,12.2655612566 +44.34,51.0043389878,0.00640051788474,21.4570601008,19.4620163215,4.25670950378,-0.154587133269,-0.0928398482723,0.481582984397,12.1961411732 +44.35,51.0043407374,0.00640112279815,21.4586097017,19.4673534614,4.23523003516,-0.155333054595,-0.0924341923619,0.480983686277,12.1261322609 +44.36,51.0043424876,0.00640172462734,21.4601628124,19.4733199429,4.2134120615,-0.155289089692,-0.0921645171638,0.478124720772,12.0578771082 +44.37,51.0043442383,0.0064023232516,21.4617111621,19.4793056498,4.19023804189,-0.154380849247,-0.0890455143394,0.476284530636,11.9867190842 +44.38,51.0043459895,0.00640291875047,21.4632529167,19.4851794989,4.16953659958,-0.153970069478,-0.0903159945668,0.474161784148,11.9184349657 +44.39,51.0043477412,0.00640351102172,21.4647915453,19.4902008206,4.14492760709,-0.153755657767,-0.0906806016304,0.473707711989,11.8504784165 +44.4,51.0043494935,0.00640410009787,21.4663317897,19.4973461703,4.12468259097,-0.154293215805,-0.091483769912,0.472421373282,11.7798133476 +44.41,51.0043512464,0.00640468618567,21.4678706668,19.5043344458,4.10297613909,-0.153482206801,-0.0925398230938,0.472405497835,11.7093990583 +44.42,51.0043529999,0.00640526911719,21.469402515,19.5106347417,4.08037347029,-0.152887427953,-0.0917374681643,0.471800958855,11.6416091579 +44.43,51.004354754,0.00640584883275,21.4709296755,19.5169650805,4.05782921008,-0.152544674055,-0.0913295396968,0.472195402534,11.5718277372 +44.44,51.0043565086,0.00640642545659,21.4724499056,19.5232788088,4.03697100356,-0.15150134673,-0.0920720847521,0.469267918685,11.5019739158 +44.45,51.0043582638,0.00640699886739,21.4739772235,19.5296716348,4.01272322671,-0.153962233803,-0.0910136493189,0.471347112324,11.4353432091 +44.46,51.0043600196,0.00640756883304,21.4755055357,19.5368701817,3.98860675672,-0.151700208385,-0.0898904822763,0.468024304766,11.361821597 +44.47,51.0043617761,0.0064081355339,21.4770231939,19.5433666026,3.96689109306,-0.151831427277,-0.0894022640576,0.466714568728,11.2946926471 +44.48,51.004363533,0.00640869930679,21.4785384868,19.5488123545,3.9475026924,-0.151227148447,-0.0911247556472,0.465740175941,11.2246506969 +44.49,51.0043652904,0.00640926011587,21.4800434103,19.5524442097,3.92528412403,-0.149757562727,-0.0891406339721,0.46201508821,11.1568342543 +44.5,51.0043670482,0.00640981774891,21.481532243,19.5580492274,3.90291630275,-0.148008970212,-0.0871855856618,0.463781635121,11.0873874343 +44.51,51.0043688066,0.00641037232131,21.48301368,19.5650039218,3.88231766578,-0.148278438379,-0.0869324482694,0.459726512259,11.0181159173 +44.52,51.0043705657,0.00641092395562,21.4844976573,19.5740883787,3.86167042069,-0.148517023729,-0.0879931836983,0.459089240623,10.9466891889 +44.53,51.0043723254,0.00641147267168,21.4859806712,19.5793368895,3.84135020656,-0.148085755678,-0.0894933600321,0.457129670492,10.8786975718 +44.54,51.0043740856,0.00641201830649,21.4874586511,19.5857082556,3.81841471742,-0.147510217022,-0.0895923473705,0.456896918959,10.8100248209 +44.55,51.0043758465,0.00641256062819,21.488937117,19.594164239,3.79483960662,-0.148182960872,-0.0907996422403,0.456546899089,10.7392922226 +44.56,51.0043776081,0.00641309969818,21.4904136436,19.5998141708,3.77276601455,-0.147122354316,-0.0900818219491,0.454708639638,10.6701651567 +44.57,51.0043793701,0.00641363565928,21.4918909741,19.6046620196,3.75119601432,-0.148343755574,-0.0874911253876,0.452439004298,10.5999926824 +44.58,51.0043811326,0.00641416844244,21.4933742265,19.6103743915,3.72815284611,-0.148306718774,-0.0894683056538,0.451348043013,10.5295241852 +44.59,51.0043828957,0.00641469802125,21.4948555645,19.6177501142,3.70621237142,-0.147960887706,-0.0896154338545,0.451432503557,10.4601567253 +44.6,51.0043846594,0.00641522459,21.4963292745,19.6246330626,3.68589652788,-0.14678110767,-0.089074394384,0.451266496768,10.3914584527 +44.61,51.0043864238,0.00641574834598,21.4978017032,19.6335636415,3.66672557534,-0.147704632106,-0.0896888121422,0.449097248801,10.3206223006 +44.62,51.0043881889,0.00641626911311,21.4992676396,19.638647746,3.64393810131,-0.145482655203,-0.0905361159192,0.448266800329,10.2519504503 +44.63,51.0043899545,0.0064167867446,21.5007306587,19.6458401842,3.62270643423,-0.147121154708,-0.0902768373264,0.448798643924,10.1822021544 +44.64,51.0043917208,0.00641730126789,21.5021940201,19.6525441581,3.60030406833,-0.145551117207,-0.08905100282,0.448117732955,10.1121362575 +44.65,51.0043934876,0.00641781262704,21.5036513359,19.6590270417,3.57828711197,-0.145912050267,-0.0875325212174,0.447289267581,10.043199237 +44.66,51.0043952549,0.00641832088282,21.5051101338,19.6633046129,3.55673789779,-0.145847527775,-0.0891908590569,0.446464570716,9.97518817498 +44.67,51.0043970227,0.00641882605746,21.5065659413,19.6706035236,3.53503310262,-0.145313972387,-0.0889889034838,0.443279567178,9.90470869515 +44.68,51.0043987911,0.00641932805681,21.5080148115,19.675370293,3.51216199099,-0.144460076906,-0.0890568466556,0.443915639749,9.83529109406 +44.69,51.00440056,0.00641982698956,21.5094544754,19.6827455384,3.49198316444,-0.143472703389,-0.0914055318491,0.441714167198,9.76592802787 +44.7,51.0044023295,0.00642032300117,21.5108909421,19.687928537,3.47115410808,-0.143820622198,-0.0913042832249,0.44212832482,9.69735596005 +44.71,51.0044040995,0.00642081586568,21.5123236352,19.6940815856,3.44780291547,-0.142718010881,-0.0896925804116,0.442774320302,9.62537899963 +44.72,51.0044058701,0.00642130554388,21.5137508615,19.701380477,3.4264237976,-0.142727241183,-0.0887734085556,0.440553070711,9.55475864355 +44.73,51.0044076413,0.00642179197725,21.5151707475,19.7073260462,3.40225084118,-0.141249968718,-0.0902750221561,0.438637690567,9.48551751915 +44.74,51.004409413,0.00642227518314,21.5165875716,19.7108686866,3.3811153594,-0.142114841328,-0.0891189362483,0.437500998621,9.41795288258 +44.75,51.0044111851,0.00642275530889,21.518011833,19.7178937927,3.35901071584,-0.142737437319,-0.0873556669204,0.434915608593,9.34654563967 +44.76,51.0044129578,0.00642323233955,21.5194373975,19.7247566559,3.33766562591,-0.14237546044,-0.0888801532912,0.434726806893,9.27756490287 +44.77,51.0044147311,0.0064237061945,21.5208536683,19.7309485213,3.31442897176,-0.140878702517,-0.0905222861211,0.4339951597,9.20901318544 +44.78,51.0044165049,0.00642417687884,21.5222660638,19.7364192714,3.29315548994,-0.141600407286,-0.0894048221388,0.43242161288,9.13781985509 +44.79,51.0044182792,0.00642464464902,21.523674921,19.7415085363,3.27351903735,-0.14017102256,-0.0884279441076,0.430717006053,9.06945021376 +44.8,51.0044200542,0.00642510934507,21.5250757761,19.75,3.25,-0.14,-0.088,0.43,9 +44.81,51.0044218295,0.00642557057036,21.5264678662,19.7512106377,3.22479521393,-0.138418019511,-0.0879497476431,0.430836752708,8.92795535846 +44.82,51.0044236051,0.006426028165,21.5278460125,19.7558200721,3.1990318035,-0.137211247506,-0.0866637927381,0.429158710974,8.85574957863 +44.83,51.004425381,0.00642648209754,21.5292216228,19.7567098575,3.17338555444,-0.137910800158,-0.0857003049728,0.426659991307,8.78625742104 +44.84,51.0044271569,0.00642693248839,21.5305983424,19.7568222323,3.14931250903,-0.13743313394,-0.0854784391119,0.424744288196,8.71774502875 +44.85,51.0044289329,0.00642737938014,21.531970461,19.7590821007,3.1242639316,-0.136990575051,-0.0856591433586,0.421655631543,8.64683383532 +44.86,51.0044307091,0.00642782271006,21.5333448254,19.7614754137,3.09931060337,-0.137882306569,-0.0853868845734,0.420969463834,8.57837486193 +44.87,51.0044324856,0.00642826239054,21.5347161012,19.7637307437,3.07303180906,-0.136372851403,-0.0846103319849,0.422513165837,8.5083263757 +44.88,51.0044342622,0.00642869850851,21.536081051,19.7665879947,3.04929907629,-0.136617122593,-0.0848582300305,0.422872858407,8.43771608025 +44.89,51.0044360392,0.00642913111762,21.5374483211,19.770191979,3.02377329261,-0.136836881732,-0.0850723837106,0.421333289115,8.36826005539 +44.9,51.0044378164,0.00642955996173,21.5388098448,19.7723905816,2.9964448838,-0.135467861374,-0.0822307164774,0.419121943926,8.29841030535 +44.91,51.0044395937,0.00642998501573,21.5401694523,19.7710723194,2.97056660749,-0.136453633246,-0.0833322544745,0.419260361526,8.22830550173 +44.92,51.0044413709,0.00643040655301,21.5415292835,19.7729885171,2.94707603269,-0.135512617564,-0.0818933470291,0.417171296639,8.15896728343 +44.93,51.0044431484,0.00643082456961,21.5428862758,19.7757823579,2.92114216752,-0.135885833318,-0.0825274971194,0.416749378812,8.08834694986 +44.94,51.0044449261,0.00643123897531,21.5442408104,19.7761064148,2.89638518842,-0.135021090562,-0.0807862980419,0.417009080387,8.01825300614 +44.95,51.0044467038,0.00643164983801,21.5455932632,19.7787477821,2.87140449827,-0.135469480073,-0.0780862128039,0.41521942778,7.94839739275 +44.96,51.0044484818,0.00643205700438,21.5469342163,19.7805533574,2.84449499527,-0.132721132212,-0.0790893900459,0.41374896524,7.87773859563 +44.97,51.00445026,0.00643246040474,21.5482629852,19.7833529176,2.81853607739,-0.133032643805,-0.077918042998,0.413901947077,7.80627810785 +44.98,51.0044520384,0.00643286027196,21.5495895656,19.7850330621,2.79489571759,-0.132283444089,-0.075889098623,0.414536448035,7.73658653042 +44.99,51.0044538168,0.0064332565713,21.5509204776,19.78555254,2.76844906554,-0.133898947969,-0.0779612899803,0.412832228565,7.66646979387 +45,51.0044555955,0.00643364921168,21.5522565141,19.7889131029,2.74353021223,-0.133308359131,-0.0776290174609,0.410235789939,7.59723901804 +45.01,51.0044573744,0.00643403842523,21.5535920767,19.7921332265,2.72034221289,-0.133804149283,-0.0762174130032,0.410329769052,7.52815356409 +45.02,51.0044591536,0.0064344239537,21.5549251133,19.7932269539,2.69179803804,-0.132803176139,-0.0785788650695,0.407851751524,7.45835860562 +45.03,51.0044609329,0.00643480569154,21.5562507082,19.7958827809,2.66712816353,-0.132315812315,-0.0747364104497,0.40716646914,7.38748687819 +45.04,51.0044627124,0.00643518381971,21.557564827,19.7978238331,2.64112434935,-0.13050794662,-0.0742510868106,0.408080692597,7.31562063263 +45.05,51.004464492,0.00643555824313,21.5588739143,19.7978995128,2.61511999531,-0.131309510867,-0.0737774213061,0.405659091091,7.24431436958 +45.06,51.0044662717,0.00643592903284,21.5601827498,19.7999423122,2.59011316065,-0.130457586231,-0.0727244696243,0.405663299085,7.17721642126 +45.07,51.0044680516,0.00643629635302,21.5614842723,19.8032390741,2.5664137081,-0.12984691725,-0.0714987594535,0.402915121966,7.10630346493 +45.08,51.0044698318,0.00643666022903,21.562781161,19.8052139412,2.54176293152,-0.129530812193,-0.0724145828137,0.402820876514,7.0345386271 +45.09,51.0044716122,0.00643702062118,21.564064659,19.8074913581,2.51750630155,-0.127168791236,-0.0726535568736,0.403665743678,6.96503058097 +45.1,51.0044733927,0.00643737744887,21.5653423654,19.8089404172,2.49172394098,-0.128372491584,-0.0719959312613,0.400611177136,6.89283692596 +45.11,51.0044751733,0.00643773074671,21.5666141763,19.8096772689,2.4679533039,-0.1259896901,-0.072343460631,0.400788881472,6.82386168754 +45.12,51.0044769541,0.00643808026982,21.5678797645,19.8116290773,2.43873320122,-0.127127952966,-0.0719304576504,0.396993129395,6.75309235711 +45.13,51.004478735,0.00643842585562,21.5691392316,19.8134512838,2.41268037724,-0.124765464421,-0.0712954371003,0.397125407493,6.68256089237 +45.14,51.0044805161,0.00643876771197,21.5703940665,19.8153044532,2.38637803984,-0.126201511538,-0.0706085529992,0.394531087514,6.61242752618 +45.15,51.0044822974,0.00643910581348,21.571646604,19.8177162216,2.35996876326,-0.124305984088,-0.0709691881824,0.393390033792,6.54297063958 +45.16,51.0044840789,0.00643944035325,21.5728974582,19.8203674067,2.33637746701,-0.125864866504,-0.0711201328976,0.393049003711,6.47171218288 +45.17,51.0044858606,0.00643977144582,21.5741507922,19.8230098555,2.31157597214,-0.124801931461,-0.0719532089705,0.389848404098,6.40190226818 +45.18,51.0044876426,0.00644009902572,21.575397477,19.8249334264,2.28706561712,-0.124535031403,-0.0701063404525,0.390435260175,6.33075389299 +45.19,51.0044894247,0.00644042317678,21.576634015,19.8277004237,2.26344093548,-0.122772572278,-0.0704069446159,0.390181458378,6.26311745733 +45.2,51.004491207,0.00644074367996,21.577862682,19.8277096361,2.23585576205,-0.122960819224,-0.0699440792086,0.387530861361,6.19212256223 +45.21,51.0044929894,0.00644106049476,21.5790919547,19.8290723415,2.21166240083,-0.122893716328,-0.0695401458516,0.386236802869,6.1230592629 +45.22,51.0044947719,0.00644137381124,21.580322718,19.8314118191,2.18674534142,-0.123258949753,-0.0700716677365,0.387087895818,6.05170155829 +45.23,51.0044965546,0.00644168342283,21.581551407,19.833205356,2.15965223649,-0.12247884514,-0.0687940651268,0.385804779742,5.98363514489 +45.24,51.0044983374,0.00644198933624,21.5827746431,19.8342311365,2.13482916311,-0.122168387627,-0.0690378349513,0.385924706774,5.91114394375 +45.25,51.0045001204,0.00644229169834,21.584003788,19.836318829,2.10979813551,-0.123660594472,-0.0688189129786,0.386697628669,5.84054446039 +45.26,51.0045019035,0.00644259060709,21.5852311459,19.8373591872,2.08634997905,-0.121810967537,-0.0690056358411,0.384123699333,5.76736752755 +45.27,51.0045036867,0.0064428860228,21.5864577534,19.8400599854,2.06076195197,-0.123510542797,-0.066325611225,0.382482980441,5.69591253172 +45.28,51.0045054702,0.00644317769636,21.587686964,19.8412873874,2.03381661292,-0.122331580452,-0.0666525292045,0.380276177359,5.62672791157 +45.29,51.0045072538,0.0064434657039,21.5889083521,19.8429080025,2.00929740521,-0.121946032132,-0.06690718523,0.380132800293,5.56032677417 +45.3,51.0045090375,0.00644375010839,21.5901314031,19.8437836054,1.98323606599,-0.122664171232,-0.0665304588236,0.377699114775,5.48913738374 +45.31,51.0045108212,0.00644403094103,21.591353022,19.8432386228,1.959154953,-0.121659607356,-0.0646733297865,0.376877829804,5.41924596629 +45.32,51.0045126051,0.00644430821497,21.5925632012,19.8480192121,1.93327794557,-0.120376229336,-0.0644352893592,0.375666344204,5.34651450585 +45.33,51.0045143894,0.00644458174376,21.5937520219,19.8518772496,1.90657954318,-0.117387910262,-0.063884535505,0.374697187796,5.27607389319 +45.34,51.0045161739,0.00644485154324,21.5949307511,19.8543751685,1.88092502068,-0.118357930826,-0.0645018327164,0.372591972298,5.20555456427 +45.35,51.0045179586,0.00644511768887,21.5961179901,19.8534697563,1.85528580293,-0.119089872508,-0.062269138134,0.373477851126,5.13390699372 +45.36,51.0045197433,0.00644538031628,21.5973028316,19.8573212259,1.83153532045,-0.11787843023,-0.0631043779635,0.371215449668,5.0659820053 +45.37,51.0045215283,0.00644563950733,21.5984759044,19.8577798487,1.80704535867,-0.116736125921,-0.0632961599269,0.369742376145,4.99700396204 +45.38,51.0045233135,0.00644589510035,21.5996476217,19.8610877455,1.78102513317,-0.117607333123,-0.0630177431928,0.369044563299,4.92577270201 +45.39,51.0045250989,0.0064461470889,21.6008234202,19.8635358829,1.75644499713,-0.117552367379,-0.0629662838403,0.369474128696,4.85600701331 +45.4,51.0045268844,0.00644639549032,21.6020004269,19.8645538527,1.73066812997,-0.117848965073,-0.061719309695,0.368035516732,4.78408475804 +45.41,51.0045286701,0.00644664031586,21.6031752125,19.8677505274,1.70624573382,-0.117108170355,-0.0612253304352,0.368414790042,4.71120973883 +45.42,51.0045304561,0.00644688143366,21.6043320384,19.8697877096,1.67861803234,-0.114257005631,-0.0613438691705,0.369199766018,4.64078244544 +45.43,51.0045322422,0.00644711880544,21.6054741566,19.8710269095,1.65365818571,-0.114166635148,-0.0597981451382,0.36658383667,4.57047971474 +45.44,51.0045340285,0.00644735254507,21.6066158921,19.8735952175,1.62762901788,-0.114180470926,-0.0606540268145,0.364927352549,4.49940646273 +45.45,51.004535815,0.00644758253776,21.6077566271,19.875361903,1.60105762136,-0.113966524917,-0.0615053469314,0.364964656724,4.42867656392 +45.46,51.0045376017,0.00644780895888,21.6088930171,19.8769830124,1.57749047763,-0.113311462514,-0.0607711379113,0.363455908191,4.35913095823 +45.47,51.0045393885,0.0064480319424,21.6100249135,19.8785712951,1.55279978032,-0.113067817057,-0.058139063265,0.361742844283,4.28901087059 +45.48,51.0045411754,0.00644825131035,21.6111540557,19.8813124754,1.52673411831,-0.112760637067,-0.0601069269831,0.362092969377,4.21758927514 +45.49,51.0045429626,0.00644846703458,21.6122776292,19.8822374211,1.50164833345,-0.111954064977,-0.0582861907772,0.360020336384,4.14912709684 +45.5,51.0045447499,0.00644867912775,21.6133919945,19.8847995012,1.47576059675,-0.110918983965,-0.0565306278664,0.358385704739,4.07735524974 +45.51,51.0045465374,0.00644888750897,21.6145056012,19.8874326713,1.44953886669,-0.111802360739,-0.05725447957,0.357585525867,4.00656258705 +45.52,51.0045483252,0.0064490922034,21.6156186567,19.8891093115,1.42400474089,-0.110808734474,-0.057602097876,0.356828154647,3.93653266428 +45.53,51.0045501131,0.00644929314501,21.6167428534,19.8915715093,1.39685577078,-0.114030601063,-0.0569898508049,0.355540157908,3.86541082152 +45.54,51.0045519012,0.00644949040471,21.6178732152,19.8927540006,1.37231714193,-0.112041760582,-0.0543106465623,0.353392432392,3.79607289426 +45.55,51.0045536893,0.00644968410298,21.6189858505,19.8930563398,1.34685973054,-0.110485314869,-0.0544831935072,0.352701289909,3.72702957143 +45.56,51.0045554776,0.00644987423695,21.6200895053,19.895574135,1.32228050233,-0.110245629938,-0.0547225665197,0.352149214703,3.65457721413 +45.57,51.004557266,0.00645006083446,21.6211825705,19.8973624579,1.29721415174,-0.108367407482,-0.0529594984433,0.351753067945,3.58397267503 +45.58,51.0045590547,0.00645024375142,21.6222793607,19.8989585297,1.27061214238,-0.110990643305,-0.0521995512645,0.350124872229,3.51444291509 +45.59,51.0045608435,0.0064504229505,21.6233904598,19.9031857079,1.2450216491,-0.111229174745,-0.0525715155019,0.34909836944,3.44401076682 +45.6,51.0045626326,0.00645059855082,21.6244990593,19.9020481844,1.22009184493,-0.110490732763,-0.0522431952681,0.348244344948,3.37438429362 +45.61,51.0045644217,0.00645077055453,21.6256041432,19.9061443307,1.19453154717,-0.110526041845,-0.0544755033078,0.346485083232,3.30479879833 +45.62,51.0045662111,0.00645093896802,21.6267052819,19.9072559384,1.16969165262,-0.10970169514,-0.0525652452098,0.345909423665,3.23244584011 +45.63,51.0045680006,0.00645110384499,21.627800809,19.9097712782,1.14488501126,-0.109403731081,-0.050823701596,0.344727356809,3.1612111985 +45.64,51.0045697904,0.00645126514938,21.6288911182,19.9108265649,1.11953896476,-0.10865810781,-0.0512614790582,0.344353793996,3.0925560187 +45.65,51.0045715802,0.00645142272817,21.6299796592,19.9118888351,1.0925841051,-0.109050083543,-0.0487691956101,0.340887579289,3.02291644969 +45.66,51.0045733701,0.00645157659613,21.6310713807,19.913296791,1.06744563465,-0.109294216994,-0.0511723785729,0.342260616762,2.952572857 +45.67,51.0045751602,0.00645172674016,21.6321561463,19.9158749998,1.04030665187,-0.107658898986,-0.050500538693,0.339602596826,2.88122511268 +45.68,51.0045769505,0.0064518732415,21.6332226118,19.9188839295,1.01630874611,-0.105634213095,-0.0500149629489,0.338309918226,2.81045768299 +45.69,51.0045787411,0.00645201634651,21.6342742173,19.9202946885,0.992628235706,-0.104686892136,-0.0488315600838,0.336012604063,2.74199299863 +45.7,51.0045805318,0.00645215581034,21.6353210257,19.9225053881,0.965192974387,-0.104674775589,-0.0471321105284,0.333887402459,2.67130711042 +45.71,51.0045823227,0.00645229154955,21.636383636,19.9254277781,0.940341315258,-0.107847288688,-0.0473458766962,0.334296318333,2.6038758791 +45.72,51.0045841139,0.00645242368293,21.6374449571,19.9272050348,0.91457340625,-0.104416924537,-0.046748475918,0.333470698441,2.53266997158 +45.73,51.0045859051,0.0064525521913,21.6384845602,19.9281655756,0.8894527584,-0.103503703682,-0.0436330950893,0.333432422317,2.46217057326 +45.74,51.0045876965,0.00645267711508,21.6395133233,19.9288469929,0.864252105072,-0.102248919757,-0.0480722186076,0.332068278473,2.38986058857 +45.75,51.0045894881,0.00645279847803,21.6405364299,19.9331967427,0.839465081531,-0.102372396471,-0.042903949221,0.331085109592,2.31937942032 +45.76,51.0045912799,0.00645291626879,21.6415660898,19.9351102198,0.814104766294,-0.10355958787,-0.0448124265125,0.331020323952,2.24977251409 +45.77,51.0045930719,0.00645303046569,21.6426035026,19.9365541524,0.789013844519,-0.10392296928,-0.0455866998363,0.331537693885,2.17862035908 +45.78,51.004594864,0.00645314105143,21.6436383019,19.9377527007,0.763410537734,-0.103036891577,-0.0431526974244,0.329127766991,2.10856699264 +45.79,51.0045966563,0.00645324810117,21.6446592778,19.9395638008,0.739374714638,-0.101158291287,-0.0423067065418,0.326927817489,2.03608593219 +45.8,51.0045984487,0.00645335157248,21.6456727298,19.9418452839,0.713175816144,-0.101532100641,-0.0441994413963,0.32691431096,1.96765209271 +45.81,51.0046002414,0.00645345124773,21.6466753778,19.9447287237,0.686084698107,-0.0989974914206,-0.0437570984932,0.326604457144,1.89839299052 +45.82,51.0046020343,0.00645354711082,21.6476659927,19.9472401271,0.659659984101,-0.0991254926749,-0.043659158183,0.325298285887,1.82677030987 +45.83,51.0046038275,0.00645363932411,21.6486620591,19.9499507331,0.634848105837,-0.100087782997,-0.0407918295936,0.324952347498,1.75817378833 +45.84,51.0046056208,0.00645372806525,21.6496545864,19.9507579028,0.610917261207,-0.0984176898326,-0.0419371986845,0.323653992613,1.68744092731 +45.85,51.0046074142,0.00645381339408,21.6506378945,19.9521903762,0.586945193151,-0.098243927562,-0.0399442766447,0.324590832281,1.61611453466 +45.86,51.0046092078,0.00645389509164,21.6516180262,19.9556225125,0.559940977697,-0.097782407284,-0.0410289977027,0.322585872765,1.54737692849 +45.87,51.0046110017,0.00645397308454,21.6525991132,19.9575314112,0.534938282644,-0.0984350012779,-0.0414762636081,0.322299685289,1.47607536327 +45.88,51.0046127957,0.0064540474408,21.6535745943,19.9589196452,0.508889041322,-0.0966612169898,-0.0381527414724,0.320356616073,1.40782001234 +45.89,51.0046145899,0.00645411832485,21.6545413646,19.9604732473,0.486194888214,-0.0966928365274,-0.037576061449,0.319211094311,1.33698177467 +45.9,51.0046163843,0.00645418564827,21.6555209174,19.9639466371,0.458903963187,-0.0992177271987,-0.0388277487307,0.318588071549,1.26625078824 +45.91,51.0046181788,0.0064542492252,21.656508997,19.9646831582,0.4336011305,-0.0983981887438,-0.0362347491947,0.316441700148,1.19160465591 +45.92,51.0046199735,0.00645430919536,21.6574850826,19.9673486578,0.40827124907,-0.0968189381955,-0.0373158890025,0.315226230825,1.12501025545 +45.93,51.0046217685,0.00645436550372,21.6584480719,19.9694345406,0.382196156094,-0.0957789139397,-0.0393102301978,0.314316884541,1.05489180993 +45.94,51.0046235636,0.0064544181478,21.6594027615,19.9711764677,0.356831389606,-0.0951590063921,-0.0366401754716,0.315010906736,0.983797486539 +45.95,51.0046253588,0.00645446717265,21.6603548978,19.9722376958,0.331388515348,-0.0952682491622,-0.0382376172585,0.313219370278,0.914174879806 +45.96,51.0046271542,0.00645451250001,21.6613133832,19.9742784676,0.30492555094,-0.0964288322995,-0.0364900656911,0.31100446741,0.844460390219 +45.97,51.0046289497,0.00645455416468,21.6622712804,19.9762724252,0.279970804641,-0.0951506070195,-0.0366054368478,0.308923693009,0.776430463501 +45.98,51.0046307455,0.0064545920781,21.6632335431,19.9794890879,0.252264786399,-0.0973019382293,-0.0361896820828,0.308582007852,0.704538334006 +45.99,51.0046325415,0.00645462630204,21.6641906255,19.9806591936,0.228177228084,-0.0941145519496,-0.0341531359557,0.308609637025,0.634423209953 +46,51.0046343376,0.00645465705008,21.6651324223,19.9834020318,0.203469525081,-0.0942447997658,-0.0352207691674,0.308570594713,0.562623500642 +46.01,51.004636134,0.00645468429223,21.6660694436,19.9859197789,0.178960694017,-0.0931594512992,-0.0343627858803,0.306734681439,0.49679332703 +46.02,51.0046379307,0.00645470795601,21.6670022175,19.9893942159,0.153235879908,-0.0933953293094,-0.0349635277456,0.306438128234,0.423894502289 +46.03,51.0046397277,0.0064547280627,21.6679354468,19.9926131823,0.129025524629,-0.0932505438049,-0.0344717821298,0.304414433836,0.352878233528 +46.04,51.0046415248,0.0064547445304,21.6688642632,19.993856365,0.102151090319,-0.0925127284605,-0.0346479004821,0.303889896864,0.284464344003 +46.05,51.0046433222,0.0064547571345,21.6697856776,19.9966650559,0.0747875563749,-0.0917701561942,-0.0313470114795,0.304080959828,0.213881545686 +46.06,51.0046451197,0.00645476598983,21.670700619,19.9979144106,0.0495251018079,-0.0912181172545,-0.0304710151661,0.30233882049,0.143180629102 +46.07,51.0046469174,0.00645477127354,21.6716071444,19.9992195204,0.0246485667328,-0.0900869760029,-0.0315890479868,0.302551663617,0.0694094622772 +46.08,51.0046487151,0.00645477302936,21.6725075793,20,0,-0.09,-0.03,0.301,0 +46.09,51.0046505128,0.00645477309099,21.6734101836,19.9984865957,0.000865140682667,-0.0905208482256,-0.0302370929816,0.299510570268,0.00171775226862 +46.1,51.0046523105,0.00645477322794,21.674307712,19.9997603753,0.00105732357371,-0.0889848399901,-0.0272455634116,0.297607167508,0.000781150543523 +46.11,51.0046541083,0.00645477337331,21.6751846859,19.9999567048,0.000983473421259,-0.0864099492414,-0.0272894644316,0.297729935544,0.000271712035944 +46.12,51.004655906,0.00645477351986,21.6760544742,19.9990756316,0.00107375813516,-0.0875477011373,-0.0274416474082,0.295800535779,-2.54846463796e-005 +46.13,51.0046577037,0.0064547735752,21.6769191882,19.9988554181,-0.00029676394517,-0.0853950999004,-0.0269124456605,0.294308439569,1.94458493103e-005 +46.14,51.0046595013,0.00645477348828,21.6777847503,19.9978418644,-0.000923480376768,-0.0877173247325,-0.0262122647781,0.293046412202,0.000283436715114 +46.15,51.0046612989,0.00645477339479,21.6786665276,19.9987860584,-0.000388958926611,-0.0886381284033,-0.0244063893239,0.292701960709,0.00154186744185 +46.16,51.0046630966,0.00645477346225,21.6795483076,19.9992502991,0.00133600989614,-0.0877178655649,-0.025737703348,0.291607979521,0.00147367228744 +46.17,51.0046648944,0.00645477367744,21.6804188226,20.0004198151,0.00168485212952,-0.0863851417706,-0.0267011156982,0.289962507492,0.000858692213617 +46.18,51.0046666921,0.00645477392228,21.6812814036,19.9982498887,0.00175227786967,-0.086131060349,-0.0248211217831,0.289664939543,0.000362055297465 +46.19,51.0046684897,0.00645477413904,21.6821459708,19.9989804982,0.00129057365585,-0.0867823850942,-0.0255129221476,0.290017129788,0.00263446020589 +46.2,51.0046702874,0.00645477426936,21.6830116293,20.0001108798,0.000538874872109,-0.0863492988904,-0.0258343297338,0.288113974845,0.00222111509732 +46.21,51.0046720852,0.00645477434406,21.6838685713,19.9997727442,0.000509853511315,-0.0850390998994,-0.0239171880748,0.285994773608,0.00292704427289 +46.22,51.0046738829,0.00645477452292,21.684717199,19.9972024626,0.00200092520933,-0.0846864531089,-0.0249784705567,0.285827769353,0.00148235288521 +46.23,51.0046756805,0.00645477476221,21.6855598966,19.9990174737,0.00135834157714,-0.0838530593547,-0.0252443149687,0.282194996149,0.00206283239201 +46.24,51.0046774781,0.00645477493464,21.6863993125,19.9987823475,0.00106224480465,-0.0840301231958,-0.0252360122071,0.280968937555,0.0010746056825 +46.25,51.0046792758,0.00645477511753,21.6872422412,19.9996227634,0.00150518519258,-0.08455562346,-0.0228297007934,0.279920986952,0.00261236544442 +46.26,51.0046810735,0.00645477531175,21.6880808531,19.9985412933,0.00122130523643,-0.0831667599332,-0.025009017669,0.276946879414,0.00152366142228 +46.27,51.0046828711,0.00645477543267,21.6889064025,19.9974237557,0.000476154783138,-0.0819431192619,-0.0253266421452,0.275336126464,0.000872473134563 +46.28,51.0046846686,0.00645477551103,21.6897231901,19.9972954463,0.000623940954351,-0.0814143939351,-0.0219155773989,0.273860138665,0.00182588050478 +46.29,51.0046864662,0.00645477562684,21.6905322627,19.9968608142,0.00100176925869,-0.0804001310903,-0.0208281087548,0.274427765378,0.00206100717709 +46.3,51.0046882636,0.00645477584232,21.6913386313,19.9967632193,0.00202317305874,-0.0808735830993,-0.0209257134194,0.275148711307,0.00285227349947 +46.31,51.0046900611,0.00645477610234,21.6921439954,19.9967250038,0.00162707348653,-0.08019922994,-0.0225352389547,0.273277775081,0.00108001666433 +46.32,51.0046918587,0.00645477631313,21.6929487773,19.9978735032,0.00133195450296,-0.0807571589292,-0.0208111517351,0.272104665632,3.65960984582e-005 +46.33,51.0046936563,0.0064547766282,21.6937505511,20.0002560845,0.00309113313405,-0.0795975916343,-0.0203816484587,0.271509537768,-0.00124981956152 +46.34,51.0046954542,0.00645477697292,21.6945540383,20.0007690063,0.00174810085819,-0.0810998556254,-0.0199290720464,0.270066266234,-0.0023403480638 +46.35,51.004697252,0.0064547771711,21.6953537547,20.0007695437,0.00103402186105,-0.0788434199703,-0.0217527586065,0.26669278891,-0.00191530785859 +46.36,51.0046990497,0.00645477737709,21.6961384357,19.9982933359,0.00185766377248,-0.0780927773933,-0.0226999809562,0.26608231733,-0.00203956780737 +46.37,51.0047008474,0.00645477761867,21.6969140894,19.9981892671,0.00153361382801,-0.0770379651746,-0.0231853041152,0.263181164853,-0.00202296645835 +46.38,51.0047026449,0.00645477805257,21.6976862983,19.9973502622,0.00455751051102,-0.0774038212837,-0.0212525507815,0.260873538015,-0.000983059175837 +46.39,51.0047044425,0.00645477860211,21.6984595911,19.9987862112,0.00315705388585,-0.0772547346937,-0.0222632075405,0.260484208806,-0.00114485906402 +46.4,51.0047062402,0.00645477900424,21.6992321622,19.9979510142,0.00248815373033,-0.0772594847422,-0.0199915558039,0.261175662154,-0.000900713951984 +46.41,51.0047080378,0.00645477942806,21.7000093261,19.9986986969,0.00346152549835,-0.0781732908632,-0.0214901847665,0.259124457738,-0.00222783860685 +46.42,51.0047098354,0.00645477993554,21.7007828371,19.9982016173,0.00366249514552,-0.076528924549,-0.0194516799875,0.259139648157,-0.00167839916823 +46.43,51.0047116331,0.00645478048849,21.7015484375,19.9989644007,0.0040999537236,-0.0765911414861,-0.0190808297955,0.257986356657,-0.00280203040947 +46.44,51.0047134307,0.00645478098962,21.7023068692,19.9984515113,0.00293492559675,-0.0750951994831,-0.0194630879302,0.257807299989,-0.00263919046315 +46.45,51.0047152283,0.0064547813498,21.7030598434,19.9972319678,0.00212133620344,-0.0754996429402,-0.017605746749,0.255466773502,-0.00299653664026 +46.46,51.0047170258,0.00645478170398,21.7038134996,19.9978566915,0.00285072808484,-0.0752316046024,-0.0169431547581,0.254457820388,-0.00198094582157 +46.47,51.0047188235,0.00645478213462,21.7045602509,19.9989585638,0.00319472378891,-0.0741186586798,-0.0166072687117,0.253453955977,-0.000909957294345 +46.48,51.0047206211,0.00645478262791,21.7052953409,19.9980778018,0.00373016661883,-0.0728993351491,-0.0169738762501,0.252445800612,-0.00104398869578 +46.49,51.0047224186,0.00645478308719,21.7060252338,19.9965450016,0.00271725606321,-0.0730792438542,-0.0168856829717,0.250618178315,-0.00256712181162 +46.5,51.0047242162,0.0064547834585,21.7067470392,19.9980283014,0.00249527120178,-0.0712818440506,-0.0184517031057,0.249436124725,-0.00221460678988 +46.51,51.0047260137,0.00645478386775,21.707453032,19.9964955165,0.00324978507126,-0.0699167132109,-0.0152068525245,0.247136947245,-0.00252603675331 +46.52,51.0047278112,0.00645478435456,21.7081591669,19.9971029228,0.00358419697528,-0.0713102561265,-0.01596143073,0.247712327172,-0.0021896821986 +46.53,51.0047296087,0.00645478490778,21.7088688254,19.9968602331,0.00418191540907,-0.0706214557877,-0.0137863817319,0.246332748432,-0.00116752132074 +46.54,51.0047314062,0.00645478545955,21.7095766706,19.9971771302,0.00356396154655,-0.0709475666501,-0.0153256257392,0.245401769483,-0.00283994248441 +46.55,51.0047332037,0.00645478591704,21.710288044,19.9980179586,0.00285837757574,-0.0713271193715,-0.0159733570989,0.244779608902,-0.000650323378104 +46.56,51.0047350013,0.00645478631423,21.7110023525,19.9975321526,0.00271740826489,-0.0715345758474,-0.0151862221622,0.241470378619,-0.000813784649668 +46.57,51.0047367988,0.00645478661403,21.7117109419,19.9968609362,0.00149120832591,-0.0701833161114,-0.0176230403608,0.23939258385,-0.00052454503625 +46.58,51.0047385964,0.00645478682545,21.712417913,19.9979634359,0.00147669721384,-0.0712109048101,-0.0144561144613,0.237534736998,-0.00126861004759 +46.59,51.0047403939,0.00645478698848,21.7131306257,19.9971636892,0.000811937123568,-0.0713316281126,-0.0139576477602,0.237146410326,-0.000801023045266 +46.6,51.0047421914,0.00645478713463,21.7138382856,19.9966567225,0.00123985713072,-0.0702003617813,-0.0127044570747,0.236195909829,-9.97117690683e-005 +46.61,51.0047439889,0.0064547872484,21.7145368028,19.9957373,0.000357213109697,-0.0695030663333,-0.0114828071048,0.234444358278,0.00111418082232 +46.62,51.0047457863,0.00645478731399,21.7152284627,19.9965477947,0.000563554812309,-0.0688289096183,-0.0111905606619,0.233543769872,0.000252994983387 +46.63,51.0047475838,0.00645478742617,21.7159181933,19.9985997419,0.00101116551894,-0.0691172184504,-0.0115556752124,0.230901493221,0.000897187619847 +46.64,51.0047493815,0.00645478765357,21.7166081103,19.9987494988,0.00218121721824,-0.0688661848792,-0.0125608052118,0.232297005277,0.00124058995924 +46.65,51.004751179,0.00645478780842,21.7172932746,19.9961415169,-7.494681662e-006,-0.0681666713369,-0.0138079788983,0.233261440058,-0.000686086471091 +46.66,51.0047529765,0.00645478786277,21.7179741055,19.9967523077,0.000770569408553,-0.067999517522,-0.0152427785387,0.229761462821,0.000489248261742 +46.67,51.004754774,0.00645478793424,21.7186453008,19.9980834898,0.000232723368645,-0.0662395423471,-0.0135899211036,0.230532599161,-0.000157913761059 +46.68,51.0047565716,0.00645478798358,21.7193095009,19.9975632743,0.000459822207272,-0.066600467861,-0.0144095955009,0.229348972729,-0.000202993811429 +46.69,51.0047583692,0.00645478810822,21.7199787965,19.9975742819,0.0012899609493,-0.0672586583542,-0.0146964533001,0.225050747201,0.00106542102508 +46.7,51.0047601667,0.00645478822033,21.7206528991,19.997176639,0.000283812401662,-0.0675618654814,-0.0155963288297,0.224244586856,0.00078415209198 +46.71,51.0047619643,0.00645478833218,21.7213216379,19.9981350117,0.00128642856962,-0.0661858843153,-0.0137918882859,0.223367646643,0.00240136108912 +46.72,51.0047637619,0.00645478849423,21.7219843711,19.9981972533,0.000988435149745,-0.0663607527872,-0.0137020678752,0.222468700487,0.00093864403518 +46.73,51.0047655594,0.00645478855419,21.7226478846,19.9965402887,-0.000146740207873,-0.0663419554702,-0.014105335683,0.221369022744,-0.000418223849077 +46.74,51.0047673569,0.00645478857738,21.7233088764,19.9968537144,0.000472287041979,-0.0658563990489,-0.013258937935,0.221307467423,0.000344251208745 +46.75,51.0047691544,0.00645478867026,21.7239555133,19.9974441795,0.000831589608044,-0.0634709742821,-0.0125631714364,0.218103194417,0.00140808409002 +46.76,51.0047709519,0.00645478868805,21.7245907312,19.9972404236,-0.000581815119886,-0.0635726070313,-0.010835596318,0.219339881354,-0.000265751751408 +46.77,51.0047727494,0.00645478870779,21.7252312008,19.9958927175,0.000858821252133,-0.0645213118708,-0.0111836736847,0.217131256714,-9.90082366231e-005 +46.78,51.0047745468,0.00645478863247,21.7258644082,19.9962309764,-0.00191614421651,-0.0621201859106,-0.00956489017802,0.217543736666,0.00359009726401 +46.79,51.0047763443,0.00645478851527,21.7264782516,19.9962817043,0.000270848739354,-0.0606484889368,-0.00937577688322,0.21444913851,0.00225630459651 +46.8,51.0047781417,0.00645478851706,21.7270950739,19.9965968421,-0.00024571148007,-0.062715969321,-0.00789697850449,0.212460319214,0.00178457906816 +46.81,51.0047799391,0.00645478859475,21.7277155661,19.9954241553,0.00133632997833,-0.0613824692492,-0.00833848222029,0.21290001529,0.0010918726095 +46.82,51.0047817365,0.0064547886755,21.7283302678,19.9956952872,-0.000202756763962,-0.0615578717308,-0.00817087166982,0.210404529545,0.000861121737132 +46.83,51.004783534,0.00645478858682,21.728941814,19.9972794471,-0.00104209536468,-0.0607513589301,-0.00699533580093,0.20853653665,0.00150821548815 +46.84,51.0047853315,0.00645478849983,21.7295450108,19.9979012659,-0.000179076080042,-0.0598880032283,-0.00664083472488,0.206598614343,0.00167563770875 +46.85,51.0047871291,0.00645478848851,21.7301446365,19.998723878,2.01528433393e-005,-0.0600371451229,-0.00699898919741,0.203850095384,-0.000344860137443 +46.86,51.0047889268,0.00645478844448,21.7307512053,19.9992578744,-0.00063828457266,-0.0612766069351,-0.00645436988433,0.202746191427,0.000336628574646 +46.87,51.0047907245,0.00645478837789,21.7313634228,19.9996899764,-0.000296448271175,-0.0611668940554,-0.00693738784199,0.201515329564,9.17187661452e-005 +46.88,51.0047925223,0.00645478822935,21.7319701261,19.9992170783,-0.0017887722344,-0.0601737688948,-0.00578953220545,0.203158839826,-0.00136151132925 +46.89,51.00479432,0.00645478806359,21.7325583391,20.0005595198,-0.000538229065473,-0.0574688361156,-0.0045089454172,0.202612962836,-0.000905880116279 +46.9,51.0047961177,0.00645478791419,21.7331336014,19.9982253457,-0.00155902555354,-0.0575836160649,-0.00390454186751,0.200539715178,-0.000242740741075 +46.91,51.0047979155,0.00645478776869,21.7336965692,20.0016169559,-0.000483578493428,-0.0550099483005,-0.00339981309146,0.198822147785,-9.64449539945e-005 +46.92,51.0047997133,0.00645478763601,21.7342613355,19.9995270188,-0.00137898344863,-0.0579433095637,-0.00233845362997,0.197566449526,-0.00243396803486 +46.93,51.004801511,0.00645478743849,21.7348409966,19.997788375,-0.00139380637708,-0.0579889193441,-0.00443280619927,0.197027335417,-0.00255363954462 +46.94,51.0048033086,0.00645478713631,21.7354139802,19.9977887523,-0.00284827673165,-0.0566077936301,-0.00382328725738,0.196270922688,-0.00228282266448 +46.95,51.0048051062,0.00645478674451,21.7359740395,19.9984982054,-0.00265189181994,-0.0554040740058,-0.00422141288457,0.196016319049,-0.00193166554492 +46.96,51.0048069038,0.00645478645844,21.7365294468,19.9978237245,-0.00136396485938,-0.0556773826433,-0.00374288717736,0.195507671303,-0.00159508487597 +46.97,51.0048087013,0.00645478631325,21.7370821111,19.9965704046,-0.000674175422592,-0.054855469135,-0.00229866609179,0.194579487643,0.000512339328709 +46.98,51.0048104989,0.00645478617477,21.7376337549,19.9992824327,-0.00126983586282,-0.0554732864376,-0.00180841471033,0.194041263387,-0.000565029046019 +46.99,51.0048122966,0.0064547860331,21.7381936436,19.9983931166,-0.00071897245348,-0.0565044625955,-0.00394168097143,0.190269510402,-0.000712990497322 +47,51.0048140942,0.00645478593689,21.7387516463,19.9977538843,-0.000631662211933,-0.055096073958,-0.00498694909625,0.190826214742,-0.000894520791969 +47.01,51.0048158917,0.00645478588948,21.7393033088,19.9963537882,-3.37956491247e-005,-0.0552364283819,-0.0071453409479,0.189879062212,-0.00288327412579 +47.02,51.0048176891,0.00645478582111,21.7398511398,19.9969636996,-0.000926097222076,-0.0543297632581,-0.00651577060174,0.190282851269,-0.00107565729748 +47.03,51.0048194867,0.00645478581718,21.7403917471,19.9987420136,0.000870955875686,-0.0537917119017,-0.00451746646487,0.185077311615,0.000652324617606 +47.04,51.0048212843,0.00645478594778,21.740924958,19.9976791569,0.00096243721168,-0.0528504524785,-0.00421002275471,0.183710015871,0.00106730497875 +47.05,51.0048230819,0.00645478615549,21.7414571747,19.9969086794,0.00195337839699,-0.0535929017327,-0.00169209925576,0.181642493691,0.00034585514774 +47.06,51.0048248793,0.00645478639861,21.7419849386,19.9967765038,0.00145965763715,-0.0519598679955,-0.00337677009575,0.181407652701,0.00144055893364 +47.07,51.0048266769,0.00645478660931,21.7425027446,19.9974690401,0.00149810036954,-0.0516013437829,-0.00326420302132,0.178348072288,0.000878098644738 +47.08,51.0048284744,0.0064547867807,21.7430149851,19.9978044579,0.000907892982349,-0.0508467570065,-0.00352384220714,0.177488240279,0.000890659330724 +47.09,51.004830272,0.00645478696591,21.7435194222,19.9973369242,0.0016922078743,-0.0500406624052,-0.00163748384868,0.176866150296,0.00373666877723 +47.1,51.0048320695,0.00645478718794,21.7440158648,19.9978718317,0.00142458200542,-0.0492478598608,-0.000435641419895,0.17828428681,0.00227423333984 +47.11,51.0048338671,0.00645478750244,21.7445133338,19.9972848106,0.00299038914749,-0.0502459364117,0.000324004969968,0.17512747794,0.000538119918948 +47.12,51.0048356647,0.0064547876817,21.7450158527,19.9979554939,-0.000473931711728,-0.0502578354946,-0.00119941458099,0.174459148892,0.000952998562526 +47.13,51.0048374623,0.00645478761187,21.7455153591,19.9985015541,-0.000506289184962,-0.0496434546813,-0.0021824194954,0.173564893058,0.000385252223155 +47.14,51.0048392599,0.00645478765568,21.7460103224,19.9981215759,0.00112130130013,-0.0493491942971,-0.00059061598465,0.170732890206,0.00229831123354 +47.15,51.0048410574,0.00645478776826,21.7465003884,19.996940911,0.000459173385375,-0.0486640087565,-0.000723282090519,0.167702306066,0.0019708455482 +47.16,51.004842855,0.00645478790891,21.7469890389,19.9983174904,0.00151525444795,-0.0490660917875,-0.00131067446385,0.168048927463,2.64593476387e-005 +47.17,51.0048446527,0.00645478812276,21.74747536,20.0010325194,0.00148673323642,-0.0481981306077,-0.00117295225524,0.169014350796,-0.000279792568655 +47.18,51.0048464506,0.00645478834872,21.7479644754,19.9999110319,0.0016853274066,-0.0496249429478,-0.000924714406942,0.164737300203,-0.000743716973273 +47.19,51.0048482483,0.00645478852106,21.7484616607,19.9997770897,0.00073409671126,-0.0498121154018,-0.000732698088338,0.166814740143,0.000532052142994 +47.2,51.004850046,0.00645478863088,21.7489441901,19.9988702185,0.000807513275317,-0.0466937669007,-0.000552434676865,0.163108266895,0.00114842972415 +47.21,51.0048518437,0.00645478865902,21.749413119,19.9988206081,-0.00041252055089,-0.0470920253823,4.96267022495e-005,0.162032260592,0.0020391565525 +47.22,51.0048536414,0.00645478867172,21.7498850055,19.998665355,0.000590879983851,-0.0472852625347,-0.0003072887714,0.159439922412,0.000161723299198 +47.23,51.0048554389,0.00645478883277,21.7503453529,19.9968132885,0.00166995027056,-0.0447842154217,-0.00134161575766,0.15856081028,-0.00103976080571 +47.24,51.0048572365,0.00645478898965,21.7508020224,19.9980677184,0.000532299240278,-0.0465496915466,0.000296659204499,0.158678763322,-0.000998456596379 +47.25,51.0048590341,0.00645478908895,21.7512605288,19.99960098,0.000861661531941,-0.0451515910638,-0.000511827578465,0.156468189651,0.000410300787262 +47.26,51.0048608319,0.00645478931407,21.7517203211,20.0000021172,0.00229860772031,-0.0468068704257,-0.00115610968909,0.153301655259,-0.0012144798471 +47.27,51.0048626296,0.00645478963263,21.7521858554,19.9977956683,0.00217338073154,-0.0462999742197,0.000312774769922,0.154969486907,-0.000708540218152 +47.28,51.0048644272,0.0064547898453,21.7526387227,19.999124006,0.000812142690204,-0.0442734928057,-9.90260484842e-005,0.153272343868,0.000340139175296 +47.29,51.004866225,0.00645478995322,21.7530795473,20.0017333149,0.00070285317936,-0.0438914392145,0.000181731834895,0.153241246968,0.000691442480605 +47.3,51.0048680229,0.00645479002407,21.753516759,20.001423576,0.000291776487677,-0.0435508937061,-0.000361795369003,0.150969578425,0.000798296870575 +47.31,51.0048698208,0.00645479002701,21.7539448071,20.0010164348,-0.000250530744396,-0.0420587255263,1.08825472679e-005,0.151063038463,0.00175230589313 +47.32,51.0048716187,0.00645479001942,21.7543675519,20.0010808715,0.000143926555738,-0.0424902259402,0.000315817031476,0.147395062564,0.00086590086141 +47.33,51.0048734166,0.00645479008363,21.7547980604,20.0018246399,0.000757515252964,-0.0436114798623,0.000708549091523,0.144142837263,0.000337650000906 +47.34,51.0048752144,0.00645479013313,21.7552295247,19.9997059738,-6.26794643912e-005,-0.0426813769451,0.000982575853511,0.144308540431,-0.00126416181559 +47.35,51.0048770122,0.00645479013385,21.7556566089,19.9998324343,7.27789518513e-005,-0.0427354635116,0.000974370007907,0.144565522236,-0.000432542278645 +47.36,51.0048788099,0.00645479013903,21.7560802862,20,0,-0.042,0,0.143,0 +47.37,51.0048806077,0.00645479007306,21.7564989901,20.0006246002,-0.000926057636418,-0.0417407746525,-0.00119773503335,0.142593549682,0.00197424290643 +47.38,51.0048824056,0.00645478999253,21.7569046154,20.0017024926,-0.000204523564226,-0.0393842840324,1.80171277983e-005,0.143089358621,0.00210600472569 +47.39,51.0048842035,0.00645478992744,21.7573128938,20.0017169242,-0.000709180506534,-0.0422713929951,0.000167279795439,0.141607709524,0.00220267518614 +47.4,51.0048860015,0.00645478989972,21.7577298123,20.0022217652,0.000320092251803,-0.0411123211516,-0.000132695078724,0.139568515155,0.00175424318819 +47.41,51.0048877995,0.00645478996582,21.758129362,20.002287272,0.000607840989581,-0.0387976059771,-0.000767397267741,0.137305966007,0.000544387661501 +47.42,51.0048895975,0.00645478992508,21.7585221002,20.0027066973,-0.00117980131445,-0.0397500473465,-0.00111324228145,0.136100761515,0.00383143129059 +47.43,51.0048913955,0.00645478986598,21.7589154131,20.0022208303,0.00035019050373,-0.0389125322476,-0.00125612865632,0.132412979766,0.00305166900396 +47.44,51.0048931934,0.00645478984915,21.7593058146,20.0018378146,-0.000586479146282,-0.0391677653942,0.000290213225773,0.130643303082,0.00106170321317 +47.45,51.0048949914,0.0064547897949,21.759700357,20.0021664769,-0.000175062595122,-0.0397407095806,-0.000874610627589,0.131772501649,0.00123392829223 +47.46,51.0048967893,0.00645478965626,21.7600879349,20.0021862542,-0.00177129811881,-0.0377748798777,-0.000890684425219,0.129453245746,-7.47567519505e-005 +47.47,51.0048985873,0.00645478957289,21.7604640188,20.0008993803,0.000601033516178,-0.0374418943615,-0.00283734130784,0.12985699451,0.00100400175512 +47.48,51.0049003852,0.00645478951332,21.7608371199,20.0021343112,-0.00143732500589,-0.0371783162857,-0.00141354853488,0.128430147383,0.000575032404433 +47.49,51.0049021832,0.00645478930816,21.7612056918,20.0033463147,-0.00144270528932,-0.0365360629213,-0.000803322367224,0.128522894672,-0.00103013458002 +47.5,51.0049039812,0.00645478916343,21.7615726123,20.0029928481,-0.000589113361748,-0.0368480522397,-0.000745544209523,0.12617575123,-0.000539542147964 +47.51,51.0049057792,0.00645478902932,21.7619402629,20.0020971766,-0.0012934728493,-0.0366820631055,-0.00171250242995,0.125811054193,0.000955216915025 +47.52,51.0049075772,0.00645478896732,21.7623095069,20.0022549448,0.000423107302368,-0.0371667314159,-0.00158724087208,0.123738209195,-0.000447941924081 +47.53,51.0049093752,0.00645478906271,21.7626905516,20.0025776358,0.000915948906943,-0.0390422030651,-0.00287525722367,0.122762707452,-5.01624438522e-005 +47.54,51.0049111732,0.00645478928646,21.7630695109,20.0018038819,0.0022251399533,-0.0367496575081,-3.09722727931e-006,0.120742129286,-0.000892251471241 +47.55,51.0049129711,0.00645478968744,21.7634386989,20.0016690317,0.00340380193567,-0.037087948269,0.00234572497165,0.119559604432,-0.00217594403932 +47.56,51.0049147689,0.00645479003898,21.7637993686,19.9997396949,0.00153122835805,-0.0350459880868,-0.00106923175031,0.118372811387,-0.000909330602736 +47.57,51.0049165668,0.00645479023299,21.7641539317,20.0015980267,0.00119232623748,-0.0358666422638,0.000794770331528,0.117403559693,-0.000552620243535 +47.58,51.0049183647,0.00645479041183,21.7645122028,20.0014316053,0.00131813495336,-0.0357875715208,-0.00106948538977,0.118355438795,0.00043411525341 +47.59,51.0049201626,0.00645479051083,21.7648675265,20.0013030519,7.16497174118e-005,-0.0352771700256,-0.000627751793983,0.117234933775,0.00056571354244 +47.6,51.0049219605,0.00645479057351,21.7652162183,20.0010784187,0.000808324170472,-0.0344611990068,-0.00197063911962,0.116489487351,0.00107224296693 +47.61,51.0049237584,0.00645479089485,21.765557337,20.0033470113,0.00370260515243,-0.0337625275521,-0.00376473617472,0.113803721215,0.00178801168879 +47.62,51.0049255565,0.00645479137868,21.7658937404,20.0035883079,0.00308949927669,-0.03351814938,-0.00389703615105,0.113611082294,0.00137315555599 +47.63,51.0049273546,0.00645479183286,21.7662197187,20.0032334225,0.00328635430408,-0.0316775139681,-0.00337380695004,0.112066657614,0.00403341329366 +47.64,51.0049291527,0.00645479217475,21.7665472773,20.0033334427,0.00151302597535,-0.033834206624,-0.0018667655401,0.111225625044,0.0016565610317 +47.65,51.0049309508,0.00645479235036,21.7668727514,20.0041295642,0.000952317556008,-0.0312606089247,0.000794671123482,0.109269110272,0.00438127893999 +47.66,51.0049327489,0.00645479254861,21.7671926459,20.0037069722,0.0018306742936,-0.0327182955697,-0.000466861906416,0.108701693745,0.00429087378467 +47.67,51.004934547,0.00645479280807,21.7675187448,20.0039611446,0.00181164493548,-0.0325014851072,-0.00147091504822,0.10857755272,0.00133278221984 +47.68,51.0049363451,0.0064547929996,21.7678435191,20.003361124,0.000877049529092,-0.0324533714944,-0.00107136442243,0.105678006247,0.00151150830456 +47.69,51.0049381431,0.0064547930495,21.768162606,20.0015610045,-0.000176444546828,-0.0313640206104,-0.000715007009868,0.105252431373,-6.92647089823e-005 +47.7,51.0049399411,0.00645479305651,21.7684859779,20.0025640665,0.00027476743044,-0.0333103521465,0.0013025531309,0.103461058461,0.0011325069373 +47.71,51.004941739,0.00645479321214,21.7688067516,20.0019456779,0.00191003673842,-0.0308443851533,-0.000677888570511,0.101832529939,0.00255986778226 +47.72,51.004943537,0.00645479333936,21.7691220506,20.0024843477,-0.000124142645753,-0.0322154255599,0.00161608964178,0.0992736319658,0.000547955563361 +47.73,51.0049453349,0.00645479318719,21.7694444316,20.0011759306,-0.00201199507406,-0.0322607766942,0.000965454420957,0.0944931059856,-0.00048995628269 +47.74,51.0049471329,0.00645479301331,21.7697623504,20.0021883336,-0.000428972113536,-0.0313229846463,1.6618280827e-005,0.0956517091625,0.00174890816607 +47.75,51.0049489308,0.00645479300072,21.7700703454,20.001590186,0.000252260436826,-0.0302760132781,0.000691276552022,0.0956520665251,0.000127865985765 +47.76,51.0049507288,0.0064547931643,21.7703767824,20.0023991937,0.00204398503705,-0.031011380697,0.000346869758087,0.094904454508,0.00120201427878 +47.77,51.0049525268,0.00645479340694,21.7706830126,20.0043777422,0.00136232928407,-0.0302346661634,0.00170124286367,0.0917465033964,0.00243186700532 +47.78,51.0049543249,0.00645479361043,21.7709928611,20.0023234087,0.00149422455954,-0.0317350280176,0.000721364319,0.093340555738,0.000855762537175 +47.79,51.0049561228,0.00645479376437,21.7713042874,20.0000518327,0.000666855245227,-0.030550228398,-0.00150493776871,0.091453498393,0.00269088698884 +47.8,51.0049579206,0.00645479393333,21.7716055894,20.0005755009,0.00170492835739,-0.0297101689846,0.000999874828605,0.0923099315033,0.000750765896022 +47.81,51.0049597185,0.00645479420042,21.7718960926,20.0021953403,0.00204456665912,-0.028390471447,-0.000396680139784,0.0924812953106,0.00227539846755 +47.82,51.0049615165,0.00645479437709,21.7721785029,20.0027267225,0.000435486997285,-0.028091601576,0.00182958888118,0.0922967943405,0.000559089730333 +47.83,51.0049633144,0.0064547945785,21.7724524986,20.0013406971,0.00239200887725,-0.0267075334702,0.00374707743051,0.0904374339921,0.0020683263371 +47.84,51.0049651124,0.00645479486205,21.7727208439,20.0021464723,0.00158843782625,-0.0269615168797,0.00123005745915,0.0893124841112,0.000491206632154 +47.85,51.0049669104,0.00645479508335,21.7729797477,20.0025103394,0.0015181606075,-0.0248192579288,0.00136238264652,0.0875168351535,0.000536577794751 +47.86,51.0049687083,0.00645479534783,21.7732399328,20.0019559113,0.00219471768565,-0.0272177469398,0.00321092541711,0.0873373231559,0.00122397266789 +47.87,51.0049705063,0.00645479569382,21.7735066047,20.0024710679,0.00266221104248,-0.0261166371446,0.00389606000605,0.0859271462896,0.000521260435751 +47.88,51.0049723043,0.00645479602566,21.7737625571,20.001541965,0.00199626719206,-0.0250738363421,0.000166686865785,0.0866832910538,0.000560552240827 +47.89,51.0049741021,0.00645479625017,21.7740139796,20.00054004,0.00115543715898,-0.0252106667216,-0.000364133762313,0.085968695373,-0.00117365001508 +47.9,51.0049758999,0.00645479642303,21.7742617631,19.9988595626,0.0012711222944,-0.0243460401282,-0.000771959513221,0.0841087370289,-0.000694284824228 +47.91,51.0049776976,0.00645479662283,21.7745122388,19.9991855083,0.00153377300608,-0.02574910769,0.00131951598002,0.0826436489342,0.000404911122654 +47.92,51.0049794953,0.00645479690295,21.7747587915,19.999803256,0.00239851687424,-0.0235614263038,0.000742153413216,0.0815065624291,0.000617914293977 +47.93,51.004981293,0.00645479727174,21.7749868934,19.9987548286,0.00277861409437,-0.0220589546022,-0.00194480633917,0.080477337546,-0.00152934844028 +47.94,51.0049830907,0.00645479762141,21.7752107425,20.000210875,0.00212998591682,-0.0227108555563,-0.00286014933907,0.0809692448902,7.65859081947e-005 +47.95,51.0049848886,0.0064547979896,21.7754383978,20.0012191479,0.00303878043626,-0.0228202103479,-0.0005873234465,0.0790270638826,0.00135712631618 +47.96,51.0049866864,0.0064547983656,21.7756641391,20.0008973445,0.0022394573727,-0.0223280541288,-0.00216305512579,0.0770479494329,-0.000824744209739 +47.97,51.0049884843,0.00645479863562,21.7758920263,20.0015241601,0.00155114788097,-0.0232493857186,-0.00204979673827,0.0777618305778,-0.00237807436031 +47.98,51.0049902822,0.00645479897756,21.7761180544,20.0011527789,0.0032489919815,-0.021956230405,-0.000940264401834,0.0760911374951,-0.00189385790619 +47.99,51.00499208,0.00645479947725,21.7763406867,19.9994194851,0.00376575104889,-0.0225702342722,-0.00108904227461,0.0737776747827,-0.00032048964002 +48,51.0049938778,0.00645479991754,21.7765591081,20.0003196615,0.00241500573993,-0.0211140318797,0.000135236560413,0.0726455614681,-0.000409846974111 +48.01,51.0049956755,0.00645480020226,21.7767658289,19.999730308,0.00158199438647,-0.0202301290554,0.000338533487695,0.0690359879533,-0.000725676468462 +48.02,51.0049974733,0.00645480031057,21.776970814,20.0009378947,-6.15221315021e-005,-0.0207669051265,-6.77548165202e-005,0.0685567850513,0.000760729743565 +48.03,51.0049992712,0.00645480020444,21.7771606137,20.0010549442,-0.00142833441787,-0.017193035174,-0.0023202294769,0.0676908859898,0.00129434663993 +48.04,51.005001069,0.00645480021683,21.7773437212,19.9987882306,0.00160225129554,-0.0194284620493,-0.00133899706461,0.0674159896634,0.000780479881162 +48.05,51.0050028667,0.00645480042405,21.7775424284,20.0001601917,0.00130671180773,-0.0203129720239,-0.00260606064165,0.0648732185484,-0.000337348261015 +48.06,51.0050046645,0.00645480054833,21.7777412409,20.0012848592,0.000437931883144,-0.0194495253478,-0.00392157483205,0.06471033285,-0.000132894469863 +48.07,51.0050064624,0.00645480060634,21.7779323864,20.0017820241,0.000376403256535,-0.018779579767,-0.00475645442281,0.065797325192,-0.000482594160993 +48.08,51.0050082603,0.00645480071727,21.7781190847,20.0004705833,0.00118085752501,-0.0185600716089,-0.00175232593563,0.0648814190733,-0.000107482314766 +48.09,51.0050100581,0.0064548007998,21.7783021003,20.0003124053,-2.22741745053e-005,-0.0180430551481,-0.00176135870414,0.0633539657158,-5.7002515685e-005 +48.1,51.005011856,0.00645480089223,21.7784844141,20.0023971339,0.00131974713385,-0.0184197155257,-0.002250264011,0.0630748656741,0.000441705961004 +48.11,51.005013654,0.00645480102187,21.7786648528,20.0018243386,0.000500144333548,-0.017668019369,-0.00145745096597,0.0612864239104,0.00147098533386 +48.12,51.0050154519,0.0064548011575,21.778841477,20.0015656314,0.00140381386957,-0.0176568089229,-0.00118586625631,0.0588604900123,-0.000515227407525 +48.13,51.0050172498,0.00645480145373,21.7790158452,20.0017592336,0.00275476392769,-0.0172168376222,-0.00173792235022,0.060887450961,0.000939699589779 +48.14,51.0050190477,0.00645480178913,21.7791840955,19.9996844157,0.00195360463053,-0.0164332290748,-0.0025633074144,0.0572530680652,-0.000553707646405 +48.15,51.0050208454,0.00645480192497,21.7793429389,19.9995841342,-4.66616922796e-005,-0.0153354491959,0.000151901920442,0.0578485210558,-0.000402047627261 +48.16,51.0050226431,0.00645480189681,21.7794980374,19.9988734278,-0.000348616542231,-0.015684242416,-0.00286098833164,0.0557363543178,-0.000236376669488 +48.17,51.0050244408,0.00645480178451,21.7796495244,20.0001338123,-0.00122792048407,-0.0146131675056,-0.00494772411653,0.0554660040709,0.000808852794886 +48.18,51.0050262385,0.00645480168515,21.7797934075,19.9984907444,-0.000166966990189,-0.0141634561131,-0.00312482118715,0.0544367201095,0.0019355391982 +48.19,51.0050280363,0.00645480163245,21.7799264563,20.0007199874,-0.000572786347239,-0.012446301236,-0.00316567316298,0.0521321466178,0.00142803233387 +48.2,51.0050298341,0.00645480152981,21.7800586064,19.9996794485,-0.000868062382919,-0.0139837097676,-0.00222387092731,0.0534638216332,-7.64099618624e-005 +48.21,51.0050316318,0.00645480161446,21.7801896288,19.9987075584,0.00205641659473,-0.0122207641587,-0.00315369287017,0.0516847810536,0.000225487500595 +48.22,51.0050334294,0.00645480178647,21.7803075928,19.9981098072,0.000358279752266,-0.0113720521464,-0.00157800430752,0.0496277458108,0.000205657876509 +48.23,51.005035227,0.00645480180504,21.7804234456,19.9975581446,-9.76957680733e-005,-0.0117984980317,-0.00171769055937,0.0488848761459,0.000574027552889 +48.24,51.0050370245,0.00645480181076,21.7805405984,19.9976985119,0.000178036265272,-0.0116320677858,-0.00273299698605,0.0490087457079,0.00100562712143 +48.25,51.0050388221,0.00645480185421,21.7806445856,19.9980099244,0.000431964364787,-0.0091653771204,-0.00216033264385,0.0478229026657,-8.62411375961e-005 +48.26,51.0050406197,0.00645480192449,21.7807372251,19.9979141075,0.00055458536353,-0.00936251548221,-0.00249698868342,0.0477158820417,0.000110853132966 +48.27,51.0050424172,0.00645480202119,21.7808230104,19.9967669465,0.000802913723423,-0.00779454908577,-0.00150225297695,0.0501951527454,-0.0015219552745 +48.28,51.0050442147,0.00645480207342,21.7809085824,19.9970290212,-6.96469566316e-005,-0.00931983840789,-0.00129950922388,0.0460323874589,-0.00019086661971 +48.29,51.0050460123,0.00645480209675,21.7809967141,19.9975173631,0.00039704137114,-0.00830649958663,-0.000374575920886,0.0437068432439,-0.000271303179085 +48.3,51.0050478099,0.00645480213152,21.781070907,19.9984259361,9.11754495652e-005,-0.00653208492359,0.000877913292162,0.0430836232506,-0.000157422010447 +48.31,51.0050496075,0.00645480228319,21.7811432457,19.9977637315,0.00203786935182,-0.00793565856938,0.00241610260524,0.0423004507596,-0.000327116615797 +48.32,51.0050514051,0.00645480245369,21.7812303221,19.998527384,0.000355685938366,-0.0094796156708,-0.000436697536144,0.0401363695415,-8.59825485987e-005 +48.33,51.0050532027,0.00645480233554,21.78132837,19.9981845852,-0.00201428140553,-0.0101299689067,-0.00218804154658,0.0377423361378,-0.00302644508448 +48.34,51.0050550003,0.00645480212189,21.7814282601,19.997219931,-0.000985030939928,-0.0098480518315,-0.00159656638772,0.0360182540476,-0.0027968094012 +48.35,51.0050567978,0.00645480198629,21.7815205488,19.9977438526,-0.000918462429098,-0.00860969104154,-0.00188751186276,0.0355266211613,-0.00115805252088 +48.36,51.0050585954,0.00645480188638,21.7816108572,19.9977225855,-0.000484118762517,-0.00945199251427,0.000302406912595,0.0338354700329,-0.00190057599742 +48.37,51.0050603929,0.00645480186752,21.7817023275,19.9971041376,0.000219379154888,-0.00884205632948,-0.000525460253112,0.0318533252175,-0.000813330257754 +48.38,51.0050621905,0.00645480173341,21.7817898206,19.998260678,-0.00210200985914,-0.00865657376293,0.00109210174935,0.0298249372677,0.00050966208862 +48.39,51.0050639881,0.00645480149473,21.7818846489,19.9986226053,-0.00124860623469,-0.0103090884904,0.000593596161034,0.027926051196,-0.000460018264167 +48.4,51.0050657858,0.0064548013362,21.7819741231,19.999522354,-0.000976867139008,-0.00758573521614,0.000938566931294,0.0273808861431,-0.0013639366221 +48.41,51.0050675835,0.00645480105725,21.7820492235,19.9995929096,-0.00293902176827,-0.00743436306941,-0.00170571638799,0.0252179848685,-0.00186332293439 +48.42,51.0050693812,0.00645480064118,21.7821178655,19.9986824028,-0.00290173303299,-0.00629402253979,-0.00103358318101,0.0248059880875,-0.000700325770625 +48.43,51.0050711788,0.00645480019836,21.7821750083,19.9969488253,-0.00331463982068,-0.00513453514479,-0.00155828603131,0.0236618153992,-0.000615147656369 +48.44,51.0050729764,0.0064547998164,21.7822314555,19.9994059408,-0.00204738681279,-0.00615490805996,-0.000395555621065,0.0226702013828,-0.000599325657572 +48.45,51.0050747741,0.00645479951151,21.7822839614,19.9982788861,-0.00223260708229,-0.00434627506213,-0.000727758230216,0.0221261878591,-0.00319862194664 +48.46,51.0050765719,0.00645479933723,21.7823325965,20.0019765483,-0.000213936571218,-0.00538074748298,0.00028137746488,0.0209286247912,-0.00218162823192 +48.47,51.0050783699,0.00645479923924,21.782385258,20.0035162165,-0.00116162449908,-0.00515154325529,-0.000789086626928,0.0204103507812,-0.00195047914906 +48.48,51.0050801678,0.0064547991107,21.7824331874,20.000519415,-0.000642918265637,-0.00443434806595,-0.00021838212868,0.017497012081,-0.00217822789437 +48.49,51.0050819657,0.00645479897044,21.7824825416,20.0011156097,-0.00132598345913,-0.00543649647209,-0.000303706893842,0.0150459671685,-0.00132765987337 +48.5,51.0050837636,0.00645479880027,21.7825252183,20.0012924522,-0.00106297318375,-0.00309883268221,0.000666459923751,0.013990247424,-0.00236846729728 +48.51,51.0050855614,0.0064547985061,21.7825617932,19.9999452075,-0.00306649712718,-0.00421615199662,0.00130538526054,0.0135419878374,-0.00196058596118 +48.52,51.0050873592,0.00645479808948,21.7825944398,20.0005068005,-0.00278207595187,-0.0023131740259,0.00228135758731,0.0118944930618,-0.00182995482291 +48.53,51.005089157,0.00645479778928,21.7826177149,20.0000802389,-0.00143218740886,-0.00234183419046,-0.000540038428751,0.00888071007717,-0.00178761918457 +48.54,51.0050909547,0.00645479750978,21.7826310066,19.999295215,-0.00249137382376,-0.000316501204034,0.0013054208033,0.00900153175045,5.93302242968e-005 +48.55,51.0050927525,0.00645479717796,21.7826449888,20.0002479881,-0.00216676727566,-0.00247995351183,7.17127882842e-005,0.00631169592,0.00147169588923 +48.56,51.0050945503,0.00645479694782,21.7826679159,20.0005497165,-0.0010639756536,-0.00210545500608,0.000501954965094,0.00827965470438,-0.00114221932177 +48.57,51.0050963481,0.00645479696001,21.7826915738,19.9998412951,0.00123513316187,-0.00262613571479,-0.000285400489646,0.00496509871201,-0.0026040639758 +48.58,51.0050981459,0.00645479700655,21.7827175606,19.9998436901,-0.000581837452364,-0.00257121755746,0.000111789731218,0.00487328363475,-0.00170244168426 +48.59,51.0050999436,0.00645479696487,21.7827367753,19.9991481832,-3.22891276893e-006,-0.0012717153168,0.00232815116941,0.00240821991123,-0.00106580516979 +48.6,51.0051017414,0.00645479689508,21.7827469293,20.0008412784,-0.000976479359085,-0.000759092033312,0.00168986925517,0.00205622049568,-0.000812134526866 +48.61,51.0051035392,0.00645479663928,21.7827549227,20.000870789,-0.00261449503008,-0.000839591648868,0.0011874760911,-0.000346652437654,0.00268325973523 +48.62,51.005105337,0.00645479629784,21.7827614191,20.0007506675,-0.00217865170681,-0.000459693119607,0.0005629145189,0.000638052249775,0.000337106438259 +48.63,51.0051071348,0.00645479593899,21.7827654711,19.9997331206,-0.00285886092701,-0.000350709422368,0.000678230458261,0.000713237533639,0.000803300992398 +48.64,51.0051089326,0.00645479573534,21.7827672247,20,0,0,0,0,0 +48.65,51.0051107304,0.0064547958089,21.7827689825,19.9997491982,0.00103268492469,-0.000351559076001,-0.00162050063178,-0.000428180407405,0.000387137760896 +48.66,51.0051125281,0.00645479596856,21.7827739029,19.9989538026,0.00120861096092,-0.000632516695752,0.00079827351954,0.00147450045883,0.00255459037071 +48.67,51.0051143258,0.00645479630453,21.782776722,19.9996972184,0.00350775104429,6.86951202863e-005,0.000637577870447,0.00248526400452,0.00273713149682 +48.68,51.0051161235,0.00645479679267,21.7827762362,19.9992688819,0.00334478827496,2.84563967282e-005,-0.000630568844486,0.000706241012935,0.000512980346036 +48.69,51.0051179212,0.00645479712667,21.7827794901,19.9996015264,0.00134380805297,-0.000679228051491,0.000111785929381,0.00143187839614,0.000919460609966 +48.7,51.005119719,0.00645479740969,21.7827883923,20.0005991123,0.00262926291393,-0.00110120996055,0.00055381070407,0.00112380708434,0.00117805036869 +48.71,51.0051215168,0.00645479761352,21.7827892303,20.0000104942,0.000232211779289,0.000933602337216,0.000167585117061,0.00171396868857,-0.000126824376542 +48.72,51.0051233146,0.00645479777432,21.7827864607,19.9996837196,0.00202506752446,-0.000379689951696,0.000222854115621,0.000459766174191,8.23660194454e-005 +48.73,51.0051251123,0.00645479812827,21.7827833662,19.9990338695,0.00294368198737,0.000998599014458,0.00135436384955,-0.00118305029232,-0.000985904053544 +48.74,51.00512691,0.00645479852323,21.7827732586,19.9994865248,0.00260083162254,0.00102291388482,0.00053088055807,-0.00044059781983,-0.000168596480088 +48.75,51.0051287078,0.00645479883941,21.7827658138,20.0005611726,0.00183768261675,0.000466054160542,0.00213472336942,-0.00023920598503,-0.000120961766655 +48.76,51.0051305056,0.00645479923307,21.7827628467,20.0001692561,0.00368843915451,0.000127357869477,0.00214456674779,-0.0011755086219,-0.00127059996101 +48.77,51.0051323034,0.00645479972169,21.7827663923,19.9997479195,0.00317088884121,-0.000836467380634,0.00218330433002,-0.00314123982031,-0.00359817333365 +48.78,51.0051341011,0.00645480005191,21.7827745366,20.000201163,0.00146471371802,-0.000792397824515,0.00474557066562,-0.00150289414866,-0.00134849305106 +48.79,51.0051358989,0.00645480015084,21.7827809631,19.9988781263,-7.58676755692e-005,-0.000492899027317,0.00215623829881,-0.00168055070734,-0.000461337489349 +48.8,51.0051376966,0.00645480026118,21.7827916063,19.999404098,0.00162477342308,-0.00163575166464,0.000789428868095,-0.000859047311604,0.000336533409115 +48.81,51.0051394942,0.0064548005375,21.7828078574,19.997320661,0.00225417541938,-0.00161445136092,0.000258868637419,0.000767061080833,-0.00101247360707 +48.82,51.0051412918,0.00645480081815,21.7828189469,19.9984753142,0.00168567113478,-0.000603450503762,0.0027547153569,-0.0010342594687,-0.000765416702949 +48.83,51.0051430894,0.00645480107537,21.7828287733,19.9988395376,0.00192525266825,-0.00136182682895,0.00385043412666,-0.000752862165693,-0.000304129526209 +48.84,51.0051448871,0.00645480125125,21.7828449332,19.9983781857,0.000543658211379,-0.00187015634659,0.00157931158484,-0.000291442211807,0.000632998659309 +48.85,51.0051466847,0.00645480119453,21.7828746764,19.9990632695,-0.001339856965,-0.0040784949837,0.000671677376997,0.000764260476737,0.000767963100022 +48.86,51.0051484824,0.00645480119251,21.7829090606,19.9993770182,0.0013115160745,-0.00279834716273,0.000975789857787,0.000314953108518,0.00147863164836 +48.87,51.0051502802,0.00645480148915,21.7829351272,20.0001954914,0.00285264293458,-0.00241496440443,-2.95775077574e-005,0.00157597624603,0.00204334645767 +48.88,51.0051520779,0.00645480180441,21.782961304,19.9993696641,0.00157302544276,-0.00282039524394,0.00120653545349,0.000127483451122,0.00347680432334 +48.89,51.0051538757,0.00645480210351,21.7829849898,19.999985931,0.00262577435508,-0.00191676582553,0.00112699828631,-0.00194784186443,0.00583481339865 +48.9,51.0051556734,0.00645480239028,21.7830045802,19.9990125167,0.00139994500789,-0.00200131648789,-0.00053631951688,0.000270728964711,0.00445869401892 +48.91,51.0051574711,0.00645480265591,21.7830329204,19.999153096,0.00232899756832,-0.00366672850971,-0.00040118507811,-3.49946558356e-005,0.00579784513043 +48.92,51.0051592688,0.00645480296925,21.7830606353,19.9989157495,0.00206962374008,-0.00187624300853,0.000341209607381,0.000819387829209,0.00214943453301 +48.93,51.0051610664,0.00645480319177,21.7830797256,19.9985662979,0.0010540427898,-0.00194181476377,-0.000874778853986,-0.000664332646598,0.00271882698771 +48.94,51.0051628641,0.00645480351472,21.7831028522,19.9980385077,0.00347957481868,-0.00268350055637,0.000114425948178,0.000365467599749,0.001386166312 +48.95,51.0051646617,0.00645480392612,21.7831357874,20.0001632861,0.00229572968946,-0.00390355674133,0.00133365129091,0.00116678571987,0.00255150122385 +48.96,51.0051664595,0.00645480414651,21.7831656273,19.9991994081,0.000798102624968,-0.00206440749407,2.4529256064e-005,-5.34903676711e-005,0.00313158587592 +48.97,51.0051682572,0.00645480409272,21.7831869253,19.9989250014,-0.00155318930791,-0.00219520010288,0.0013091235369,0.000325706486088,0.00344792663922 +48.98,51.0051700548,0.00645480408403,21.7832108216,19.9984051068,0.00143120110287,-0.00258406161573,0.000216253203993,0.00042368969211,0.00352196551802 +48.99,51.0051718525,0.00645480423614,21.7832419433,19.9983605775,0.000704136621392,-0.00364027982765,-0.0012993481996,0.000860276186954,0.00255275991462 +49,51.00517365,0.00645480433623,21.7832712689,19.9966021226,0.000700837813989,-0.00222482781679,0.000373140522615,0.0010041914547,0.00289848521057 +49.01,51.0051754474,0.00645480437275,21.7832939404,19.9951460141,-0.000188166810714,-0.00230947108016,0.00149046156777,0.00296350170255,0.00374188376309 +49.02,51.0051772448,0.00645480432318,21.7833175,19.996758974,-0.000507659176666,-0.00240246152432,0.00205217855628,0.000848502773248,0.00286324381865 +49.03,51.0051790423,0.00645480427867,21.7833371696,19.9959154748,-0.000117236504188,-0.00153144640837,0.000896238963819,0.00137130781121,0.00248233891682 +49.04,51.0051808397,0.00645480429861,21.7833485382,19.9969441639,0.000397206517667,-0.000742277263914,0.000791094496697,0.000418534438044,0.00187236956591 +49.05,51.0051826373,0.00645480427734,21.7833564481,19.9981789027,-0.000695748763524,-0.000839700389817,0.000431024902055,1.73939268875e-005,0.000994974290941 +49.06,51.0051844349,0.00645480417675,21.7833691108,19.9990977937,-0.000716423691055,-0.00169285666619,0.00106430459279,0.00036637885673,0.000806611475488 +49.07,51.0051862326,0.00645480410202,21.7833907665,19.9996596543,-0.000332585372808,-0.00263826608212,0.000391695595502,0.00126285713856,0.00311759591854 +49.08,51.0051880303,0.0064548040984,21.7834157181,19.9977030696,0.000281770140776,-0.00235206250806,0.0011720504922,-0.00090139924045,0.0012323345959 +49.09,51.0051898278,0.00645480413695,21.7834403711,19.99721738,0.00025944924484,-0.00257853080338,0.00376570636845,0.000837779144426,0.00164375798378 +49.1,51.0051916255,0.00645480427554,21.7834738258,19.9992836348,0.00168600651078,-0.0041124095494,0.000943942161003,0.000409597545432,-0.00146260723151 +49.11,51.0051934231,0.00645480458349,21.7835067221,19.9977646776,0.00263701201388,-0.00246684781487,0.000949933462052,0.000595545884347,-0.000782104324273 +49.12,51.0051952207,0.00645480479201,21.7835343385,19.9982697048,0.000290159321571,-0.00305644863646,0.00056033209495,-0.0017702396809,0.00127836836429 +49.13,51.0051970184,0.00645480481112,21.7835631234,20.0000679278,-2.17984665197e-005,-0.00270053050848,-0.00060204039843,-3.94658136979e-005,-0.000355489080653 +49.14,51.0051988161,0.00645480480084,21.7835923967,19.9994695824,-0.000122628775381,-0.00315412391999,0.000369125076227,-0.0019706278965,0.00190780602473 +49.15,51.0052006139,0.00645480466681,21.783622558,20.0007164209,-0.00175883354305,-0.00287812928525,0.000456894193153,0.00152455846394,0.00198788546241 +49.16,51.0052024118,0.00645480453031,21.7836586804,20.0017226673,-0.00015737214903,-0.00434635237381,0.000561179127885,0.000658147157472,0.00139169765808 +49.17,51.0052042097,0.00645480447592,21.7836970607,20.0009727393,-0.000606070290524,-0.00332972024858,0.00102779643535,-0.00017140045309,-0.000249837648684 +49.18,51.0052060075,0.00645480442765,21.783740057,20.0002279278,-7.16441346872e-005,-0.00526952161032,0.00203629422379,-0.00219653146598,0.00110753865879 +49.19,51.0052078053,0.00645480455917,21.7837870307,20.0005672943,0.00191789948437,-0.00412521990806,0.00342224144438,-0.00199605714087,-0.000373351532551 +49.2,51.0052096031,0.00645480483254,21.7838299637,19.99980571,0.00191979154567,-0.00446138922675,0.00133555458409,9.36772096793e-005,0.000707434672127 +49.21,51.0052114009,0.00645480503761,21.7838744757,19.9995520721,0.000958908376233,-0.00444100769374,0.0019790933563,-0.00154069280412,0.00427096987879 +49.22,51.0052131986,0.00645480513001,21.7839170214,20.0004804329,0.000338171057292,-0.00406812748315,0.00251734789223,-0.00145247532591,0.00337068001451 +49.23,51.0052149965,0.00645480524059,21.7839565644,20.0013270239,0.00121419236237,-0.00384046870473,0.00362373757943,-0.00098773164969,0.00619389862288 +49.24,51.0052167944,0.00645480538523,21.7839876552,20.0008784973,0.00081631931037,-0.0023777061643,0.00120608852252,0.00126180648805,0.00204443004788 +49.25,51.0052185922,0.0064548055331,21.7840127827,20.0009488681,0.00125947110859,-0.00264778488983,0.000475729730187,0.000260325959093,-0.00012492557747 +49.26,51.00522039,0.00645480574099,21.7840391619,19.9994102225,0.00165889574143,-0.00262806616141,0.000829401423432,-0.0018396532559,-0.000493972458136 +49.27,51.0052221877,0.00645480601182,21.7840686092,19.9986597076,0.00214303889211,-0.00326137846909,0.001441932964,-0.00140318204463,0.00163814312246 +49.28,51.0052239854,0.00645480618168,21.784098592,19.9999449738,0.000241456372243,-0.00273518034125,0.000221750796448,-0.000166611057292,0.0016668210016 +49.29,51.0052257831,0.00645480620316,21.7841277217,19.9982974519,6.00413201791e-005,-0.00309076529797,0.00146555811869,0.000747690085268,0.00239386020248 +49.3,51.0052275807,0.00645480610702,21.7841580827,19.9986013785,-0.00140971782045,-0.00298144487913,0.000194363423034,0.00120033221877,0.00191841631248 +49.31,51.0052293783,0.00645480593411,21.784188644,19.9968693824,-0.00101758489207,-0.00313080727712,0.000628170800124,0.00161287898404,0.00258191994341 +49.32,51.0052311759,0.00645480580745,21.7842183578,19.9991754474,-0.00076045514568,-0.00281194588172,-0.000663587447063,0.000716487500212,0.00270047137871 +49.33,51.0052329736,0.00645480565336,21.7842421115,20.0001066119,-0.00140264387188,-0.00193881145755,-0.000787206909543,0.00177194117543,0.0014501776299 +49.34,51.0052347713,0.00645480540119,21.7842585626,19.9979066203,-0.00213735419261,-0.00135139152517,-0.00146025762359,0.000666420687137,0.000971405282722 +49.35,51.0052365689,0.00645480506037,21.784278473,19.9978690779,-0.00264710447982,-0.00263069247268,-0.00158120583572,0.00204225878016,0.00505336824681 +49.36,51.0052383665,0.00645480477005,21.7842922945,19.9978927208,-0.00142839527169,-0.000133602479337,-0.00203176550147,0.00118618049443,0.00292709431762 +49.37,51.005240164,0.00645480463595,21.7842860399,19.9965579017,-0.000454068861008,0.00138451357909,-0.00142413832974,0.000188610363045,0.00457475371691 +49.38,51.0052419615,0.00645480455053,21.7842723622,19.9972165765,-0.000745094186371,0.00135102172062,-0.000809058265777,-0.000163534758612,0.00250427292033 +49.39,51.0052437591,0.00645480433756,21.7842631775,19.9993752794,-0.00224450285578,0.000485923638961,4.08272427395e-006,0.00201736631786,0.00463093874601 +49.4,51.0052455568,0.00645480411499,21.7842658653,19.997836569,-0.000879951158748,-0.00102348826403,-0.000769421134524,-0.0018817650172,0.00361600822773 +49.41,51.0052473543,0.00645480412171,21.7842786765,19.9967629144,0.000974336808053,-0.00153873832732,-0.00248317492329,-0.00193990044028,0.000772606179295 +49.42,51.0052491518,0.00645480414032,21.7842880815,19.996745825,-0.000713082366289,-0.00034226150063,0.000265849132854,-0.000234397607906,0.00125286012605 +49.43,51.0052509493,0.00645480415264,21.7842828102,19.9975614733,0.000885970063385,0.00139650891569,0.00191834565275,-0.0030026170703,0.000193853304148 +49.44,51.0052527469,0.00645480417523,21.7842794188,19.9981695384,-0.00056884184222,-0.000718218823234,-0.00083143809713,-0.000738258847635,0.000915829546188 +49.45,51.0052545445,0.00645480412475,21.7842799653,19.9973541285,-0.000139786496513,0.000608907515343,0.000333184320409,0.000505389290813,0.000258768163528 +49.46,51.005256342,0.00645480411187,21.7842715148,19.997130217,-4.10638575337e-005,0.00108119789176,-0.00103424187414,0.00134564158357,0.000573290502656 +49.47,51.0052581395,0.00645480403956,21.7842651928,19.9984289476,-0.000973942000294,0.000183206364123,-0.00063581757793,0.000846692288047,4.74473072509e-005 +49.48,51.0052599371,0.00645480388405,21.7842593585,19.9968828191,-0.00120915989369,0.00098364740226,0.00124226393406,0.000924719886507,-9.82532882634e-005 +49.49,51.0052617346,0.0064548036698,21.7842448956,19.9974243557,-0.00179850818554,0.00190892870911,0.00108265221685,-0.000862438238033,0.000299723466599 +49.5,51.005263532,0.00645480352506,21.7842345674,19.9944804542,-0.000233350639587,0.000156724930602,9.57086132307e-005,-0.00205328492458,0.00289724590901 +49.51,51.0052653294,0.00645480358911,21.7842333421,19.9968399335,0.00113245551873,8.83199425818e-005,0.00121021737457,-0.00214624104958,0.00241158344714 +49.52,51.0052671269,0.00645480364418,21.7842252368,19.9975541365,-0.000359407458313,0.00153275461086,-0.000493640173567,-0.000549048858769,0.00041709570846 +49.53,51.0052689245,0.00645480356802,21.7841936199,19.9986372255,-0.000709713380711,0.00479062670766,-0.000733663646269,-0.00117143141295,-0.00113553406048 +49.54,51.0052707222,0.00645480348441,21.7841569197,19.9991307658,-0.000463939652391,0.00254939708962,-6.1992071115e-005,2.98059827534e-005,-0.000115992619547 +49.55,51.0052725199,0.00645480349359,21.7841339352,19.9984967993,0.00059277808383,0.00204751904728,-0.000540939661299,7.1331487833e-005,0.000372826122552 +49.56,51.0052743176,0.00645480361739,21.7841171795,19.9992230145,0.00114520398461,0.00130361357878,0.000283964391029,0.00145360863645,7.71367637815e-006 +49.57,51.0052761152,0.00645480377337,21.7841074122,19.9988931945,0.00104438482973,0.000649852713775,0.000896173630289,0.0037971641953,-0.00210809842564 +49.58,51.0052779129,0.00645480381563,21.7841073331,19.998531376,-0.000451207038708,-0.000634036276539,0.00052790264085,0.00229170448007,-0.00181835929693 +49.59,51.0052797105,0.00645480374295,21.7841135192,19.9973564146,-0.000569020824707,-0.000603182441048,-0.00213926540813,0.0013216953731,-0.000694557772739 +49.6,51.0052815081,0.00645480375762,21.7841162772,19.9988428556,0.000774965055507,5.15764910283e-005,-0.000835207155938,-2.24496526618e-005,-0.000147326682302 +49.61,51.0052833057,0.00645480386565,21.7841300428,19.9979285704,0.000741600730105,-0.00280470617641,-0.00192375457743,-0.00191260810724,-0.00177286652775 +49.62,51.0052851033,0.00645480398324,21.7841514535,19.9973719285,0.000909046535552,-0.00147741798971,-0.00121763302313,-0.00106799100261,-0.00427533305454 +49.63,51.0052869009,0.0064548041221,21.7841737618,19.9997516727,0.00104033930369,-0.00298424823087,-0.000616156924139,-0.00397245750834,-0.00378900062151 +49.64,51.0052886986,0.00645480424032,21.7841983352,19.9988380079,0.000619218562244,-0.00193044004806,-0.00171285330711,-0.00190310827732,-0.00156145448518 +49.65,51.0052904962,0.00645480425705,21.7842075526,19.9975266669,-0.000384436646632,8.69684073826e-005,-0.00271477151145,-0.00157127187141,-0.00262659631209 +49.66,51.0052922939,0.00645480418508,21.7842160563,19.9995394643,-0.000625838950184,-0.00178771087112,-0.00143373501539,-0.00145441983692,-0.00320242391523 +49.67,51.0052940917,0.00645480417001,21.7842368855,20.001403243,0.000414345109818,-0.00237812250552,-0.00327568030878,-0.00330712151537,-0.00406108313512 +49.68,51.0052958895,0.00645480429466,21.7842496152,19.999883997,0.00133541511057,-0.000167815994939,-0.0013224294712,-0.00286252137346,-0.00370881904154 +49.69,51.0052976872,0.00645480446563,21.7842450026,19.9984671808,0.00106468617368,0.00109033073011,-0.00141142847031,-0.0025079091424,-0.00390764610711 +49.7,51.005299485,0.00645480465087,21.7842358481,20.0016840768,0.00153573978964,0.000740577143239,0.000333062228232,-0.00284873314596,-0.00488268372947 +49.71,51.005301283,0.00645480492351,21.7842409876,20.0029685923,0.00229154288569,-0.00176849535826,0.00033092165905,-0.00215174728663,-0.00242037217646 +49.72,51.005303081,0.0064548052545,21.7842484691,20.0013888321,0.00235490759265,0.000272195713862,0.000230060420491,-0.00223331461187,-0.00400811250487 +49.73,51.0053048788,0.00645480558648,21.784233671,20.0013139959,0.0023054694954,0.0026874376187,0.000814034928151,-0.00212969080297,-0.00258211652513 +49.74,51.0053066767,0.00645480580893,21.7842121277,20.000868308,0.000817206977081,0.00162121735894,0.00100821102038,-0.0022042354385,-0.00309106864849 +49.75,51.0053084746,0.00645480585216,21.7841992732,20.0008545365,-0.000210379695112,0.000949678446923,0.00182261009301,-0.00103075377324,-0.00116730275562 +49.76,51.0053102724,0.00645480600269,21.7841865891,20.0004429309,0.00232357141423,0.00158714413639,0.00113972209156,-0.00214807777288,-0.00204127078671 +49.77,51.0053120702,0.00645480626556,21.7841692018,20.0012141999,0.00136663139663,0.00189030900488,-0.000813134298149,-0.00240792224944,0.000451621643173 +49.78,51.0053138681,0.00645480645097,21.7841541418,20.0003802457,0.00123604797114,0.00112169947103,3.60751947107e-006,-0.00288674664341,2.35002053582e-005 +49.79,51.005315666,0.00645480656929,21.7841400431,20.0020076263,0.000424961409734,0.00169804465996,-8.71170235284e-005,-0.0035595999545,-0.000653614644855 +49.8,51.0053174639,0.00645480668355,21.784122634,20.001696114,0.00117911455454,0.00178376432319,-0.00130239806453,-0.00320632131723,-0.00063634390965 +49.81,51.0053192619,0.00645480683211,21.7841069576,20.0040891571,0.000906357212711,0.0013515165789,-0.000860648364884,-0.00333172374008,-0.00101681812028 +49.82,51.00532106,0.00645480701713,21.7840926532,20.0018067348,0.00169091971649,0.00150936564311,-0.00135549497218,-0.00276680323388,-0.000402472805737 +49.83,51.0053228578,0.00645480726676,21.7840880241,20.0002616825,0.00181332869038,-0.000583546078959,0.0012478037914,-0.00411579366203,-0.000914268205685 +49.84,51.0053246557,0.00645480755341,21.784089841,20.000418745,0.00221072202484,0.000220164004816,-0.00044515577498,-0.0012861056878,-0.000734233945437 +49.85,51.0053264535,0.00645480784052,21.7840680645,20.0022084589,0.00181968778317,0.0041351341521,-0.00134273958556,-0.000440776028406,-0.00194645120737 +49.86,51.0053282515,0.00645480800886,21.784041423,20.0007587845,0.000543424389066,0.00119316627918,-0.000291125731886,0.000197056995091,-0.000699485629382 +49.87,51.0053300493,0.00645480820938,21.7840224378,20.0010710782,0.00227150290236,0.00260387401165,-0.00284377275598,0.000841067207224,-0.00071212897412 +49.88,51.0053318471,0.00645480843632,21.7840030166,20.0003150261,0.000914249694591,0.00128037320087,-0.000878375227471,0.000326426604079,0.00128797512401 +49.89,51.0053336449,0.006454808699,21.7839975582,20.0001341699,0.00277326243259,-0.000188691916139,-0.00178560964496,-0.00189521817545,0.00324536209899 +49.9,51.0053354427,0.00645480895959,21.7839958176,19.9987743416,0.000884949878127,0.000536802028616,0.000729447122949,-0.00236030726896,0.00100996733255 +49.91,51.0053372404,0.00645480894201,21.7839919242,20.0002133368,-0.00113174598157,0.000241883787619,0.000151914933682,-0.00167683350761,0.000780629406726 +49.92,51.0053390382,0.00645480886139,21.7839907148,20,0,0,0,0,0 +49.93,51.0053408359,0.00645480880484,21.7839842775,19.9996965902,-0.000793833028249,0.00128745994028,0.0021464395787,-0.00197701765972,0.000507452549677 +49.94,51.0053426337,0.00645480877239,21.7839740498,19.9993893065,0.000338237080737,0.000758074895306,0.00254588445622,-0.00370354545565,-5.0807988581e-005 +49.95,51.0053444315,0.00645480882355,21.7839655914,20.0024065942,0.000379914267379,0.000933601016303,0.00111516063115,-0.00192028302546,0.000505731612647 +49.96,51.0053462294,0.00645480879613,21.7839519019,20.0009532745,-0.000764785741213,0.00180431583342,0.00135181889403,-0.00442988061335,0.000522361544859 +49.97,51.0053480272,0.00645480864231,21.7839297637,19.9994484412,-0.00139459233899,0.00262330674418,0.00293930156378,-0.00530822081283,0.00109967510975 +49.98,51.005349825,0.00645480844421,21.78389867,19.9998771221,-0.00138624358948,0.00359544526191,0.00158926209863,-0.00632831824173,-0.00093056738882 +49.99,51.0053516228,0.00645480824822,21.7838654985,20.0004345283,-0.00136510215201,0.00303884839473,0.000484748050298,-0.00928382900349,-0.00182344786209 +50,51.0053534206,0.00645480816259,21.7838295584,20.0000953422,0.000162974927091,0.00414918007239,0.00120342643529,-0.0117375168492,0.000308144664281 +50.01,51.0053552183,0.00645480824025,21.7837893,19.9986678857,0.000927333794485,0.00390250242427,-0.000974431693781,-0.0138775788113,-0.00146805286138 +50.02,51.0053570159,0.00645480832802,21.7837479834,19.9988302082,0.000304769029467,0.00436080148795,-0.00108949619621,-0.016091841835,-0.000976855334447 +50.03,51.0053588136,0.00645480853196,21.783707466,19.9996225571,0.00255811404195,0.00374268118905,-0.00202181241454,-0.0164309652453,0.000127970051015 +50.04,51.0053606114,0.00645480875037,21.7836778577,20.0012193993,0.000507883433415,0.00217899360258,0.000555916736495,-0.0179816177058,0.00111111776011 +50.05,51.0053624093,0.00645480885318,21.7836607181,20.00024006,0.000935349801733,0.00124891274044,0.000225210454957,-0.0186407086561,-0.000142314481421 +50.06,51.0053642071,0.00645480895691,21.7836456471,20.0012394711,0.000520861424804,0.0017652992117,-0.00230641904468,-0.0206631965943,-0.000853257588481 +50.07,51.005366005,0.00645480903802,21.783622432,20.0010001209,0.000617667951228,0.00287770903457,-0.00043616350255,-0.0231916168967,0.00106255819334 +50.08,51.0053678028,0.00645480906908,21.7836011139,20.0007230153,-0.0001816308549,0.00138591960255,-0.000359605999769,-0.0243587248483,0.000742587557978 +50.09,51.0053696006,0.00645480919996,21.7835806855,19.9992528656,0.00201898965585,0.00269976618471,-5.20036053271e-005,-0.0271018748862,0.00126638139753 +50.1,51.0053713984,0.00645480944931,21.7835501469,20.0009543622,0.0014813175515,0.003407944039,0.000472286579414,-0.028900927046,-0.001003148378 +50.11,51.0053731962,0.00645480969111,21.783521582,20.0004630457,0.00191303547066,0.00230503933749,-0.00076165983239,-0.0277665919003,-0.00120764017021 +50.12,51.0053749941,0.00645480983443,21.7834877858,20.0023148411,9.89928970098e-005,0.00445420159595,6.41215181982e-005,-0.0302264711254,0.0012000715405 +50.13,51.0053767921,0.0064548098349,21.78345253,20.0018810898,-9.23890209063e-005,0.0025969628773,0.00175420547826,-0.0313462776133,0.00132205338245 +50.14,51.00537859,0.00645480987243,21.7834280691,20.0017326067,0.000619184988037,0.00229520765309,-0.00104243200616,-0.0336399076318,0.00272639254833 +50.15,51.005380388,0.00645480999374,21.7834054116,20.0016437244,0.00108379611605,0.00223628483028,-0.001739345558,-0.0341984805058,0.00175258528499 +50.16,51.0053821859,0.0064548100387,21.7833777404,20.0015330918,-0.00045272121199,0.00329797108222,-0.00166757337105,-0.0355268393223,0.000879003975803 +50.17,51.0053839839,0.00645481007379,21.7833384655,20.0041446478,0.000945341898679,0.00455699773272,-0.00357708530627,-0.0359845410652,0.00246723494219 +50.18,51.005385782,0.00645481019762,21.7832984952,20.0031593759,0.000792948019723,0.003437069997,-0.00075502181674,-0.0378730162726,9.10740109472e-005 +50.19,51.00538758,0.00645481030346,21.7832733169,20.0027915686,0.000692863931451,0.00159858661613,-0.00109713217652,-0.0403093369156,0.00127264924751 +50.2,51.0053893781,0.00645481039409,21.7832536146,20.0036884394,0.00057936122963,0.00234186477263,-0.000869514035825,-0.0427075409449,-0.000609283290496 +50.21,51.0053911762,0.00645481054537,21.7832294254,20.0041560367,0.0015443956936,0.00249599085544,-0.00313396782153,-0.0435073913741,-0.000629959505177 +50.22,51.0053929743,0.00645481072975,21.7832038616,20.0019104233,0.0010438698635,0.00261677015009,-0.00145138873712,-0.0449936295342,-0.000264092097219 +50.23,51.0053947722,0.0064548107515,21.783189239,20.0012073184,-0.000738503857267,0.00030774640016,-0.000828532507422,-0.0467230650595,-0.000884564816545 +50.24,51.0053965701,0.0064548107735,21.7831849154,20.0015697736,0.0010473223311,0.00055696809447,-0.000616611138969,-0.0489891179553,-0.00052755585452 +50.25,51.005398368,0.00645481080684,21.7831689066,20.0022786538,-0.000579309387683,0.00264478617286,-0.00129169717248,-0.0501043914955,-0.000453602533537 +50.26,51.005400166,0.00645481075408,21.7831502771,20.001626746,-0.00016142138254,0.001081129257,-0.000648821352973,-0.0505825820544,-0.000651845703486 +50.27,51.0054019638,0.00645481068439,21.7831408858,20.0002960701,-0.000816831646496,0.000797112683892,-0.000864324707224,-0.0527933014816,-7.25395215293e-005 +50.28,51.0054037617,0.00645481057557,21.7831343218,20.0015602492,-0.000710754272374,0.000515695724051,-0.000333444400645,-0.0552638353453,-0.0010286033064 +50.29,51.0054055596,0.00645481043936,21.7831333592,20.0021601108,-0.00120143634422,-0.000323182787935,-0.00116609829198,-0.0569316732433,-0.000406007723769 +50.3,51.0054073575,0.00645481020237,21.783133511,20.0009755961,-0.00212534523865,0.000292828471425,-0.00175221841499,-0.0585546382482,-6.85441324725e-005 +50.31,51.0054091555,0.00645480995362,21.7831339202,20.0024812117,-0.00136665263039,-0.000374659270708,-0.00122292319077,-0.0593677856047,-0.000172932523588 +50.32,51.0054109535,0.00645480990403,21.783141731,20.0019843681,0.000670574028757,-0.00118750881991,-0.00133076410455,-0.0608049048545,-0.000436932443391 +50.33,51.0054127515,0.00645481003112,21.7831547908,20.0041295493,0.00111354763373,-0.0014244547771,-0.000877654857928,-0.0657740068544,-0.00243250259521 +50.34,51.0054145496,0.00645481011236,21.7831767665,20.0036686918,2.68082731404e-005,-0.00297067146822,-0.00298852570514,-0.0659457191309,-0.0011748447514 +50.35,51.0054163477,0.00645481011924,21.7831990299,20.0024692842,6.98390105592e-005,-0.00148202265482,-0.00407348778872,-0.06820111553,-0.00113536241295 +50.36,51.0054181457,0.00645481024952,21.7832046446,20.0025143631,0.00175900631738,0.000359095323254,-0.00221575518095,-0.0687221253305,0.000160850281175 +50.37,51.0054199437,0.00645481048731,21.7831996631,20.0027933831,0.00157903187515,0.000637202225525,-0.00183567899548,-0.0689443533282,0.00169527034367 +50.38,51.0054217416,0.00645481074724,21.7831901347,20.0015145099,0.00206989119006,0.0012684685099,-0.00215471375101,-0.071228597171,0.00313120647582 +50.39,51.0054235395,0.00645481117758,21.7831802005,20.0013797108,0.00397117784965,0.000718373005206,-0.00232082438573,-0.0720672806165,0.00277894777258 +50.4,51.0054253374,0.00645481160139,21.7831773602,20.0005065954,0.00197825835266,-0.000150316542392,-0.00136821299235,-0.0747247455935,-5.5182410346e-005 +50.41,51.0054271352,0.00645481189513,21.783185554,19.999546328,0.00214527852591,-0.00148843468607,-0.00215786965325,-0.0774679889353,-0.000854868942317 +50.42,51.0054289328,0.00645481216884,21.7831971977,19.99804365,0.00169706059727,-0.000840308546457,-0.00282246746462,-0.0800024491548,-0.000505327641949 +50.43,51.0054307305,0.00645481235331,21.7832028136,19.9990895834,0.000892432338353,-0.000282877552576,-0.00129487152572,-0.0800583220181,0.000874060304631 +50.44,51.0054325282,0.00645481263404,21.7832039725,19.9998743204,0.00304848379124,5.10950388912e-005,-0.000157604572788,-0.0821327041675,0.000101842929755 +50.45,51.0054343259,0.00645481311748,21.7832007081,19.9984903768,0.00373797823744,0.000601787716733,-0.000912468644715,-0.082801587351,-0.000205943455225 +50.46,51.0054361236,0.00645481359802,21.7831851969,20.0002618884,0.00300791847114,0.00250045810503,0.000630223239324,-0.0819729139951,0.00182429146172 +50.47,51.0054379214,0.00645481408208,21.7831636141,19.9995348135,0.00378724868348,0.00181610779287,0.000676205594984,-0.0820056181352,0.000938058248971 +50.48,51.0054397192,0.00645481447534,21.7831530345,20.0012867228,0.00173325248014,0.000299802871843,0.000675411212226,-0.08610461607,-0.000963397170614 +50.49,51.0054415171,0.00645481473922,21.7831445685,20.0003455696,0.00197106301579,0.00139340981547,0.00197581173616,-0.088365982431,-0.000713684253967 +50.5,51.0054433148,0.00645481494633,21.7831298254,19.9997160539,0.000936444536303,0.00155519982029,0.00110508204149,-0.090052916216,-0.00211522592492 +50.51,51.0054451126,0.00645481508032,21.7831163412,20.0005821529,0.000944387923276,0.00114163972412,-0.00101948824655,-0.0909317149652,-0.00108600747279 +50.52,51.0054469104,0.00645481518378,21.7831056564,19.9991861131,0.000508034168697,0.000995317974788,0.000742897878192,-0.0914217829596,-0.000363297976043 +50.53,51.005448708,0.00645481519421,21.7830965603,19.9985263629,-0.000361554172246,0.000823900645563,0.00233259658002,-0.0948524801878,-0.000979745345377 +50.54,51.0054505057,0.00645481509347,21.7830861384,19.9995065541,-0.00105265465923,0.00126048835776,0.000448079961669,-0.0963894752366,-0.00165841221572 +50.55,51.0054523035,0.00645481502598,21.7830860434,20.0000280908,0.000105227395045,-0.00124149510881,0.000171410260441,-0.0983743079958,-0.00102671249476 +50.56,51.0054541012,0.00645481515664,21.7830909914,19.9996033106,0.00172890324942,0.000251892524702,-0.000708809847349,-0.0988812097495,0.00015010418618 +50.57,51.005455899,0.00645481546586,21.7830874768,20.0001538714,0.00261201267058,0.000451039623297,-0.00221690690787,-0.098289520373,-0.000263882605524 +50.58,51.0054576967,0.00645481580072,21.7830889474,19.9985503365,0.00208864437505,-0.000745161133416,-0.00150919016902,-0.0996954188427,0.00124745595166 +50.59,51.0054594944,0.00645481598338,21.7830936583,19.9993875696,0.000475602839053,-0.000197023385629,-0.00228575435965,-0.102607328685,0.000406743042438 +50.6,51.0054612921,0.0064548161506,21.7830954975,19.9992084976,0.00187176174673,-0.000170811552812,-0.00121082392178,-0.105231693326,0.000651743567123 +50.61,51.0054630898,0.00645481641403,21.7830912436,19.9997132669,0.00182622689831,0.00102158119233,-0.000374737800359,-0.106575870518,-0.000504701617019 +50.62,51.0054648875,0.00645481658564,21.783087377,19.9981916045,0.000582845245985,-0.000248259867875,0.00157887993975,-0.109115007786,-0.00159040713812 +50.63,51.0054666851,0.00645481663888,21.7830980134,19.9987475574,0.000164562399464,-0.0018790099306,-0.000619347906098,-0.10967456545,0.000199551847841 +50.64,51.0054684828,0.00645481673876,21.7831131108,19.9984954502,0.00123756386764,-0.00114047989436,-0.00134008644323,-0.112222822901,0.000529398056851 +50.65,51.0054702804,0.00645481688574,21.7831242346,19.9968883915,0.000825645555452,-0.00108427476719,0.000542968503628,-0.113322142165,3.20874156576e-005 +50.66,51.005472078,0.00645481700893,21.7831326031,19.9996286474,0.00090379284439,-0.000589433837593,-0.00069737020015,-0.113666315151,0.00148277449231 +50.67,51.0054738757,0.00645481717133,21.7831272247,19.9992857905,0.00137585388066,0.00166511334928,-0.00226538722018,-0.114640831431,0.00171992418049 +50.68,51.0054756734,0.00645481731882,21.7831221979,19.998530037,0.000694643934998,-0.000659738204879,-0.000416812800902,-0.11625255617,0.000872964564204 +50.69,51.005477471,0.0064548173217,21.7831345314,19.9978873451,-0.000654190492378,-0.00180696643799,-0.000502834971688,-0.117409014653,0.00169555057631 +50.7,51.0054792685,0.00645481743067,21.7831589024,19.9973692938,0.00218386312823,-0.00306722969815,-0.000126875724816,-0.120271837964,0.000431379902405 +50.71,51.0054810661,0.00645481762247,21.7831942676,19.9980559067,0.000508627765026,-0.00400581466068,-0.00124254850736,-0.121432635155,-0.00042946954515 +50.72,51.0054828637,0.00645481781337,21.7832277583,19.9976233983,0.00217120852345,-0.00269233091621,-0.00103049055654,-0.122763581304,-0.000598406768207 +50.73,51.0054846613,0.00645481814436,21.7832488438,19.9994209892,0.00247515234815,-0.00152477304175,-0.000559377669814,-0.123332915111,0.00159418717153 +50.74,51.005486459,0.00645481844014,21.7832671381,19.9974761156,0.00167707430128,-0.0021340896313,-0.00102946341009,-0.124923559698,0.00103237234479 +50.75,51.0054882566,0.0064548187699,21.7832867994,19.9984784044,0.00295209563994,-0.00179816628008,-0.000823854072898,-0.126931195344,-0.00100687148419 +50.76,51.0054900542,0.00645481914577,21.7833063525,19.9987496678,0.00232431730888,-0.00211243995632,0.000229640417154,-0.127023954219,0.00145834571881 +50.77,51.0054918519,0.00645481947867,21.7833368052,19.9985736308,0.002348934579,-0.0039781039351,-0.000791057839361,-0.126190831736,0.00246492936358 +50.78,51.0054936496,0.00645481977747,21.7833679921,19.9998411954,0.00184556675376,-0.00225927814926,0.000579049807893,-0.130284412429,0.00169665870794 +50.79,51.0054954473,0.00645481994677,21.7833874883,19.998451154,0.000531033611587,-0.00163995412276,0.000173793691168,-0.132046396012,0.000325132623499 +50.8,51.0054972449,0.0064548201991,21.7834085384,19.9978893229,0.00301115095145,-0.00257006805709,0.000181409237644,-0.133990936646,0.000129239441898 +50.81,51.0054990425,0.00645482059084,21.7834306785,19.9981702343,0.00248811364672,-0.00185795831747,-0.00171694324537,-0.136776534538,-0.00128866000552 +50.82,51.0055008401,0.00645482100113,21.7834458939,19.9987086657,0.00327152096314,-0.00118512041204,0.000694939699819,-0.138111102624,0.000225620461037 +50.83,51.0055026377,0.00645482151458,21.7834749299,19.998270342,0.00393622403022,-0.00462208590903,0.000550073073636,-0.138892798911,0.00202704269246 +50.84,51.0055044353,0.00645482195986,21.7835068549,19.998395723,0.00231461277364,-0.0017629176748,0.000350190801363,-0.14191009859,0.000764182347495 +50.85,51.005506233,0.00645482208035,21.783531268,19.9978315276,-0.00062321698826,-0.00311969733022,-0.000219532066851,-0.143735223493,0.00149834949273 +50.86,51.0055080305,0.00645482206961,21.7835587469,19.9972260348,0.000472439616543,-0.00237608829668,0.000627117760463,-0.146699417426,0.000859396621526 +50.87,51.005509828,0.00645482220127,21.7835785568,19.9965436023,0.00137582559133,-0.00158588721477,3.24186444361e-005,-0.146608877324,0.00385260334185 +50.88,51.0055116255,0.00645482237192,21.7835900269,19.9973546952,0.0010196970168,-0.00070813276533,-0.00026448752296,-0.147936349972,-7.9789025969e-005 +50.89,51.005513423,0.00645482263735,21.7835980431,19.9964225256,0.0027063357925,-0.000895099677786,-0.00236218565925,-0.147920828391,0.000813396340335 +50.9,51.0055152205,0.00645482296301,21.7836014846,19.996858073,0.00186535771045,0.000206800584613,0.00016781685611,-0.152243797624,0.000226278272412 +50.91,51.0055170179,0.00645482318533,21.7835941867,19.9949997832,0.00125543106265,0.00125276455322,-0.00145474873361,-0.151765644376,0.00220940494816 +50.92,51.0055188152,0.00645482334487,21.783589634,19.9959156189,0.000984226852617,-0.00034221676609,-0.000640499588793,-0.153269901566,0.000478860239043 +50.93,51.0055206127,0.00645482338938,21.7835879525,19.996258758,-0.000359345931038,0.000678517531327,-0.00175836255398,-0.154834925403,0.00145785669656 +50.94,51.0055224101,0.00645482336375,21.7835868431,19.9969623206,-4.21077896037e-007,-0.000456634757795,-0.00132360494626,-0.157231126947,0.000144701351611 +50.95,51.0055242075,0.00645482346229,21.7835965757,19.9950327448,0.00138367870522,-0.00148989104629,-0.00224527780902,-0.158410127876,-0.000332721277243 +50.96,51.0055260049,0.00645482357698,21.7836067859,19.9965563799,0.000226259139678,-0.000552137632466,-0.00067894059217,-0.160776330368,0.000825057771926 +50.97,51.0055278025,0.0064548237054,21.7836135725,19.9982387411,0.00157659975943,-0.000805181231922,-0.00172803825264,-0.16290656933,0.00147674243836 +50.98,51.0055296,0.00645482394263,21.7836312144,19.9972689289,0.00175352708005,-0.00272320932491,-0.00148573266352,-0.164388685269,0.000699688987293 +50.99,51.0055313976,0.00645482412147,21.7836594274,19.9983900059,0.000756984205539,-0.00291937993076,-0.00181835064949,-0.168613657,0.00325045139255 +51,51.0055331952,0.00645482417956,21.7836848043,19.9974515869,5.84745015579e-005,-0.00215600369622,-0.00165901736539,-0.168540384347,0.00158963749891 +51.01,51.0055349928,0.00645482414734,21.7837085717,19.9986187508,-0.000510666679047,-0.00259747291879,-0.00283495220174,-0.170381887891,0.00248392226842 +51.02,51.0055367905,0.00645482412659,21.7837331965,19.9999219374,0.000219395634197,-0.0023274981149,-0.0012588584673,-0.171815420495,0.00323545173389 +51.03,51.0055385882,0.00645482426984,21.7837433806,19.9992313996,0.00179151284426,0.000290686396322,-0.00254789140267,-0.173613239084,0.0028076041669 +51.04,51.0055403859,0.00645482444268,21.7837431521,19.9983824202,0.000634799793626,-0.000244991815509,-0.00141547670395,-0.173426215084,0.00199827346358 +51.05,51.0055421836,0.00645482470533,21.7837497144,19.9997351207,0.00305218279311,-0.00106747327034,-0.0047354272261,-0.175699925527,0.00249532224716 +51.06,51.0055439813,0.00645482509155,21.7837559525,19.9998032615,0.00236955407272,-0.000180134151319,-0.0033542172025,-0.175966281841,0.00293760981308 +51.07,51.0055457791,0.00645482532132,21.7837685646,19.9991062736,0.000855977312645,-0.00234229141576,-0.00319154506135,-0.176117540235,0.0032229102712 +51.08,51.0055475768,0.00645482555531,21.7837745329,19.9994667377,0.00242868990161,0.00114862533719,-0.00199120538551,-0.179014756008,0.00255929172427 +51.09,51.0055493745,0.00645482591169,21.7837636512,19.9994572923,0.00257424761377,0.00102772626069,-0.00161973386757,-0.180111850278,0.00167037736256 +51.1,51.0055511722,0.00645482620874,21.7837542735,19.9991238194,0.00159567917688,0.00084780060717,-0.00184496676499,-0.182191773329,0.0020655477542 +51.11,51.00555297,0.00645482641377,21.7837414173,20.0007835365,0.00128246956198,0.00172343972934,-0.00352534822955,-0.182369296842,0.00164646180157 +51.12,51.0055547678,0.00645482661828,21.7837288899,19.9993857177,0.00158845052262,0.00078204457744,-0.000216504502625,-0.186403440446,0.00268275351343 +51.13,51.0055565654,0.00645482682852,21.7837283408,19.9975840642,0.00136287427678,-0.000672228610383,-0.000944116723823,-0.188271453204,0.00248331653212 +51.14,51.005558363,0.00645482694691,21.783732991,19.9994517508,0.000299019627992,-0.0002578079144,0.000605640078051,-0.191592396395,0.00203510633514 +51.15,51.0055601608,0.00645482692452,21.7837397717,19.9999147732,-0.000613329751317,-0.00109832050444,-0.000352441154487,-0.194192845626,0.00224728704238 +51.16,51.0055619585,0.00645482683893,21.7837452779,19.9984712493,-0.000588130919417,-2.93411121061e-006,0.000572213094957,-0.192447423504,0.00278924489188 +51.17,51.0055637561,0.00645482677446,21.7837504772,19.9977627451,-0.000316908522844,-0.00103692386271,-0.000292323077145,-0.195890015971,0.00173834205015 +51.18,51.0055655537,0.0064548267853,21.7837578608,19.9984421649,0.000469085620199,-0.000439789766482,0.000188349224329,-0.19488929408,0.00303242851358 +51.19,51.0055673513,0.00645482686777,21.7837547024,19.9976092827,0.000688676435969,0.00107147582289,0.000926573396033,-0.197925303676,0.000909452311377 +51.2,51.0055691489,0.00645482691683,21.783749345,20,0,0,0,-0.2,0 +51.21,51.005570946,0.00645482685864,21.7837506163,19.9845921499,-0.000816909004593,-0.000254265671861,-0.00108001340789,-0.203489887951,0.000867066968209 +51.22,51.0055727418,0.00645482681465,21.7837557244,19.9700012027,0.000199435777408,-0.000767352335842,0.00117971299761,-0.206661436311,-0.000271584031735 +51.23,51.0055745361,0.00645482668206,21.7837629384,19.9540108346,-0.00206076413734,-0.000675443274664,0.00127648682431,-0.210772298636,-0.00103880348722 +51.24,51.0055763291,0.00645482649249,21.783764504,19.9384504277,-0.000600377045459,0.000362315057019,7.62625028314e-005,-0.209695199992,-0.00208577007852 +51.25,51.0055781205,0.00645482639704,21.7837551799,19.9216895968,-0.000739552062068,0.00150251607344,0.00229020167422,-0.211631113459,-0.00270739639501 +51.26,51.0055799106,0.00645482624202,21.7837484291,19.9063908105,-0.00143657153261,-0.000152359471917,0.00103340091249,-0.213746298245,-0.00287997980511 +51.27,51.0055816993,0.00645482614154,21.7837509161,19.8912630452,2.59684191605e-005,-0.000345053576496,0.00164258150684,-0.218191791815,-0.0012466134248 +51.28,51.0055834865,0.00645482614275,21.7837534676,19.8752761676,-8.87679724542e-006,-0.000165241344834,0.00135890390297,-0.220314178869,-0.000652455699301 +51.29,51.0055852724,0.00645482614416,21.7837541902,19.8598066421,2.86059762146e-005,2.07257464613e-005,0.00320412161968,-0.221493803992,0.000129905612009 +51.3,51.0055870569,0.00645482613392,21.7837475962,19.8443059078,-0.000172363432566,0.00129807009201,0.00275703803849,-0.225695162827,-0.000112637254388 +51.31,51.00558884,0.00645482590205,21.7837303588,19.8291444748,-0.00308258281897,0.00214941313702,0.00106434419527,-0.228416680612,0.0010033298816 +51.32,51.0055906217,0.00645482550764,21.7837172581,19.8133792995,-0.0024540822352,0.000470728135931,0.00244445720795,-0.23009579973,-0.000498186066531 +51.33,51.005592402,0.00645482518248,21.7837010785,19.7972245423,-0.00211056252927,0.00276518598733,-0.000456297080422,-0.231332347329,0.00135709457466 +51.34,51.0055941808,0.00645482481841,21.7836733062,19.7816052823,-0.00300022554753,0.00278927592855,0.000946498923047,-0.232783296158,0.00270215853609 +51.35,51.0055959583,0.00645482448547,21.783643432,19.7665431912,-0.00167344421812,0.00318556915224,0.00237540315355,-0.232972129125,0.00430488288724 +51.36,51.0055977343,0.00645482431193,21.783621078,19.7500039307,-0.000762701739865,0.0012852220904,0.000646690645314,-0.236917485997,0.00327265314308 +51.37,51.0055995089,0.00645482422069,21.7836099561,19.7348548699,-0.000518110011024,0.000939170792583,-0.00089412265063,-0.240346396905,0.00362866972595 +51.38,51.0056012821,0.00645482414968,21.7836036431,19.7182519498,-0.0004787714082,0.000323421935249,-0.00152123476608,-0.241528133692,0.0035522554407 +51.39,51.0056030539,0.00645482409611,21.7836005119,19.7022206406,-0.000273191694751,0.000302816355343,0.00029924806666,-0.244241125129,0.00245638528033 +51.4,51.0056048242,0.00645482405915,21.7836015098,19.6874272529,-0.000245664969457,-0.000502385347963,0.00249146858413,-0.247051880694,0.00253156632549 +51.41,51.0056065932,0.00645482412804,21.7836096427,19.6725817919,0.00121265733357,-0.00112421145556,0.00363144708106,-0.250234609835,0.00100563436204 +51.42,51.0056083608,0.00645482423324,21.7836259281,19.6551760001,0.000264153581304,-0.00213285850209,0.00158097910264,-0.251595363226,0.00349843462036 +51.43,51.0056101268,0.00645482430973,21.783633996,19.6390009544,0.000809575516087,0.00051927144599,0.00181492014651,-0.254853366391,0.00242758523008 +51.44,51.0056118914,0.0064548243527,21.7836248756,19.6225616071,-0.000206365528576,0.00130481859989,0.000983970285174,-0.257689379193,0.00142496355818 +51.45,51.0056136546,0.00645482446091,21.7836104137,19.607306368,0.0017255283765,0.00158755094747,-0.00137344876351,-0.259393837073,2.55957359186e-005 +51.46,51.0056154164,0.00645482463003,21.783597616,19.5924925267,0.00064851208906,0.000971987615783,0.000537220087416,-0.263986029556,0.000644664638483 +51.47,51.0056171768,0.0064548247936,21.7835858165,19.5763392309,0.00164769852692,0.00138792629354,-2.42743792389e-005,-0.264652746814,5.58575884694e-005 +51.48,51.0056189358,0.00645482500775,21.7835792451,19.5617409951,0.00135848027165,-7.36595460403e-005,0.00142828146166,-0.266658011918,0.00160919251917 +51.49,51.0056206935,0.00645482515661,21.7835769541,19.5461776484,0.00073120167477,0.000531858283637,0.00154936258116,-0.266879550086,0.00153536569957 +51.5,51.0056224498,0.0064548252804,21.7835656906,19.5307119342,0.00100649079983,0.00172084103613,0.00131415861914,-0.270502681793,0.000784837142834 +51.51,51.0056242046,0.00645482538647,21.7835456502,19.5139172123,0.000482522857177,0.00228725187256,0.000971515185812,-0.272752850663,0.00211069006913 +51.52,51.005625958,0.00645482540593,21.7835224402,19.4984078259,-0.000209359387764,0.00235473939489,0.0024789608862,-0.274109630578,0.00212000454577 +51.53,51.0056277101,0.00645482539811,21.7835023302,19.4844885553,9.96461676466e-005,0.00166726810099,0.00255358520135,-0.273539385707,0.00132391732572 +51.54,51.0056294607,0.00645482536145,21.7834910882,19.4680175423,-0.000614305601154,0.000581130210033,0.00140184197227,-0.277136199083,0.00202168219198 +51.55,51.00563121,0.0064548252827,21.7834799801,19.4526343404,-0.000491111730722,0.00164048703658,0.00126632042022,-0.278996810678,0.00362903522892 +51.56,51.0056329578,0.0064548250883,21.7834670431,19.4353033114,-0.00223791067019,0.000946919675181,0.00458267217593,-0.280113680431,0.00426180533171 +51.57,51.0056347041,0.00645482491763,21.78345457,19.420047999,-0.000157878346835,0.0015476920807,0.00213636289367,-0.284452811245,0.00512522525543 +51.58,51.0056364491,0.00645482494588,21.7834478623,19.4043648739,0.000554390340109,-0.000206159240806,0.00423534182622,-0.285761652447,0.00486609941414 +51.59,51.0056381926,0.006454824938,21.7834485272,19.3897037017,-0.000664988751799,7.31816470577e-005,0.00343711676844,-0.288118329205,0.00481389850226 +51.6,51.0056399349,0.00645482491362,21.7834474829,19.374301591,0.000322683818225,0.000135680332483,0.00254349359981,-0.291097965118,0.00455586797512 +51.61,51.0056416757,0.00645482500643,21.783445496,19.3580189845,0.000980250696648,0.000261703896143,0.00243877523067,-0.294560207147,0.00526760258159 +51.62,51.005643415,0.00645482514016,21.7834457648,19.3411901509,0.000896934229868,-0.000315462174515,0.00223150268119,-0.29630081813,0.00500584949152 +51.63,51.0056451528,0.00645482516786,21.7834542418,19.324218748,-0.000507987602427,-0.00137994359367,0.00208655733497,-0.297530664743,0.00345589868811 +51.64,51.0056468891,0.00645482505371,21.7834656984,19.3095107422,-0.00109442015331,-0.000911381900704,0.000125911923262,-0.30123532675,0.00352919179792 +51.65,51.0056486242,0.0064548250224,21.7834744598,19.2951146744,0.00065480714518,-0.000840883679309,0.00134804839971,-0.303535294464,0.00416555177097 +51.66,51.0056503579,0.00645482517364,21.7834768673,19.2798241465,0.0014683737401,0.000359371732671,0.00113634661842,-0.308373224944,0.00107000407647 +51.67,51.0056520902,0.00645482541039,21.7834790449,19.2628753018,0.00185510243691,-0.000794883759049,0.00189563691458,-0.310478629163,0.000120907690321 +51.68,51.0056538211,0.00645482559748,21.7834810917,19.2484890565,0.000771200202489,0.000385523632413,0.00236289702027,-0.312811379093,0.00207320081775 +51.69,51.0056555506,0.00645482577543,21.783470333,19.2333711154,0.0017267511903,0.00176621621575,0.00219335540156,-0.316153523373,0.000524875588121 +51.7,51.0056572787,0.00645482610946,21.7834567975,19.2159419454,0.00296237631201,0.000940881426614,0.000222588153889,-0.317420910775,-0.000386431122824 +51.71,51.0056590052,0.00645482645369,21.7834406881,19.1998790601,0.00186983027005,0.00228100276179,0.000512325407107,-0.320739868271,-0.000622011417417 +51.72,51.0056607305,0.0064548266474,21.7834205524,19.1858137451,0.000849479165058,0.00174614446833,0.000426497237123,-0.323585536394,0.000365253656527 +51.73,51.0056624543,0.00645482664821,21.783400738,19.1696609289,-0.000838043394176,0.00221672733168,-5.840725312e-005,-0.326425931101,0.000839878669098 +51.74,51.0056641768,0.00645482662766,21.7833721261,19.1555523033,0.000549521886031,0.00350564329417,0.000140643007639,-0.329172522314,0.000849271150116 +51.75,51.005665898,0.00645482655254,21.7833466445,19.1398342766,-0.00160398201732,0.00159068198421,-0.000642291334852,-0.328720579351,0.0009095121357 +51.76,51.0056676177,0.00645482644443,21.7833323773,19.1238678577,8.62346475501e-005,0.00126276253783,0.000852669382329,-0.331823953613,0.000101031008239 +51.77,51.0056693361,0.00645482655654,21.7833189976,19.1096357939,0.00148767418481,0.00141316813919,-0.000662932408068,-0.3332332144,0.000794661426091 +51.78,51.0056710531,0.00645482668046,21.7833015164,19.094043423,0.000251853215968,0.00208307525958,0.00108427526332,-0.333932198656,0.00204216338375 +51.79,51.0056727687,0.00645482649338,21.7832848488,19.0773209521,-0.00287807327537,0.00125044343753,-0.00178636200665,-0.337513181388,0.00413679515552 +51.8,51.0056744828,0.00645482624454,21.7832705351,19.0615558138,-0.000615139699426,0.00161229948267,0.000409466389106,-0.339862570448,0.00252264067596 +51.81,51.0056761956,0.0064548260367,21.7832499309,19.046960736,-0.00230247963143,0.00250854490657,0.00147816654333,-0.343226211548,0.00171848132187 +51.82,51.005677907,0.00645482573828,21.7832296082,19.0307294982,-0.00188673887485,0.00155599089485,-0.000363347226963,-0.346475657824,0.00443092853541 +51.83,51.0056796169,0.00645482551221,21.7832165197,19.0151951571,-0.00128678817205,0.00106171124436,0.000328646729874,-0.349358493583,0.00325802261049 +51.84,51.0056813255,0.0064548254139,21.7832087621,18.9996356428,-9.33122242771e-005,0.000489806484716,0.00160592198851,-0.350314236689,0.000774428646027 +51.85,51.0056830326,0.00645482537234,21.7832133768,18.9840899507,-0.00049004013934,-0.00141274857104,0.000250608020965,-0.351893095718,0.00122713406603 +51.86,51.0056847384,0.00645482533876,21.7832324145,18.9684580646,1.86370157838e-005,-0.00239478182909,0.000376898775531,-0.353433389076,0.00117933337663 +51.87,51.0056864427,0.00645482533529,21.7832529354,18.9530978811,-6.73652639218e-005,-0.00170939930511,-0.000878986538767,-0.35770472589,-0.00105226203556 +51.88,51.0056881457,0.00645482530452,21.7832637115,18.9375815689,-0.000364488044939,-0.000445815020399,0.000531921790541,-0.359452780677,-0.000609030508317 +51.89,51.0056898474,0.00645482531339,21.7832609183,18.923937622,0.000488881192672,0.00100443892763,0.00143858753617,-0.361992314676,-0.00140107482626 +51.9,51.0056915476,0.00645482534885,21.7832556659,18.9050593159,8.95176501327e-006,4.60444436402e-005,0.000955991909618,-0.36507958762,-0.000292755108345 +51.91,51.0056932463,0.00645482536538,21.7832469574,18.8911219674,0.000223174032971,0.00169566739275,0.00119830237371,-0.366892729682,0.000510022823084 +51.92,51.0056949437,0.00645482535518,21.7832364941,18.8753912936,-0.000366450593573,0.000396974352336,0.00216644580074,-0.37038360083,0.000242845187425 +51.93,51.0056966397,0.00645482538116,21.7832379029,18.8603098237,0.000731239151359,-0.000678727113333,0.00287912634541,-0.374122416952,-0.000199832019801 +51.94,51.0056983343,0.00645482542306,21.7832373025,18.8431646108,-0.000143109506132,0.000798814032665,0.00496252505484,-0.378522320727,0.00205293915482 +51.95,51.0057000273,0.00645482551573,21.7832325842,18.8268065826,0.00144394430626,0.000144837385858,0.00443076514808,-0.378890276953,0.00304801393636 +51.96,51.005701719,0.00645482559917,21.7832363283,18.8130208595,-0.000272584068002,-0.000893650073338,0.0033684624003,-0.381879971632,0.000889391664957 +51.97,51.0057034094,0.00645482562892,21.7832350881,18.7989558622,0.000690242094005,0.00114168799364,0.00101282317261,-0.38583474336,-6.86005862174e-005 +51.98,51.0057050985,0.00645482572107,21.7832296317,18.7812964209,0.000603299329392,-5.04169623653e-005,0.00208272485683,-0.385643267207,-0.000164800550914 +51.99,51.0057067859,0.00645482579524,21.7832350279,18.7645702845,0.00043789973474,-0.00102881380731,0.000980655736939,-0.389293192309,4.25955062399e-005 +52,51.005708472,0.00645482581424,21.783240599,18.7502049826,-0.000171226219641,-8.54173518852e-005,-0.000208976729872,-0.391573481085,0.000161210586493 +52.01,51.0057101568,0.00645482578553,21.783241108,18.7362759663,-0.000231670784428,-1.63746448707e-005,-0.00085384079827,-0.396670781808,-0.00132987435392 +52.02,51.0057118403,0.0064548258377,21.7832560017,18.7218668623,0.000963996501144,-0.0029623570679,0.00256026299095,-0.397637267746,0.000723858103584 +52.03,51.0057135225,0.00645482597563,21.7832817273,18.7053498126,0.000972228155428,-0.00218276756463,0.00264769065669,-0.399150472176,0.00303639090229 +52.04,51.0057152032,0.00645482609489,21.7833046057,18.6900043403,0.000701843050348,-0.00239292382541,-0.000489593535036,-0.400028017296,0.00195633088257 +52.05,51.0057168825,0.00645482626058,21.7833275233,18.6744948776,0.00162410658561,-0.00219058911166,0.000419513030151,-0.400893881855,0.00333512955982 +52.06,51.0057185604,0.00645482643684,21.7833462935,18.6586626755,0.00085031496829,-0.00156344959667,0.000602036774824,-0.405177362438,0.00272913691292 +52.07,51.0057202368,0.00645482658063,21.7833678849,18.6401831585,0.00116805617715,-0.00275482360392,0.00138650398325,-0.405943006682,0.00365465653988 +52.08,51.0057219116,0.00645482668361,21.783392438,18.6240871629,0.00027769506808,-0.00215580566094,0.00147317085122,-0.408912362543,0.00183374465629 +52.09,51.0057235851,0.00645482671085,21.7834122121,18.6094645872,0.000104665983868,-0.00179900722934,0.000349537500274,-0.407824820645,0.00315066927623 +52.1,51.0057252571,0.00645482682865,21.7834315014,18.5935881128,0.00154892347132,-0.00205886361302,-0.00213588635385,-0.411902998664,0.00219512180337 +52.11,51.0057269277,0.00645482701194,21.7834539183,18.576819686,0.00102413031492,-0.00242451612372,-0.00208568368354,-0.413616338264,0.000846269667928 +52.12,51.0057285969,0.00645482707938,21.7834715414,18.5613698383,-7.74711022456e-005,-0.00110009417549,-0.00153341802384,-0.416118523767,0.000750681572604 +52.13,51.0057302647,0.00645482696688,21.7834769768,18.5473993991,-0.00150176390348,1.30162365093e-005,-0.00075023965023,-0.417225366015,0.000734241803474 +52.14,51.0057319311,0.00645482681909,21.7834718506,18.5305282414,-0.000572886653468,0.0010122184909,0.00120895852287,-0.4201052339,-0.000760767110557 +52.15,51.0057335961,0.00645482672286,21.7834678695,18.5138251096,-0.000777955368481,-0.000215989431964,-0.00114802033416,-0.421126520517,0.000250471709277 +52.16,51.0057352596,0.00645482658295,21.7834712524,18.4993636569,-0.00118605929208,-0.000460593756658,0.000423550288017,-0.426899817903,0.000576610536225 +52.17,51.0057369217,0.00645482660344,21.7834865736,18.4806907222,0.00147361794798,-0.00260366078412,-0.000678664547864,-0.427153346235,-0.000271441237861 +52.18,51.0057385822,0.00645482674578,21.7835008326,18.4661673561,0.000524512288637,-0.000248131948015,-0.00103198152794,-0.430546303955,0.000126733254949 +52.19,51.0057402415,0.00645482678298,21.7835047533,18.4519937425,-2.2903708156e-006,-0.000536000581726,-0.000797011941489,-0.431594682144,-0.000746187529286 +52.2,51.0057418994,0.00645482679235,21.7835109035,18.4360757091,0.000133833416187,-0.00069403695038,9.99943499481e-005,-0.434062737502,-0.00134242676517 +52.21,51.0057435558,0.006454826938,21.7835131473,18.4189143622,0.00191078355687,0.000245262066593,-0.00099978028919,-0.434815119147,-0.00108443306219 +52.22,51.0057452109,0.00645482712201,21.783517177,18.4056350475,0.000672387561706,-0.00105118644906,0.000690477547916,-0.43804433847,-0.00166304157955 +52.23,51.0057468645,0.00645482719737,21.7835363833,18.388189982,0.000385473878148,-0.00279008415817,0.00190290968203,-0.438177468769,-0.00062595020846 +52.24,51.0057485168,0.00645482713296,21.7835543485,18.3740579563,-0.00128963256186,-0.00080295109248,0.000224587791434,-0.442303323922,-0.00121511241717 +52.25,51.0057501677,0.00645482703065,21.783563273,18.3591690959,-0.000146607855267,-0.000981949836197,-0.00205711917813,-0.445488042154,0.00046281794866 +52.26,51.0057518173,0.00645482703177,21.7835819576,18.3424437301,0.00016237299314,-0.0027549768379,0.000980485508595,-0.448001796077,-0.00121940700812 +52.27,51.0057534653,0.00645482706893,21.7835953808,18.3264610012,0.000359283359122,7.0338627855e-005,0.00119699039304,-0.449819703271,-0.00185733990875 +52.28,51.005755112,0.006454827092,21.783596026,18.3112551556,-3.55415291646e-005,-0.000199367272574,0.000871700623472,-0.452436617931,8.42542527844e-005 +52.29,51.0057567572,0.00645482713208,21.783596793,18.2957096043,0.000598249353413,4.59633886871e-005,0.000529940145527,-0.454699788899,-0.00104061824619 +52.3,51.0057584011,0.00645482717738,21.7835995538,18.2794765075,3.76043733769e-005,-0.000598131879481,-0.000211913724797,-0.457301052126,-0.00158666600319 +52.31,51.0057600435,0.00645482714163,21.7836048203,18.2640857125,-0.000539361132013,-0.000455164856923,-0.00129935206251,-0.460248514608,0.000499167881713 +52.32,51.0057616845,0.00645482712756,21.7836063677,18.2482415693,0.00034174827365,0.000145679847691,-7.61607184143e-005,-0.462880547831,0.0003944988413 +52.33,51.0057633242,0.00645482730858,21.783607302,18.2327170556,0.0021994595343,-0.00033253909944,0.00294928462744,-0.464349159165,0.00235664589579 +52.34,51.0057649624,0.0064548274409,21.7836080869,18.2180951694,-0.000341946791555,0.000175559556014,0.00206743795104,-0.468041228706,-0.00190931837869 +52.35,51.0057665993,0.00645482725912,21.7836121079,18.2015326231,-0.00220992076219,-0.000979749087099,0.00227356610506,-0.469098747343,-0.000913634646107 +52.36,51.0057682347,0.00645482701754,21.7836154939,18.1871164727,-0.00118136986871,0.000302544110579,0.0013903938032,-0.47394726419,-0.00140495553586 +52.37,51.0057698689,0.00645482683419,21.7836171413,18.1722342936,-0.00139241009209,-0.000632019941016,0.00523083035522,-0.475496487879,-0.00258266633221 +52.38,51.0057715016,0.00645482656118,21.7836206099,18.1565504983,-0.00244011486817,-6.17116299162e-005,0.00138452458164,-0.477226389628,-0.000911285966044 +52.39,51.005773133,0.00645482643432,21.7836261552,18.1413123652,0.000659270572663,-0.00104734013185,0.00119018708373,-0.478063668271,-5.28368077247e-005 +52.4,51.005774763,0.0064548264732,21.7836223302,18.1241650366,-0.000113427746241,0.00181233914847,0.00128849499926,-0.481724796585,-0.00045512750604 +52.41,51.0057763914,0.00645482639632,21.7836033367,18.1086548233,-0.000965772848861,0.00198635905955,0.00306864397322,-0.484131930917,-0.00276370967863 +52.42,51.0057780184,0.00645482621297,21.7835859983,18.0922850134,-0.00160806275393,0.00148131361752,0.00296826383375,-0.48639497039,-0.00187381190998 +52.43,51.0057796441,0.00645482599872,21.7835773891,18.0773481373,-0.00139952209861,0.000240531557879,0.000624980768166,-0.486144283273,-0.0017913368794 +52.44,51.0057812684,0.00645482587789,21.7835740027,18.0631452802,-0.000296763425463,0.000436754807362,0.00135564283684,-0.489446294592,-0.00242494656042 +52.45,51.0057828915,0.00645482596599,21.7835577307,18.0504183987,0.00153356721923,0.00281764140699,-0.00198751227447,-0.492249588874,-0.00152892478801 +52.46,51.0057845132,0.00645482616566,21.7835344841,18.0336486743,0.00126935738532,0.00183167302877,-0.00125959953412,-0.496241929801,-0.0012423499891 +52.47,51.0057861336,0.00645482630693,21.7835177459,18.018033508,0.000713720579053,0.00151597358143,-9.90005303604e-005,-0.498484037276,-0.00131195749533 +52.48,51.0057877524,0.00645482635777,21.783510166,18,0,0,0,-0.5,0 +52.49,51.0057893694,0.00645482624946,21.783499228,17.9795613391,-0.00152047283495,0.00218761079207,5.11429231762e-005,-0.501205161553,-0.00159483345831 +52.5,51.0057909847,0.00645482597497,21.7834854884,17.9585154931,-0.00233276038381,0.000560307983103,-0.000573932819517,-0.500274858338,-0.00190914660731 +52.51,51.0057925981,0.00645482562731,21.7834839356,17.9399461075,-0.00254755258715,-0.000249748226393,0.00031093631174,-0.501824942634,-0.00310160446167 +52.52,51.0057942098,0.00645482543037,21.7834807218,17.920545467,-0.000217076481324,0.000892510518497,-0.000444973619803,-0.502819756987,-0.00205442742852 +52.53,51.0057958197,0.00645482526764,21.7834803286,17.8994200608,-0.00206737347777,-0.00081388631249,0.00097439841452,-0.504937316706,-0.00193739670294 +52.54,51.0057974278,0.0064548250579,21.7834830355,17.8800358291,-0.000876933611467,0.000272512035252,0.00221752237597,-0.505039685917,-0.000390255124907 +52.55,51.0057990341,0.006454824882,21.7834847735,17.8591052711,-0.00159226796436,-0.000620103866374,0.00104521179392,-0.507049946502,-0.00295124745837 +52.56,51.0058006386,0.00645482468645,21.7834939276,17.8403036754,-0.00115281866404,-0.00121072161943,-5.33731003431e-005,-0.506751596077,-0.000684043572959 +52.57,51.0058022414,0.00645482458431,21.7835042383,17.8215544256,-0.000281002786256,-0.000851423525423,0.00131408587306,-0.506965424944,-0.00158107942228 +52.58,51.0058038424,0.00645482459775,21.7835156921,17.8016593427,0.000469581831631,-0.00143933698489,0.00101775155985,-0.509938813358,-0.000615897397083 +52.59,51.0058054417,0.00645482470717,21.7835328022,17.7826446072,0.00106643755656,-0.00198266890602,-0.00159177936262,-0.510250087744,0.000126241110356 +52.6,51.0058070392,0.00645482481692,21.7835615538,17.7602879697,0.0004743034714,-0.00376765414502,-0.000889862632522,-0.513413339883,-0.000106994077502 +52.61,51.0058086347,0.00645482496523,21.7836004796,17.7403933725,0.00160761169935,-0.00401751014724,-0.00315236652133,-0.51556923748,0.000513929347316 +52.62,51.0058102286,0.00645482519196,21.7836351383,17.7221990692,0.00157522043111,-0.00291423928027,-0.00216530245004,-0.514841276275,-0.000189350490462 +52.63,51.0058118208,0.00645482539788,21.7836718468,17.7040875699,0.00131547709752,-0.00442744806015,-0.00230911153068,-0.514430948733,0.000830211312517 +52.64,51.0058134113,0.00645482549587,21.7837014516,17.6853393841,5.99654679321e-005,-0.00149350630678,-0.000470777403615,-0.515715340242,0.00057482654818 +52.65,51.0058150002,0.00645482563334,21.783725171,17.6655586753,0.00186986434486,-0.00325037662152,0.000299683033555,-0.516964489998,-0.00208459045519 +52.66,51.0058165873,0.00645482591437,21.7837510397,17.6471185262,0.00207519812369,-0.00192336232686,0.0028752716792,-0.516288124827,-0.00223977575102 +52.67,51.0058181727,0.00645482611643,21.7837728016,17.627654235,0.000761265055356,-0.00242902412642,0.00284343833124,-0.518848288914,0.000887179464634 +52.68,51.0058197564,0.00645482632133,21.7837904903,17.6101943662,0.00211514369505,-0.00110871407623,0.00267309153139,-0.518134247573,0.0022203648971 +52.69,51.0058213385,0.0064548265131,21.7838048089,17.5914188879,0.000576902246663,-0.0017550027235,0.00206845069123,-0.519322255148,0.00131632075458 +52.7,51.0058229189,0.00645482661657,21.7838121321,17.5721645264,0.000875593387559,0.000290349680852,0.00118349781041,-0.520439582079,0.00218309838844 +52.71,51.0058244976,0.00645482682302,21.7838095522,17.5526151741,0.00202249064012,0.000225636372042,0.00228213656536,-0.520769595535,0.00117262563843 +52.72,51.0058260745,0.00645482704214,21.7838068295,17.5323094515,0.0010535161555,0.000318908370228,0.00363968908377,-0.521551066441,0.000547077518792 +52.73,51.0058276496,0.00645482713863,21.783807812,17.5137046138,0.000300958331506,-0.000515402699096,0.00251677083596,-0.523365977162,0.000852005508174 +52.74,51.0058292229,0.00645482708005,21.7838094455,17.4934506325,-0.00112335312154,0.000188688462897,0.00223344260108,-0.524484881886,-0.00108020205369 +52.75,51.0058307945,0.00645482678264,21.7838065735,17.4738032179,-0.00305164077715,0.000385718565254,0.00234930830571,-0.52519606039,-0.00311618341385 +52.76,51.0058323643,0.00645482650521,21.7837972587,17.4532773564,-0.000842832226849,0.00147723937721,0.00251753210525,-0.524807329265,-0.00139528494057 +52.77,51.0058339323,0.00645482627855,21.7837877868,17.4345932281,-0.00233901531787,0.00041714298473,0.00124553153862,-0.526642039567,0.000486436954531 +52.78,51.0058354986,0.00645482598555,21.783786947,17.4138619931,-0.00177400781523,-0.000249176953226,0.00189317893069,-0.527637846571,-0.000593518603427 +52.79,51.005837063,0.00645482576886,21.7837869342,17.394188139,-0.0012678454968,0.000251729577515,0.00161049774324,-0.525654604595,0.0005702974008 +52.8,51.0058386256,0.00645482574424,21.7837896715,17.3746074205,0.000922146848445,-0.000799190768355,0.000613002146904,-0.526915674768,0.000445580309255 +52.81,51.0058401865,0.00645482581156,21.7838062841,17.3540070258,2.29336957303e-005,-0.0025233339845,0.0013129151232,-0.529341057573,-0.000713466849707 +52.82,51.0058417455,0.00645482576748,21.7838318935,17.3344882128,-0.000641651220785,-0.0025985356755,-0.000261263520028,-0.529286646446,3.78552496926e-005 +52.83,51.0058433028,0.00645482574526,21.7838629876,17.3141637083,0.000329676570351,-0.00362027942803,0.000908578654647,-0.527871059518,-0.00114279566238 +52.84,51.0058448582,0.00645482579017,21.7838904219,17.2940500027,0.000300741506078,-0.00186659918765,0.000720703978713,-0.529034108615,0.000293959995635 +52.85,51.0058464119,0.00645482598389,21.7839056993,17.2748971106,0.00241863553731,-0.00118887669851,0.00219293868208,-0.528718967661,0.000173627033933 +52.86,51.0058479639,0.00645482619886,21.7839138358,17.2552026025,0.000599157032926,-0.000438423243016,0.00202431721171,-0.530080333401,0.000421907497742 +52.87,51.0058495141,0.00645482623915,21.78392898,17.2376782531,-3.35613175262e-005,-0.00259041035685,0.00157460295835,-0.531433876621,0.000846961811677 +52.88,51.0058510627,0.0064548262706,21.783950259,17.2186038189,0.000474934900472,-0.00166539923332,0.000982824343846,-0.532141686569,0.000285594827738 +52.89,51.0058526096,0.00645482635213,21.7839614054,17.198357937,0.000669658999742,-0.000563866919176,0.00172388922844,-0.532846591746,0.00222068150892 +52.9,51.0058541547,0.00645482656445,21.7839770022,17.1792282284,0.0023107799597,-0.00255549956415,0.00138439706684,-0.532387602987,3.39064396392e-005 +52.91,51.005855698,0.00645482676785,21.7840005792,17.1594798761,0.000544620342592,-0.00215989914248,-0.000336753233317,-0.531529947937,-0.00292549972473 +52.92,51.0058572396,0.00645482691746,21.7840210781,17.1402330965,0.00155554097419,-0.0019398735393,0.00280643851139,-0.533409627176,-0.00026759247099 +52.93,51.0058587795,0.00645482711791,21.7840391297,17.1223173459,0.00125833475914,-0.00167046273811,0.0013803070032,-0.534381231968,-0.00284043822111 +52.94,51.0058603177,0.00645482738423,21.7840601562,17.1020389811,0.00248015306061,-0.00253482399081,0.00309525265928,-0.535180498775,-0.00235544504841 +52.95,51.0058618541,0.00645482778248,21.7840814222,17.0844185875,0.0031103891468,-0.00171837326535,0.00435757800686,-0.538125788361,-0.00257576843139 +52.96,51.0058633889,0.00645482807615,21.7840926776,17.0624459208,0.00101212444,-0.00053271013542,0.00240345707207,-0.539184996158,-0.00115796148544 +52.97,51.0058649218,0.00645482813043,21.7841050169,17.0443957963,-0.000250083372434,-0.00193515108575,0.00312847755935,-0.539843895412,-0.00240600194645 +52.98,51.0058664531,0.00645482814069,21.7841150679,17.0265672234,0.000394007816805,-7.50563020719e-005,0.00284750658203,-0.540056343499,-0.00302697438388 +52.99,51.0058679826,0.00645482829979,21.7841131599,17.0060065441,0.00183941751821,0.000456653564037,0.00261121582724,-0.538856061057,-0.00150166754333 +53,51.0058695104,0.00645482845336,21.784112685,16.9857962132,0.000316444733511,-0.00036167635005,0.0016056802048,-0.542352393298,-0.00160529169436 +53.01,51.0058710363,0.00645482841605,21.7841171998,16.965835487,-0.000840270044883,-0.000541264259738,0.00179413742719,-0.543606906851,-0.00203526610996 +53.02,51.0058725605,0.00645482847191,21.7841287794,16.947335855,0.00162445583132,-0.00177466973342,-0.000576508592484,-0.544798997386,0.000610318621418 +53.03,51.005874083,0.00645482873292,21.784136759,16.9285978463,0.00203952972845,0.000178744963103,0.00144344537325,-0.545798164409,-0.00151121070908 +53.04,51.0058756038,0.0064548289443,21.7841412765,16.9071019295,0.000927876244623,-0.0010822313155,0.00162225595308,-0.545484786617,-0.00105397627668 +53.05,51.0058771227,0.0064548289699,21.7841486439,16.888090165,-0.000568520558294,-0.00039125508313,0.000939038754274,-0.545772566577,-0.00110329153636 +53.06,51.0058786399,0.00645482887419,21.7841560238,16.869841984,-0.000775019679446,-0.00108473213605,0.00141789180051,-0.548300220874,-0.00125660905495 +53.07,51.0058801553,0.0064548287693,21.7841738629,16.8479636595,-0.000697486436561,-0.00248308183445,0.00100503258957,-0.547436605619,-9.34157007722e-005 +53.08,51.0058816689,0.00645482875562,21.7841888124,16.8295274321,0.00050545770435,-0.000506807767359,0.0017540799779,-0.549700873484,-0.000320492966225 +53.09,51.0058831807,0.00645482890954,21.7841911911,16.8074138462,0.0016551959754,3.10680145505e-005,0.00241350025906,-0.549936733203,-0.00143129508628 +53.1,51.0058846907,0.00645482906844,21.7841928974,16.7901750901,0.000575527528674,-0.00037234248938,0.00115595914024,-0.549989071477,0.00165256685909 +53.11,51.0058861991,0.00645482913371,21.7842010169,16.7709728822,0.000340677694417,-0.00125154379393,0.000478535805622,-0.550910706648,0.000298429472187 +53.12,51.0058877057,0.00645482920573,21.7842062328,16.7501905808,0.000670363177514,0.000208356972439,0.000375716695503,-0.550943314576,0.000380335799805 +53.13,51.0058892104,0.00645482923901,21.7842080658,16.7293427272,-0.00020319811468,-0.000574961731254,-0.0002330049447,-0.551102254238,-0.000698425325283 +53.14,51.0058907134,0.00645482923528,21.7842152688,16.7113962042,0.00015072998748,-0.000865631830366,0.000637512428532,-0.551800028391,-0.000648938801266 +53.15,51.0058922148,0.00645482944802,21.7842284442,16.6940025025,0.00283573898839,-0.00176945810684,0.000262794206421,-0.552355554259,-0.00131546092354 +53.16,51.0058937145,0.00645482973008,21.784239244,16.6741691946,0.00112373790422,-0.000390498154353,0.00239833315457,-0.551504432158,0.0013413736751 +53.17,51.0058952124,0.00645482985146,21.7842448848,16.6536442154,0.000580195246734,-0.000737652781995,0.00216529817632,-0.553303785441,0.000640440727719 +53.18,51.0058967085,0.0064548300088,21.784244934,16.6341324369,0.00162848647512,0.000727806799856,0.00249213886433,-0.555116470439,0.000540516073716 +53.19,51.0058982028,0.00645483016253,21.784248731,16.6142928068,0.000529533832789,-0.00148721084056,0.00169750837323,-0.5558245428,0.000548032664944 +53.2,51.0058996954,0.00645483023329,21.7842545852,16.5950243697,0.000463838331385,0.000316370266887,0.00195937278848,-0.556962631423,-0.00150386888598 +53.21,51.0059011863,0.00645483014753,21.7842447252,16.5769032668,-0.00166777991136,0.00165563567292,0.0026246466836,-0.556092458159,-0.00156613835842 +53.22,51.0059026754,0.00645483002856,21.7842328573,16.5568208035,-2.20131533261e-006,0.000717935332479,0.00201276641551,-0.557398115357,-0.000666792763706 +53.23,51.0059041629,0.00645483010905,21.7842340891,16.5384558739,0.00113198407842,-0.000964289713594,0.0033762282482,-0.562076855072,-0.00148307926795 +53.24,51.0059056486,0.00645483019183,21.7842382432,16.5179030603,3.00751054621e-005,0.000133467853442,0.00181295026122,-0.561099107607,-0.00120654264881 +53.25,51.0059071324,0.00645483010881,21.7842369612,16.4977108333,-0.00119547044606,0.000122937757994,0.000754659359646,-0.561844615272,-0.00124200126622 +53.26,51.0059086145,0.00645483001155,21.7842318623,16.4773600297,-0.000169810772681,0.000896842278764,0.000541701003732,-0.562266856317,-0.00225360656846 +53.27,51.0059100947,0.00645482997055,21.7842205621,16.4583206874,-0.000405741126136,0.00136320383155,0.000738449556314,-0.564643349883,-0.000339672914879 +53.28,51.0059115733,0.00645482999268,21.7842102153,16.4382925119,0.000716367054265,0.000706151022936,0.00118267772622,-0.56469744516,-0.000642706160497 +53.29,51.00591305,0.00645483002801,21.7841980144,16.4193780826,-0.000220370560232,0.00173402040237,-0.0023904671067,-0.56420234169,-0.00241752050198 +53.3,51.0059145251,0.00645482994569,21.7841840893,16.3998943219,-0.000935285358387,0.00105099826541,0.000121592523181,-0.564508166718,-0.0015934725013 +53.31,51.0059159984,0.00645482990556,21.7841678644,16.3804295438,0.000371979178957,0.00219399423468,-0.000919237425289,-0.564431992245,0.00189912625294 +53.32,51.0059174699,0.00645482985577,21.7841545217,16.3600118462,-0.00107091981064,0.000474545281484,0.00144916790668,-0.564726024594,0.00158268268079 +53.33,51.0059189396,0.00645482959569,21.784161072,16.3405019193,-0.00257998557672,-0.00178460477317,0.000582947721827,-0.56506835245,0.00130276967887 +53.34,51.0059204075,0.00645482931168,21.784175408,16.3200050738,-0.00140690655859,-0.00108259469633,0.000444886050283,-0.565274923527,0.000945794701806 +53.35,51.0059218736,0.00645482911028,21.7841943486,16.3005348361,-0.00142036609306,-0.00270553345418,-0.000730542079018,-0.567716216986,0.00252202704861 +53.36,51.0059233379,0.00645482895605,21.7842132898,16.2802684966,-0.000744675729437,-0.00108270308647,0.00082928309028,-0.568511741746,0.000771384899473 +53.37,51.0059248005,0.00645482888381,21.7842230104,16.2616608287,-0.00026937606375,-0.000861410326615,-0.0010760512013,-0.571384758203,0.00254106419514 +53.38,51.0059262613,0.00645482889835,21.7842340027,16.242029736,0.000473553869566,-0.00133706256133,0.000126839301141,-0.568939176941,0.000831087740814 +53.39,51.0059277204,0.00645482891952,21.7842526839,16.2223575576,-0.000176409253035,-0.00239917605925,-0.00166187713177,-0.572059899348,0.00206124162886 +53.4,51.0059291777,0.00645482892895,21.7842693847,16.2023692135,0.000308749294572,-0.00094097352773,-0.000537118578827,-0.574672168894,-0.000343418387946 +53.41,51.0059306333,0.00645482910475,21.7842753859,16.1842764073,0.00215904606986,-0.000259263783155,0.00107719150838,-0.575924079161,0.000179287990433 +53.42,51.0059320872,0.00645482928828,21.7842741486,16.1634889269,0.000417430218378,0.000506711726905,3.46350472342e-005,-0.575360801668,0.00147082873699 +53.43,51.0059335392,0.0064548294469,21.7842720591,16.1438832932,0.00180914006667,-8.88131530322e-005,0.00043232153906,-0.575798085615,0.000516932144851 +53.44,51.0059349895,0.00645482952723,21.7842736124,16.1246822266,-0.000681486316231,-0.000221844220827,0.000512727849419,-0.575484914083,0.000231727259636 +53.45,51.005936438,0.0064548293619,21.7842700258,16.1055208286,-0.00163927387736,0.000939163299755,0.000287270328153,-0.578996618686,-0.000400718014773 +53.46,51.0059378848,0.00645482914206,21.7842683376,16.0854617421,-0.00144684470358,-0.000601517498566,0.00219722274601,-0.576722403897,0.00102125753297 +53.47,51.00593933,0.00645482899439,21.7842723841,16.0676769474,-0.000626084765722,-0.000207779434858,0.000214440809832,-0.577850116203,0.00289838828713 +53.48,51.0059407733,0.00645482879212,21.7842716106,16.0466960394,-0.00221334604141,0.000362481870005,-0.000957184033391,-0.577545256228,0.00096536572031 +53.49,51.0059422148,0.00645482853938,21.7842694888,16.0252531444,-0.00133454271212,6.1877299073e-005,-0.00157487228441,-0.577750468344,0.000895007498515 +53.5,51.0059436543,0.00645482829986,21.7842738265,16.0045719001,-0.00202789568838,-0.000929425771048,-0.000724859275153,-0.580054931231,0.00235099650651 +53.51,51.0059450922,0.00645482807425,21.7842818911,15.9871244565,-0.00113917731018,-0.000683492606831,0.00285207595169,-0.58210265039,0.000890148525105 +53.52,51.0059465284,0.0064548278587,21.7842919932,15.9683728502,-0.00188662009447,-0.00133692380983,0.000588443670186,-0.583081123412,-0.000919676569517 +53.53,51.0059479628,0.00645482758006,21.7843041404,15.9462118822,-0.00202491230013,-0.00109251686693,0.000568945571039,-0.586400340574,-0.00299965417973 +53.54,51.0059493953,0.00645482737579,21.7843119882,15.9280699638,-0.00084248103201,-0.000477046436206,-0.000591287367343,-0.585189397485,-0.00223644638543 +53.55,51.0059508262,0.00645482732142,21.7843151711,15.909307582,7.9223106384e-005,-0.000159530945719,-0.000282669181473,-0.5862037225,-0.00271454495961 +53.56,51.0059522554,0.00645482729134,21.7843136659,15.8893148685,-0.000501521024304,0.000460576911534,-0.00116580627258,-0.585668871172,-0.000572766359665 +53.57,51.0059536828,0.00645482715805,21.7843099796,15.8691915655,-0.00136950164497,0.000276667618536,-0.00161492340997,-0.586571499166,-0.00137089308589 +53.58,51.0059551083,0.00645482704433,21.7843037236,15.8488924419,-0.000226899948184,0.000974532913459,-0.00176878417437,-0.5866179532,-0.00109166443325 +53.59,51.0059565322,0.00645482699264,21.7842945772,15.831275693,-0.000498818659342,0.000854760746322,-0.00134700931179,-0.586866035761,0.000751116856664 +53.6,51.0059579543,0.00645482691652,21.7842865794,15.8117763455,-0.000569702387632,0.000744795020878,-0.00123534726104,-0.587827148039,-0.00240238649643 +53.61,51.0059593748,0.00645482675923,21.7842827229,15.7934667957,-0.0016383219376,2.65030376492e-005,-0.000833547846085,-0.588852464772,-0.000590582941934 +53.62,51.0059607936,0.00645482651774,21.7842827584,15.7744766583,-0.00175157382308,-3.36024802883e-005,-0.00211562751107,-0.589331103602,-0.0017203696294 +53.63,51.0059622106,0.00645482621236,21.7842922829,15.7540829675,-0.00253531696526,-0.00187129073642,-0.00280258833853,-0.591446184253,-0.00111085959788 +53.64,51.0059636258,0.0064548258644,21.7843056037,15.7337792605,-0.002349283774,-0.000792875439453,-0.00395260775584,-0.591725681444,-0.0020126199475 +53.65,51.0059650393,0.00645482553802,21.7843120514,15.715671699,-0.00223238836324,-0.000496660149752,-0.00424996902021,-0.592759017019,-0.00317914345882 +53.66,51.0059664512,0.00645482520131,21.7843085968,15.6976378658,-0.00249429828098,0.00118758398767,-0.00370684222428,-0.592786524103,-0.00150883450151 +53.67,51.0059678612,0.00645482503908,21.7843018616,15.6763185305,0.000217045673824,0.000159455135012,-0.00300655196399,-0.593336234266,-0.0011219948188 +53.68,51.0059692695,0.0064548249924,21.7843078485,15.6570980177,-0.000872438810079,-0.00135683643611,-0.00237592640709,-0.59457129988,0.000217535660193 +53.69,51.0059706761,0.00645482494183,21.7843201459,15.6384458562,0.000162585050293,-0.00110264464569,-0.00151253757059,-0.593131116522,0.000298521750859 +53.7,51.0059720809,0.00645482505538,21.7843265447,15.6177529331,0.00143140580788,-0.000177122087605,-0.0015300977758,-0.595934983088,0.000132852209501 +53.71,51.0059734838,0.00645482522005,21.7843386855,15.5975487957,0.000880211009285,-0.00225103176377,-0.00170965039534,-0.598445630555,0.000328898224299 +53.72,51.0059748849,0.00645482534714,21.7843554816,15.5774565014,0.000903841229803,-0.00110819381621,-0.00107130176136,-0.59724507246,-0.000176975935587 +53.73,51.0059762844,0.00645482541385,21.7843644047,15.5596447027,3.27037889743e-005,-0.000676430631178,-0.00282860312783,-0.595948846297,-0.00149648093033 +53.74,51.0059776821,0.0064548254169,21.7843683752,15.5395800904,1.00297462932e-005,-0.000117658772229,-7.77031579344e-005,-0.595206293259,-0.00042253892058 +53.75,51.0059790781,0.00645482535857,21.7843790967,15.5213616135,-0.000828834643362,-0.00202664102588,-0.000755330856017,-0.598163040211,-0.00195636770842 +53.76,51.0059804724,0.00645482529953,21.7843892299,15.5,0,0,0,-0.6,0 +53.77,51.0059818646,0.00645482532103,21.7843947002,15.4777861382,0.000301819930785,-0.00109406347138,0.000203409290377,-0.600580285347,-0.00212987317316 +53.78,51.0059832548,0.00645482525441,21.7844055366,15.4538020201,-0.00123696681111,-0.00107322259614,-0.00177917559488,-0.602102782225,-0.000332309878222 +53.79,51.0059846429,0.00645482513607,21.7844106655,15.4298758316,-0.000424293842427,4.74364138392e-005,-0.00284023764148,-0.603925444792,0.00135834268779 +53.8,51.0059860288,0.00645482502444,21.7844112495,15.4063891075,-0.00114276194427,-0.000164224038399,-0.000805954971341,-0.602825194763,-1.76544437055e-005 +53.81,51.0059874125,0.00645482489089,21.7844138858,15.3796695799,-0.000731889704456,-0.00036304763829,-0.000905115884595,-0.604815974676,-0.00147799079045 +53.82,51.0059887939,0.00645482477735,21.7844177672,15.3577510551,-0.000862028615337,-0.000413229544147,0.000353955739673,-0.604705995766,-0.00226846508572 +53.83,51.0059901734,0.00645482462119,21.7844280511,15.3346988006,-0.00133005440627,-0.00164354614568,0.000311847706744,-0.606231859884,-0.000793888767472 +53.84,51.0059915508,0.00645482446268,21.7844506636,15.311699074,-0.000895175712226,-0.00287895591686,0.0015226154348,-0.606790125244,0.00116837175016 +53.85,51.0059929261,0.00645482424329,21.7844773045,15.2885691377,-0.00218454780614,-0.00244922569685,0.00322806621908,-0.606614203941,0.00080644809823 +53.86,51.0059942993,0.00645482403731,21.7845048262,15.265238899,-0.000706955481874,-0.00305510164085,0.0028264609676,-0.608175974769,0.00233108606466 +53.87,51.0059956704,0.00645482398109,21.7845335443,15.2419987242,-8.22776851305e-005,-0.00268852765162,0.000989799781325,-0.609013324087,-0.00140922917844 +53.88,51.0059970394,0.00645482394968,21.784554118,15.2181264864,-0.000358551378979,-0.00142620118309,5.00038685967e-006,-0.610240778468,0.00153942190504 +53.89,51.0059984063,0.00645482378381,21.7845627329,15.1946128086,-0.00196991714344,-0.000296779013194,-0.00125782036867,-0.609370460115,0.00149826658243 +53.9,51.0059997711,0.00645482363464,21.7845649769,15.1717927791,-0.000124110209322,-0.000152030169633,-0.000743887564791,-0.610721513339,0.00335960869602 +53.91,51.0060011339,0.00645482363126,21.7845764199,15.1507148532,7.67180654561e-005,-0.00213657915402,-0.00142618139064,-0.611875213772,0.00236629290852 +53.92,51.0060024947,0.00645482370284,21.7845912863,15.1254008383,0.000928106247732,-0.000836693070904,0.000897999872994,-0.612307376191,0.00308062769711 +53.93,51.0060038533,0.00645482361657,21.7846043269,15.1040346449,-0.00213924377181,-0.00177141951161,0.00130249063322,-0.612398608096,0.00254288583385 +53.94,51.0060052098,0.0064548234367,21.784622745,15.0781130395,-0.000385658114758,-0.00191220114023,0.00272929498241,-0.614162268943,0.0019418918555 +53.95,51.006006564,0.00645482342859,21.7846451284,15.0525851628,0.00027172345525,-0.00256447798621,0.0028584814438,-0.612641895847,0.00146985398909 +53.96,51.006007916,0.00645482348907,21.7846667275,15.0295490372,0.000577279438527,-0.00175535589134,0.00268476842084,-0.614224023512,0.00172825652391 +53.97,51.0060092659,0.00645482364888,21.784685496,15.0055112642,0.0016661566608,-0.00199833910815,0.0015016009063,-0.614804444197,0.00176246547651 +53.98,51.0060106137,0.00645482375295,21.7846982913,14.9820769534,-0.000205268332686,-0.000560710187712,0.00111936492093,-0.614834806695,0.00196173117138 +53.99,51.0060119594,0.00645482377269,21.7847011868,14.9582225111,0.000482465943824,-1.83942455021e-005,0.00219285926327,-0.615886588959,0.00231404729732 +54,51.0060133029,0.0064548238392,21.7847026125,14.9358151631,0.000451129679784,-0.00026675786551,0.00131724457977,-0.617901488047,0.000153340913758 +54.01,51.0060146444,0.00645482404703,21.7846918528,14.9123001521,0.00246626758956,0.00241870220399,0.00288050021986,-0.617590098865,8.73186777833e-005 +54.02,51.0060159838,0.00645482441221,21.7846714182,14.8890453765,0.00266012348756,0.00166821373333,0.0032006577687,-0.617485539078,0.00266216991672 +54.03,51.0060173212,0.00645482479181,21.7846630277,14.866721147,0.00266865082914,9.88816732569e-006,0.00336239455734,-0.618354725949,0.0012392114039 +54.04,51.0060186565,0.00645482512095,21.7846590616,14.8426821625,0.00195171034629,0.000783330011786,0.00198896572206,-0.621561112552,-9.47980649925e-005 +54.05,51.0060199897,0.00645482538353,21.7846538514,14.8205424746,0.00173425637828,0.000258716305583,0.00152613510044,-0.618311648398,-0.000376644728813 +54.06,51.0060213209,0.00645482563088,21.784655746,14.7992681336,0.00173809391843,-0.000637637897595,0.00296960478784,-0.619809363573,-0.00137196767764 +54.07,51.00602265,0.00645482580581,21.7846587957,14.7738010215,0.00071752630606,2.76991252459e-005,0.00419501006675,-0.619390271597,-0.0014488958044 +54.08,51.0060239769,0.00645482589722,21.7846550846,14.7490736539,0.000565556599139,0.000714524452633,0.00187597564682,-0.622981162112,0.000158885841307 +54.09,51.0060253016,0.00645482602092,21.7846470714,14.7254706172,0.00117098415919,0.000888110805194,0.00218890516735,-0.624579492682,0.00137213119229 +54.1,51.0060266243,0.00645482607198,21.7846300786,14.7030525337,-0.000454272321269,0.00251044987752,0.000593135121483,-0.626114774734,0.00102689469123 +54.11,51.0060279449,0.006454826039,21.784601343,14.6794903752,-8.57937937536e-006,0.00323668160808,0.00134706243913,-0.626599268469,-0.000719910480962 +54.12,51.0060292633,0.00645482608422,21.7845736238,14.6565219942,0.00064330040647,0.00230715111941,0.000653487077492,-0.625675980995,-0.000780366124028 +54.13,51.0060305797,0.00645482622807,21.7845519115,14.6316344284,0.00137600788531,0.00203530178294,-0.00217438217015,-0.630876104156,-0.00142840801365 +54.14,51.0060318939,0.00645482637794,21.7845340985,14.610209258,0.000727798406456,0.00152729936658,-0.000457302135478,-0.630038011161,0.000265286488225 +54.15,51.0060332061,0.00645482642878,21.7845216847,14.5858482465,-1.41084780581e-005,0.000955471870885,0.00111114324457,-0.630899963789,0.000262688961998 +54.16,51.0060345162,0.00645482645527,21.7845094543,14.5636773589,0.000386056791216,0.00149059350263,0.000774348098923,-0.629529133471,0.000315077402562 +54.17,51.0060358244,0.00645482659011,21.7845029596,14.5416485779,0.00150679291328,-0.000191646716411,-0.000862918256922,-0.630253597035,-9.34646916406e-005 +54.18,51.0060371304,0.00645482679678,21.7844985309,14.5183003562,0.0013942815605,0.00107739559151,-0.000958611719804,-0.630908835221,-0.00135451631158 +54.19,51.0060384344,0.00645482693738,21.7844768869,14.4944534151,0.000579443620181,0.00325139747117,9.45416639708e-005,-0.632547696326,0.00212565711452 +54.2,51.0060397362,0.00645482716849,21.7844527589,14.4702285053,0.00266483791619,0.00157420900528,0.00041978943743,-0.632522861926,-0.00148690747038 +54.21,51.0060410359,0.00645482759161,21.7844448918,14.4476273444,0.00327486584078,-7.95596527847e-007,0.000119250854545,-0.633291557708,-0.00277400175194 +54.22,51.0060423335,0.00645482813578,21.784442326,14.4243681499,0.0043640229125,0.000513958810274,-0.000581992174725,-0.633610330244,-0.00148381739877 +54.23,51.0060436291,0.00645482870276,21.7844349418,14.4013244843,0.00359518485764,0.000962878228536,-5.63370255849e-005,-0.635023331985,-0.00209199985335 +54.24,51.0060449225,0.00645482903736,21.7844164899,14.3775034336,0.00110178307091,0.0027275109444,0.00133468865119,-0.635111819483,-0.000551076688609 +54.25,51.0060462138,0.00645482921398,21.7843814008,14.3537697128,0.00137763703636,0.00429029037388,0.000144573041312,-0.636401421529,-0.00053384658841 +54.26,51.006047503,0.00645482939303,21.7843410732,14.3308716592,0.00113580608655,0.00377523586949,0.00144647631981,-0.636497095082,-0.000461363137507 +54.27,51.0060487901,0.0064548296079,21.7843102815,14.3063701896,0.00188044559243,0.00238311301587,0.00353061393602,-0.63739240057,0.000322399947878 +54.28,51.006050075,0.00645482982935,21.7842859394,14.2827689896,0.001228267214,0.00248530164111,0.00301302817414,-0.638360788699,-0.000747756008911 +54.29,51.0060513578,0.00645482986586,21.784257569,14.2584457307,-0.000715754890306,0.00318877367851,0.00228133703706,-0.639230447869,-0.00101040162727 +54.3,51.0060526385,0.00645482982652,21.7842303448,14.2363953071,0.000163429308309,0.00225607497429,-0.00108231388444,-0.638951048718,-0.00134106789348 +54.31,51.006053917,0.00645482998238,21.7842092727,14.2109667075,0.00202452561715,0.00195833556092,0.000453045069688,-0.640999629571,-0.00288087311297 +54.32,51.0060551934,0.00645483015597,21.7841904953,14.1889887835,0.000412313757487,0.001797153087,0.00010340456932,-0.641852518254,-0.00134172761366 +54.33,51.0060564678,0.00645483012248,21.7841654329,14.1649769311,-0.000882473943086,0.00321531435976,-0.00247666448447,-0.642417051921,-0.00027697195285 +54.34,51.00605774,0.00645482997111,21.7841430286,14.1418578366,-0.00124238377993,0.00126555553833,-0.000931901423252,-0.644070474741,-0.00189935868746 +54.35,51.0060590102,0.00645482970583,21.7841266907,14.1193420919,-0.00248155273213,0.00200201575526,-0.00153744409553,-0.645188815594,-0.00254888695781 +54.36,51.0060602783,0.00645482946005,21.7841043304,14.0953402576,-0.000968629779415,0.00247005751614,-0.000576882153582,-0.646071105938,-0.0016296082777 +54.37,51.0060615442,0.00645482935009,21.784087476,14.0705659237,-0.000574942666092,0.00090081798745,0.000761217931911,-0.645581354137,-0.000157751382771 +54.38,51.0060628079,0.0064548293091,21.7840789166,14.0463688472,-4.74250812476e-007,0.000811063751321,-0.000448949332374,-0.646732542757,-0.000243163619135 +54.39,51.0060640694,0.00645482919119,21.7840649336,14.0214519903,-0.00165480941978,0.00198552602757,0.000776656191789,-0.647340725386,-0.00216948047182 +54.4,51.0060653288,0.00645482910036,21.7840495613,14.0003439139,0.000379747972292,0.00108893929929,0.00114002462419,-0.649760951115,-0.000457435505952 +54.41,51.0060665863,0.00645482904621,21.7840297857,13.9779533334,-0.00113978922112,0.00286618730606,0.00207012335675,-0.649405402311,-0.00027892480345 +54.42,51.0060678417,0.00645482897117,21.7840097631,13.9544214573,8.63381502876e-005,0.00113832847071,0.00237842365558,-0.649285979971,0.00107852246573 +54.43,51.006069095,0.00645482905027,21.7840007754,13.9309914182,0.00102408781103,0.000659218600171,0.00288533542469,-0.648839092239,0.0014742043641 +54.44,51.0060703461,0.00645482918033,21.7839947525,13.9072742529,0.00080161679412,0.000545344484995,0.00195141401522,-0.651855841399,0.000284683595353 +54.45,51.0060715952,0.00645482939247,21.7839964979,13.8839267593,0.00217633804387,-0.000894415694399,0.00373192389981,-0.65131747503,-1.68761053133e-005 +54.46,51.0060728422,0.00645482967193,21.7840023646,13.8608152751,0.0017466472168,-0.000278913921858,0.000600492589349,-0.652558303488,-0.000889064590771 +54.47,51.006074087,0.00645482999253,21.784006068,13.8369559007,0.00275384017088,-0.000461766230398,0.000317427309052,-0.656127958567,-0.00159801626094 +54.48,51.0060753298,0.00645483025738,21.7840032892,13.8139805252,0.000964125619953,0.00101752370797,-0.000840423437974,-0.655742539503,0.00035649793907 +54.49,51.0060765705,0.00645483044572,21.7839895121,13.7911066325,0.00167966602112,0.00173788533879,-0.00395204504932,-0.656293773537,7.67091811708e-005 +54.5,51.006077809,0.00645483066287,21.7839821344,13.7661928384,0.0013686757298,-0.000262341358496,-0.00375728719659,-0.656570660532,-5.91620308583e-005 +54.51,51.0060790453,0.00645483096271,21.7839880563,13.7423429713,0.00284042965594,-0.000922041450919,-0.0035357413525,-0.657553347357,-0.000852160587978 +54.52,51.0060802796,0.00645483127124,21.7839888111,13.7183973607,0.00149061662607,0.000771085134561,-0.00106979142824,-0.658274836232,2.62492180598e-007 +54.53,51.0060815116,0.0064548315418,21.7839871878,13.693451232,0.00230738457926,-0.000446428629434,0.00152393563892,-0.658599087847,0.000104359947627 +54.54,51.0060827414,0.00645483185142,21.7839809254,13.669863339,0.00203904688509,0.00169891325866,0.0012126577799,-0.660460579956,0.00131910941374 +54.55,51.0060839691,0.00645483209379,21.783960142,13.6468542828,0.00136329483226,0.00245775528751,-0.00150268598867,-0.659824953835,0.00286722421484 +54.56,51.0060851947,0.00645483229757,21.7839431457,13.6231673759,0.00149736129991,0.000941513347268,-0.000823709468718,-0.660907979789,0.00139892775989 +54.57,51.0060864183,0.00645483242168,21.783935557,13.6014262373,0.000244773553934,0.000576232580546,-0.00271639909436,-0.662371472106,0.00426070998399 +54.58,51.0060876398,0.0064548324596,21.7839402148,13.575923562,0.000287632787223,-0.00150780412442,-0.00102119977488,-0.663015342849,0.000212591968739 +54.59,51.006088859,0.00645483256171,21.7839646476,13.5512874273,0.00114571355533,-0.00337875658843,0.000935166506123,-0.660903210104,0.000824516099865 +54.6,51.0060900761,0.00645483268659,21.7839945018,13.5287460521,0.000607267532555,-0.00259207149409,-0.00030676022508,-0.662004166927,0.00243531533495 +54.61,51.0060912912,0.00645483281368,21.7840182331,13.5055094823,0.00117686052876,-0.00215419092653,0.00169504668323,-0.663009392185,0.00203817728354 +54.62,51.0060925042,0.00645483281767,21.7840364841,13.4838892314,-0.00112086898437,-0.00149600240207,0.00141999714111,-0.664438165576,0.00206357471286 +54.63,51.0060937152,0.0064548326517,21.7840484029,13.4616235721,-0.00120897591145,-0.000887768850007,0.00155473291872,-0.663832546885,0.0024807539431 +54.64,51.0060949242,0.006454832539,21.7840545092,13.4375164066,-0.000373154847404,-0.00033348908464,0.000630238462274,-0.667026449638,0.000942656700445 +54.65,51.0060961309,0.00645483246982,21.7840532417,13.4113285811,-0.000597881691145,0.000586992739383,-0.000403264303113,-0.668833995805,0.00322467732117 +54.66,51.0060973353,0.00645483238746,21.7840490596,13.386801927,-0.000558348238801,0.000249424077801,-0.000647061187241,-0.669927665555,0.00303554714953 +54.67,51.0060985376,0.00645483233622,21.784054084,13.3639957712,-0.000160914009865,-0.00125430802965,0.00109357511235,-0.671275161954,0.00294925591175 +54.68,51.0060997378,0.00645483231026,21.7840697317,13.340721803,-0.000203533891101,-0.00187523805121,-0.000872477545166,-0.671269961625,0.00215038974211 +54.69,51.0061009359,0.00645483224768,21.7840875516,13.3160287804,-0.000674883156651,-0.00168872556141,-0.00128992531211,-0.672658222713,0.0034730101221 +54.7,51.0061021318,0.00645483214028,21.784100058,13.2922485883,-0.000832820975072,-0.000812557819847,0.000104155122144,-0.673733773807,0.00184095296337 +54.71,51.0061033256,0.00645483201987,21.7841055237,13.2707994635,-0.000857403935146,-0.00028058489558,-0.00238083476632,-0.673520168515,0.00187970650446 +54.72,51.0061045175,0.00645483191517,21.7841070764,13.2483529863,-0.000612397299087,-2.99547115015e-005,0.00030157523881,-0.675230209882,0.00164994858627 +54.73,51.0061057073,0.00645483183594,21.7841135746,13.2229345432,-0.000499815834513,-0.00126968360253,-0.00068042461376,-0.676401024912,0.000940941727288 +54.74,51.0061068949,0.00645483169625,21.784122405,13.2007501713,-0.00146101734505,-0.000496399978576,0.00123640446377,-0.676339267651,0.00235415799776 +54.75,51.0061080805,0.00645483140919,21.7841262605,13.178844531,-0.00256869072117,-0.000274690493028,0.000917181459092,-0.676577232265,-0.000366824816568 +54.76,51.006109264,0.00645483103856,21.784122295,13.1547369592,-0.00263419829574,0.00106777663446,0.00115371680545,-0.675759104444,0.000676059506454 +54.77,51.0061104454,0.00645483068201,21.7841208681,13.1315059996,-0.00237095976699,-0.000782392268512,-0.000595726614053,-0.676309883079,0.00185782070471 +54.78,51.0061116248,0.00645483029232,21.7841278181,13.1081797574,-0.00309929973991,-0.000607598105389,0.000926880081521,-0.676559988659,0.000944681397994 +54.79,51.006112802,0.00645483003132,21.7841321076,13.0855628514,-0.000564663383219,-0.00025030465062,0.00199242092908,-0.677741797254,0.00187023477611 +54.8,51.0061139771,0.00645482994533,21.7841333415,13.0604947968,-0.000642422828295,3.50885277785e-006,0.00232252688329,-0.678257223304,0.000705299948151 +54.81,51.0061151501,0.00645482987399,21.7841380589,13.037295112,-0.000359051177066,-0.000946984375479,-0.00188108112742,-0.679470553806,0.00161413766828 +54.82,51.0061163209,0.00645482984073,21.7841418497,13.0132030317,-0.000107761742134,0.000188837801725,-0.00207497507238,-0.681796057638,-0.000523590937253 +54.83,51.0061174895,0.00645482980686,21.7841425945,12.9880155606,-0.000367741552802,-0.000337815256878,-0.00154551603019,-0.682190669184,0.000526808780287 +54.84,51.006118656,0.00645482975774,21.7841474018,12.9658256485,-0.000321840485889,-0.000623643522043,-0.000689527465599,-0.684094010294,-0.00145629663874 +54.85,51.0061198205,0.00645482972271,21.7841524621,12.9450518827,-0.000169812408788,-0.000388409075951,-0.00257684618298,-0.684184795279,-0.00138250313125 +54.86,51.0061209831,0.00645482978741,21.7841573799,12.9211545222,0.00107797921151,-0.000595156567454,-0.00223047721512,-0.684889722192,-0.00171684595484 +54.87,51.0061221435,0.00645482995131,21.784172838,12.8978070053,0.00122286913631,-0.00249645202854,0.000559744127251,-0.684537224525,-0.00284997051331 +54.88,51.0061233018,0.00645483002903,21.7841890642,12.8744986905,-0.000131861081475,-0.0007487972613,0.000411700835127,-0.68624306008,-0.000821005807538 +54.89,51.0061244581,0.00645483011356,21.7841909953,12.8531978412,0.00131849237266,0.000362582667674,0.00225201052443,-0.686174084219,-0.00286728474304 +54.9,51.0061256123,0.00645483012599,21.7841916569,12.8271281609,-0.00114404445858,-0.000494902355128,0.00151047162555,-0.688497444614,-0.00278275597964 +54.91,51.0061267642,0.00645483009792,21.7841884496,12.8025195822,0.000750078033004,0.0011363509463,0.000739622665891,-0.690446121501,-0.00362227197405 +54.92,51.0061279139,0.00645483009851,21.7841812543,12.7780883415,-0.00074186040525,0.000302713559945,-0.000362164960458,-0.688331668464,-0.00115706525863 +54.93,51.0061290615,0.00645482995834,21.7841781501,12.7547310759,-0.00122579542635,0.000318133017558,-0.00206115511993,-0.687070787405,-0.000737276392804 +54.94,51.006130207,0.00645482986882,21.7841663848,12.73291511,-3.09143782857e-005,0.00203492401444,-0.00188786461656,-0.689054132394,0.000434686675457 +54.95,51.0061313505,0.00645482987509,21.7841399346,12.7096348496,0.000118911953082,0.00325511984851,0.000986905843215,-0.6910124992,0.000441234816271 +54.96,51.0061324919,0.00645482990363,21.7841194383,12.6866495776,0.000281788745815,0.000844130802409,-0.000977460460827,-0.693841495302,0.00123735519217 +54.97,51.0061336312,0.00645483006601,21.7841174863,12.6610639515,0.00199767145135,-0.000453725043994,-0.00140539807504,-0.693484180519,0.00141415170733 +54.98,51.0061347683,0.00645483036212,21.7841133017,12.6394952506,0.00215906321956,0.00129064003244,-0.00132980371112,-0.695746320505,0.00130468162667 +54.99,51.0061359034,0.00645483073784,21.7840966244,12.6164299776,0.00311520678126,0.00204482453383,-0.00150812608382,-0.696149278586,0.000217422713976 +55,51.0061370365,0.00645483099288,21.7840791916,12.5942952297,0.000464987529391,0.00144174589083,-0.00151027568042,-0.698127777303,0.00115682659736 +55.01,51.0061381675,0.00645483107676,21.7840711457,12.5713017819,0.000712499669133,0.000167421642583,-0.000138761255576,-0.70258718941,0.00047829615435 +55.02,51.0061392965,0.0064548311889,21.7840734541,12.5476412766,0.000861630796049,-0.000629107164776,-0.000745038867447,-0.700929922465,0.000406164347393 +55.03,51.0061404233,0.00645483127729,21.7840831782,12.5241540371,0.00037910324964,-0.00131569615352,-0.000345717369575,-0.701671236014,0.000441943015863 +55.04,51.006141548,0.00645483130429,21.7840897566,12.5,0,0,0,-0.7,0 +55.05,51.0061426704,0.00645483126639,21.7840929266,12.4729485228,-0.000532009342916,-0.000633988193444,-0.00329699067457,-0.701224086377,0.00227610490386 +55.06,51.0061437903,0.006454831356,21.7840986944,12.4444758435,0.00178984345176,-0.000519581591225,-0.00088330420857,-0.702258989433,0.001012651263 +55.07,51.0061449076,0.00645483148943,21.7840996503,12.4165219099,8.32529441593e-005,0.000328415432537,0.000496962272345,-0.701858665756,0.00250758870829 +55.08,51.0061460225,0.00645483155943,21.7841106208,12.38977572,0.000899362847196,-0.00252251776906,0.000831965716199,-0.701994819104,0.00166344699806 +55.09,51.0061471349,0.00645483174135,21.7841345375,12.3596650573,0.00165436477996,-0.00226081924504,0.000648986971699,-0.703243518799,0.00101615893124 +55.1,51.0061482447,0.00645483207484,21.7841574237,12.3328625443,0.00302714170389,-0.00231642046903,0.000521921398853,-0.70360916546,0.000320849440159 +55.11,51.0061493521,0.00645483237885,21.7841758663,12.3066122359,0.0012404355631,-0.00137210477303,0.000171073626521,-0.705249174392,0.00146071939841 +55.12,51.0061504571,0.00645483258346,21.7841887521,12.2793221833,0.00163185168689,-0.0012050650291,0.00105334313163,-0.707460004173,0.00119738347643 +55.13,51.0061515597,0.0064548328614,21.7842043133,12.2530704983,0.00226973277524,-0.0019071718287,0.00140229843084,-0.706440368241,-0.000963514913622 +55.14,51.0061526598,0.00645483305446,21.7842235167,12.2238883875,0.000440453053054,-0.00193349592381,0.00159841297489,-0.709431883851,0.00193355558562 +55.15,51.0061537573,0.00645483324051,21.7842293161,12.1960743895,0.00217124734995,0.000773602456433,0.000822505317752,-0.710750084313,0.00298434932724 +55.16,51.0061548524,0.00645483349838,21.7842303186,12.1690394556,0.00144872873261,-0.000974090075441,-2.99238666969e-005,-0.710743659178,0.000615025578702 +55.17,51.006155945,0.00645483367933,21.7842382584,12.1415773626,0.00109133200528,-0.000613877710012,-0.000746647124116,-0.711065502064,-0.000639059339249 +55.18,51.0061570351,0.00645483392551,21.7842473656,12.1137507954,0.00236453104062,-0.00120755780017,0.000608339032776,-0.713103937986,0.000423301157955 +55.19,51.0061581228,0.00645483420881,21.7842510789,12.0865288734,0.00161229819427,0.000464894016765,-0.0012112156958,-0.715147945651,0.000402857956976 +55.2,51.0061592081,0.00645483445002,21.7842454705,12.060108277,0.00177378870272,0.000656792628795,0.000485257020833,-0.713239680896,-0.00129482733538 +55.21,51.0061602909,0.00645483475671,21.7842458999,12.032860797,0.00253140793956,-0.00074267799459,0.00108197464126,-0.712490290738,-0.000825280014162 +55.22,51.0061613712,0.00645483516819,21.7842499398,12.0044545668,0.00324483509191,-6.53124384518e-005,0.00184042042764,-0.714477065333,-0.000700262373237 +55.23,51.0061624491,0.00645483563643,21.7842441408,11.9770584544,0.00332810987858,0.001225116416,0.0010681893636,-0.714054683915,-0.00114991213287 +55.24,51.0061635245,0.00645483603392,21.7842358635,11.9513123924,0.00225177186033,0.000430353083134,0.00110239737814,-0.715010779333,-0.000576806497482 +55.25,51.0061645976,0.00645483624037,21.784232917,11.9241909402,0.000646384075876,0.000158939163308,-0.00121794762409,-0.716286577943,-0.00357998866384 +55.26,51.0061656681,0.00645483637388,21.7842243869,11.8954078281,0.00122777706328,0.00154708256535,-0.00239539885524,-0.716480715732,-0.000474411045354 +55.27,51.0061667362,0.00645483650104,21.7842095939,11.8678953293,0.000557255744324,0.0014115138315,-0.000627738940855,-0.71894212909,-0.00103118344073 +55.28,51.0061678018,0.00645483664444,21.7841887883,11.8413089333,0.00145572191042,0.00274960793432,4.55144891894e-005,-0.720180861002,-0.000128969169475 +55.29,51.0061688649,0.00645483684951,21.7841577367,11.8123220464,0.00142298505812,0.00346072430885,0.000716949550761,-0.71947355771,0.000243676249782 +55.3,51.0061699255,0.00645483699248,21.7841314545,11.7860587483,0.000583979524388,0.0017957080456,0.000472927301995,-0.71951053155,0.00102540342275 +55.31,51.0061709837,0.00645483707569,21.7841192886,11.7594949071,0.000584161651189,0.000637470439224,0.00208298596536,-0.721196160686,-0.000743775342264 +55.32,51.0061720395,0.00645483715992,21.7841084264,11.7323175734,0.00059815950712,0.00153496459087,0.000975985093442,-0.723677486904,-0.000298304662719 +55.33,51.0061730929,0.0064548372593,21.7840991226,11.7055853737,0.000796972685968,0.000325810587719,-0.00102370607733,-0.721466701319,-0.000835184390245 +55.34,51.006174144,0.00645483738339,21.7841027398,11.6791808227,0.000944983813684,-0.00104925101455,0.001622414999,-0.723314084435,-0.000779816630046 +55.35,51.0061751925,0.00645483746609,21.7841090134,11.6499449913,0.00021593927977,-0.000205472970742,0.000396628042006,-0.723931640269,9.32150148037e-005 +55.36,51.0061762385,0.00645483757085,21.7841080162,11.6233557699,0.00125463789856,0.000404898570137,0.000644664662981,-0.724644922028,6.18476718654e-005 +55.37,51.006177282,0.00645483766803,21.7841015262,11.5953466547,0.000109520322412,0.000893110756924,0.00412720706055,-0.725457288301,0.000139790183528 +55.38,51.0061783231,0.00645483778918,21.7840940256,11.5683726024,0.00159116021579,0.000607005144649,0.00471839996232,-0.725165788184,-0.000284667553017 +55.39,51.0061793618,0.00645483802835,21.7840877892,11.5417783464,0.00176627824797,0.00064028375691,0.00402945548234,-0.727828080752,0.000968197867214 +55.4,51.006180398,0.00645483828649,21.784078559,11.5146725557,0.00185742556342,0.0012057455761,0.003470541642,-0.728605175017,0.00199856013446 +55.41,51.0061814319,0.00645483849419,21.784069544,11.4879194628,0.00105820869072,0.000597254676801,0.00409106728706,-0.727381949891,0.0018335498806 +55.42,51.0061824632,0.00645483864778,21.7840662564,11.4600095289,0.00109775631615,6.0275349713e-005,0.00261350435079,-0.728548856635,0.00119213125434 +55.43,51.0061834922,0.00645483865753,21.7840653406,11.4337073353,-0.000960791812425,0.000122874348817,0.00141775248254,-0.729468025689,0.00222133676979 +55.44,51.0061845187,0.00645483856003,21.7840677111,11.4059992681,-0.000407935638924,-0.000596965791616,0.00170062994193,-0.730512519037,0.00114402351238 +55.45,51.0061855427,0.00645483852948,21.784067582,11.3778840194,-2.09186916981e-005,0.000622787936685,0.00201582178135,-0.731448759121,0.0018196479292 +55.46,51.0061865643,0.00645483851292,21.7840681041,11.3517541497,-0.000211495950182,-0.000727210139479,0.00210961043294,-0.731850379807,-0.000764035712573 +55.47,51.0061875834,0.00645483841909,21.7840747489,11.3238322531,-0.00110577423135,-0.000601744955568,0.00106970752393,-0.731671285782,0.000689252392892 +55.48,51.0061886,0.00645483845908,21.7840871521,11.2962493782,0.00166718351091,-0.00187890659738,0.000490865549882,-0.733940715466,0.000536376864475 +55.49,51.0061896142,0.00645483870305,21.7840970769,11.2693547254,0.00175763424872,-0.000106046530748,0.00175715673816,-0.73402104574,0.00133892686483 +55.5,51.006190626,0.00645483893546,21.784100371,11.2409372119,0.00150486108666,-0.000552785033416,0.00124701995361,-0.737157125319,0.00183184736575 +55.51,51.0061916351,0.00645483911287,21.7841014579,11.2128387067,0.000985560529137,0.000335407458155,0.000296946826767,-0.738734124344,-0.000867607675908 +55.52,51.0061926419,0.0064548392005,21.7841062417,11.1878388429,0.000244604336883,-0.00129216887645,0.000915094883022,-0.738311790388,0.00117116586529 +55.53,51.0061936463,0.00645483923875,21.7841250159,11.1593199808,0.000292363612573,-0.00246265988469,0.000101145737132,-0.739548893389,0.00181473821047 +55.54,51.0061946482,0.00645483929094,21.7841395533,11.133646397,0.000440176114357,-0.00044482665475,0.00146063591638,-0.739981900343,0.00308877190517 +55.55,51.0061956479,0.0064548392623,21.7841349859,11.1082374009,-0.000842204862562,0.00135830023239,0.00327282753333,-0.73882575694,0.000617227609383 +55.56,51.0061966451,0.00645483921608,21.7841274349,11.0807676286,0.0001934247194,0.000151908154879,0.00138164877127,-0.740223648682,0.000413571785766 +55.57,51.0061976401,0.00645483928097,21.7841241855,11.0563517836,0.000717419564407,0.000497969467652,0.00245056781712,-0.739906885373,0.000541338336072 +55.58,51.0061986326,0.00645483927986,21.7841201029,11.0275395626,-0.000732937380916,0.000318551130637,0.000431582467138,-0.741354172904,-0.00148925070007 +55.59,51.0061996226,0.00645483927212,21.7841163385,10.9997892029,0.000624239744141,0.000434329440837,0.00127165502168,-0.740757785029,-0.00232020990251 +55.6,51.00620061,0.00645483936964,21.7841136893,10.9696643689,0.000744673536459,9.55116924602e-005,0.000560693394397,-0.743043599283,-0.000890491091765 +55.61,51.0062015948,0.00645483953269,21.7841064424,10.9412811091,0.00154426158675,0.00135385953179,0.000132274255618,-0.743544443327,-0.00262155988675 +55.62,51.0062025771,0.00645483954497,21.7841038216,10.9153512218,-0.00137190550511,-0.000829680706511,-0.000667629610094,-0.746400271482,-0.00186379276669 +55.63,51.006203557,0.00645483940526,21.7841104927,10.88698394,-0.00058931525709,-0.000504558082682,0.00127122730621,-0.744308080876,-1.39658493854e-005 +55.64,51.0062045344,0.00645483940146,21.7841105374,10.8599538056,0.000536036256149,0.000495626179761,-0.000584310351225,-0.746325906868,0.000603908189103 +55.65,51.0062055095,0.00645483960288,21.7841019186,10.8345097386,0.00229144054443,0.00122813414913,-0.00297577879943,-0.747816408685,-0.000329596251037 +55.66,51.006206482,0.00645483987746,21.7841022451,10.8051934199,0.00156304985948,-0.00129342588685,-0.0010260090536,-0.748009134709,0.000362289596784 +55.67,51.006207452,0.00645483992397,21.7841079421,10.7761058419,-0.000910190048231,0.000154027143948,0.000140354920733,-0.749034662144,0.00105453804269 +55.68,51.0062084195,0.00645483985003,21.7841084465,10.750506011,-0.000127763459903,-0.00025492082916,-8.9431089599e-005,-0.750360561581,-0.000353421455409 +55.69,51.0062093846,0.00645483976526,21.7841084589,10.7233305245,-0.00106220557414,0.000252450299436,0.000823053865221,-0.751651624119,0.00148345746146 +55.7,51.0062103474,0.00645483965854,21.7841121376,10.6971026944,-0.000435972465101,-0.000988187974634,0.000926129947236,-0.752485695257,0.000297315452493 +55.71,51.0062113077,0.00645483956252,21.7841221524,10.6701766783,-0.000911851922277,-0.00101477121222,0.000246946621089,-0.752191939076,-0.000722689822943 +55.72,51.0062122656,0.00645483951129,21.7841250349,10.6421594798,0.000192661561835,0.00043825999357,-0.00128530982045,-0.753802581941,-0.000677156082918 +55.73,51.006213221,0.0064548394453,21.7841175942,10.6169751126,-0.00111906275194,0.00104988896824,-0.00333391590204,-0.752911447953,0.00140152018804 +55.74,51.0062141741,0.00645483940919,21.7841164453,10.5874835703,0.000612263626341,-0.000820123057691,-0.00235515861919,-0.754706858849,0.00100257271946 +55.75,51.0062151246,0.0064548394713,21.7841171828,10.5612288442,0.000259597367387,0.000672639384858,-0.000414890001542,-0.755716566375,0.000869166152877 +55.76,51.0062160726,0.00645483938324,21.7841156373,10.5321654556,-0.00149572789128,-0.000363543321004,-7.21955228367e-005,-0.755377516303,5.2683415831e-005 +55.77,51.0062170181,0.00645483917301,21.7841226005,10.5041672787,-0.00145550486216,-0.00102909649118,-0.000607756175649,-0.755374714477,-0.000682849657645 +55.78,51.0062179611,0.00645483888707,21.7841294676,10.4770822449,-0.00255842967869,-0.000344326399175,-0.000691117751722,-0.757392442371,-0.00296984446908 +55.79,51.0062189016,0.00645483861207,21.7841292418,10.4493162311,-0.00130198306152,0.000389490345449,-0.00126009259591,-0.758475866201,-0.000348111658364 +55.8,51.0062198397,0.00645483840457,21.7841217884,10.4238210041,-0.00161071410481,0.00110118870669,-0.000460821983409,-0.757952334955,-0.00163335189694 +55.81,51.0062207755,0.00645483815352,21.7841216441,10.3982439955,-0.00191345706402,-0.00107233815171,-0.00170350274849,-0.758947363695,0.00295183834368 +55.82,51.0062217089,0.00645483782481,21.7841334141,10.3685071667,-0.00270093659786,-0.00128165413938,-0.000814458567865,-0.759920127678,-3.39806237307e-005 +55.83,51.0062226397,0.00645483743789,21.7841437141,10.3422873145,-0.00273057863295,-0.000778347412228,-0.000946701575082,-0.760412875666,-0.000450350148278 +55.84,51.0062235681,0.00645483712609,21.784148753,10.3142304082,-0.00164628868319,-0.000229426786852,-3.77820146045e-005,-0.761880242569,0.000473012990883 +55.85,51.006224494,0.00645483703569,21.7841549837,10.286848941,0.000377178518775,-0.00101671158647,0.00224799754583,-0.763871401644,0.000971289863201 +55.86,51.0062254174,0.00645483692484,21.7841564506,10.2584323634,-0.00193320907943,0.000723330117221,0.0021226323317,-0.765873126529,-0.000384573276365 +55.87,51.0062263383,0.0064548367327,21.7841465748,10.2306592828,-0.00076399661807,0.00125183294577,0.00177321044184,-0.764792470478,0.00038675882152 +55.88,51.0062272567,0.00645483652676,21.784143324,10.2038135474,-0.00212694487036,-0.000601689009364,0.000491596462742,-0.766025666018,-0.000932684280484 +55.89,51.0062281727,0.00645483629199,21.7841449252,10.1771750728,-0.00116861682248,0.000281461800086,0.00017768147878,-0.767464620745,-0.000635906209367 +55.9,51.0062290863,0.00645483611406,21.7841424635,10.150793024,-0.00132917892612,0.000210864824541,-0.00256720466957,-0.766357220945,-0.00203245876963 +55.91,51.0062299975,0.00645483585661,21.7841527134,10.1223568553,-0.00228483915217,-0.00226083637732,-0.00112583874345,-0.768136109787,-0.00329433536456 +55.92,51.0062309061,0.00645483555775,21.7841672889,10.0949447034,-0.00191049621448,-0.000654266131787,-0.00153346056117,-0.768669417084,-0.000632317779874 +55.93,51.0062318123,0.00645483509135,21.7841774244,10.067424325,-0.00463656452521,-0.0013728275974,0.0011727115498,-0.771634119012,-0.00175525286887 +55.94,51.006232716,0.00645483461969,21.7841833602,10.0398108119,-0.00198458649834,0.000185657817537,-0.00170099357506,-0.770827252209,-0.000470652140785 +55.95,51.0062336173,0.00645483435106,21.784181074,10.0132140509,-0.00178625387973,0.000271582575292,-0.00105771360825,-0.770172853297,4.46580641904e-005 +55.96,51.0062345161,0.00645483417141,21.7841847659,9.98513801088,-0.000735657683929,-0.00100996702788,-0.00182563697384,-0.770963994852,5.24028438749e-005 +55.97,51.0062354124,0.00645483399253,21.7841923223,9.95684965659,-0.00177541799754,-0.000501311061554,-0.00312450809732,-0.769694938076,-0.00133917930958 +55.98,51.0062363062,0.00645483376061,21.7841941211,9.92978411993,-0.0014802120573,0.00014156302612,-0.0054533830266,-0.77231120081,-0.000696808751179 +55.99,51.0062371974,0.00645483352974,21.7841913582,9.90052950849,-0.00176067102817,0.000411011465135,-0.000594753801116,-0.771822566055,-0.000300489312639 +56,51.0062380862,0.00645483318141,21.7841930029,9.87519540611,-0.00312906743593,-0.00073995457171,-6.32357034079e-005,-0.774290019152,-0.000279850142191 +56.01,51.0062389726,0.00645483284407,21.7841970858,9.84698591398,-0.00160638944621,-7.66150892314e-005,0.00144234174025,-0.775369174459,-0.00161627897668 +56.02,51.0062398565,0.00645483264034,21.7841967886,9.81916838191,-0.0012535213075,0.000136055745736,0.0019234742666,-0.774145526232,-0.000533758569886 +56.03,51.0062407379,0.00645483246721,21.7841993576,9.79201044812,-0.00117684588756,-0.000649855444195,0.000735391082029,-0.776514326936,-0.000512183295698 +56.04,51.0062416169,0.00645483232127,21.784205036,9.76370928925,-0.000871817383659,-0.000485833258058,-0.00138780526504,-0.777392484054,-0.000403182297479 +56.05,51.0062424934,0.00645483225099,21.7842190194,9.73805126475,-0.000114757283782,-0.00231084032245,-0.00160465662902,-0.779527204372,-0.000809230267757 +56.06,51.0062433675,0.00645483219173,21.7842382038,9.71160160325,-0.000717102210995,-0.00152604630577,-0.000753371504065,-0.779624367849,0.00172835404096 +56.07,51.0062442392,0.00645483215673,21.78425407,9.68386130825,0.00022578452179,-0.00164719092553,-0.00253276014147,-0.780191914601,0.00144078891395 +56.08,51.0062451084,0.00645483205027,21.7842630839,9.65538231709,-0.00172020007022,-0.000155597303396,-0.000840861919647,-0.781993250958,0.000572678817535 +56.09,51.0062459751,0.00645483170896,21.784263131,9.6287955451,-0.00307098665918,0.000146181105676,-0.000423817214788,-0.783004528183,-0.000730409424612 +56.1,51.0062468394,0.00645483140732,21.7842640423,9.60155411156,-0.00116345541625,-0.000328440393715,-0.00296954909967,-0.784386003441,0.000710383249531 +56.11,51.0062477013,0.00645483117598,21.7842727912,9.57443228389,-0.00208391044401,-0.00142132810446,-0.00200576737097,-0.78443651802,0.00109525692396 +56.12,51.0062485606,0.00645483097269,21.7842886772,9.54596548318,-0.000769926697211,-0.00175587414027,-0.00134516612765,-0.784312853149,0.00117269365764 +56.13,51.0062494175,0.0064548307777,21.7842987873,9.51825259211,-0.00196724725948,-0.000266161471379,-0.00181651308198,-0.7847934193,-0.000568701696208 +56.14,51.0062502718,0.00645483060128,21.7843068241,9.49036260563,-0.000509202290124,-0.00134119304457,-0.00161232351014,-0.789401172835,0.00306108468609 +56.15,51.0062511236,0.00645483059697,21.7843203346,9.46227398702,0.00044869501088,-0.00136091190444,-0.000877743195193,-0.788648543848,0.00166606117708 +56.16,51.006251973,0.00645483059373,21.7843281645,9.43671910033,-0.000494308562153,-0.000205067477499,-0.00161880334708,-0.788280409911,0.000293709976954 +56.17,51.00625282,0.00645483048344,21.7843411721,9.40912060303,-0.00105378045148,-0.002396436329,-0.00409354879472,-0.790086625902,-0.00311776973839 +56.18,51.0062536646,0.0064548302992,21.7843581288,9.38284332135,-0.00153256886959,-0.000994921915493,-0.00377345113694,-0.792103381679,-0.00116607121734 +56.19,51.0062545068,0.00645483012318,21.7843639383,9.35478900886,-0.000938307113596,-0.000166972086926,-0.00278268739483,-0.7911041744,-0.00129107241669 +56.2,51.0062553464,0.00645482997177,21.784360455,9.32747332446,-0.0011871478872,0.000863630489314,-0.00189736182118,-0.791105004189,-0.00212786937475 +56.21,51.0062561836,0.00645482985092,21.7843507133,9.29914826726,-0.000509377218025,0.00108470463041,-0.00139520180068,-0.791843709057,-0.00198366715159 +56.22,51.0062570183,0.00645482979333,21.7843443133,9.2729402254,-0.000299036990745,0.000195295498072,0.000345582978253,-0.794914082753,-0.00298407702029 +56.23,51.0062578505,0.00645482966952,21.7843487146,9.24335945039,-0.0014390082457,-0.00107554881013,-0.00166956194467,-0.795269872173,-0.00197238833897 +56.24,51.0062586802,0.00645482933971,21.7843548522,9.21714391714,-0.00319072335178,-0.000151969956484,-4.71666130943e-005,-0.796325781488,-0.00148166723218 +56.25,51.0062595075,0.00645482880361,21.7843560919,9.19060782553,-0.00433488217596,-9.59592178843e-005,0.00158026101788,-0.798074792223,-0.00230546290073 +56.26,51.0062603324,0.00645482827739,21.7843624856,9.1621392648,-0.00305202725574,-0.00118278981817,-0.000178081504196,-0.79879251016,-0.00288759908673 +56.27,51.0062611547,0.00645482790593,21.7843759059,9.13408195735,-0.00216246478773,-0.00150126930145,-0.000860146845286,-0.798587360835,-0.00435005436681 +56.28,51.0062619746,0.00645482759425,21.7843879103,9.10821868604,-0.00221275882381,-0.000899619728461,-0.000532235853769,-0.798040115489,-0.00237162227197 +56.29,51.0062627921,0.00645482719256,21.7843962496,9.08126663683,-0.00342609493188,-0.000768240479595,-0.00214411928355,-0.798419059464,-0.000956181513681 +56.3,51.0062636072,0.00645482680457,21.7844047306,9.05485199208,-0.00202034443943,-0.000927951148439,-0.00183278301786,-0.800957468483,-0.0016141664205 +56.31,51.0062644198,0.00645482670177,21.7844111531,9.02623886852,0.000577252374318,-0.000356547810941,-0.000149353476263,-0.800375288325,-0.0037139762866 +56.32,51.00626523,0.00645482674289,21.7844129358,9,0,0,0,-0.8,0 +56.33,51.0062660375,0.00645482672759,21.7844211491,8.96729364935,-0.000214756229813,-0.00164266305537,0.00128663148013,-0.802066211106,0.000123101018878 +56.34,51.0062668423,0.00645482662038,21.7844439901,8.93778286045,-0.00129024787415,-0.00292552745991,-0.00153524134638,-0.804780288727,0.00109919824594 +56.35,51.0062676443,0.00645482650611,21.7844729395,8.90687971095,-0.000313878383204,-0.00286434556714,-0.0013680747153,-0.804782266837,0.00160093665398 +56.36,51.0062684434,0.00645482648518,21.7845001101,8.87431305155,2.00647172541e-005,-0.00256977372809,-0.00194026232758,-0.807376868052,-2.56346960232e-005 +56.37,51.0062692397,0.00645482644991,21.7845259808,8.84303741052,-0.000515106465274,-0.00260437359668,-0.00245845269027,-0.809804761461,0.000926709047702 +56.38,51.0062700332,0.00645482644145,21.7845562241,8.81107464606,0.0003963394156,-0.00344428147105,-0.00186210224471,-0.811339955488,-0.000404557105552 +56.39,51.0062708238,0.00645482641527,21.7845894723,8.77892188814,-0.000763917539809,-0.00320535920343,-0.000881365835686,-0.811821989334,-0.00119821816498 +56.4,51.0062716115,0.00645482634345,21.784615583,8.74900701436,-0.000244209232778,-0.00201678766679,-0.000592661877168,-0.812835485169,0.00175794535944 +56.41,51.0062723966,0.00645482624434,21.7846259921,8.71823913851,-0.00114703918621,-6.50247003489e-005,-0.00104476784245,-0.811601450847,-2.92749628016e-005 +56.42,51.0062731789,0.00645482607145,21.7846287593,8.68723167954,-0.00127995118719,-0.000488429328507,-0.000772866142016,-0.814994234043,1.27713340618e-005 +56.43,51.0062739584,0.00645482589639,21.7846372081,8.65807587805,-0.00117749099825,-0.00120132317196,-5.79559539211e-005,-0.818415638011,-0.000292628343889 +56.44,51.0062747352,0.00645482570776,21.7846523968,8.62478251187,-0.00147049322018,-0.00183642258432,0.000438565655327,-0.820019092217,0.000449637263574 +56.45,51.0062755091,0.00645482548864,21.7846686612,8.59350219446,-0.00160544117569,-0.00141644167059,0.00165710347713,-0.821243473319,0.00155358631118 +56.46,51.0062762801,0.00645482519668,21.7846867218,8.56172466158,-0.00249292255896,-0.00219569344588,0.000234901378374,-0.823111647095,0.000756199790545 +56.47,51.0062770483,0.00645482493594,21.7847092284,8.52947521309,-0.00116723297601,-0.00230562905913,0.000759883702467,-0.823862054784,0.00210554404081 +56.48,51.0062778136,0.00645482474881,21.7847260693,8.49872649777,-0.00145969712525,-0.00106254086283,0.00236878359839,-0.825397938823,0.00160048241811 +56.49,51.0062785761,0.00645482448182,21.7847367262,8.46724961479,-0.00228816825229,-0.00106883825753,0.001864612619,-0.827721431434,0.00141670720011 +56.5,51.0062793358,0.00645482420244,21.7847451118,8.43669670784,-0.00163368109024,-0.000608282718342,0.00108844145639,-0.830174122779,0.00200867956501 +56.51,51.0062800928,0.00645482401867,21.7847568308,8.40560618271,-0.00094615615498,-0.00173552064478,0.000826026602598,-0.833042289613,0.0012721069328 +56.52,51.006280847,0.00645482385951,21.784772967,8.37469812788,-0.00128797750842,-0.00149171711703,0.001723427931,-0.832588655998,-0.000258328550369 +56.53,51.0062815983,0.00645482367407,21.7847845211,8.34259419544,-0.00131517074422,-0.000819110042817,0.00191989346049,-0.833527035188,0.000267792596688 +56.54,51.0062823469,0.006454823371,21.7847927951,8.31245715609,-0.00293923679397,-0.000835677410375,0.000760570876737,-0.836046873086,0.000513262806321 +56.55,51.0062830927,0.00645482303236,21.7847975737,8.28144325169,-0.00181451542912,-0.000120037899908,-0.000898468724799,-0.838889569457,-0.000484315197078 +56.56,51.0062838357,0.00645482275707,21.7847993897,8.24998100012,-0.00204993250201,-0.000243176188862,0.00148017834669,-0.837750224997,0.000371912370501 +56.57,51.0062845758,0.00645482236952,21.7847983885,8.21863889794,-0.00339038843432,0.000443420321185,0.00127345178111,-0.839411062479,0.0024521790081 +56.58,51.0062853132,0.0064548219812,21.7847892435,8.18626653766,-0.00206070631412,0.00138558878477,0.00257118796619,-0.840684277722,-0.000741249218963 +56.59,51.0062860476,0.00645482168763,21.784776256,8.15583804451,-0.0020603833246,0.00121191014187,0.00191945949855,-0.843559004154,0.00194523330141 +56.6,51.0062867793,0.00645482142775,21.7847608309,8.12416181799,-0.00158769527728,0.00187310549299,0.00120194759989,-0.843972081477,0.00088306587532 +56.61,51.0062875082,0.00645482112438,21.7847450374,8.09226255809,-0.00267085026101,0.00128559928701,0.0015514110083,-0.845395039178,0.00195107044139 +56.62,51.0062882342,0.00645482079522,21.7847343676,8.06082156468,-0.0019498723396,0.000848353058573,-0.00104381547866,-0.848424402209,0.00243794481733 +56.63,51.0062889574,0.00645482052267,21.7847265783,8.03095375933,-0.00187609080406,0.000709510984777,-0.000711207112742,-0.850519123136,0.00213057228467 +56.64,51.0062896779,0.00645482032117,21.784723592,8.00005184537,-0.000952483504177,-0.000112249870403,0.00110537397243,-0.851904164734,0.00100167466529 +56.65,51.0062903957,0.00645482011104,21.7847295249,7.9700523045,-0.00199722792734,-0.00107434414619,7.17936471348e-005,-0.851603270998,0.00274354401658 +56.66,51.0062911107,0.00645481989858,21.7847300435,7.9388215867,-0.000985296118133,0.000970629250748,0.000904517292255,-0.854241088444,0.000558852478886 +56.67,51.0062918229,0.00645481977341,21.7847210962,7.90758264964,-0.000771805840177,0.000818832391264,0.000710165418517,-0.855862379636,0.00115132896737 +56.68,51.0062925323,0.00645481953382,21.7847172903,7.87657972051,-0.00259147228721,-5.76412603869e-005,0.000638223346788,-0.857271491872,0.000885500924267 +56.69,51.0062932389,0.00645481926084,21.7847229357,7.84619887232,-0.00124051808319,-0.00107144494734,0.000695375627217,-0.860070404359,0.000423470457142 +56.7,51.0062939428,0.00645481902906,21.7847313735,7.81478603389,-0.00201315825422,-0.000616113202866,-0.00157762223364,-0.862554619437,0.00121437517367 +56.71,51.0062946438,0.00645481875683,21.7847414707,7.78225776077,-0.00180823672004,-0.00140332632219,0.00172722325033,-0.863410023502,0.00188441627955 +56.72,51.0062953419,0.00645481844025,21.7847510365,7.74995928983,-0.00263580723108,-0.000509849091799,0.00117764381677,-0.866141632532,0.00180516339468 +56.73,51.0062960372,0.00645481810122,21.7847595426,7.71955111121,-0.00212347552762,-0.00119136883865,-0.000792981313228,-0.866226214241,0.00236074196676 +56.74,51.0062967296,0.00645481782376,21.7847718653,7.68817857927,-0.00177140412997,-0.00127315862267,-0.000797420381076,-0.870327036997,0.00330115686068 +56.75,51.0062974193,0.00645481756737,21.7847793339,7.6569975174,-0.00182775181128,-0.000220557372629,-0.000834179734566,-0.870040085678,0.00151394137589 +56.76,51.0062981063,0.00645481745211,21.7847779407,7.62762979125,0.000209877853673,0.000499186969651,-0.000186658456457,-0.872482318374,0.000947820750439 +56.77,51.0062987905,0.00645481739992,21.784775435,7.59543367923,-0.000942555083192,1.96274832014e-006,-0.000879036076171,-0.874855249101,-0.00086815495839 +56.78,51.0062994718,0.00645481734126,21.7847703104,7.56352131709,0.00011913771662,0.00102295553242,-0.000792897395446,-0.876096812683,0.00296333398674 +56.79,51.0063001502,0.00645481738324,21.7847657625,7.53077010137,0.000470180317159,-0.000113387024537,0.000553335550623,-0.878209056106,0.000326537247544 +56.8,51.0063008257,0.00645481739711,21.7847616055,7.4996805907,-0.000275549623333,0.00094479065652,0.00136782759627,-0.877550779394,0.001703238946 +56.81,51.0063014984,0.00645481729195,21.7847494525,7.4668726693,-0.00120055832843,0.00148580916198,0.00112995592916,-0.879870132407,0.00322521333836 +56.82,51.0063021682,0.00645481706457,21.7847412022,7.43704393625,-0.00199138195617,0.000164251537049,0.00238394347667,-0.882098290938,0.000573132153275 +56.83,51.0063028354,0.00645481688654,21.7847347671,7.40662612313,-0.000507720259537,0.00112277274204,0.00210811670441,-0.885737944553,0.000292782651508 +56.84,51.0063034997,0.00645481676375,21.7847195893,7.37543635281,-0.00121605936958,0.00191278760349,0.000882875859784,-0.884131845047,0.000989521203733 +56.85,51.0063041613,0.00645481656795,21.7847040774,7.34392291274,-0.00153244088369,0.00118958819137,0.00275271041582,-0.882019572376,-0.000264666808989 +56.86,51.00630482,0.00645481634998,21.7846916795,7.31195059078,-0.00152732689327,0.00128998915927,0.00301312181971,-0.886382088033,0.00113810620296 +56.87,51.0063054759,0.0064548161962,21.7846802795,7.28198380964,-0.00063142962395,0.000990014701012,0.00415918923659,-0.887483291045,-0.00120712256965 +56.88,51.006306129,0.00645481617825,21.7846709744,7.25010683548,0.000379462319032,0.000871013439253,0.00440946948181,-0.88907328081,0.000802185224224 +56.89,51.0063067794,0.00645481626891,21.7846623309,7.2200818258,0.000893194240034,0.00085767900859,0.00458591291801,-0.889425890341,-0.000318521230009 +56.9,51.006307427,0.00645481635103,21.7846489377,7.18824427908,0.000259626835225,0.00182095519266,0.00343770185604,-0.890708956988,0.000508407833003 +56.91,51.0063080716,0.00645481636433,21.7846269786,7.15583092127,-7.29271287933e-005,0.00257086739632,0.00117534644553,-0.893498331847,-0.00280812566588 +56.92,51.0063087135,0.00645481637625,21.7846040443,7.12541944426,0.000240170571823,0.00201599258559,0.00335309450065,-0.896791753558,-0.00189643166855 +56.93,51.0063093526,0.00645481641849,21.7845833328,7.09448682415,0.00035283213587,0.00212630838857,0.000744551118743,-0.896544297927,-0.000741588985359 +56.94,51.0063099889,0.00645481655752,21.784559678,7.06336992194,0.00159882168321,0.00260465568225,0.00230292378582,-0.899017191971,-0.00131757696824 +56.95,51.0063106224,0.00645481675685,21.7845410305,7.03197876949,0.00119926493683,0.00112484741692,0.00184637084117,-0.899082258699,-0.000149294578954 +56.96,51.0063112531,0.00645481683306,21.7845287678,7.00040126822,-0.000129420671803,0.00132768323183,0.000768664716194,-0.900792646877,-5.64001784849e-005 +56.97,51.006311881,0.00645481678062,21.7845155591,6.9693486659,-0.000606743893795,0.00131405318316,0.00244129467715,-0.901828750048,0.000575624700881 +56.98,51.0063125061,0.00645481673061,21.7844982795,6.93968172215,-9.52019042318e-005,0.00214186938598,0.000707089495426,-0.905697653861,-0.000362406950444 +56.99,51.0063131285,0.00645481662454,21.7844771957,6.90936234399,-0.00139387565004,0.00207490175709,0.000263492032006,-0.907818385766,0.000738771910589 +57,51.0063137482,0.00645481652693,21.7844611572,6.87704664785,2.37533860759e-005,0.0011327862023,0.000679594333654,-0.908332979685,-0.00115077115242 +57.01,51.0063143649,0.00645481660893,21.7844518223,6.84553404858,0.0011272155206,0.000734198226524,0.000596571826201,-0.911055265345,-0.000517324452139 +57.02,51.0063149789,0.00645481663996,21.7844440144,6.81631900688,-0.000691505425569,0.000827387880255,0.0013829518226,-0.914221902758,-0.002202579551 +57.03,51.0063155902,0.00645481657705,21.7844339926,6.78341008865,-0.000191629465814,0.00117696106376,-0.000219675267185,-0.91768154592,-0.00177259479935 +57.04,51.0063161985,0.0064548165652,21.784426843,6.75179034561,2.52693834136e-005,0.000252959634475,0.00132679686405,-0.916139545521,-0.00095673563442 +57.05,51.006316804,0.00645481655915,21.7844191926,6.72108331534,-0.000110245144718,0.00127712435964,-0.00224677341694,-0.917672424296,0.00140447275686 +57.06,51.0063174067,0.00645481662031,21.7844115243,6.68874413635,0.000968761277765,0.000256542515092,-0.000987401264396,-0.918776681377,0.00321907539265 +57.07,51.0063180066,0.00645481671739,21.7844100858,6.65785280537,0.000394017225184,3.11607221112e-005,-0.000113878814634,-0.917565097871,0.00310453364768 +57.08,51.0063186036,0.00645481674971,21.7844096851,6.62647621934,5.97865660256e-005,4.89688764115e-005,-0.000689495957176,-0.920361128735,-0.000204028044197 +57.09,51.0063191979,0.00645481666892,21.7844054743,6.59649124423,-0.00119400500321,0.000793190913983,0.000382101620654,-0.920461251468,7.78297845911e-005 +57.1,51.0063197895,0.00645481655483,21.7843988523,6.56511973443,-0.000407427334507,0.000531217808706,-0.000331755497406,-0.923679778146,0.000159721906312 +57.11,51.0063203781,0.0064548165673,21.7843949147,6.53164298263,0.000582373757628,0.000256302965861,0.00189616099067,-0.925583968675,-0.00129029601963 +57.12,51.0063209638,0.00645481658693,21.7843941465,6.50128908959,-0.000306744891956,-0.000102661693846,0.00196433430953,-0.927305309582,-0.000975669192895 +57.13,51.0063215468,0.00645481657784,21.7843957686,6.4703683459,0.000179101950966,-0.000221770114531,0.00114843694556,-0.929401981223,0.000141436074319 +57.14,51.006322127,0.00645481646808,21.7843952155,6.43854527845,-0.00171991156684,0.000332383552028,0.0016525100818,-0.929909335315,-0.000525021964019 +57.15,51.0063227043,0.00645481629162,21.7843970684,6.40640938797,-0.000757087874372,-0.00070294539288,6.05398542764e-005,-0.932779586619,-0.00264826402352 +57.16,51.0063232788,0.00645481621776,21.7843948978,6.37475287283,-0.000279755645947,0.00113705494472,0.000975520756499,-0.933092333087,-0.00293161697805 +57.17,51.0063238503,0.00645481620655,21.784375619,6.34221884849,0.000122418886353,0.00271870610263,-0.000572567302969,-0.933449028317,-0.00222397237684 +57.18,51.006324419,0.00645481619561,21.7843553111,6.3106155486,-0.000276092905191,0.00134287965695,-0.000541923085762,-0.936899304075,-0.00213926359666 +57.19,51.0063249849,0.00645481619918,21.7843403162,6.27969259515,0.000326296919172,0.0016560948867,-0.00041460370742,-0.93881361197,-0.00114729803198 +57.2,51.006325548,0.00645481617941,21.7843355316,6.24912899946,-0.000603813423447,-0.000699171906386,0.0015395606085,-0.940857795788,-0.00064516933053 +57.21,51.0063261084,0.00645481612278,21.784339029,6.21968997091,-0.00019115033784,-3.05689477597e-007,0.00277984935373,-0.942620898252,-0.000971932452741 +57.22,51.006326666,0.00645481600769,21.7843442535,6.18704384594,-0.00142445767837,-0.00104460135978,-0.000389933795907,-0.942618430133,-0.00219378773709 +57.23,51.0063272208,0.00645481588128,21.7843567185,6.15714901518,-0.00035007073251,-0.00144839413635,0.0018020484785,-0.945149588674,0.000401541766531 +57.24,51.0063277728,0.0064548158799,21.7843682956,6.1249377415,0.000330656794722,-0.000867026911967,3.43869292933e-005,-0.945379215851,-0.000797784963547 +57.25,51.006328322,0.00645481581199,21.7843678505,6.09460095689,-0.00128388087847,0.000956054285731,0.000839292602973,-0.946981486929,-0.000644542798446 +57.26,51.0063288685,0.00645481569247,21.7843600977,6.06448369504,-0.000393970375706,0.000594491272574,0.000860034251149,-0.949231157213,-0.00277404568433 +57.27,51.0063294121,0.00645481559778,21.7843476501,6.03065484337,-0.000935185945997,0.00189502991458,0.000431510972112,-0.951797726148,-0.00192214306405 +57.28,51.0063299528,0.00645481548556,21.7843347291,5.99937550215,-0.000640210958014,0.00068916720575,0.00102898631098,-0.950593531441,-0.000770928974722 +57.29,51.0063304906,0.00645481545645,21.784327099,5.96730866087,0.000231633136346,0.00083686041174,-0.00119491308383,-0.952501755312,-0.00173334741866 +57.3,51.0063310255,0.0064548154398,21.7843177926,5.93457665636,-0.000465350224937,0.00102442864548,-0.00145848140859,-0.95690890462,0.000581401732258 +57.31,51.0063315576,0.00645481533006,21.7843042399,5.90431224102,-0.00107516811671,0.00168609957887,-0.000549938901976,-0.957098623702,-0.00080827910622 +57.32,51.006332087,0.00645481518372,21.7842911753,5.87468335311,-0.000979128614631,0.000926820398156,-0.00208378308854,-0.958093030565,-0.000216613957654 +57.33,51.0063326136,0.00645481504576,21.7842710006,5.84210607125,-0.000957531591422,0.00310811331009,-0.00204241023412,-0.958986863782,-0.00217470635245 +57.34,51.0063331373,0.00645481495566,21.7842467063,5.81085289054,-0.000307144488943,0.00175075402184,-0.000689128868046,-0.96059799578,-0.0016441502384 +57.35,51.0063336583,0.00645481491463,21.7842277348,5.77994091227,-0.000268819784932,0.00204353987724,-0.000373644905274,-0.963373316768,-0.00189665751591 +57.36,51.0063341765,0.00645481488245,21.78420496,5.74947606425,-0.000183007737393,0.0025114294661,0.000591417544712,-0.961952705243,-0.000793116966003 +57.37,51.0063346918,0.0064548149572,21.7841746452,5.71758390086,0.00123230283816,0.00355153721378,0.000213209749186,-0.96346002289,-0.000857267390566 +57.38,51.0063352044,0.00645481511399,21.7841404708,5.68586764261,0.000968654784196,0.00328332746052,0.000918568197081,-0.963860157596,0.000656571403973 +57.39,51.0063357141,0.0064548152756,21.784117074,5.65513425957,0.00130001270548,0.0013960350516,0.00163358945467,-0.965217669997,0.0034736432574 +57.4,51.006336221,0.0064548153667,21.7841035239,5.62354509068,-2.12036143992e-005,0.00131399764696,0.00178573444366,-0.967664680068,0.00170793322256 +57.41,51.0063367252,0.0064548154,21.7840875387,5.59422799937,0.000488715644434,0.00188302877571,0.00138905267954,-0.967859503087,0.00131373600574 +57.42,51.0063372267,0.00645481551283,21.7840699064,5.56391718297,0.00109515915655,0.0016434325076,0.000445019593653,-0.969583961846,0.000556858436146 +57.43,51.0063377255,0.0064548155273,21.7840562242,5.53461966634,-0.000892104748068,0.00109301156774,0.00168772110252,-0.972154316671,-0.000677742945439 +57.44,51.0063382214,0.00645481546379,21.7840399113,5.50048421192,6.15472931464e-007,0.00216957643918,0.000658692546851,-0.973826230255,0.000692020101967 +57.45,51.0063387144,0.00645481551486,21.7840095841,5.46887581494,0.000716261001078,0.00389585393326,-0.00150508878137,-0.977798066688,0.00207289464697 +57.46,51.0063392047,0.00645481559363,21.7839828315,5.43855736136,0.000389470447593,0.00145467531262,-0.00166802920617,-0.977584305864,-0.000453192687026 +57.47,51.0063396922,0.00645481555651,21.7839782075,5.4085847529,-0.000910472239514,-0.000529879934755,-0.000213572619133,-0.978356674816,-0.00108797260186 +57.48,51.0063401769,0.00645481553581,21.7839775678,5.37666221235,0.000619915573097,0.000657817956651,-0.000247101330734,-0.979938371469,-0.000784695449641 +57.49,51.0063406588,0.00645481547792,21.7839720226,5.34579781699,-0.00143259838354,0.000451227345411,0.000285977465556,-0.983148117951,0.000975077155524 +57.5,51.0063411379,0.00645481527797,21.7839613057,5.31382226123,-0.00137419222467,0.00169215143306,-0.000635118915577,-0.984490397959,0.00104928331083 +57.51,51.0063416142,0.00645481512349,21.7839513791,5.28271761552,-0.000794387857427,0.000293157533127,-0.00117945750608,-0.984186769315,0.00260667567018 +57.52,51.0063420877,0.00645481513193,21.7839482239,5.25255990168,0.000912858213939,0.000337891507441,0.000323353675386,-0.985762944024,0.00115591066169 +57.53,51.0063425584,0.00645481536692,21.7839543598,5.22064667627,0.00238583810052,-0.0015650721961,-0.000507571801961,-0.987348981377,0.00129109107362 +57.54,51.0063430262,0.00645481566932,21.7839602365,5.18858494606,0.00185918736054,0.000389738079452,-0.00186034946433,-0.989672782538,0.000241041511615 +57.55,51.0063434912,0.00645481579589,21.7839569526,5.15671241213,-8.23928575905e-005,0.00026703524521,-0.000288451100672,-0.989933307793,-0.00168641217388 +57.56,51.0063439533,0.00645481579904,21.7839605768,5.12461792663,0.000126617729676,-0.000991874717914,0.00127526612058,-0.993648350033,0.000534214696675 +57.57,51.0063444126,0.00645481585961,21.7839825886,5.09513171823,0.000723569406064,-0.00341048208545,0.000717366388506,-0.996017354131,0.00317779306707 +57.58,51.0063448692,0.00645481597053,21.7840052522,5.0630554302,0.000833523335218,-0.00112225224111,7.23233512336e-005,-0.995466867299,0.00111079916144 +57.59,51.0063453228,0.00645481607083,21.7840186376,5.03088877713,0.000574451540759,-0.0015548199913,-0.000872159045917,-0.999187111401,-0.000541047324317 +57.6,51.0063457737,0.00645481611175,21.7840264117,5,0,0,0,-1,0 +57.61,51.0063462213,0.00645481624958,21.7840346533,4.959812363,0.00193475187681,-0.00164832813701,-0.00117091878913,-0.997001177656,-0.00282349153654 +57.62,51.0063466654,0.00645481643326,21.7840453771,4.92077785455,0.000643739844507,-0.000496423529923,0.00076493543284,-0.994555693714,-0.00136098967495 +57.63,51.0063471059,0.00645481655592,21.7840449919,4.88107939691,0.00107806381303,0.00057347230733,0.000911943022627,-0.991295445115,-0.00266761302334 +57.64,51.0063475429,0.00645481664496,21.7840317902,4.84266869925,0.000171840376134,0.00206685219045,0.00125075342339,-0.987692545557,-0.000718615684026 +57.65,51.0063479765,0.0064548166288,21.7840121152,4.80472594383,-0.000398689683914,0.00186814878253,0.00119117881545,-0.98202190815,0.00122027295381 +57.66,51.0063484067,0.00645481663205,21.7839949658,4.7657991913,0.000444295003881,0.00156173349496,0.00181327290233,-0.978499634001,-0.00104974681028 +57.67,51.0063488333,0.00645481661903,21.7839827178,4.72701873061,-0.000627096141529,0.000887869643629,0.00282437352894,-0.975207195315,-0.00113897501231 +57.68,51.0063492565,0.0064548165484,21.7839716636,4.68789872922,-0.000364258776348,0.00132297457794,0.00325072881527,-0.97034213717,-0.000228899634202 +57.69,51.0063496761,0.00645481650537,21.7839582806,4.64960889488,-0.000239904450781,0.00135361969274,0.00336473111884,-0.9667299194,-0.00146252224572 +57.7,51.0063500923,0.00645481637508,21.7839405157,4.60920231011,-0.00158894310251,0.00219936951359,0.0030391716529,-0.965728398065,-0.00200651732473 +57.71,51.0063505049,0.00645481611379,21.7839217361,4.57091230829,-0.00207899086116,0.00155655321816,0.001602626321,-0.962469695132,-0.00180931412196 +57.72,51.0063509139,0.00645481590079,21.7839060844,4.53130582254,-0.000911087315035,0.00157377645088,0.00400727241382,-0.955897740434,-0.000936015555953 +57.73,51.0063513194,0.0064548157135,21.7838940444,4.49042507902,-0.00171792883521,0.00083423146959,0.00323596023907,-0.951471012399,-0.00143917131182 +57.74,51.0063517213,0.00645481550865,21.783875282,4.45098638768,-0.00115773497735,0.00291824765502,0.00340087648466,-0.949252872913,0.000213671937226 +57.75,51.0063521198,0.00645481543301,21.7838566983,4.41478196121,9.59130068174e-005,0.000798484128152,0.00226197216271,-0.943997467618,0.000300821292216 +57.76,51.0063525148,0.00645481540754,21.7838467005,4.37392905406,-0.00045345266534,0.00120107148415,0.000673095795428,-0.94026788642,-0.000716274454049 +57.77,51.0063529061,0.00645481540846,21.7838349652,4.33366966281,0.000466416509226,0.00114599252031,0.000603879937758,-0.936895973291,0.00056848012346 +57.78,51.0063532939,0.00645481539832,21.7838282217,4.29469621738,-0.000608775983169,0.000202708389671,0.000758077166113,-0.93330366032,0.00101917223484 +57.79,51.0063536781,0.00645481527827,21.7838224626,4.25339623725,-0.00107651253918,0.00094911796793,0.00157444695876,-0.929265171083,-0.000753104168521 +57.8,51.0063540587,0.00645481518833,21.7838174175,4.21564819308,-0.000186030360869,5.98869024984e-005,0.000391792563372,-0.926429749646,-0.00132502045898 +57.81,51.0063544359,0.00645481518548,21.78380597,4.1763694995,0.000146099200579,0.00222961746527,-7.82062598453e-005,-0.922560242662,-0.000575439095398 +57.82,51.0063548096,0.00645481505705,21.7837924189,4.1375171242,-0.00194902780953,0.000480615878056,4.25092815642e-006,-0.917770412852,-0.000247784401825 +57.83,51.0063551798,0.00645481483851,21.7837873112,4.09955211096,-0.00111873174383,0.000540918970969,0.000292359721866,-0.912474684666,0.00165766305914 +57.84,51.0063555466,0.00645481473633,21.7837776772,4.06128455587,-0.000315666947263,0.0013858739202,0.00315904445663,-0.909350453985,-0.000184216820498 +57.85,51.0063559098,0.00645481458728,21.7837595842,4.02124976985,-0.00177662670204,0.00223272999565,0.00330274641911,-0.906866261881,-0.000337316971976 +57.86,51.0063562695,0.00645481451858,21.7837329015,3.98177369847,0.000812238393809,0.00310381364016,0.0036715891568,-0.903819210272,-0.00329298724241 +57.87,51.0063566258,0.00645481454649,21.7836977137,3.94444191088,-0.000420494171752,0.00393373502188,0.00238064495784,-0.899663408623,-0.00340559986151 +57.88,51.0063569785,0.00645481446757,21.7836559781,3.90483369165,-0.000687376446699,0.0044134015495,0.00304092158381,-0.89274265541,-0.00417178483306 +57.89,51.0063573278,0.00645481434715,21.7836188661,3.8671729661,-0.00100304304567,0.00300898399992,0.00393208110204,-0.88918982299,-0.00322077141247 +57.9,51.0063576737,0.0064548141915,21.7835875826,3.82819668717,-0.00118179280046,0.00324772615431,0.00330711535548,-0.885839105742,-0.00300683490793 +57.91,51.0063580161,0.00645481404236,21.7835559155,3.78917170354,-0.000911895283247,0.00308569810918,0.000863726027626,-0.881307608328,-0.00280022738672 +57.92,51.0063583549,0.00645481398942,21.7835312067,3.74968348972,0.000168747813147,0.00185605749151,0.00177905723554,-0.875860373673,-0.00267917405198 +57.93,51.00635869,0.006454814072,21.7835152416,3.70680891267,0.000990504012243,0.00133696372587,0.000544963519029,-0.871984105089,-0.00144138201417 +57.94,51.0063590215,0.0064548141982,21.7835017623,3.66862779554,0.000781053668102,0.00135889662581,0.000872346509202,-0.868086867731,-0.00139212969557 +57.95,51.0063593496,0.00645481442532,21.7834841491,3.63044652078,0.00240717807901,0.00216372969559,-0.000913873191242,-0.863650174488,-0.00479733331088 +57.96,51.0063596741,0.00645481471374,21.7834671886,3.59018348071,0.00164161395276,0.0012283821748,-0.00082045607884,-0.861798351618,-0.00281586611733 +57.97,51.0063599951,0.00645481487205,21.7834571792,3.55263349731,0.000580606955098,0.000773489451809,-0.00045664573851,-0.857164698538,-0.0050463014137 +57.98,51.0063603127,0.00645481488703,21.7834490797,3.51299664867,-0.000370244082583,0.000846424442537,-0.000342282804691,-0.852058186385,-0.00502815427529 +57.99,51.0063606268,0.00645481476057,21.7834303668,3.47564702269,-0.00140500882533,0.00289614503665,-0.000799644537341,-0.847319299671,-0.00596962892964 +58,51.0063609375,0.00645481464721,21.7834072391,3.43693017943,-0.000186244103092,0.00172940452162,-0.00122023976006,-0.845372355302,-0.00468992447339 +58.01,51.0063612446,0.00645481467326,21.7833898025,3.39672116031,0.000551843188287,0.00175791377443,-0.00105476901004,-0.842107387136,-0.00441460963756 +58.02,51.0063615481,0.0064548147371,21.7833746082,3.35712535614,0.000344417616479,0.00128093921019,0.000207194386846,-0.83544485797,-0.00438689612803 +58.03,51.0063618482,0.00645481478459,21.7833653881,3.3183349813,0.000322188927582,0.000563078105017,-0.000355232100321,-0.832666330813,-0.00422230980817 +58.04,51.0063621447,0.00645481464621,21.7833534731,3.27992978173,-0.00226473596421,0.00181993386394,-0.00136127881164,-0.830256970534,-0.00453279668004 +58.05,51.0063624378,0.00645481441027,21.7833437183,3.24090442314,-0.00104728392882,0.000131015337716,2.46459648516e-005,-0.82521815379,-0.00354434300775 +58.06,51.0063627273,0.00645481418038,21.7833281527,3.20173468687,-0.00217980196787,0.00298211463871,-0.000958619371253,-0.822087815403,-0.00407720214707 +58.07,51.0063630135,0.00645481384288,21.783299975,3.16587470018,-0.00255800929882,0.00265342083423,-0.000638818694492,-0.819734161744,-0.00488048589914 +58.08,51.0063632962,0.00645481357875,21.7832716497,3.12368932466,-0.00114969320442,0.00301162840959,-0.000152867215012,-0.813685115569,-0.00438744973572 +58.09,51.0063635752,0.00645481337295,21.7832487777,3.08463638597,-0.00173924242471,0.00156278391909,0.00117970193579,-0.810574040488,-0.00226033826071 +58.1,51.0063638507,0.00645481316745,21.7832338632,3.04502086219,-0.0011454628354,0.00142012087797,0.000427550400255,-0.806721699429,-0.0048021386491 +58.11,51.0063641227,0.00645481308263,21.7832165066,3.00625561646,-4.52114559914e-005,0.00205118940739,-0.000510221881823,-0.803466387676,-0.00612823709007 +58.12,51.0063643912,0.00645481311467,21.7831942409,2.96776799093,0.000494855883614,0.00240195901135,0.000480270497779,-0.798834335399,-0.00436764197028 +58.13,51.0063646562,0.00645481333008,21.7831663999,2.92942570507,0.00252909162462,0.00316623110663,-0.00114696680098,-0.794299960138,-0.00184999882959 +58.14,51.0063649178,0.00645481352917,21.7831340713,2.89016913328,0.000265660374018,0.00329949028364,0.000586989375243,-0.789838330488,-0.00156393342544 +58.15,51.0063651759,0.00645481355246,21.7830965795,2.85186735965,6.12157480642e-005,0.00419886725879,0.00234878572592,-0.784785900702,-0.00173054384297 +58.16,51.0063654304,0.00645481362532,21.7830619501,2.8120815476,0.000961596270115,0.0027270202871,0.00103501942135,-0.781279590023,-0.00294253220221 +58.17,51.0063656815,0.00645481362612,21.7830363529,2.77283165372,-0.000950355298084,0.00239241568743,-5.34516585067e-007,-0.777126733196,-0.0039336107332 +58.18,51.006365929,0.00645481350795,21.7830115854,2.73500150459,-0.000708476973227,0.00256108062283,0.000995384087389,-0.772521801792,-0.00273154226754 +58.19,51.0063661731,0.00645481337298,21.7829763194,2.69630074811,-0.00118618806514,0.00449212213433,0.00267980490701,-0.766838471849,-0.00162559711279 +58.2,51.0063664136,0.00645481325366,21.7829402988,2.65566294438,-0.000488848826024,0.00271200354325,0.0013289702622,-0.762414806546,-0.000607304900521 +58.21,51.0063666506,0.00645481314749,21.7829181014,2.61724714713,-0.00100152325568,0.00172747832268,0.00167543046999,-0.76054647034,-0.00067961442846 +58.22,51.0063668842,0.00645481313231,21.7828987242,2.57877636094,0.000788507755782,0.0021479493742,0.00339670394184,-0.756631274048,0.000502612402658 +58.23,51.0063671142,0.00645481318651,21.7828748336,2.53996296789,-2.77140657449e-005,0.0026301714163,0.00452509015933,-0.750307564138,-0.000688777123589 +58.24,51.0063673407,0.00645481320614,21.7828514003,2.49967326903,0.000303248303061,0.00205650030235,0.00195629687749,-0.749414733061,-0.000215075632358 +58.25,51.0063675637,0.00645481336112,21.7828256074,2.46063162462,0.00187236344412,0.00310207359847,-0.000336654954387,-0.743248219993,0.00270325004069 +58.26,51.006367783,0.00645481371541,21.7827939048,2.42002560235,0.00310107271246,0.00323845354887,0.000757804450895,-0.741180427134,0.00125957677395 +58.27,51.0063679988,0.00645481419069,21.7827610179,2.38060665318,0.00357072727391,0.0033389228822,0.00335442756153,-0.737054200294,0.000532997486687 +58.28,51.006368211,0.00645481452182,21.7827374586,2.34227037135,0.00107754752033,0.00137293602524,0.00180806774157,-0.733308781255,-0.000786813382526 +58.29,51.0063684198,0.00645481471551,21.7827189086,2.3022937924,0.00164134659863,0.00233706041571,0.000105024783112,-0.727785601621,0.000775611534846 +58.3,51.006368625,0.00645481486161,21.7827051198,2.26449511433,0.000409669516451,0.000420696890925,0.00222343517398,-0.724597675592,-0.0011651509918 +58.31,51.0063688269,0.00645481499911,21.7826929883,2.22682539992,0.00152038889415,0.00200561423806,0.00233030734777,-0.719514839721,-0.00119684452662 +58.32,51.0063690253,0.00645481517451,21.7826755678,2.18760493745,0.000941856947407,0.00147847865372,0.00164925350243,-0.718712340229,0.00033553205711 +58.33,51.0063692201,0.00645481533577,21.7826595712,2.14753020315,0.00132192087931,0.0017208410023,0.00262326373472,-0.717694402652,0.00139626359884 +58.34,51.0063694114,0.00645481546142,21.7826427567,2.10799375579,0.000441860339375,0.0016420514001,0.00179307702205,-0.712529444094,0.00154848582014 +58.35,51.0063695993,0.00645481557889,21.7826351594,2.07226370876,0.00120717820541,-0.000122585711937,0.00240629170528,-0.706447012791,-0.000136125694733 +58.36,51.0063697837,0.00645481571923,21.782631383,2.03170552809,0.000762906855818,0.000877869286496,0.00170520989341,-0.702634061149,-0.000774559680084 +58.37,51.0063699646,0.00645481582664,21.7826233523,1.99215990346,0.000744769870339,0.000728258412797,0.00296958515744,-0.696834226532,-2.91301869079e-006 +58.38,51.0063701419,0.00645481595025,21.7826097482,1.95258084917,0.000990427397966,0.00199257286321,0.00351303952736,-0.692536233643,-0.00278549370897 +58.39,51.0063703157,0.00645481616778,21.7825886919,1.91406257757,0.00206316741919,0.0022186860933,0.0023278004024,-0.689740682875,-0.00201822355694 +58.4,51.006370486,0.0064548163701,21.7825807579,1.87623339984,0.000776957448329,-0.000631894109709,0.00283121867833,-0.686587481887,-0.000462442374094 +58.41,51.0063706529,0.00645481639334,21.7825838139,1.83737998214,-0.000450615665596,2.06909825903e-005,0.00216266991017,-0.682911845698,-0.00232977550398 +58.42,51.0063708164,0.00645481633429,21.7825861493,1.8001312517,-0.000378359137625,-0.000487751390646,0.00166426108005,-0.678021916557,-0.00101618749992 +58.43,51.0063709765,0.00645481626126,21.7825966906,1.76127001187,-0.000646769564162,-0.00162051756292,0.00144683454109,-0.674517323001,-0.00106263024413 +58.44,51.0063711329,0.00645481619667,21.7826089854,1.71977835245,-0.000259993031772,-0.000838439037343,0.00306117487028,-0.66948838032,-0.00132032505372 +58.45,51.0063712856,0.00645481609952,21.7826176001,1.67779829925,-0.00110368866741,-0.000884504619168,0.00149765735638,-0.666687694094,-0.00363546389322 +58.46,51.0063714348,0.0064548159587,21.7826335648,1.64068628367,-0.000873208992953,-0.00230843530823,0.00252082938976,-0.660750467221,-0.002450852461 +58.47,51.0063715806,0.00645481581256,21.7826628554,1.60401756035,-0.00117826756637,-0.00354969165258,0.00228461526767,-0.658191786411,5.72238945093e-005 +58.48,51.0063717229,0.00645481567328,21.7826939017,1.56272572177,-0.000776806280401,-0.00265956042442,0.00213138237454,-0.6548564535,0.000931989144181 +58.49,51.0063718617,0.00645481568683,21.7827240769,1.52395575452,0.000967010425297,-0.00337548123652,0.00161403135018,-0.650951765796,-0.000886287519288 +58.5,51.0063719968,0.00645481578157,21.7827664961,1.48330019537,0.000362828579096,-0.00510835622944,0.00239716555908,-0.64799623694,-0.000464204353131 +58.51,51.0063721284,0.00645481578168,21.7828092467,1.44485051509,-0.000361157160422,-0.00344176298551,0.00235879560801,-0.643526045877,-0.00110638080424 +58.52,51.0063722565,0.00645481577799,21.7828476986,1.40575377862,0.000309308920991,-0.00424861721946,0.00213887202336,-0.639648437291,-0.000424655760532 +58.53,51.0063723813,0.00645481589528,21.7828856963,1.3692849492,0.00133714640664,-0.00335091844719,0.00410695382012,-0.634020358296,-0.000203601733129 +58.54,51.0063725026,0.00645481608731,21.7829170961,1.32971637723,0.00135844630018,-0.00292905557827,0.00113745961696,-0.631702051072,-0.000805088150849 +58.55,51.0063726203,0.00645481636542,21.7829436535,1.28960323079,0.00254564800097,-0.00238241567353,0.00188121464362,-0.626514930302,0.000686903513403 +58.56,51.0063727344,0.00645481662181,21.7829654533,1.24993893537,0.00105343219755,-0.00197754790579,0.00173357782505,-0.623836079936,-0.000302247339075 +58.57,51.006372845,0.00645481669954,21.7829861667,1.21030108488,3.78055537543e-005,-0.00216513242229,-0.000990462481794,-0.620823532701,0.000893882023751 +58.58,51.0063729521,0.00645481671877,21.7830000824,1.17226341758,0.000232091938672,-0.000618001758265,0.00165527565588,-0.618429023513,0.000700787927945 +58.59,51.0063730557,0.00645481673755,21.7830071208,1.13274098128,3.15092464913e-005,-0.000789682129089,0.00336517935825,-0.612689034324,-0.00188621522115 +58.6,51.0063731557,0.00645481665844,21.7830156623,1.09284039448,-0.0011420922333,-0.000918611677316,0.00164480589338,-0.609132441786,-0.000373375627659 +58.61,51.0063732521,0.0064548165293,21.7830278997,1.0524870192,-0.000670615332382,-0.00152887721328,0.00292862251689,-0.603852167649,-0.000872743607056 +58.62,51.006373345,0.00645481638739,21.7830394355,1.01372619184,-0.00132157522977,-0.000778273597884,0.00205647249161,-0.60008102671,-0.00177928107229 +58.63,51.0063734344,0.00645481627363,21.7830479448,0.975607217868,-0.000275339394769,-0.000923587804927,0.00157156841786,-0.595921784929,-0.0013946148481 +58.64,51.0063735204,0.00645481624358,21.7830574791,0.938131849652,-0.000146389369332,-0.000983285600976,9.66775564858e-005,-0.593270552817,-0.000282719247098 +58.65,51.0063736031,0.00645481626554,21.783065578,0.900925411519,0.000454567099473,-0.000636491017062,0.00131869672069,-0.589234986462,-0.000531980225868 +58.66,51.0063736823,0.00645481636095,21.7830746969,0.861470448725,0.000884819983348,-0.00118728411799,0.000871207216765,-0.584864128169,-0.00209535942942 +58.67,51.0063737579,0.0064548166087,21.7830841306,0.82145071623,0.0025930236685,-0.000699448853558,0.004108129116,-0.581429951823,-0.00209366023823 +58.68,51.00637383,0.00645481683217,21.783096723,0.782332727578,0.000543915480622,-0.00181903660406,0.00302650482376,-0.576724894077,-0.000543355997264 +58.69,51.0063738985,0.00645481688731,21.78311304,0.742444757924,0.000230165745068,-0.0014443569408,0.000155383280369,-0.573169563815,-0.0011365782268 +58.7,51.0063739635,0.00645481693396,21.7831290347,0.704159836109,0.000424715870924,-0.00175459136268,0.00290859021996,-0.56945189237,-0.00112258540367 +58.71,51.0063740251,0.00645481693061,21.7831541686,0.664442490843,-0.000471821365781,-0.00327217858103,0.00126970206147,-0.566413344306,-0.00216630947561 +58.72,51.006374083,0.00645481688361,21.7831806003,0.62544054938,-0.000187969400696,-0.00201417110773,0.000143422500007,-0.562342920741,0.000426034494219 +58.73,51.0063741375,0.0064548168738,21.7832119964,0.586143597527,5.02484334849e-005,-0.0042650402937,0.0010643623658,-0.557115894871,-0.00056725249539 +58.74,51.0063741885,0.00645481676568,21.7832498533,0.548089057785,-0.00156789610885,-0.00330635833546,0.000948690609587,-0.553907846586,-0.00199161519237 +58.75,51.0063742359,0.00645481660771,21.7832791475,0.507659495445,-0.000649658320629,-0.00255248115739,-0.00103784448383,-0.550514422471,0.00039132074541 +58.76,51.0063742799,0.00645481649878,21.7833051448,0.470422885272,-0.000879416596236,-0.00264697873059,-0.00167031036572,-0.54700867495,-0.00120309383345 +58.77,51.0063743204,0.00645481629767,21.7833335857,0.432128761787,-0.00194369805604,-0.00304120060758,-0.00177430443459,-0.544112321175,-0.000606797066693 +58.78,51.0063743575,0.00645481608464,21.7833583324,0.391593148322,-0.00104682867042,-0.00190813548073,-0.00354761856335,-0.53773576082,0.00169095354275 +58.79,51.0063743909,0.00645481588836,21.7833757333,0.352567322777,-0.00170848004124,-0.00157204356749,-0.0018495700428,-0.532236448818,0.000694457904334 +58.8,51.0063744208,0.00645481566761,21.783389717,0.312385993473,-0.0013903787799,-0.00122470224381,-0.00114233171045,-0.53024478035,0.000226601305367 +58.81,51.0063744472,0.00645481554011,21.7834033326,0.275728886191,-0.000399419885721,-0.00149841802512,0.00171527546627,-0.525641333703,-0.00178771548623 +58.82,51.0063744702,0.00645481552703,21.783425567,0.234810753916,0.000215910578668,-0.0029484464423,-0.000111783723977,-0.52230274194,-0.00264091359999 +58.83,51.0063744895,0.00645481561902,21.7834504694,0.195373625375,0.00107542004174,-0.00203203047939,0.000811015870283,-0.521292103144,-0.00330612226551 +58.84,51.0063745053,0.00645481580883,21.7834633739,0.155957876616,0.00158898637284,-0.000548885211404,-0.000407669044167,-0.516799509964,-0.00275690144318 +58.85,51.0063745175,0.00645481603423,21.7834707185,0.115881926136,0.00157511331674,-0.000920027010359,-0.000137136556551,-0.513117890836,-0.00136360009743 +58.86,51.0063745262,0.00645481619416,21.7834819091,0.0773382904878,0.000669971325861,-0.00131809235837,0.000103253073814,-0.508592544764,-0.000181962073643 +58.87,51.0063745314,0.00645481629365,21.7834918423,0.0390958810257,0.000726550858899,-0.000668545490253,-0.000901443927302,-0.504087840933,-0.00164645953012 +58.88,51.0063745332,0.0064548163454,21.783495185,0,0,0,0,-0.5,0 +58.89,51.0063745331,0.00645481626235,21.7834883768,-0.000824041464461,-0.00116589466191,0.00136164917166,0.00106218564449,-0.494080219416,-0.00177662868255 +58.9,51.006374533,0.00645481609896,21.7834762829,-0.00147750384552,-0.00112766847067,0.00105712350905,0.00141116471372,-0.492944792981,-0.000796989836439 +58.91,51.0063745328,0.00645481602676,21.7834624684,-0.00377139162354,0.000114194853622,0.00170576956623,0.00290220675148,-0.489477234524,-0.000381742826735 +58.92,51.0063745326,0.0064548159828,21.7834432478,-0.0017478363811,-0.000731375387425,0.00213836607796,0.00267857939092,-0.485494491572,-0.000748675757879 +58.93,51.0063745324,0.00645481593384,21.7834263523,-0.0009130520359,4.40839735081e-005,0.00124072877505,0.00172333816984,-0.481145937616,0.000584128299221 +58.94,51.0063745324,0.00645481597238,21.7834177692,-9.78576574858e-005,0.00049692656578,0.000475882148407,0.0014465335811,-0.477881716558,0.000607836994176 +58.95,51.0063745324,0.00645481608273,21.7834122143,0.0003294545518,0.00105222892302,0.00063510549615,0.00366279601899,-0.472394936392,0.00287076136804 +58.96,51.0063745325,0.00645481621351,21.7834053258,0.00133076776746,0.000783527228402,0.000742582804932,0.00182901091533,-0.467520008293,-0.0006010632762 +58.97,51.0063745326,0.0064548161961,21.7833990763,0.00170638160118,-0.00102796996432,0.000507327249158,0.00092993849706,-0.461948653581,0.00164899241459 +58.98,51.0063745327,0.00645481603547,21.7833860725,0.000311990546513,-0.00122679315219,0.00209343424614,0.00372693281945,-0.460925759272,-0.000266538142437 +58.99,51.0063745328,0.00645481578645,21.7833601965,0.00120424214416,-0.00226884592253,0.00308176622132,0.00157338533221,-0.459038144483,-0.0010809383577 +59,51.0063745329,0.00645481564041,21.7833346292,0.000509312548868,0.000218739276312,0.00203168826038,0.0015066371077,-0.453939034811,0.000522796238169 +59.01,51.0063745329,0.0064548157313,21.7833181188,-0.000418973318105,0.00105720293655,0.00127040128217,0.000299322568449,-0.448916845468,0.000837576017958 +59.02,51.0063745329,0.00645481570528,21.7833007403,0.00136068846536,-0.00142246731765,0.00220530130112,0.00159075584132,-0.44458270748,0.00192249192817 +59.03,51.006374533,0.00645481552716,21.7832812849,0.0010261274178,-0.00107804544671,0.00168577872081,0.00291640316978,-0.43814590738,0.000972099575696 +59.04,51.0063745331,0.00645481540685,21.783263588,0.000541529948285,-0.000610730821947,0.00185359006847,0.00169602864255,-0.436217894763,0.00102518295907 +59.05,51.0063745331,0.00645481533952,21.7832476519,5.60832931331e-005,-0.000334471175485,0.00133363531477,0.000494468094535,-0.430325905003,0.000545332111725 +59.06,51.0063745331,0.00645481534521,21.783237476,0.000189063655682,0.000414336628252,0.000701532438896,-0.000217154493852,-0.429463990261,-0.00028203384999 +59.07,51.006374533,0.00645481550348,21.7832263175,-0.00361101612698,0.00180747220594,0.00153016862377,-0.00148852265576,-0.42468505544,0.000461202274595 +59.08,51.0063745327,0.00645481568426,21.7832129112,-0.00138582364704,0.000730252607562,0.00115109519078,-0.00057821182375,-0.420668877623,0.000378695940456 +59.09,51.0063745326,0.0064548157809,21.7831985097,-0.00148234313523,0.000626284637294,0.00172921074072,-0.000125079151633,-0.416438963131,-0.00119527539918 +59.1,51.0063745325,0.00645481585916,21.7831931284,0.000140520981717,0.000472314415343,-0.000652954443454,-0.000813404304422,-0.414202136239,7.1517289605e-005 +59.11,51.0063745325,0.00645481581735,21.7831928576,-0.00141560448691,-0.00105923236973,0.000707118256946,-0.00184569094937,-0.410024526186,0.00127901594586 +59.12,51.0063745325,0.00645481581078,21.7831894894,0.000576140240498,0.000967055554442,-3.34749196813e-005,-0.000486272967808,-0.405667201475,0.0019206113534 +59.13,51.0063745325,0.00645481584953,21.7831811609,0.00102769237228,-0.000423163284635,0.00169917280114,0.000663459951946,-0.401756984545,0.00328582513595 +59.14,51.0063745325,0.0064548157721,21.7831691966,-0.000797771960302,-0.000663765192221,0.000693687692752,0.00229357231627,-0.398575847054,0.00216087683762 +59.15,51.0063745325,0.00645481585493,21.7831718951,0.00101869861892,0.00182658082547,-0.00123338947581,0.00271000120051,-0.393971209294,0.00038180286181 +59.16,51.0063745326,0.00645481602589,21.7831731896,-0.000269820299673,0.000573263475029,0.000974493638106,0.00238197189044,-0.389356074368,-0.000121929080227 +59.17,51.0063745326,0.00645481609537,21.783167521,0.000999194735253,0.000402028252406,0.000159223995708,0.0015097363676,-0.385339784926,-0.00163210915153 +59.18,51.0063745327,0.00645481625413,21.7831589831,0.000435093824896,0.00182659866579,0.00154835086543,0.00281329892951,-0.380592441607,-0.00152115006938 +59.19,51.0063745328,0.006454816514,21.7831398673,0.00305515931325,0.0018213768396,0.00227481905295,0.00151158376607,-0.377850364826,-0.000177530428811 +59.2,51.006374533,0.00645481672926,21.7831319851,0.000413901304559,0.00120039469976,-0.00069838380123,0.00169698859296,-0.373606961603,0.000653379257637 +59.21,51.006374533,0.00645481690064,21.7831557784,0.000380799062577,0.00120531164461,-0.00406027843525,0.00094531065846,-0.370340871745,0.00164303683532 +59.22,51.006374533,0.00645481715323,21.7831863071,-0.000860995676272,0.0023404552149,-0.00204547203035,0.0019074361439,-0.365839758177,0.000882809865315 +59.23,51.0063745329,0.00645481760746,21.7832074777,-0.000747766363102,0.00403596337812,-0.00218864733331,0.00215948643254,-0.36116980443,9.64914374379e-005 +59.24,51.0063745329,0.00645481818198,21.7832300946,0.000647650302697,0.00402897964164,-0.00233472886479,0.00245402423114,-0.356287736004,0.00164707335664 +59.25,51.006374533,0.00645481881752,21.7832454332,0.000400053859522,0.00489241180502,-0.000732979426974,0.000442132175342,-0.353700617444,0.000736195345233 +59.26,51.006374533,0.0064548193227,21.7832587596,0.000268865642507,0.0021992284953,-0.00193231659687,0.000595075488463,-0.350454870795,-0.00213852224117 +59.27,51.006374533,0.00645481956817,21.7832807237,-0.000281986309753,0.0012465618953,-0.00246049260882,0.00226876559978,-0.347445022376,-0.000141043534712 +59.28,51.006374533,0.00645481978074,21.7833043584,0.0007948319821,0.00173733375363,-0.00226645396544,0.00250164853938,-0.342664807274,0.00173286334739 +59.29,51.006374533,0.00645482013709,21.7833197941,-0.000361268980697,0.00326501091435,-0.000820673799963,0.00477306897301,-0.340084028707,0.000644650391207 +59.3,51.0063745331,0.00645482052652,21.7833250141,0.000494960920454,0.0022016564601,-0.000223342571372,0.0024672682295,-0.335930062874,0.000729486810602 +59.31,51.0063745331,0.00645482071376,21.783318154,0.000173802472819,0.000426826983602,0.00159537603922,0.00169809139426,-0.332778680209,0.000345631958889 +59.32,51.006374533,0.00645482075761,21.7833166204,-0.00164083412547,0.000188779090424,-0.00128865377045,0.00173088499861,-0.326664256291,0.00144595509888 +59.33,51.006374533,0.00645482087728,21.7833249287,0.00051800383741,0.0014910058186,-0.000373006121122,0.002808468822,-0.323443218721,0.00124286453891 +59.34,51.0063745329,0.00645482109308,21.7833299693,-0.00150997812281,0.00153840065225,-0.000635122113073,0.000264921318707,-0.31925238224,0.0010062346649 +59.35,51.0063745328,0.00645482127651,21.7833298582,-0.00192550602166,0.00103645547924,0.000657344924104,0.000887732633408,-0.315785665781,0.000525969174467 +59.36,51.0063745326,0.00645482142886,21.7833289649,-0.00133759539507,0.001102177788,-0.000478677081846,0.00165215418838,-0.311894618622,0.00087367355545 +59.37,51.0063745325,0.00645482143921,21.7833465635,-0.00160665045496,-0.000956790319313,-0.00304106112442,0.00118496750164,-0.307367730857,0.00101744219356 +59.38,51.0063745324,0.0064548213666,21.7833668865,-0.000918175654767,-6.25846295704e-005,-0.00102353466321,0.00257566605966,-0.302258398238,0.000967002650453 +59.39,51.0063745323,0.0064548214681,21.7833753094,-0.00141567669515,0.00148738820868,-0.000661038746539,0.00251594019255,-0.300211037817,-0.00127871926305 +59.4,51.0063745321,0.006454821681,21.7833781662,-0.00125080422338,0.00150133325008,8.96750466692e-005,0.0023758109802,-0.297370347099,-0.000277471110107 +59.41,51.0063745321,0.00645482182032,21.7833837752,0.000466528116822,0.000454389373335,-0.00121147401037,0.00108107137517,-0.291487647421,-0.0014223173652 +59.42,51.0063745321,0.0064548220233,21.7833895493,-0.000508517548706,0.00239498694562,5.66546245211e-005,0.000570929860682,-0.288901766547,-0.000137768000892 +59.43,51.0063745321,0.00645482228476,21.7833955901,-0.000533364837463,0.00127522921099,-0.00126480879225,0.0013459611327,-0.285184447965,0.000513362897404 +59.44,51.006374532,0.00645482248509,21.7833960872,-0.000307029752049,0.00153693771839,0.00116538947923,0.00199323254467,-0.280185676434,0.00122904329145 +59.45,51.006374532,0.00645482276237,21.783380745,-8.84403894348e-005,0.00235536963205,0.00190304019359,0.00189884536707,-0.276733216508,0.000455498334122 +59.46,51.006374532,0.00645482317409,21.7833634075,-0.000111567224277,0.00342434566986,0.00156445966929,0.002553434719,-0.271937000626,0.00118025456578 +59.47,51.006374532,0.00645482358547,21.7833481484,-0.00094284604003,0.00235039626511,0.00148737400333,0.00182415493698,-0.267826601613,-0.000172854061466 +59.48,51.0063745319,0.00645482391051,21.7833338873,-0.000409344761645,0.00221243181256,0.00136482691341,0.000252158189859,-0.26542242333,0.000509836264734 +59.49,51.0063745319,0.00645482423757,21.7833249141,-0.000379467424215,0.00237865981414,0.000429813296884,-0.000891045515641,-0.261204411994,0.00232837794834 +59.5,51.0063745318,0.00645482460207,21.7833165206,-0.000625836003744,0.00273813943147,0.00124890474715,5.47126294926e-005,-0.255898434139,0.0022619033815 +59.51,51.0063745317,0.00645482494581,21.7832978517,-0.00131310161062,0.00208719223265,0.00248485879828,-0.00184889455839,-0.252412597548,0.00231470669356 +59.52,51.0063745316,0.00645482517594,21.7832847756,-0.000589429408264,0.00114327648968,0.000130367868201,0.000672036890483,-0.249881513007,0.000303142062453 +59.53,51.0063745316,0.0064548254629,21.7832846475,-0.000276026713656,0.00288499682715,-0.000104750041528,-0.00162031608391,-0.248771975527,0.000983454323887 +59.54,51.0063745315,0.00645482588286,21.7832794618,-0.00132028292743,0.00301022084268,0.0011418997491,-0.000784370461624,-0.24533552556,0.000665599601782 +59.55,51.0063745314,0.00645482625877,21.7832723969,-0.000893122480072,0.0022666013167,0.000271077415039,-0.00213226669467,-0.237664675181,-0.000349781377832 +59.56,51.0063745314,0.00645482655754,21.7832668952,7.28392905756e-005,0.00192750061975,0.000829254495559,-9.29963264167e-005,-0.234618076654,0.000145191276011 +59.57,51.0063745313,0.00645482681461,21.7832625441,-0.00127666106634,0.00168106619774,4.09706827559e-005,0.000674579173174,-0.229977980274,0.00167196506799 +59.58,51.0063745313,0.0064548271324,21.7832617806,7.6087731654e-005,0.00278006408136,0.00011173193463,-0.00192172852155,-0.227748311696,0.00100937013337 +59.59,51.0063745314,0.00645482740744,21.7832609082,0.00194958556637,0.00108080103092,6.27427861556e-005,-0.000375426467202,-0.222554842836,0.00227918275994 +59.6,51.0063745315,0.0064548275395,21.7832650222,0.00106973200321,0.000772995234272,-0.000885545339718,0.000651986109012,-0.218066983167,0.00104338071788 +59.61,51.0063745317,0.00645482766228,21.7832699703,0.0021315365254,0.000950632686816,-0.000104079423625,0.00162605628226,-0.213235131757,0.000599980087684 +59.62,51.0063745318,0.00645482781163,21.7832771326,0.000470975950223,0.00114589443363,-0.00132836203592,-0.000961290803863,-0.208835873418,0.000330674310542 +59.63,51.0063745317,0.0064548281533,21.7832914746,-0.00102003469924,0.00365027093314,-0.00154004945495,-0.000585798346782,-0.203515650529,0.000346578099996 +59.64,51.0063745317,0.00645482856894,21.7833035534,-0.000262786026067,0.00218440847192,-0.000875703568355,-0.000344717561865,-0.201226183548,0.00108125488475 +59.65,51.0063745316,0.00645482887616,21.7833131919,-0.00146149019246,0.00212826040689,-0.00105199892326,-0.00362171966963,-0.197389890362,0.00157581466548 +59.66,51.0063745315,0.00645482906719,21.7833151707,-0.00179989686283,0.000553268933908,0.000656240946763,-0.00206378263567,-0.194314290969,0.00133505801793 +59.67,51.0063745313,0.00645482901398,21.7833058565,-0.00206786715754,-0.00130016906133,0.00120658736746,-0.00293591459081,-0.190266893477,0.00121030395204 +59.68,51.0063745312,0.00645482903722,21.7832997253,0.000507768943782,0.0016263419012,1.96666991195e-005,-0.00226785289242,-0.186569461784,0.00130606199438 +59.69,51.0063745314,0.00645482933236,21.7832973585,0.00237971758146,0.00251682476618,0.000453689466776,-0.00252261963339,-0.182580877019,0.00233902900515 +59.7,51.0063745315,0.00645482970511,21.7832901543,0.00175626867299,0.00271566423659,0.000987150354459,-0.0011891994041,-0.179109626838,0.000392213461007 +59.71,51.0063745316,0.00645483002774,21.7832876516,-0.000412053840425,0.00181326453165,-0.000486612464516,-0.000658212308951,-0.173413281673,0.00163271526585 +59.72,51.0063745317,0.00645483018606,21.7832800836,0.00185355030139,0.000409220536109,0.00200020206544,-0.00213047633066,-0.169177755582,0.000661543683212 +59.73,51.0063745319,0.00645483014569,21.7832572162,0.00240807731137,-0.000975873152964,0.00257329369749,-0.00296373821233,-0.163802784362,0.000567183409505 +59.74,51.006374532,0.00645483005982,21.7832411556,0.000748860373325,-0.0002295458675,0.000638825297643,-0.00309399649535,-0.162386871268,0.000101414374188 +59.75,51.006374532,0.00645483016593,21.7832285346,-9.75600816922e-005,0.00171908638463,0.0018853725491,-0.00400827950033,-0.157726753861,0.000642521680102 +59.76,51.0063745321,0.00645483026308,21.7832134479,0.000918472690306,-0.000355327291087,0.00113197394609,-0.0040441766299,-0.154596551196,0.000663982663366 +59.77,51.0063745321,0.00645483012051,21.7832084242,0.000752792888045,-0.00164608192674,-0.000127237447206,-0.00283777311766,-0.150037242501,0.00059830679596 +59.78,51.0063745322,0.00645483004965,21.7832050849,0.00148540287562,0.000651401239464,0.000795087094766,-0.00212868780601,-0.144403820523,0.000230475806551 +59.79,51.0063745323,0.00645483023221,21.7831945627,0.000398950639671,0.00191127393423,0.00130935849473,-0.00113249234434,-0.142960206333,-0.00205132304117 +59.8,51.0063745324,0.00645483049904,21.7831834454,0.00129422640704,0.0018343909207,0.000914108131847,0.000781861813081,-0.138742319123,-0.000777025634523 +59.81,51.0063745325,0.00645483080086,21.7831773039,0.000656910466666,0.00240243314998,0.000314193253824,0.002412826305,-0.136102280538,7.98030533555e-005 +59.82,51.0063745325,0.00645483104385,21.7831781147,-0.000164143034022,0.00100868745055,-0.000476355240851,0.00135980188932,-0.131487600383,-0.00189022462093 +59.83,51.0063745325,0.00645483120442,21.7831795322,-0.000169280879624,0.00124524303482,0.000192849021385,0.00011174077171,-0.127670355197,-0.00342428432601 +59.84,51.0063745325,0.00645483134611,21.7831814219,0.000469643637236,0.000743726070599,-0.000570794610462,0.000638121782063,-0.124301345366,-0.000219139220679 +59.85,51.0063745325,0.00645483141589,21.7831856735,-0.000156949443862,0.000235891160738,-0.000279520782504,0.00213063323885,-0.12048134348,-0.00144618014323 +59.86,51.0063745326,0.00645483144624,21.7831984224,0.0011470405216,0.000190118614239,-0.00227025982196,0.00201401198369,-0.115821351265,-0.000857756376179 +59.87,51.0063745327,0.00645483149342,21.7832096387,0.00268786927579,0.00047216482951,2.70071439496e-005,0.000805575423613,-0.109844045459,-0.00119259628931 +59.88,51.0063745329,0.00645483140868,21.7832095007,0.00121125968583,-0.00166166994563,5.77858488479e-007,-0.000469731719955,-0.107755347597,-0.00029608020807 +59.89,51.006374533,0.00645483120255,21.7832168472,0.00176034483145,-0.00123192252682,-0.00146987873222,-0.00042827104269,-0.102783187278,0.000884111901099 +59.9,51.0063745333,0.00645483104992,21.7832345708,0.00365287543429,-0.000910691257626,-0.00207483436164,-0.00244795821259,-0.0990349147499,-0.000294842096951 +59.91,51.0063745336,0.00645483097487,21.7832477424,0.0034754232182,-0.000142781793922,-0.000559473567833,-0.00247120554082,-0.0934417559021,-0.00013070783254 +59.92,51.0063745339,0.00645483091943,21.7832584538,0.00219112999511,-0.00063547778555,-0.00158282589376,0.000262947591495,-0.0926830374002,0.000643760959553 +59.93,51.0063745341,0.00645483087113,21.7832769099,0.00213873514717,-4.24628356841e-005,-0.00210839034429,0.00105606633041,-0.0860436065037,-0.000137210175258 +59.94,51.0063745343,0.00645483077235,21.783296064,0.00277894767019,-0.0013442665535,-0.00172241987941,0.000336655918506,-0.0841895648496,-0.00046205584649 +59.95,51.0063745345,0.00645483050886,21.7833043765,0.00133368962352,-0.00235444133636,5.99239921016e-005,0.00315100459529,-0.0792778872531,-0.00100888067347 +59.96,51.0063745346,0.00645483032278,21.7833067208,0.0016295042961,-0.000257750798646,-0.00052879030614,0.00104617837319,-0.0781775959073,-0.000154117666398 +59.97,51.0063745347,0.00645483023094,21.7833057889,-4.96726608112e-005,-0.00103150260732,0.00071517814557,0.00108815920659,-0.0731289791796,-9.41422631137e-005 +59.98,51.0063745348,0.00645483019311,21.7833003235,0.0019377374823,0.000500440721801,0.000377891250999,0.00202078406496,-0.0691252859662,0.000386667133293 +59.99,51.006374535,0.0064548301213,21.7832964402,0.00246133176529,-0.00150847037631,0.000398771577316,0.000650547362091,-0.0655353375492,-0.00110932115482 +60,51.0063745351,0.00645482995856,21.7833015203,0.00169522948194,-0.000776029355588,-0.00141478916574,-0.000172938131499,-0.0628102057084,0.00119690891189 \ No newline at end of file diff --git a/Profile_2.csv b/Profile_2.csv new file mode 100644 index 0000000..6eef555 --- /dev/null +++ b/Profile_2.csv @@ -0,0 +1,17501 @@ +0,50.425,-3.5958333,50,0,10,0,0,0,90.00000001 +0.01,50.425,-3.595831893,50,0,9.999262536,0,0,0,90.00000001 +0.02,50.425,-3.595830486,50,0,9.999671048,0,0,0,90.00000001 +0.03,50.425,-3.595829079,50,0,10.00090751,0,0,0,90.00000001 +0.04,50.425,-3.595827671,50,0,10.00179579,0,0,0,90.00000001 +0.05,50.425,-3.595826264,50,0,10.00179579,0,0,0,90.00000001 +0.06,50.425,-3.595824856,50,0,10.00090751,0,0,0,90.00000001 +0.07,50.425,-3.595823449,50,0,9.999575096,0,0,0,90.00000001 +0.08,50.425,-3.595822042,50,0,9.998686816,0,0,0,90.00000001 +0.09,50.425,-3.595820635,50,0,9.998686816,0,0,0,90.00000001 +0.1,50.425,-3.595819228,50,0,9.999575096,0,0,0,90.00000001 +0.11,50.425,-3.595817821,50,0,10.00068544,0,0,0,90.00000001 +0.12,50.425,-3.595816413,50,0,10.00068544,0,0,0,90.00000001 +0.13,50.425,-3.595815006,50,0,9.999575095,0,0,0,90.00000001 +0.14,50.425,-3.595813599,50,0,9.998908887,0,0,0,90.00000001 +0.15,50.425,-3.595812192,50,0,9.999575096,0,0,0,90.00000001 +0.16,50.425,-3.595810785,50,0,10.00068544,0,0,0,90.00000001 +0.17,50.425,-3.595809377,50,0,10.00068544,0,0,0,90.00000001 +0.18,50.425,-3.59580797,50,0,9.999575096,0,0,0,90.00000001 +0.19,50.425,-3.595806563,50,0,9.998908887,0,0,0,90.00000001 +0.2,50.425,-3.595805156,50,0,9.999575095,0,0,0,90.00000001 +0.21,50.425,-3.595803749,50,0,10.00068544,0,0,0,90.00000001 +0.22,50.425,-3.595802341,50,0,10.00090751,0,0,0,90.00000001 +0.23,50.425,-3.595800934,50,0,10.00068544,0,0,0,90.00000001 +0.24,50.425,-3.595799527,50,0,10.00090751,0,0,0,90.00000001 +0.25,50.425,-3.595798119,50,0,10.00068544,0,0,0,90.00000001 +0.26,50.425,-3.595796712,50,0,9.999575095,0,0,0,90.00000001 +0.27,50.425,-3.595795305,50,0,9.998908885,0,0,0,90.00000001 +0.28,50.425,-3.595793898,50,0,9.999575095,0,0,0,90.00000001 +0.29,50.425,-3.595792491,50,0,10.00068544,0,0,0,90.00000001 +0.3,50.425,-3.595791083,50,0,10.00068544,0,0,0,90.00000001 +0.31,50.425,-3.595789676,50,0,9.999575095,0,0,0,90.00000001 +0.32,50.425,-3.595788269,50,0,9.998686816,0,0,0,90.00000001 +0.33,50.425,-3.595786862,50,0,9.998686816,0,0,0,90.00000001 +0.34,50.425,-3.595785455,50,0,9.999575096,0,0,0,90.00000001 +0.35,50.425,-3.595784048,50,0,10.00068544,0,0,0,90.00000001 +0.36,50.425,-3.59578264,50,0,10.00068544,0,0,0,90.00000001 +0.37,50.425,-3.595781233,50,0,9.999575096,0,0,0,90.00000001 +0.38,50.425,-3.595779826,50,0,9.998908886,0,0,0,90.00000001 +0.39,50.425,-3.595778419,50,0,9.999575095,0,0,0,90.00000001 +0.4,50.425,-3.595777012,50,0,10.00090751,0,0,0,90.00000001 +0.41,50.425,-3.595775604,50,0,10.00179579,0,0,0,90.00000001 +0.42,50.425,-3.595774197,50,0,10.00179579,0,0,0,90.00000001 +0.43,50.425,-3.595772789,50,0,10.00090751,0,0,0,90.00000001 +0.44,50.425,-3.595771382,50,0,9.999575096,0,0,0,90.00000001 +0.45,50.425,-3.595769975,50,0,9.998686818,0,0,0,90.00000001 +0.46,50.425,-3.595768568,50,0,9.998686817,0,0,0,90.00000001 +0.47,50.425,-3.595767161,50,0,9.999575095,0,0,0,90.00000001 +0.48,50.425,-3.595765754,50,0,10.00068544,0,0,0,90.00000001 +0.49,50.425,-3.595764346,50,0,10.00068544,0,0,0,90.00000001 +0.5,50.425,-3.595762939,50,0,9.999575096,0,0,0,90.00000001 +0.51,50.425,-3.595761532,50,0,9.998908886,0,0,0,90.00000001 +0.52,50.425,-3.595760125,50,0,9.999575095,0,0,0,90.00000001 +0.53,50.425,-3.595758718,50,0,10.00068544,0,0,0,90.00000001 +0.54,50.425,-3.59575731,50,0,10.00068544,0,0,0,90.00000001 +0.55,50.425,-3.595755903,50,0,9.999575095,0,0,0,90.00000001 +0.56,50.425,-3.595754496,50,0,9.998686816,0,0,0,90.00000001 +0.57,50.425,-3.595753089,50,0,9.998686817,0,0,0,90.00000001 +0.58,50.425,-3.595751682,50,0,9.999575096,0,0,0,90.00000001 +0.59,50.425,-3.595750275,50,0,10.00090751,0,0,0,90.00000001 +0.6,50.425,-3.595748867,50,0,10.00179579,0,0,0,90.00000001 +0.61,50.425,-3.59574746,50,0,10.00179579,0,0,0,90.00000001 +0.62,50.425,-3.595746052,50,0,10.00090751,0,0,0,90.00000001 +0.63,50.425,-3.595744645,50,0,9.999575096,0,0,0,90.00000001 +0.64,50.425,-3.595743238,50,0,9.998908886,0,0,0,90.00000001 +0.65,50.425,-3.595741831,50,0,9.999575095,0,0,0,90.00000001 +0.66,50.425,-3.595740424,50,0,10.00068544,0,0,0,90.00000001 +0.67,50.425,-3.595739016,50,0,10.00068544,0,0,0,90.00000001 +0.68,50.425,-3.595737609,50,0,9.999575096,0,0,0,90.00000001 +0.69,50.425,-3.595736202,50,0,9.998686816,0,0,0,90.00000001 +0.7,50.425,-3.595734795,50,0,9.998686816,0,0,0,90.00000001 +0.71,50.425,-3.595733388,50,0,9.999575095,0,0,0,90.00000001 +0.72,50.425,-3.595731981,50,0,10.00068544,0,0,0,90.00000001 +0.73,50.425,-3.595730573,50,0,10.00068544,0,0,0,90.00000001 +0.74,50.425,-3.595729166,50,0,9.999575095,0,0,0,90.00000001 +0.75,50.425,-3.595727759,50,0,9.998908886,0,0,0,90.00000001 +0.76,50.425,-3.595726352,50,0,9.999575095,0,0,0,90.00000001 +0.77,50.425,-3.595724945,50,0,10.00068544,0,0,0,90.00000001 +0.78,50.425,-3.595723537,50,0,10.00090751,0,0,0,90.00000001 +0.79,50.425,-3.59572213,50,0,10.00068544,0,0,0,90.00000001 +0.8,50.425,-3.595720723,50,0,10.00090751,0,0,0,90.00000001 +0.81,50.425,-3.595719315,50,0,10.00068544,0,0,0,90.00000001 +0.82,50.425,-3.595717908,50,0,9.999575095,0,0,0,90.00000001 +0.83,50.425,-3.595716501,50,0,9.998908887,0,0,0,90.00000001 +0.84,50.425,-3.595715094,50,0,9.999575096,0,0,0,90.00000001 +0.85,50.425,-3.595713687,50,0,10.00068544,0,0,0,90.00000001 +0.86,50.425,-3.595712279,50,0,10.00068544,0,0,0,90.00000001 +0.87,50.425,-3.595710872,50,0,9.999575095,0,0,0,90.00000001 +0.88,50.425,-3.595709465,50,0,9.998908887,0,0,0,90.00000001 +0.89,50.425,-3.595708058,50,0,9.999575096,0,0,0,90.00000001 +0.9,50.425,-3.595706651,50,0,10.00068544,0,0,0,90.00000001 +0.91,50.425,-3.595705243,50,0,10.00068544,0,0,0,90.00000001 +0.92,50.425,-3.595703836,50,0,9.999575095,0,0,0,90.00000001 +0.93,50.425,-3.595702429,50,0,9.998908886,0,0,0,90.00000001 +0.94,50.425,-3.595701022,50,0,9.999575095,0,0,0,90.00000001 +0.95,50.425,-3.595699615,50,0,10.00068544,0,0,0,90.00000001 +0.96,50.425,-3.595698207,50,0,10.00090751,0,0,0,90.00000001 +0.97,50.425,-3.5956968,50,0,10.00068544,0,0,0,90.00000001 +0.98,50.425,-3.595695393,50,0,10.00090751,0,0,0,90.00000001 +0.99,50.425,-3.595693985,50,0,10.00068544,0,0,0,90.00000001 +1,50.425,-3.595692578,50,0,9.999575095,0,0,0,90.00000001 +1.01,50.425,-3.595691171,50,0,9.998686816,0,0,0,90.00000001 +1.02,50.425,-3.595689764,50,0,9.998686816,0,0,0,90.00000001 +1.03,50.425,-3.595688357,50,0,9.999575095,0,0,0,90.00000001 +1.04,50.425,-3.59568695,50,0,10.00068544,0,0,0,90.00000001 +1.05,50.425,-3.595685542,50,0,10.00068544,0,0,0,90.00000001 +1.06,50.425,-3.595684135,50,0,9.999575096,0,0,0,90.00000001 +1.07,50.425,-3.595682728,50,0,9.998908887,0,0,0,90.00000001 +1.08,50.425,-3.595681321,50,0,9.999575095,0,0,0,90.00000001 +1.09,50.425,-3.595679914,50,0,10.00068544,0,0,0,90.00000001 +1.1,50.425,-3.595678506,50,0,10.00068544,0,0,0,90.00000001 +1.11,50.425,-3.595677099,50,0,9.999797165,0,0,0,90.00000001 +1.12,50.425,-3.595675692,50,0,9.999797165,0,0,0,90.00000001 +1.13,50.425,-3.595674285,50,0,10.00068544,0,0,0,90.00000001 +1.14,50.425,-3.595672877,50,0,10.00068544,0,0,0,90.00000001 +1.15,50.425,-3.59567147,50,0,9.999797165,0,0,0,90.00000001 +1.16,50.425,-3.595670063,50,0,9.999797165,0,0,0,90.00000001 +1.17,50.425,-3.595668656,50,0,10.00068544,0,0,0,90.00000001 +1.18,50.425,-3.595667248,50,0,10.00068544,0,0,0,90.00000001 +1.19,50.425,-3.595665841,50,0,9.999575095,0,0,0,90.00000001 +1.2,50.425,-3.595664434,50,0,9.998908885,0,0,0,90.00000001 +1.21,50.425,-3.595663027,50,0,9.999575095,0,0,0,90.00000001 +1.22,50.425,-3.59566162,50,0,10.00068544,0,0,0,90.00000001 +1.23,50.425,-3.595660212,50,0,10.00068544,0,0,0,90.00000001 +1.24,50.425,-3.595658805,50,0,9.999575095,0,0,0,90.00000001 +1.25,50.425,-3.595657398,50,0,9.998686816,0,0,0,90.00000001 +1.26,50.425,-3.595655991,50,0,9.998686817,0,0,0,90.00000001 +1.27,50.425,-3.595654584,50,0,9.999575096,0,0,0,90.00000001 +1.28,50.425,-3.595653177,50,0,10.00068544,0,0,0,90.00000001 +1.29,50.425,-3.595651769,50,0,10.00090751,0,0,0,90.00000001 +1.3,50.425,-3.595650362,50,0,10.00068544,0,0,0,90.00000001 +1.31,50.425,-3.595648955,50,0,10.00090751,0,0,0,90.00000001 +1.32,50.425,-3.595647547,50,0,10.00068544,0,0,0,90.00000001 +1.33,50.425,-3.59564614,50,0,9.999797166,0,0,0,90.00000001 +1.34,50.425,-3.595644733,50,0,9.999797165,0,0,0,90.00000001 +1.35,50.425,-3.595643326,50,0,10.00068544,0,0,0,90.00000001 +1.36,50.425,-3.595641918,50,0,10.00068544,0,0,0,90.00000001 +1.37,50.425,-3.595640511,50,0,9.999575096,0,0,0,90.00000001 +1.38,50.425,-3.595639104,50,0,9.998686817,0,0,0,90.00000001 +1.39,50.425,-3.595637697,50,0,9.998686816,0,0,0,90.00000001 +1.4,50.425,-3.59563629,50,0,9.999575095,0,0,0,90.00000001 +1.41,50.425,-3.595634883,50,0,10.00068544,0,0,0,90.00000001 +1.42,50.425,-3.595633475,50,0,10.00068544,0,0,0,90.00000001 +1.43,50.425,-3.595632068,50,0,9.999575095,0,0,0,90.00000001 +1.44,50.425,-3.595630661,50,0,9.998908886,0,0,0,90.00000001 +1.45,50.425,-3.595629254,50,0,9.999575096,0,0,0,90.00000001 +1.46,50.425,-3.595627847,50,0,10.00068544,0,0,0,90.00000001 +1.47,50.425,-3.595626439,50,0,10.00090751,0,0,0,90.00000001 +1.48,50.425,-3.595625032,50,0,10.00068544,0,0,0,90.00000001 +1.49,50.425,-3.595623625,50,0,10.00090751,0,0,0,90.00000001 +1.5,50.425,-3.595622217,50,0,10.00068544,0,0,0,90.00000001 +1.51,50.425,-3.59562081,50,0,9.999575095,0,0,0,90.00000001 +1.52,50.425,-3.595619403,50,0,9.998908886,0,0,0,90.00000001 +1.53,50.425,-3.595617996,50,0,9.999575096,0,0,0,90.00000001 +1.54,50.425,-3.595616589,50,0,10.00068544,0,0,0,90.00000001 +1.55,50.425,-3.595615181,50,0,10.00068544,0,0,0,90.00000001 +1.56,50.425,-3.595613774,50,0,9.999575095,0,0,0,90.00000001 +1.57,50.425,-3.595612367,50,0,9.998908886,0,0,0,90.00000001 +1.58,50.425,-3.59561096,50,0,9.999575096,0,0,0,90.00000001 +1.59,50.425,-3.595609553,50,0,10.00068544,0,0,0,90.00000001 +1.6,50.425,-3.595608145,50,0,10.00068544,0,0,0,90.00000001 +1.61,50.425,-3.595606738,50,0,9.999575095,0,0,0,90.00000001 +1.62,50.425,-3.595605331,50,0,9.998686816,0,0,0,90.00000001 +1.63,50.425,-3.595603924,50,0,9.998686816,0,0,0,90.00000001 +1.64,50.425,-3.595602517,50,0,9.999575095,0,0,0,90.00000001 +1.65,50.425,-3.59560111,50,0,10.00090751,0,0,0,90.00000001 +1.66,50.425,-3.595599702,50,0,10.00179579,0,0,0,90.00000001 +1.67,50.425,-3.595598295,50,0,10.00179579,0,0,0,90.00000001 +1.68,50.425,-3.595596887,50,0,10.00090751,0,0,0,90.00000001 +1.69,50.425,-3.59559548,50,0,9.999575095,0,0,0,90.00000001 +1.7,50.425,-3.595594073,50,0,9.998686816,0,0,0,90.00000001 +1.71,50.425,-3.595592666,50,0,9.998686817,0,0,0,90.00000001 +1.72,50.425,-3.595591259,50,0,9.999575096,0,0,0,90.00000001 +1.73,50.425,-3.595589852,50,0,10.00068544,0,0,0,90.00000001 +1.74,50.425,-3.595588444,50,0,10.00068544,0,0,0,90.00000001 +1.75,50.425,-3.595587037,50,0,9.999575096,0,0,0,90.00000001 +1.76,50.425,-3.59558563,50,0,9.998908887,0,0,0,90.00000001 +1.77,50.425,-3.595584223,50,0,9.999575096,0,0,0,90.00000001 +1.78,50.425,-3.595582816,50,0,10.00068544,0,0,0,90.00000001 +1.79,50.425,-3.595581408,50,0,10.00068544,0,0,0,90.00000001 +1.8,50.425,-3.595580001,50,0,9.999575096,0,0,0,90.00000001 +1.81,50.425,-3.595578594,50,0,9.998908887,0,0,0,90.00000001 +1.82,50.425,-3.595577187,50,0,9.999575095,0,0,0,90.00000001 +1.83,50.425,-3.59557578,50,0,10.00068544,0,0,0,90.00000001 +1.84,50.425,-3.595574372,50,0,10.00090751,0,0,0,90.00000001 +1.85,50.425,-3.595572965,50,0,10.00068544,0,0,0,90.00000001 +1.86,50.425,-3.595571558,50,0,10.00090751,0,0,0,90.00000001 +1.87,50.425,-3.59557015,50,0,10.00068544,0,0,0,90.00000001 +1.88,50.425,-3.595568743,50,0,9.999575095,0,0,0,90.00000001 +1.89,50.425,-3.595567336,50,0,9.998908886,0,0,0,90.00000001 +1.9,50.425,-3.595565929,50,0,9.999575095,0,0,0,90.00000001 +1.91,50.425,-3.595564522,50,0,10.00068544,0,0,0,90.00000001 +1.92,50.425,-3.595563114,50,0,10.00068544,0,0,0,90.00000001 +1.93,50.425,-3.595561707,50,0,9.999575096,0,0,0,90.00000001 +1.94,50.425,-3.5955603,50,0,9.998686816,0,0,0,90.00000001 +1.95,50.425,-3.595558893,50,0,9.998686816,0,0,0,90.00000001 +1.96,50.425,-3.595557486,50,0,9.999575096,0,0,0,90.00000001 +1.97,50.425,-3.595556079,50,0,10.00068544,0,0,0,90.00000001 +1.98,50.425,-3.595554671,50,0,10.00068544,0,0,0,90.00000001 +1.99,50.425,-3.595553264,50,0,9.999575096,0,0,0,90.00000001 +2,50.425,-3.595551857,50,0,9.998908886,0,0,0,90.00000001 +2.01,50.425,-3.59555045,50,0,9.999575095,0,0,0,90.00000001 +2.02,50.425,-3.595549043,50,0,10.00090751,0,0,0,90.00000001 +2.03,50.425,-3.595547635,50,0,10.00179579,0,0,0,90.00000001 +2.04,50.425,-3.595546228,50,0,10.00179579,0,0,0,90.00000001 +2.05,50.425,-3.59554482,50,0,10.00090751,0,0,0,90.00000001 +2.06,50.425,-3.595543413,50,0,9.999575096,0,0,0,90.00000001 +2.07,50.425,-3.595542006,50,0,9.998686817,0,0,0,90.00000001 +2.08,50.425,-3.595540599,50,0,9.998686816,0,0,0,90.00000001 +2.09,50.425,-3.595539192,50,0,9.999575095,0,0,0,90.00000001 +2.1,50.425,-3.595537785,50,0,10.00068544,0,0,0,90.00000001 +2.11,50.425,-3.595536377,50,0,10.00068544,0,0,0,90.00000001 +2.12,50.425,-3.59553497,50,0,9.999575095,0,0,0,90.00000001 +2.13,50.425,-3.595533563,50,0,9.998908886,0,0,0,90.00000001 +2.14,50.425,-3.595532156,50,0,9.999575096,0,0,0,90.00000001 +2.15,50.425,-3.595530749,50,0,10.00068544,0,0,0,90.00000001 +2.16,50.425,-3.595529341,50,0,10.00068544,0,0,0,90.00000001 +2.17,50.425,-3.595527934,50,0,9.999575095,0,0,0,90.00000001 +2.18,50.425,-3.595526527,50,0,9.998686817,0,0,0,90.00000001 +2.19,50.425,-3.59552512,50,0,9.998686818,0,0,0,90.00000001 +2.2,50.425,-3.595523713,50,0,9.999575096,0,0,0,90.00000001 +2.21,50.425,-3.595522306,50,0,10.00090751,0,0,0,90.00000001 +2.22,50.425,-3.595520898,50,0,10.00179579,0,0,0,90.00000001 +2.23,50.425,-3.595519491,50,0,10.00179579,0,0,0,90.00000001 +2.24,50.425,-3.595518083,50,0,10.00090751,0,0,0,90.00000001 +2.25,50.425,-3.595516676,50,0,9.999575097,0,0,0,90.00000001 +2.26,50.425,-3.595515269,50,0,9.998908887,0,0,0,90.00000001 +2.27,50.425,-3.595513862,50,0,9.999575095,0,0,0,90.00000001 +2.28,50.425,-3.595512455,50,0,10.00068544,0,0,0,90.00000001 +2.29,50.425,-3.595511047,50,0,10.00068544,0,0,0,90.00000001 +2.3,50.425,-3.59550964,50,0,9.999575096,0,0,0,90.00000001 +2.31,50.425,-3.595508233,50,0,9.998686816,0,0,0,90.00000001 +2.32,50.425,-3.595506826,50,0,9.998686816,0,0,0,90.00000001 +2.33,50.425,-3.595505419,50,0,9.999575095,0,0,0,90.00000001 +2.34,50.425,-3.595504012,50,0,10.00068544,0,0,0,90.00000001 +2.35,50.425,-3.595502604,50,0,10.00068544,0,0,0,90.00000001 +2.36,50.425,-3.595501197,50,0,9.999575095,0,0,0,90.00000001 +2.37,50.425,-3.59549979,50,0,9.998908886,0,0,0,90.00000001 +2.38,50.425,-3.595498383,50,0,9.999575095,0,0,0,90.00000001 +2.39,50.425,-3.595496976,50,0,10.00090751,0,0,0,90.00000001 +2.4,50.425,-3.595495568,50,0,10.00179579,0,0,0,90.00000001 +2.41,50.425,-3.595494161,50,0,10.00179579,0,0,0,90.00000001 +2.42,50.425,-3.595492753,50,0,10.00090751,0,0,0,90.00000001 +2.43,50.425,-3.595491346,50,0,9.999575095,0,0,0,90.00000001 +2.44,50.425,-3.595489939,50,0,9.998686817,0,0,0,90.00000001 +2.45,50.425,-3.595488532,50,0,9.998686818,0,0,0,90.00000001 +2.46,50.425,-3.595487125,50,0,9.999575097,0,0,0,90.00000001 +2.47,50.425,-3.595485718,50,0,10.00068544,0,0,0,90.00000001 +2.48,50.425,-3.59548431,50,0,10.00068544,0,0,0,90.00000001 +2.49,50.425,-3.595482903,50,0,9.999575095,0,0,0,90.00000001 +2.5,50.425,-3.595481496,50,0,9.998908886,0,0,0,90.00000001 +2.51,50.425,-3.595480089,50,0,9.999575095,0,0,0,90.00000001 +2.52,50.425,-3.595478682,50,0,10.00068544,0,0,0,90.00000001 +2.53,50.425,-3.595477274,50,0,10.00068544,0,0,0,90.00000001 +2.54,50.425,-3.595475867,50,0,9.999575095,0,0,0,90.00000001 +2.55,50.425,-3.59547446,50,0,9.998686816,0,0,0,90.00000001 +2.56,50.425,-3.595473053,50,0,9.998686816,0,0,0,90.00000001 +2.57,50.425,-3.595471646,50,0,9.999575096,0,0,0,90.00000001 +2.58,50.425,-3.595470239,50,0,10.00090751,0,0,0,90.00000001 +2.59,50.425,-3.595468831,50,0,10.00179579,0,0,0,90.00000001 +2.6,50.425,-3.595467424,50,0,10.00179579,0,0,0,90.00000001 +2.61,50.425,-3.595466016,50,0,10.00090751,0,0,0,90.00000001 +2.62,50.425,-3.595464609,50,0,9.999575096,0,0,0,90.00000001 +2.63,50.425,-3.595463202,50,0,9.998908887,0,0,0,90.00000001 +2.64,50.425,-3.595461795,50,0,9.999575096,0,0,0,90.00000001 +2.65,50.425,-3.595460388,50,0,10.00068544,0,0,0,90.00000001 +2.66,50.425,-3.59545898,50,0,10.00068544,0,0,0,90.00000001 +2.67,50.425,-3.595457573,50,0,9.999575096,0,0,0,90.00000001 +2.68,50.425,-3.595456166,50,0,9.998686818,0,0,0,90.00000001 +2.69,50.425,-3.595454759,50,0,9.998686817,0,0,0,90.00000001 +2.7,50.425,-3.595453352,50,0,9.999575095,0,0,0,90.00000001 +2.71,50.425,-3.595451945,50,0,10.00068544,0,0,0,90.00000001 +2.72,50.425,-3.595450537,50,0,10.00068544,0,0,0,90.00000001 +2.73,50.425,-3.59544913,50,0,9.999575096,0,0,0,90.00000001 +2.74,50.425,-3.595447723,50,0,9.998908886,0,0,0,90.00000001 +2.75,50.425,-3.595446316,50,0,9.999575095,0,0,0,90.00000001 +2.76,50.425,-3.595444909,50,0,10.00068544,0,0,0,90.00000001 +2.77,50.425,-3.595443501,50,0,10.00090751,0,0,0,90.00000001 +2.78,50.425,-3.595442094,50,0,10.00068544,0,0,0,90.00000001 +2.79,50.425,-3.595440687,50,0,10.00090751,0,0,0,90.00000001 +2.8,50.425,-3.595439279,50,0,10.00068544,0,0,0,90.00000001 +2.81,50.425,-3.595437872,50,0,9.999575096,0,0,0,90.00000001 +2.82,50.425,-3.595436465,50,0,9.998908886,0,0,0,90.00000001 +2.83,50.425,-3.595435058,50,0,9.999575095,0,0,0,90.00000001 +2.84,50.425,-3.595433651,50,0,10.00068544,0,0,0,90.00000001 +2.85,50.425,-3.595432243,50,0,10.00068544,0,0,0,90.00000001 +2.86,50.425,-3.595430836,50,0,9.999575095,0,0,0,90.00000001 +2.87,50.425,-3.595429429,50,0,9.998908886,0,0,0,90.00000001 +2.88,50.425,-3.595428022,50,0,9.999575096,0,0,0,90.00000001 +2.89,50.425,-3.595426615,50,0,10.00068544,0,0,0,90.00000001 +2.9,50.425,-3.595425207,50,0,10.00068544,0,0,0,90.00000001 +2.91,50.425,-3.5954238,50,0,9.999575095,0,0,0,90.00000001 +2.92,50.425,-3.595422393,50,0,9.998908886,0,0,0,90.00000001 +2.93,50.425,-3.595420986,50,0,9.999575096,0,0,0,90.00000001 +2.94,50.425,-3.595419579,50,0,10.00068544,0,0,0,90.00000001 +2.95,50.425,-3.595418171,50,0,10.00090751,0,0,0,90.00000001 +2.96,50.425,-3.595416764,50,0,10.00068544,0,0,0,90.00000001 +2.97,50.425,-3.595415357,50,0,10.00090751,0,0,0,90.00000001 +2.98,50.425,-3.595413949,50,0,10.00068544,0,0,0,90.00000001 +2.99,50.425,-3.595412542,50,0,9.999575096,0,0,0,90.00000001 +3,50.425,-3.595411135,50,0,9.998686816,0,0,0,90.00000001 +3.01,50.425,-3.595409728,50,0,9.998686816,0,0,0,90.00000001 +3.02,50.425,-3.595408321,50,0,9.999575096,0,0,0,90.00000001 +3.03,50.425,-3.595406914,50,0,10.00068544,0,0,0,90.00000001 +3.04,50.425,-3.595405506,50,0,10.00068544,0,0,0,90.00000001 +3.05,50.425,-3.595404099,50,0,9.999575095,0,0,0,90.00000001 +3.06,50.425,-3.595402692,50,0,9.998908887,0,0,0,90.00000001 +3.07,50.425,-3.595401285,50,0,9.999575096,0,0,0,90.00000001 +3.08,50.425,-3.595399878,50,0,10.00068544,0,0,0,90.00000001 +3.09,50.425,-3.59539847,50,0,10.00068544,0,0,0,90.00000001 +3.1,50.425,-3.595397063,50,0,9.999797165,0,0,0,90.00000001 +3.11,50.425,-3.595395656,50,0,9.999797166,0,0,0,90.00000001 +3.12,50.425,-3.595394249,50,0,10.00068544,0,0,0,90.00000001 +3.13,50.425,-3.595392841,50,0,10.00068544,0,0,0,90.00000001 +3.14,50.425,-3.595391434,50,0,9.999797165,0,0,0,90.00000001 +3.15,50.425,-3.595390027,50,0,9.999797165,0,0,0,90.00000001 +3.16,50.425,-3.59538862,50,0,10.00068544,0,0,0,90.00000001 +3.17,50.425,-3.595387212,50,0,10.00068544,0,0,0,90.00000001 +3.18,50.425,-3.595385805,50,0,9.999575095,0,0,0,90.00000001 +3.19,50.425,-3.595384398,50,0,9.998908886,0,0,0,90.00000001 +3.2,50.425,-3.595382991,50,0,9.999575096,0,0,0,90.00000001 +3.21,50.425,-3.595381584,50,0,10.00068544,0,0,0,90.00000001 +3.22,50.425,-3.595380176,50,0,10.00068544,0,0,0,90.00000001 +3.23,50.425,-3.595378769,50,0,9.999575095,0,0,0,90.00000001 +3.24,50.425,-3.595377362,50,0,9.998686816,0,0,0,90.00000001 +3.25,50.425,-3.595375955,50,0,9.998686816,0,0,0,90.00000001 +3.26,50.425,-3.595374548,50,0,9.999575095,0,0,0,90.00000001 +3.27,50.425,-3.595373141,50,0,10.00068544,0,0,0,90.00000001 +3.28,50.425,-3.595371733,50,0,10.00090751,0,0,0,90.00000001 +3.29,50.425,-3.595370326,50,0,10.00068544,0,0,0,90.00000001 +3.3,50.425,-3.595368919,50,0,10.00090751,0,0,0,90.00000001 +3.31,50.425,-3.595367511,50,0,10.00068544,0,0,0,90.00000001 +3.32,50.425,-3.595366104,50,0,9.999797166,0,0,0,90.00000001 +3.33,50.425,-3.595364697,50,0,9.999797165,0,0,0,90.00000001 +3.34,50.425,-3.59536329,50,0,10.00068544,0,0,0,90.00000001 +3.35,50.425,-3.595361882,50,0,10.00068544,0,0,0,90.00000001 +3.36,50.425,-3.595360475,50,0,9.999575096,0,0,0,90.00000001 +3.37,50.425,-3.595359068,50,0,9.998686818,0,0,0,90.00000001 +3.38,50.425,-3.595357661,50,0,9.998686817,0,0,0,90.00000001 +3.39,50.425,-3.595356254,50,0,9.999575095,0,0,0,90.00000001 +3.4,50.425,-3.595354847,50,0,10.00068544,0,0,0,90.00000001 +3.41,50.425,-3.595353439,50,0,10.00068544,0,0,0,90.00000001 +3.42,50.425,-3.595352032,50,0,9.999575096,0,0,0,90.00000001 +3.43,50.425,-3.595350625,50,0,9.998908886,0,0,0,90.00000001 +3.44,50.425,-3.595349218,50,0,9.999575095,0,0,0,90.00000001 +3.45,50.425,-3.595347811,50,0,10.00068544,0,0,0,90.00000001 +3.46,50.425,-3.595346403,50,0,10.00090751,0,0,0,90.00000001 +3.47,50.425,-3.595344996,50,0,10.00068544,0,0,0,90.00000001 +3.48,50.425,-3.595343589,50,0,10.00090751,0,0,0,90.00000001 +3.49,50.425,-3.595342181,50,0,10.00068544,0,0,0,90.00000001 +3.5,50.425,-3.595340774,50,0,9.999575095,0,0,0,90.00000001 +3.51,50.425,-3.595339367,50,0,9.998908885,0,0,0,90.00000001 +3.52,50.425,-3.59533796,50,0,9.999575095,0,0,0,90.00000001 +3.53,50.425,-3.595336553,50,0,10.00068544,0,0,0,90.00000001 +3.54,50.425,-3.595335145,50,0,10.00068544,0,0,0,90.00000001 +3.55,50.425,-3.595333738,50,0,9.999575096,0,0,0,90.00000001 +3.56,50.425,-3.595332331,50,0,9.998908886,0,0,0,90.00000001 +3.57,50.425,-3.595330924,50,0,9.999575095,0,0,0,90.00000001 +3.58,50.425,-3.595329517,50,0,10.00068544,0,0,0,90.00000001 +3.59,50.425,-3.595328109,50,0,10.00068544,0,0,0,90.00000001 +3.6,50.425,-3.595326702,50,0,9.999575096,0,0,0,90.00000001 +3.61,50.425,-3.595325295,50,0,9.998686817,0,0,0,90.00000001 +3.62,50.425,-3.595323888,50,0,9.998686816,0,0,0,90.00000001 +3.63,50.425,-3.595322481,50,0,9.999575095,0,0,0,90.00000001 +3.64,50.425,-3.595321074,50,0,10.00090751,0,0,0,90.00000001 +3.65,50.425,-3.595319666,50,0,10.00179579,0,0,0,90.00000001 +3.66,50.425,-3.595318259,50,0,10.00179579,0,0,0,90.00000001 +3.67,50.425,-3.595316851,50,0,10.00090751,0,0,0,90.00000001 +3.68,50.425,-3.595315444,50,0,9.999575095,0,0,0,90.00000001 +3.69,50.425,-3.595314037,50,0,9.998686816,0,0,0,90.00000001 +3.7,50.425,-3.59531263,50,0,9.998686816,0,0,0,90.00000001 +3.71,50.425,-3.595311223,50,0,9.999575096,0,0,0,90.00000001 +3.72,50.425,-3.595309816,50,0,10.00068544,0,0,0,90.00000001 +3.73,50.425,-3.595308408,50,0,10.00068544,0,0,0,90.00000001 +3.74,50.425,-3.595307001,50,0,9.999575095,0,0,0,90.00000001 +3.75,50.425,-3.595305594,50,0,9.998908887,0,0,0,90.00000001 +3.76,50.425,-3.595304187,50,0,9.999575096,0,0,0,90.00000001 +3.77,50.425,-3.59530278,50,0,10.00068544,0,0,0,90.00000001 +3.78,50.425,-3.595301372,50,0,10.00068544,0,0,0,90.00000001 +3.79,50.425,-3.595299965,50,0,9.999575096,0,0,0,90.00000001 +3.8,50.425,-3.595298558,50,0,9.998908888,0,0,0,90.00000001 +3.81,50.425,-3.595297151,50,0,9.999575097,0,0,0,90.00000001 +3.82,50.425,-3.595295744,50,0,10.00068544,0,0,0,90.00000001 +3.83,50.425,-3.595294336,50,0,10.00090751,0,0,0,90.00000001 +3.84,50.425,-3.595292929,50,0,10.00068544,0,0,0,90.00000001 +3.85,50.425,-3.595291522,50,0,10.00090751,0,0,0,90.00000001 +3.86,50.425,-3.595290114,50,0,10.00068544,0,0,0,90.00000001 +3.87,50.425,-3.595288707,50,0,9.999575096,0,0,0,90.00000001 +3.88,50.425,-3.5952873,50,0,9.998908886,0,0,0,90.00000001 +3.89,50.425,-3.595285893,50,0,9.999575095,0,0,0,90.00000001 +3.9,50.425,-3.595284486,50,0,10.00068544,0,0,0,90.00000001 +3.91,50.425,-3.595283078,50,0,10.00068544,0,0,0,90.00000001 +3.92,50.425,-3.595281671,50,0,9.999575095,0,0,0,90.00000001 +3.93,50.425,-3.595280264,50,0,9.998686816,0,0,0,90.00000001 +3.94,50.425,-3.595278857,50,0,9.998686816,0,0,0,90.00000001 +3.95,50.425,-3.59527745,50,0,9.999575095,0,0,0,90.00000001 +3.96,50.425,-3.595276043,50,0,10.00068544,0,0,0,90.00000001 +3.97,50.425,-3.595274635,50,0,10.00068544,0,0,0,90.00000001 +3.98,50.425,-3.595273228,50,0,9.999575097,0,0,0,90.00000001 +3.99,50.425,-3.595271821,50,0,9.998908887,0,0,0,90.00000001 +4,50.425,-3.595270414,50,0,9.999575095,0,0,0,90.00000001 +4.01,50.425,-3.595269007,50,0,10.00090751,0,0,0,90.00000001 +4.02,50.425,-3.595267599,50,0,10.00179579,0,0,0,90.00000001 +4.03,50.425,-3.595266192,50,0,10.00179579,0,0,0,90.00000001 +4.04,50.425,-3.595264784,50,0,10.00090751,0,0,0,90.00000001 +4.05,50.425,-3.595263377,50,0,9.999575095,0,0,0,90.00000001 +4.06,50.425,-3.59526197,50,0,9.998686817,0,0,0,90.00000001 +4.07,50.425,-3.595260563,50,0,9.998686818,0,0,0,90.00000001 +4.08,50.425,-3.595259156,50,0,9.999575096,0,0,0,90.00000001 +4.09,50.425,-3.595257749,50,0,10.00068544,0,0,0,90.00000001 +4.1,50.425,-3.595256341,50,0,10.00068544,0,0,0,90.00000001 +4.11,50.425,-3.595254934,50,0,9.999575095,0,0,0,90.00000001 +4.12,50.425,-3.595253527,50,0,9.998908886,0,0,0,90.00000001 +4.13,50.425,-3.59525212,50,0,9.999575095,0,0,0,90.00000001 +4.14,50.425,-3.595250713,50,0,10.00068544,0,0,0,90.00000001 +4.15,50.425,-3.595249305,50,0,10.00068544,0,0,0,90.00000001 +4.16,50.425,-3.595247898,50,0,9.999575095,0,0,0,90.00000001 +4.17,50.425,-3.595246491,50,0,9.998686816,0,0,0,90.00000001 +4.18,50.425,-3.595245084,50,0,9.998686817,0,0,0,90.00000001 +4.19,50.425,-3.595243677,50,0,9.999575096,0,0,0,90.00000001 +4.2,50.425,-3.59524227,50,0,10.00090751,0,0,0,90.00000001 +4.21,50.425,-3.595240862,50,0,10.00179579,0,0,0,90.00000001 +4.22,50.425,-3.595239455,50,0,10.00179579,0,0,0,90.00000001 +4.23,50.425,-3.595238047,50,0,10.00090751,0,0,0,90.00000001 +4.24,50.425,-3.59523664,50,0,9.999575096,0,0,0,90.00000001 +4.25,50.425,-3.595235233,50,0,9.998908888,0,0,0,90.00000001 +4.26,50.425,-3.595233826,50,0,9.999575096,0,0,0,90.00000001 +4.27,50.425,-3.595232419,50,0,10.00068544,0,0,0,90.00000001 +4.28,50.425,-3.595231011,50,0,10.00068544,0,0,0,90.00000001 +4.29,50.425,-3.595229604,50,0,9.999575096,0,0,0,90.00000001 +4.3,50.425,-3.595228197,50,0,9.998686817,0,0,0,90.00000001 +4.31,50.425,-3.59522679,50,0,9.998686816,0,0,0,90.00000001 +4.32,50.425,-3.595225383,50,0,9.999575095,0,0,0,90.00000001 +4.33,50.425,-3.595223976,50,0,10.00068544,0,0,0,90.00000001 +4.34,50.425,-3.595222568,50,0,10.00068544,0,0,0,90.00000001 +4.35,50.425,-3.595221161,50,0,9.999575095,0,0,0,90.00000001 +4.36,50.425,-3.595219754,50,0,9.998908886,0,0,0,90.00000001 +4.37,50.425,-3.595218347,50,0,9.999575096,0,0,0,90.00000001 +4.38,50.425,-3.59521694,50,0,10.00068544,0,0,0,90.00000001 +4.39,50.425,-3.595215532,50,0,10.00090751,0,0,0,90.00000001 +4.4,50.425,-3.595214125,50,0,10.00068544,0,0,0,90.00000001 +4.41,50.425,-3.595212718,50,0,10.00090751,0,0,0,90.00000001 +4.42,50.425,-3.59521131,50,0,10.00068544,0,0,0,90.00000001 +4.43,50.425,-3.595209903,50,0,9.999575095,0,0,0,90.00000001 +4.44,50.425,-3.595208496,50,0,9.998908886,0,0,0,90.00000001 +4.45,50.425,-3.595207089,50,0,9.999575096,0,0,0,90.00000001 +4.46,50.425,-3.595205682,50,0,10.00068544,0,0,0,90.00000001 +4.47,50.425,-3.595204274,50,0,10.00068544,0,0,0,90.00000001 +4.48,50.425,-3.595202867,50,0,9.999575095,0,0,0,90.00000001 +4.49,50.425,-3.59520146,50,0,9.998908886,0,0,0,90.00000001 +4.5,50.425,-3.595200053,50,0,9.999575096,0,0,0,90.00000001 +4.51,50.425,-3.595198646,50,0,10.00068544,0,0,0,90.00000001 +4.52,50.425,-3.595197238,50,0,10.00068544,0,0,0,90.00000001 +4.53,50.425,-3.595195831,50,0,9.999575095,0,0,0,90.00000001 +4.54,50.425,-3.595194424,50,0,9.998686816,0,0,0,90.00000001 +4.55,50.425,-3.595193017,50,0,9.998686816,0,0,0,90.00000001 +4.56,50.425,-3.59519161,50,0,9.999575095,0,0,0,90.00000001 +4.57,50.425,-3.595190203,50,0,10.00090751,0,0,0,90.00000001 +4.58,50.425,-3.595188795,50,0,10.00179579,0,0,0,90.00000001 +4.59,50.425,-3.595187388,50,0,10.00179579,0,0,0,90.00000001 +4.6,50.425,-3.59518598,50,0,10.00090751,0,0,0,90.00000001 +4.61,50.425,-3.595184573,50,0,9.999575095,0,0,0,90.00000001 +4.62,50.425,-3.595183166,50,0,9.998686816,0,0,0,90.00000001 +4.63,50.425,-3.595181759,50,0,9.998686817,0,0,0,90.00000001 +4.64,50.425,-3.595180352,50,0,9.999575096,0,0,0,90.00000001 +4.65,50.425,-3.595178945,50,0,10.00068544,0,0,0,90.00000001 +4.66,50.425,-3.595177537,50,0,10.00068544,0,0,0,90.00000001 +4.67,50.425,-3.59517613,50,0,9.999575096,0,0,0,90.00000001 +4.68,50.425,-3.595174723,50,0,9.998908887,0,0,0,90.00000001 +4.69,50.425,-3.595173316,50,0,9.999575096,0,0,0,90.00000001 +4.7,50.425,-3.595171909,50,0,10.00068544,0,0,0,90.00000001 +4.71,50.425,-3.595170501,50,0,10.00068544,0,0,0,90.00000001 +4.72,50.425,-3.595169094,50,0,9.999575096,0,0,0,90.00000001 +4.73,50.425,-3.595167687,50,0,9.998908887,0,0,0,90.00000001 +4.74,50.425,-3.59516628,50,0,9.999575095,0,0,0,90.00000001 +4.75,50.425,-3.595164873,50,0,10.00068544,0,0,0,90.00000001 +4.76,50.425,-3.595163465,50,0,10.00090751,0,0,0,90.00000001 +4.77,50.425,-3.595162058,50,0,10.00068544,0,0,0,90.00000001 +4.78,50.425,-3.595160651,50,0,10.00090751,0,0,0,90.00000001 +4.79,50.425,-3.595159243,50,0,10.00068544,0,0,0,90.00000001 +4.8,50.425,-3.595157836,50,0,9.999575095,0,0,0,90.00000001 +4.81,50.425,-3.595156429,50,0,9.998908885,0,0,0,90.00000001 +4.82,50.425,-3.595155022,50,0,9.999575095,0,0,0,90.00000001 +4.83,50.425,-3.595153615,50,0,10.00068544,0,0,0,90.00000001 +4.84,50.425,-3.595152207,50,0,10.00068544,0,0,0,90.00000001 +4.85,50.425,-3.5951508,50,0,9.999575095,0,0,0,90.00000001 +4.86,50.425,-3.595149393,50,0,9.998686816,0,0,0,90.00000001 +4.87,50.425,-3.595147986,50,0,9.998686816,0,0,0,90.00000001 +4.88,50.425,-3.595146579,50,0,9.999575096,0,0,0,90.00000001 +4.89,50.425,-3.595145172,50,0,10.00068544,0,0,0,90.00000001 +4.9,50.425,-3.595143764,50,0,10.00068544,0,0,0,90.00000001 +4.91,50.425,-3.595142357,50,0,9.999797165,0,0,0,90.00000001 +4.92,50.425,-3.59514095,50,0,9.999797165,0,0,0,90.00000001 +4.93,50.425,-3.595139543,50,0,10.00068544,0,0,0,90.00000001 +4.94,50.425,-3.595138135,50,0,10.00090751,0,0,0,90.00000001 +4.95,50.425,-3.595136728,50,0,10.00068544,0,0,0,90.00000001 +4.96,50.425,-3.595135321,50,0,10.00090751,0,0,0,90.00000001 +4.97,50.425,-3.595133913,50,0,10.00068544,0,0,0,90.00000001 +4.98,50.425,-3.595132506,50,0,9.999575096,0,0,0,90.00000001 +4.99,50.425,-3.595131099,50,0,9.998686817,0,0,0,90.00000001 +5,50.425,-3.595129692,50,0,9.998686816,0,0,0,90.00000001 +5.01,50.425,-3.595128285,50,0,9.999575095,0,0,0,90.00000001 +5.02,50.425,-3.595126878,50,0,10.00068544,0,0,0,90.00000001 +5.03,50.425,-3.59512547,50,0,10.00068544,0,0,0,90.00000001 +5.04,50.425,-3.595124063,50,0,9.999575095,0,0,0,90.00000001 +5.05,50.425,-3.595122656,50,0,9.998908886,0,0,0,90.00000001 +5.06,50.425,-3.595121249,50,0,9.999575096,0,0,0,90.00000001 +5.07,50.425,-3.595119842,50,0,10.00068544,0,0,0,90.00000001 +5.08,50.425,-3.595118434,50,0,10.00068544,0,0,0,90.00000001 +5.09,50.425,-3.595117027,50,0,9.999797165,0,0,0,90.00000001 +5.1,50.425,-3.59511562,50,0,9.999797165,0,0,0,90.00000001 +5.11,50.425,-3.595114213,50,0,10.00068544,0,0,0,90.00000001 +5.12,50.425,-3.595112805,50,0,10.00068544,0,0,0,90.00000001 +5.13,50.425,-3.595111398,50,0,9.999797165,0,0,0,90.00000001 +5.14,50.425,-3.595109991,50,0,9.999797165,0,0,0,90.00000001 +5.15,50.425,-3.595108584,50,0,10.00068544,0,0,0,90.00000001 +5.16,50.425,-3.595107176,50,0,10.00068544,0,0,0,90.00000001 +5.17,50.425,-3.595105769,50,0,9.999575096,0,0,0,90.00000001 +5.18,50.425,-3.595104362,50,0,9.998908886,0,0,0,90.00000001 +5.19,50.425,-3.595102955,50,0,9.999575095,0,0,0,90.00000001 +5.2,50.425,-3.595101548,50,0,10.00068544,0,0,0,90.00000001 +5.21,50.425,-3.59510014,50,0,10.00068544,0,0,0,90.00000001 +5.22,50.425,-3.595098733,50,0,9.999575096,0,0,0,90.00000001 +5.23,50.425,-3.595097326,50,0,9.998686816,0,0,0,90.00000001 +5.24,50.425,-3.595095919,50,0,9.998686816,0,0,0,90.00000001 +5.25,50.425,-3.595094512,50,0,9.999575095,0,0,0,90.00000001 +5.26,50.425,-3.595093105,50,0,10.00068544,0,0,0,90.00000001 +5.27,50.425,-3.595091697,50,0,10.00090751,0,0,0,90.00000001 +5.28,50.425,-3.59509029,50,0,10.00068544,0,0,0,90.00000001 +5.29,50.425,-3.595088883,50,0,10.00090751,0,0,0,90.00000001 +5.3,50.425,-3.595087475,50,0,10.00068544,0,0,0,90.00000001 +5.31,50.425,-3.595086068,50,0,9.999797165,0,0,0,90.00000001 +5.32,50.425,-3.595084661,50,0,9.999797165,0,0,0,90.00000001 +5.33,50.425,-3.595083254,50,0,10.00068544,0,0,0,90.00000001 +5.34,50.425,-3.595081846,50,0,10.00068544,0,0,0,90.00000001 +5.35,50.425,-3.595080439,50,0,9.999575095,0,0,0,90.00000001 +5.36,50.425,-3.595079032,50,0,9.998686816,0,0,0,90.00000001 +5.37,50.425,-3.595077625,50,0,9.998686817,0,0,0,90.00000001 +5.38,50.425,-3.595076218,50,0,9.999575096,0,0,0,90.00000001 +5.39,50.425,-3.595074811,50,0,10.00068544,0,0,0,90.00000001 +5.4,50.425,-3.595073403,50,0,10.00068544,0,0,0,90.00000001 +5.41,50.425,-3.595071996,50,0,9.999575095,0,0,0,90.00000001 +5.42,50.425,-3.595070589,50,0,9.998908887,0,0,0,90.00000001 +5.43,50.425,-3.595069182,50,0,9.999575096,0,0,0,90.00000001 +5.44,50.425,-3.595067775,50,0,10.00068544,0,0,0,90.00000001 +5.45,50.425,-3.595066367,50,0,10.00090751,0,0,0,90.00000001 +5.46,50.425,-3.59506496,50,0,10.00068544,0,0,0,90.00000001 +5.47,50.425,-3.595063553,50,0,10.00090751,0,0,0,90.00000001 +5.48,50.425,-3.595062145,50,0,10.00068544,0,0,0,90.00000001 +5.49,50.425,-3.595060738,50,0,9.999575095,0,0,0,90.00000001 +5.5,50.425,-3.595059331,50,0,9.998908885,0,0,0,90.00000001 +5.51,50.425,-3.595057924,50,0,9.999575095,0,0,0,90.00000001 +5.52,50.425,-3.595056517,50,0,10.00068544,0,0,0,90.00000001 +5.53,50.425,-3.595055109,50,0,10.00068544,0,0,0,90.00000001 +5.54,50.425,-3.595053702,50,0,9.999575095,0,0,0,90.00000001 +5.55,50.425,-3.595052295,50,0,9.998908886,0,0,0,90.00000001 +5.56,50.425,-3.595050888,50,0,9.999575095,0,0,0,90.00000001 +5.57,50.425,-3.595049481,50,0,10.00068544,0,0,0,90.00000001 +5.58,50.425,-3.595048073,50,0,10.00068544,0,0,0,90.00000001 +5.59,50.425,-3.595046666,50,0,9.999575097,0,0,0,90.00000001 +5.6,50.425,-3.595045259,50,0,9.998686818,0,0,0,90.00000001 +5.61,50.425,-3.595043852,50,0,9.998686817,0,0,0,90.00000001 +5.62,50.425,-3.595042445,50,0,9.999575095,0,0,0,90.00000001 +5.63,50.425,-3.595041038,50,0,10.00090751,0,0,0,90.00000001 +5.64,50.425,-3.59503963,50,0,10.00179579,0,0,0,90.00000001 +5.65,50.425,-3.595038223,50,0,10.00179579,0,0,0,90.00000001 +5.66,50.425,-3.595036815,50,0,10.00090751,0,0,0,90.00000001 +5.67,50.425,-3.595035408,50,0,9.999575095,0,0,0,90.00000001 +5.68,50.425,-3.595034001,50,0,9.998686817,0,0,0,90.00000001 +5.69,50.425,-3.595032594,50,0,9.998686817,0,0,0,90.00000001 +5.7,50.425,-3.595031187,50,0,9.999575096,0,0,0,90.00000001 +5.71,50.425,-3.59502978,50,0,10.00068544,0,0,0,90.00000001 +5.72,50.425,-3.595028372,50,0,10.00068544,0,0,0,90.00000001 +5.73,50.425,-3.595026965,50,0,9.999575095,0,0,0,90.00000001 +5.74,50.425,-3.595025558,50,0,9.998908885,0,0,0,90.00000001 +5.75,50.425,-3.595024151,50,0,9.999575095,0,0,0,90.00000001 +5.76,50.425,-3.595022744,50,0,10.00068544,0,0,0,90.00000001 +5.77,50.425,-3.595021336,50,0,10.00068544,0,0,0,90.00000001 +5.78,50.425,-3.595019929,50,0,9.999575095,0,0,0,90.00000001 +5.79,50.425,-3.595018522,50,0,9.998908886,0,0,0,90.00000001 +5.8,50.425,-3.595017115,50,0,9.999575096,0,0,0,90.00000001 +5.81,50.425,-3.595015708,50,0,10.00068544,0,0,0,90.00000001 +5.82,50.425,-3.5950143,50,0,10.00090751,0,0,0,90.00000001 +5.83,50.425,-3.595012893,50,0,10.00068544,0,0,0,90.00000001 +5.84,50.425,-3.595011486,50,0,10.00090751,0,0,0,90.00000001 +5.85,50.425,-3.595010078,50,0,10.00068544,0,0,0,90.00000001 +5.86,50.425,-3.595008671,50,0,9.999575096,0,0,0,90.00000001 +5.87,50.425,-3.595007264,50,0,9.998908887,0,0,0,90.00000001 +5.88,50.425,-3.595005857,50,0,9.999575095,0,0,0,90.00000001 +5.89,50.425,-3.59500445,50,0,10.00068544,0,0,0,90.00000001 +5.9,50.425,-3.595003042,50,0,10.00068544,0,0,0,90.00000001 +5.91,50.425,-3.595001635,50,0,9.999575096,0,0,0,90.00000001 +5.92,50.425,-3.595000228,50,0,9.998686816,0,0,0,90.00000001 +5.93,50.425,-3.594998821,50,0,9.998686816,0,0,0,90.00000001 +5.94,50.425,-3.594997414,50,0,9.999575096,0,0,0,90.00000001 +5.95,50.425,-3.594996007,50,0,10.00068544,0,0,0,90.00000001 +5.96,50.425,-3.594994599,50,0,10.00068544,0,0,0,90.00000001 +5.97,50.425,-3.594993192,50,0,9.999575095,0,0,0,90.00000001 +5.98,50.425,-3.594991785,50,0,9.998908887,0,0,0,90.00000001 +5.99,50.425,-3.594990378,50,0,9.999575096,0,0,0,90.00000001 +6,50.425,-3.594988971,50,0,10.00090751,0,0,0,90.00000001 +6.01,50.425,-3.594987563,50,0,10.00179579,0,0,0,90.00000001 +6.02,50.425,-3.594986156,50,0,10.00179579,0,0,0,90.00000001 +6.03,50.425,-3.594984748,50,0,10.00090751,0,0,0,90.00000001 +6.04,50.425,-3.594983341,50,0,9.999575095,0,0,0,90.00000001 +6.05,50.425,-3.594981934,50,0,9.998686816,0,0,0,90.00000001 +6.06,50.425,-3.594980527,50,0,9.998686817,0,0,0,90.00000001 +6.07,50.425,-3.59497912,50,0,9.999575096,0,0,0,90.00000001 +6.08,50.425,-3.594977713,50,0,10.00068544,0,0,0,90.00000001 +6.09,50.425,-3.594976305,50,0,10.00068544,0,0,0,90.00000001 +6.1,50.425,-3.594974898,50,0,9.999575095,0,0,0,90.00000001 +6.11,50.425,-3.594973491,50,0,9.998908886,0,0,0,90.00000001 +6.12,50.425,-3.594972084,50,0,9.999575096,0,0,0,90.00000001 +6.13,50.425,-3.594970677,50,0,10.00068544,0,0,0,90.00000001 +6.14,50.425,-3.594969269,50,0,10.00068544,0,0,0,90.00000001 +6.15,50.425,-3.594967862,50,0,9.999575095,0,0,0,90.00000001 +6.16,50.425,-3.594966455,50,0,9.998686816,0,0,0,90.00000001 +6.17,50.425,-3.594965048,50,0,9.998686816,0,0,0,90.00000001 +6.18,50.425,-3.594963641,50,0,9.999575095,0,0,0,90.00000001 +6.19,50.425,-3.594962234,50,0,10.00090751,0,0,0,90.00000001 +6.2,50.425,-3.594960826,50,0,10.00179579,0,0,0,90.00000001 +6.21,50.425,-3.594959419,50,0,10.00179579,0,0,0,90.00000001 +6.22,50.425,-3.594958011,50,0,10.00090751,0,0,0,90.00000001 +6.23,50.425,-3.594956604,50,0,9.999575095,0,0,0,90.00000001 +6.24,50.425,-3.594955197,50,0,9.998908886,0,0,0,90.00000001 +6.25,50.425,-3.59495379,50,0,9.999575096,0,0,0,90.00000001 +6.26,50.425,-3.594952383,50,0,10.00068544,0,0,0,90.00000001 +6.27,50.425,-3.594950975,50,0,10.00068544,0,0,0,90.00000001 +6.28,50.425,-3.594949568,50,0,9.999575095,0,0,0,90.00000001 +6.29,50.425,-3.594948161,50,0,9.998686817,0,0,0,90.00000001 +6.3,50.425,-3.594946754,50,0,9.998686818,0,0,0,90.00000001 +6.31,50.425,-3.594945347,50,0,9.999575096,0,0,0,90.00000001 +6.32,50.425,-3.59494394,50,0,10.00068544,0,0,0,90.00000001 +6.33,50.425,-3.594942532,50,0,10.00068544,0,0,0,90.00000001 +6.34,50.425,-3.594941125,50,0,9.999575095,0,0,0,90.00000001 +6.35,50.425,-3.594939718,50,0,9.998908886,0,0,0,90.00000001 +6.36,50.425,-3.594938311,50,0,9.999575095,0,0,0,90.00000001 +6.37,50.425,-3.594936904,50,0,10.00068544,0,0,0,90.00000001 +6.38,50.425,-3.594935496,50,0,10.00090751,0,0,0,90.00000001 +6.39,50.425,-3.594934089,50,0,10.00068544,0,0,0,90.00000001 +6.4,50.425,-3.594932682,50,0,10.00090751,0,0,0,90.00000001 +6.41,50.425,-3.594931274,50,0,10.00068544,0,0,0,90.00000001 +6.42,50.425,-3.594929867,50,0,9.999575095,0,0,0,90.00000001 +6.43,50.425,-3.59492846,50,0,9.998908885,0,0,0,90.00000001 +6.44,50.425,-3.594927053,50,0,9.999575095,0,0,0,90.00000001 +6.45,50.425,-3.594925646,50,0,10.00068544,0,0,0,90.00000001 +6.46,50.425,-3.594924238,50,0,10.00068544,0,0,0,90.00000001 +6.47,50.425,-3.594922831,50,0,9.999575096,0,0,0,90.00000001 +6.48,50.425,-3.594921424,50,0,9.998908886,0,0,0,90.00000001 +6.49,50.425,-3.594920017,50,0,9.999575095,0,0,0,90.00000001 +6.5,50.425,-3.59491861,50,0,10.00068544,0,0,0,90.00000001 +6.51,50.425,-3.594917202,50,0,10.00068544,0,0,0,90.00000001 +6.52,50.425,-3.594915795,50,0,9.999575096,0,0,0,90.00000001 +6.53,50.425,-3.594914388,50,0,9.998908887,0,0,0,90.00000001 +6.54,50.425,-3.594912981,50,0,9.999575095,0,0,0,90.00000001 +6.55,50.425,-3.594911574,50,0,10.00068544,0,0,0,90.00000001 +6.56,50.425,-3.594910166,50,0,10.00090751,0,0,0,90.00000001 +6.57,50.425,-3.594908759,50,0,10.00068544,0,0,0,90.00000001 +6.58,50.425,-3.594907352,50,0,10.00090751,0,0,0,90.00000001 +6.59,50.425,-3.594905944,50,0,10.00068544,0,0,0,90.00000001 +6.6,50.425,-3.594904537,50,0,9.999575096,0,0,0,90.00000001 +6.61,50.425,-3.59490313,50,0,9.998686817,0,0,0,90.00000001 +6.62,50.425,-3.594901723,50,0,9.998686816,0,0,0,90.00000001 +6.63,50.425,-3.594900316,50,0,9.999575095,0,0,0,90.00000001 +6.64,50.425,-3.594898909,50,0,10.00068544,0,0,0,90.00000001 +6.65,50.425,-3.594897501,50,0,10.00068544,0,0,0,90.00000001 +6.66,50.425,-3.594896094,50,0,9.999575095,0,0,0,90.00000001 +6.67,50.425,-3.594894687,50,0,9.998908886,0,0,0,90.00000001 +6.68,50.425,-3.59489328,50,0,9.999575096,0,0,0,90.00000001 +6.69,50.425,-3.594891873,50,0,10.00068544,0,0,0,90.00000001 +6.7,50.425,-3.594890465,50,0,10.00068544,0,0,0,90.00000001 +6.71,50.425,-3.594889058,50,0,9.999797165,0,0,0,90.00000001 +6.72,50.425,-3.594887651,50,0,9.999797165,0,0,0,90.00000001 +6.73,50.425,-3.594886244,50,0,10.00068544,0,0,0,90.00000001 +6.74,50.425,-3.594884836,50,0,10.00068544,0,0,0,90.00000001 +6.75,50.425,-3.594883429,50,0,9.999797165,0,0,0,90.00000001 +6.76,50.425,-3.594882022,50,0,9.999797165,0,0,0,90.00000001 +6.77,50.425,-3.594880615,50,0,10.00068544,0,0,0,90.00000001 +6.78,50.425,-3.594879207,50,0,10.00068544,0,0,0,90.00000001 +6.79,50.425,-3.5948778,50,0,9.999575096,0,0,0,90.00000001 +6.8,50.425,-3.594876393,50,0,9.998908886,0,0,0,90.00000001 +6.81,50.425,-3.594874986,50,0,9.999575095,0,0,0,90.00000001 +6.82,50.425,-3.594873579,50,0,10.00068544,0,0,0,90.00000001 +6.83,50.425,-3.594872171,50,0,10.00068544,0,0,0,90.00000001 +6.84,50.425,-3.594870764,50,0,9.999575095,0,0,0,90.00000001 +6.85,50.425,-3.594869357,50,0,9.998686816,0,0,0,90.00000001 +6.86,50.425,-3.59486795,50,0,9.998686816,0,0,0,90.00000001 +6.87,50.425,-3.594866543,50,0,9.999575095,0,0,0,90.00000001 +6.88,50.425,-3.594865136,50,0,10.00068544,0,0,0,90.00000001 +6.89,50.425,-3.594863728,50,0,10.00068544,0,0,0,90.00000001 +6.9,50.425,-3.594862321,50,0,9.999797166,0,0,0,90.00000001 +6.91,50.425,-3.594860914,50,0,9.999797165,0,0,0,90.00000001 +6.92,50.425,-3.594859507,50,0,10.00068544,0,0,0,90.00000001 +6.93,50.425,-3.594858099,50,0,10.00090751,0,0,0,90.00000001 +6.94,50.425,-3.594856692,50,0,10.00068544,0,0,0,90.00000001 +6.95,50.425,-3.594855285,50,0,10.00090751,0,0,0,90.00000001 +6.96,50.425,-3.594853877,50,0,10.00068544,0,0,0,90.00000001 +6.97,50.425,-3.59485247,50,0,9.999575095,0,0,0,90.00000001 +6.98,50.425,-3.594851063,50,0,9.998686817,0,0,0,90.00000001 +6.99,50.425,-3.594849656,50,0,9.998686818,0,0,0,90.00000001 +7,50.425,-3.594848249,50,0,9.999575096,0,0,0,90.00000001 +7.01,50.425,-3.594846842,50,0,10.00068544,0,0,0,90.00000001 +7.02,50.425,-3.594845434,50,0,10.00068544,0,0,0,90.00000001 +7.03,50.425,-3.594844027,50,0,9.999575095,0,0,0,90.00000001 +7.04,50.425,-3.59484262,50,0,9.998908886,0,0,0,90.00000001 +7.05,50.425,-3.594841213,50,0,9.999575095,0,0,0,90.00000001 +7.06,50.425,-3.594839806,50,0,10.00068544,0,0,0,90.00000001 +7.07,50.425,-3.594838398,50,0,10.00068544,0,0,0,90.00000001 +7.08,50.425,-3.594836991,50,0,9.999797165,0,0,0,90.00000001 +7.09,50.425,-3.594835584,50,0,9.999797165,0,0,0,90.00000001 +7.1,50.425,-3.594834177,50,0,10.00068544,0,0,0,90.00000001 +7.11,50.425,-3.594832769,50,0,10.00068544,0,0,0,90.00000001 +7.12,50.425,-3.594831362,50,0,9.999797165,0,0,0,90.00000001 +7.13,50.425,-3.594829955,50,0,9.999797165,0,0,0,90.00000001 +7.14,50.425,-3.594828548,50,0,10.00068544,0,0,0,90.00000001 +7.15,50.425,-3.59482714,50,0,10.00068544,0,0,0,90.00000001 +7.16,50.425,-3.594825733,50,0,9.999575095,0,0,0,90.00000001 +7.17,50.425,-3.594824326,50,0,9.998908886,0,0,0,90.00000001 +7.18,50.425,-3.594822919,50,0,9.999575095,0,0,0,90.00000001 +7.19,50.425,-3.594821512,50,0,10.00068544,0,0,0,90.00000001 +7.2,50.425,-3.594820104,50,0,10.00068544,0,0,0,90.00000001 +7.21,50.425,-3.594818697,50,0,9.999575096,0,0,0,90.00000001 +7.22,50.425,-3.59481729,50,0,9.998686817,0,0,0,90.00000001 +7.23,50.425,-3.594815883,50,0,9.998686816,0,0,0,90.00000001 +7.24,50.425,-3.594814476,50,0,9.999575095,0,0,0,90.00000001 +7.25,50.425,-3.594813069,50,0,10.00068544,0,0,0,90.00000001 +7.26,50.425,-3.594811661,50,0,10.00090751,0,0,0,90.00000001 +7.27,50.425,-3.594810254,50,0,10.00068544,0,0,0,90.00000001 +7.28,50.425,-3.594808847,50,0,10.00090751,0,0,0,90.00000001 +7.29,50.425,-3.594807439,50,0,10.00068544,0,0,0,90.00000001 +7.3,50.425,-3.594806032,50,0,9.999575096,0,0,0,90.00000001 +7.31,50.425,-3.594804625,50,0,9.998908886,0,0,0,90.00000001 +7.32,50.425,-3.594803218,50,0,9.999575095,0,0,0,90.00000001 +7.33,50.425,-3.594801811,50,0,10.00068544,0,0,0,90.00000001 +7.34,50.425,-3.594800403,50,0,10.00068544,0,0,0,90.00000001 +7.35,50.425,-3.594798996,50,0,9.999575095,0,0,0,90.00000001 +7.36,50.425,-3.594797589,50,0,9.998908886,0,0,0,90.00000001 +7.37,50.425,-3.594796182,50,0,9.999575096,0,0,0,90.00000001 +7.38,50.425,-3.594794775,50,0,10.00068544,0,0,0,90.00000001 +7.39,50.425,-3.594793367,50,0,10.00068544,0,0,0,90.00000001 +7.4,50.425,-3.59479196,50,0,9.999575095,0,0,0,90.00000001 +7.41,50.425,-3.594790553,50,0,9.998908886,0,0,0,90.00000001 +7.42,50.425,-3.594789146,50,0,9.999575096,0,0,0,90.00000001 +7.43,50.425,-3.594787739,50,0,10.00068544,0,0,0,90.00000001 +7.44,50.425,-3.594786331,50,0,10.00090751,0,0,0,90.00000001 +7.45,50.425,-3.594784924,50,0,10.00068544,0,0,0,90.00000001 +7.46,50.425,-3.594783517,50,0,10.00090751,0,0,0,90.00000001 +7.47,50.425,-3.594782109,50,0,10.00068544,0,0,0,90.00000001 +7.48,50.425,-3.594780702,50,0,9.999575096,0,0,0,90.00000001 +7.49,50.425,-3.594779295,50,0,9.998908887,0,0,0,90.00000001 +7.5,50.425,-3.594777888,50,0,9.999575095,0,0,0,90.00000001 +7.51,50.425,-3.594776481,50,0,10.00068544,0,0,0,90.00000001 +7.52,50.425,-3.594775073,50,0,10.00068544,0,0,0,90.00000001 +7.53,50.425,-3.594773666,50,0,9.999575096,0,0,0,90.00000001 +7.54,50.425,-3.594772259,50,0,9.998686816,0,0,0,90.00000001 +7.55,50.425,-3.594770852,50,0,9.998686816,0,0,0,90.00000001 +7.56,50.425,-3.594769445,50,0,9.999575095,0,0,0,90.00000001 +7.57,50.425,-3.594768038,50,0,10.00068544,0,0,0,90.00000001 +7.58,50.425,-3.59476663,50,0,10.00068544,0,0,0,90.00000001 +7.59,50.425,-3.594765223,50,0,9.999575096,0,0,0,90.00000001 +7.6,50.425,-3.594763816,50,0,9.998908887,0,0,0,90.00000001 +7.61,50.425,-3.594762409,50,0,9.999575096,0,0,0,90.00000001 +7.62,50.425,-3.594761002,50,0,10.00090751,0,0,0,90.00000001 +7.63,50.425,-3.594759594,50,0,10.00179579,0,0,0,90.00000001 +7.64,50.425,-3.594758187,50,0,10.00179579,0,0,0,90.00000001 +7.65,50.425,-3.594756779,50,0,10.00090751,0,0,0,90.00000001 +7.66,50.425,-3.594755372,50,0,9.999575095,0,0,0,90.00000001 +7.67,50.425,-3.594753965,50,0,9.998686816,0,0,0,90.00000001 +7.68,50.425,-3.594752558,50,0,9.998686817,0,0,0,90.00000001 +7.69,50.425,-3.594751151,50,0,9.999575097,0,0,0,90.00000001 +7.7,50.425,-3.594749744,50,0,10.00068544,0,0,0,90.00000001 +7.71,50.425,-3.594748336,50,0,10.00068544,0,0,0,90.00000001 +7.72,50.425,-3.594746929,50,0,9.999575095,0,0,0,90.00000001 +7.73,50.425,-3.594745522,50,0,9.998908885,0,0,0,90.00000001 +7.74,50.425,-3.594744115,50,0,9.999575095,0,0,0,90.00000001 +7.75,50.425,-3.594742708,50,0,10.00068544,0,0,0,90.00000001 +7.76,50.425,-3.5947413,50,0,10.00068544,0,0,0,90.00000001 +7.77,50.425,-3.594739893,50,0,9.999575095,0,0,0,90.00000001 +7.78,50.425,-3.594738486,50,0,9.998686816,0,0,0,90.00000001 +7.79,50.425,-3.594737079,50,0,9.998686816,0,0,0,90.00000001 +7.8,50.425,-3.594735672,50,0,9.999575096,0,0,0,90.00000001 +7.81,50.425,-3.594734265,50,0,10.00090751,0,0,0,90.00000001 +7.82,50.425,-3.594732857,50,0,10.00179579,0,0,0,90.00000001 +7.83,50.425,-3.59473145,50,0,10.00179579,0,0,0,90.00000001 +7.84,50.425,-3.594730042,50,0,10.00090751,0,0,0,90.00000001 +7.85,50.425,-3.594728635,50,0,9.999575095,0,0,0,90.00000001 +7.86,50.425,-3.594727228,50,0,9.998908887,0,0,0,90.00000001 +7.87,50.425,-3.594725821,50,0,9.999575096,0,0,0,90.00000001 +7.88,50.425,-3.594724414,50,0,10.00068544,0,0,0,90.00000001 +7.89,50.425,-3.594723006,50,0,10.00068544,0,0,0,90.00000001 +7.9,50.425,-3.594721599,50,0,9.999575096,0,0,0,90.00000001 +7.91,50.425,-3.594720192,50,0,9.998686818,0,0,0,90.00000001 +7.92,50.425,-3.594718785,50,0,9.998686817,0,0,0,90.00000001 +7.93,50.425,-3.594717378,50,0,9.999575095,0,0,0,90.00000001 +7.94,50.425,-3.594715971,50,0,10.00068544,0,0,0,90.00000001 +7.95,50.425,-3.594714563,50,0,10.00068544,0,0,0,90.00000001 +7.96,50.425,-3.594713156,50,0,9.999575096,0,0,0,90.00000001 +7.97,50.425,-3.594711749,50,0,9.998908886,0,0,0,90.00000001 +7.98,50.425,-3.594710342,50,0,9.999575095,0,0,0,90.00000001 +7.99,50.425,-3.594708935,50,0,10.00090751,0,0,0,90.00000001 +8,50.425,-3.594707527,50,0,10.00179579,0,0,0,90.00000001 +8.01,50.425,-3.59470612,50,0,10.00179579,0,0,0,90.00000001 +8.02,50.425,-3.594704712,50,0,10.00090751,0,0,0,90.00000001 +8.03,50.425,-3.594703305,50,0,9.999575095,0,0,0,90.00000001 +8.04,50.425,-3.594701898,50,0,9.998686816,0,0,0,90.00000001 +8.05,50.425,-3.594700491,50,0,9.998686816,0,0,0,90.00000001 +8.06,50.425,-3.594699084,50,0,9.999575095,0,0,0,90.00000001 +8.07,50.425,-3.594697677,50,0,10.00068544,0,0,0,90.00000001 +8.08,50.425,-3.594696269,50,0,10.00068544,0,0,0,90.00000001 +8.09,50.425,-3.594694862,50,0,9.999575096,0,0,0,90.00000001 +8.1,50.425,-3.594693455,50,0,9.998908886,0,0,0,90.00000001 +8.11,50.425,-3.594692048,50,0,9.999575095,0,0,0,90.00000001 +8.12,50.425,-3.594690641,50,0,10.00068544,0,0,0,90.00000001 +8.13,50.425,-3.594689233,50,0,10.00068544,0,0,0,90.00000001 +8.14,50.425,-3.594687826,50,0,9.999575096,0,0,0,90.00000001 +8.15,50.425,-3.594686419,50,0,9.998686816,0,0,0,90.00000001 +8.16,50.425,-3.594685012,50,0,9.998686816,0,0,0,90.00000001 +8.17,50.425,-3.594683605,50,0,9.999575095,0,0,0,90.00000001 +8.18,50.425,-3.594682198,50,0,10.00090751,0,0,0,90.00000001 +8.19,50.425,-3.59468079,50,0,10.00179579,0,0,0,90.00000001 +8.2,50.425,-3.594679383,50,0,10.00179579,0,0,0,90.00000001 +8.21,50.425,-3.594677975,50,0,10.00090751,0,0,0,90.00000001 +8.22,50.425,-3.594676568,50,0,9.999575096,0,0,0,90.00000001 +8.23,50.425,-3.594675161,50,0,9.998908886,0,0,0,90.00000001 +8.24,50.425,-3.594673754,50,0,9.999575095,0,0,0,90.00000001 +8.25,50.425,-3.594672347,50,0,10.00068544,0,0,0,90.00000001 +8.26,50.425,-3.594670939,50,0,10.00068544,0,0,0,90.00000001 +8.27,50.425,-3.594669532,50,0,9.999575095,0,0,0,90.00000001 +8.28,50.425,-3.594668125,50,0,9.998686816,0,0,0,90.00000001 +8.29,50.425,-3.594666718,50,0,9.998686817,0,0,0,90.00000001 +8.3,50.425,-3.594665311,50,0,9.999575096,0,0,0,90.00000001 +8.31,50.425,-3.594663904,50,0,10.00068544,0,0,0,90.00000001 +8.32,50.425,-3.594662496,50,0,10.00068544,0,0,0,90.00000001 +8.33,50.425,-3.594661089,50,0,9.999575096,0,0,0,90.00000001 +8.34,50.425,-3.594659682,50,0,9.998908888,0,0,0,90.00000001 +8.35,50.425,-3.594658275,50,0,9.999575097,0,0,0,90.00000001 +8.36,50.425,-3.594656868,50,0,10.00068544,0,0,0,90.00000001 +8.37,50.425,-3.59465546,50,0,10.00090751,0,0,0,90.00000001 +8.38,50.425,-3.594654053,50,0,10.00068544,0,0,0,90.00000001 +8.39,50.425,-3.594652646,50,0,10.00090751,0,0,0,90.00000001 +8.4,50.425,-3.594651238,50,0,10.00068544,0,0,0,90.00000001 +8.41,50.425,-3.594649831,50,0,9.999575096,0,0,0,90.00000001 +8.42,50.425,-3.594648424,50,0,9.998908886,0,0,0,90.00000001 +8.43,50.425,-3.594647017,50,0,9.999575095,0,0,0,90.00000001 +8.44,50.425,-3.59464561,50,0,10.00068544,0,0,0,90.00000001 +8.45,50.425,-3.594644202,50,0,10.00068544,0,0,0,90.00000001 +8.46,50.425,-3.594642795,50,0,9.999575095,0,0,0,90.00000001 +8.47,50.425,-3.594641388,50,0,9.998686816,0,0,0,90.00000001 +8.48,50.425,-3.594639981,50,0,9.998686816,0,0,0,90.00000001 +8.49,50.425,-3.594638574,50,0,9.999575095,0,0,0,90.00000001 +8.5,50.425,-3.594637167,50,0,10.00068544,0,0,0,90.00000001 +8.51,50.425,-3.594635759,50,0,10.00068544,0,0,0,90.00000001 +8.52,50.425,-3.594634352,50,0,9.999797166,0,0,0,90.00000001 +8.53,50.425,-3.594632945,50,0,9.999797165,0,0,0,90.00000001 +8.54,50.425,-3.594631538,50,0,10.00068544,0,0,0,90.00000001 +8.55,50.425,-3.59463013,50,0,10.00090751,0,0,0,90.00000001 +8.56,50.425,-3.594628723,50,0,10.00068544,0,0,0,90.00000001 +8.57,50.425,-3.594627316,50,0,10.00090751,0,0,0,90.00000001 +8.58,50.425,-3.594625908,50,0,10.00068544,0,0,0,90.00000001 +8.59,50.425,-3.594624501,50,0,9.999575095,0,0,0,90.00000001 +8.6,50.425,-3.594623094,50,0,9.998686817,0,0,0,90.00000001 +8.61,50.425,-3.594621687,50,0,9.998686817,0,0,0,90.00000001 +8.62,50.425,-3.59462028,50,0,9.999575096,0,0,0,90.00000001 +8.63,50.425,-3.594618873,50,0,10.00068544,0,0,0,90.00000001 +8.64,50.425,-3.594617465,50,0,10.00068544,0,0,0,90.00000001 +8.65,50.425,-3.594616058,50,0,9.999575095,0,0,0,90.00000001 +8.66,50.425,-3.594614651,50,0,9.998908885,0,0,0,90.00000001 +8.67,50.425,-3.594613244,50,0,9.999575095,0,0,0,90.00000001 +8.68,50.425,-3.594611837,50,0,10.00068544,0,0,0,90.00000001 +8.69,50.425,-3.594610429,50,0,10.00068544,0,0,0,90.00000001 +8.7,50.425,-3.594609022,50,0,9.999797165,0,0,0,90.00000001 +8.71,50.425,-3.594607615,50,0,9.999797165,0,0,0,90.00000001 +8.72,50.425,-3.594606208,50,0,10.00068544,0,0,0,90.00000001 +8.73,50.425,-3.5946048,50,0,10.00068544,0,0,0,90.00000001 +8.74,50.425,-3.594603393,50,0,9.999797165,0,0,0,90.00000001 +8.75,50.425,-3.594601986,50,0,9.999797165,0,0,0,90.00000001 +8.76,50.425,-3.594600579,50,0,10.00068544,0,0,0,90.00000001 +8.77,50.425,-3.594599171,50,0,10.00068544,0,0,0,90.00000001 +8.78,50.425,-3.594597764,50,0,9.999575097,0,0,0,90.00000001 +8.79,50.425,-3.594596357,50,0,9.998908888,0,0,0,90.00000001 +8.8,50.425,-3.59459495,50,0,9.999575096,0,0,0,90.00000001 +8.81,50.425,-3.594593543,50,0,10.00068544,0,0,0,90.00000001 +8.82,50.425,-3.594592135,50,0,10.00068544,0,0,0,90.00000001 +8.83,50.425,-3.594590728,50,0,9.999575096,0,0,0,90.00000001 +8.84,50.425,-3.594589321,50,0,9.998686817,0,0,0,90.00000001 +8.85,50.425,-3.594587914,50,0,9.998686816,0,0,0,90.00000001 +8.86,50.425,-3.594586507,50,0,9.999575095,0,0,0,90.00000001 +8.87,50.425,-3.5945851,50,0,10.00068544,0,0,0,90.00000001 +8.88,50.425,-3.594583692,50,0,10.00090751,0,0,0,90.00000001 +8.89,50.425,-3.594582285,50,0,10.00068544,0,0,0,90.00000001 +8.9,50.425,-3.594580878,50,0,10.00090751,0,0,0,90.00000001 +8.91,50.425,-3.59457947,50,0,10.00068544,0,0,0,90.00000001 +8.92,50.425,-3.594578063,50,0,9.999797165,0,0,0,90.00000001 +8.93,50.425,-3.594576656,50,0,9.999797165,0,0,0,90.00000001 +8.94,50.425,-3.594575249,50,0,10.00068544,0,0,0,90.00000001 +8.95,50.425,-3.594573841,50,0,10.00068544,0,0,0,90.00000001 +8.96,50.425,-3.594572434,50,0,9.999575096,0,0,0,90.00000001 +8.97,50.425,-3.594571027,50,0,9.998686816,0,0,0,90.00000001 +8.98,50.425,-3.59456962,50,0,9.998686816,0,0,0,90.00000001 +8.99,50.425,-3.594568213,50,0,9.999575096,0,0,0,90.00000001 +9,50.425,-3.594566806,50,0,10.00068544,0,0,0,90.00000001 +9.01,50.425,-3.594565398,50,0,10.00068544,0,0,0,90.00000001 +9.02,50.425,-3.594563991,50,0,9.999575095,0,0,0,90.00000001 +9.03,50.425,-3.594562584,50,0,9.998908886,0,0,0,90.00000001 +9.04,50.425,-3.594561177,50,0,9.999575096,0,0,0,90.00000001 +9.05,50.425,-3.59455977,50,0,10.00068544,0,0,0,90.00000001 +9.06,50.425,-3.594558362,50,0,10.00090751,0,0,0,90.00000001 +9.07,50.425,-3.594556955,50,0,10.00068544,0,0,0,90.00000001 +9.08,50.425,-3.594555548,50,0,10.00090751,0,0,0,90.00000001 +9.09,50.425,-3.59455414,50,0,10.00068544,0,0,0,90.00000001 +9.1,50.425,-3.594552733,50,0,9.999575096,0,0,0,90.00000001 +9.11,50.425,-3.594551326,50,0,9.998908886,0,0,0,90.00000001 +9.12,50.425,-3.594549919,50,0,9.999575095,0,0,0,90.00000001 +9.13,50.425,-3.594548512,50,0,10.00068544,0,0,0,90.00000001 +9.14,50.425,-3.594547104,50,0,10.00068544,0,0,0,90.00000001 +9.15,50.425,-3.594545697,50,0,9.999575095,0,0,0,90.00000001 +9.16,50.425,-3.59454429,50,0,9.998908886,0,0,0,90.00000001 +9.17,50.425,-3.594542883,50,0,9.999575096,0,0,0,90.00000001 +9.18,50.425,-3.594541476,50,0,10.00068544,0,0,0,90.00000001 +9.19,50.425,-3.594540068,50,0,10.00068544,0,0,0,90.00000001 +9.2,50.425,-3.594538661,50,0,9.999575095,0,0,0,90.00000001 +9.21,50.425,-3.594537254,50,0,9.998686817,0,0,0,90.00000001 +9.22,50.425,-3.594535847,50,0,9.998686818,0,0,0,90.00000001 +9.23,50.425,-3.59453444,50,0,9.999575096,0,0,0,90.00000001 +9.24,50.425,-3.594533033,50,0,10.00090751,0,0,0,90.00000001 +9.25,50.425,-3.594531625,50,0,10.00179579,0,0,0,90.00000001 +9.26,50.425,-3.594530218,50,0,10.00179579,0,0,0,90.00000001 +9.27,50.425,-3.59452881,50,0,10.00090751,0,0,0,90.00000001 +9.28,50.425,-3.594527403,50,0,9.999575096,0,0,0,90.00000001 +9.29,50.425,-3.594525996,50,0,9.998686816,0,0,0,90.00000001 +9.3,50.425,-3.594524589,50,0,9.998686816,0,0,0,90.00000001 +9.31,50.425,-3.594523182,50,0,9.999575096,0,0,0,90.00000001 +9.32,50.425,-3.594521775,50,0,10.00068544,0,0,0,90.00000001 +9.33,50.425,-3.594520367,50,0,10.00068544,0,0,0,90.00000001 +9.34,50.425,-3.59451896,50,0,9.999575095,0,0,0,90.00000001 +9.35,50.425,-3.594517553,50,0,9.998908885,0,0,0,90.00000001 +9.36,50.425,-3.594516146,50,0,9.999575095,0,0,0,90.00000001 +9.37,50.425,-3.594514739,50,0,10.00068544,0,0,0,90.00000001 +9.38,50.425,-3.594513331,50,0,10.00068544,0,0,0,90.00000001 +9.39,50.425,-3.594511924,50,0,9.999575095,0,0,0,90.00000001 +9.4,50.425,-3.594510517,50,0,9.998908885,0,0,0,90.00000001 +9.41,50.425,-3.59450911,50,0,9.999575095,0,0,0,90.00000001 +9.42,50.425,-3.594507703,50,0,10.00068544,0,0,0,90.00000001 +9.43,50.425,-3.594506295,50,0,10.00090751,0,0,0,90.00000001 +9.44,50.425,-3.594504888,50,0,10.00068544,0,0,0,90.00000001 +9.45,50.425,-3.594503481,50,0,10.00090751,0,0,0,90.00000001 +9.46,50.425,-3.594502073,50,0,10.00068544,0,0,0,90.00000001 +9.47,50.425,-3.594500666,50,0,9.999575096,0,0,0,90.00000001 +9.48,50.425,-3.594499259,50,0,9.998908887,0,0,0,90.00000001 +9.49,50.425,-3.594497852,50,0,9.999575096,0,0,0,90.00000001 +9.5,50.425,-3.594496445,50,0,10.00068544,0,0,0,90.00000001 +9.51,50.425,-3.594495037,50,0,10.00068544,0,0,0,90.00000001 +9.52,50.425,-3.59449363,50,0,9.999575096,0,0,0,90.00000001 +9.53,50.425,-3.594492223,50,0,9.998686817,0,0,0,90.00000001 +9.54,50.425,-3.594490816,50,0,9.998686816,0,0,0,90.00000001 +9.55,50.425,-3.594489409,50,0,9.999575095,0,0,0,90.00000001 +9.56,50.425,-3.594488002,50,0,10.00068544,0,0,0,90.00000001 +9.57,50.425,-3.594486594,50,0,10.00068544,0,0,0,90.00000001 +9.58,50.425,-3.594485187,50,0,9.999575095,0,0,0,90.00000001 +9.59,50.425,-3.59448378,50,0,9.998908886,0,0,0,90.00000001 +9.6,50.425,-3.594482373,50,0,9.999575096,0,0,0,90.00000001 +9.61,50.425,-3.594480966,50,0,10.00090751,0,0,0,90.00000001 +9.62,50.425,-3.594479558,50,0,10.00179579,0,0,0,90.00000001 +9.63,50.425,-3.594478151,50,0,10.00179579,0,0,0,90.00000001 +9.64,50.425,-3.594476743,50,0,10.00090751,0,0,0,90.00000001 +9.65,50.425,-3.594475336,50,0,9.999575095,0,0,0,90.00000001 +9.66,50.425,-3.594473929,50,0,9.998686817,0,0,0,90.00000001 +9.67,50.425,-3.594472522,50,0,9.998686816,0,0,0,90.00000001 +9.68,50.425,-3.594471115,50,0,9.999575095,0,0,0,90.00000001 +9.69,50.425,-3.594469708,50,0,10.00068544,0,0,0,90.00000001 +9.7,50.425,-3.5944683,50,0,10.00068544,0,0,0,90.00000001 +9.71,50.425,-3.594466893,50,0,9.999575096,0,0,0,90.00000001 +9.72,50.425,-3.594465486,50,0,9.998908886,0,0,0,90.00000001 +9.73,50.425,-3.594464079,50,0,9.999575095,0,0,0,90.00000001 +9.74,50.425,-3.594462672,50,0,10.00068544,0,0,0,90.00000001 +9.75,50.425,-3.594461264,50,0,10.00068544,0,0,0,90.00000001 +9.76,50.425,-3.594459857,50,0,9.999575096,0,0,0,90.00000001 +9.77,50.425,-3.59445845,50,0,9.998686816,0,0,0,90.00000001 +9.78,50.425,-3.594457043,50,0,9.998686816,0,0,0,90.00000001 +9.79,50.425,-3.594455636,50,0,9.999575095,0,0,0,90.00000001 +9.8,50.425,-3.594454229,50,0,10.00090751,0,0,0,90.00000001 +9.81,50.425,-3.594452821,50,0,10.00179579,0,0,0,90.00000001 +9.82,50.425,-3.594451414,50,0,10.00179579,0,0,0,90.00000001 +9.83,50.425,-3.594450006,50,0,10.00090751,0,0,0,90.00000001 +9.84,50.425,-3.594448599,50,0,9.999575096,0,0,0,90.00000001 +9.85,50.425,-3.594447192,50,0,9.998908886,0,0,0,90.00000001 +9.86,50.425,-3.594445785,50,0,9.999575095,0,0,0,90.00000001 +9.87,50.425,-3.594444378,50,0,10.00068544,0,0,0,90.00000001 +9.88,50.425,-3.59444297,50,0,10.00068544,0,0,0,90.00000001 +9.89,50.425,-3.594441563,50,0,9.999575095,0,0,0,90.00000001 +9.9,50.425,-3.594440156,50,0,9.998686817,0,0,0,90.00000001 +9.91,50.425,-3.594438749,50,0,9.998686818,0,0,0,90.00000001 +9.92,50.425,-3.594437342,50,0,9.999575096,0,0,0,90.00000001 +9.93,50.425,-3.594435935,50,0,10.00068544,0,0,0,90.00000001 +9.94,50.425,-3.594434527,50,0,10.00068544,0,0,0,90.00000001 +9.95,50.425,-3.59443312,50,0,9.999575096,0,0,0,90.00000001 +9.96,50.425,-3.594431713,50,0,9.998908887,0,0,0,90.00000001 +9.97,50.425,-3.594430306,50,0,9.999575096,0,0,0,90.00000001 +9.98,50.425,-3.594428899,50,0,10.00068544,0,0,0,90.00000001 +9.99,50.425,-3.594427491,50,0,10.00112958,0,0,0,90.00000001 +10,50.425,-3.594426084,50,0,10.002462,0,0,0,90.00000001 +10.01,50.425,-3.594424677,50,0,10.0075696,0,0,0,90.00000001 +10.02,50.425,-3.594423268,50,0,10.01645239,0,0,0,90.00000001 +10.03,50.425,-3.594421858,50,0,10.0266676,0,0,0,90.00000001 +10.04,50.425,-3.594420446,50,0,10.03621659,0,0,0,90.00000001 +10.05,50.425,-3.594419033,50,0,10.04465524,0,0,0,90.00000001 +10.06,50.425,-3.594417619,50,0,10.05331596,0,0,0,90.00000001 +10.07,50.425,-3.594416204,50,0,10.06375323,0,0,0,90.00000001 +10.08,50.425,-3.594414787,50,0,10.07530085,0,0,0,90.00000001 +10.09,50.425,-3.594413368,50,0,10.0859602,0,0,0,90.00000001 +10.1,50.425,-3.594411948,50,0,10.09550919,0,0,0,90.00000001 +10.11,50.425,-3.594410527,50,0,10.10505819,0,0,0,90.00000001 +10.12,50.425,-3.594409104,50,0,10.11460718,0,0,0,90.00000001 +10.13,50.425,-3.59440768,50,0,10.12415618,0,0,0,90.00000001 +10.14,50.425,-3.594406255,50,0,10.13459345,0,0,0,90.00000001 +10.15,50.425,-3.594404828,50,0,10.14547487,0,0,0,90.00000001 +10.16,50.425,-3.594403399,50,0,10.15569007,0,0,0,90.00000001 +10.17,50.425,-3.59440197,50,0,10.16546114,0,0,0,90.00000001 +10.18,50.425,-3.594400538,50,0,10.17501013,0,0,0,90.00000001 +10.19,50.425,-3.594399106,50,0,10.18433706,0,0,0,90.00000001 +10.2,50.425,-3.594397672,50,0,10.19433019,0,0,0,90.00000001 +10.21,50.425,-3.594396237,50,0,10.20543368,0,0,0,90.00000001 +10.22,50.425,-3.5943948,50,0,10.21631509,0,0,0,90.00000001 +10.23,50.425,-3.594393361,50,0,10.22564202,0,0,0,90.00000001 +10.24,50.425,-3.594391922,50,0,10.23430273,0,0,0,90.00000001 +10.25,50.425,-3.594390481,50,0,10.2440738,0,0,0,90.00000001 +10.26,50.425,-3.594389039,50,0,10.25539935,0,0,0,90.00000001 +10.27,50.425,-3.594387595,50,0,10.26694698,0,0,0,90.00000001 +10.28,50.425,-3.594386149,50,0,10.27671804,0,0,0,90.00000001 +10.29,50.425,-3.594384702,50,0,10.28515669,0,0,0,90.00000001 +10.3,50.425,-3.594383255,50,0,10.29470568,0,0,0,90.00000001 +10.31,50.425,-3.594381805,50,0,10.30536503,0,0,0,90.00000001 +10.32,50.425,-3.594380354,50,0,10.31558023,0,0,0,90.00000001 +10.33,50.425,-3.594378902,50,0,10.32557337,0,0,0,90.00000001 +10.34,50.425,-3.594377448,50,0,10.33578857,0,0,0,90.00000001 +10.35,50.425,-3.594375993,50,0,10.34555964,0,0,0,90.00000001 +10.36,50.425,-3.594374536,50,0,10.35510863,0,0,0,90.00000001 +10.37,50.425,-3.594373079,50,0,10.36554591,0,0,0,90.00000001 +10.38,50.425,-3.594371619,50,0,10.37620525,0,0,0,90.00000001 +10.39,50.425,-3.594370158,50,0,10.38553218,0,0,0,90.00000001 +10.4,50.425,-3.594368696,50,0,10.3941929,0,0,0,90.00000001 +10.41,50.425,-3.594367233,50,0,10.40374189,0,0,0,90.00000001 +10.42,50.425,-3.594365768,50,0,10.41417917,0,0,0,90.00000001 +10.43,50.425,-3.594364302,50,0,10.42483851,0,0,0,90.00000001 +10.44,50.425,-3.594362834,50,0,10.43549785,0,0,0,90.00000001 +10.45,50.425,-3.594361365,50,0,10.4461572,0,0,0,90.00000001 +10.46,50.425,-3.594359894,50,0,10.45659447,0,0,0,90.00000001 +10.47,50.425,-3.594358422,50,0,10.46614347,0,0,0,90.00000001 +10.48,50.425,-3.594356948,50,0,10.47480419,0,0,0,90.00000001 +10.49,50.425,-3.594355474,50,0,10.48413111,0,0,0,90.00000001 +10.5,50.425,-3.594353998,50,0,10.49501253,0,0,0,90.00000001 +10.51,50.425,-3.59435252,50,0,10.50633808,0,0,0,90.00000001 +10.52,50.425,-3.594351041,50,0,10.51699742,0,0,0,90.00000001 +10.53,50.425,-3.59434956,50,0,10.52676849,0,0,0,90.00000001 +10.54,50.425,-3.594348078,50,0,10.53609541,0,0,0,90.00000001 +10.55,50.425,-3.594346595,50,0,10.54564441,0,0,0,90.00000001 +10.56,50.425,-3.59434511,50,0,10.55519341,0,0,0,90.00000001 +10.57,50.425,-3.594343624,50,0,10.5647424,0,0,0,90.00000001 +10.58,50.425,-3.594342137,50,0,10.57517968,0,0,0,90.00000001 +10.59,50.425,-3.594340648,50,0,10.58583902,0,0,0,90.00000001 +10.6,50.425,-3.594339157,50,0,10.59538802,0,0,0,90.00000001 +10.61,50.425,-3.594337666,50,0,10.60493701,0,0,0,90.00000001 +10.62,50.425,-3.594336173,50,0,10.61559635,0,0,0,90.00000001 +10.63,50.425,-3.594334678,50,0,10.62603363,0,0,0,90.00000001 +10.64,50.425,-3.594333182,50,0,10.63558263,0,0,0,90.00000001 +10.65,50.425,-3.594331685,50,0,10.64535369,0,0,0,90.00000001 +10.66,50.425,-3.594330186,50,0,10.65579097,0,0,0,90.00000001 +10.67,50.425,-3.594328686,50,0,10.66622824,0,0,0,90.00000001 +10.68,50.425,-3.594327184,50,0,10.67599931,0,0,0,90.00000001 +10.69,50.425,-3.594325681,50,0,10.68532623,0,0,0,90.00000001 +10.7,50.425,-3.594324177,50,0,10.6950973,0,0,0,90.00000001 +10.71,50.425,-3.594322671,50,0,10.70553457,0,0,0,90.00000001 +10.72,50.425,-3.594321164,50,0,10.71597184,0,0,0,90.00000001 +10.73,50.425,-3.594319655,50,0,10.72574291,0,0,0,90.00000001 +10.74,50.425,-3.594318145,50,0,10.73529191,0,0,0,90.00000001 +10.75,50.425,-3.594316634,50,0,10.74572918,0,0,0,90.00000001 +10.76,50.425,-3.594315121,50,0,10.75638852,0,0,0,90.00000001 +10.77,50.425,-3.594313606,50,0,10.76593752,0,0,0,90.00000001 +10.78,50.425,-3.594312091,50,0,10.77548652,0,0,0,90.00000001 +10.79,50.425,-3.594310574,50,0,10.78614586,0,0,0,90.00000001 +10.8,50.425,-3.594309055,50,0,10.79658313,0,0,0,90.00000001 +10.81,50.425,-3.594307535,50,0,10.80613213,0,0,0,90.00000001 +10.82,50.425,-3.594306014,50,0,10.8159032,0,0,0,90.00000001 +10.83,50.425,-3.594304491,50,0,10.82634047,0,0,0,90.00000001 +10.84,50.425,-3.594302967,50,0,10.83677774,0,0,0,90.00000001 +10.85,50.425,-3.594301441,50,0,10.84654881,0,0,0,90.00000001 +10.86,50.425,-3.594299914,50,0,10.85565367,0,0,0,90.00000001 +10.87,50.425,-3.594298386,50,0,10.86453645,0,0,0,90.00000001 +10.88,50.425,-3.594296856,50,0,10.87386338,0,0,0,90.00000001 +10.89,50.425,-3.594295326,50,0,10.88430065,0,0,0,90.00000001 +10.9,50.425,-3.594293793,50,0,10.89540414,0,0,0,90.00000001 +10.91,50.425,-3.594292259,50,0,10.90650762,0,0,0,90.00000001 +10.92,50.425,-3.594290724,50,0,10.91738903,0,0,0,90.00000001 +10.93,50.425,-3.594289186,50,0,10.92693803,0,0,0,90.00000001 +10.94,50.425,-3.594287648,50,0,10.93537668,0,0,0,90.00000001 +10.95,50.425,-3.594286109,50,0,10.94514774,0,0,0,90.00000001 +10.96,50.425,-3.594284568,50,0,10.9564733,0,0,0,90.00000001 +10.97,50.425,-3.594283025,50,0,10.96713264,0,0,0,90.00000001 +10.98,50.425,-3.594281481,50,0,10.97668164,0,0,0,90.00000001 +10.99,50.425,-3.594279936,50,0,10.98623063,0,0,0,90.00000001 +11,50.425,-3.594278389,50,0,10.99577963,0,0,0,90.00000001 +11.01,50.425,-3.594276841,50,0,11.00532862,0,0,0,90.00000001 +11.02,50.425,-3.594275292,50,0,11.0157659,0,0,0,90.00000001 +11.03,50.425,-3.594273741,50,0,11.02642524,0,0,0,90.00000001 +11.04,50.425,-3.594272188,50,0,11.03597424,0,0,0,90.00000001 +11.05,50.425,-3.594270635,50,0,11.04552323,0,0,0,90.00000001 +11.06,50.425,-3.59426908,50,0,11.05618258,0,0,0,90.00000001 +11.07,50.425,-3.594267523,50,0,11.06661985,0,0,0,90.00000001 +11.08,50.425,-3.594265965,50,0,11.07616885,0,0,0,90.00000001 +11.09,50.425,-3.594264406,50,0,11.08571784,0,0,0,90.00000001 +11.1,50.425,-3.594262845,50,0,11.09548891,0,0,0,90.00000001 +11.11,50.425,-3.594261283,50,0,11.10570411,0,0,0,90.00000001 +11.12,50.425,-3.59425972,50,0,11.11658553,0,0,0,90.00000001 +11.13,50.425,-3.594258154,50,0,11.1270228,0,0,0,90.00000001 +11.14,50.425,-3.594256588,50,0,11.1365718,0,0,0,90.00000001 +11.15,50.425,-3.59425502,50,0,11.14634286,0,0,0,90.00000001 +11.16,50.425,-3.594253451,50,0,11.15655807,0,0,0,90.00000001 +11.17,50.425,-3.59425188,50,0,11.16632913,0,0,0,90.00000001 +11.18,50.425,-3.594250308,50,0,11.17565606,0,0,0,90.00000001 +11.19,50.425,-3.594248735,50,0,11.18542712,0,0,0,90.00000001 +11.2,50.425,-3.59424716,50,0,11.1958644,0,0,0,90.00000001 +11.21,50.425,-3.594245584,50,0,11.20630167,0,0,0,90.00000001 +11.22,50.425,-3.594244006,50,0,11.21607274,0,0,0,90.00000001 +11.23,50.425,-3.594242427,50,0,11.22562173,0,0,0,90.00000001 +11.24,50.425,-3.594240847,50,0,11.23605901,0,0,0,90.00000001 +11.25,50.425,-3.594239265,50,0,11.24671835,0,0,0,90.00000001 +11.26,50.425,-3.594237681,50,0,11.25626735,0,0,0,90.00000001 +11.27,50.425,-3.594236097,50,0,11.26581634,0,0,0,90.00000001 +11.28,50.425,-3.594234511,50,0,11.27647569,0,0,0,90.00000001 +11.29,50.425,-3.594232923,50,0,11.28691296,0,0,0,90.00000001 +11.3,50.425,-3.594231334,50,0,11.29646196,0,0,0,90.00000001 +11.31,50.425,-3.594229744,50,0,11.30601095,0,0,0,90.00000001 +11.32,50.425,-3.594228152,50,0,11.31578202,0,0,0,90.00000001 +11.33,50.425,-3.594226559,50,0,11.32599722,0,0,0,90.00000001 +11.34,50.425,-3.594224965,50,0,11.33687864,0,0,0,90.00000001 +11.35,50.425,-3.594223368,50,0,11.34731591,0,0,0,90.00000001 +11.36,50.425,-3.594221771,50,0,11.35664284,0,0,0,90.00000001 +11.37,50.425,-3.594220172,50,0,11.36552563,0,0,0,90.00000001 +11.38,50.425,-3.594218572,50,0,11.37485255,0,0,0,90.00000001 +11.39,50.425,-3.594216971,50,0,11.3855119,0,0,0,90.00000001 +11.4,50.425,-3.594215368,50,0,11.39705952,0,0,0,90.00000001 +11.41,50.425,-3.594213763,50,0,11.40771886,0,0,0,90.00000001 +11.42,50.425,-3.594212157,50,0,11.41726786,0,0,0,90.00000001 +11.43,50.425,-3.59421055,50,0,11.42681685,0,0,0,90.00000001 +11.44,50.425,-3.594208941,50,0,11.43636585,0,0,0,90.00000001 +11.45,50.425,-3.594207331,50,0,11.44569278,0,0,0,90.00000001 +11.46,50.425,-3.59420572,50,0,11.45546384,0,0,0,90.00000001 +11.47,50.425,-3.594204107,50,0,11.46590112,0,0,0,90.00000001 +11.48,50.425,-3.594202493,50,0,11.47656046,0,0,0,90.00000001 +11.49,50.425,-3.594200877,50,0,11.48699773,0,0,0,90.00000001 +11.5,50.425,-3.59419926,50,0,11.4967688,0,0,0,90.00000001 +11.51,50.425,-3.594197641,50,0,11.50609573,0,0,0,90.00000001 +11.52,50.425,-3.594196022,50,0,11.51586679,0,0,0,90.00000001 +11.53,50.425,-3.5941944,50,0,11.52630407,0,0,0,90.00000001 +11.54,50.425,-3.594192778,50,0,11.53674134,0,0,0,90.00000001 +11.55,50.425,-3.594191153,50,0,11.54673447,0,0,0,90.00000001 +11.56,50.425,-3.594189528,50,0,11.55672761,0,0,0,90.00000001 +11.57,50.425,-3.594187901,50,0,11.56672074,0,0,0,90.00000001 +11.58,50.425,-3.594186272,50,0,11.57604767,0,0,0,90.00000001 +11.59,50.425,-3.594184643,50,0,11.58559667,0,0,0,90.00000001 +11.6,50.425,-3.594183012,50,0,11.59647808,0,0,0,90.00000001 +11.61,50.425,-3.594181379,50,0,11.60780363,0,0,0,90.00000001 +11.62,50.425,-3.594179745,50,0,11.61846298,0,0,0,90.00000001 +11.63,50.425,-3.594178109,50,0,11.62801197,0,0,0,90.00000001 +11.64,50.425,-3.594176472,50,0,11.63667269,0,0,0,90.00000001 +11.65,50.425,-3.594174834,50,0,11.64599962,0,0,0,90.00000001 +11.66,50.425,-3.594173195,50,0,11.65643689,0,0,0,90.00000001 +11.67,50.425,-3.594171553,50,0,11.66620796,0,0,0,90.00000001 +11.68,50.425,-3.594169911,50,0,11.67553488,0,0,0,90.00000001 +11.69,50.425,-3.594168268,50,0,11.68619423,0,0,0,90.00000001 +11.7,50.425,-3.594166622,50,0,11.69685357,0,0,0,90.00000001 +11.71,50.425,-3.594164975,50,0,11.7061805,0,0,0,90.00000001 +11.72,50.425,-3.594163328,50,0,11.71617363,0,0,0,90.00000001 +11.73,50.425,-3.594161678,50,0,11.72749919,0,0,0,90.00000001 +11.74,50.425,-3.594160027,50,0,11.73815853,0,0,0,90.00000001 +11.75,50.425,-3.594158374,50,0,11.74770752,0,0,0,90.00000001 +11.76,50.425,-3.594156721,50,0,11.75703445,0,0,0,90.00000001 +11.77,50.425,-3.594155065,50,0,11.76591724,0,0,0,90.00000001 +11.78,50.425,-3.594153409,50,0,11.77502209,0,0,0,90.00000001 +11.79,50.425,-3.594151752,50,0,11.78590351,0,0,0,90.00000001 +11.8,50.425,-3.594150092,50,0,11.79745113,0,0,0,90.00000001 +11.81,50.425,-3.594148431,50,0,11.8078884,0,0,0,90.00000001 +11.82,50.425,-3.594146769,50,0,11.81765947,0,0,0,90.00000001 +11.83,50.425,-3.594145105,50,0,11.82720847,0,0,0,90.00000001 +11.84,50.425,-3.59414344,50,0,11.83653539,0,0,0,90.00000001 +11.85,50.425,-3.594141774,50,0,11.84630646,0,0,0,90.00000001 +11.86,50.425,-3.594140106,50,0,11.85674373,0,0,0,90.00000001 +11.87,50.425,-3.594138437,50,0,11.86718101,0,0,0,90.00000001 +11.88,50.425,-3.594136766,50,0,11.87695207,0,0,0,90.00000001 +11.89,50.425,-3.594135094,50,0,11.886279,0,0,0,90.00000001 +11.9,50.425,-3.594133421,50,0,11.89605006,0,0,0,90.00000001 +11.91,50.425,-3.594131746,50,0,11.90648734,0,0,0,90.00000001 +11.92,50.425,-3.59413007,50,0,11.91714668,0,0,0,90.00000001 +11.93,50.425,-3.594128392,50,0,11.92758395,0,0,0,90.00000001 +11.94,50.425,-3.594126713,50,0,11.93735502,0,0,0,90.00000001 +11.95,50.425,-3.594125032,50,0,11.94668195,0,0,0,90.00000001 +11.96,50.425,-3.594123351,50,0,11.95645301,0,0,0,90.00000001 +11.97,50.425,-3.594121667,50,0,11.96689029,0,0,0,90.00000001 +11.98,50.425,-3.594119983,50,0,11.97732756,0,0,0,90.00000001 +11.99,50.425,-3.594118296,50,0,11.98709863,0,0,0,90.00000001 +12,50.425,-3.594116609,50,0,11.99642555,0,0,0,90.00000001 +12.01,50.425,-3.59411492,50,0,12.00619662,0,0,0,90.00000001 +12.02,50.425,-3.59411323,50,0,12.01663389,0,0,0,90.00000001 +12.03,50.425,-3.594111538,50,0,12.02729324,0,0,0,90.00000001 +12.04,50.425,-3.594109845,50,0,12.03773051,0,0,0,90.00000001 +12.05,50.425,-3.59410815,50,0,12.04750158,0,0,0,90.00000001 +12.06,50.425,-3.594106454,50,0,12.0568285,0,0,0,90.00000001 +12.07,50.425,-3.594104757,50,0,12.06659957,0,0,0,90.00000001 +12.08,50.425,-3.594103058,50,0,12.07703684,0,0,0,90.00000001 +12.09,50.425,-3.594101358,50,0,12.08747412,0,0,0,90.00000001 +12.1,50.425,-3.594099656,50,0,12.09724518,0,0,0,90.00000001 +12.11,50.425,-3.594097953,50,0,12.10679418,0,0,0,90.00000001 +12.12,50.425,-3.594096249,50,0,12.11723145,0,0,0,90.00000001 +12.13,50.425,-3.594094543,50,0,12.1278908,0,0,0,90.00000001 +12.14,50.425,-3.594092835,50,0,12.13743979,0,0,0,90.00000001 +12.15,50.425,-3.594091127,50,0,12.14676672,0,0,0,90.00000001 +12.16,50.425,-3.594089417,50,0,12.15675985,0,0,0,90.00000001 +12.17,50.425,-3.594087705,50,0,12.16697506,0,0,0,90.00000001 +12.18,50.425,-3.594085993,50,0,12.1776344,0,0,0,90.00000001 +12.19,50.425,-3.594084278,50,0,12.18829375,0,0,0,90.00000001 +12.2,50.425,-3.594082562,50,0,12.19762067,0,0,0,90.00000001 +12.21,50.425,-3.594080845,50,0,12.20628139,0,0,0,90.00000001 +12.22,50.425,-3.594079127,50,0,12.21583039,0,0,0,90.00000001 +12.23,50.425,-3.594077407,50,0,12.22626766,0,0,0,90.00000001 +12.24,50.425,-3.594075686,50,0,12.236927,0,0,0,90.00000001 +12.25,50.425,-3.594073963,50,0,12.24758635,0,0,0,90.00000001 +12.26,50.425,-3.594072239,50,0,12.25824569,0,0,0,90.00000001 +12.27,50.425,-3.594070513,50,0,12.26868297,0,0,0,90.00000001 +12.28,50.425,-3.594068786,50,0,12.27823196,0,0,0,90.00000001 +12.29,50.425,-3.594067057,50,0,12.28689268,0,0,0,90.00000001 +12.3,50.425,-3.594065328,50,0,12.29621961,0,0,0,90.00000001 +12.31,50.425,-3.594063597,50,0,12.30687895,0,0,0,90.00000001 +12.32,50.425,-3.594061864,50,0,12.31731622,0,0,0,90.00000001 +12.33,50.425,-3.59406013,50,0,12.32708729,0,0,0,90.00000001 +12.34,50.425,-3.594058395,50,0,12.33752456,0,0,0,90.00000001 +12.35,50.425,-3.594056658,50,0,12.34818391,0,0,0,90.00000001 +12.36,50.425,-3.594054919,50,0,12.3577329,0,0,0,90.00000001 +12.37,50.425,-3.59405318,50,0,12.36705983,0,0,0,90.00000001 +12.38,50.425,-3.594051439,50,0,12.37705297,0,0,0,90.00000001 +12.39,50.425,-3.594049696,50,0,12.3870461,0,0,0,90.00000001 +12.4,50.425,-3.594047953,50,0,12.39703923,0,0,0,90.00000001 +12.41,50.425,-3.594046207,50,0,12.40747651,0,0,0,90.00000001 +12.42,50.425,-3.594044461,50,0,12.41791378,0,0,0,90.00000001 +12.43,50.425,-3.594042712,50,0,12.42768485,0,0,0,90.00000001 +12.44,50.425,-3.594040963,50,0,12.43701177,0,0,0,90.00000001 +12.45,50.425,-3.594039212,50,0,12.44678284,0,0,0,90.00000001 +12.46,50.425,-3.59403746,50,0,12.45722011,0,0,0,90.00000001 +12.47,50.425,-3.594035706,50,0,12.46787946,0,0,0,90.00000001 +12.48,50.425,-3.594033951,50,0,12.47831673,0,0,0,90.00000001 +12.49,50.425,-3.594032194,50,0,12.4880878,0,0,0,90.00000001 +12.5,50.425,-3.594030436,50,0,12.49741473,0,0,0,90.00000001 +12.51,50.425,-3.594028677,50,0,12.50718579,0,0,0,90.00000001 +12.52,50.425,-3.594026916,50,0,12.51762307,0,0,0,90.00000001 +12.53,50.425,-3.594025154,50,0,12.52806034,0,0,0,90.00000001 +12.54,50.425,-3.59402339,50,0,12.5378314,0,0,0,90.00000001 +12.55,50.425,-3.594021625,50,0,12.54715833,0,0,0,90.00000001 +12.56,50.425,-3.594019859,50,0,12.5569294,0,0,0,90.00000001 +12.57,50.425,-3.594018091,50,0,12.56736667,0,0,0,90.00000001 +12.58,50.425,-3.594016322,50,0,12.57780394,0,0,0,90.00000001 +12.59,50.425,-3.594014551,50,0,12.58757501,0,0,0,90.00000001 +12.6,50.425,-3.594012779,50,0,12.59712401,0,0,0,90.00000001 +12.61,50.425,-3.594011006,50,0,12.60756128,0,0,0,90.00000001 +12.62,50.425,-3.594009231,50,0,12.61822062,0,0,0,90.00000001 +12.63,50.425,-3.594007454,50,0,12.62776962,0,0,0,90.00000001 +12.64,50.425,-3.594005677,50,0,12.63731862,0,0,0,90.00000001 +12.65,50.425,-3.594003898,50,0,12.64797796,0,0,0,90.00000001 +12.66,50.425,-3.594002117,50,0,12.65819316,0,0,0,90.00000001 +12.67,50.425,-3.594000335,50,0,12.66707595,0,0,0,90.00000001 +12.68,50.425,-3.593998552,50,0,12.67662495,0,0,0,90.00000001 +12.69,50.425,-3.593996768,50,0,12.6879505,0,0,0,90.00000001 +12.7,50.425,-3.593994981,50,0,12.69883191,0,0,0,90.00000001 +12.71,50.425,-3.593993193,50,0,12.70793677,0,0,0,90.00000001 +12.72,50.425,-3.593991405,50,0,12.71704163,0,0,0,90.00000001 +12.73,50.425,-3.593989614,50,0,12.72725683,0,0,0,90.00000001 +12.74,50.425,-3.593987823,50,0,12.73769411,0,0,0,90.00000001 +12.75,50.425,-3.593986029,50,0,12.74746517,0,0,0,90.00000001 +12.76,50.425,-3.593984235,50,0,12.7567921,0,0,0,90.00000001 +12.77,50.425,-3.593982439,50,0,12.76678523,0,0,0,90.00000001 +12.78,50.425,-3.593980642,50,0,12.77788872,0,0,0,90.00000001 +12.79,50.425,-3.593978843,50,0,12.78877013,0,0,0,90.00000001 +12.8,50.425,-3.593977042,50,0,12.79831912,0,0,0,90.00000001 +12.81,50.425,-3.593975241,50,0,12.80764605,0,0,0,90.00000001 +12.82,50.425,-3.593973438,50,0,12.81763919,0,0,0,90.00000001 +12.83,50.425,-3.593971633,50,0,12.82785439,0,0,0,90.00000001 +12.84,50.425,-3.593969828,50,0,12.83851373,0,0,0,90.00000001 +12.85,50.425,-3.59396802,50,0,12.84917308,0,0,0,90.00000001 +12.86,50.425,-3.593966211,50,0,12.85850001,0,0,0,90.00000001 +12.87,50.425,-3.593964401,50,0,12.86716072,0,0,0,90.00000001 +12.88,50.425,-3.59396259,50,0,12.87670972,0,0,0,90.00000001 +12.89,50.425,-3.593960777,50,0,12.88714699,0,0,0,90.00000001 +12.9,50.425,-3.593958963,50,0,12.89758427,0,0,0,90.00000001 +12.91,50.425,-3.593957147,50,0,12.9075774,0,0,0,90.00000001 +12.92,50.425,-3.59395533,50,0,12.91779261,0,0,0,90.00000001 +12.93,50.425,-3.593953512,50,0,12.92867402,0,0,0,90.00000001 +12.94,50.425,-3.593951691,50,0,12.9391113,0,0,0,90.00000001 +12.95,50.425,-3.59394987,50,0,12.94843822,0,0,0,90.00000001 +12.96,50.425,-3.593948047,50,0,12.95754308,0,0,0,90.00000001 +12.97,50.425,-3.593946223,50,0,12.96753621,0,0,0,90.00000001 +12.98,50.425,-3.593944398,50,0,12.97841763,0,0,0,90.00000001 +12.99,50.425,-3.59394257,50,0,12.9888549,0,0,0,90.00000001 +13,50.425,-3.593940742,50,0,12.99818183,0,0,0,90.00000001 +13.01,50.425,-3.593938912,50,0,13.00728668,0,0,0,90.00000001 +13.02,50.425,-3.593937081,50,0,13.01727982,0,0,0,90.00000001 +13.03,50.425,-3.593935249,50,0,13.02816123,0,0,0,90.00000001 +13.04,50.425,-3.593933414,50,0,13.03859851,0,0,0,90.00000001 +13.05,50.425,-3.593931579,50,0,13.0481475,0,0,0,90.00000001 +13.06,50.425,-3.593929742,50,0,13.05791857,0,0,0,90.00000001 +13.07,50.425,-3.593927904,50,0,13.06835584,0,0,0,90.00000001 +13.08,50.425,-3.593926064,50,0,13.07879312,0,0,0,90.00000001 +13.09,50.425,-3.593924223,50,0,13.08834211,0,0,0,90.00000001 +13.1,50.425,-3.59392238,50,0,13.09700283,0,0,0,90.00000001 +13.11,50.425,-3.593920537,50,0,13.10632976,0,0,0,90.00000001 +13.12,50.425,-3.593918692,50,0,13.11721117,0,0,0,90.00000001 +13.13,50.425,-3.593916845,50,0,13.12853672,0,0,0,90.00000001 +13.14,50.425,-3.593914997,50,0,13.13919607,0,0,0,90.00000001 +13.15,50.425,-3.593913147,50,0,13.14896713,0,0,0,90.00000001 +13.16,50.425,-3.593911296,50,0,13.15829406,0,0,0,90.00000001 +13.17,50.425,-3.593909444,50,0,13.16806512,0,0,0,90.00000001 +13.18,50.425,-3.59390759,50,0,13.1785024,0,0,0,90.00000001 +13.19,50.425,-3.593905735,50,0,13.18893967,0,0,0,90.00000001 +13.2,50.425,-3.593903878,50,0,13.19871074,0,0,0,90.00000001 +13.21,50.425,-3.59390202,50,0,13.20803766,0,0,0,90.00000001 +13.22,50.425,-3.593900161,50,0,13.21780873,0,0,0,90.00000001 +13.23,50.425,-3.5938983,50,0,13.228246,0,0,0,90.00000001 +13.24,50.425,-3.593896438,50,0,13.23868328,0,0,0,90.00000001 +13.25,50.425,-3.593894574,50,0,13.24845434,0,0,0,90.00000001 +13.26,50.425,-3.593892709,50,0,13.25778127,0,0,0,90.00000001 +13.27,50.425,-3.593890843,50,0,13.26755233,0,0,0,90.00000001 +13.28,50.425,-3.593888975,50,0,13.27798961,0,0,0,90.00000001 +13.29,50.425,-3.593887106,50,0,13.28842688,0,0,0,90.00000001 +13.3,50.425,-3.593885235,50,0,13.29819795,0,0,0,90.00000001 +13.31,50.425,-3.593883363,50,0,13.30774694,0,0,0,90.00000001 +13.32,50.425,-3.59388149,50,0,13.31818422,0,0,0,90.00000001 +13.33,50.425,-3.593879615,50,0,13.32884356,0,0,0,90.00000001 +13.34,50.425,-3.593877738,50,0,13.33839256,0,0,0,90.00000001 +13.35,50.425,-3.593875861,50,0,13.34771949,0,0,0,90.00000001 +13.36,50.425,-3.593873982,50,0,13.35771262,0,0,0,90.00000001 +13.37,50.425,-3.593872101,50,0,13.36792782,0,0,0,90.00000001 +13.38,50.425,-3.59387022,50,0,13.37858717,0,0,0,90.00000001 +13.39,50.425,-3.593868336,50,0,13.38924651,0,0,0,90.00000001 +13.4,50.425,-3.593866451,50,0,13.39857344,0,0,0,90.00000001 +13.41,50.425,-3.593864565,50,0,13.40745623,0,0,0,90.00000001 +13.42,50.425,-3.593862678,50,0,13.41767143,0,0,0,90.00000001 +13.43,50.425,-3.593860789,50,0,13.42855284,0,0,0,90.00000001 +13.44,50.425,-3.593858898,50,0,13.43876805,0,0,0,90.00000001 +13.45,50.425,-3.593857007,50,0,13.44853911,0,0,0,90.00000001 +13.46,50.425,-3.593855113,50,0,13.45831018,0,0,0,90.00000001 +13.47,50.425,-3.593853219,50,0,13.46852538,0,0,0,90.00000001 +13.48,50.425,-3.593851323,50,0,13.4794068,0,0,0,90.00000001 +13.49,50.425,-3.593849425,50,0,13.48984407,0,0,0,90.00000001 +13.5,50.425,-3.593847526,50,0,13.49939307,0,0,0,90.00000001 +13.51,50.425,-3.593845626,50,0,13.50894206,0,0,0,90.00000001 +13.52,50.425,-3.593843724,50,0,13.51849106,0,0,0,90.00000001 +13.53,50.425,-3.593841821,50,0,13.52781799,0,0,0,90.00000001 +13.54,50.425,-3.593839917,50,0,13.53758905,0,0,0,90.00000001 +13.55,50.425,-3.593838011,50,0,13.54802633,0,0,0,90.00000001 +13.56,50.425,-3.593836104,50,0,13.5584636,0,0,0,90.00000001 +13.57,50.425,-3.593834195,50,0,13.56823467,0,0,0,90.00000001 +13.58,50.425,-3.593832285,50,0,13.57778366,0,0,0,90.00000001 +13.59,50.425,-3.593830374,50,0,13.58844301,0,0,0,90.00000001 +13.6,50.425,-3.593828461,50,0,13.59999063,0,0,0,90.00000001 +13.61,50.425,-3.593826546,50,0,13.6104279,0,0,0,90.00000001 +13.62,50.425,-3.59382463,50,0,13.61908862,0,0,0,90.00000001 +13.63,50.425,-3.593822713,50,0,13.62774934,0,0,0,90.00000001 +13.64,50.425,-3.593820795,50,0,13.63796454,0,0,0,90.00000001 +13.65,50.425,-3.593818875,50,0,13.64862389,0,0,0,90.00000001 +13.66,50.425,-3.593816953,50,0,13.65817288,0,0,0,90.00000001 +13.67,50.425,-3.593815031,50,0,13.66772188,0,0,0,90.00000001 +13.68,50.425,-3.593813107,50,0,13.67860329,0,0,0,90.00000001 +13.69,50.425,-3.593811181,50,0,13.68970677,0,0,0,90.00000001 +13.7,50.425,-3.593809254,50,0,13.69947784,0,0,0,90.00000001 +13.71,50.425,-3.593807325,50,0,13.70813856,0,0,0,90.00000001 +13.72,50.425,-3.593805396,50,0,13.71746548,0,0,0,90.00000001 +13.73,50.425,-3.593803465,50,0,13.7283469,0,0,0,90.00000001 +13.74,50.425,-3.593801532,50,0,13.73945038,0,0,0,90.00000001 +13.75,50.425,-3.593799598,50,0,13.74922144,0,0,0,90.00000001 +13.76,50.425,-3.593797662,50,0,13.75810423,0,0,0,90.00000001 +13.77,50.425,-3.593795726,50,0,13.76831944,0,0,0,90.00000001 +13.78,50.425,-3.593793788,50,0,13.78008913,0,0,0,90.00000001 +13.79,50.425,-3.593791847,50,0,13.7905264,0,0,0,90.00000001 +13.8,50.425,-3.593789906,50,0,13.79896505,0,0,0,90.00000001 +13.81,50.425,-3.593787964,50,0,13.80784784,0,0,0,90.00000001 +13.82,50.425,-3.59378602,50,0,13.81806304,0,0,0,90.00000001 +13.83,50.425,-3.593784075,50,0,13.82850032,0,0,0,90.00000001 +13.84,50.425,-3.593782128,50,0,13.83827138,0,0,0,90.00000001 +13.85,50.425,-3.59378018,50,0,13.84782038,0,0,0,90.00000001 +13.86,50.425,-3.593778231,50,0,13.85847972,0,0,0,90.00000001 +13.87,50.425,-3.59377628,50,0,13.87002734,0,0,0,90.00000001 +13.88,50.425,-3.593774327,50,0,13.88046462,0,0,0,90.00000001 +13.89,50.425,-3.593772373,50,0,13.88912534,0,0,0,90.00000001 +13.9,50.425,-3.593770418,50,0,13.89778605,0,0,0,90.00000001 +13.91,50.425,-3.593768462,50,0,13.90800126,0,0,0,90.00000001 +13.92,50.425,-3.593766504,50,0,13.91888267,0,0,0,90.00000001 +13.93,50.425,-3.593764544,50,0,13.92909788,0,0,0,90.00000001 +13.94,50.425,-3.593762584,50,0,13.93886894,0,0,0,90.00000001 +13.95,50.425,-3.593760621,50,0,13.94864001,0,0,0,90.00000001 +13.96,50.425,-3.593758658,50,0,13.95863314,0,0,0,90.00000001 +13.97,50.425,-3.593756693,50,0,13.96884835,0,0,0,90.00000001 +13.98,50.425,-3.593754726,50,0,13.97906355,0,0,0,90.00000001 +13.99,50.425,-3.593752759,50,0,13.9897229,0,0,0,90.00000001 +14,50.425,-3.593750789,50,0,14.00038224,0,0,0,90.00000001 +14.01,50.425,-3.593748818,50,0,14.00970917,0,0,0,90.00000001 +14.02,50.425,-3.593746846,50,0,14.01836988,0,0,0,90.00000001 +14.03,50.425,-3.593744873,50,0,14.02791888,0,0,0,90.00000001 +14.04,50.425,-3.593742898,50,0,14.03835615,0,0,0,90.00000001 +14.05,50.425,-3.593740922,50,0,14.0490155,0,0,0,90.00000001 +14.06,50.425,-3.593738944,50,0,14.05967484,0,0,0,90.00000001 +14.07,50.425,-3.593736965,50,0,14.07011212,0,0,0,90.00000001 +14.08,50.425,-3.593734984,50,0,14.07988318,0,0,0,90.00000001 +14.09,50.425,-3.593733002,50,0,14.08921011,0,0,0,90.00000001 +14.1,50.425,-3.593731019,50,0,14.0987591,0,0,0,90.00000001 +14.11,50.425,-3.593729034,50,0,14.10853017,0,0,0,90.00000001 +14.12,50.425,-3.593727048,50,0,14.11874537,0,0,0,90.00000001 +14.13,50.425,-3.593725061,50,0,14.12962679,0,0,0,90.00000001 +14.14,50.425,-3.593723071,50,0,14.14006406,0,0,0,90.00000001 +14.15,50.425,-3.593721081,50,0,14.14939099,0,0,0,90.00000001 +14.16,50.425,-3.593719089,50,0,14.15849584,0,0,0,90.00000001 +14.17,50.425,-3.593717096,50,0,14.16848898,0,0,0,90.00000001 +14.18,50.425,-3.593715102,50,0,14.17914832,0,0,0,90.00000001 +14.19,50.425,-3.593713105,50,0,14.18891939,0,0,0,90.00000001 +14.2,50.425,-3.593711108,50,0,14.19824631,0,0,0,90.00000001 +14.21,50.425,-3.59370911,50,0,14.20912773,0,0,0,90.00000001 +14.22,50.425,-3.593707109,50,0,14.22045328,0,0,0,90.00000001 +14.23,50.425,-3.593705107,50,0,14.23000228,0,0,0,90.00000001 +14.24,50.425,-3.593703104,50,0,14.23866299,0,0,0,90.00000001 +14.25,50.425,-3.5937011,50,0,14.24821199,0,0,0,90.00000001 +14.26,50.425,-3.593699094,50,0,14.25864926,0,0,0,90.00000001 +14.27,50.425,-3.593697087,50,0,14.26930861,0,0,0,90.00000001 +14.28,50.425,-3.593695078,50,0,14.27996795,0,0,0,90.00000001 +14.29,50.425,-3.593693068,50,0,14.29040523,0,0,0,90.00000001 +14.3,50.425,-3.593691056,50,0,14.30017629,0,0,0,90.00000001 +14.31,50.425,-3.593689043,50,0,14.30950322,0,0,0,90.00000001 +14.32,50.425,-3.593687029,50,0,14.31905221,0,0,0,90.00000001 +14.33,50.425,-3.593685013,50,0,14.32860121,0,0,0,90.00000001 +14.34,50.425,-3.593682996,50,0,14.33815021,0,0,0,90.00000001 +14.35,50.425,-3.593680978,50,0,14.34858748,0,0,0,90.00000001 +14.36,50.425,-3.593678958,50,0,14.35946889,0,0,0,90.00000001 +14.37,50.425,-3.593676936,50,0,14.36990617,0,0,0,90.00000001 +14.38,50.425,-3.593674914,50,0,14.38034344,0,0,0,90.00000001 +14.39,50.425,-3.593672889,50,0,14.39033658,0,0,0,90.00000001 +14.4,50.425,-3.593670863,50,0,14.39921936,0,0,0,90.00000001 +14.41,50.425,-3.593668837,50,0,14.40832422,0,0,0,90.00000001 +14.42,50.425,-3.593666808,50,0,14.41853942,0,0,0,90.00000001 +14.43,50.425,-3.593664779,50,0,14.4289767,0,0,0,90.00000001 +14.44,50.425,-3.593662747,50,0,14.43896984,0,0,0,90.00000001 +14.45,50.425,-3.593660715,50,0,14.44918504,0,0,0,90.00000001 +14.46,50.425,-3.593658681,50,0,14.46006645,0,0,0,90.00000001 +14.47,50.425,-3.593656645,50,0,14.47050373,0,0,0,90.00000001 +14.48,50.425,-3.593654608,50,0,14.48005272,0,0,0,90.00000001 +14.49,50.425,-3.59365257,50,0,14.48960172,0,0,0,90.00000001 +14.5,50.425,-3.59365053,50,0,14.49915072,0,0,0,90.00000001 +14.51,50.425,-3.593648489,50,0,14.50869971,0,0,0,90.00000001 +14.52,50.425,-3.593646447,50,0,14.51935906,0,0,0,90.00000001 +14.53,50.425,-3.593644403,50,0,14.53068461,0,0,0,90.00000001 +14.54,50.425,-3.593642357,50,0,14.54045567,0,0,0,90.00000001 +14.55,50.425,-3.59364031,50,0,14.54889432,0,0,0,90.00000001 +14.56,50.425,-3.593638263,50,0,14.55844332,0,0,0,90.00000001 +14.57,50.425,-3.593636213,50,0,14.56910266,0,0,0,90.00000001 +14.58,50.425,-3.593634162,50,0,14.57953993,0,0,0,90.00000001 +14.59,50.425,-3.59363211,50,0,14.59019928,0,0,0,90.00000001 +14.6,50.425,-3.593630056,50,0,14.60085862,0,0,0,90.00000001 +14.61,50.425,-3.593628,50,0,14.61018555,0,0,0,90.00000001 +14.62,50.425,-3.593625944,50,0,14.61884627,0,0,0,90.00000001 +14.63,50.425,-3.593623886,50,0,14.62839526,0,0,0,90.00000001 +14.64,50.425,-3.593621827,50,0,14.63883254,0,0,0,90.00000001 +14.65,50.425,-3.593619766,50,0,14.64949188,0,0,0,90.00000001 +14.66,50.425,-3.593617704,50,0,14.66015122,0,0,0,90.00000001 +14.67,50.425,-3.59361564,50,0,14.6705885,0,0,0,90.00000001 +14.68,50.425,-3.593613575,50,0,14.68035956,0,0,0,90.00000001 +14.69,50.425,-3.593611508,50,0,14.68990856,0,0,0,90.00000001 +14.7,50.425,-3.593609441,50,0,14.70012377,0,0,0,90.00000001 +14.71,50.425,-3.593607371,50,0,14.7101169,0,0,0,90.00000001 +14.72,50.425,-3.5936053,50,0,14.71922176,0,0,0,90.00000001 +14.73,50.425,-3.593603229,50,0,14.72899282,0,0,0,90.00000001 +14.74,50.425,-3.593601155,50,0,14.73965217,0,0,0,90.00000001 +14.75,50.425,-3.59359908,50,0,14.74986737,0,0,0,90.00000001 +14.76,50.425,-3.593597004,50,0,14.75986051,0,0,0,90.00000001 +14.77,50.425,-3.593594926,50,0,14.77007571,0,0,0,90.00000001 +14.78,50.425,-3.593592847,50,0,14.77984678,0,0,0,90.00000001 +14.79,50.425,-3.593590766,50,0,14.78939577,0,0,0,90.00000001 +14.8,50.425,-3.593588685,50,0,14.79983305,0,0,0,90.00000001 +14.81,50.425,-3.593586601,50,0,14.81071446,0,0,0,90.00000001 +14.82,50.425,-3.593584516,50,0,14.82092966,0,0,0,90.00000001 +14.83,50.425,-3.59358243,50,0,14.83070073,0,0,0,90.00000001 +14.84,50.425,-3.593580342,50,0,14.84024973,0,0,0,90.00000001 +14.85,50.425,-3.593578253,50,0,14.84957665,0,0,0,90.00000001 +14.86,50.425,-3.593576163,50,0,14.85912565,0,0,0,90.00000001 +14.87,50.425,-3.593574071,50,0,14.86867464,0,0,0,90.00000001 +14.88,50.425,-3.593571978,50,0,14.87822364,0,0,0,90.00000001 +14.89,50.425,-3.593569884,50,0,14.88888298,0,0,0,90.00000001 +14.9,50.425,-3.593567788,50,0,14.90043061,0,0,0,90.00000001 +14.91,50.425,-3.59356569,50,0,14.91108995,0,0,0,90.00000001 +14.92,50.425,-3.593563591,50,0,14.92063895,0,0,0,90.00000001 +14.93,50.425,-3.593561491,50,0,14.93018794,0,0,0,90.00000001 +14.94,50.425,-3.593559389,50,0,14.93973694,0,0,0,90.00000001 +14.95,50.425,-3.593557286,50,0,14.94906386,0,0,0,90.00000001 +14.96,50.425,-3.593555182,50,0,14.95883493,0,0,0,90.00000001 +14.97,50.425,-3.593553076,50,0,14.9692722,0,0,0,90.00000001 +14.98,50.425,-3.593550969,50,0,14.97993155,0,0,0,90.00000001 +14.99,50.425,-3.59354886,50,0,14.99059089,0,0,0,90.00000001 +15,50.425,-3.59354675,50,0,15.00102817,0,0,0,90.00000001 +15.01,50.425,-3.593544638,50,0,15.01079923,0,0,0,90.00000001 +15.02,50.425,-3.593542525,50,0,15.02012616,0,0,0,90.00000001 +15.03,50.425,-3.593540411,50,0,15.02989722,0,0,0,90.00000001 +15.04,50.425,-3.593538295,50,0,15.04011243,0,0,0,90.00000001 +15.05,50.425,-3.593536178,50,0,15.04988349,0,0,0,90.00000001 +15.06,50.425,-3.593534059,50,0,15.05943249,0,0,0,90.00000001 +15.07,50.425,-3.59353194,50,0,15.06986976,0,0,0,90.00000001 +15.08,50.425,-3.593529818,50,0,15.08075118,0,0,0,90.00000001 +15.09,50.425,-3.593527695,50,0,15.09074431,0,0,0,90.00000001 +15.1,50.425,-3.593525571,50,0,15.09984917,0,0,0,90.00000001 +15.11,50.425,-3.593523445,50,0,15.10917609,0,0,0,90.00000001 +15.12,50.425,-3.593521319,50,0,15.11961337,0,0,0,90.00000001 +15.13,50.425,-3.59351919,50,0,15.13049478,0,0,0,90.00000001 +15.14,50.425,-3.59351706,50,0,15.14070999,0,0,0,90.00000001 +15.15,50.425,-3.593514929,50,0,15.15048105,0,0,0,90.00000001 +15.16,50.425,-3.593512796,50,0,15.16003005,0,0,0,90.00000001 +15.17,50.425,-3.593510662,50,0,15.16957904,0,0,0,90.00000001 +15.18,50.425,-3.593508527,50,0,15.18001632,0,0,0,90.00000001 +15.19,50.425,-3.59350639,50,0,15.19067566,0,0,0,90.00000001 +15.2,50.425,-3.593504251,50,0,15.20022466,0,0,0,90.00000001 +15.21,50.425,-3.593502112,50,0,15.20977365,0,0,0,90.00000001 +15.22,50.425,-3.593499971,50,0,15.220433,0,0,0,90.00000001 +15.23,50.425,-3.593497828,50,0,15.23087027,0,0,0,90.00000001 +15.24,50.425,-3.593495684,50,0,15.24041927,0,0,0,90.00000001 +15.25,50.425,-3.593493539,50,0,15.24996826,0,0,0,90.00000001 +15.26,50.425,-3.593491392,50,0,15.25951726,0,0,0,90.00000001 +15.27,50.425,-3.593489244,50,0,15.26906626,0,0,0,90.00000001 +15.28,50.425,-3.593487095,50,0,15.2797256,0,0,0,90.00000001 +15.29,50.425,-3.593484944,50,0,15.29127322,0,0,0,90.00000001 +15.3,50.425,-3.593482791,50,0,15.30193257,0,0,0,90.00000001 +15.31,50.425,-3.593480637,50,0,15.31125949,0,0,0,90.00000001 +15.32,50.425,-3.593478482,50,0,15.32014228,0,0,0,90.00000001 +15.33,50.425,-3.593476325,50,0,15.3294692,0,0,0,90.00000001 +15.34,50.425,-3.593474168,50,0,15.33990648,0,0,0,90.00000001 +15.35,50.425,-3.593472008,50,0,15.35056582,0,0,0,90.00000001 +15.36,50.425,-3.593469847,50,0,15.36011482,0,0,0,90.00000001 +15.37,50.425,-3.593467685,50,0,15.36966382,0,0,0,90.00000001 +15.38,50.425,-3.593465522,50,0,15.38032316,0,0,0,90.00000001 +15.39,50.425,-3.593463356,50,0,15.39076043,0,0,0,90.00000001 +15.4,50.425,-3.59346119,50,0,15.40030943,0,0,0,90.00000001 +15.41,50.425,-3.593459022,50,0,15.41008049,0,0,0,90.00000001 +15.42,50.425,-3.593456853,50,0,15.4202957,0,0,0,90.00000001 +15.43,50.425,-3.593454682,50,0,15.43006676,0,0,0,90.00000001 +15.44,50.425,-3.59345251,50,0,15.43961576,0,0,0,90.00000001 +15.45,50.425,-3.593450337,50,0,15.45005304,0,0,0,90.00000001 +15.46,50.425,-3.593448162,50,0,15.46093445,0,0,0,90.00000001 +15.47,50.425,-3.593445985,50,0,15.47114965,0,0,0,90.00000001 +15.48,50.425,-3.593443808,50,0,15.48092072,0,0,0,90.00000001 +15.49,50.425,-3.593441628,50,0,15.49046971,0,0,0,90.00000001 +15.5,50.425,-3.593439448,50,0,15.50001871,0,0,0,90.00000001 +15.51,50.425,-3.593437266,50,0,15.51045598,0,0,0,90.00000001 +15.52,50.425,-3.593435083,50,0,15.52111533,0,0,0,90.00000001 +15.53,50.425,-3.593432897,50,0,15.53066433,0,0,0,90.00000001 +15.54,50.425,-3.593430712,50,0,15.54021332,0,0,0,90.00000001 +15.55,50.425,-3.593428524,50,0,15.55087266,0,0,0,90.00000001 +15.56,50.425,-3.593426335,50,0,15.56108787,0,0,0,90.00000001 +15.57,50.425,-3.593424144,50,0,15.56997066,0,0,0,90.00000001 +15.58,50.425,-3.593421953,50,0,15.57929758,0,0,0,90.00000001 +15.59,50.425,-3.59341976,50,0,15.590179,0,0,0,90.00000001 +15.6,50.425,-3.593417565,50,0,15.60128248,0,0,0,90.00000001 +15.61,50.425,-3.593415369,50,0,15.61127561,0,0,0,90.00000001 +15.62,50.425,-3.593413171,50,0,15.62060254,0,0,0,90.00000001 +15.63,50.425,-3.593410973,50,0,15.63015154,0,0,0,90.00000001 +15.64,50.425,-3.593408772,50,0,15.6399226,0,0,0,90.00000001 +15.65,50.425,-3.593406571,50,0,15.65013781,0,0,0,90.00000001 +15.66,50.425,-3.593404368,50,0,15.66101922,0,0,0,90.00000001 +15.67,50.425,-3.593402163,50,0,15.67145649,0,0,0,90.00000001 +15.68,50.425,-3.593399957,50,0,15.68100549,0,0,0,90.00000001 +15.69,50.425,-3.59339775,50,0,15.69077655,0,0,0,90.00000001 +15.7,50.425,-3.593395541,50,0,15.70121383,0,0,0,90.00000001 +15.71,50.425,-3.593393331,50,0,15.7116511,0,0,0,90.00000001 +15.72,50.425,-3.593391119,50,0,15.72142217,0,0,0,90.00000001 +15.73,50.425,-3.593388906,50,0,15.7307491,0,0,0,90.00000001 +15.74,50.425,-3.593386692,50,0,15.74052016,0,0,0,90.00000001 +15.75,50.425,-3.593384476,50,0,15.75073537,0,0,0,90.00000001 +15.76,50.425,-3.593382259,50,0,15.76050643,0,0,0,90.00000001 +15.77,50.425,-3.59338004,50,0,15.77005543,0,0,0,90.00000001 +15.78,50.425,-3.593377821,50,0,15.7804927,0,0,0,90.00000001 +15.79,50.425,-3.593375599,50,0,15.79137411,0,0,0,90.00000001 +15.8,50.425,-3.593373376,50,0,15.80136725,0,0,0,90.00000001 +15.81,50.425,-3.593371152,50,0,15.81047211,0,0,0,90.00000001 +15.82,50.425,-3.593368926,50,0,15.81979903,0,0,0,90.00000001 +15.83,50.425,-3.5933667,50,0,15.83023631,0,0,0,90.00000001 +15.84,50.425,-3.593364471,50,0,15.84111772,0,0,0,90.00000001 +15.85,50.425,-3.593362241,50,0,15.85133293,0,0,0,90.00000001 +15.86,50.425,-3.59336001,50,0,15.86132606,0,0,0,90.00000001 +15.87,50.425,-3.593357777,50,0,15.87176333,0,0,0,90.00000001 +15.88,50.425,-3.593355543,50,0,15.88197854,0,0,0,90.00000001 +15.89,50.425,-3.593353307,50,0,15.89086133,0,0,0,90.00000001 +15.9,50.425,-3.59335107,50,0,15.89929997,0,0,0,90.00000001 +15.91,50.425,-3.593348833,50,0,15.90973725,0,0,0,90.00000001 +15.92,50.425,-3.593346593,50,0,15.92150694,0,0,0,90.00000001 +15.93,50.425,-3.593344351,50,0,15.93172215,0,0,0,90.00000001 +15.94,50.425,-3.593342109,50,0,15.94060493,0,0,0,90.00000001 +15.95,50.425,-3.593339865,50,0,15.95015393,0,0,0,90.00000001 +15.96,50.425,-3.59333762,50,0,15.9605912,0,0,0,90.00000001 +15.97,50.425,-3.593335373,50,0,15.97125055,0,0,0,90.00000001 +15.98,50.425,-3.593333125,50,0,15.98168782,0,0,0,90.00000001 +15.99,50.425,-3.593330875,50,0,15.99145889,0,0,0,90.00000001 +16,50.425,-3.593328624,50,0,16.00078581,0,0,0,90.00000001 +16.01,50.425,-3.593326372,50,0,16.01033481,0,0,0,90.00000001 +16.02,50.425,-3.593324118,50,0,16.02010587,0,0,0,90.00000001 +16.03,50.425,-3.593321863,50,0,16.03032108,0,0,0,90.00000001 +16.04,50.425,-3.593319607,50,0,16.04120249,0,0,0,90.00000001 +16.05,50.425,-3.593317348,50,0,16.05163977,0,0,0,90.00000001 +16.06,50.425,-3.593315089,50,0,16.06118876,0,0,0,90.00000001 +16.07,50.425,-3.593312828,50,0,16.07095983,0,0,0,90.00000001 +16.08,50.425,-3.593310566,50,0,16.08117503,0,0,0,90.00000001 +16.09,50.425,-3.593308302,50,0,16.0909461,0,0,0,90.00000001 +16.1,50.425,-3.593306037,50,0,16.10049509,0,0,0,90.00000001 +16.11,50.425,-3.593303771,50,0,16.11093237,0,0,0,90.00000001 +16.12,50.425,-3.593301503,50,0,16.12181378,0,0,0,90.00000001 +16.13,50.425,-3.593299233,50,0,16.13202899,0,0,0,90.00000001 +16.14,50.425,-3.593296963,50,0,16.14180005,0,0,0,90.00000001 +16.15,50.425,-3.59329469,50,0,16.15134905,0,0,0,90.00000001 +16.16,50.425,-3.593292417,50,0,16.16067597,0,0,0,90.00000001 +16.17,50.425,-3.593290142,50,0,16.17044704,0,0,0,90.00000001 +16.18,50.425,-3.593287866,50,0,16.18088431,0,0,0,90.00000001 +16.19,50.425,-3.593285588,50,0,16.19154366,0,0,0,90.00000001 +16.2,50.425,-3.593283309,50,0,16.20198093,0,0,0,90.00000001 +16.21,50.425,-3.593281028,50,0,16.211752,0,0,0,90.00000001 +16.22,50.425,-3.593278746,50,0,16.22107892,0,0,0,90.00000001 +16.23,50.425,-3.593276463,50,0,16.23084999,0,0,0,90.00000001 +16.24,50.425,-3.593274178,50,0,16.24106519,0,0,0,90.00000001 +16.25,50.425,-3.593271892,50,0,16.25083626,0,0,0,90.00000001 +16.26,50.425,-3.593269604,50,0,16.26038526,0,0,0,90.00000001 +16.27,50.425,-3.593267316,50,0,16.27082253,0,0,0,90.00000001 +16.28,50.425,-3.593265025,50,0,16.28170394,0,0,0,90.00000001 +16.29,50.425,-3.593262733,50,0,16.29191915,0,0,0,90.00000001 +16.3,50.425,-3.59326044,50,0,16.30191228,0,0,0,90.00000001 +16.31,50.425,-3.593258145,50,0,16.31212749,0,0,0,90.00000001 +16.32,50.425,-3.593255849,50,0,16.32189855,0,0,0,90.00000001 +16.33,50.425,-3.593253551,50,0,16.33122548,0,0,0,90.00000001 +16.34,50.425,-3.593251253,50,0,16.34099654,0,0,0,90.00000001 +16.35,50.425,-3.593248952,50,0,16.35143382,0,0,0,90.00000001 +16.36,50.425,-3.593246651,50,0,16.36187109,0,0,0,90.00000001 +16.37,50.425,-3.593244347,50,0,16.37164216,0,0,0,90.00000001 +16.38,50.425,-3.593242043,50,0,16.38096908,0,0,0,90.00000001 +16.39,50.425,-3.593239737,50,0,16.39074015,0,0,0,90.00000001 +16.4,50.425,-3.59323743,50,0,16.40095535,0,0,0,90.00000001 +16.41,50.425,-3.593235121,50,0,16.41072642,0,0,0,90.00000001 +16.42,50.425,-3.593232811,50,0,16.42027542,0,0,0,90.00000001 +16.43,50.425,-3.5932305,50,0,16.43093476,0,0,0,90.00000001 +16.44,50.425,-3.593228187,50,0,16.44248238,0,0,0,90.00000001 +16.45,50.425,-3.593225872,50,0,16.45291966,0,0,0,90.00000001 +16.46,50.425,-3.593223556,50,0,16.46158037,0,0,0,90.00000001 +16.47,50.425,-3.593221239,50,0,16.47024109,0,0,0,90.00000001 +16.48,50.425,-3.593218921,50,0,16.48067837,0,0,0,90.00000001 +16.49,50.425,-3.593216601,50,0,16.49222599,0,0,0,90.00000001 +16.5,50.425,-3.593214279,50,0,16.50288533,0,0,0,90.00000001 +16.51,50.425,-3.593211956,50,0,16.51243433,0,0,0,90.00000001 +16.52,50.425,-3.593209632,50,0,16.52198332,0,0,0,90.00000001 +16.53,50.425,-3.593207306,50,0,16.53153232,0,0,0,90.00000001 +16.54,50.425,-3.593204979,50,0,16.54085925,0,0,0,90.00000001 +16.55,50.425,-3.593202651,50,0,16.55063031,0,0,0,90.00000001 +16.56,50.425,-3.593200321,50,0,16.56106758,0,0,0,90.00000001 +16.57,50.425,-3.59319799,50,0,16.57150486,0,0,0,90.00000001 +16.58,50.425,-3.593195657,50,0,16.58127593,0,0,0,90.00000001 +16.59,50.425,-3.593193323,50,0,16.59082492,0,0,0,90.00000001 +16.6,50.425,-3.593190988,50,0,16.60148426,0,0,0,90.00000001 +16.61,50.425,-3.593188651,50,0,16.61303189,0,0,0,90.00000001 +16.62,50.425,-3.593186312,50,0,16.62346916,0,0,0,90.00000001 +16.63,50.425,-3.593183972,50,0,16.63212988,0,0,0,90.00000001 +16.64,50.425,-3.593181631,50,0,16.6407906,0,0,0,90.00000001 +16.65,50.425,-3.593179289,50,0,16.6510058,0,0,0,90.00000001 +16.66,50.425,-3.593176945,50,0,16.66166515,0,0,0,90.00000001 +16.67,50.425,-3.593174599,50,0,16.67121414,0,0,0,90.00000001 +16.68,50.425,-3.593172253,50,0,16.68076314,0,0,0,90.00000001 +16.69,50.425,-3.593169905,50,0,16.69142248,0,0,0,90.00000001 +16.7,50.425,-3.593167555,50,0,16.70185976,0,0,0,90.00000001 +16.71,50.425,-3.593165204,50,0,16.71163082,0,0,0,90.00000001 +16.72,50.425,-3.593162852,50,0,16.72206809,0,0,0,90.00000001 +16.73,50.425,-3.593160498,50,0,16.73272744,0,0,0,90.00000001 +16.74,50.425,-3.593158142,50,0,16.74205436,0,0,0,90.00000001 +16.75,50.425,-3.593155786,50,0,16.75071508,0,0,0,90.00000001 +16.76,50.425,-3.593153428,50,0,16.76048615,0,0,0,90.00000001 +16.77,50.425,-3.593151069,50,0,16.77158963,0,0,0,90.00000001 +16.78,50.425,-3.593148708,50,0,16.78247104,0,0,0,90.00000001 +16.79,50.425,-3.593146345,50,0,16.79202004,0,0,0,90.00000001 +16.8,50.425,-3.593143982,50,0,16.80156904,0,0,0,90.00000001 +16.81,50.425,-3.593141617,50,0,16.81222838,0,0,0,90.00000001 +16.82,50.425,-3.59313925,50,0,16.82266565,0,0,0,90.00000001 +16.83,50.425,-3.593136882,50,0,16.83221465,0,0,0,90.00000001 +16.84,50.425,-3.593134513,50,0,16.84198572,0,0,0,90.00000001 +16.85,50.425,-3.593132142,50,0,16.85242299,0,0,0,90.00000001 +16.86,50.425,-3.59312977,50,0,16.86286027,0,0,0,90.00000001 +16.87,50.425,-3.593127396,50,0,16.87240926,0,0,0,90.00000001 +16.88,50.425,-3.593125021,50,0,16.88106998,0,0,0,90.00000001 +16.89,50.425,-3.593122645,50,0,16.8903969,0,0,0,90.00000001 +16.9,50.425,-3.593120268,50,0,16.90105625,0,0,0,90.00000001 +16.91,50.425,-3.593117888,50,0,16.91171559,0,0,0,90.00000001 +16.92,50.425,-3.593115508,50,0,16.9219308,0,0,0,90.00000001 +16.93,50.425,-3.593113126,50,0,16.932146,0,0,0,90.00000001 +16.94,50.425,-3.593110742,50,0,16.94213914,0,0,0,90.00000001 +16.95,50.425,-3.593108358,50,0,16.9519102,0,0,0,90.00000001 +16.96,50.425,-3.593105971,50,0,16.96168127,0,0,0,90.00000001 +16.97,50.425,-3.593103584,50,0,16.9716744,0,0,0,90.00000001 +16.98,50.425,-3.593101195,50,0,16.98188961,0,0,0,90.00000001 +16.99,50.425,-3.593098804,50,0,16.99210481,0,0,0,90.00000001 +17,50.425,-3.593096413,50,0,17.00276416,0,0,0,90.00000001 +17.01,50.425,-3.593094019,50,0,17.0134235,0,0,0,90.00000001 +17.02,50.425,-3.593091624,50,0,17.02275043,0,0,0,90.00000001 +17.03,50.425,-3.593089228,50,0,17.03141114,0,0,0,90.00000001 +17.04,50.425,-3.593086831,50,0,17.04096014,0,0,0,90.00000001 +17.05,50.425,-3.593084432,50,0,17.05139741,0,0,0,90.00000001 +17.06,50.425,-3.593082032,50,0,17.06205676,0,0,0,90.00000001 +17.07,50.425,-3.59307963,50,0,17.0727161,0,0,0,90.00000001 +17.08,50.425,-3.593077227,50,0,17.08315338,0,0,0,90.00000001 +17.09,50.425,-3.593074822,50,0,17.09292444,0,0,0,90.00000001 +17.1,50.425,-3.593072416,50,0,17.10225137,0,0,0,90.00000001 +17.11,50.425,-3.593070009,50,0,17.11180036,0,0,0,90.00000001 +17.12,50.425,-3.5930676,50,0,17.12134936,0,0,0,90.00000001 +17.13,50.425,-3.59306519,50,0,17.13067629,0,0,0,90.00000001 +17.14,50.425,-3.593062779,50,0,17.14066942,0,0,0,90.00000001 +17.15,50.425,-3.593060366,50,0,17.15199497,0,0,0,90.00000001 +17.16,50.425,-3.593057952,50,0,17.1635426,0,0,0,90.00000001 +17.17,50.425,-3.593055535,50,0,17.17353573,0,0,0,90.00000001 +17.18,50.425,-3.593053118,50,0,17.18264059,0,0,0,90.00000001 +17.19,50.425,-3.5930507,50,0,17.19241165,0,0,0,90.00000001 +17.2,50.425,-3.593048279,50,0,17.20173858,0,0,0,90.00000001 +17.21,50.425,-3.593045858,50,0,17.21017723,0,0,0,90.00000001 +17.22,50.425,-3.593043436,50,0,17.21994829,0,0,0,90.00000001 +17.23,50.425,-3.593041012,50,0,17.23149591,0,0,0,90.00000001 +17.24,50.425,-3.593038586,50,0,17.24304354,0,0,0,90.00000001 +17.25,50.425,-3.593036159,50,0,17.25370288,0,0,0,90.00000001 +17.26,50.425,-3.59303373,50,0,17.26347395,0,0,0,90.00000001 +17.27,50.425,-3.5930313,50,0,17.27280087,0,0,0,90.00000001 +17.28,50.425,-3.593028869,50,0,17.28257194,0,0,0,90.00000001 +17.29,50.425,-3.593026436,50,0,17.29278714,0,0,0,90.00000001 +17.3,50.425,-3.593024002,50,0,17.30255821,0,0,0,90.00000001 +17.31,50.425,-3.593021566,50,0,17.31188513,0,0,0,90.00000001 +17.32,50.425,-3.59301913,50,0,17.32143413,0,0,0,90.00000001 +17.33,50.425,-3.593016691,50,0,17.33120519,0,0,0,90.00000001 +17.34,50.425,-3.593014252,50,0,17.3414204,0,0,0,90.00000001 +17.35,50.425,-3.593011811,50,0,17.35230181,0,0,0,90.00000001 +17.36,50.425,-3.593009368,50,0,17.36273909,0,0,0,90.00000001 +17.37,50.425,-3.593006924,50,0,17.37228808,0,0,0,90.00000001 +17.38,50.425,-3.593004479,50,0,17.38205915,0,0,0,90.00000001 +17.39,50.425,-3.593002032,50,0,17.39249642,0,0,0,90.00000001 +17.4,50.425,-3.592999584,50,0,17.40315577,0,0,0,90.00000001 +17.41,50.425,-3.592997134,50,0,17.41381511,0,0,0,90.00000001 +17.42,50.425,-3.592994683,50,0,17.42425239,0,0,0,90.00000001 +17.43,50.425,-3.59299223,50,0,17.43380138,0,0,0,90.00000001 +17.44,50.425,-3.592989776,50,0,17.44224003,0,0,0,90.00000001 +17.45,50.425,-3.592987321,50,0,17.45090075,0,0,0,90.00000001 +17.46,50.425,-3.592984865,50,0,17.46111595,0,0,0,90.00000001 +17.47,50.425,-3.592982407,50,0,17.47199736,0,0,0,90.00000001 +17.48,50.425,-3.592979947,50,0,17.48221257,0,0,0,90.00000001 +17.49,50.425,-3.592977487,50,0,17.49220571,0,0,0,90.00000001 +17.5,50.425,-3.592975024,50,0,17.50264298,0,0,0,90.00000001 +17.51,50.425,-3.592972561,50,0,17.51308025,0,0,0,90.00000001 +17.52,50.425,-3.592970095,50,0,17.52285132,0,0,0,90.00000001 +17.53,50.425,-3.592967629,50,0,17.53217824,0,0,0,90.00000001 +17.54,50.425,-3.592965161,50,0,17.54194931,0,0,0,90.00000001 +17.55,50.425,-3.592962692,50,0,17.55238659,0,0,0,90.00000001 +17.56,50.425,-3.592960221,50,0,17.56282386,0,0,0,90.00000001 +17.57,50.425,-3.592957749,50,0,17.57259492,0,0,0,90.00000001 +17.58,50.425,-3.592955275,50,0,17.58214392,0,0,0,90.00000001 +17.59,50.425,-3.592952801,50,0,17.5925812,0,0,0,90.00000001 +17.6,50.425,-3.592950324,50,0,17.60346261,0,0,0,90.00000001 +17.61,50.425,-3.592947846,50,0,17.61345574,0,0,0,90.00000001 +17.62,50.425,-3.592945367,50,0,17.6225606,0,0,0,90.00000001 +17.63,50.425,-3.592942886,50,0,17.63188753,0,0,0,90.00000001 +17.64,50.425,-3.592940405,50,0,17.6423248,0,0,0,90.00000001 +17.65,50.425,-3.592937921,50,0,17.65320621,0,0,0,90.00000001 +17.66,50.425,-3.592935436,50,0,17.66342142,0,0,0,90.00000001 +17.67,50.425,-3.59293295,50,0,17.67319248,0,0,0,90.00000001 +17.68,50.425,-3.592930462,50,0,17.68274148,0,0,0,90.00000001 +17.69,50.425,-3.592927973,50,0,17.69206841,0,0,0,90.00000001 +17.7,50.425,-3.592925483,50,0,17.70183947,0,0,0,90.00000001 +17.71,50.425,-3.592922991,50,0,17.71227675,0,0,0,90.00000001 +17.72,50.425,-3.592920498,50,0,17.72293609,0,0,0,90.00000001 +17.73,50.425,-3.592918003,50,0,17.73337336,0,0,0,90.00000001 +17.74,50.425,-3.592915507,50,0,17.74314443,0,0,0,90.00000001 +17.75,50.425,-3.592913009,50,0,17.75247136,0,0,0,90.00000001 +17.76,50.425,-3.592910511,50,0,17.76224242,0,0,0,90.00000001 +17.77,50.425,-3.59290801,50,0,17.7726797,0,0,0,90.00000001 +17.78,50.425,-3.592905509,50,0,17.78311697,0,0,0,90.00000001 +17.79,50.425,-3.592903005,50,0,17.79288804,0,0,0,90.00000001 +17.8,50.425,-3.592900501,50,0,17.80221496,0,0,0,90.00000001 +17.81,50.425,-3.592897995,50,0,17.81198603,0,0,0,90.00000001 +17.82,50.425,-3.592895488,50,0,17.8224233,0,0,0,90.00000001 +17.83,50.425,-3.592892979,50,0,17.83308265,0,0,0,90.00000001 +17.84,50.425,-3.592890469,50,0,17.84351992,0,0,0,90.00000001 +17.85,50.425,-3.592887957,50,0,17.85329099,0,0,0,90.00000001 +17.86,50.425,-3.592885444,50,0,17.86261791,0,0,0,90.00000001 +17.87,50.425,-3.59288293,50,0,17.87238898,0,0,0,90.00000001 +17.88,50.425,-3.592880414,50,0,17.88282625,0,0,0,90.00000001 +17.89,50.425,-3.592877897,50,0,17.89326353,0,0,0,90.00000001 +17.9,50.425,-3.592875378,50,0,17.90303459,0,0,0,90.00000001 +17.91,50.425,-3.592872858,50,0,17.91258359,0,0,0,90.00000001 +17.92,50.425,-3.592870337,50,0,17.92302086,0,0,0,90.00000001 +17.93,50.425,-3.592867814,50,0,17.93368021,0,0,0,90.00000001 +17.94,50.425,-3.592865289,50,0,17.94300713,0,0,0,90.00000001 +17.95,50.425,-3.592862764,50,0,17.95188992,0,0,0,90.00000001 +17.96,50.425,-3.592860237,50,0,17.96232719,0,0,0,90.00000001 +17.97,50.425,-3.592857709,50,0,17.97365275,0,0,0,90.00000001 +17.98,50.425,-3.592855178,50,0,17.98364588,0,0,0,90.00000001 +17.99,50.425,-3.592852647,50,0,17.99275074,0,0,0,90.00000001 +18,50.425,-3.592850115,50,0,18.00274387,0,0,0,90.00000001 +18.01,50.425,-3.59284758,50,0,18.01295908,0,0,0,90.00000001 +18.02,50.425,-3.592845045,50,0,18.02250807,0,0,0,90.00000001 +18.03,50.425,-3.592842508,50,0,18.03227914,0,0,0,90.00000001 +18.04,50.425,-3.59283997,50,0,18.04271641,0,0,0,90.00000001 +18.05,50.425,-3.59283743,50,0,18.05337576,0,0,0,90.00000001 +18.06,50.425,-3.592834889,50,0,18.0640351,0,0,0,90.00000001 +18.07,50.425,-3.592832346,50,0,18.07447238,0,0,0,90.00000001 +18.08,50.425,-3.592829802,50,0,18.08402137,0,0,0,90.00000001 +18.09,50.425,-3.592827256,50,0,18.09268209,0,0,0,90.00000001 +18.1,50.425,-3.59282471,50,0,18.10200901,0,0,0,90.00000001 +18.11,50.425,-3.592822162,50,0,18.11266836,0,0,0,90.00000001 +18.12,50.425,-3.592819612,50,0,18.12310563,0,0,0,90.00000001 +18.13,50.425,-3.592817061,50,0,18.13265463,0,0,0,90.00000001 +18.14,50.425,-3.592814509,50,0,18.14242569,0,0,0,90.00000001 +18.15,50.425,-3.592811955,50,0,18.15286297,0,0,0,90.00000001 +18.16,50.425,-3.5928094,50,0,18.16352231,0,0,0,90.00000001 +18.17,50.425,-3.592806843,50,0,18.17418166,0,0,0,90.00000001 +18.18,50.425,-3.592804285,50,0,18.18461893,0,0,0,90.00000001 +18.19,50.425,-3.592801725,50,0,18.19416793,0,0,0,90.00000001 +18.2,50.425,-3.592799164,50,0,18.20282864,0,0,0,90.00000001 +18.21,50.425,-3.592796602,50,0,18.21215557,0,0,0,90.00000001 +18.22,50.425,-3.592794039,50,0,18.22281491,0,0,0,90.00000001 +18.23,50.425,-3.592791473,50,0,18.23325219,0,0,0,90.00000001 +18.24,50.425,-3.592788907,50,0,18.24280118,0,0,0,90.00000001 +18.25,50.425,-3.592786339,50,0,18.25257225,0,0,0,90.00000001 +18.26,50.425,-3.59278377,50,0,18.26300952,0,0,0,90.00000001 +18.27,50.425,-3.592781199,50,0,18.27366887,0,0,0,90.00000001 +18.28,50.425,-3.592778627,50,0,18.28410614,0,0,0,90.00000001 +18.29,50.425,-3.592776053,50,0,18.29387721,0,0,0,90.00000001 +18.3,50.425,-3.592773478,50,0,18.30320413,0,0,0,90.00000001 +18.31,50.425,-3.592770902,50,0,18.3129752,0,0,0,90.00000001 +18.32,50.425,-3.592768324,50,0,18.32341247,0,0,0,90.00000001 +18.33,50.425,-3.592765745,50,0,18.33384975,0,0,0,90.00000001 +18.34,50.425,-3.592763164,50,0,18.34362081,0,0,0,90.00000001 +18.35,50.425,-3.592760582,50,0,18.35294774,0,0,0,90.00000001 +18.36,50.425,-3.592757999,50,0,18.3627188,0,0,0,90.00000001 +18.37,50.425,-3.592755414,50,0,18.37315608,0,0,0,90.00000001 +18.38,50.425,-3.592752828,50,0,18.38381542,0,0,0,90.00000001 +18.39,50.425,-3.59275024,50,0,18.3942527,0,0,0,90.00000001 +18.4,50.425,-3.592747651,50,0,18.40402376,0,0,0,90.00000001 +18.41,50.425,-3.59274506,50,0,18.41335069,0,0,0,90.00000001 +18.42,50.425,-3.592742469,50,0,18.42289969,0,0,0,90.00000001 +18.43,50.425,-3.592739875,50,0,18.43267075,0,0,0,90.00000001 +18.44,50.425,-3.592737281,50,0,18.44288596,0,0,0,90.00000001 +18.45,50.425,-3.592734685,50,0,18.45376737,0,0,0,90.00000001 +18.46,50.425,-3.592732087,50,0,18.46420464,0,0,0,90.00000001 +18.47,50.425,-3.592729488,50,0,18.47375364,0,0,0,90.00000001 +18.48,50.425,-3.592726888,50,0,18.48330263,0,0,0,90.00000001 +18.49,50.425,-3.592724286,50,0,18.49285163,0,0,0,90.00000001 +18.5,50.425,-3.592721683,50,0,18.50240063,0,0,0,90.00000001 +18.51,50.425,-3.592719079,50,0,18.5128379,0,0,0,90.00000001 +18.52,50.425,-3.592716473,50,0,18.52371931,0,0,0,90.00000001 +18.53,50.425,-3.592713865,50,0,18.53393452,0,0,0,90.00000001 +18.54,50.425,-3.592711257,50,0,18.54370558,0,0,0,90.00000001 +18.55,50.425,-3.592708646,50,0,18.55325458,0,0,0,90.00000001 +18.56,50.425,-3.592706035,50,0,18.56280358,0,0,0,90.00000001 +18.57,50.425,-3.592703422,50,0,18.57346292,0,0,0,90.00000001 +18.58,50.425,-3.592700808,50,0,18.58478847,0,0,0,90.00000001 +18.59,50.425,-3.592698191,50,0,18.59455954,0,0,0,90.00000001 +18.6,50.425,-3.592695574,50,0,18.60299819,0,0,0,90.00000001 +18.61,50.425,-3.592692956,50,0,18.61276925,0,0,0,90.00000001 +18.62,50.425,-3.592690336,50,0,18.6240948,0,0,0,90.00000001 +18.63,50.425,-3.592687714,50,0,18.63475415,0,0,0,90.00000001 +18.64,50.425,-3.592685091,50,0,18.64430315,0,0,0,90.00000001 +18.65,50.425,-3.592682467,50,0,18.65385214,0,0,0,90.00000001 +18.66,50.425,-3.592679841,50,0,18.66340113,0,0,0,90.00000001 +18.67,50.425,-3.592677214,50,0,18.67272806,0,0,0,90.00000001 +18.68,50.425,-3.592674586,50,0,18.68249913,0,0,0,90.00000001 +18.69,50.425,-3.592671956,50,0,18.69315847,0,0,0,90.00000001 +18.7,50.425,-3.592669325,50,0,18.70448402,0,0,0,90.00000001 +18.71,50.425,-3.592666692,50,0,18.71536544,0,0,0,90.00000001 +18.72,50.425,-3.592664057,50,0,18.72469236,0,0,0,90.00000001 +18.73,50.425,-3.592661422,50,0,18.73335308,0,0,0,90.00000001 +18.74,50.425,-3.592658785,50,0,18.74290208,0,0,0,90.00000001 +18.75,50.425,-3.592656147,50,0,18.75333935,0,0,0,90.00000001 +18.76,50.425,-3.592653507,50,0,18.76377663,0,0,0,90.00000001 +18.77,50.425,-3.592650866,50,0,18.77354769,0,0,0,90.00000001 +18.78,50.425,-3.592648223,50,0,18.78309669,0,0,0,90.00000001 +18.79,50.425,-3.59264558,50,0,18.79353396,0,0,0,90.00000001 +18.8,50.425,-3.592642934,50,0,18.80419331,0,0,0,90.00000001 +18.81,50.425,-3.592640287,50,0,18.8137423,0,0,0,90.00000001 +18.82,50.425,-3.592637639,50,0,18.8232913,0,0,0,90.00000001 +18.83,50.425,-3.59263499,50,0,18.83395064,0,0,0,90.00000001 +18.84,50.425,-3.592632338,50,0,18.84438792,0,0,0,90.00000001 +18.85,50.425,-3.592629686,50,0,18.85393691,0,0,0,90.00000001 +18.86,50.425,-3.592627032,50,0,18.86370798,0,0,0,90.00000001 +18.87,50.425,-3.592624377,50,0,18.87414525,0,0,0,90.00000001 +18.88,50.425,-3.59262172,50,0,18.8848046,0,0,0,90.00000001 +18.89,50.425,-3.592619062,50,0,18.89524187,0,0,0,90.00000001 +18.9,50.425,-3.592616402,50,0,18.90479086,0,0,0,90.00000001 +18.91,50.425,-3.592613741,50,0,18.91345158,0,0,0,90.00000001 +18.92,50.425,-3.592611079,50,0,18.92277851,0,0,0,90.00000001 +18.93,50.425,-3.592608416,50,0,18.93343785,0,0,0,90.00000001 +18.94,50.425,-3.59260575,50,0,18.94387513,0,0,0,90.00000001 +18.95,50.425,-3.592603084,50,0,18.95342412,0,0,0,90.00000001 +18.96,50.425,-3.592600416,50,0,18.96319519,0,0,0,90.00000001 +18.97,50.425,-3.592597747,50,0,18.97363246,0,0,0,90.00000001 +18.98,50.425,-3.592595076,50,0,18.98429181,0,0,0,90.00000001 +18.99,50.425,-3.592592404,50,0,18.99472908,0,0,0,90.00000001 +19,50.425,-3.59258973,50,0,19.00450015,0,0,0,90.00000001 +19.01,50.425,-3.592587055,50,0,19.01382707,0,0,0,90.00000001 +19.02,50.425,-3.592584379,50,0,19.02359814,0,0,0,90.00000001 +19.03,50.425,-3.592581701,50,0,19.03403541,0,0,0,90.00000001 +19.04,50.425,-3.592579022,50,0,19.04447269,0,0,0,90.00000001 +19.05,50.425,-3.592576341,50,0,19.05424375,0,0,0,90.00000001 +19.06,50.425,-3.592573659,50,0,19.06357068,0,0,0,90.00000001 +19.07,50.425,-3.592570976,50,0,19.07334174,0,0,0,90.00000001 +19.08,50.425,-3.592568291,50,0,19.08377902,0,0,0,90.00000001 +19.09,50.425,-3.592565605,50,0,19.09421629,0,0,0,90.00000001 +19.1,50.425,-3.592562917,50,0,19.10420943,0,0,0,90.00000001 +19.11,50.425,-3.592560228,50,0,19.11442463,0,0,0,90.00000001 +19.12,50.425,-3.592557538,50,0,19.12508398,0,0,0,90.00000001 +19.13,50.425,-3.592554845,50,0,19.13485504,0,0,0,90.00000001 +19.14,50.425,-3.592552152,50,0,19.1439599,0,0,0,90.00000001 +19.15,50.425,-3.592549458,50,0,19.15395303,0,0,0,90.00000001 +19.16,50.425,-3.592546761,50,0,19.16439031,0,0,0,90.00000001 +19.17,50.425,-3.592544064,50,0,19.17460551,0,0,0,90.00000001 +19.18,50.425,-3.592541365,50,0,19.18459865,0,0,0,90.00000001 +19.19,50.425,-3.592538664,50,0,19.19392557,0,0,0,90.00000001 +19.2,50.425,-3.592535963,50,0,19.20347457,0,0,0,90.00000001 +19.21,50.425,-3.59253326,50,0,19.21413391,0,0,0,90.00000001 +19.22,50.425,-3.592530555,50,0,19.22457119,0,0,0,90.00000001 +19.23,50.425,-3.592527849,50,0,19.23412018,0,0,0,90.00000001 +19.24,50.425,-3.592525142,50,0,19.24389125,0,0,0,90.00000001 +19.25,50.425,-3.592522433,50,0,19.25432852,0,0,0,90.00000001 +19.26,50.425,-3.592519723,50,0,19.2647658,0,0,0,90.00000001 +19.27,50.425,-3.592517011,50,0,19.27453686,0,0,0,90.00000001 +19.28,50.425,-3.592514298,50,0,19.28386379,0,0,0,90.00000001 +19.29,50.425,-3.592511584,50,0,19.29363486,0,0,0,90.00000001 +19.3,50.425,-3.592508868,50,0,19.30407213,0,0,0,90.00000001 +19.31,50.425,-3.592506151,50,0,19.3145094,0,0,0,90.00000001 +19.32,50.425,-3.592503432,50,0,19.32428047,0,0,0,90.00000001 +19.33,50.425,-3.592500712,50,0,19.33360739,0,0,0,90.00000001 +19.34,50.425,-3.592497991,50,0,19.34337846,0,0,0,90.00000001 +19.35,50.425,-3.592495268,50,0,19.35381573,0,0,0,90.00000001 +19.36,50.425,-3.592492544,50,0,19.36447508,0,0,0,90.00000001 +19.37,50.425,-3.592489818,50,0,19.37513442,0,0,0,90.00000001 +19.38,50.425,-3.592487091,50,0,19.3855717,0,0,0,90.00000001 +19.39,50.425,-3.592484362,50,0,19.39512069,0,0,0,90.00000001 +19.4,50.425,-3.592481632,50,0,19.40378141,0,0,0,90.00000001 +19.41,50.425,-3.592478901,50,0,19.4133304,0,0,0,90.00000001 +19.42,50.425,-3.592476169,50,0,19.42487803,0,0,0,90.00000001 +19.43,50.425,-3.592473434,50,0,19.43642565,0,0,0,90.00000001 +19.44,50.425,-3.592470698,50,0,19.44597465,0,0,0,90.00000001 +19.45,50.425,-3.592467961,50,0,19.45463536,0,0,0,90.00000001 +19.46,50.425,-3.592465223,50,0,19.46396229,0,0,0,90.00000001 +19.47,50.425,-3.592462483,50,0,19.47351129,0,0,0,90.00000001 +19.48,50.425,-3.592459742,50,0,19.48306028,0,0,0,90.00000001 +19.49,50.425,-3.592457,50,0,19.49371963,0,0,0,90.00000001 +19.5,50.425,-3.592454256,50,0,19.50526725,0,0,0,90.00000001 +19.51,50.425,-3.59245151,50,0,19.51570452,0,0,0,90.00000001 +19.52,50.425,-3.592448763,50,0,19.52458731,0,0,0,90.00000001 +19.53,50.425,-3.592446015,50,0,19.53391424,0,0,0,90.00000001 +19.54,50.425,-3.592443266,50,0,19.54457358,0,0,0,90.00000001 +19.55,50.425,-3.592440514,50,0,19.55501085,0,0,0,90.00000001 +19.56,50.425,-3.592437762,50,0,19.56433778,0,0,0,90.00000001 +19.57,50.425,-3.592435008,50,0,19.57344264,0,0,0,90.00000001 +19.58,50.425,-3.592432253,50,0,19.58343577,0,0,0,90.00000001 +19.59,50.425,-3.592429497,50,0,19.59431719,0,0,0,90.00000001 +19.6,50.425,-3.592426738,50,0,19.60475446,0,0,0,90.00000001 +19.61,50.425,-3.592423979,50,0,19.61430346,0,0,0,90.00000001 +19.62,50.425,-3.592421218,50,0,19.62407452,0,0,0,90.00000001 +19.63,50.425,-3.592418456,50,0,19.6345118,0,0,0,90.00000001 +19.64,50.425,-3.592415692,50,0,19.64517114,0,0,0,90.00000001 +19.65,50.425,-3.592412927,50,0,19.65560841,0,0,0,90.00000001 +19.66,50.425,-3.59241016,50,0,19.66537948,0,0,0,90.00000001 +19.67,50.425,-3.592407392,50,0,19.6747064,0,0,0,90.00000001 +19.68,50.425,-3.592404623,50,0,19.68447747,0,0,0,90.00000001 +19.69,50.425,-3.592401852,50,0,19.69491475,0,0,0,90.00000001 +19.7,50.425,-3.59239908,50,0,19.70535202,0,0,0,90.00000001 +19.71,50.425,-3.592396306,50,0,19.71512309,0,0,0,90.00000001 +19.72,50.425,-3.592393531,50,0,19.72445001,0,0,0,90.00000001 +19.73,50.425,-3.592390755,50,0,19.73422108,0,0,0,90.00000001 +19.74,50.425,-3.592387977,50,0,19.74465835,0,0,0,90.00000001 +19.75,50.425,-3.592385198,50,0,19.75509562,0,0,0,90.00000001 +19.76,50.425,-3.592382417,50,0,19.76486669,0,0,0,90.00000001 +19.77,50.425,-3.592379635,50,0,19.77419362,0,0,0,90.00000001 +19.78,50.425,-3.592376852,50,0,19.78396468,0,0,0,90.00000001 +19.79,50.425,-3.592374067,50,0,19.79440196,0,0,0,90.00000001 +19.8,50.425,-3.592371281,50,0,19.80483923,0,0,0,90.00000001 +19.81,50.425,-3.592368493,50,0,19.8146103,0,0,0,90.00000001 +19.82,50.425,-3.592365704,50,0,19.82415929,0,0,0,90.00000001 +19.83,50.425,-3.592362914,50,0,19.83459657,0,0,0,90.00000001 +19.84,50.425,-3.592360122,50,0,19.84525591,0,0,0,90.00000001 +19.85,50.425,-3.592357328,50,0,19.85480491,0,0,0,90.00000001 +19.86,50.425,-3.592354534,50,0,19.8643539,0,0,0,90.00000001 +19.87,50.425,-3.592351738,50,0,19.87501325,0,0,0,90.00000001 +19.88,50.425,-3.59234894,50,0,19.88545052,0,0,0,90.00000001 +19.89,50.425,-3.592346141,50,0,19.89499952,0,0,0,90.00000001 +19.9,50.425,-3.592343341,50,0,19.90477058,0,0,0,90.00000001 +19.91,50.425,-3.592340539,50,0,19.91520786,0,0,0,90.00000001 +19.92,50.425,-3.592337736,50,0,19.92564513,0,0,0,90.00000001 +19.93,50.425,-3.592334931,50,0,19.9354162,0,0,0,90.00000001 +19.94,50.425,-3.592332125,50,0,19.94474312,0,0,0,90.00000001 +19.95,50.425,-3.592329318,50,0,19.95451419,0,0,0,90.00000001 +19.96,50.425,-3.592326509,50,0,19.96495146,0,0,0,90.00000001 +19.97,50.425,-3.592323699,50,0,19.97538874,0,0,0,90.00000001 +19.98,50.425,-3.592320887,50,0,19.98493773,0,0,0,90.00000001 +19.99,50.425,-3.592318074,50,0,19.99271017,0,0,0,90.00000001 +20,50.425,-3.59231526,50,0,19.9975957,0,0,0,90.00000001 +20.01,50.425,-3.592312445,50,0,19.99915019,0,0,0,90.00000001 +20.02,50.425,-3.592309631,50,0,19.99915019,0,0,0,90.00000001 +20.03,50.425,-3.592306817,50,0,19.99959433,0,0,0,90.00000001 +20.04,50.425,-3.592304002,50,0,20.00026054,0,0,0,90.00000001 +20.05,50.425,-3.592301188,50,0,20.00026054,0,0,0,90.00000001 +20.06,50.425,-3.592298373,50,0,19.99959433,0,0,0,90.00000001 +20.07,50.425,-3.592295559,50,0,19.99937226,0,0,0,90.00000001 +20.08,50.425,-3.592292745,50,0,20.00048261,0,0,0,90.00000001 +20.09,50.425,-3.59228993,50,0,20.00137089,0,0,0,90.00000001 +20.1,50.425,-3.592287115,50,0,20.00048261,0,0,0,90.00000001 +20.11,50.425,-3.592284301,50,0,19.99937226,0,0,0,90.00000001 +20.12,50.425,-3.592281487,50,0,19.99937226,0,0,0,90.00000001 +20.13,50.425,-3.592278672,50,0,19.99937226,0,0,0,90.00000001 +20.14,50.425,-3.592275858,50,0,19.99915019,0,0,0,90.00000001 +20.15,50.425,-3.592273044,50,0,19.99959433,0,0,0,90.00000001 +20.16,50.425,-3.592270229,50,0,20.00048261,0,0,0,90.00000001 +20.17,50.425,-3.592267415,50,0,20.00137089,0,0,0,90.00000001 +20.18,50.425,-3.5922646,50,0,20.00159296,0,0,0,90.00000001 +20.19,50.425,-3.592261785,50,0,20.00048261,0,0,0,90.00000001 +20.2,50.425,-3.592258971,50,0,19.99937226,0,0,0,90.00000001 +20.21,50.425,-3.592256157,50,0,19.99937226,0,0,0,90.00000001 +20.22,50.425,-3.592253342,50,0,19.99937226,0,0,0,90.00000001 +20.23,50.425,-3.592250528,50,0,19.99915019,0,0,0,90.00000001 +20.24,50.425,-3.592247714,50,0,19.99959433,0,0,0,90.00000001 +20.25,50.425,-3.592244899,50,0,20.00026054,0,0,0,90.00000001 +20.26,50.425,-3.592242085,50,0,20.00048261,0,0,0,90.00000001 +20.27,50.425,-3.59223927,50,0,20.00048261,0,0,0,90.00000001 +20.28,50.425,-3.592236456,50,0,20.00048261,0,0,0,90.00000001 +20.29,50.425,-3.592233641,50,0,20.00048261,0,0,0,90.00000001 +20.3,50.425,-3.592230827,50,0,20.00026054,0,0,0,90.00000001 +20.31,50.425,-3.592228012,50,0,19.99959433,0,0,0,90.00000001 +20.32,50.425,-3.592225198,50,0,19.99915019,0,0,0,90.00000001 +20.33,50.425,-3.592222384,50,0,19.99959433,0,0,0,90.00000001 +20.34,50.425,-3.592219569,50,0,20.00026054,0,0,0,90.00000001 +20.35,50.425,-3.592216755,50,0,20.00048261,0,0,0,90.00000001 +20.36,50.425,-3.59221394,50,0,20.00048261,0,0,0,90.00000001 +20.37,50.425,-3.592211126,50,0,20.00026054,0,0,0,90.00000001 +20.38,50.425,-3.592208311,50,0,19.99959433,0,0,0,90.00000001 +20.39,50.425,-3.592205497,50,0,19.99915019,0,0,0,90.00000001 +20.4,50.425,-3.592202683,50,0,19.99959433,0,0,0,90.00000001 +20.41,50.425,-3.592199868,50,0,20.00026054,0,0,0,90.00000001 +20.42,50.425,-3.592197054,50,0,20.00048261,0,0,0,90.00000001 +20.43,50.425,-3.592194239,50,0,20.00048261,0,0,0,90.00000001 +20.44,50.425,-3.592191425,50,0,20.00048261,0,0,0,90.00000001 +20.45,50.425,-3.59218861,50,0,20.00048261,0,0,0,90.00000001 +20.46,50.425,-3.592185796,50,0,20.00026054,0,0,0,90.00000001 +20.47,50.425,-3.592182981,50,0,19.99959433,0,0,0,90.00000001 +20.48,50.425,-3.592180167,50,0,19.99915019,0,0,0,90.00000001 +20.49,50.425,-3.592177353,50,0,19.99937226,0,0,0,90.00000001 +20.5,50.425,-3.592174538,50,0,19.99937226,0,0,0,90.00000001 +20.51,50.425,-3.592171724,50,0,19.99937226,0,0,0,90.00000001 +20.52,50.425,-3.59216891,50,0,20.00048261,0,0,0,90.00000001 +20.53,50.425,-3.592166095,50,0,20.00137089,0,0,0,90.00000001 +20.54,50.425,-3.59216328,50,0,20.00048261,0,0,0,90.00000001 +20.55,50.425,-3.592160466,50,0,19.99937226,0,0,0,90.00000001 +20.56,50.425,-3.592157652,50,0,19.99959433,0,0,0,90.00000001 +20.57,50.425,-3.592154837,50,0,20.00026054,0,0,0,90.00000001 +20.58,50.425,-3.592152023,50,0,20.00026054,0,0,0,90.00000001 +20.59,50.425,-3.592149208,50,0,19.99959433,0,0,0,90.00000001 +20.6,50.425,-3.592146394,50,0,19.99915019,0,0,0,90.00000001 +20.61,50.425,-3.59214358,50,0,19.99959433,0,0,0,90.00000001 +20.62,50.425,-3.592140765,50,0,20.00026054,0,0,0,90.00000001 +20.63,50.425,-3.592137951,50,0,20.00048261,0,0,0,90.00000001 +20.64,50.425,-3.592135136,50,0,20.00048261,0,0,0,90.00000001 +20.65,50.425,-3.592132322,50,0,20.00026054,0,0,0,90.00000001 +20.66,50.425,-3.592129507,50,0,19.99959433,0,0,0,90.00000001 +20.67,50.425,-3.592126693,50,0,19.99915019,0,0,0,90.00000001 +20.68,50.425,-3.592123879,50,0,19.99959433,0,0,0,90.00000001 +20.69,50.425,-3.592121064,50,0,20.00026054,0,0,0,90.00000001 +20.7,50.425,-3.59211825,50,0,20.00048261,0,0,0,90.00000001 +20.71,50.425,-3.592115435,50,0,20.00048261,0,0,0,90.00000001 +20.72,50.425,-3.592112621,50,0,20.00048261,0,0,0,90.00000001 +20.73,50.425,-3.592109806,50,0,20.00048261,0,0,0,90.00000001 +20.74,50.425,-3.592106992,50,0,20.00026054,0,0,0,90.00000001 +20.75,50.425,-3.592104177,50,0,19.99959433,0,0,0,90.00000001 +20.76,50.425,-3.592101363,50,0,19.99915019,0,0,0,90.00000001 +20.77,50.425,-3.592098549,50,0,19.99937226,0,0,0,90.00000001 +20.78,50.425,-3.592095734,50,0,19.99937226,0,0,0,90.00000001 +20.79,50.425,-3.59209292,50,0,19.99937226,0,0,0,90.00000001 +20.8,50.425,-3.592090106,50,0,20.00048261,0,0,0,90.00000001 +20.81,50.425,-3.592087291,50,0,20.00159296,0,0,0,90.00000001 +20.82,50.425,-3.592084476,50,0,20.00137089,0,0,0,90.00000001 +20.83,50.425,-3.592081662,50,0,20.00048261,0,0,0,90.00000001 +20.84,50.425,-3.592078847,50,0,19.99959433,0,0,0,90.00000001 +20.85,50.425,-3.592076033,50,0,19.99915019,0,0,0,90.00000001 +20.86,50.425,-3.592073219,50,0,19.99937226,0,0,0,90.00000001 +20.87,50.425,-3.592070404,50,0,19.99937226,0,0,0,90.00000001 +20.88,50.425,-3.59206759,50,0,19.99937226,0,0,0,90.00000001 +20.89,50.425,-3.592064776,50,0,20.00048261,0,0,0,90.00000001 +20.9,50.425,-3.592061961,50,0,20.00137089,0,0,0,90.00000001 +20.91,50.425,-3.592059146,50,0,20.00048261,0,0,0,90.00000001 +20.92,50.425,-3.592056332,50,0,19.99937226,0,0,0,90.00000001 +20.93,50.425,-3.592053518,50,0,19.99959433,0,0,0,90.00000001 +20.94,50.425,-3.592050703,50,0,20.00026054,0,0,0,90.00000001 +20.95,50.425,-3.592047889,50,0,20.00026054,0,0,0,90.00000001 +20.96,50.425,-3.592045074,50,0,19.99959433,0,0,0,90.00000001 +20.97,50.425,-3.59204226,50,0,19.99937226,0,0,0,90.00000001 +20.98,50.425,-3.592039446,50,0,20.00048261,0,0,0,90.00000001 +20.99,50.425,-3.592036631,50,0,20.00137089,0,0,0,90.00000001 +21,50.425,-3.592033816,50,0,20.00048261,0,0,0,90.00000001 +21.01,50.425,-3.592031002,50,0,19.99937226,0,0,0,90.00000001 +21.02,50.425,-3.592028188,50,0,19.99937226,0,0,0,90.00000001 +21.03,50.425,-3.592025373,50,0,19.99937226,0,0,0,90.00000001 +21.04,50.425,-3.592022559,50,0,19.99915019,0,0,0,90.00000001 +21.05,50.425,-3.592019745,50,0,19.99959433,0,0,0,90.00000001 +21.06,50.425,-3.59201693,50,0,20.00026054,0,0,0,90.00000001 +21.07,50.425,-3.592014116,50,0,20.00048261,0,0,0,90.00000001 +21.08,50.425,-3.592011301,50,0,20.00048261,0,0,0,90.00000001 +21.09,50.425,-3.592008487,50,0,20.00048261,0,0,0,90.00000001 +21.1,50.425,-3.592005672,50,0,20.00048261,0,0,0,90.00000001 +21.11,50.425,-3.592002858,50,0,20.00026054,0,0,0,90.00000001 +21.12,50.425,-3.592000043,50,0,19.99959433,0,0,0,90.00000001 +21.13,50.425,-3.591997229,50,0,19.99915019,0,0,0,90.00000001 +21.14,50.425,-3.591994415,50,0,19.99937226,0,0,0,90.00000001 +21.15,50.425,-3.5919916,50,0,19.99937226,0,0,0,90.00000001 +21.16,50.425,-3.591988786,50,0,19.99937226,0,0,0,90.00000001 +21.17,50.425,-3.591985972,50,0,20.00048261,0,0,0,90.00000001 +21.18,50.425,-3.591983157,50,0,20.00137089,0,0,0,90.00000001 +21.19,50.425,-3.591980342,50,0,20.00048261,0,0,0,90.00000001 +21.2,50.425,-3.591977528,50,0,19.99937226,0,0,0,90.00000001 +21.21,50.425,-3.591974714,50,0,19.99959433,0,0,0,90.00000001 +21.22,50.425,-3.591971899,50,0,20.00026054,0,0,0,90.00000001 +21.23,50.425,-3.591969085,50,0,20.00026054,0,0,0,90.00000001 +21.24,50.425,-3.59196627,50,0,19.99959433,0,0,0,90.00000001 +21.25,50.425,-3.591963456,50,0,19.99937226,0,0,0,90.00000001 +21.26,50.425,-3.591960642,50,0,20.00048261,0,0,0,90.00000001 +21.27,50.425,-3.591957827,50,0,20.00137089,0,0,0,90.00000001 +21.28,50.425,-3.591955012,50,0,20.00048261,0,0,0,90.00000001 +21.29,50.425,-3.591952198,50,0,19.99937226,0,0,0,90.00000001 +21.3,50.425,-3.591949384,50,0,19.99937226,0,0,0,90.00000001 +21.31,50.425,-3.591946569,50,0,19.99937226,0,0,0,90.00000001 +21.32,50.425,-3.591943755,50,0,19.99915019,0,0,0,90.00000001 +21.33,50.425,-3.591940941,50,0,19.99959433,0,0,0,90.00000001 +21.34,50.425,-3.591938126,50,0,20.00026054,0,0,0,90.00000001 +21.35,50.425,-3.591935312,50,0,20.00048261,0,0,0,90.00000001 +21.36,50.425,-3.591932497,50,0,20.00048261,0,0,0,90.00000001 +21.37,50.425,-3.591929683,50,0,20.00048261,0,0,0,90.00000001 +21.38,50.425,-3.591926868,50,0,20.00048261,0,0,0,90.00000001 +21.39,50.425,-3.591924054,50,0,20.00026054,0,0,0,90.00000001 +21.4,50.425,-3.591921239,50,0,19.99959433,0,0,0,90.00000001 +21.41,50.425,-3.591918425,50,0,19.99915019,0,0,0,90.00000001 +21.42,50.425,-3.591915611,50,0,19.99959433,0,0,0,90.00000001 +21.43,50.425,-3.591912796,50,0,20.00026054,0,0,0,90.00000001 +21.44,50.425,-3.591909982,50,0,20.00048261,0,0,0,90.00000001 +21.45,50.425,-3.591907167,50,0,20.00048261,0,0,0,90.00000001 +21.46,50.425,-3.591904353,50,0,20.00026054,0,0,0,90.00000001 +21.47,50.425,-3.591901538,50,0,19.99959433,0,0,0,90.00000001 +21.48,50.425,-3.591898724,50,0,19.99915019,0,0,0,90.00000001 +21.49,50.425,-3.59189591,50,0,19.99959433,0,0,0,90.00000001 +21.5,50.425,-3.591893095,50,0,20.00026054,0,0,0,90.00000001 +21.51,50.425,-3.591890281,50,0,20.00048261,0,0,0,90.00000001 +21.52,50.425,-3.591887466,50,0,20.00048261,0,0,0,90.00000001 +21.53,50.425,-3.591884652,50,0,20.00048261,0,0,0,90.00000001 +21.54,50.425,-3.591881837,50,0,20.00048261,0,0,0,90.00000001 +21.55,50.425,-3.591879023,50,0,20.00026054,0,0,0,90.00000001 +21.56,50.425,-3.591876208,50,0,19.99959433,0,0,0,90.00000001 +21.57,50.425,-3.591873394,50,0,19.99915019,0,0,0,90.00000001 +21.58,50.425,-3.59187058,50,0,19.99937226,0,0,0,90.00000001 +21.59,50.425,-3.591867765,50,0,19.99937226,0,0,0,90.00000001 +21.6,50.425,-3.591864951,50,0,19.99937226,0,0,0,90.00000001 +21.61,50.425,-3.591862137,50,0,20.00048261,0,0,0,90.00000001 +21.62,50.425,-3.591859322,50,0,20.00159296,0,0,0,90.00000001 +21.63,50.425,-3.591856507,50,0,20.00137089,0,0,0,90.00000001 +21.64,50.425,-3.591853693,50,0,20.00048261,0,0,0,90.00000001 +21.65,50.425,-3.591850878,50,0,19.99959433,0,0,0,90.00000001 +21.66,50.425,-3.591848064,50,0,19.99915019,0,0,0,90.00000001 +21.67,50.425,-3.59184525,50,0,19.99937226,0,0,0,90.00000001 +21.68,50.425,-3.591842435,50,0,19.99937226,0,0,0,90.00000001 +21.69,50.425,-3.591839621,50,0,19.99937226,0,0,0,90.00000001 +21.7,50.425,-3.591836807,50,0,20.00048261,0,0,0,90.00000001 +21.71,50.425,-3.591833992,50,0,20.00137089,0,0,0,90.00000001 +21.72,50.425,-3.591831177,50,0,20.00048261,0,0,0,90.00000001 +21.73,50.425,-3.591828363,50,0,19.99937226,0,0,0,90.00000001 +21.74,50.425,-3.591825549,50,0,19.99959433,0,0,0,90.00000001 +21.75,50.425,-3.591822734,50,0,20.00026054,0,0,0,90.00000001 +21.76,50.425,-3.59181992,50,0,20.00026054,0,0,0,90.00000001 +21.77,50.425,-3.591817105,50,0,19.99959433,0,0,0,90.00000001 +21.78,50.425,-3.591814291,50,0,19.99937226,0,0,0,90.00000001 +21.79,50.425,-3.591811477,50,0,20.00048261,0,0,0,90.00000001 +21.8,50.425,-3.591808662,50,0,20.00137089,0,0,0,90.00000001 +21.81,50.425,-3.591805847,50,0,20.00048261,0,0,0,90.00000001 +21.82,50.425,-3.591803033,50,0,19.99937226,0,0,0,90.00000001 +21.83,50.425,-3.591800219,50,0,19.99937226,0,0,0,90.00000001 +21.84,50.425,-3.591797404,50,0,19.99937226,0,0,0,90.00000001 +21.85,50.425,-3.59179459,50,0,19.99915019,0,0,0,90.00000001 +21.86,50.425,-3.591791776,50,0,19.99959433,0,0,0,90.00000001 +21.87,50.425,-3.591788961,50,0,20.00026054,0,0,0,90.00000001 +21.88,50.425,-3.591786147,50,0,20.00048261,0,0,0,90.00000001 +21.89,50.425,-3.591783332,50,0,20.00048261,0,0,0,90.00000001 +21.9,50.425,-3.591780518,50,0,20.00048261,0,0,0,90.00000001 +21.91,50.425,-3.591777703,50,0,20.00048261,0,0,0,90.00000001 +21.92,50.425,-3.591774889,50,0,20.00026054,0,0,0,90.00000001 +21.93,50.425,-3.591772074,50,0,19.99959433,0,0,0,90.00000001 +21.94,50.425,-3.59176926,50,0,19.99915019,0,0,0,90.00000001 +21.95,50.425,-3.591766446,50,0,19.99937226,0,0,0,90.00000001 +21.96,50.425,-3.591763631,50,0,19.99937226,0,0,0,90.00000001 +21.97,50.425,-3.591760817,50,0,19.99937226,0,0,0,90.00000001 +21.98,50.425,-3.591758003,50,0,20.00048261,0,0,0,90.00000001 +21.99,50.425,-3.591755188,50,0,20.00137089,0,0,0,90.00000001 +22,50.425,-3.591752373,50,0,20.00048261,0,0,0,90.00000001 +22.01,50.425,-3.591749559,50,0,19.99937226,0,0,0,90.00000001 +22.02,50.425,-3.591746745,50,0,19.99959433,0,0,0,90.00000001 +22.03,50.425,-3.59174393,50,0,20.00026054,0,0,0,90.00000001 +22.04,50.425,-3.591741116,50,0,20.00026054,0,0,0,90.00000001 +22.05,50.425,-3.591738301,50,0,19.99959433,0,0,0,90.00000001 +22.06,50.425,-3.591735487,50,0,19.99937226,0,0,0,90.00000001 +22.07,50.425,-3.591732673,50,0,20.00048261,0,0,0,90.00000001 +22.08,50.425,-3.591729858,50,0,20.00137089,0,0,0,90.00000001 +22.09,50.425,-3.591727043,50,0,20.00048261,0,0,0,90.00000001 +22.1,50.425,-3.591724229,50,0,19.99937226,0,0,0,90.00000001 +22.11,50.425,-3.591721415,50,0,19.99937226,0,0,0,90.00000001 +22.12,50.425,-3.5917186,50,0,19.99937226,0,0,0,90.00000001 +22.13,50.425,-3.591715786,50,0,19.99915019,0,0,0,90.00000001 +22.14,50.425,-3.591712972,50,0,19.99959433,0,0,0,90.00000001 +22.15,50.425,-3.591710157,50,0,20.00048261,0,0,0,90.00000001 +22.16,50.425,-3.591707343,50,0,20.00137089,0,0,0,90.00000001 +22.17,50.425,-3.591704528,50,0,20.00159296,0,0,0,90.00000001 +22.18,50.425,-3.591701713,50,0,20.00048261,0,0,0,90.00000001 +22.19,50.425,-3.591698899,50,0,19.99937226,0,0,0,90.00000001 +22.2,50.425,-3.591696085,50,0,19.99937226,0,0,0,90.00000001 +22.21,50.425,-3.59169327,50,0,19.99937226,0,0,0,90.00000001 +22.22,50.425,-3.591690456,50,0,19.99915019,0,0,0,90.00000001 +22.23,50.425,-3.591687642,50,0,19.99959433,0,0,0,90.00000001 +22.24,50.425,-3.591684827,50,0,20.00026054,0,0,0,90.00000001 +22.25,50.425,-3.591682013,50,0,20.00048261,0,0,0,90.00000001 +22.26,50.425,-3.591679198,50,0,20.00048261,0,0,0,90.00000001 +22.27,50.425,-3.591676384,50,0,20.00048261,0,0,0,90.00000001 +22.28,50.425,-3.591673569,50,0,20.00048261,0,0,0,90.00000001 +22.29,50.425,-3.591670755,50,0,20.00026054,0,0,0,90.00000001 +22.3,50.425,-3.59166794,50,0,19.99959433,0,0,0,90.00000001 +22.31,50.425,-3.591665126,50,0,19.99915019,0,0,0,90.00000001 +22.32,50.425,-3.591662312,50,0,19.99959433,0,0,0,90.00000001 +22.33,50.425,-3.591659497,50,0,20.00026054,0,0,0,90.00000001 +22.34,50.425,-3.591656683,50,0,20.00048261,0,0,0,90.00000001 +22.35,50.425,-3.591653868,50,0,20.00048261,0,0,0,90.00000001 +22.36,50.425,-3.591651054,50,0,20.00026054,0,0,0,90.00000001 +22.37,50.425,-3.591648239,50,0,19.99959433,0,0,0,90.00000001 +22.38,50.425,-3.591645425,50,0,19.99915019,0,0,0,90.00000001 +22.39,50.425,-3.591642611,50,0,19.99959433,0,0,0,90.00000001 +22.4,50.425,-3.591639796,50,0,20.00026054,0,0,0,90.00000001 +22.41,50.425,-3.591636982,50,0,20.00048261,0,0,0,90.00000001 +22.42,50.425,-3.591634167,50,0,20.00048261,0,0,0,90.00000001 +22.43,50.425,-3.591631353,50,0,20.00048261,0,0,0,90.00000001 +22.44,50.425,-3.591628538,50,0,20.00048261,0,0,0,90.00000001 +22.45,50.425,-3.591625724,50,0,20.00026054,0,0,0,90.00000001 +22.46,50.425,-3.591622909,50,0,19.99959433,0,0,0,90.00000001 +22.47,50.425,-3.591620095,50,0,19.99915019,0,0,0,90.00000001 +22.48,50.425,-3.591617281,50,0,19.99937226,0,0,0,90.00000001 +22.49,50.425,-3.591614466,50,0,19.99937226,0,0,0,90.00000001 +22.5,50.425,-3.591611652,50,0,19.99937226,0,0,0,90.00000001 +22.51,50.425,-3.591608838,50,0,20.00048261,0,0,0,90.00000001 +22.52,50.425,-3.591606023,50,0,20.00137089,0,0,0,90.00000001 +22.53,50.425,-3.591603208,50,0,20.00048261,0,0,0,90.00000001 +22.54,50.425,-3.591600394,50,0,19.99937226,0,0,0,90.00000001 +22.55,50.425,-3.59159758,50,0,19.99959433,0,0,0,90.00000001 +22.56,50.425,-3.591594765,50,0,20.00026054,0,0,0,90.00000001 +22.57,50.425,-3.591591951,50,0,20.00026054,0,0,0,90.00000001 +22.58,50.425,-3.591589136,50,0,19.99959433,0,0,0,90.00000001 +22.59,50.425,-3.591586322,50,0,19.99937226,0,0,0,90.00000001 +22.6,50.425,-3.591583508,50,0,20.00048261,0,0,0,90.00000001 +22.61,50.425,-3.591580693,50,0,20.00137089,0,0,0,90.00000001 +22.62,50.425,-3.591577878,50,0,20.00048261,0,0,0,90.00000001 +22.63,50.425,-3.591575064,50,0,19.99937226,0,0,0,90.00000001 +22.64,50.425,-3.59157225,50,0,19.99937226,0,0,0,90.00000001 +22.65,50.425,-3.591569435,50,0,19.99937226,0,0,0,90.00000001 +22.66,50.425,-3.591566621,50,0,19.99915019,0,0,0,90.00000001 +22.67,50.425,-3.591563807,50,0,19.99959433,0,0,0,90.00000001 +22.68,50.425,-3.591560992,50,0,20.00026054,0,0,0,90.00000001 +22.69,50.425,-3.591558178,50,0,20.00048261,0,0,0,90.00000001 +22.7,50.425,-3.591555363,50,0,20.00048261,0,0,0,90.00000001 +22.71,50.425,-3.591552549,50,0,20.00048261,0,0,0,90.00000001 +22.72,50.425,-3.591549734,50,0,20.00048261,0,0,0,90.00000001 +22.73,50.425,-3.59154692,50,0,20.00026054,0,0,0,90.00000001 +22.74,50.425,-3.591544105,50,0,19.99959433,0,0,0,90.00000001 +22.75,50.425,-3.591541291,50,0,19.99915019,0,0,0,90.00000001 +22.76,50.425,-3.591538477,50,0,19.99937226,0,0,0,90.00000001 +22.77,50.425,-3.591535662,50,0,19.99937226,0,0,0,90.00000001 +22.78,50.425,-3.591532848,50,0,19.99937226,0,0,0,90.00000001 +22.79,50.425,-3.591530034,50,0,20.00048261,0,0,0,90.00000001 +22.8,50.425,-3.591527219,50,0,20.00137089,0,0,0,90.00000001 +22.81,50.425,-3.591524404,50,0,20.00048261,0,0,0,90.00000001 +22.82,50.425,-3.59152159,50,0,19.99937226,0,0,0,90.00000001 +22.83,50.425,-3.591518776,50,0,19.99959433,0,0,0,90.00000001 +22.84,50.425,-3.591515961,50,0,20.00026054,0,0,0,90.00000001 +22.85,50.425,-3.591513147,50,0,20.00026054,0,0,0,90.00000001 +22.86,50.425,-3.591510332,50,0,19.99959433,0,0,0,90.00000001 +22.87,50.425,-3.591507518,50,0,19.99937226,0,0,0,90.00000001 +22.88,50.425,-3.591504704,50,0,20.00048261,0,0,0,90.00000001 +22.89,50.425,-3.591501889,50,0,20.00137089,0,0,0,90.00000001 +22.9,50.425,-3.591499074,50,0,20.00048261,0,0,0,90.00000001 +22.91,50.425,-3.59149626,50,0,19.99937226,0,0,0,90.00000001 +22.92,50.425,-3.591493446,50,0,19.99937226,0,0,0,90.00000001 +22.93,50.425,-3.591490631,50,0,19.99937226,0,0,0,90.00000001 +22.94,50.425,-3.591487817,50,0,19.99915019,0,0,0,90.00000001 +22.95,50.425,-3.591485003,50,0,19.99959433,0,0,0,90.00000001 +22.96,50.425,-3.591482188,50,0,20.00048261,0,0,0,90.00000001 +22.97,50.425,-3.591479374,50,0,20.00137089,0,0,0,90.00000001 +22.98,50.425,-3.591476559,50,0,20.00159296,0,0,0,90.00000001 +22.99,50.425,-3.591473744,50,0,20.00048261,0,0,0,90.00000001 +23,50.425,-3.59147093,50,0,19.99937226,0,0,0,90.00000001 +23.01,50.425,-3.591468116,50,0,19.99937226,0,0,0,90.00000001 +23.02,50.425,-3.591465301,50,0,19.99937226,0,0,0,90.00000001 +23.03,50.425,-3.591462487,50,0,19.99915019,0,0,0,90.00000001 +23.04,50.425,-3.591459673,50,0,19.99937226,0,0,0,90.00000001 +23.05,50.425,-3.591456858,50,0,19.99937226,0,0,0,90.00000001 +23.06,50.425,-3.591454044,50,0,19.99937226,0,0,0,90.00000001 +23.07,50.425,-3.59145123,50,0,20.00048261,0,0,0,90.00000001 +23.08,50.425,-3.591448415,50,0,20.00159296,0,0,0,90.00000001 +23.09,50.425,-3.5914456,50,0,20.00137089,0,0,0,90.00000001 +23.1,50.425,-3.591442786,50,0,20.00048261,0,0,0,90.00000001 +23.11,50.425,-3.591439971,50,0,19.99959433,0,0,0,90.00000001 +23.12,50.425,-3.591437157,50,0,19.99915019,0,0,0,90.00000001 +23.13,50.425,-3.591434343,50,0,19.99937226,0,0,0,90.00000001 +23.14,50.425,-3.591431528,50,0,19.99937226,0,0,0,90.00000001 +23.15,50.425,-3.591428714,50,0,19.99937226,0,0,0,90.00000001 +23.16,50.425,-3.5914259,50,0,20.00048261,0,0,0,90.00000001 +23.17,50.425,-3.591423085,50,0,20.00137089,0,0,0,90.00000001 +23.18,50.425,-3.59142027,50,0,20.00048261,0,0,0,90.00000001 +23.19,50.425,-3.591417456,50,0,19.99937226,0,0,0,90.00000001 +23.2,50.425,-3.591414642,50,0,19.99959433,0,0,0,90.00000001 +23.21,50.425,-3.591411827,50,0,20.00026054,0,0,0,90.00000001 +23.22,50.425,-3.591409013,50,0,20.00026054,0,0,0,90.00000001 +23.23,50.425,-3.591406198,50,0,19.99959433,0,0,0,90.00000001 +23.24,50.425,-3.591403384,50,0,19.99937226,0,0,0,90.00000001 +23.25,50.425,-3.59140057,50,0,20.00048261,0,0,0,90.00000001 +23.26,50.425,-3.591397755,50,0,20.00137089,0,0,0,90.00000001 +23.27,50.425,-3.59139494,50,0,20.00048261,0,0,0,90.00000001 +23.28,50.425,-3.591392126,50,0,19.99937226,0,0,0,90.00000001 +23.29,50.425,-3.591389312,50,0,19.99937226,0,0,0,90.00000001 +23.3,50.425,-3.591386497,50,0,19.99937226,0,0,0,90.00000001 +23.31,50.425,-3.591383683,50,0,19.99915019,0,0,0,90.00000001 +23.32,50.425,-3.591380869,50,0,19.99959433,0,0,0,90.00000001 +23.33,50.425,-3.591378054,50,0,20.00026054,0,0,0,90.00000001 +23.34,50.425,-3.59137524,50,0,20.00048261,0,0,0,90.00000001 +23.35,50.425,-3.591372425,50,0,20.00048261,0,0,0,90.00000001 +23.36,50.425,-3.591369611,50,0,20.00048261,0,0,0,90.00000001 +23.37,50.425,-3.591366796,50,0,20.00048261,0,0,0,90.00000001 +23.38,50.425,-3.591363982,50,0,20.00026054,0,0,0,90.00000001 +23.39,50.425,-3.591361167,50,0,19.99959433,0,0,0,90.00000001 +23.4,50.425,-3.591358353,50,0,19.99915019,0,0,0,90.00000001 +23.41,50.425,-3.591355539,50,0,19.99959433,0,0,0,90.00000001 +23.42,50.425,-3.591352724,50,0,20.00026054,0,0,0,90.00000001 +23.43,50.425,-3.59134991,50,0,20.00048261,0,0,0,90.00000001 +23.44,50.425,-3.591347095,50,0,20.00048261,0,0,0,90.00000001 +23.45,50.425,-3.591344281,50,0,20.00026054,0,0,0,90.00000001 +23.46,50.425,-3.591341466,50,0,19.99959433,0,0,0,90.00000001 +23.47,50.425,-3.591338652,50,0,19.99915019,0,0,0,90.00000001 +23.48,50.425,-3.591335838,50,0,19.99959433,0,0,0,90.00000001 +23.49,50.425,-3.591333023,50,0,20.00026054,0,0,0,90.00000001 +23.5,50.425,-3.591330209,50,0,20.00048261,0,0,0,90.00000001 +23.51,50.425,-3.591327394,50,0,20.00048261,0,0,0,90.00000001 +23.52,50.425,-3.59132458,50,0,20.00048261,0,0,0,90.00000001 +23.53,50.425,-3.591321765,50,0,20.00048261,0,0,0,90.00000001 +23.54,50.425,-3.591318951,50,0,20.00026054,0,0,0,90.00000001 +23.55,50.425,-3.591316136,50,0,19.99959433,0,0,0,90.00000001 +23.56,50.425,-3.591313322,50,0,19.99915019,0,0,0,90.00000001 +23.57,50.425,-3.591310508,50,0,19.99937226,0,0,0,90.00000001 +23.58,50.425,-3.591307693,50,0,19.99937226,0,0,0,90.00000001 +23.59,50.425,-3.591304879,50,0,19.99937226,0,0,0,90.00000001 +23.6,50.425,-3.591302065,50,0,20.00048261,0,0,0,90.00000001 +23.61,50.425,-3.59129925,50,0,20.00159296,0,0,0,90.00000001 +23.62,50.425,-3.591296435,50,0,20.00137089,0,0,0,90.00000001 +23.63,50.425,-3.591293621,50,0,20.00048261,0,0,0,90.00000001 +23.64,50.425,-3.591290806,50,0,19.99959433,0,0,0,90.00000001 +23.65,50.425,-3.591287992,50,0,19.99915019,0,0,0,90.00000001 +23.66,50.425,-3.591285178,50,0,19.99937226,0,0,0,90.00000001 +23.67,50.425,-3.591282363,50,0,19.99937226,0,0,0,90.00000001 +23.68,50.425,-3.591279549,50,0,19.99937226,0,0,0,90.00000001 +23.69,50.425,-3.591276735,50,0,20.00048261,0,0,0,90.00000001 +23.7,50.425,-3.59127392,50,0,20.00137089,0,0,0,90.00000001 +23.71,50.425,-3.591271105,50,0,20.00048261,0,0,0,90.00000001 +23.72,50.425,-3.591268291,50,0,19.99937226,0,0,0,90.00000001 +23.73,50.425,-3.591265477,50,0,19.99937226,0,0,0,90.00000001 +23.74,50.425,-3.591262662,50,0,19.99937226,0,0,0,90.00000001 +23.75,50.425,-3.591259848,50,0,19.99915019,0,0,0,90.00000001 +23.76,50.425,-3.591257034,50,0,19.99959433,0,0,0,90.00000001 +23.77,50.425,-3.591254219,50,0,20.00048261,0,0,0,90.00000001 +23.78,50.425,-3.591251405,50,0,20.00137089,0,0,0,90.00000001 +23.79,50.425,-3.59124859,50,0,20.00159296,0,0,0,90.00000001 +23.8,50.425,-3.591245775,50,0,20.00048261,0,0,0,90.00000001 +23.81,50.425,-3.591242961,50,0,19.99937226,0,0,0,90.00000001 +23.82,50.425,-3.591240147,50,0,19.99937226,0,0,0,90.00000001 +23.83,50.425,-3.591237332,50,0,19.99937226,0,0,0,90.00000001 +23.84,50.425,-3.591234518,50,0,19.99915019,0,0,0,90.00000001 +23.85,50.425,-3.591231704,50,0,19.99937226,0,0,0,90.00000001 +23.86,50.425,-3.591228889,50,0,19.99937226,0,0,0,90.00000001 +23.87,50.425,-3.591226075,50,0,19.99937226,0,0,0,90.00000001 +23.88,50.425,-3.591223261,50,0,20.00048261,0,0,0,90.00000001 +23.89,50.425,-3.591220446,50,0,20.00159296,0,0,0,90.00000001 +23.9,50.425,-3.591217631,50,0,20.00137089,0,0,0,90.00000001 +23.91,50.425,-3.591214817,50,0,20.00048261,0,0,0,90.00000001 +23.92,50.425,-3.591212002,50,0,19.99959433,0,0,0,90.00000001 +23.93,50.425,-3.591209188,50,0,19.99915019,0,0,0,90.00000001 +23.94,50.425,-3.591206374,50,0,19.99937226,0,0,0,90.00000001 +23.95,50.425,-3.591203559,50,0,19.99937226,0,0,0,90.00000001 +23.96,50.425,-3.591200745,50,0,19.99937226,0,0,0,90.00000001 +23.97,50.425,-3.591197931,50,0,20.00048261,0,0,0,90.00000001 +23.98,50.425,-3.591195116,50,0,20.00137089,0,0,0,90.00000001 +23.99,50.425,-3.591192301,50,0,20.00048261,0,0,0,90.00000001 +24,50.425,-3.591189487,50,0,19.99937226,0,0,0,90.00000001 +24.01,50.425,-3.591186673,50,0,19.99959433,0,0,0,90.00000001 +24.02,50.425,-3.591183858,50,0,20.00026054,0,0,0,90.00000001 +24.03,50.425,-3.591181044,50,0,20.00026054,0,0,0,90.00000001 +24.04,50.425,-3.591178229,50,0,19.99959433,0,0,0,90.00000001 +24.05,50.425,-3.591175415,50,0,19.99937226,0,0,0,90.00000001 +24.06,50.425,-3.591172601,50,0,20.00048261,0,0,0,90.00000001 +24.07,50.425,-3.591169786,50,0,20.00137089,0,0,0,90.00000001 +24.08,50.425,-3.591166971,50,0,20.00048261,0,0,0,90.00000001 +24.09,50.425,-3.591164157,50,0,19.99937226,0,0,0,90.00000001 +24.1,50.425,-3.591161343,50,0,19.99937226,0,0,0,90.00000001 +24.11,50.425,-3.591158528,50,0,19.99937226,0,0,0,90.00000001 +24.12,50.425,-3.591155714,50,0,19.99915019,0,0,0,90.00000001 +24.13,50.425,-3.5911529,50,0,19.99959433,0,0,0,90.00000001 +24.14,50.425,-3.591150085,50,0,20.00026054,0,0,0,90.00000001 +24.15,50.425,-3.591147271,50,0,20.00048261,0,0,0,90.00000001 +24.16,50.425,-3.591144456,50,0,20.00048261,0,0,0,90.00000001 +24.17,50.425,-3.591141642,50,0,20.00048261,0,0,0,90.00000001 +24.18,50.425,-3.591138827,50,0,20.00048261,0,0,0,90.00000001 +24.19,50.425,-3.591136013,50,0,20.00026054,0,0,0,90.00000001 +24.2,50.425,-3.591133198,50,0,19.99959433,0,0,0,90.00000001 +24.21,50.425,-3.591130384,50,0,19.99915019,0,0,0,90.00000001 +24.22,50.425,-3.59112757,50,0,19.99959433,0,0,0,90.00000001 +24.23,50.425,-3.591124755,50,0,20.00026054,0,0,0,90.00000001 +24.24,50.425,-3.591121941,50,0,20.00048261,0,0,0,90.00000001 +24.25,50.425,-3.591119126,50,0,20.00048261,0,0,0,90.00000001 +24.26,50.425,-3.591116312,50,0,20.00026054,0,0,0,90.00000001 +24.27,50.425,-3.591113497,50,0,19.99959433,0,0,0,90.00000001 +24.28,50.425,-3.591110683,50,0,19.99915019,0,0,0,90.00000001 +24.29,50.425,-3.591107869,50,0,19.99959433,0,0,0,90.00000001 +24.3,50.425,-3.591105054,50,0,20.00026054,0,0,0,90.00000001 +24.31,50.425,-3.59110224,50,0,20.00048261,0,0,0,90.00000001 +24.32,50.425,-3.591099425,50,0,20.00048261,0,0,0,90.00000001 +24.33,50.425,-3.591096611,50,0,20.00048261,0,0,0,90.00000001 +24.34,50.425,-3.591093796,50,0,20.00048261,0,0,0,90.00000001 +24.35,50.425,-3.591090982,50,0,20.00026054,0,0,0,90.00000001 +24.36,50.425,-3.591088167,50,0,19.99959433,0,0,0,90.00000001 +24.37,50.425,-3.591085353,50,0,19.99915019,0,0,0,90.00000001 +24.38,50.425,-3.591082539,50,0,19.99937226,0,0,0,90.00000001 +24.39,50.425,-3.591079724,50,0,19.99937226,0,0,0,90.00000001 +24.4,50.425,-3.59107691,50,0,19.99937226,0,0,0,90.00000001 +24.41,50.425,-3.591074096,50,0,20.00048261,0,0,0,90.00000001 +24.42,50.425,-3.591071281,50,0,20.00159296,0,0,0,90.00000001 +24.43,50.425,-3.591068466,50,0,20.00137089,0,0,0,90.00000001 +24.44,50.425,-3.591065652,50,0,20.00048261,0,0,0,90.00000001 +24.45,50.425,-3.591062837,50,0,19.99959433,0,0,0,90.00000001 +24.46,50.425,-3.591060023,50,0,19.99915019,0,0,0,90.00000001 +24.47,50.425,-3.591057209,50,0,19.99937226,0,0,0,90.00000001 +24.48,50.425,-3.591054394,50,0,19.99937226,0,0,0,90.00000001 +24.49,50.425,-3.59105158,50,0,19.99937226,0,0,0,90.00000001 +24.5,50.425,-3.591048766,50,0,20.00048261,0,0,0,90.00000001 +24.51,50.425,-3.591045951,50,0,20.00137089,0,0,0,90.00000001 +24.52,50.425,-3.591043136,50,0,20.00048261,0,0,0,90.00000001 +24.53,50.425,-3.591040322,50,0,19.99937226,0,0,0,90.00000001 +24.54,50.425,-3.591037508,50,0,19.99959433,0,0,0,90.00000001 +24.55,50.425,-3.591034693,50,0,20.00026054,0,0,0,90.00000001 +24.56,50.425,-3.591031879,50,0,20.00026054,0,0,0,90.00000001 +24.57,50.425,-3.591029064,50,0,19.99959433,0,0,0,90.00000001 +24.58,50.425,-3.59102625,50,0,19.99937226,0,0,0,90.00000001 +24.59,50.425,-3.591023436,50,0,20.00048261,0,0,0,90.00000001 +24.6,50.425,-3.591020621,50,0,20.00137089,0,0,0,90.00000001 +24.61,50.425,-3.591017806,50,0,20.00048261,0,0,0,90.00000001 +24.62,50.425,-3.591014992,50,0,19.99937226,0,0,0,90.00000001 +24.63,50.425,-3.591012178,50,0,19.99937226,0,0,0,90.00000001 +24.64,50.425,-3.591009363,50,0,19.99937226,0,0,0,90.00000001 +24.65,50.425,-3.591006549,50,0,19.99915019,0,0,0,90.00000001 +24.66,50.425,-3.591003735,50,0,19.99959433,0,0,0,90.00000001 +24.67,50.425,-3.59100092,50,0,20.00026054,0,0,0,90.00000001 +24.68,50.425,-3.590998106,50,0,20.00048261,0,0,0,90.00000001 +24.69,50.425,-3.590995291,50,0,20.00048261,0,0,0,90.00000001 +24.7,50.425,-3.590992477,50,0,20.00048261,0,0,0,90.00000001 +24.71,50.425,-3.590989662,50,0,20.00048261,0,0,0,90.00000001 +24.72,50.425,-3.590986848,50,0,20.00026054,0,0,0,90.00000001 +24.73,50.425,-3.590984033,50,0,19.99959433,0,0,0,90.00000001 +24.74,50.425,-3.590981219,50,0,19.99915019,0,0,0,90.00000001 +24.75,50.425,-3.590978405,50,0,19.99937226,0,0,0,90.00000001 +24.76,50.425,-3.59097559,50,0,19.99937226,0,0,0,90.00000001 +24.77,50.425,-3.590972776,50,0,19.99937226,0,0,0,90.00000001 +24.78,50.425,-3.590969962,50,0,20.00048261,0,0,0,90.00000001 +24.79,50.425,-3.590967147,50,0,20.00137089,0,0,0,90.00000001 +24.8,50.425,-3.590964332,50,0,20.00048261,0,0,0,90.00000001 +24.81,50.425,-3.590961518,50,0,19.99937226,0,0,0,90.00000001 +24.82,50.425,-3.590958704,50,0,19.99959433,0,0,0,90.00000001 +24.83,50.425,-3.590955889,50,0,20.00026054,0,0,0,90.00000001 +24.84,50.425,-3.590953075,50,0,20.00026054,0,0,0,90.00000001 +24.85,50.425,-3.59095026,50,0,19.99959433,0,0,0,90.00000001 +24.86,50.425,-3.590947446,50,0,19.99937226,0,0,0,90.00000001 +24.87,50.425,-3.590944632,50,0,20.00048261,0,0,0,90.00000001 +24.88,50.425,-3.590941817,50,0,20.00137089,0,0,0,90.00000001 +24.89,50.425,-3.590939002,50,0,20.00048261,0,0,0,90.00000001 +24.9,50.425,-3.590936188,50,0,19.99937226,0,0,0,90.00000001 +24.91,50.425,-3.590933374,50,0,19.99937226,0,0,0,90.00000001 +24.92,50.425,-3.590930559,50,0,19.99937226,0,0,0,90.00000001 +24.93,50.425,-3.590927745,50,0,19.99915019,0,0,0,90.00000001 +24.94,50.425,-3.590924931,50,0,19.99959433,0,0,0,90.00000001 +24.95,50.425,-3.590922116,50,0,20.00048261,0,0,0,90.00000001 +24.96,50.425,-3.590919302,50,0,20.00137089,0,0,0,90.00000001 +24.97,50.425,-3.590916487,50,0,20.00159296,0,0,0,90.00000001 +24.98,50.425,-3.590913672,50,0,20.00048261,0,0,0,90.00000001 +24.99,50.425,-3.590910858,50,0,19.99937226,0,0,0,90.00000001 +25,50.425,-3.590908044,50,0,19.99937226,0,0,0,90.00000001 +25.01,50.425,-3.590905229,50,0,19.99937226,0,0,0,90.00000001 +25.02,50.425,-3.590902415,50,0,19.99915019,0,0,0,90.00000001 +25.03,50.425,-3.590899601,50,0,19.99959433,0,0,0,90.00000001 +25.04,50.425,-3.590896786,50,0,20.00026054,0,0,0,90.00000001 +25.05,50.425,-3.590893972,50,0,20.00048261,0,0,0,90.00000001 +25.06,50.425,-3.590891157,50,0,20.00048261,0,0,0,90.00000001 +25.07,50.425,-3.590888343,50,0,20.00026054,0,0,0,90.00000001 +25.08,50.425,-3.590885528,50,0,19.99959433,0,0,0,90.00000001 +25.09,50.425,-3.590882714,50,0,19.99915019,0,0,0,90.00000001 +25.1,50.425,-3.5908799,50,0,19.99959433,0,0,0,90.00000001 +25.11,50.425,-3.590877085,50,0,20.00026054,0,0,0,90.00000001 +25.12,50.425,-3.590874271,50,0,20.00048261,0,0,0,90.00000001 +25.13,50.425,-3.590871456,50,0,20.00048261,0,0,0,90.00000001 +25.14,50.425,-3.590868642,50,0,20.00048261,0,0,0,90.00000001 +25.15,50.425,-3.590865827,50,0,20.00048261,0,0,0,90.00000001 +25.16,50.425,-3.590863013,50,0,20.00026054,0,0,0,90.00000001 +25.17,50.425,-3.590860198,50,0,19.99959433,0,0,0,90.00000001 +25.18,50.425,-3.590857384,50,0,19.99915019,0,0,0,90.00000001 +25.19,50.425,-3.59085457,50,0,19.99937226,0,0,0,90.00000001 +25.2,50.425,-3.590851755,50,0,19.99937226,0,0,0,90.00000001 +25.21,50.425,-3.590848941,50,0,19.99937226,0,0,0,90.00000001 +25.22,50.425,-3.590846127,50,0,20.00048261,0,0,0,90.00000001 +25.23,50.425,-3.590843312,50,0,20.00159296,0,0,0,90.00000001 +25.24,50.425,-3.590840497,50,0,20.00137089,0,0,0,90.00000001 +25.25,50.425,-3.590837683,50,0,20.00048261,0,0,0,90.00000001 +25.26,50.425,-3.590834868,50,0,19.99959433,0,0,0,90.00000001 +25.27,50.425,-3.590832054,50,0,19.99915019,0,0,0,90.00000001 +25.28,50.425,-3.59082924,50,0,19.99937226,0,0,0,90.00000001 +25.29,50.425,-3.590826425,50,0,19.99937226,0,0,0,90.00000001 +25.3,50.425,-3.590823611,50,0,19.99937226,0,0,0,90.00000001 +25.31,50.425,-3.590820797,50,0,20.00048261,0,0,0,90.00000001 +25.32,50.425,-3.590817982,50,0,20.00137089,0,0,0,90.00000001 +25.33,50.425,-3.590815167,50,0,20.00048261,0,0,0,90.00000001 +25.34,50.425,-3.590812353,50,0,19.99937226,0,0,0,90.00000001 +25.35,50.425,-3.590809539,50,0,19.99959433,0,0,0,90.00000001 +25.36,50.425,-3.590806724,50,0,20.00026054,0,0,0,90.00000001 +25.37,50.425,-3.59080391,50,0,20.00026054,0,0,0,90.00000001 +25.38,50.425,-3.590801095,50,0,19.99959433,0,0,0,90.00000001 +25.39,50.425,-3.590798281,50,0,19.99915019,0,0,0,90.00000001 +25.4,50.425,-3.590795467,50,0,19.99959433,0,0,0,90.00000001 +25.41,50.425,-3.590792652,50,0,20.00026054,0,0,0,90.00000001 +25.42,50.425,-3.590789838,50,0,20.00048261,0,0,0,90.00000001 +25.43,50.425,-3.590787023,50,0,20.00048261,0,0,0,90.00000001 +25.44,50.425,-3.590784209,50,0,20.00026054,0,0,0,90.00000001 +25.45,50.425,-3.590781394,50,0,19.99959433,0,0,0,90.00000001 +25.46,50.425,-3.59077858,50,0,19.99915019,0,0,0,90.00000001 +25.47,50.425,-3.590775766,50,0,19.99959433,0,0,0,90.00000001 +25.48,50.425,-3.590772951,50,0,20.00026054,0,0,0,90.00000001 +25.49,50.425,-3.590770137,50,0,20.00048261,0,0,0,90.00000001 +25.5,50.425,-3.590767322,50,0,20.00048261,0,0,0,90.00000001 +25.51,50.425,-3.590764508,50,0,20.00048261,0,0,0,90.00000001 +25.52,50.425,-3.590761693,50,0,20.00048261,0,0,0,90.00000001 +25.53,50.425,-3.590758879,50,0,20.00026054,0,0,0,90.00000001 +25.54,50.425,-3.590756064,50,0,19.99959433,0,0,0,90.00000001 +25.55,50.425,-3.59075325,50,0,19.99915019,0,0,0,90.00000001 +25.56,50.425,-3.590750436,50,0,19.99937226,0,0,0,90.00000001 +25.57,50.425,-3.590747621,50,0,19.99937226,0,0,0,90.00000001 +25.58,50.425,-3.590744807,50,0,19.99937226,0,0,0,90.00000001 +25.59,50.425,-3.590741993,50,0,20.00048261,0,0,0,90.00000001 +25.6,50.425,-3.590739178,50,0,20.00137089,0,0,0,90.00000001 +25.61,50.425,-3.590736363,50,0,20.00048261,0,0,0,90.00000001 +25.62,50.425,-3.590733549,50,0,19.99937226,0,0,0,90.00000001 +25.63,50.425,-3.590730735,50,0,19.99959433,0,0,0,90.00000001 +25.64,50.425,-3.59072792,50,0,20.00026054,0,0,0,90.00000001 +25.65,50.425,-3.590725106,50,0,20.00026054,0,0,0,90.00000001 +25.66,50.425,-3.590722291,50,0,19.99959433,0,0,0,90.00000001 +25.67,50.425,-3.590719477,50,0,19.99937226,0,0,0,90.00000001 +25.68,50.425,-3.590716663,50,0,20.00048261,0,0,0,90.00000001 +25.69,50.425,-3.590713848,50,0,20.00137089,0,0,0,90.00000001 +25.7,50.425,-3.590711033,50,0,20.00048261,0,0,0,90.00000001 +25.71,50.425,-3.590708219,50,0,19.99937226,0,0,0,90.00000001 +25.72,50.425,-3.590705405,50,0,19.99937226,0,0,0,90.00000001 +25.73,50.425,-3.59070259,50,0,19.99937226,0,0,0,90.00000001 +25.74,50.425,-3.590699776,50,0,19.99915019,0,0,0,90.00000001 +25.75,50.425,-3.590696962,50,0,19.99959433,0,0,0,90.00000001 +25.76,50.425,-3.590694147,50,0,20.00048261,0,0,0,90.00000001 +25.77,50.425,-3.590691333,50,0,20.00137089,0,0,0,90.00000001 +25.78,50.425,-3.590688518,50,0,20.00159296,0,0,0,90.00000001 +25.79,50.425,-3.590685703,50,0,20.00048261,0,0,0,90.00000001 +25.8,50.425,-3.590682889,50,0,19.99937226,0,0,0,90.00000001 +25.81,50.425,-3.590680075,50,0,19.99937226,0,0,0,90.00000001 +25.82,50.425,-3.59067726,50,0,19.99937226,0,0,0,90.00000001 +25.83,50.425,-3.590674446,50,0,19.99915019,0,0,0,90.00000001 +25.84,50.425,-3.590671632,50,0,19.99937226,0,0,0,90.00000001 +25.85,50.425,-3.590668817,50,0,19.99937226,0,0,0,90.00000001 +25.86,50.425,-3.590666003,50,0,19.99937226,0,0,0,90.00000001 +25.87,50.425,-3.590663189,50,0,20.00048261,0,0,0,90.00000001 +25.88,50.425,-3.590660374,50,0,20.00159296,0,0,0,90.00000001 +25.89,50.425,-3.590657559,50,0,20.00137089,0,0,0,90.00000001 +25.9,50.425,-3.590654745,50,0,20.00048261,0,0,0,90.00000001 +25.91,50.425,-3.59065193,50,0,19.99959433,0,0,0,90.00000001 +25.92,50.425,-3.590649116,50,0,19.99915019,0,0,0,90.00000001 +25.93,50.425,-3.590646302,50,0,19.99937226,0,0,0,90.00000001 +25.94,50.425,-3.590643487,50,0,19.99937226,0,0,0,90.00000001 +25.95,50.425,-3.590640673,50,0,19.99937226,0,0,0,90.00000001 +25.96,50.425,-3.590637859,50,0,20.00048261,0,0,0,90.00000001 +25.97,50.425,-3.590635044,50,0,20.00137089,0,0,0,90.00000001 +25.98,50.425,-3.590632229,50,0,20.00048261,0,0,0,90.00000001 +25.99,50.425,-3.590629415,50,0,19.99937226,0,0,0,90.00000001 +26,50.425,-3.590626601,50,0,19.99959433,0,0,0,90.00000001 +26.01,50.425,-3.590623786,50,0,20.00026054,0,0,0,90.00000001 +26.02,50.425,-3.590620972,50,0,20.00026054,0,0,0,90.00000001 +26.03,50.425,-3.590618157,50,0,19.99959433,0,0,0,90.00000001 +26.04,50.425,-3.590615343,50,0,19.99937226,0,0,0,90.00000001 +26.05,50.425,-3.590612529,50,0,20.00048261,0,0,0,90.00000001 +26.06,50.425,-3.590609714,50,0,20.00137089,0,0,0,90.00000001 +26.07,50.425,-3.590606899,50,0,20.00048261,0,0,0,90.00000001 +26.08,50.425,-3.590604085,50,0,19.99937226,0,0,0,90.00000001 +26.09,50.425,-3.590601271,50,0,19.99937226,0,0,0,90.00000001 +26.1,50.425,-3.590598456,50,0,19.99937226,0,0,0,90.00000001 +26.11,50.425,-3.590595642,50,0,19.99915019,0,0,0,90.00000001 +26.12,50.425,-3.590592828,50,0,19.99959433,0,0,0,90.00000001 +26.13,50.425,-3.590590013,50,0,20.00026054,0,0,0,90.00000001 +26.14,50.425,-3.590587199,50,0,20.00048261,0,0,0,90.00000001 +26.15,50.425,-3.590584384,50,0,20.00048261,0,0,0,90.00000001 +26.16,50.425,-3.59058157,50,0,20.00048261,0,0,0,90.00000001 +26.17,50.425,-3.590578755,50,0,20.00048261,0,0,0,90.00000001 +26.18,50.425,-3.590575941,50,0,20.00026054,0,0,0,90.00000001 +26.19,50.425,-3.590573126,50,0,19.99959433,0,0,0,90.00000001 +26.2,50.425,-3.590570312,50,0,19.99915019,0,0,0,90.00000001 +26.21,50.425,-3.590567498,50,0,19.99959433,0,0,0,90.00000001 +26.22,50.425,-3.590564683,50,0,20.00026054,0,0,0,90.00000001 +26.23,50.425,-3.590561869,50,0,20.00048261,0,0,0,90.00000001 +26.24,50.425,-3.590559054,50,0,20.00048261,0,0,0,90.00000001 +26.25,50.425,-3.59055624,50,0,20.00026054,0,0,0,90.00000001 +26.26,50.425,-3.590553425,50,0,19.99959433,0,0,0,90.00000001 +26.27,50.425,-3.590550611,50,0,19.99915019,0,0,0,90.00000001 +26.28,50.425,-3.590547797,50,0,19.99959433,0,0,0,90.00000001 +26.29,50.425,-3.590544982,50,0,20.00026054,0,0,0,90.00000001 +26.3,50.425,-3.590542168,50,0,20.00048261,0,0,0,90.00000001 +26.31,50.425,-3.590539353,50,0,20.00048261,0,0,0,90.00000001 +26.32,50.425,-3.590536539,50,0,20.00048261,0,0,0,90.00000001 +26.33,50.425,-3.590533724,50,0,20.00048261,0,0,0,90.00000001 +26.34,50.425,-3.59053091,50,0,20.00026054,0,0,0,90.00000001 +26.35,50.425,-3.590528095,50,0,19.99959433,0,0,0,90.00000001 +26.36,50.425,-3.590525281,50,0,19.99915019,0,0,0,90.00000001 +26.37,50.425,-3.590522467,50,0,19.99937226,0,0,0,90.00000001 +26.38,50.425,-3.590519652,50,0,19.99937226,0,0,0,90.00000001 +26.39,50.425,-3.590516838,50,0,19.99937226,0,0,0,90.00000001 +26.4,50.425,-3.590514024,50,0,20.00048261,0,0,0,90.00000001 +26.41,50.425,-3.590511209,50,0,20.00137089,0,0,0,90.00000001 +26.42,50.425,-3.590508394,50,0,20.00048261,0,0,0,90.00000001 +26.43,50.425,-3.59050558,50,0,19.99937226,0,0,0,90.00000001 +26.44,50.425,-3.590502766,50,0,19.99959433,0,0,0,90.00000001 +26.45,50.425,-3.590499951,50,0,20.00026054,0,0,0,90.00000001 +26.46,50.425,-3.590497137,50,0,20.00026054,0,0,0,90.00000001 +26.47,50.425,-3.590494322,50,0,19.99959433,0,0,0,90.00000001 +26.48,50.425,-3.590491508,50,0,19.99937226,0,0,0,90.00000001 +26.49,50.425,-3.590488694,50,0,20.00048261,0,0,0,90.00000001 +26.5,50.425,-3.590485879,50,0,20.00137089,0,0,0,90.00000001 +26.51,50.425,-3.590483064,50,0,20.00048261,0,0,0,90.00000001 +26.52,50.425,-3.59048025,50,0,19.99937226,0,0,0,90.00000001 +26.53,50.425,-3.590477436,50,0,19.99937226,0,0,0,90.00000001 +26.54,50.425,-3.590474621,50,0,19.99937226,0,0,0,90.00000001 +26.55,50.425,-3.590471807,50,0,19.99915019,0,0,0,90.00000001 +26.56,50.425,-3.590468993,50,0,19.99959433,0,0,0,90.00000001 +26.57,50.425,-3.590466178,50,0,20.00048261,0,0,0,90.00000001 +26.58,50.425,-3.590463364,50,0,20.00137089,0,0,0,90.00000001 +26.59,50.425,-3.590460549,50,0,20.00159296,0,0,0,90.00000001 +26.6,50.425,-3.590457734,50,0,20.00048261,0,0,0,90.00000001 +26.61,50.425,-3.59045492,50,0,19.99937226,0,0,0,90.00000001 +26.62,50.425,-3.590452106,50,0,19.99937226,0,0,0,90.00000001 +26.63,50.425,-3.590449291,50,0,19.99937226,0,0,0,90.00000001 +26.64,50.425,-3.590446477,50,0,19.99915019,0,0,0,90.00000001 +26.65,50.425,-3.590443663,50,0,19.99937226,0,0,0,90.00000001 +26.66,50.425,-3.590440848,50,0,19.99937226,0,0,0,90.00000001 +26.67,50.425,-3.590438034,50,0,19.99937226,0,0,0,90.00000001 +26.68,50.425,-3.59043522,50,0,20.00048261,0,0,0,90.00000001 +26.69,50.425,-3.590432405,50,0,20.00159296,0,0,0,90.00000001 +26.7,50.425,-3.59042959,50,0,20.00137089,0,0,0,90.00000001 +26.71,50.425,-3.590426776,50,0,20.00048261,0,0,0,90.00000001 +26.72,50.425,-3.590423961,50,0,19.99959433,0,0,0,90.00000001 +26.73,50.425,-3.590421147,50,0,19.99915019,0,0,0,90.00000001 +26.74,50.425,-3.590418333,50,0,19.99937226,0,0,0,90.00000001 +26.75,50.425,-3.590415518,50,0,19.99937226,0,0,0,90.00000001 +26.76,50.425,-3.590412704,50,0,19.99937226,0,0,0,90.00000001 +26.77,50.425,-3.59040989,50,0,20.00048261,0,0,0,90.00000001 +26.78,50.425,-3.590407075,50,0,20.00137089,0,0,0,90.00000001 +26.79,50.425,-3.59040426,50,0,20.00048261,0,0,0,90.00000001 +26.8,50.425,-3.590401446,50,0,19.99937226,0,0,0,90.00000001 +26.81,50.425,-3.590398632,50,0,19.99959433,0,0,0,90.00000001 +26.82,50.425,-3.590395817,50,0,20.00026054,0,0,0,90.00000001 +26.83,50.425,-3.590393003,50,0,20.00026054,0,0,0,90.00000001 +26.84,50.425,-3.590390188,50,0,19.99959433,0,0,0,90.00000001 +26.85,50.425,-3.590387374,50,0,19.99937226,0,0,0,90.00000001 +26.86,50.425,-3.59038456,50,0,20.00048261,0,0,0,90.00000001 +26.87,50.425,-3.590381745,50,0,20.00137089,0,0,0,90.00000001 +26.88,50.425,-3.59037893,50,0,20.00048261,0,0,0,90.00000001 +26.89,50.425,-3.590376116,50,0,19.99937226,0,0,0,90.00000001 +26.9,50.425,-3.590373302,50,0,19.99937226,0,0,0,90.00000001 +26.91,50.425,-3.590370487,50,0,19.99937226,0,0,0,90.00000001 +26.92,50.425,-3.590367673,50,0,19.99915019,0,0,0,90.00000001 +26.93,50.425,-3.590364859,50,0,19.99959433,0,0,0,90.00000001 +26.94,50.425,-3.590362044,50,0,20.00026054,0,0,0,90.00000001 +26.95,50.425,-3.59035923,50,0,20.00048261,0,0,0,90.00000001 +26.96,50.425,-3.590356415,50,0,20.00048261,0,0,0,90.00000001 +26.97,50.425,-3.590353601,50,0,20.00048261,0,0,0,90.00000001 +26.98,50.425,-3.590350786,50,0,20.00048261,0,0,0,90.00000001 +26.99,50.425,-3.590347972,50,0,20.00026054,0,0,0,90.00000001 +27,50.425,-3.590345157,50,0,19.99959433,0,0,0,90.00000001 +27.01,50.425,-3.590342343,50,0,19.99915019,0,0,0,90.00000001 +27.02,50.425,-3.590339529,50,0,19.99959433,0,0,0,90.00000001 +27.03,50.425,-3.590336714,50,0,20.00026054,0,0,0,90.00000001 +27.04,50.425,-3.5903339,50,0,20.00048261,0,0,0,90.00000001 +27.05,50.425,-3.590331085,50,0,20.00048261,0,0,0,90.00000001 +27.06,50.425,-3.590328271,50,0,20.00026054,0,0,0,90.00000001 +27.07,50.425,-3.590325456,50,0,19.99959433,0,0,0,90.00000001 +27.08,50.425,-3.590322642,50,0,19.99915019,0,0,0,90.00000001 +27.09,50.425,-3.590319828,50,0,19.99959433,0,0,0,90.00000001 +27.1,50.425,-3.590317013,50,0,20.00026054,0,0,0,90.00000001 +27.11,50.425,-3.590314199,50,0,20.00048261,0,0,0,90.00000001 +27.12,50.425,-3.590311384,50,0,20.00048261,0,0,0,90.00000001 +27.13,50.425,-3.59030857,50,0,20.00048261,0,0,0,90.00000001 +27.14,50.425,-3.590305755,50,0,20.00048261,0,0,0,90.00000001 +27.15,50.425,-3.590302941,50,0,20.00026054,0,0,0,90.00000001 +27.16,50.425,-3.590300126,50,0,19.99959433,0,0,0,90.00000001 +27.17,50.425,-3.590297312,50,0,19.99915019,0,0,0,90.00000001 +27.18,50.425,-3.590294498,50,0,19.99937226,0,0,0,90.00000001 +27.19,50.425,-3.590291683,50,0,19.99937226,0,0,0,90.00000001 +27.2,50.425,-3.590288869,50,0,19.99937226,0,0,0,90.00000001 +27.21,50.425,-3.590286055,50,0,20.00048261,0,0,0,90.00000001 +27.22,50.425,-3.59028324,50,0,20.00159296,0,0,0,90.00000001 +27.23,50.425,-3.590280425,50,0,20.00137089,0,0,0,90.00000001 +27.24,50.425,-3.590277611,50,0,20.00048261,0,0,0,90.00000001 +27.25,50.425,-3.590274796,50,0,19.99959433,0,0,0,90.00000001 +27.26,50.425,-3.590271982,50,0,19.99915019,0,0,0,90.00000001 +27.27,50.425,-3.590269168,50,0,19.99937226,0,0,0,90.00000001 +27.28,50.425,-3.590266353,50,0,19.99937226,0,0,0,90.00000001 +27.29,50.425,-3.590263539,50,0,19.99937226,0,0,0,90.00000001 +27.3,50.425,-3.590260725,50,0,20.00048261,0,0,0,90.00000001 +27.31,50.425,-3.59025791,50,0,20.00137089,0,0,0,90.00000001 +27.32,50.425,-3.590255095,50,0,20.00048261,0,0,0,90.00000001 +27.33,50.425,-3.590252281,50,0,19.99937226,0,0,0,90.00000001 +27.34,50.425,-3.590249467,50,0,19.99959433,0,0,0,90.00000001 +27.35,50.425,-3.590246652,50,0,20.00026054,0,0,0,90.00000001 +27.36,50.425,-3.590243838,50,0,20.00026054,0,0,0,90.00000001 +27.37,50.425,-3.590241023,50,0,19.99959433,0,0,0,90.00000001 +27.38,50.425,-3.590238209,50,0,19.99937226,0,0,0,90.00000001 +27.39,50.425,-3.590235395,50,0,20.00048261,0,0,0,90.00000001 +27.4,50.425,-3.59023258,50,0,20.00137089,0,0,0,90.00000001 +27.41,50.425,-3.590229765,50,0,20.00048261,0,0,0,90.00000001 +27.42,50.425,-3.590226951,50,0,19.99937226,0,0,0,90.00000001 +27.43,50.425,-3.590224137,50,0,19.99937226,0,0,0,90.00000001 +27.44,50.425,-3.590221322,50,0,19.99937226,0,0,0,90.00000001 +27.45,50.425,-3.590218508,50,0,19.99915019,0,0,0,90.00000001 +27.46,50.425,-3.590215694,50,0,19.99959433,0,0,0,90.00000001 +27.47,50.425,-3.590212879,50,0,20.00026054,0,0,0,90.00000001 +27.48,50.425,-3.590210065,50,0,20.00048261,0,0,0,90.00000001 +27.49,50.425,-3.59020725,50,0,20.00048261,0,0,0,90.00000001 +27.5,50.425,-3.590204436,50,0,20.00048261,0,0,0,90.00000001 +27.51,50.425,-3.590201621,50,0,20.00048261,0,0,0,90.00000001 +27.52,50.425,-3.590198807,50,0,20.00026054,0,0,0,90.00000001 +27.53,50.425,-3.590195992,50,0,19.99959433,0,0,0,90.00000001 +27.54,50.425,-3.590193178,50,0,19.99915019,0,0,0,90.00000001 +27.55,50.425,-3.590190364,50,0,19.99937226,0,0,0,90.00000001 +27.56,50.425,-3.590187549,50,0,19.99937226,0,0,0,90.00000001 +27.57,50.425,-3.590184735,50,0,19.99937226,0,0,0,90.00000001 +27.58,50.425,-3.590181921,50,0,20.00048261,0,0,0,90.00000001 +27.59,50.425,-3.590179106,50,0,20.00137089,0,0,0,90.00000001 +27.6,50.425,-3.590176291,50,0,20.00048261,0,0,0,90.00000001 +27.61,50.425,-3.590173477,50,0,19.99937226,0,0,0,90.00000001 +27.62,50.425,-3.590170663,50,0,19.99959433,0,0,0,90.00000001 +27.63,50.425,-3.590167848,50,0,20.00026054,0,0,0,90.00000001 +27.64,50.425,-3.590165034,50,0,20.00026054,0,0,0,90.00000001 +27.65,50.425,-3.590162219,50,0,19.99959433,0,0,0,90.00000001 +27.66,50.425,-3.590159405,50,0,19.99937226,0,0,0,90.00000001 +27.67,50.425,-3.590156591,50,0,20.00048261,0,0,0,90.00000001 +27.68,50.425,-3.590153776,50,0,20.00137089,0,0,0,90.00000001 +27.69,50.425,-3.590150961,50,0,20.00048261,0,0,0,90.00000001 +27.7,50.425,-3.590148147,50,0,19.99937226,0,0,0,90.00000001 +27.71,50.425,-3.590145333,50,0,19.99937226,0,0,0,90.00000001 +27.72,50.425,-3.590142518,50,0,19.99937226,0,0,0,90.00000001 +27.73,50.425,-3.590139704,50,0,19.99915019,0,0,0,90.00000001 +27.74,50.425,-3.59013689,50,0,19.99959433,0,0,0,90.00000001 +27.75,50.425,-3.590134075,50,0,20.00026054,0,0,0,90.00000001 +27.76,50.425,-3.590131261,50,0,20.00048261,0,0,0,90.00000001 +27.77,50.425,-3.590128446,50,0,20.00048261,0,0,0,90.00000001 +27.78,50.425,-3.590125632,50,0,20.00048261,0,0,0,90.00000001 +27.79,50.425,-3.590122817,50,0,20.00048261,0,0,0,90.00000001 +27.8,50.425,-3.590120003,50,0,20.00026054,0,0,0,90.00000001 +27.81,50.425,-3.590117188,50,0,19.99959433,0,0,0,90.00000001 +27.82,50.425,-3.590114374,50,0,19.99915019,0,0,0,90.00000001 +27.83,50.425,-3.59011156,50,0,19.99937226,0,0,0,90.00000001 +27.84,50.425,-3.590108745,50,0,19.99937226,0,0,0,90.00000001 +27.85,50.425,-3.590105931,50,0,19.99937226,0,0,0,90.00000001 +27.86,50.425,-3.590103117,50,0,20.00048261,0,0,0,90.00000001 +27.87,50.425,-3.590100302,50,0,20.00137089,0,0,0,90.00000001 +27.88,50.425,-3.590097487,50,0,20.00048261,0,0,0,90.00000001 +27.89,50.425,-3.590094673,50,0,19.99937226,0,0,0,90.00000001 +27.9,50.425,-3.590091859,50,0,19.99959433,0,0,0,90.00000001 +27.91,50.425,-3.590089044,50,0,20.00026054,0,0,0,90.00000001 +27.92,50.425,-3.59008623,50,0,20.00026054,0,0,0,90.00000001 +27.93,50.425,-3.590083415,50,0,19.99959433,0,0,0,90.00000001 +27.94,50.425,-3.590080601,50,0,19.99937226,0,0,0,90.00000001 +27.95,50.425,-3.590077787,50,0,20.00048261,0,0,0,90.00000001 +27.96,50.425,-3.590074972,50,0,20.00137089,0,0,0,90.00000001 +27.97,50.425,-3.590072157,50,0,20.00048261,0,0,0,90.00000001 +27.98,50.425,-3.590069343,50,0,19.99937226,0,0,0,90.00000001 +27.99,50.425,-3.590066529,50,0,19.99937226,0,0,0,90.00000001 +28,50.425,-3.590063714,50,0,19.99937226,0,0,0,90.00000001 +28.01,50.425,-3.5900609,50,0,19.99915019,0,0,0,90.00000001 +28.02,50.425,-3.590058086,50,0,19.99959433,0,0,0,90.00000001 +28.03,50.425,-3.590055271,50,0,20.00048261,0,0,0,90.00000001 +28.04,50.425,-3.590052457,50,0,20.00137089,0,0,0,90.00000001 +28.05,50.425,-3.590049642,50,0,20.00159296,0,0,0,90.00000001 +28.06,50.425,-3.590046827,50,0,20.00048261,0,0,0,90.00000001 +28.07,50.425,-3.590044013,50,0,19.99937226,0,0,0,90.00000001 +28.08,50.425,-3.590041199,50,0,19.99937226,0,0,0,90.00000001 +28.09,50.425,-3.590038384,50,0,19.99937226,0,0,0,90.00000001 +28.1,50.425,-3.59003557,50,0,19.99915019,0,0,0,90.00000001 +28.11,50.425,-3.590032756,50,0,19.99959433,0,0,0,90.00000001 +28.12,50.425,-3.590029941,50,0,20.00026054,0,0,0,90.00000001 +28.13,50.425,-3.590027127,50,0,20.00048261,0,0,0,90.00000001 +28.14,50.425,-3.590024312,50,0,20.00048261,0,0,0,90.00000001 +28.15,50.425,-3.590021498,50,0,20.00048261,0,0,0,90.00000001 +28.16,50.425,-3.590018683,50,0,20.00048261,0,0,0,90.00000001 +28.17,50.425,-3.590015869,50,0,20.00026054,0,0,0,90.00000001 +28.18,50.425,-3.590013054,50,0,19.99959433,0,0,0,90.00000001 +28.19,50.425,-3.59001024,50,0,19.99915019,0,0,0,90.00000001 +28.2,50.425,-3.590007426,50,0,19.99959433,0,0,0,90.00000001 +28.21,50.425,-3.590004611,50,0,20.00026054,0,0,0,90.00000001 +28.22,50.425,-3.590001797,50,0,20.00048261,0,0,0,90.00000001 +28.23,50.425,-3.589998982,50,0,20.00048261,0,0,0,90.00000001 +28.24,50.425,-3.589996168,50,0,20.00026054,0,0,0,90.00000001 +28.25,50.425,-3.589993353,50,0,19.99959433,0,0,0,90.00000001 +28.26,50.425,-3.589990539,50,0,19.99915019,0,0,0,90.00000001 +28.27,50.425,-3.589987725,50,0,19.99959433,0,0,0,90.00000001 +28.28,50.425,-3.58998491,50,0,20.00026054,0,0,0,90.00000001 +28.29,50.425,-3.589982096,50,0,20.00048261,0,0,0,90.00000001 +28.3,50.425,-3.589979281,50,0,20.00048261,0,0,0,90.00000001 +28.31,50.425,-3.589976467,50,0,20.00048261,0,0,0,90.00000001 +28.32,50.425,-3.589973652,50,0,20.00048261,0,0,0,90.00000001 +28.33,50.425,-3.589970838,50,0,20.00026054,0,0,0,90.00000001 +28.34,50.425,-3.589968023,50,0,19.99959433,0,0,0,90.00000001 +28.35,50.425,-3.589965209,50,0,19.99915019,0,0,0,90.00000001 +28.36,50.425,-3.589962395,50,0,19.99937226,0,0,0,90.00000001 +28.37,50.425,-3.58995958,50,0,19.99937226,0,0,0,90.00000001 +28.38,50.425,-3.589956766,50,0,19.99937226,0,0,0,90.00000001 +28.39,50.425,-3.589953952,50,0,20.00048261,0,0,0,90.00000001 +28.4,50.425,-3.589951137,50,0,20.00137089,0,0,0,90.00000001 +28.41,50.425,-3.589948322,50,0,20.00048261,0,0,0,90.00000001 +28.42,50.425,-3.589945508,50,0,19.99937226,0,0,0,90.00000001 +28.43,50.425,-3.589942694,50,0,19.99959433,0,0,0,90.00000001 +28.44,50.425,-3.589939879,50,0,20.00026054,0,0,0,90.00000001 +28.45,50.425,-3.589937065,50,0,20.00026054,0,0,0,90.00000001 +28.46,50.425,-3.58993425,50,0,19.99959433,0,0,0,90.00000001 +28.47,50.425,-3.589931436,50,0,19.99937226,0,0,0,90.00000001 +28.48,50.425,-3.589928622,50,0,20.00048261,0,0,0,90.00000001 +28.49,50.425,-3.589925807,50,0,20.00137089,0,0,0,90.00000001 +28.5,50.425,-3.589922992,50,0,20.00048261,0,0,0,90.00000001 +28.51,50.425,-3.589920178,50,0,19.99937226,0,0,0,90.00000001 +28.52,50.425,-3.589917364,50,0,19.99937226,0,0,0,90.00000001 +28.53,50.425,-3.589914549,50,0,19.99937226,0,0,0,90.00000001 +28.54,50.425,-3.589911735,50,0,19.99915019,0,0,0,90.00000001 +28.55,50.425,-3.589908921,50,0,19.99959433,0,0,0,90.00000001 +28.56,50.425,-3.589906106,50,0,20.00048261,0,0,0,90.00000001 +28.57,50.425,-3.589903292,50,0,20.00137089,0,0,0,90.00000001 +28.58,50.425,-3.589900477,50,0,20.00159296,0,0,0,90.00000001 +28.59,50.425,-3.589897662,50,0,20.00048261,0,0,0,90.00000001 +28.6,50.425,-3.589894848,50,0,19.99937226,0,0,0,90.00000001 +28.61,50.425,-3.589892034,50,0,19.99937226,0,0,0,90.00000001 +28.62,50.425,-3.589889219,50,0,19.99937226,0,0,0,90.00000001 +28.63,50.425,-3.589886405,50,0,19.99915019,0,0,0,90.00000001 +28.64,50.425,-3.589883591,50,0,19.99937226,0,0,0,90.00000001 +28.65,50.425,-3.589880776,50,0,19.99937226,0,0,0,90.00000001 +28.66,50.425,-3.589877962,50,0,19.99937226,0,0,0,90.00000001 +28.67,50.425,-3.589875148,50,0,20.00048261,0,0,0,90.00000001 +28.68,50.425,-3.589872333,50,0,20.00159296,0,0,0,90.00000001 +28.69,50.425,-3.589869518,50,0,20.00137089,0,0,0,90.00000001 +28.7,50.425,-3.589866704,50,0,20.00048261,0,0,0,90.00000001 +28.71,50.425,-3.589863889,50,0,19.99959433,0,0,0,90.00000001 +28.72,50.425,-3.589861075,50,0,19.99915019,0,0,0,90.00000001 +28.73,50.425,-3.589858261,50,0,19.99937226,0,0,0,90.00000001 +28.74,50.425,-3.589855446,50,0,19.99937226,0,0,0,90.00000001 +28.75,50.425,-3.589852632,50,0,19.99937226,0,0,0,90.00000001 +28.76,50.425,-3.589849818,50,0,20.00048261,0,0,0,90.00000001 +28.77,50.425,-3.589847003,50,0,20.00137089,0,0,0,90.00000001 +28.78,50.425,-3.589844188,50,0,20.00048261,0,0,0,90.00000001 +28.79,50.425,-3.589841374,50,0,19.99937226,0,0,0,90.00000001 +28.8,50.425,-3.58983856,50,0,19.99959433,0,0,0,90.00000001 +28.81,50.425,-3.589835745,50,0,20.00026054,0,0,0,90.00000001 +28.82,50.425,-3.589832931,50,0,20.00026054,0,0,0,90.00000001 +28.83,50.425,-3.589830116,50,0,19.99959433,0,0,0,90.00000001 +28.84,50.425,-3.589827302,50,0,19.99937226,0,0,0,90.00000001 +28.85,50.425,-3.589824488,50,0,20.00048261,0,0,0,90.00000001 +28.86,50.425,-3.589821673,50,0,20.00137089,0,0,0,90.00000001 +28.87,50.425,-3.589818858,50,0,20.00048261,0,0,0,90.00000001 +28.88,50.425,-3.589816044,50,0,19.99937226,0,0,0,90.00000001 +28.89,50.425,-3.58981323,50,0,19.99937226,0,0,0,90.00000001 +28.9,50.425,-3.589810415,50,0,19.99937226,0,0,0,90.00000001 +28.91,50.425,-3.589807601,50,0,19.99915019,0,0,0,90.00000001 +28.92,50.425,-3.589804787,50,0,19.99959433,0,0,0,90.00000001 +28.93,50.425,-3.589801972,50,0,20.00026054,0,0,0,90.00000001 +28.94,50.425,-3.589799158,50,0,20.00048261,0,0,0,90.00000001 +28.95,50.425,-3.589796343,50,0,20.00048261,0,0,0,90.00000001 +28.96,50.425,-3.589793529,50,0,20.00048261,0,0,0,90.00000001 +28.97,50.425,-3.589790714,50,0,20.00048261,0,0,0,90.00000001 +28.98,50.425,-3.5897879,50,0,20.00026054,0,0,0,90.00000001 +28.99,50.425,-3.589785085,50,0,19.99959433,0,0,0,90.00000001 +29,50.425,-3.589782271,50,0,19.99915019,0,0,0,90.00000001 +29.01,50.425,-3.589779457,50,0,19.99959433,0,0,0,90.00000001 +29.02,50.425,-3.589776642,50,0,20.00026054,0,0,0,90.00000001 +29.03,50.425,-3.589773828,50,0,20.00048261,0,0,0,90.00000001 +29.04,50.425,-3.589771013,50,0,20.00048261,0,0,0,90.00000001 +29.05,50.425,-3.589768199,50,0,20.00026054,0,0,0,90.00000001 +29.06,50.425,-3.589765384,50,0,19.99959433,0,0,0,90.00000001 +29.07,50.425,-3.58976257,50,0,19.99915019,0,0,0,90.00000001 +29.08,50.425,-3.589759756,50,0,19.99959433,0,0,0,90.00000001 +29.09,50.425,-3.589756941,50,0,20.00026054,0,0,0,90.00000001 +29.1,50.425,-3.589754127,50,0,20.00048261,0,0,0,90.00000001 +29.11,50.425,-3.589751312,50,0,20.00048261,0,0,0,90.00000001 +29.12,50.425,-3.589748498,50,0,20.00048261,0,0,0,90.00000001 +29.13,50.425,-3.589745683,50,0,20.00048261,0,0,0,90.00000001 +29.14,50.425,-3.589742869,50,0,20.00026054,0,0,0,90.00000001 +29.15,50.425,-3.589740054,50,0,19.99959433,0,0,0,90.00000001 +29.16,50.425,-3.58973724,50,0,19.99915019,0,0,0,90.00000001 +29.17,50.425,-3.589734426,50,0,19.99937226,0,0,0,90.00000001 +29.18,50.425,-3.589731611,50,0,19.99937226,0,0,0,90.00000001 +29.19,50.425,-3.589728797,50,0,19.99937226,0,0,0,90.00000001 +29.2,50.425,-3.589725983,50,0,20.00048261,0,0,0,90.00000001 +29.21,50.425,-3.589723168,50,0,20.00137089,0,0,0,90.00000001 +29.22,50.425,-3.589720353,50,0,20.00048261,0,0,0,90.00000001 +29.23,50.425,-3.589717539,50,0,19.99937226,0,0,0,90.00000001 +29.24,50.425,-3.589714725,50,0,19.99959433,0,0,0,90.00000001 +29.25,50.425,-3.58971191,50,0,20.00026054,0,0,0,90.00000001 +29.26,50.425,-3.589709096,50,0,20.00026054,0,0,0,90.00000001 +29.27,50.425,-3.589706281,50,0,19.99959433,0,0,0,90.00000001 +29.28,50.425,-3.589703467,50,0,19.99937226,0,0,0,90.00000001 +29.29,50.425,-3.589700653,50,0,20.00048261,0,0,0,90.00000001 +29.3,50.425,-3.589697838,50,0,20.00137089,0,0,0,90.00000001 +29.31,50.425,-3.589695023,50,0,20.00048261,0,0,0,90.00000001 +29.32,50.425,-3.589692209,50,0,19.99937226,0,0,0,90.00000001 +29.33,50.425,-3.589689395,50,0,19.99937226,0,0,0,90.00000001 +29.34,50.425,-3.58968658,50,0,19.99937226,0,0,0,90.00000001 +29.35,50.425,-3.589683766,50,0,19.99915019,0,0,0,90.00000001 +29.36,50.425,-3.589680952,50,0,19.99959433,0,0,0,90.00000001 +29.37,50.425,-3.589678137,50,0,20.00048261,0,0,0,90.00000001 +29.38,50.425,-3.589675323,50,0,20.00137089,0,0,0,90.00000001 +29.39,50.425,-3.589672508,50,0,20.00159296,0,0,0,90.00000001 +29.4,50.425,-3.589669693,50,0,20.00048261,0,0,0,90.00000001 +29.41,50.425,-3.589666879,50,0,19.99937226,0,0,0,90.00000001 +29.42,50.425,-3.589664065,50,0,19.99937226,0,0,0,90.00000001 +29.43,50.425,-3.58966125,50,0,19.99937226,0,0,0,90.00000001 +29.44,50.425,-3.589658436,50,0,19.99915019,0,0,0,90.00000001 +29.45,50.425,-3.589655622,50,0,19.99937226,0,0,0,90.00000001 +29.46,50.425,-3.589652807,50,0,19.99937226,0,0,0,90.00000001 +29.47,50.425,-3.589649993,50,0,19.99937226,0,0,0,90.00000001 +29.48,50.425,-3.589647179,50,0,20.00048261,0,0,0,90.00000001 +29.49,50.425,-3.589644364,50,0,20.00159296,0,0,0,90.00000001 +29.5,50.425,-3.589641549,50,0,20.00137089,0,0,0,90.00000001 +29.51,50.425,-3.589638735,50,0,20.00048261,0,0,0,90.00000001 +29.52,50.425,-3.58963592,50,0,19.99959433,0,0,0,90.00000001 +29.53,50.425,-3.589633106,50,0,19.99915019,0,0,0,90.00000001 +29.54,50.425,-3.589630292,50,0,19.99937226,0,0,0,90.00000001 +29.55,50.425,-3.589627477,50,0,19.99937226,0,0,0,90.00000001 +29.56,50.425,-3.589624663,50,0,19.99937226,0,0,0,90.00000001 +29.57,50.425,-3.589621849,50,0,20.00048261,0,0,0,90.00000001 +29.58,50.425,-3.589619034,50,0,20.00137089,0,0,0,90.00000001 +29.59,50.425,-3.589616219,50,0,20.00048261,0,0,0,90.00000001 +29.6,50.425,-3.589613405,50,0,19.99937226,0,0,0,90.00000001 +29.61,50.425,-3.589610591,50,0,19.99959433,0,0,0,90.00000001 +29.62,50.425,-3.589607776,50,0,20.00026054,0,0,0,90.00000001 +29.63,50.425,-3.589604962,50,0,20.00026054,0,0,0,90.00000001 +29.64,50.425,-3.589602147,50,0,19.99959433,0,0,0,90.00000001 +29.65,50.425,-3.589599333,50,0,19.99937226,0,0,0,90.00000001 +29.66,50.425,-3.589596519,50,0,20.00048261,0,0,0,90.00000001 +29.67,50.425,-3.589593704,50,0,20.00137089,0,0,0,90.00000001 +29.68,50.425,-3.589590889,50,0,20.00048261,0,0,0,90.00000001 +29.69,50.425,-3.589588075,50,0,19.99937226,0,0,0,90.00000001 +29.7,50.425,-3.589585261,50,0,19.99937226,0,0,0,90.00000001 +29.71,50.425,-3.589582446,50,0,19.99937226,0,0,0,90.00000001 +29.72,50.425,-3.589579632,50,0,19.99915019,0,0,0,90.00000001 +29.73,50.425,-3.589576818,50,0,19.99959433,0,0,0,90.00000001 +29.74,50.425,-3.589574003,50,0,20.00026054,0,0,0,90.00000001 +29.75,50.425,-3.589571189,50,0,20.00048261,0,0,0,90.00000001 +29.76,50.425,-3.589568374,50,0,20.00048261,0,0,0,90.00000001 +29.77,50.425,-3.58956556,50,0,20.00048261,0,0,0,90.00000001 +29.78,50.425,-3.589562745,50,0,20.00048261,0,0,0,90.00000001 +29.79,50.425,-3.589559931,50,0,20.00026054,0,0,0,90.00000001 +29.8,50.425,-3.589557116,50,0,19.99959433,0,0,0,90.00000001 +29.81,50.425,-3.589554302,50,0,19.99915019,0,0,0,90.00000001 +29.82,50.425,-3.589551488,50,0,19.99959433,0,0,0,90.00000001 +29.83,50.425,-3.589548673,50,0,20.00026054,0,0,0,90.00000001 +29.84,50.425,-3.589545859,50,0,20.00048261,0,0,0,90.00000001 +29.85,50.425,-3.589543044,50,0,20.00048261,0,0,0,90.00000001 +29.86,50.425,-3.58954023,50,0,20.00026054,0,0,0,90.00000001 +29.87,50.425,-3.589537415,50,0,19.99959433,0,0,0,90.00000001 +29.88,50.425,-3.589534601,50,0,19.99915019,0,0,0,90.00000001 +29.89,50.425,-3.589531787,50,0,19.99959433,0,0,0,90.00000001 +29.9,50.425,-3.589528972,50,0,20.00026054,0,0,0,90.00000001 +29.91,50.425,-3.589526158,50,0,20.00048261,0,0,0,90.00000001 +29.92,50.425,-3.589523343,50,0,20.00048261,0,0,0,90.00000001 +29.93,50.425,-3.589520529,50,0,20.00048261,0,0,0,90.00000001 +29.94,50.425,-3.589517714,50,0,20.00048261,0,0,0,90.00000001 +29.95,50.425,-3.5895149,50,0,20.00026054,0,0,0,90.00000001 +29.96,50.425,-3.589512085,50,0,19.99959433,0,0,0,90.00000001 +29.97,50.425,-3.589509271,50,0,19.99915019,0,0,0,90.00000001 +29.98,50.425,-3.589506457,50,0,19.99937226,0,0,0,90.00000001 +29.99,50.425,-3.589503642,50,0,19.99915019,0,0,0,90.00000001 +30,50.425,-3.589500828,50,0,19.99737363,0,0,0,90.00000001 +30.01,50.425,-3.589498014,50,0,19.99293224,0,0,0,90.00000001 +30.02,50.425,-3.5894952,50,0,19.98471566,0,0,0,90.00000001 +30.03,50.425,-3.589492389,50,0,19.97450046,0,0,0,90.00000001 +30.04,50.425,-3.589489579,50,0,19.96495146,0,0,0,90.00000001 +30.05,50.425,-3.58948677,50,0,19.95540247,0,0,0,90.00000001 +30.06,50.425,-3.589483962,50,0,19.94474312,0,0,0,90.00000001 +30.07,50.425,-3.589481157,50,0,19.93430585,0,0,0,90.00000001 +30.08,50.425,-3.589478352,50,0,19.92475685,0,0,0,90.00000001 +30.09,50.425,-3.589475549,50,0,19.91498579,0,0,0,90.00000001 +30.1,50.425,-3.589472747,50,0,19.90454851,0,0,0,90.00000001 +30.11,50.425,-3.589469947,50,0,19.89411124,0,0,0,90.00000001 +30.12,50.425,-3.589467148,50,0,19.88434017,0,0,0,90.00000001 +30.13,50.425,-3.589464351,50,0,19.87501325,0,0,0,90.00000001 +30.14,50.425,-3.589461554,50,0,19.86546425,0,0,0,90.00000001 +30.15,50.425,-3.58945876,50,0,19.85569319,0,0,0,90.00000001 +30.16,50.425,-3.589455966,50,0,19.84547798,0,0,0,90.00000001 +30.17,50.425,-3.589453174,50,0,19.83459657,0,0,0,90.00000001 +30.18,50.425,-3.589450384,50,0,19.82415929,0,0,0,90.00000001 +30.19,50.425,-3.589447595,50,0,19.8146103,0,0,0,90.00000001 +30.2,50.425,-3.589444807,50,0,19.80483923,0,0,0,90.00000001 +30.21,50.425,-3.589442021,50,0,19.79462403,0,0,0,90.00000001 +30.22,50.425,-3.589439236,50,0,19.78485296,0,0,0,90.00000001 +30.23,50.425,-3.589436453,50,0,19.77552603,0,0,0,90.00000001 +30.24,50.425,-3.58943367,50,0,19.76575497,0,0,0,90.00000001 +30.25,50.425,-3.58943089,50,0,19.7553177,0,0,0,90.00000001 +30.26,50.425,-3.58942811,50,0,19.74488042,0,0,0,90.00000001 +30.27,50.425,-3.589425333,50,0,19.73488729,0,0,0,90.00000001 +30.28,50.425,-3.589422556,50,0,19.72467208,0,0,0,90.00000001 +30.29,50.425,-3.589419781,50,0,19.71379067,0,0,0,90.00000001 +30.3,50.425,-3.589417008,50,0,19.70335339,0,0,0,90.00000001 +30.31,50.425,-3.589414236,50,0,19.6938044,0,0,0,90.00000001 +30.32,50.425,-3.589411465,50,0,19.6842554,0,0,0,90.00000001 +30.33,50.425,-3.589408696,50,0,19.6747064,0,0,0,90.00000001 +30.34,50.425,-3.589405928,50,0,19.66537948,0,0,0,90.00000001 +30.35,50.425,-3.589403161,50,0,19.65560841,0,0,0,90.00000001 +30.36,50.425,-3.589400396,50,0,19.64517114,0,0,0,90.00000001 +30.37,50.425,-3.589397632,50,0,19.63473386,0,0,0,90.00000001 +30.38,50.425,-3.58939487,50,0,19.62474073,0,0,0,90.00000001 +30.39,50.425,-3.589392109,50,0,19.61452552,0,0,0,90.00000001 +30.4,50.425,-3.589389349,50,0,19.60364411,0,0,0,90.00000001 +30.41,50.425,-3.589386592,50,0,19.59320684,0,0,0,90.00000001 +30.42,50.425,-3.589383835,50,0,19.58387991,0,0,0,90.00000001 +30.43,50.425,-3.58938108,50,0,19.57499712,0,0,0,90.00000001 +30.44,50.425,-3.589378326,50,0,19.5656702,0,0,0,90.00000001 +30.45,50.425,-3.589375573,50,0,19.55523292,0,0,0,90.00000001 +30.46,50.425,-3.589372822,50,0,19.54457358,0,0,0,90.00000001 +30.47,50.425,-3.589370073,50,0,19.53502458,0,0,0,90.00000001 +30.48,50.425,-3.589367324,50,0,19.52547559,0,0,0,90.00000001 +30.49,50.425,-3.589364577,50,0,19.51481624,0,0,0,90.00000001 +30.5,50.425,-3.589361832,50,0,19.50437897,0,0,0,90.00000001 +30.51,50.425,-3.589359088,50,0,19.49482997,0,0,0,90.00000001 +30.52,50.425,-3.589356345,50,0,19.48505891,0,0,0,90.00000001 +30.53,50.425,-3.589353604,50,0,19.47462163,0,0,0,90.00000001 +30.54,50.425,-3.589350864,50,0,19.46396229,0,0,0,90.00000001 +30.55,50.425,-3.589348126,50,0,19.45330295,0,0,0,90.00000001 +30.56,50.425,-3.589345389,50,0,19.44286567,0,0,0,90.00000001 +30.57,50.425,-3.589342654,50,0,19.43331668,0,0,0,90.00000001 +30.58,50.425,-3.58933992,50,0,19.42465596,0,0,0,90.00000001 +30.59,50.425,-3.589337187,50,0,19.41532903,0,0,0,90.00000001 +30.6,50.425,-3.589334455,50,0,19.40466969,0,0,0,90.00000001 +30.61,50.425,-3.589331726,50,0,19.39423241,0,0,0,90.00000001 +30.62,50.425,-3.589328997,50,0,19.38468342,0,0,0,90.00000001 +30.63,50.425,-3.58932627,50,0,19.37491235,0,0,0,90.00000001 +30.64,50.425,-3.589323544,50,0,19.36447508,0,0,0,90.00000001 +30.65,50.425,-3.58932082,50,0,19.3540378,0,0,0,90.00000001 +30.66,50.425,-3.589318097,50,0,19.34426674,0,0,0,90.00000001 +30.67,50.425,-3.589315376,50,0,19.33471774,0,0,0,90.00000001 +30.68,50.425,-3.589312655,50,0,19.32428047,0,0,0,90.00000001 +30.69,50.425,-3.589309937,50,0,19.31362113,0,0,0,90.00000001 +30.7,50.425,-3.58930722,50,0,19.3042942,0,0,0,90.00000001 +30.71,50.425,-3.589304504,50,0,19.29563348,0,0,0,90.00000001 +30.72,50.425,-3.589301789,50,0,19.28608448,0,0,0,90.00000001 +30.73,50.425,-3.589299076,50,0,19.27542514,0,0,0,90.00000001 +30.74,50.425,-3.589296364,50,0,19.26409959,0,0,0,90.00000001 +30.75,50.425,-3.589293654,50,0,19.25299611,0,0,0,90.00000001 +30.76,50.425,-3.589290946,50,0,19.2427809,0,0,0,90.00000001 +30.77,50.425,-3.589288238,50,0,19.23300983,0,0,0,90.00000001 +30.78,50.425,-3.589285533,50,0,19.22346084,0,0,0,90.00000001 +30.79,50.425,-3.589282828,50,0,19.21413391,0,0,0,90.00000001 +30.8,50.425,-3.589280125,50,0,19.20436285,0,0,0,90.00000001 +30.81,50.425,-3.589277423,50,0,19.19414764,0,0,0,90.00000001 +30.82,50.425,-3.589274723,50,0,19.18437658,0,0,0,90.00000001 +30.83,50.425,-3.589272024,50,0,19.17482758,0,0,0,90.00000001 +30.84,50.425,-3.589269326,50,0,19.16439031,0,0,0,90.00000001 +30.85,50.425,-3.58926663,50,0,19.15373096,0,0,0,90.00000001 +30.86,50.425,-3.589263936,50,0,19.14418197,0,0,0,90.00000001 +30.87,50.425,-3.589261242,50,0,19.13463297,0,0,0,90.00000001 +30.88,50.425,-3.58925855,50,0,19.12397363,0,0,0,90.00000001 +30.89,50.425,-3.58925586,50,0,19.11353635,0,0,0,90.00000001 +30.9,50.425,-3.589253171,50,0,19.10398736,0,0,0,90.00000001 +30.91,50.425,-3.589250483,50,0,19.09421629,0,0,0,90.00000001 +30.92,50.425,-3.589247797,50,0,19.08377902,0,0,0,90.00000001 +30.93,50.425,-3.589245112,50,0,19.07334174,0,0,0,90.00000001 +30.94,50.425,-3.589242429,50,0,19.06379275,0,0,0,90.00000001 +30.95,50.425,-3.589239747,50,0,19.05513203,0,0,0,90.00000001 +30.96,50.425,-3.589237066,50,0,19.04558303,0,0,0,90.00000001 +30.97,50.425,-3.589234386,50,0,19.03403541,0,0,0,90.00000001 +30.98,50.425,-3.589231709,50,0,19.02248779,0,0,0,90.00000001 +30.99,50.425,-3.589229033,50,0,19.01293879,0,0,0,90.00000001 +31,50.425,-3.589226358,50,0,19.00427808,0,0,0,90.00000001 +31.01,50.425,-3.589223684,50,0,18.99472908,0,0,0,90.00000001 +31.02,50.425,-3.589221012,50,0,18.98429181,0,0,0,90.00000001 +31.03,50.425,-3.589218341,50,0,18.97385453,0,0,0,90.00000001 +31.04,50.425,-3.589215672,50,0,18.96408347,0,0,0,90.00000001 +31.05,50.425,-3.589213004,50,0,18.95453447,0,0,0,90.00000001 +31.06,50.425,-3.589210337,50,0,18.9440972,0,0,0,90.00000001 +31.07,50.425,-3.589207672,50,0,18.93343785,0,0,0,90.00000001 +31.08,50.425,-3.589205009,50,0,18.92388886,0,0,0,90.00000001 +31.09,50.425,-3.589202346,50,0,18.91433986,0,0,0,90.00000001 +31.1,50.425,-3.589199685,50,0,18.90368052,0,0,0,90.00000001 +31.11,50.425,-3.589197026,50,0,18.89324324,0,0,0,90.00000001 +31.12,50.425,-3.589194368,50,0,18.88369425,0,0,0,90.00000001 +31.13,50.425,-3.589191711,50,0,18.87392318,0,0,0,90.00000001 +31.14,50.425,-3.589189056,50,0,18.86348591,0,0,0,90.00000001 +31.15,50.425,-3.589186402,50,0,18.85304863,0,0,0,90.00000001 +31.16,50.425,-3.58918375,50,0,18.84349964,0,0,0,90.00000001 +31.17,50.425,-3.589181099,50,0,18.83483892,0,0,0,90.00000001 +31.18,50.425,-3.589178449,50,0,18.82528992,0,0,0,90.00000001 +31.19,50.425,-3.5891758,50,0,18.81396437,0,0,0,90.00000001 +31.2,50.425,-3.589173154,50,0,18.80308296,0,0,0,90.00000001 +31.21,50.425,-3.589170509,50,0,18.79375603,0,0,0,90.00000001 +31.22,50.425,-3.589167864,50,0,18.78398497,0,0,0,90.00000001 +31.23,50.425,-3.589165222,50,0,18.77354769,0,0,0,90.00000001 +31.24,50.425,-3.589162581,50,0,18.7639987,0,0,0,90.00000001 +31.25,50.425,-3.589159941,50,0,18.7544497,0,0,0,90.00000001 +31.26,50.425,-3.589157302,50,0,18.74379036,0,0,0,90.00000001 +31.27,50.425,-3.589154666,50,0,18.73335308,0,0,0,90.00000001 +31.28,50.425,-3.58915203,50,0,18.72380409,0,0,0,90.00000001 +31.29,50.425,-3.589149396,50,0,18.71403302,0,0,0,90.00000001 +31.3,50.425,-3.589146763,50,0,18.70381781,0,0,0,90.00000001 +31.31,50.425,-3.589144132,50,0,18.69404675,0,0,0,90.00000001 +31.32,50.425,-3.589141502,50,0,18.68449775,0,0,0,90.00000001 +31.33,50.425,-3.589138873,50,0,18.67406048,0,0,0,90.00000001 +31.34,50.425,-3.589136246,50,0,18.66317907,0,0,0,90.00000001 +31.35,50.425,-3.589133621,50,0,18.65296386,0,0,0,90.00000001 +31.36,50.425,-3.589130996,50,0,18.6431928,0,0,0,90.00000001 +31.37,50.425,-3.589128374,50,0,18.6336438,0,0,0,90.00000001 +31.38,50.425,-3.589125752,50,0,18.62431687,0,0,0,90.00000001 +31.39,50.425,-3.589123132,50,0,18.61432374,0,0,0,90.00000001 +31.4,50.425,-3.589120513,50,0,18.60322026,0,0,0,90.00000001 +31.41,50.425,-3.589117896,50,0,18.59233884,0,0,0,90.00000001 +31.42,50.425,-3.589115281,50,0,18.58301192,0,0,0,90.00000001 +31.43,50.425,-3.589112666,50,0,18.5743512,0,0,0,90.00000001 +31.44,50.425,-3.589110053,50,0,18.5648022,0,0,0,90.00000001 +31.45,50.425,-3.589107441,50,0,18.55436493,0,0,0,90.00000001 +31.46,50.425,-3.589104831,50,0,18.54370558,0,0,0,90.00000001 +31.47,50.425,-3.589102222,50,0,18.53304624,0,0,0,90.00000001 +31.48,50.425,-3.589099615,50,0,18.52260897,0,0,0,90.00000001 +31.49,50.425,-3.589097009,50,0,18.5128379,0,0,0,90.00000001 +31.5,50.425,-3.589094405,50,0,18.50351097,0,0,0,90.00000001 +31.51,50.425,-3.589091801,50,0,18.49373991,0,0,0,90.00000001 +31.52,50.425,-3.5890892,50,0,18.48330263,0,0,0,90.00000001 +31.53,50.425,-3.589086599,50,0,18.47286536,0,0,0,90.00000001 +31.54,50.425,-3.589084001,50,0,18.4630943,0,0,0,90.00000001 +31.55,50.425,-3.589081403,50,0,18.45376737,0,0,0,90.00000001 +31.56,50.425,-3.589078807,50,0,18.4439963,0,0,0,90.00000001 +31.57,50.425,-3.589076212,50,0,18.43355903,0,0,0,90.00000001 +31.58,50.425,-3.589073619,50,0,18.42289968,0,0,0,90.00000001 +31.59,50.425,-3.589071027,50,0,18.41246241,0,0,0,90.00000001 +31.6,50.425,-3.589068437,50,0,18.40269134,0,0,0,90.00000001 +31.61,50.425,-3.589065848,50,0,18.39336442,0,0,0,90.00000001 +31.62,50.425,-3.58906326,50,0,18.38359335,0,0,0,90.00000001 +31.63,50.425,-3.589060674,50,0,18.37337815,0,0,0,90.00000001 +31.64,50.425,-3.589058089,50,0,18.36360708,0,0,0,90.00000001 +31.65,50.425,-3.589055506,50,0,18.35405809,0,0,0,90.00000001 +31.66,50.425,-3.589052923,50,0,18.34362081,0,0,0,90.00000001 +31.67,50.425,-3.589050343,50,0,18.33296147,0,0,0,90.00000001 +31.68,50.425,-3.589047764,50,0,18.32341247,0,0,0,90.00000001 +31.69,50.425,-3.589045186,50,0,18.31386348,0,0,0,90.00000001 +31.7,50.425,-3.589042609,50,0,18.30320413,0,0,0,90.00000001 +31.71,50.425,-3.589040035,50,0,18.29276686,0,0,0,90.00000001 +31.72,50.425,-3.589037461,50,0,18.28321786,0,0,0,90.00000001 +31.73,50.425,-3.589034889,50,0,18.2734468,0,0,0,90.00000001 +31.74,50.425,-3.589032318,50,0,18.26323159,0,0,0,90.00000001 +31.75,50.425,-3.589029749,50,0,18.25346053,0,0,0,90.00000001 +31.76,50.425,-3.589027181,50,0,18.2441336,0,0,0,90.00000001 +31.77,50.425,-3.589024614,50,0,18.23436254,0,0,0,90.00000001 +31.78,50.425,-3.589022049,50,0,18.22392526,0,0,0,90.00000001 +31.79,50.425,-3.589019485,50,0,18.21326592,0,0,0,90.00000001 +31.8,50.425,-3.589016923,50,0,18.20260657,0,0,0,90.00000001 +31.81,50.425,-3.589014362,50,0,18.1921693,0,0,0,90.00000001 +31.82,50.425,-3.589011803,50,0,18.18239823,0,0,0,90.00000001 +31.83,50.425,-3.589009245,50,0,18.17307131,0,0,0,90.00000001 +31.84,50.425,-3.589006688,50,0,18.16330024,0,0,0,90.00000001 +31.85,50.425,-3.589004133,50,0,18.15286297,0,0,0,90.00000001 +31.86,50.425,-3.589001579,50,0,18.14242569,0,0,0,90.00000001 +31.87,50.425,-3.588999027,50,0,18.13265463,0,0,0,90.00000001 +31.88,50.425,-3.588996476,50,0,18.1233277,0,0,0,90.00000001 +31.89,50.425,-3.588993926,50,0,18.11377871,0,0,0,90.00000001 +31.9,50.425,-3.588991378,50,0,18.10400764,0,0,0,90.00000001 +31.91,50.425,-3.588988831,50,0,18.09379244,0,0,0,90.00000001 +31.92,50.425,-3.588986285,50,0,18.08291102,0,0,0,90.00000001 +31.93,50.425,-3.588983742,50,0,18.07247375,0,0,0,90.00000001 +31.94,50.425,-3.588981199,50,0,18.06292475,0,0,0,90.00000001 +31.95,50.425,-3.588978658,50,0,18.05315369,0,0,0,90.00000001 +31.96,50.425,-3.588976118,50,0,18.04293848,0,0,0,90.00000001 +31.97,50.425,-3.58897358,50,0,18.03294535,0,0,0,90.00000001 +31.98,50.425,-3.588971043,50,0,18.02295221,0,0,0,90.00000001 +31.99,50.425,-3.588968507,50,0,18.01295908,0,0,0,90.00000001 +32,50.425,-3.588965974,50,0,18.00341008,0,0,0,90.00000001 +32.01,50.425,-3.58896344,50,0,17.99319488,0,0,0,90.00000001 +32.02,50.425,-3.588960909,50,0,17.98209139,0,0,0,90.00000001 +32.03,50.425,-3.58895838,50,0,17.97209826,0,0,0,90.00000001 +32.04,50.425,-3.588955851,50,0,17.96321547,0,0,0,90.00000001 +32.05,50.425,-3.588953324,50,0,17.95366648,0,0,0,90.00000001 +32.06,50.425,-3.588950798,50,0,17.94345127,0,0,0,90.00000001 +32.07,50.425,-3.588948274,50,0,17.93345814,0,0,0,90.00000001 +32.08,50.425,-3.588945751,50,0,17.92324293,0,0,0,90.00000001 +32.09,50.425,-3.588943229,50,0,17.91236152,0,0,0,90.00000001 +32.1,50.425,-3.58894071,50,0,17.90192424,0,0,0,90.00000001 +32.11,50.425,-3.588938191,50,0,17.89237525,0,0,0,90.00000001 +32.12,50.425,-3.588935674,50,0,17.88260418,0,0,0,90.00000001 +32.13,50.425,-3.588933158,50,0,17.87238898,0,0,0,90.00000001 +32.14,50.425,-3.588930644,50,0,17.86261791,0,0,0,90.00000001 +32.15,50.425,-3.588928131,50,0,17.85329099,0,0,0,90.00000001 +32.16,50.425,-3.588925619,50,0,17.84351992,0,0,0,90.00000001 +32.17,50.425,-3.588923109,50,0,17.83330471,0,0,0,90.00000001 +32.18,50.425,-3.5889206,50,0,17.82353365,0,0,0,90.00000001 +32.19,50.425,-3.588918093,50,0,17.81398465,0,0,0,90.00000001 +32.2,50.425,-3.588915586,50,0,17.80354738,0,0,0,90.00000001 +32.21,50.425,-3.588913082,50,0,17.79266597,0,0,0,90.00000001 +32.22,50.425,-3.588910579,50,0,17.78245076,0,0,0,90.00000001 +32.23,50.425,-3.588908077,50,0,17.77245763,0,0,0,90.00000001 +32.24,50.425,-3.588905577,50,0,17.76224242,0,0,0,90.00000001 +32.25,50.425,-3.588903078,50,0,17.75247136,0,0,0,90.00000001 +32.26,50.425,-3.588900581,50,0,17.74292236,0,0,0,90.00000001 +32.27,50.425,-3.588898084,50,0,17.73248509,0,0,0,90.00000001 +32.28,50.425,-3.58889559,50,0,17.72182574,0,0,0,90.00000001 +32.29,50.425,-3.588893097,50,0,17.71249882,0,0,0,90.00000001 +32.3,50.425,-3.588890605,50,0,17.70361603,0,0,0,90.00000001 +32.31,50.425,-3.588888114,50,0,17.69317875,0,0,0,90.00000001 +32.32,50.425,-3.588885625,50,0,17.68163113,0,0,0,90.00000001 +32.33,50.425,-3.588883138,50,0,17.67119386,0,0,0,90.00000001 +32.34,50.425,-3.588880652,50,0,17.66253314,0,0,0,90.00000001 +32.35,50.425,-3.588878167,50,0,17.65409449,0,0,0,90.00000001 +32.36,50.425,-3.588875683,50,0,17.6445455,0,0,0,90.00000001 +32.37,50.425,-3.588873201,50,0,17.63388615,0,0,0,90.00000001 +32.38,50.425,-3.58887072,50,0,17.6225606,0,0,0,90.00000001 +32.39,50.425,-3.588868241,50,0,17.61167919,0,0,0,90.00000001 +32.4,50.425,-3.588865764,50,0,17.60213019,0,0,0,90.00000001 +32.41,50.425,-3.588863287,50,0,17.59258119,0,0,0,90.00000001 +32.42,50.425,-3.588860812,50,0,17.58192185,0,0,0,90.00000001 +32.43,50.425,-3.588858339,50,0,17.57170665,0,0,0,90.00000001 +32.44,50.425,-3.588855867,50,0,17.56282386,0,0,0,90.00000001 +32.45,50.425,-3.588853396,50,0,17.55349693,0,0,0,90.00000001 +32.46,50.425,-3.588850926,50,0,17.54283759,0,0,0,90.00000001 +32.47,50.425,-3.588848459,50,0,17.53217825,0,0,0,90.00000001 +32.48,50.425,-3.588845992,50,0,17.52196304,0,0,0,90.00000001 +32.49,50.425,-3.588843527,50,0,17.51196991,0,0,0,90.00000001 +32.5,50.425,-3.588841064,50,0,17.50264298,0,0,0,90.00000001 +32.51,50.425,-3.588838601,50,0,17.49309398,0,0,0,90.00000001 +32.52,50.425,-3.58883614,50,0,17.48243464,0,0,0,90.00000001 +32.53,50.425,-3.588833681,50,0,17.47199737,0,0,0,90.00000001 +32.54,50.425,-3.588831223,50,0,17.46244837,0,0,0,90.00000001 +32.55,50.425,-3.588828766,50,0,17.4526773,0,0,0,90.00000001 +32.56,50.425,-3.588826311,50,0,17.44224003,0,0,0,90.00000001 +32.57,50.425,-3.588823857,50,0,17.43180275,0,0,0,90.00000001 +32.58,50.425,-3.588821405,50,0,17.42203169,0,0,0,90.00000001 +32.59,50.425,-3.588818954,50,0,17.41270476,0,0,0,90.00000001 +32.6,50.425,-3.588816504,50,0,17.4029337,0,0,0,90.00000001 +32.61,50.425,-3.588814056,50,0,17.39249642,0,0,0,90.00000001 +32.62,50.425,-3.588811609,50,0,17.38205915,0,0,0,90.00000001 +32.63,50.425,-3.588809164,50,0,17.37228808,0,0,0,90.00000001 +32.64,50.425,-3.58880672,50,0,17.36296116,0,0,0,90.00000001 +32.65,50.425,-3.588804277,50,0,17.35319009,0,0,0,90.00000001 +32.66,50.425,-3.588801836,50,0,17.34275282,0,0,0,90.00000001 +32.67,50.425,-3.588799396,50,0,17.33231554,0,0,0,90.00000001 +32.68,50.425,-3.588796958,50,0,17.32254448,0,0,0,90.00000001 +32.69,50.425,-3.588794521,50,0,17.31299548,0,0,0,90.00000001 +32.7,50.425,-3.588792085,50,0,17.30233614,0,0,0,90.00000001 +32.71,50.425,-3.588789651,50,0,17.29078852,0,0,0,90.00000001 +32.72,50.425,-3.588787219,50,0,17.28035124,0,0,0,90.00000001 +32.73,50.425,-3.588784788,50,0,17.27169052,0,0,0,90.00000001 +32.74,50.425,-3.588782358,50,0,17.26302981,0,0,0,90.00000001 +32.75,50.425,-3.588779929,50,0,17.2528146,0,0,0,90.00000001 +32.76,50.425,-3.588777502,50,0,17.24215526,0,0,0,90.00000001 +32.77,50.425,-3.588775077,50,0,17.23260626,0,0,0,90.00000001 +32.78,50.425,-3.588772652,50,0,17.22305727,0,0,0,90.00000001 +32.79,50.425,-3.588770229,50,0,17.21239792,0,0,0,90.00000001 +32.8,50.425,-3.588767808,50,0,17.20196065,0,0,0,90.00000001 +32.81,50.425,-3.588765388,50,0,17.19218958,0,0,0,90.00000001 +32.82,50.425,-3.588762969,50,0,17.18175231,0,0,0,90.00000001 +32.83,50.425,-3.588760552,50,0,17.17109296,0,0,0,90.00000001 +32.84,50.425,-3.588758137,50,0,17.16176604,0,0,0,90.00000001 +32.85,50.425,-3.588755722,50,0,17.15310532,0,0,0,90.00000001 +32.86,50.425,-3.588753309,50,0,17.14333426,0,0,0,90.00000001 +32.87,50.425,-3.588750897,50,0,17.13223077,0,0,0,90.00000001 +32.88,50.425,-3.588748487,50,0,17.12134936,0,0,0,90.00000001 +32.89,50.425,-3.588746079,50,0,17.11180036,0,0,0,90.00000001 +32.9,50.425,-3.588743671,50,0,17.10225137,0,0,0,90.00000001 +32.91,50.425,-3.588741265,50,0,17.09159202,0,0,0,90.00000001 +32.92,50.425,-3.588738861,50,0,17.08115475,0,0,0,90.00000001 +32.93,50.425,-3.588736458,50,0,17.07160575,0,0,0,90.00000001 +32.94,50.425,-3.588734056,50,0,17.06205676,0,0,0,90.00000001 +32.95,50.425,-3.588731656,50,0,17.05250776,0,0,0,90.00000001 +32.96,50.425,-3.588729257,50,0,17.04318084,0,0,0,90.00000001 +32.97,50.425,-3.588726859,50,0,17.03340977,0,0,0,90.00000001 +32.98,50.425,-3.588724463,50,0,17.02297249,0,0,0,90.00000001 +32.99,50.425,-3.588722068,50,0,17.01231315,0,0,0,90.00000001 +33,50.425,-3.588719675,50,0,17.00165381,0,0,0,90.00000001 +33.01,50.425,-3.588717283,50,0,16.99121653,0,0,0,90.00000001 +33.02,50.425,-3.588714893,50,0,16.98144547,0,0,0,90.00000001 +33.03,50.425,-3.588712504,50,0,16.97211854,0,0,0,90.00000001 +33.04,50.425,-3.588710116,50,0,16.96234748,0,0,0,90.00000001 +33.05,50.425,-3.58870773,50,0,16.9519102,0,0,0,90.00000001 +33.06,50.425,-3.588705345,50,0,16.94147293,0,0,0,90.00000001 +33.07,50.425,-3.588702962,50,0,16.93170186,0,0,0,90.00000001 +33.08,50.425,-3.58870058,50,0,16.92237494,0,0,0,90.00000001 +33.09,50.425,-3.588698199,50,0,16.91260387,0,0,0,90.00000001 +33.1,50.425,-3.58869582,50,0,16.9021666,0,0,0,90.00000001 +33.11,50.425,-3.588693442,50,0,16.89172932,0,0,0,90.00000001 +33.12,50.425,-3.588691066,50,0,16.88195826,0,0,0,90.00000001 +33.13,50.425,-3.588688691,50,0,16.87240926,0,0,0,90.00000001 +33.14,50.425,-3.588686317,50,0,16.86197199,0,0,0,90.00000001 +33.15,50.425,-3.588683945,50,0,16.85109057,0,0,0,90.00000001 +33.16,50.425,-3.588681575,50,0,16.84087537,0,0,0,90.00000001 +33.17,50.425,-3.588679205,50,0,16.8311043,0,0,0,90.00000001 +33.18,50.425,-3.588676838,50,0,16.82155531,0,0,0,90.00000001 +33.19,50.425,-3.588674471,50,0,16.81222838,0,0,0,90.00000001 +33.2,50.425,-3.588672106,50,0,16.80245732,0,0,0,90.00000001 +33.21,50.425,-3.588669742,50,0,16.79202004,0,0,0,90.00000001 +33.22,50.425,-3.58866738,50,0,16.7813607,0,0,0,90.00000001 +33.23,50.425,-3.588665019,50,0,16.77092342,0,0,0,90.00000001 +33.24,50.425,-3.58866266,50,0,16.76115236,0,0,0,90.00000001 +33.25,50.425,-3.588660302,50,0,16.75182543,0,0,0,90.00000001 +33.26,50.425,-3.588657945,50,0,16.74227644,0,0,0,90.00000001 +33.27,50.425,-3.58865559,50,0,16.73250537,0,0,0,90.00000001 +33.28,50.425,-3.588653236,50,0,16.72229016,0,0,0,90.00000001 +33.29,50.425,-3.588650883,50,0,16.71140875,0,0,0,90.00000001 +33.3,50.425,-3.588648533,50,0,16.70097148,0,0,0,90.00000001 +33.31,50.425,-3.588646183,50,0,16.69142248,0,0,0,90.00000001 +33.32,50.425,-3.588643835,50,0,16.68165142,0,0,0,90.00000001 +33.33,50.425,-3.588641488,50,0,16.67143621,0,0,0,90.00000001 +33.34,50.425,-3.588639143,50,0,16.66166515,0,0,0,90.00000001 +33.35,50.425,-3.588636799,50,0,16.65211615,0,0,0,90.00000001 +33.36,50.425,-3.588634456,50,0,16.64167888,0,0,0,90.00000001 +33.37,50.425,-3.588632115,50,0,16.63101953,0,0,0,90.00000001 +33.38,50.425,-3.588629776,50,0,16.62147053,0,0,0,90.00000001 +33.39,50.425,-3.588627437,50,0,16.61192154,0,0,0,90.00000001 +33.4,50.425,-3.5886251,50,0,16.6012622,0,0,0,90.00000001 +33.41,50.425,-3.588622765,50,0,16.59082492,0,0,0,90.00000001 +33.42,50.425,-3.588620431,50,0,16.58127593,0,0,0,90.00000001 +33.43,50.425,-3.588618098,50,0,16.57172693,0,0,0,90.00000001 +33.44,50.425,-3.588615767,50,0,16.56217793,0,0,0,90.00000001 +33.45,50.425,-3.588613437,50,0,16.55262894,0,0,0,90.00000001 +33.46,50.425,-3.588611108,50,0,16.54219166,0,0,0,90.00000001 +33.47,50.425,-3.588608781,50,0,16.53153232,0,0,0,90.00000001 +33.48,50.425,-3.588606456,50,0,16.52198332,0,0,0,90.00000001 +33.49,50.425,-3.588604131,50,0,16.51243433,0,0,0,90.00000001 +33.5,50.425,-3.588601808,50,0,16.50155291,0,0,0,90.00000001 +33.51,50.425,-3.588599487,50,0,16.49044943,0,0,0,90.00000001 +33.52,50.425,-3.588597167,50,0,16.4804563,0,0,0,90.00000001 +33.53,50.425,-3.588594849,50,0,16.47112937,0,0,0,90.00000001 +33.54,50.425,-3.588592531,50,0,16.46158037,0,0,0,90.00000001 +33.55,50.425,-3.588590216,50,0,16.45180931,0,0,0,90.00000001 +33.56,50.425,-3.588587901,50,0,16.4415941,0,0,0,90.00000001 +33.57,50.425,-3.588585588,50,0,16.43071269,0,0,0,90.00000001 +33.58,50.425,-3.588583277,50,0,16.42027542,0,0,0,90.00000001 +33.59,50.425,-3.588580967,50,0,16.41072642,0,0,0,90.00000001 +33.6,50.425,-3.588578658,50,0,16.40117742,0,0,0,90.00000001 +33.61,50.425,-3.588576351,50,0,16.39162843,0,0,0,90.00000001 +33.62,50.425,-3.588574045,50,0,16.3823015,0,0,0,90.00000001 +33.63,50.425,-3.58857174,50,0,16.37253044,0,0,0,90.00000001 +33.64,50.425,-3.588569437,50,0,16.36209316,0,0,0,90.00000001 +33.65,50.425,-3.588567135,50,0,16.35143382,0,0,0,90.00000001 +33.66,50.425,-3.588564835,50,0,16.34077447,0,0,0,90.00000001 +33.67,50.425,-3.588562536,50,0,16.3303372,0,0,0,90.00000001 +33.68,50.425,-3.588560239,50,0,16.32056614,0,0,0,90.00000001 +33.69,50.425,-3.588557943,50,0,16.31123921,0,0,0,90.00000001 +33.7,50.425,-3.588555648,50,0,16.30146814,0,0,0,90.00000001 +33.71,50.425,-3.588553355,50,0,16.29103087,0,0,0,90.00000001 +33.72,50.425,-3.588551063,50,0,16.28059359,0,0,0,90.00000001 +33.73,50.425,-3.588548773,50,0,16.27082253,0,0,0,90.00000001 +33.74,50.425,-3.588546484,50,0,16.2614956,0,0,0,90.00000001 +33.75,50.425,-3.588544196,50,0,16.25172454,0,0,0,90.00000001 +33.76,50.425,-3.58854191,50,0,16.24150933,0,0,0,90.00000001 +33.77,50.425,-3.588539625,50,0,16.23173827,0,0,0,90.00000001 +33.78,50.425,-3.588537342,50,0,16.22218927,0,0,0,90.00000001 +33.79,50.425,-3.588535059,50,0,16.211752,0,0,0,90.00000001 +33.8,50.425,-3.588532779,50,0,16.20087058,0,0,0,90.00000001 +33.81,50.425,-3.5885305,50,0,16.19065538,0,0,0,90.00000001 +33.82,50.425,-3.588528222,50,0,16.18088431,0,0,0,90.00000001 +33.83,50.425,-3.588525946,50,0,16.17133532,0,0,0,90.00000001 +33.84,50.425,-3.588523671,50,0,16.16200839,0,0,0,90.00000001 +33.85,50.425,-3.588521397,50,0,16.15223733,0,0,0,90.00000001 +33.86,50.425,-3.588519125,50,0,16.14180005,0,0,0,90.00000001 +33.87,50.425,-3.588516854,50,0,16.13114071,0,0,0,90.00000001 +33.88,50.425,-3.588514585,50,0,16.12070343,0,0,0,90.00000001 +33.89,50.425,-3.588512317,50,0,16.11093237,0,0,0,90.00000001 +33.9,50.425,-3.588510051,50,0,16.10138337,0,0,0,90.00000001 +33.91,50.425,-3.588507785,50,0,16.0909461,0,0,0,90.00000001 +33.92,50.425,-3.588505522,50,0,16.08006468,0,0,0,90.00000001 +33.93,50.425,-3.58850326,50,0,16.06984948,0,0,0,90.00000001 +33.94,50.425,-3.588500999,50,0,16.06007841,0,0,0,90.00000001 +33.95,50.425,-3.58849874,50,0,16.05052942,0,0,0,90.00000001 +33.96,50.425,-3.588496482,50,0,16.04120249,0,0,0,90.00000001 +33.97,50.425,-3.588494225,50,0,16.03165349,0,0,0,90.00000001 +33.98,50.425,-3.58849197,50,0,16.02188243,0,0,0,90.00000001 +33.99,50.425,-3.588489716,50,0,16.01166723,0,0,0,90.00000001 +34,50.425,-3.588487463,50,0,16.00078581,0,0,0,90.00000001 +34.01,50.425,-3.588485213,50,0,15.99034854,0,0,0,90.00000001 +34.02,50.425,-3.588482963,50,0,15.98102161,0,0,0,90.00000001 +34.03,50.425,-3.588480715,50,0,15.97191676,0,0,0,90.00000001 +34.04,50.425,-3.588478468,50,0,15.96192362,0,0,0,90.00000001 +34.05,50.425,-3.588476222,50,0,15.95104221,0,0,0,90.00000001 +34.06,50.425,-3.588473979,50,0,15.94038286,0,0,0,90.00000001 +34.07,50.425,-3.588471736,50,0,15.93016766,0,0,0,90.00000001 +34.08,50.425,-3.588469495,50,0,15.92017452,0,0,0,90.00000001 +34.09,50.425,-3.588467256,50,0,15.9108476,0,0,0,90.00000001 +34.1,50.425,-3.588465017,50,0,15.9012986,0,0,0,90.00000001 +34.11,50.425,-3.58846278,50,0,15.89063926,0,0,0,90.00000001 +34.12,50.425,-3.588460545,50,0,15.88020198,0,0,0,90.00000001 +34.13,50.425,-3.588458311,50,0,15.87065299,0,0,0,90.00000001 +34.14,50.425,-3.588456078,50,0,15.86110399,0,0,0,90.00000001 +34.15,50.425,-3.588453847,50,0,15.85155499,0,0,0,90.00000001 +34.16,50.425,-3.588451617,50,0,15.84222807,0,0,0,90.00000001 +34.17,50.425,-3.588449388,50,0,15.832457,0,0,0,90.00000001 +34.18,50.425,-3.588447161,50,0,15.82179766,0,0,0,90.00000001 +34.19,50.425,-3.588444935,50,0,15.81047211,0,0,0,90.00000001 +34.2,50.425,-3.588442711,50,0,15.79959069,0,0,0,90.00000001 +34.21,50.425,-3.588440489,50,0,15.7900417,0,0,0,90.00000001 +34.22,50.425,-3.588438267,50,0,15.78071477,0,0,0,90.00000001 +34.23,50.425,-3.588436047,50,0,15.77072164,0,0,0,90.00000001 +34.24,50.425,-3.588433829,50,0,15.7607285,0,0,0,90.00000001 +34.25,50.425,-3.588431611,50,0,15.75095744,0,0,0,90.00000001 +34.26,50.425,-3.588429396,50,0,15.74118637,0,0,0,90.00000001 +34.27,50.425,-3.588427181,50,0,15.73097116,0,0,0,90.00000001 +34.28,50.425,-3.588424968,50,0,15.72008975,0,0,0,90.00000001 +34.29,50.425,-3.588422757,50,0,15.70965248,0,0,0,90.00000001 +34.3,50.425,-3.588420547,50,0,15.70010348,0,0,0,90.00000001 +34.31,50.425,-3.588418338,50,0,15.69033242,0,0,0,90.00000001 +34.32,50.425,-3.588416131,50,0,15.68011721,0,0,0,90.00000001 +34.33,50.425,-3.588413925,50,0,15.67034615,0,0,0,90.00000001 +34.34,50.425,-3.588411721,50,0,15.66101922,0,0,0,90.00000001 +34.35,50.425,-3.588409517,50,0,15.65147022,0,0,0,90.00000001 +34.36,50.425,-3.588407316,50,0,15.64169916,0,0,0,90.00000001 +34.37,50.425,-3.588405115,50,0,15.63148395,0,0,0,90.00000001 +34.38,50.425,-3.588402916,50,0,15.62060254,0,0,0,90.00000001 +34.39,50.425,-3.588400719,50,0,15.61016527,0,0,0,90.00000001 +34.4,50.425,-3.588398523,50,0,15.60061627,0,0,0,90.00000001 +34.41,50.425,-3.588396328,50,0,15.5908452,0,0,0,90.00000001 +34.42,50.425,-3.588394135,50,0,15.58040793,0,0,0,90.00000001 +34.43,50.425,-3.588391943,50,0,15.56997066,0,0,0,90.00000001 +34.44,50.425,-3.588389753,50,0,15.56019959,0,0,0,90.00000001 +34.45,50.425,-3.588387564,50,0,15.55087266,0,0,0,90.00000001 +34.46,50.425,-3.588385376,50,0,15.5411016,0,0,0,90.00000001 +34.47,50.425,-3.58838319,50,0,15.53066433,0,0,0,90.00000001 +34.48,50.425,-3.588381005,50,0,15.52022705,0,0,0,90.00000001 +34.49,50.425,-3.588378822,50,0,15.51045599,0,0,0,90.00000001 +34.5,50.425,-3.58837664,50,0,15.50090699,0,0,0,90.00000001 +34.51,50.425,-3.588374459,50,0,15.49046971,0,0,0,90.00000001 +34.52,50.425,-3.58837228,50,0,15.47981037,0,0,0,90.00000001 +34.53,50.425,-3.588370103,50,0,15.47026137,0,0,0,90.00000001 +34.54,50.425,-3.588367926,50,0,15.46071238,0,0,0,90.00000001 +34.55,50.425,-3.588365751,50,0,15.45005303,0,0,0,90.00000001 +34.56,50.425,-3.588363578,50,0,15.43983783,0,0,0,90.00000001 +34.57,50.425,-3.588361406,50,0,15.43095504,0,0,0,90.00000001 +34.58,50.425,-3.588359235,50,0,15.42162812,0,0,0,90.00000001 +34.59,50.425,-3.588357065,50,0,15.41096877,0,0,0,90.00000001 +34.6,50.425,-3.588354898,50,0,15.4005315,0,0,0,90.00000001 +34.61,50.425,-3.588352731,50,0,15.39076043,0,0,0,90.00000001 +34.62,50.425,-3.588350566,50,0,15.38032316,0,0,0,90.00000001 +34.63,50.425,-3.588348402,50,0,15.36966381,0,0,0,90.00000001 +34.64,50.425,-3.588346241,50,0,15.36011482,0,0,0,90.00000001 +34.65,50.425,-3.588344079,50,0,15.35056582,0,0,0,90.00000001 +34.66,50.425,-3.58834192,50,0,15.33990648,0,0,0,90.00000001 +34.67,50.425,-3.588339762,50,0,15.32969127,0,0,0,90.00000001 +34.68,50.425,-3.588337606,50,0,15.32080849,0,0,0,90.00000001 +34.69,50.425,-3.58833545,50,0,15.31148156,0,0,0,90.00000001 +34.7,50.425,-3.588333296,50,0,15.30060015,0,0,0,90.00000001 +34.71,50.425,-3.588331144,50,0,15.28927459,0,0,0,90.00000001 +34.72,50.425,-3.588328993,50,0,15.27861525,0,0,0,90.00000001 +34.73,50.425,-3.588326844,50,0,15.26884419,0,0,0,90.00000001 +34.74,50.425,-3.588324696,50,0,15.25951726,0,0,0,90.00000001 +34.75,50.425,-3.588322549,50,0,15.24996826,0,0,0,90.00000001 +34.76,50.425,-3.588320404,50,0,15.24041927,0,0,0,90.00000001 +34.77,50.425,-3.58831826,50,0,15.23109234,0,0,0,90.00000001 +34.78,50.425,-3.588316117,50,0,15.22132128,0,0,0,90.00000001 +34.79,50.425,-3.588313976,50,0,15.210884,0,0,0,90.00000001 +34.8,50.425,-3.588311836,50,0,15.20044673,0,0,0,90.00000001 +34.81,50.425,-3.588309698,50,0,15.19045359,0,0,0,90.00000001 +34.82,50.425,-3.588307561,50,0,15.18023839,0,0,0,90.00000001 +34.83,50.425,-3.588305425,50,0,15.16935697,0,0,0,90.00000001 +34.84,50.425,-3.588303292,50,0,15.15914177,0,0,0,90.00000001 +34.85,50.425,-3.588301159,50,0,15.15025898,0,0,0,90.00000001 +34.86,50.425,-3.588299028,50,0,15.14093206,0,0,0,90.00000001 +34.87,50.425,-3.588296897,50,0,15.13049478,0,0,0,90.00000001 +34.88,50.425,-3.58829477,50,0,15.12072372,0,0,0,90.00000001 +34.89,50.425,-3.588292642,50,0,15.11139679,0,0,0,90.00000001 +34.9,50.425,-3.588290516,50,0,15.10051538,0,0,0,90.00000001 +34.91,50.425,-3.588288392,50,0,15.08918982,0,0,0,90.00000001 +34.92,50.425,-3.58828627,50,0,15.07941876,0,0,0,90.00000001 +34.93,50.425,-3.588284148,50,0,15.06986976,0,0,0,90.00000001 +34.94,50.425,-3.588282028,50,0,15.05921042,0,0,0,90.00000001 +34.95,50.425,-3.58827991,50,0,15.04877314,0,0,0,90.00000001 +34.96,50.425,-3.588277793,50,0,15.03922415,0,0,0,90.00000001 +34.97,50.425,-3.588275677,50,0,15.02967515,0,0,0,90.00000001 +34.98,50.425,-3.588273563,50,0,15.02012616,0,0,0,90.00000001 +34.99,50.425,-3.58827145,50,0,15.01079923,0,0,0,90.00000001 +35,50.425,-3.588269338,50,0,15.00102817,0,0,0,90.00000001 +35.01,50.425,-3.588267228,50,0,14.99059089,0,0,0,90.00000001 +35.02,50.425,-3.588265119,50,0,14.97993155,0,0,0,90.00000001 +35.03,50.425,-3.588263012,50,0,14.96949427,0,0,0,90.00000001 +35.04,50.425,-3.588260906,50,0,14.95972321,0,0,0,90.00000001 +35.05,50.425,-3.588258802,50,0,14.95017421,0,0,0,90.00000001 +35.06,50.425,-3.588256698,50,0,14.93995901,0,0,0,90.00000001 +35.07,50.425,-3.588254597,50,0,14.92996587,0,0,0,90.00000001 +35.08,50.425,-3.588252497,50,0,14.92086102,0,0,0,90.00000001 +35.09,50.425,-3.588250397,50,0,14.91086788,0,0,0,90.00000001 +35.1,50.425,-3.5882483,50,0,14.89954233,0,0,0,90.00000001 +35.11,50.425,-3.588246204,50,0,14.88910505,0,0,0,90.00000001 +35.12,50.425,-3.58824411,50,0,14.88022227,0,0,0,90.00000001 +35.13,50.425,-3.588242016,50,0,14.87089534,0,0,0,90.00000001 +35.14,50.425,-3.588239924,50,0,14.860236,0,0,0,90.00000001 +35.15,50.425,-3.588237834,50,0,14.84979872,0,0,0,90.00000001 +35.16,50.425,-3.588235745,50,0,14.84002766,0,0,0,90.00000001 +35.17,50.425,-3.588233657,50,0,14.82959038,0,0,0,90.00000001 +35.18,50.425,-3.588231571,50,0,14.81893104,0,0,0,90.00000001 +35.19,50.425,-3.588229487,50,0,14.80938204,0,0,0,90.00000001 +35.2,50.425,-3.588227403,50,0,14.79983305,0,0,0,90.00000001 +35.21,50.425,-3.588225321,50,0,14.7891737,0,0,0,90.00000001 +35.22,50.425,-3.588223241,50,0,14.77873643,0,0,0,90.00000001 +35.23,50.425,-3.588221162,50,0,14.7694095,0,0,0,90.00000001 +35.24,50.425,-3.588219084,50,0,14.76052671,0,0,0,90.00000001 +35.25,50.425,-3.588217008,50,0,14.75119979,0,0,0,90.00000001 +35.26,50.425,-3.588214932,50,0,14.74076251,0,0,0,90.00000001 +35.27,50.425,-3.588212859,50,0,14.7298811,0,0,0,90.00000001 +35.28,50.425,-3.588210787,50,0,14.7196659,0,0,0,90.00000001 +35.29,50.425,-3.588208716,50,0,14.70967276,0,0,0,90.00000001 +35.3,50.425,-3.588206647,50,0,14.69945756,0,0,0,90.00000001 +35.31,50.425,-3.588204579,50,0,14.68968649,0,0,0,90.00000001 +35.32,50.425,-3.588202513,50,0,14.68013749,0,0,0,90.00000001 +35.33,50.425,-3.588200447,50,0,14.66970022,0,0,0,90.00000001 +35.34,50.425,-3.588198384,50,0,14.65904088,0,0,0,90.00000001 +35.35,50.425,-3.588196322,50,0,14.64971395,0,0,0,90.00000001 +35.36,50.425,-3.588194261,50,0,14.64083116,0,0,0,90.00000001 +35.37,50.425,-3.588192201,50,0,14.63039389,0,0,0,90.00000001 +35.38,50.425,-3.588190143,50,0,14.61884627,0,0,0,90.00000001 +35.39,50.425,-3.588188087,50,0,14.60840899,0,0,0,90.00000001 +35.4,50.425,-3.588186032,50,0,14.5995262,0,0,0,90.00000001 +35.41,50.425,-3.588183978,50,0,14.59019928,0,0,0,90.00000001 +35.42,50.425,-3.588181925,50,0,14.57953993,0,0,0,90.00000001 +35.43,50.425,-3.588179875,50,0,14.56910266,0,0,0,90.00000001 +35.44,50.425,-3.588177825,50,0,14.55955367,0,0,0,90.00000001 +35.45,50.425,-3.588175777,50,0,14.5497826,0,0,0,90.00000001 +35.46,50.425,-3.58817373,50,0,14.53934533,0,0,0,90.00000001 +35.47,50.425,-3.588171685,50,0,14.52868598,0,0,0,90.00000001 +35.48,50.425,-3.588169641,50,0,14.51824871,0,0,0,90.00000001 +35.49,50.425,-3.588167599,50,0,14.50869971,0,0,0,90.00000001 +35.5,50.425,-3.588165558,50,0,14.50003899,0,0,0,90.00000001 +35.51,50.425,-3.588163518,50,0,14.49071207,0,0,0,90.00000001 +35.52,50.425,-3.588161479,50,0,14.48005272,0,0,0,90.00000001 +35.53,50.425,-3.588159443,50,0,14.46939338,0,0,0,90.00000001 +35.54,50.425,-3.588157407,50,0,14.45917817,0,0,0,90.00000001 +35.55,50.425,-3.588155373,50,0,14.44918504,0,0,0,90.00000001 +35.56,50.425,-3.588153341,50,0,14.43985811,0,0,0,90.00000001 +35.57,50.425,-3.588151309,50,0,14.43030912,0,0,0,90.00000001 +35.58,50.425,-3.588149279,50,0,14.4194277,0,0,0,90.00000001 +35.59,50.425,-3.588147251,50,0,14.40832422,0,0,0,90.00000001 +35.6,50.425,-3.588145224,50,0,14.39855316,0,0,0,90.00000001 +35.61,50.425,-3.588143199,50,0,14.38989244,0,0,0,90.00000001 +35.62,50.425,-3.588141174,50,0,14.38056551,0,0,0,90.00000001 +35.63,50.425,-3.588139151,50,0,14.3696841,0,0,0,90.00000001 +35.64,50.425,-3.58813713,50,0,14.35858061,0,0,0,90.00000001 +35.65,50.425,-3.58813511,50,0,14.34858748,0,0,0,90.00000001 +35.66,50.425,-3.588133092,50,0,14.33926055,0,0,0,90.00000001 +35.67,50.425,-3.588131074,50,0,14.32971156,0,0,0,90.00000001 +35.68,50.425,-3.588129059,50,0,14.31994049,0,0,0,90.00000001 +35.69,50.425,-3.588127044,50,0,14.30972529,0,0,0,90.00000001 +35.7,50.425,-3.588125031,50,0,14.29884388,0,0,0,90.00000001 +35.71,50.425,-3.58812302,50,0,14.2884066,0,0,0,90.00000001 +35.72,50.425,-3.58812101,50,0,14.2788576,0,0,0,90.00000001 +35.73,50.425,-3.588119001,50,0,14.26930861,0,0,0,90.00000001 +35.74,50.425,-3.588116994,50,0,14.25975961,0,0,0,90.00000001 +35.75,50.425,-3.588114988,50,0,14.25021062,0,0,0,90.00000001 +35.76,50.425,-3.588112983,50,0,14.23955127,0,0,0,90.00000001 +35.77,50.425,-3.58811098,50,0,14.22800365,0,0,0,90.00000001 +35.78,50.425,-3.588108979,50,0,14.21756638,0,0,0,90.00000001 +35.79,50.425,-3.588106979,50,0,14.20890566,0,0,0,90.00000001 +35.8,50.425,-3.58810498,50,0,14.20024494,0,0,0,90.00000001 +35.81,50.425,-3.588102982,50,0,14.19002974,0,0,0,90.00000001 +35.82,50.425,-3.588100986,50,0,14.17914832,0,0,0,90.00000001 +35.83,50.425,-3.588098992,50,0,14.16893312,0,0,0,90.00000001 +35.84,50.425,-3.588096998,50,0,14.15916205,0,0,0,90.00000001 +35.85,50.425,-3.588095007,50,0,14.14939099,0,0,0,90.00000001 +35.86,50.425,-3.588093016,50,0,14.13939785,0,0,0,90.00000001 +35.87,50.425,-3.588091027,50,0,14.12918265,0,0,0,90.00000001 +35.88,50.425,-3.58808904,50,0,14.11918951,0,0,0,90.00000001 +35.89,50.425,-3.588087053,50,0,14.10941845,0,0,0,90.00000001 +35.9,50.425,-3.588085069,50,0,14.09964738,0,0,0,90.00000001 +35.91,50.425,-3.588083085,50,0,14.08943218,0,0,0,90.00000001 +35.92,50.425,-3.588081103,50,0,14.07855076,0,0,0,90.00000001 +35.93,50.425,-3.588079123,50,0,14.06811349,0,0,0,90.00000001 +35.94,50.425,-3.588077144,50,0,14.05856449,0,0,0,90.00000001 +35.95,50.425,-3.588075166,50,0,14.0490155,0,0,0,90.00000001 +35.96,50.425,-3.58807319,50,0,14.0394665,0,0,0,90.00000001 +35.97,50.425,-3.588071215,50,0,14.02991751,0,0,0,90.00000001 +35.98,50.425,-3.588069241,50,0,14.01925816,0,0,0,90.00000001 +35.99,50.425,-3.588067269,50,0,14.00793261,0,0,0,90.00000001 +36,50.425,-3.588065299,50,0,13.99816154,0,0,0,90.00000001 +36.01,50.425,-3.58806333,50,0,13.9897229,0,0,0,90.00000001 +36.02,50.425,-3.588061361,50,0,13.9801739,0,0,0,90.00000001 +36.03,50.425,-3.588059395,50,0,13.96951456,0,0,0,90.00000001 +36.04,50.425,-3.58805743,50,0,13.95929935,0,0,0,90.00000001 +36.05,50.425,-3.588055466,50,0,13.94930622,0,0,0,90.00000001 +36.06,50.425,-3.588053504,50,0,13.93886894,0,0,0,90.00000001 +36.07,50.425,-3.588051543,50,0,13.92843167,0,0,0,90.00000001 +36.08,50.425,-3.588049584,50,0,13.9186606,0,0,0,90.00000001 +36.09,50.425,-3.588047626,50,0,13.90911161,0,0,0,90.00000001 +36.1,50.425,-3.588045669,50,0,13.89867433,0,0,0,90.00000001 +36.11,50.425,-3.588043714,50,0,13.88801499,0,0,0,90.00000001 +36.12,50.425,-3.588041761,50,0,13.87846599,0,0,0,90.00000001 +36.13,50.425,-3.588039808,50,0,13.868917,0,0,0,90.00000001 +36.14,50.425,-3.588037857,50,0,13.85825765,0,0,0,90.00000001 +36.15,50.425,-3.588035908,50,0,13.84782038,0,0,0,90.00000001 +36.16,50.425,-3.58803396,50,0,13.83827138,0,0,0,90.00000001 +36.17,50.425,-3.588032013,50,0,13.82872239,0,0,0,90.00000001 +36.18,50.425,-3.588030068,50,0,13.81917339,0,0,0,90.00000001 +36.19,50.425,-3.588028124,50,0,13.80962439,0,0,0,90.00000001 +36.2,50.425,-3.588026181,50,0,13.79918712,0,0,0,90.00000001 +36.21,50.425,-3.58802424,50,0,13.78852778,0,0,0,90.00000001 +36.22,50.425,-3.588022301,50,0,13.77897878,0,0,0,90.00000001 +36.23,50.425,-3.588020362,50,0,13.76942979,0,0,0,90.00000001 +36.24,50.425,-3.588018425,50,0,13.75877044,0,0,0,90.00000001 +36.25,50.425,-3.58801649,50,0,13.74833317,0,0,0,90.00000001 +36.26,50.425,-3.588014556,50,0,13.73878417,0,0,0,90.00000001 +36.27,50.425,-3.588012623,50,0,13.72901311,0,0,0,90.00000001 +36.28,50.425,-3.588010692,50,0,13.71857583,0,0,0,90.00000001 +36.29,50.425,-3.588008762,50,0,13.70813856,0,0,0,90.00000001 +36.3,50.425,-3.588006834,50,0,13.69836749,0,0,0,90.00000001 +36.31,50.425,-3.588004907,50,0,13.68904056,0,0,0,90.00000001 +36.32,50.425,-3.588002981,50,0,13.6792695,0,0,0,90.00000001 +36.33,50.425,-3.588001057,50,0,13.66883222,0,0,0,90.00000001 +36.34,50.425,-3.587999134,50,0,13.65839495,0,0,0,90.00000001 +36.35,50.425,-3.587997213,50,0,13.64862389,0,0,0,90.00000001 +36.36,50.425,-3.587995293,50,0,13.63929696,0,0,0,90.00000001 +36.37,50.425,-3.587993374,50,0,13.62952589,0,0,0,90.00000001 +36.38,50.425,-3.587991457,50,0,13.61908862,0,0,0,90.00000001 +36.39,50.425,-3.587989541,50,0,13.60865134,0,0,0,90.00000001 +36.4,50.425,-3.587987627,50,0,13.59865821,0,0,0,90.00000001 +36.41,50.425,-3.587985714,50,0,13.588443,0,0,0,90.00000001 +36.42,50.425,-3.587983802,50,0,13.57756159,0,0,0,90.00000001 +36.43,50.425,-3.587981893,50,0,13.56712432,0,0,0,90.00000001 +36.44,50.425,-3.587979984,50,0,13.55779739,0,0,0,90.00000001 +36.45,50.425,-3.587978077,50,0,13.5489146,0,0,0,90.00000001 +36.46,50.425,-3.587976171,50,0,13.53958768,0,0,0,90.00000001 +36.47,50.425,-3.587974266,50,0,13.5291504,0,0,0,90.00000001 +36.48,50.425,-3.587972363,50,0,13.51849106,0,0,0,90.00000001 +36.49,50.425,-3.587970462,50,0,13.50894206,0,0,0,90.00000001 +36.5,50.425,-3.587968561,50,0,13.49939307,0,0,0,90.00000001 +36.51,50.425,-3.587966662,50,0,13.48851165,0,0,0,90.00000001 +36.52,50.425,-3.587964765,50,0,13.4771861,0,0,0,90.00000001 +36.53,50.425,-3.587962869,50,0,13.46652676,0,0,0,90.00000001 +36.54,50.425,-3.587960975,50,0,13.45697776,0,0,0,90.00000001 +36.55,50.425,-3.587959082,50,0,13.44853911,0,0,0,90.00000001 +36.56,50.425,-3.58795719,50,0,13.4398784,0,0,0,90.00000001 +36.57,50.425,-3.587955299,50,0,13.42966319,0,0,0,90.00000001 +36.58,50.425,-3.58795341,50,0,13.41878178,0,0,0,90.00000001 +36.59,50.425,-3.587951523,50,0,13.4083445,0,0,0,90.00000001 +36.6,50.425,-3.587949636,50,0,13.39790723,0,0,0,90.00000001 +36.61,50.425,-3.587947752,50,0,13.3879141,0,0,0,90.00000001 +36.62,50.425,-3.587945869,50,0,13.37880924,0,0,0,90.00000001 +36.63,50.425,-3.587943986,50,0,13.36903817,0,0,0,90.00000001 +36.64,50.425,-3.587942106,50,0,13.35837883,0,0,0,90.00000001 +36.65,50.425,-3.587940227,50,0,13.34816362,0,0,0,90.00000001 +36.66,50.425,-3.587938349,50,0,13.33839256,0,0,0,90.00000001 +36.67,50.425,-3.587936473,50,0,13.32884356,0,0,0,90.00000001 +36.68,50.425,-3.587934598,50,0,13.31929457,0,0,0,90.00000001 +36.69,50.425,-3.587932724,50,0,13.30863522,0,0,0,90.00000001 +36.7,50.425,-3.587930852,50,0,13.2970876,0,0,0,90.00000001 +36.71,50.425,-3.587928982,50,0,13.28665033,0,0,0,90.00000001 +36.72,50.425,-3.587927113,50,0,13.27798961,0,0,0,90.00000001 +36.73,50.425,-3.587925245,50,0,13.26955096,0,0,0,90.00000001 +36.74,50.425,-3.587923378,50,0,13.26000197,0,0,0,90.00000001 +36.75,50.425,-3.587921513,50,0,13.24934262,0,0,0,90.00000001 +36.76,50.425,-3.587919649,50,0,13.23801707,0,0,0,90.00000001 +36.77,50.425,-3.587917787,50,0,13.22713565,0,0,0,90.00000001 +36.78,50.425,-3.587915927,50,0,13.21758666,0,0,0,90.00000001 +36.79,50.425,-3.587914067,50,0,13.20825973,0,0,0,90.00000001 +36.8,50.425,-3.587912209,50,0,13.1982666,0,0,0,90.00000001 +36.81,50.425,-3.587910353,50,0,13.18805139,0,0,0,90.00000001 +36.82,50.425,-3.587908497,50,0,13.17761412,0,0,0,90.00000001 +36.83,50.425,-3.587906644,50,0,13.16762098,0,0,0,90.00000001 +36.84,50.425,-3.587904792,50,0,13.15851613,0,0,0,90.00000001 +36.85,50.425,-3.58790294,50,0,13.14874506,0,0,0,90.00000001 +36.86,50.425,-3.587901091,50,0,13.13808572,0,0,0,90.00000001 +36.87,50.425,-3.587899243,50,0,13.12787051,0,0,0,90.00000001 +36.88,50.425,-3.587897396,50,0,13.11809945,0,0,0,90.00000001 +36.89,50.425,-3.587895551,50,0,13.10832838,0,0,0,90.00000001 +36.9,50.425,-3.587893707,50,0,13.09811318,0,0,0,90.00000001 +36.91,50.425,-3.587891864,50,0,13.08723176,0,0,0,90.00000001 +36.92,50.425,-3.587890024,50,0,13.07679449,0,0,0,90.00000001 +36.93,50.425,-3.587888184,50,0,13.06746756,0,0,0,90.00000001 +36.94,50.425,-3.587886346,50,0,13.05858478,0,0,0,90.00000001 +36.95,50.425,-3.587884509,50,0,13.04925785,0,0,0,90.00000001 +36.96,50.425,-3.587882673,50,0,13.03859851,0,0,0,90.00000001 +36.97,50.425,-3.587880839,50,0,13.02727295,0,0,0,90.00000001 +36.98,50.425,-3.587879007,50,0,13.01750189,0,0,0,90.00000001 +36.99,50.425,-3.587877176,50,0,13.00906324,0,0,0,90.00000001 +37,50.425,-3.587875345,50,0,12.99929218,0,0,0,90.00000001 +37.01,50.425,-3.587873517,50,0,12.98796662,0,0,0,90.00000001 +37.02,50.425,-3.58787169,50,0,12.97730728,0,0,0,90.00000001 +37.03,50.425,-3.587869865,50,0,12.96775828,0,0,0,90.00000001 +37.04,50.425,-3.58786804,50,0,12.95798722,0,0,0,90.00000001 +37.05,50.425,-3.587866218,50,0,12.94754994,0,0,0,90.00000001 +37.06,50.425,-3.587864396,50,0,12.93711267,0,0,0,90.00000001 +37.07,50.425,-3.587862577,50,0,12.9273416,0,0,0,90.00000001 +37.08,50.425,-3.587860758,50,0,12.91801468,0,0,0,90.00000001 +37.09,50.425,-3.587858941,50,0,12.90824361,0,0,0,90.00000001 +37.1,50.425,-3.587857125,50,0,12.89802841,0,0,0,90.00000001 +37.11,50.425,-3.587855311,50,0,12.88825734,0,0,0,90.00000001 +37.12,50.425,-3.587853498,50,0,12.87870835,0,0,0,90.00000001 +37.13,50.425,-3.587851686,50,0,12.86827107,0,0,0,90.00000001 +37.14,50.425,-3.587849876,50,0,12.85761173,0,0,0,90.00000001 +37.15,50.425,-3.587848068,50,0,12.84806273,0,0,0,90.00000001 +37.16,50.425,-3.58784626,50,0,12.83851374,0,0,0,90.00000001 +37.17,50.425,-3.587844454,50,0,12.82785439,0,0,0,90.00000001 +37.18,50.425,-3.58784265,50,0,12.81741712,0,0,0,90.00000001 +37.19,50.425,-3.587840847,50,0,12.80786812,0,0,0,90.00000001 +37.2,50.425,-3.587839045,50,0,12.79809706,0,0,0,90.00000001 +37.21,50.425,-3.587837245,50,0,12.78765978,0,0,0,90.00000001 +37.22,50.425,-3.587835446,50,0,12.77722251,0,0,0,90.00000001 +37.23,50.425,-3.587833649,50,0,12.76745144,0,0,0,90.00000001 +37.24,50.425,-3.587831853,50,0,12.75812451,0,0,0,90.00000001 +37.25,50.425,-3.587830058,50,0,12.74835345,0,0,0,90.00000001 +37.26,50.425,-3.587828265,50,0,12.73791617,0,0,0,90.00000001 +37.27,50.425,-3.587826473,50,0,12.7274789,0,0,0,90.00000001 +37.28,50.425,-3.587824683,50,0,12.71748577,0,0,0,90.00000001 +37.29,50.425,-3.587822894,50,0,12.70727056,0,0,0,90.00000001 +37.3,50.425,-3.587821106,50,0,12.69661122,0,0,0,90.00000001 +37.31,50.425,-3.587819321,50,0,12.68706222,0,0,0,90.00000001 +37.32,50.425,-3.587817536,50,0,12.67862357,0,0,0,90.00000001 +37.33,50.425,-3.587815752,50,0,12.66885251,0,0,0,90.00000001 +37.34,50.425,-3.58781397,50,0,12.65752696,0,0,0,90.00000001 +37.35,50.425,-3.58781219,50,0,12.64686761,0,0,0,90.00000001 +37.36,50.425,-3.587810411,50,0,12.63731862,0,0,0,90.00000001 +37.37,50.425,-3.587808633,50,0,12.62754755,0,0,0,90.00000001 +37.38,50.425,-3.587806857,50,0,12.61733235,0,0,0,90.00000001 +37.39,50.425,-3.587805082,50,0,12.60756128,0,0,0,90.00000001 +37.4,50.425,-3.587803309,50,0,12.59801228,0,0,0,90.00000001 +37.41,50.425,-3.587801536,50,0,12.58757501,0,0,0,90.00000001 +37.42,50.425,-3.587799766,50,0,12.57691567,0,0,0,90.00000001 +37.43,50.425,-3.587797997,50,0,12.56758874,0,0,0,90.00000001 +37.44,50.425,-3.587796229,50,0,12.55870595,0,0,0,90.00000001 +37.45,50.425,-3.587794462,50,0,12.54849075,0,0,0,90.00000001 +37.46,50.425,-3.587792697,50,0,12.53760933,0,0,0,90.00000001 +37.47,50.425,-3.587790934,50,0,12.52739413,0,0,0,90.00000001 +37.48,50.425,-3.587789171,50,0,12.51762306,0,0,0,90.00000001 +37.49,50.425,-3.587787411,50,0,12.507852,0,0,0,90.00000001 +37.5,50.425,-3.587785651,50,0,12.49763679,0,0,0,90.00000001 +37.51,50.425,-3.587783893,50,0,12.48675538,0,0,0,90.00000001 +37.52,50.425,-3.587782137,50,0,12.47631811,0,0,0,90.00000001 +37.53,50.425,-3.587780382,50,0,12.46676911,0,0,0,90.00000001 +37.54,50.425,-3.587778628,50,0,12.45722012,0,0,0,90.00000001 +37.55,50.425,-3.587776876,50,0,12.44767112,0,0,0,90.00000001 +37.56,50.425,-3.587775125,50,0,12.43812212,0,0,0,90.00000001 +37.57,50.425,-3.587773375,50,0,12.42768485,0,0,0,90.00000001 +37.58,50.425,-3.587771627,50,0,12.4170255,0,0,0,90.00000001 +37.59,50.425,-3.587769881,50,0,12.40747651,0,0,0,90.00000001 +37.6,50.425,-3.587768135,50,0,12.39792751,0,0,0,90.00000001 +37.61,50.425,-3.587766391,50,0,12.38726817,0,0,0,90.00000001 +37.62,50.425,-3.587764649,50,0,12.3768309,0,0,0,90.00000001 +37.63,50.425,-3.587762908,50,0,12.3672819,0,0,0,90.00000001 +37.64,50.425,-3.587761168,50,0,12.35751083,0,0,0,90.00000001 +37.65,50.425,-3.58775943,50,0,12.34729563,0,0,0,90.00000001 +37.66,50.425,-3.587757693,50,0,12.33752456,0,0,0,90.00000001 +37.67,50.425,-3.587755958,50,0,12.32797557,0,0,0,90.00000001 +37.68,50.425,-3.587754223,50,0,12.31753829,0,0,0,90.00000001 +37.69,50.425,-3.587752491,50,0,12.30687895,0,0,0,90.00000001 +37.7,50.425,-3.58775076,50,0,12.29732995,0,0,0,90.00000001 +37.71,50.425,-3.58774903,50,0,12.28778096,0,0,0,90.00000001 +37.72,50.425,-3.587747301,50,0,12.27712161,0,0,0,90.00000001 +37.73,50.425,-3.587745575,50,0,12.26668434,0,0,0,90.00000001 +37.74,50.425,-3.587743849,50,0,12.25713534,0,0,0,90.00000001 +37.75,50.425,-3.587742125,50,0,12.24736428,0,0,0,90.00000001 +37.76,50.425,-3.587740402,50,0,12.23714907,0,0,0,90.00000001 +37.77,50.425,-3.587738681,50,0,12.22737801,0,0,0,90.00000001 +37.78,50.425,-3.587736961,50,0,12.21782901,0,0,0,90.00000001 +37.79,50.425,-3.587735242,50,0,12.20716967,0,0,0,90.00000001 +37.8,50.425,-3.587733525,50,0,12.19584411,0,0,0,90.00000001 +37.81,50.425,-3.58773181,50,0,12.18607305,0,0,0,90.00000001 +37.82,50.425,-3.587730096,50,0,12.1776344,0,0,0,90.00000001 +37.83,50.425,-3.587728382,50,0,12.16808541,0,0,0,90.00000001 +37.84,50.425,-3.587726671,50,0,12.15742606,0,0,0,90.00000001 +37.85,50.425,-3.587724961,50,0,12.14721086,0,0,0,90.00000001 +37.86,50.425,-3.587723252,50,0,12.13743979,0,0,0,90.00000001 +37.87,50.425,-3.587721545,50,0,12.12766873,0,0,0,90.00000001 +37.88,50.425,-3.587719839,50,0,12.11745352,0,0,0,90.00000001 +37.89,50.425,-3.587718134,50,0,12.10657211,0,0,0,90.00000001 +37.9,50.425,-3.587716432,50,0,12.09613483,0,0,0,90.00000001 +37.91,50.425,-3.58771473,50,0,12.08680791,0,0,0,90.00000001 +37.92,50.425,-3.58771303,50,0,12.07770305,0,0,0,90.00000001 +37.93,50.425,-3.587711331,50,0,12.06770992,0,0,0,90.00000001 +37.94,50.425,-3.587709633,50,0,12.0568285,0,0,0,90.00000001 +37.95,50.425,-3.587707938,50,0,12.04639123,0,0,0,90.00000001 +37.96,50.425,-3.587706243,50,0,12.0370643,0,0,0,90.00000001 +37.97,50.425,-3.58770455,50,0,12.02795945,0,0,0,90.00000001 +37.98,50.425,-3.587702858,50,0,12.01796631,0,0,0,90.00000001 +37.99,50.425,-3.587701167,50,0,12.0070849,0,0,0,90.00000001 +38,50.425,-3.587699479,50,0,11.99664762,0,0,0,90.00000001 +38.01,50.425,-3.587697791,50,0,11.98709863,0,0,0,90.00000001 +38.02,50.425,-3.587696105,50,0,11.97732756,0,0,0,90.00000001 +38.03,50.425,-3.58769442,50,0,11.96689029,0,0,0,90.00000001 +38.04,50.425,-3.587692737,50,0,11.95623094,0,0,0,90.00000001 +38.05,50.425,-3.587691055,50,0,11.94579367,0,0,0,90.00000001 +38.06,50.425,-3.587689375,50,0,11.9360226,0,0,0,90.00000001 +38.07,50.425,-3.587687696,50,0,11.92669568,0,0,0,90.00000001 +38.08,50.425,-3.587686018,50,0,11.91692461,0,0,0,90.00000001 +38.09,50.425,-3.587684342,50,0,11.90670941,0,0,0,90.00000001 +38.1,50.425,-3.587682667,50,0,11.89693834,0,0,0,90.00000001 +38.11,50.425,-3.587680994,50,0,11.88761142,0,0,0,90.00000001 +38.12,50.425,-3.587679321,50,0,11.87784035,0,0,0,90.00000001 +38.13,50.425,-3.587677651,50,0,11.86740308,0,0,0,90.00000001 +38.14,50.425,-3.587675981,50,0,11.8569658,0,0,0,90.00000001 +38.15,50.425,-3.587674314,50,0,11.84697267,0,0,0,90.00000001 +38.16,50.425,-3.587672647,50,0,11.83697953,0,0,0,90.00000001 +38.17,50.425,-3.587670982,50,0,11.82676433,0,0,0,90.00000001 +38.18,50.425,-3.587669319,50,0,11.81654912,0,0,0,90.00000001 +38.19,50.425,-3.587667656,50,0,11.80611185,0,0,0,90.00000001 +38.2,50.425,-3.587665996,50,0,11.79611871,0,0,0,90.00000001 +38.21,50.425,-3.587664337,50,0,11.78701386,0,0,0,90.00000001 +38.22,50.425,-3.587662678,50,0,11.77724279,0,0,0,90.00000001 +38.23,50.425,-3.587661022,50,0,11.76658345,0,0,0,90.00000001 +38.24,50.425,-3.587659367,50,0,11.75636824,0,0,0,90.00000001 +38.25,50.425,-3.587657713,50,0,11.74637511,0,0,0,90.00000001 +38.26,50.425,-3.587656061,50,0,11.7361599,0,0,0,90.00000001 +38.27,50.425,-3.58765441,50,0,11.72661091,0,0,0,90.00000001 +38.28,50.425,-3.587652761,50,0,11.71772812,0,0,0,90.00000001 +38.29,50.425,-3.587651112,50,0,11.70751291,0,0,0,90.00000001 +38.3,50.425,-3.587649465,50,0,11.69574322,0,0,0,90.00000001 +38.31,50.425,-3.587647821,50,0,11.68530595,0,0,0,90.00000001 +38.32,50.425,-3.587646177,50,0,11.6768673,0,0,0,90.00000001 +38.33,50.425,-3.587644534,50,0,11.66798451,0,0,0,90.00000001 +38.34,50.425,-3.587642893,50,0,11.65776931,0,0,0,90.00000001 +38.35,50.425,-3.587641253,50,0,11.64710996,0,0,0,90.00000001 +38.36,50.425,-3.587639615,50,0,11.63645062,0,0,0,90.00000001 +38.37,50.425,-3.587637978,50,0,11.62601335,0,0,0,90.00000001 +38.38,50.425,-3.587636343,50,0,11.61624228,0,0,0,90.00000001 +38.39,50.425,-3.587634709,50,0,11.60691535,0,0,0,90.00000001 +38.4,50.425,-3.587633076,50,0,11.59714429,0,0,0,90.00000001 +38.41,50.425,-3.587631445,50,0,11.58670702,0,0,0,90.00000001 +38.42,50.425,-3.587629815,50,0,11.57626974,0,0,0,90.00000001 +38.43,50.425,-3.587628187,50,0,11.56627661,0,0,0,90.00000001 +38.44,50.425,-3.58762656,50,0,11.55628347,0,0,0,90.00000001 +38.45,50.425,-3.587624934,50,0,11.54629034,0,0,0,90.00000001 +38.46,50.425,-3.587623311,50,0,11.53696341,0,0,0,90.00000001 +38.47,50.425,-3.587621687,50,0,11.52741441,0,0,0,90.00000001 +38.48,50.425,-3.587620066,50,0,11.516533,0,0,0,90.00000001 +38.49,50.425,-3.587618446,50,0,11.50542952,0,0,0,90.00000001 +38.5,50.425,-3.587616828,50,0,11.49543638,0,0,0,90.00000001 +38.51,50.425,-3.587615211,50,0,11.48610946,0,0,0,90.00000001 +38.52,50.425,-3.587613595,50,0,11.47656046,0,0,0,90.00000001 +38.53,50.425,-3.587611981,50,0,11.46701146,0,0,0,90.00000001 +38.54,50.425,-3.587610368,50,0,11.45768454,0,0,0,90.00000001 +38.55,50.425,-3.587608756,50,0,11.44791347,0,0,0,90.00000001 +38.56,50.425,-3.587607146,50,0,11.43725413,0,0,0,90.00000001 +38.57,50.425,-3.587605537,50,0,11.42592857,0,0,0,90.00000001 +38.58,50.425,-3.58760393,50,0,11.41504716,0,0,0,90.00000001 +38.59,50.425,-3.587602325,50,0,11.40572024,0,0,0,90.00000001 +38.6,50.425,-3.58760072,50,0,11.39705952,0,0,0,90.00000001 +38.61,50.425,-3.587599117,50,0,11.38728845,0,0,0,90.00000001 +38.62,50.425,-3.587597515,50,0,11.37618497,0,0,0,90.00000001 +38.63,50.425,-3.587595915,50,0,11.36530356,0,0,0,90.00000001 +38.64,50.425,-3.587594317,50,0,11.35597663,0,0,0,90.00000001 +38.65,50.425,-3.587592719,50,0,11.34709384,0,0,0,90.00000001 +38.66,50.425,-3.587591123,50,0,11.33665657,0,0,0,90.00000001 +38.67,50.425,-3.587589528,50,0,11.32533102,0,0,0,90.00000001 +38.68,50.425,-3.587587936,50,0,11.31533788,0,0,0,90.00000001 +38.69,50.425,-3.587586344,50,0,11.30623302,0,0,0,90.00000001 +38.7,50.425,-3.587584753,50,0,11.29623989,0,0,0,90.00000001 +38.71,50.425,-3.587583165,50,0,11.28602468,0,0,0,90.00000001 +38.72,50.425,-3.587581577,50,0,11.27647569,0,0,0,90.00000001 +38.73,50.425,-3.587579991,50,0,11.26670462,0,0,0,90.00000001 +38.74,50.425,-3.587578406,50,0,11.25648942,0,0,0,90.00000001 +38.75,50.425,-3.587576823,50,0,11.24671835,0,0,0,90.00000001 +38.76,50.425,-3.587575241,50,0,11.23716936,0,0,0,90.00000001 +38.77,50.425,-3.58757366,50,0,11.22651001,0,0,0,90.00000001 +38.78,50.425,-3.587572081,50,0,11.21496239,0,0,0,90.00000001 +38.79,50.425,-3.587570504,50,0,11.20452512,0,0,0,90.00000001 +38.8,50.425,-3.587568928,50,0,11.1958644,0,0,0,90.00000001 +38.81,50.425,-3.587567353,50,0,11.18720368,0,0,0,90.00000001 +38.82,50.425,-3.587565779,50,0,11.17698848,0,0,0,90.00000001 +38.83,50.425,-3.587564207,50,0,11.16610706,0,0,0,90.00000001 +38.84,50.425,-3.587562637,50,0,11.15589186,0,0,0,90.00000001 +38.85,50.425,-3.587561067,50,0,11.14612079,0,0,0,90.00000001 +38.86,50.425,-3.5875595,50,0,11.13634973,0,0,0,90.00000001 +38.87,50.425,-3.587557933,50,0,11.12635659,0,0,0,90.00000001 +38.88,50.425,-3.587556368,50,0,11.11614139,0,0,0,90.00000001 +38.89,50.425,-3.587554805,50,0,11.10592618,0,0,0,90.00000001 +38.9,50.425,-3.587553242,50,0,11.09548891,0,0,0,90.00000001 +38.91,50.425,-3.587551682,50,0,11.08549577,0,0,0,90.00000001 +38.92,50.425,-3.587550123,50,0,11.07639092,0,0,0,90.00000001 +38.93,50.425,-3.587548564,50,0,11.06661985,0,0,0,90.00000001 +38.94,50.425,-3.587547008,50,0,11.05596051,0,0,0,90.00000001 +38.95,50.425,-3.587545453,50,0,11.0457453,0,0,0,90.00000001 +38.96,50.425,-3.587543899,50,0,11.03597424,0,0,0,90.00000001 +38.97,50.425,-3.587542347,50,0,11.02642524,0,0,0,90.00000001 +38.98,50.425,-3.587540796,50,0,11.01687625,0,0,0,90.00000001 +38.99,50.425,-3.587539246,50,0,11.00643897,0,0,0,90.00000001 +39,50.425,-3.587537698,50,0,10.99577963,0,0,0,90.00000001 +39.01,50.425,-3.587536152,50,0,10.98623063,0,0,0,90.00000001 +39.02,50.425,-3.587534606,50,0,10.97668164,0,0,0,90.00000001 +39.03,50.425,-3.587533062,50,0,10.96580022,0,0,0,90.00000001 +39.04,50.425,-3.58753152,50,0,10.95469674,0,0,0,90.00000001 +39.05,50.425,-3.587529979,50,0,10.9447036,0,0,0,90.00000001 +39.06,50.425,-3.58752844,50,0,10.93537668,0,0,0,90.00000001 +39.07,50.425,-3.587526901,50,0,10.92582768,0,0,0,90.00000001 +39.08,50.425,-3.587525365,50,0,10.91605662,0,0,0,90.00000001 +39.09,50.425,-3.587523829,50,0,10.90606348,0,0,0,90.00000001 +39.1,50.425,-3.587522295,50,0,10.89607035,0,0,0,90.00000001 +39.11,50.425,-3.587520763,50,0,10.88674342,0,0,0,90.00000001 +39.12,50.425,-3.587519231,50,0,10.87719443,0,0,0,90.00000001 +39.13,50.425,-3.587517701,50,0,10.86653508,0,0,0,90.00000001 +39.14,50.425,-3.587516173,50,0,10.85609781,0,0,0,90.00000001 +39.15,50.425,-3.587514646,50,0,10.84632674,0,0,0,90.00000001 +39.16,50.425,-3.58751312,50,0,10.83588947,0,0,0,90.00000001 +39.17,50.425,-3.587511596,50,0,10.82500805,0,0,0,90.00000001 +39.18,50.425,-3.587510074,50,0,10.81479285,0,0,0,90.00000001 +39.19,50.425,-3.587508552,50,0,10.80502178,0,0,0,90.00000001 +39.2,50.425,-3.587507033,50,0,10.79547279,0,0,0,90.00000001 +39.21,50.425,-3.587505514,50,0,10.78614586,0,0,0,90.00000001 +39.22,50.425,-3.587503997,50,0,10.7763748,0,0,0,90.00000001 +39.23,50.425,-3.587502481,50,0,10.76593752,0,0,0,90.00000001 +39.24,50.425,-3.587500967,50,0,10.75550025,0,0,0,90.00000001 +39.25,50.425,-3.587499454,50,0,10.74572918,0,0,0,90.00000001 +39.26,50.425,-3.587497943,50,0,10.73618018,0,0,0,90.00000001 +39.27,50.425,-3.587496432,50,0,10.72574291,0,0,0,90.00000001 +39.28,50.425,-3.587494924,50,0,10.7148615,0,0,0,90.00000001 +39.29,50.425,-3.587493417,50,0,10.70464629,0,0,0,90.00000001 +39.3,50.425,-3.587491911,50,0,10.69487523,0,0,0,90.00000001 +39.31,50.425,-3.587490407,50,0,10.6855483,0,0,0,90.00000001 +39.32,50.425,-3.587488904,50,0,10.67688758,0,0,0,90.00000001 +39.33,50.425,-3.587487402,50,0,10.66733859,0,0,0,90.00000001 +39.34,50.425,-3.587485901,50,0,10.65579097,0,0,0,90.00000001 +39.35,50.425,-3.587484403,50,0,10.64424334,0,0,0,90.00000001 +39.36,50.425,-3.587482906,50,0,10.63469435,0,0,0,90.00000001 +39.37,50.425,-3.58748141,50,0,10.62603363,0,0,0,90.00000001 +39.38,50.425,-3.587479915,50,0,10.61648463,0,0,0,90.00000001 +39.39,50.425,-3.587478422,50,0,10.60604736,0,0,0,90.00000001 +39.4,50.425,-3.58747693,50,0,10.59561008,0,0,0,90.00000001 +39.41,50.425,-3.58747544,50,0,10.58583902,0,0,0,90.00000001 +39.42,50.425,-3.587473951,50,0,10.57629002,0,0,0,90.00000001 +39.43,50.425,-3.587472463,50,0,10.56585275,0,0,0,90.00000001 +39.44,50.425,-3.587470977,50,0,10.55497134,0,0,0,90.00000001 +39.45,50.425,-3.587469493,50,0,10.54475613,0,0,0,90.00000001 +39.46,50.425,-3.587468009,50,0,10.53498507,0,0,0,90.00000001 +39.47,50.425,-3.587466528,50,0,10.525214,0,0,0,90.00000001 +39.48,50.425,-3.587465047,50,0,10.51522087,0,0,0,90.00000001 +39.49,50.425,-3.587463568,50,0,10.50522773,0,0,0,90.00000001 +39.5,50.425,-3.587462091,50,0,10.4959008,0,0,0,90.00000001 +39.51,50.425,-3.587460614,50,0,10.48635181,0,0,0,90.00000001 +39.52,50.425,-3.587459139,50,0,10.47569246,0,0,0,90.00000001 +39.53,50.425,-3.587457666,50,0,10.46525519,0,0,0,90.00000001 +39.54,50.425,-3.587456194,50,0,10.45570619,0,0,0,90.00000001 +39.55,50.425,-3.587454723,50,0,10.44593513,0,0,0,90.00000001 +39.56,50.425,-3.587453254,50,0,10.43549786,0,0,0,90.00000001 +39.57,50.425,-3.587451786,50,0,10.42506058,0,0,0,90.00000001 +39.58,50.425,-3.58745032,50,0,10.41528951,0,0,0,90.00000001 +39.59,50.425,-3.587448855,50,0,10.40574052,0,0,0,90.00000001 +39.6,50.425,-3.587447391,50,0,10.39530325,0,0,0,90.00000001 +39.61,50.425,-3.587445929,50,0,10.3846439,0,0,0,90.00000001 +39.62,50.425,-3.587444469,50,0,10.3750949,0,0,0,90.00000001 +39.63,50.425,-3.587443009,50,0,10.36576798,0,0,0,90.00000001 +39.64,50.425,-3.587441551,50,0,10.35577484,0,0,0,90.00000001 +39.65,50.425,-3.587440095,50,0,10.34578171,0,0,0,90.00000001 +39.66,50.425,-3.587438639,50,0,10.33578857,0,0,0,90.00000001 +39.67,50.425,-3.587437186,50,0,10.3253513,0,0,0,90.00000001 +39.68,50.425,-3.587435733,50,0,10.31491402,0,0,0,90.00000001 +39.69,50.425,-3.587434283,50,0,10.30514296,0,0,0,90.00000001 +39.7,50.425,-3.587432833,50,0,10.29581603,0,0,0,90.00000001 +39.71,50.425,-3.587431385,50,0,10.2858229,0,0,0,90.00000001 +39.72,50.425,-3.587429938,50,0,10.27471941,0,0,0,90.00000001 +39.73,50.425,-3.587428493,50,0,10.263838,0,0,0,90.00000001 +39.74,50.425,-3.58742705,50,0,10.25428901,0,0,0,90.00000001 +39.75,50.425,-3.587425607,50,0,10.24496208,0,0,0,90.00000001 +39.76,50.425,-3.587424166,50,0,10.23519101,0,0,0,90.00000001 +39.77,50.425,-3.587422727,50,0,10.22586409,0,0,0,90.00000001 +39.78,50.425,-3.587421288,50,0,10.21631509,0,0,0,90.00000001 +39.79,50.425,-3.587419851,50,0,10.20565575,0,0,0,90.00000001 +39.8,50.425,-3.587418416,50,0,10.19521847,0,0,0,90.00000001 +39.81,50.425,-3.587416982,50,0,10.18566948,0,0,0,90.00000001 +39.82,50.425,-3.587415549,50,0,10.17589841,0,0,0,90.00000001 +39.83,50.425,-3.587414118,50,0,10.16546114,0,0,0,90.00000001 +39.84,50.425,-3.587412688,50,0,10.15480179,0,0,0,90.00000001 +39.85,50.425,-3.58741126,50,0,10.14436452,0,0,0,90.00000001 +39.86,50.425,-3.587409833,50,0,10.13459345,0,0,0,90.00000001 +39.87,50.425,-3.587408408,50,0,10.12526653,0,0,0,90.00000001 +39.88,50.425,-3.587406983,50,0,10.11571753,0,0,0,90.00000001 +39.89,50.425,-3.587405561,50,0,10.10594647,0,0,0,90.00000001 +39.9,50.425,-3.587404139,50,0,10.09573126,0,0,0,90.00000001 +39.91,50.425,-3.587402719,50,0,10.08484985,0,0,0,90.00000001 +39.92,50.425,-3.587401301,50,0,10.07441257,0,0,0,90.00000001 +39.93,50.425,-3.587399884,50,0,10.06486358,0,0,0,90.00000001 +39.94,50.425,-3.587398468,50,0,10.05509251,0,0,0,90.00000001 +39.95,50.425,-3.587397054,50,0,10.04465524,0,0,0,90.00000001 +39.96,50.425,-3.587395641,50,0,10.03421796,0,0,0,90.00000001 +39.97,50.425,-3.58739423,50,0,10.0244469,0,0,0,90.00000001 +39.98,50.425,-3.58739282,50,0,10.01534204,0,0,0,90.00000001 +39.99,50.425,-3.587391411,50,0,10.00734753,0,0,0,90.00000001 +40,50.425,-3.587390004,50,0,10.002462,0,0,0,90.00000001 +40.01,50.425,-3.587388597,50,-0.003476189,10.00112958,0,0,0,90.00593356 +40.02,50.425,-3.587387189,50,-0.017380947,10.00068544,0,0,0,90.04746836 +40.03,50.425,-3.587385782,50,-0.041714274,9.999575096,0,0,0,90.16020571 +40.04,50.42499999,-3.587384375,50,-0.076476181,9.998686819,0,0,0,90.37974681 +40.05,50.42499999,-3.587382968,50,-0.132095245,9.998242682,0,0,0,90.72982592 +40.06,50.42499997,-3.587381561,50,-0.208571466,9.997132337,0,0,0,91.18670882 +40.07,50.42499995,-3.587380154,50,-0.295476258,9.994689574,0,0,0,91.71479428 +40.08,50.42499992,-3.587378748,50,-0.392809615,9.991358534,0,0,0,92.27848105 +40.09,50.42499988,-3.587377342,50,-0.500571534,9.987583358,0,0,0,92.84810125 +40.1,50.42499983,-3.587375937,50,-0.60833345,9.982697837,0,0,0,93.41772151 +40.11,50.42499977,-3.587374532,50,-0.705666797,9.975813691,0,0,0,93.98734177 +40.12,50.4249997,-3.587373129,50,-0.796047771,9.967597128,0,0,0,94.55696202 +40.13,50.42499963,-3.587371727,50,-0.889904935,9.959380566,0,0,0,95.12658228 +40.14,50.42499954,-3.587370326,50,-0.987238292,9.950719866,0,0,0,95.69620254 +40.15,50.42499945,-3.587368926,50,-1.091524033,9.940060541,0,0,0,96.2658228 +40.16,50.42499935,-3.587367528,50,-1.206238345,9.927402591,0,0,0,96.83544306 +40.17,50.42499923,-3.587366132,50,-1.310524078,9.914522574,0,0,0,97.40506332 +40.18,50.42499911,-3.587364738,50,-1.39047647,9.902308767,0,0,0,97.97468358 +40.19,50.42499898,-3.587363345,50,-1.470428857,9.889206683,0,0,0,98.54430378 +40.2,50.42499885,-3.587361954,50,-1.574714588,9.873661834,0,0,0,99.11392404 +40.21,50.4249987,-3.587360566,50,-1.685952719,9.85634043,0,0,0,99.68354429 +40.22,50.42499854,-3.58735918,50,-1.779809897,9.838574889,0,0,0,100.2531646 +40.23,50.42499838,-3.587357797,50,-1.873667055,9.820809349,0,0,0,100.8227848 +40.24,50.42499821,-3.587356416,50,-1.984905155,9.802599672,0,0,0,101.3924051 +40.25,50.42499802,-3.587355038,50,-2.089190879,9.782835508,0,0,0,101.9620253 +40.26,50.42499783,-3.587353662,50,-2.16914328,9.761294788,0,0,0,102.5316456 +40.27,50.42499763,-3.587352291,50,-2.249095685,9.73908786,0,0,0,103.1012658 +40.28,50.42499743,-3.587350921,50,-2.353381418,9.716436797,0,0,0,103.6708861 +40.29,50.42499721,-3.587349556,50,-2.464619527,9.692453316,0,0,0,104.2405064 +40.3,50.42499698,-3.587348193,50,-2.555000496,9.666915348,0,0,0,104.8101266 +40.31,50.42499675,-3.587346835,50,-2.634952898,9.640489102,0,0,0,105.3797468 +40.32,50.42499651,-3.58734548,50,-2.728810068,9.613618719,0,0,0,105.9493671 +40.33,50.42499626,-3.587344129,50,-2.836571996,9.58608213,0,0,0,106.5189873 +40.34,50.424996,-3.587342782,50,-2.947810109,9.557879332,0,0,0,107.0886076 +40.35,50.42499573,-3.587341439,50,-3.055572029,9.529010326,0,0,0,107.6582279 +40.36,50.42499545,-3.5873401,50,-3.149429187,9.498586834,0,0,0,108.2278481 +40.37,50.42499516,-3.587338765,50,-3.225905398,9.466386787,0,0,0,108.7974684 +40.38,50.42499487,-3.587337436,50,-3.302381612,9.433520532,0,0,0,109.3670886 +40.39,50.42499457,-3.58733611,50,-3.39623877,9.400210137,0,0,0,109.9367089 +40.4,50.42499426,-3.58733479,50,-3.500524496,9.365567325,0,0,0,110.5063291 +40.41,50.42499394,-3.587333474,50,-3.597857845,9.329370027,0,0,0,111.0759494 +40.42,50.42499361,-3.587332164,50,-3.688238816,9.292506522,0,0,0,111.6455696 +40.43,50.42499328,-3.587330859,50,-3.782095982,9.256087157,0,0,0,112.2151899 +40.44,50.42499293,-3.587329559,50,-3.875953156,9.219889863,0,0,0,112.7848101 +40.45,50.42499258,-3.587328264,50,-3.966334131,9.182138081,0,0,0,113.3544304 +40.46,50.42499222,-3.587326974,50,-4.060191282,9.141943534,0,0,0,113.9240506 +40.47,50.42499185,-3.587325691,50,-4.150572239,9.10041657,0,0,0,114.4936709 +40.48,50.42499147,-3.587324413,50,-4.227048442,9.058223399,0,0,0,115.0632912 +40.49,50.42499109,-3.587323141,50,-4.303524653,9.015141949,0,0,0,115.6329114 +40.5,50.4249907,-3.587321876,50,-4.397381822,8.971394289,0,0,0,116.2025316 +40.51,50.4249903,-3.587320616,50,-4.50514375,8.926758351,0,0,0,116.7721519 +40.52,50.42498989,-3.587319363,50,-4.612905674,8.881234137,0,0,0,117.3417721 +40.53,50.42498947,-3.587318117,50,-4.706762836,8.835487855,0,0,0,117.9113924 +40.54,50.42498904,-3.587316876,50,-4.783239047,8.789075363,0,0,0,118.4810127 +40.55,50.42498861,-3.587315643,50,-4.856239064,8.741552521,0,0,0,119.0506329 +40.56,50.42498817,-3.587314416,50,-4.936191451,8.693141402,0,0,0,119.6202532 +40.57,50.42498772,-3.587313196,50,-5.023096215,8.643397865,0,0,0,120.1898734 +40.58,50.42498727,-3.587311983,50,-5.116953374,8.592543981,0,0,0,120.7594937 +40.59,50.4249868,-3.587310778,50,-5.207334354,8.541468027,0,0,0,121.329114 +40.6,50.42498633,-3.587309579,50,-5.28381056,8.489503795,0,0,0,121.8987342 +40.61,50.42498585,-3.587308388,50,-5.36028676,8.435985074,0,0,0,122.4683544 +40.62,50.42498537,-3.587307205,50,-5.450667733,8.382022215,0,0,0,123.0379747 +40.63,50.42498487,-3.587306029,50,-5.541048714,8.328281425,0,0,0,123.6075949 +40.64,50.42498437,-3.587304861,50,-5.617524925,8.273652357,0,0,0,124.1772152 +40.65,50.42498386,-3.5873037,50,-5.694001123,8.217024661,0,0,0,124.7468354 +40.66,50.42498335,-3.587302548,50,-5.780905886,8.158842476,0,0,0,125.3164557 +40.67,50.42498282,-3.587301404,50,-5.860858273,8.100216153,0,0,0,125.886076 +40.68,50.42498229,-3.587300268,50,-5.930382103,8.041589828,0,0,0,126.4556962 +40.69,50.42498176,-3.587299141,50,-6.010334509,7.982741434,0,0,0,127.0253165 +40.7,50.42498121,-3.587298021,50,-6.100715482,7.923226831,0,0,0,127.5949367 +40.71,50.42498066,-3.587296911,50,-6.187620265,7.862601879,0,0,0,128.1645569 +40.72,50.4249801,-3.587295808,50,-6.267572665,7.800422439,0,0,0,128.7341772 +40.73,50.42497953,-3.587294715,50,-6.337096481,7.737132649,0,0,0,129.3037975 +40.74,50.42497896,-3.587293631,50,-6.39966791,7.673620789,0,0,0,129.8734177 +40.75,50.42497838,-3.587292555,50,-6.472667916,7.609442719,0,0,0,130.443038 +40.76,50.4249778,-3.587291489,50,-6.563048886,7.54437637,0,0,0,131.0126582 +40.77,50.4249772,-3.587290432,50,-6.653429863,7.47931002,0,0,0,131.5822785 +40.78,50.4249766,-3.587289384,50,-6.726429884,7.41379953,0,0,0,132.1518988 +40.79,50.42497599,-3.587288345,50,-6.785525137,7.346512481,0,0,0,132.721519 +40.8,50.42497538,-3.587287316,50,-6.844620383,7.277893013,0,0,0,133.2911393 +40.81,50.42497476,-3.587286297,50,-6.917620394,7.209273544,0,0,0,133.8607595 +40.82,50.42497414,-3.587285287,50,-7.004525176,7.140654074,0,0,0,134.4303797 +40.83,50.4249735,-3.587284287,50,-7.081001382,7.071590463,0,0,0,135 +40.84,50.42497286,-3.587283297,50,-7.13662043,7.001638573,0,0,0,135.5696202 +40.85,50.42497222,-3.587282316,50,-7.195715677,6.929688054,0,0,0,136.1392405 +40.86,50.42497157,-3.587281346,50,-7.268715695,6.856183045,0,0,0,136.7088608 +40.87,50.42497091,-3.587280387,50,-7.341715703,6.783122174,0,0,0,137.278481 +40.88,50.42497025,-3.587279437,50,-7.414715709,6.710505441,0,0,0,137.8481013 +40.89,50.42496958,-3.587278498,50,-7.491191923,6.637000428,0,0,0,138.4177215 +40.9,50.4249689,-3.587277569,50,-7.560715757,6.562385065,0,0,0,138.9873418 +40.91,50.42496822,-3.587276651,50,-7.619810997,6.486659351,0,0,0,139.5569621 +40.92,50.42496753,-3.587275743,50,-7.675430042,6.409823287,0,0,0,140.1265823 +40.93,50.42496684,-3.587274847,50,-7.731049106,6.332765153,0,0,0,140.6962025 +40.94,50.42496614,-3.587273961,50,-7.790144367,6.255929086,0,0,0,141.2658228 +40.95,50.42496544,-3.587273086,50,-7.859668196,6.178648878,0,0,0,141.835443 +40.96,50.42496473,-3.587272222,50,-7.932668206,6.100702458,0,0,0,142.4050633 +40.97,50.42496401,-3.587271369,50,-7.988287249,6.022311898,0,0,0,142.9746836 +40.98,50.42496329,-3.587270527,50,-8.030001533,5.942810987,0,0,0,143.5443038 +40.99,50.42496257,-3.587269696,50,-8.085620597,5.861533515,0,0,0,144.1139241 +41,50.42496184,-3.587268877,50,-8.158620615,5.779811901,0,0,0,144.6835443 +41.01,50.4249611,-3.58726807,50,-8.228144435,5.698978565,0,0,0,145.2531646 +41.02,50.42496036,-3.587267273,50,-8.283763496,5.617479018,0,0,0,145.8227848 +41.03,50.42495961,-3.587266488,50,-8.325477793,5.53420291,0,0,0,146.392405 +41.04,50.42495886,-3.587265716,50,-8.363715888,5.45070473,0,0,0,146.9620253 +41.05,50.42495811,-3.587264954,50,-8.41933494,5.367650687,0,0,0,147.5316456 +41.06,50.42495735,-3.587264205,50,-8.488858769,5.284374572,0,0,0,148.1012658 +41.07,50.42495658,-3.587263467,50,-8.54447783,5.200432246,0,0,0,148.6708861 +41.08,50.42495581,-3.587262741,50,-8.586192116,5.114935428,0,0,0,149.2405063 +41.09,50.42495504,-3.587262027,50,-8.64181117,5.02766205,0,0,0,149.8101266 +41.1,50.42495426,-3.587261326,50,-8.711334994,4.940388669,0,0,0,150.3797469 +41.11,50.42495347,-3.587260637,50,-8.763477857,4.854669775,0,0,0,150.9493671 +41.12,50.42495268,-3.58725996,50,-8.791287377,4.769172948,0,0,0,151.5189874 +41.13,50.42495189,-3.587259294,50,-8.826049288,4.681677489,0,0,0,152.0886076 +41.14,50.4249511,-3.587258642,50,-8.881668353,4.592849609,0,0,0,152.6582278 +41.15,50.42495029,-3.587258002,50,-8.933811223,4.504243795,0,0,0,153.2278481 +41.16,50.42494949,-3.587257374,50,-8.972049328,4.415193839,0,0,0,153.7974684 +41.17,50.42494868,-3.587256759,50,-9.013763625,4.325255601,0,0,0,154.3670886 +41.18,50.42494787,-3.587256157,50,-9.062430293,4.235317362,0,0,0,154.9367089 +41.19,50.42494705,-3.587255567,50,-9.104144579,4.14537912,0,0,0,155.5063291 +41.2,50.42494623,-3.58725499,50,-9.138906495,4.054996734,0,0,0,156.0759494 +41.21,50.42494541,-3.587254426,50,-9.177144607,3.964170205,0,0,0,156.6455696 +41.22,50.42494458,-3.587253874,50,-9.21538271,3.872899533,0,0,0,157.2151899 +41.23,50.42494375,-3.587253336,50,-9.250144606,3.781406789,0,0,0,157.7848101 +41.24,50.42494292,-3.58725281,50,-9.288382689,3.689247832,0,0,0,158.3544304 +41.25,50.42494208,-3.587252297,50,-9.326620794,3.595534382,0,0,0,158.9240506 +41.26,50.42494124,-3.587251798,50,-9.361382728,3.501154721,0,0,0,159.4936709 +41.27,50.4249404,-3.587251312,50,-9.399620839,3.407663336,0,0,0,160.0632911 +41.28,50.42493955,-3.587250839,50,-9.437858927,3.315060228,0,0,0,160.6329114 +41.29,50.4249387,-3.587250379,50,-9.469144629,3.222457116,0,0,0,161.2025317 +41.3,50.42493785,-3.587249932,50,-9.496954157,3.12896572,0,0,0,161.7721519 +41.31,50.42493699,-3.587249498,50,-9.528239888,3.034141901,0,0,0,162.3417722 +41.32,50.42493614,-3.587249078,50,-9.563001802,2.9384298,0,0,0,162.9113924 +41.33,50.42493527,-3.587248671,50,-9.587335132,2.842495626,0,0,0,163.4810127 +41.34,50.42493441,-3.587248278,50,-9.601239894,2.746561449,0,0,0,164.0506329 +41.35,50.42493355,-3.587247898,50,-9.625573233,2.650849338,0,0,0,164.6202532 +41.36,50.42493268,-3.587247532,50,-9.660335136,2.555803434,0,0,0,165.1898734 +41.37,50.42493181,-3.587247179,50,-9.695097038,2.460979596,0,0,0,165.7594937 +41.38,50.42493094,-3.587246839,50,-9.729858954,2.364823335,0,0,0,166.3291139 +41.39,50.42493006,-3.587246513,50,-9.75071611,2.26689051,0,0,0,166.8987342 +41.4,50.42492918,-3.587246201,50,-9.754192307,2.168735613,0,0,0,167.4683544 +41.41,50.42492831,-3.587245903,50,-9.771573259,2.071691062,0,0,0,168.0379747 +41.42,50.42492743,-3.587245618,50,-9.809811348,1.975312716,0,0,0,168.607595 +41.43,50.42492654,-3.587245347,50,-9.83762087,1.878268157,0,0,0,169.1772152 +41.44,50.42492566,-3.587245089,50,-9.844573251,1.780113245,0,0,0,169.7468354 +41.45,50.42492477,-3.587244846,50,-9.848049439,1.68173626,0,0,0,170.3164557 +41.46,50.42492389,-3.587244616,50,-9.861954205,1.58358134,0,0,0,170.8860759 +41.47,50.424923,-3.5872444,50,-9.882811362,1.485204348,0,0,0,171.4556962 +41.48,50.42492211,-3.587244198,50,-9.900192318,1.387049421,0,0,0,172.0253165 +41.49,50.42492122,-3.58724401,50,-9.917573262,1.289560701,0,0,0,172.5949367 +41.5,50.42492033,-3.587243835,50,-9.938430403,1.191405767,0,0,0,173.164557 +41.51,50.42491943,-3.587243674,50,-9.952335172,1.09191841,0,0,0,173.7341772 +41.52,50.42491854,-3.587243528,50,-9.955811366,0.992653118,0,0,0,174.3037975 +41.53,50.42491764,-3.587243395,50,-9.959287552,0.894054032,0,0,0,174.8734178 +41.54,50.42491675,-3.587243276,50,-9.969716118,0.794788733,0,0,0,175.443038 +41.55,50.42491585,-3.587243171,50,-9.976668497,0.69507929,0,0,0,176.0126582 +41.56,50.42491495,-3.587243081,50,-9.973192304,0.595813985,0,0,0,176.5822785 +41.57,50.42491406,-3.587243003,50,-9.976668494,0.496548675,0,0,0,177.1518987 +41.58,50.42491316,-3.587242941,50,-9.99404945,0.398171641,0,0,0,177.721519 +41.59,50.42491226,-3.587242892,50,-10.00795421,0.303347725,0,0,0,178.2852057 +41.6,50.42491136,-3.587242856,50,-10.00795421,0.215185908,0,0,0,178.8132912 +41.61,50.42491046,-3.587242833,50,-9.99404945,0.139015873,0,0,0,179.2701741 +41.62,50.42490956,-3.58724282,50,-9.976668504,0.080389371,0,0,0,179.6202532 +41.63,50.42490867,-3.587242813,50,-9.976668512,0.040638826,0,0,0,179.8397943 +41.64,50.42490777,-3.587242811,50,-9.994049459,0.017321468,0,0,0,179.9525317 +41.65,50.42490687,-3.58724281,50,-10.00795421,0.005995893,0,0,0,179.9940665 +41.66,50.42490597,-3.58724281,50,-10.0114304,0.001554491,0,0,0,-180 +41.67,50.42490507,-3.58724281,50,-10.01143039,0.00022207,0,0,0,-180 +41.68,50.42490417,-3.58724281,50,-10.01490658,2.08E-12,0,0,0,-180 +41.69,50.42490327,-3.58724281,50,-10.02881135,1.05E-11,0,0,0,-180 +41.7,50.42490237,-3.58724281,50,-10.0461923,2.10E-11,0,0,0,-180 +41.71,50.42490146,-3.58724281,50,-10.04966849,1.90E-11,0,0,0,-180 +41.72,50.42490056,-3.58724281,50,-10.0461923,2.50E-13,0,0,0,-180 +41.73,50.42489966,-3.58724281,50,-10.05314468,-2.05E-11,0,0,0,-180 +41.74,50.42489875,-3.58724281,50,-10.06704945,-2.88E-11,0,0,0,-180 +41.75,50.42489785,-3.58724281,50,-10.0844304,-2.26E-11,0,0,0,-180 +41.76,50.42489694,-3.58724281,50,-10.10528754,-1.01E-11,0,0,0,-180 +41.77,50.42489603,-3.58724281,50,-10.1191923,-1.83E-12,0,0,0,-180 +41.78,50.42489512,-3.58724281,50,-10.12266849,2.50E-13,0,0,0,-180 +41.79,50.42489421,-3.58724281,50,-10.1226685,2.50E-13,0,0,0,-180 +41.8,50.4248933,-3.58724281,50,-10.12614469,2.33E-12,0,0,0,-180 +41.81,50.42489239,-3.58724281,50,-10.14004945,1.06E-11,0,0,0,-180 +41.82,50.42489148,-3.58724281,50,-10.16090659,2.31E-11,0,0,0,-180 +41.83,50.42489056,-3.58724281,50,-10.17481135,3.13E-11,0,0,0,-180 +41.84,50.42488965,-3.58724281,50,-10.17828754,3.33E-11,0,0,0,-180 +41.85,50.42488873,-3.58724281,50,-10.18176372,3.10E-11,0,0,0,-180 +41.86,50.42488782,-3.58724281,50,-10.19566849,2.27E-11,0,0,0,-180 +41.87,50.4248869,-3.58724281,50,-10.21652564,1.04E-11,0,0,0,-180 +41.88,50.42488598,-3.58724281,50,-10.2304304,2.22E-12,0,0,0,-180 +41.89,50.42488506,-3.58724281,50,-10.23390658,1.41E-13,0,0,0,-180 +41.9,50.42488414,-3.58724281,50,-10.23390658,2.78E-17,0,0,0,-180 +41.91,50.42488322,-3.58724281,50,-10.23390659,-1.41E-13,0,0,0,-180 +41.92,50.4248823,-3.58724281,50,-10.23738278,1.94E-12,0,0,0,-180 +41.93,50.42488138,-3.58724281,50,-10.25128755,1.04E-11,0,0,0,-180 +41.94,50.42488046,-3.58724281,50,-10.2721447,2.30E-11,0,0,0,-180 +41.95,50.42487953,-3.58724281,50,-10.28952564,2.93E-11,0,0,0,-180 +41.96,50.42487861,-3.58724281,50,-10.30343039,2.09E-11,0,0,0,-180 +41.97,50.42487768,-3.58724281,50,-10.31038277,9.38E-14,0,0,0,-180 +41.98,50.42487675,-3.58724281,50,-10.30690659,-1.85E-11,0,0,0,-180 +41.99,50.42487583,-3.58724281,50,-10.31038278,-2.06E-11,0,0,0,-180 +42,50.4248749,-3.58724281,50,-10.32776373,-1.03E-11,0,0,0,-180 +42.01,50.42487397,-3.58724281,50,-10.34514468,-4.14E-12,0,0,0,-180 +42.02,50.42487304,-3.58724281,50,-10.36252563,-1.04E-11,0,0,0,-180 +42.03,50.42487211,-3.58724281,50,-10.37990659,-2.08E-11,0,0,0,-180 +42.04,50.42487117,-3.58724281,50,-10.3833828,-1.88E-11,0,0,0,-180 +42.05,50.42487024,-3.58724281,50,-10.37990661,-1.56E-13,0,0,0,-180 +42.06,50.42486931,-3.58724281,50,-10.38685898,2.06E-11,0,0,0,-180 +42.07,50.42486837,-3.58724281,50,-10.40076373,2.90E-11,0,0,0,-180 +42.08,50.42486744,-3.58724281,50,-10.41814468,2.28E-11,0,0,0,-180 +42.09,50.4248665,-3.58724281,50,-10.43900183,1.04E-11,0,0,0,-180 +42.1,50.42486556,-3.58724281,50,-10.45290659,2.08E-12,0,0,0,-180 +42.11,50.42486462,-3.58724281,50,-10.45638278,-2.78E-17,0,0,0,-180 +42.12,50.42486368,-3.58724281,50,-10.45638278,-2.78E-17,0,0,0,-180 +42.13,50.42486274,-3.58724281,50,-10.45638278,-2.78E-17,0,0,0,-180 +42.14,50.4248618,-3.58724281,50,-10.45985896,2.08E-12,0,0,0,-180 +42.15,50.42486086,-3.58724281,50,-10.47376372,1.04E-11,0,0,0,-180 +42.16,50.42485992,-3.58724281,50,-10.49462088,2.29E-11,0,0,0,-180 +42.17,50.42485897,-3.58724281,50,-10.50852564,3.12E-11,0,0,0,-180 +42.18,50.42485803,-3.58724281,50,-10.51200183,3.33E-11,0,0,0,-180 +42.19,50.42485708,-3.58724281,50,-10.51547802,3.12E-11,0,0,0,-180 +42.2,50.42485614,-3.58724281,50,-10.52938279,2.29E-11,0,0,0,-180 +42.21,50.42485519,-3.58724281,50,-10.55023992,1.04E-11,0,0,0,-180 +42.22,50.42485424,-3.58724281,50,-10.56414469,2.08E-12,0,0,0,-180 +42.23,50.42485329,-3.58724281,50,-10.56762089,1.56E-14,0,0,0,-180 +42.24,50.42485234,-3.58724281,50,-10.57109708,2.16E-12,0,0,0,-180 +42.25,50.42485139,-3.58724281,50,-10.58500184,1.05E-11,0,0,0,-180 +42.26,50.42485044,-3.58724281,50,-10.6023828,2.09E-11,0,0,0,-180 +42.27,50.42484948,-3.58724281,50,-10.60585899,1.88E-11,0,0,0,-180 +42.28,50.42484853,-3.58724281,50,-10.60585897,2.09E-12,0,0,0,-180 +42.29,50.42484758,-3.58724281,50,-10.62323992,-8.30E-12,0,0,0,-180 +42.3,50.42484662,-3.58724281,50,-10.64062087,2.16E-12,0,0,0,-180 +42.31,50.42484566,-3.58724281,50,-10.64062087,1.89E-11,0,0,0,-180 +42.32,50.42484471,-3.58724281,50,-10.64409706,2.09E-11,0,0,0,-180 +42.33,50.42484375,-3.58724281,50,-10.66147803,1.05E-11,0,0,0,-180 +42.34,50.42484279,-3.58724281,50,-10.67885899,4.16E-12,0,0,0,-180 +42.35,50.42484183,-3.58724281,50,-10.69623994,1.03E-11,0,0,0,-180 +42.36,50.42484087,-3.58724281,50,-10.71362087,2.06E-11,0,0,0,-180 +42.37,50.4248399,-3.58724281,50,-10.71709705,1.86E-11,0,0,0,-180 +42.38,50.42483894,-3.58724281,50,-10.71362088,2.60E-17,0,0,0,-180 +42.39,50.42483798,-3.58724281,50,-10.72057327,-2.06E-11,0,0,0,-180 +42.4,50.42483701,-3.58724281,50,-10.73447802,-2.90E-11,0,0,0,-180 +42.41,50.42483605,-3.58724281,50,-10.74838278,-2.08E-11,0,0,0,-180 +42.42,50.42483508,-3.58724281,50,-10.75533516,-1.41E-13,0,0,0,-180 +42.43,50.42483411,-3.58724281,50,-10.75185896,1.86E-11,0,0,0,-180 +42.44,50.42483315,-3.58724281,50,-10.75533515,2.08E-11,0,0,0,-180 +42.45,50.42483218,-3.58724281,50,-10.77619231,8.47E-12,0,0,0,-180 +42.46,50.42483121,-3.58724281,50,-10.80400184,-8.08E-12,0,0,0,-180 +42.47,50.42483024,-3.58724281,50,-10.82485898,-2.05E-11,0,0,0,-180 +42.48,50.42482926,-3.58724281,50,-10.82833516,-1.85E-11,0,0,0,-180 +42.49,50.42482829,-3.58724281,50,-10.82485897,8.67E-18,0,0,0,-180 +42.5,50.42482732,-3.58724281,50,-10.83181135,2.06E-11,0,0,0,-180 +42.51,50.42482634,-3.58724281,50,-10.84571613,2.89E-11,0,0,0,-180 +42.52,50.42482537,-3.58724281,50,-10.85962089,2.05E-11,0,0,0,-180 +42.53,50.42482439,-3.58724281,50,-10.86657326,-2.50E-13,0,0,0,-180 +42.54,50.42482341,-3.58724281,50,-10.86309706,-1.90E-11,0,0,0,-180 +42.55,50.42482244,-3.58724281,50,-10.86657325,-2.10E-11,0,0,0,-180 +42.56,50.42482146,-3.58724281,50,-10.88743039,-8.56E-12,0,0,0,-180 +42.57,50.42482048,-3.58724281,50,-10.91523992,8.06E-12,0,0,0,-180 +42.58,50.4248195,-3.58724281,50,-10.93609707,2.05E-11,0,0,0,-180 +42.59,50.42481851,-3.58724281,50,-10.93957327,1.85E-11,0,0,0,-180 +42.6,50.42481753,-3.58724281,50,-10.93609708,-1.56E-13,0,0,0,-180 +42.61,50.42481655,-3.58724281,50,-10.94304945,-2.08E-11,0,0,0,-180 +42.62,50.42481556,-3.58724281,50,-10.9569542,-2.89E-11,0,0,0,-180 +42.63,50.42481458,-3.58724281,50,-10.97085896,-2.05E-11,0,0,0,-180 +42.64,50.42481359,-3.58724281,50,-10.97781134,2.34E-13,0,0,0,-180 +42.65,50.4248126,-3.58724281,50,-10.97433515,1.89E-11,0,0,0,-180 +42.66,50.42481162,-3.58724281,50,-10.97781134,2.08E-11,0,0,0,-180 +42.67,50.42481063,-3.58724281,50,-10.9951923,1.03E-11,0,0,0,-180 +42.68,50.42480964,-3.58724281,50,-11.01257325,4.02E-12,0,0,0,-180 +42.69,50.42480865,-3.58724281,50,-11.02995421,1.04E-11,0,0,0,-180 +42.7,50.42480766,-3.58724281,50,-11.05081136,2.30E-11,0,0,0,-180 +42.71,50.42480666,-3.58724281,50,-11.06471614,3.13E-11,0,0,0,-180 +42.72,50.42480567,-3.58724281,50,-11.06819233,3.32E-11,0,0,0,-180 +42.73,50.42480467,-3.58724281,50,-11.06819231,3.31E-11,0,0,0,-180 +42.74,50.42480368,-3.58724281,50,-11.0681923,3.31E-11,0,0,0,-180 +42.75,50.42480268,-3.58724281,50,-11.07166848,3.11E-11,0,0,0,-180 +42.76,50.42480169,-3.58724281,50,-11.08557325,2.29E-11,0,0,0,-180 +42.77,50.42480069,-3.58724281,50,-11.10643039,1.05E-11,0,0,0,-180 +42.78,50.42479969,-3.58724281,50,-11.12033515,2.23E-12,0,0,0,-180 +42.79,50.42479869,-3.58724281,50,-11.12381134,1.56E-13,0,0,0,-180 +42.8,50.42479769,-3.58724281,50,-11.12728753,2.16E-12,0,0,0,-180 +42.81,50.42479669,-3.58724281,50,-11.1411923,1.04E-11,0,0,0,-180 +42.82,50.42479569,-3.58724281,50,-11.16204944,2.28E-11,0,0,0,-180 +42.83,50.42479468,-3.58724281,50,-11.17595421,3.10E-11,0,0,0,-180 +42.84,50.42479368,-3.58724281,50,-11.1794304,3.31E-11,0,0,0,-180 +42.85,50.42479267,-3.58724281,50,-11.18290659,3.11E-11,0,0,0,-180 +42.86,50.42479167,-3.58724281,50,-11.19681135,2.28E-11,0,0,0,-180 +42.87,50.42479066,-3.58724281,50,-11.21766849,1.04E-11,0,0,0,-180 +42.88,50.42478965,-3.58724281,50,-11.23157325,2.08E-12,0,0,0,-180 +42.89,50.42478864,-3.58724281,50,-11.23504945,8.67E-18,0,0,0,-180 +42.9,50.42478763,-3.58724281,50,-11.23504945,0,0,0,0,-180 +42.91,50.42478662,-3.58724281,50,-11.23504944,-8.67E-18,0,0,0,-180 +42.92,50.42478561,-3.58724281,50,-11.23852563,2.08E-12,0,0,0,-180 +42.93,50.4247846,-3.58724281,50,-11.2524304,1.04E-11,0,0,0,-180 +42.94,50.42478359,-3.58724281,50,-11.27328754,2.29E-11,0,0,0,-180 +42.95,50.42478257,-3.58724281,50,-11.29066848,2.91E-11,0,0,0,-180 +42.96,50.42478156,-3.58724281,50,-11.30457322,2.08E-11,0,0,0,-180 +42.97,50.42478054,-3.58724281,50,-11.3115256,2.78E-17,0,0,0,-180 +42.98,50.42477952,-3.58724281,50,-11.30804943,-1.87E-11,0,0,0,-180 +42.99,50.42477851,-3.58724281,50,-11.31152564,-2.08E-11,0,0,0,-180 +43,50.42477749,-3.58724281,50,-11.32890659,-1.04E-11,0,0,0,-180 +43.01,50.42477647,-3.58724281,50,-11.34628754,-4.16E-12,0,0,0,-180 +43.02,50.42477545,-3.58724281,50,-11.36366848,-1.04E-11,0,0,0,-180 +43.03,50.42477443,-3.58724281,50,-11.38104944,-2.08E-11,0,0,0,-180 +43.04,50.4247734,-3.58724281,50,-11.38452563,-1.86E-11,0,0,0,-180 +43.05,50.42477238,-3.58724281,50,-11.38104943,1.56E-13,0,0,0,-180 +43.06,50.42477136,-3.58724281,50,-11.38800181,2.09E-11,0,0,0,-180 +43.07,50.42477033,-3.58724281,50,-11.40190657,2.92E-11,0,0,0,-180 +43.08,50.42476931,-3.58724281,50,-11.41928751,2.29E-11,0,0,0,-180 +43.09,50.42476828,-3.58724281,50,-11.44014466,1.04E-11,0,0,0,-180 +43.1,50.42476725,-3.58724281,50,-11.45404943,2.16E-12,0,0,0,-180 +43.11,50.42476622,-3.58724281,50,-11.45752563,1.56E-13,0,0,0,-180 +43.12,50.42476519,-3.58724281,50,-11.45752563,1.56E-13,0,0,0,-180 +43.13,50.42476416,-3.58724281,50,-11.45752563,9.38E-14,0,0,0,-180 +43.14,50.42476313,-3.58724281,50,-11.46100182,2.17E-12,0,0,0,-180 +43.15,50.4247621,-3.58724281,50,-11.47490657,1.05E-11,0,0,0,-180 +43.16,50.42476107,-3.58724281,50,-11.4957637,2.30E-11,0,0,0,-180 +43.17,50.42476003,-3.58724281,50,-11.50966847,3.13E-11,0,0,0,-180 +43.18,50.424759,-3.58724281,50,-11.51314467,3.33E-11,0,0,0,-180 +43.19,50.42475796,-3.58724281,50,-11.51662087,3.13E-11,0,0,0,-180 +43.2,50.42475693,-3.58724281,50,-11.53052563,2.30E-11,0,0,0,-180 +43.21,50.42475589,-3.58724281,50,-11.55138277,1.04E-11,0,0,0,-180 +43.22,50.42475485,-3.58724281,50,-11.56528752,1.92E-12,0,0,0,-180 +43.23,50.42475381,-3.58724281,50,-11.56876371,-2.34E-13,0,0,0,-180 +43.24,50.42475277,-3.58724281,50,-11.5722399,1.84E-12,0,0,0,-180 +43.25,50.42475173,-3.58724281,50,-11.58614466,1.02E-11,0,0,0,-180 +43.26,50.42475069,-3.58724281,50,-11.60700181,2.29E-11,0,0,0,-180 +43.27,50.42474964,-3.58724281,50,-11.62090657,3.13E-11,0,0,0,-180 +43.28,50.4247486,-3.58724281,50,-11.62438276,3.35E-11,0,0,0,-180 +43.29,50.42474755,-3.58724281,50,-11.62438276,3.35E-11,0,0,0,-180 +43.3,50.42474651,-3.58724281,50,-11.62438275,3.34E-11,0,0,0,-180 +43.31,50.42474546,-3.58724281,50,-11.62785893,3.12E-11,0,0,0,-180 +43.32,50.42474442,-3.58724281,50,-11.64176369,2.27E-11,0,0,0,-180 +43.33,50.42474337,-3.58724281,50,-11.66262084,1.02E-11,0,0,0,-180 +43.34,50.42474232,-3.58724281,50,-11.68000182,3.91E-12,0,0,0,-180 +43.35,50.42474127,-3.58724281,50,-11.69738277,1.02E-11,0,0,0,-180 +43.36,50.42474022,-3.58724281,50,-11.71476371,2.06E-11,0,0,0,-180 +43.37,50.42473916,-3.58724281,50,-11.71823989,1.87E-11,0,0,0,-180 +43.38,50.42473811,-3.58724281,50,-11.71476369,1.56E-13,0,0,0,-180 +43.39,50.42473706,-3.58724281,50,-11.72171608,-2.05E-11,0,0,0,-180 +43.4,50.424736,-3.58724281,50,-11.73562084,-2.89E-11,0,0,0,-180 +43.41,50.42473495,-3.58724281,50,-11.7495256,-2.06E-11,0,0,0,-180 +43.42,50.42473389,-3.58724281,50,-11.75647798,0,0,0,0,-180 +43.43,50.42473283,-3.58724281,50,-11.7530018,1.85E-11,0,0,0,-180 +43.44,50.42473178,-3.58724281,50,-11.756478,2.05E-11,0,0,0,-180 +43.45,50.42473072,-3.58724281,50,-11.77733513,8.08E-12,0,0,0,-180 +43.46,50.42472966,-3.58724281,50,-11.80514465,-8.47E-12,0,0,0,-180 +43.47,50.4247286,-3.58724281,50,-11.82600179,-2.08E-11,0,0,0,-180 +43.48,50.42472753,-3.58724281,50,-11.82947797,-1.86E-11,0,0,0,-180 +43.49,50.42472647,-3.58724281,50,-11.82600179,1.41E-13,0,0,0,-180 +43.5,50.42472541,-3.58724281,50,-11.83295418,2.08E-11,0,0,0,-180 +43.51,50.42472434,-3.58724281,50,-11.84685894,2.90E-11,0,0,0,-180 +43.52,50.42472328,-3.58724281,50,-11.86076369,2.06E-11,0,0,0,-180 +43.53,50.42472221,-3.58724281,50,-11.86771607,-9.37E-14,0,0,0,-180 +43.54,50.42472114,-3.58724281,50,-11.86423988,-1.88E-11,0,0,0,-180 +43.55,50.42472008,-3.58724281,50,-11.86771608,-2.09E-11,0,0,0,-180 +43.56,50.42471901,-3.58724281,50,-11.88857322,-8.47E-12,0,0,0,-180 +43.57,50.42471794,-3.58724281,50,-11.91638274,8.23E-12,0,0,0,-180 +43.58,50.42471687,-3.58724281,50,-11.93723988,2.08E-11,0,0,0,-180 +43.59,50.42471579,-3.58724281,50,-11.94071607,1.88E-11,0,0,0,-180 +43.6,50.42471472,-3.58724281,50,-11.93723988,1.56E-13,0,0,0,-180 +43.61,50.42471365,-3.58724281,50,-11.94419226,-2.06E-11,0,0,0,-180 +43.62,50.42471257,-3.58724281,50,-11.95809702,-2.90E-11,0,0,0,-180 +43.63,50.4247115,-3.58724281,50,-11.97200179,-2.08E-11,0,0,0,-180 +43.64,50.42471042,-3.58724281,50,-11.97895415,0,0,0,0,-180 +43.65,50.42470934,-3.58724281,50,-11.97547795,1.87E-11,0,0,0,-180 +43.66,50.42470827,-3.58724281,50,-11.97895414,2.08E-11,0,0,0,-180 +43.67,50.42470719,-3.58724281,50,-11.9998113,8.31E-12,0,0,0,-180 +43.68,50.42470611,-3.58724281,50,-12.02762084,-8.31E-12,0,0,0,-180 +43.69,50.42470503,-3.58724281,50,-12.04847798,-2.08E-11,0,0,0,-180 +43.7,50.42470394,-3.58724281,50,-12.05195417,-1.88E-11,0,0,0,-180 +43.71,50.42470286,-3.58724281,50,-12.04847797,-1.56E-13,0,0,0,-180 +43.72,50.42470178,-3.58724281,50,-12.05543034,2.06E-11,0,0,0,-180 +43.73,50.42470069,-3.58724281,50,-12.06585891,3.11E-11,0,0,0,-180 +43.74,50.42469961,-3.58724281,50,-12.0693351,3.32E-11,0,0,0,-180 +43.75,50.42469852,-3.58724281,50,-12.07281129,3.12E-11,0,0,0,-180 +43.76,50.42469744,-3.58724281,50,-12.08671606,2.29E-11,0,0,0,-180 +43.77,50.42469635,-3.58724281,50,-12.1075732,1.05E-11,0,0,0,-180 +43.78,50.42469526,-3.58724281,50,-12.12147796,2.23E-12,0,0,0,-180 +43.79,50.42469417,-3.58724281,50,-12.12495415,7.81E-14,0,0,0,-180 +43.8,50.42469308,-3.58724281,50,-12.12843033,2.09E-12,0,0,0,-180 +43.81,50.42469199,-3.58724281,50,-12.14233509,1.04E-11,0,0,0,-180 +43.82,50.4246909,-3.58724281,50,-12.16319224,2.29E-11,0,0,0,-180 +43.83,50.4246898,-3.58724281,50,-12.17709702,3.12E-11,0,0,0,-180 +43.84,50.42468871,-3.58724281,50,-12.1805732,3.32E-11,0,0,0,-180 +43.85,50.42468761,-3.58724281,50,-12.18404938,3.11E-11,0,0,0,-180 +43.86,50.42468652,-3.58724281,50,-12.19795414,2.27E-11,0,0,0,-180 +43.87,50.42468542,-3.58724281,50,-12.21881129,1.02E-11,0,0,0,-180 +43.88,50.42468432,-3.58724281,50,-12.23271606,2.00E-12,0,0,0,-180 +43.89,50.42468322,-3.58724281,50,-12.23619223,8.67E-18,0,0,0,-180 +43.9,50.42468212,-3.58724281,50,-12.23619222,7.81E-14,0,0,0,-180 +43.91,50.42468102,-3.58724281,50,-12.23619223,1.56E-13,0,0,0,-180 +43.92,50.42467992,-3.58724281,50,-12.23966843,2.23E-12,0,0,0,-180 +43.93,50.42467882,-3.58724281,50,-12.25357319,1.05E-11,0,0,0,-180 +43.94,50.42467772,-3.58724281,50,-12.27443033,2.29E-11,0,0,0,-180 +43.95,50.42467661,-3.58724281,50,-12.29181127,2.90E-11,0,0,0,-180 +43.96,50.42467551,-3.58724281,50,-12.30571603,2.06E-11,0,0,0,-180 +43.97,50.4246744,-3.58724281,50,-12.31266841,-1.41E-13,0,0,0,-180 +43.98,50.42467329,-3.58724281,50,-12.30919222,-1.87E-11,0,0,0,-180 +43.99,50.42467219,-3.58724281,50,-12.31266842,-2.06E-11,0,0,0,-180 +44,50.42467108,-3.58724281,50,-12.33004939,-1.02E-11,0,0,0,-180 +44.01,50.42466997,-3.58724281,50,-12.34743034,-4.16E-12,0,0,0,-180 +44.02,50.42466886,-3.58724281,50,-12.36481128,-1.05E-11,0,0,0,-180 +44.03,50.42466775,-3.58724281,50,-12.38219223,-2.10E-11,0,0,0,-180 +44.04,50.42466663,-3.58724281,50,-12.38566842,-1.89E-11,0,0,0,-180 +44.05,50.42466552,-3.58724281,50,-12.38219222,-1.56E-13,0,0,0,-180 +44.06,50.42466441,-3.58724281,50,-12.3891446,2.08E-11,0,0,0,-180 +44.07,50.42466329,-3.58724281,50,-12.40304936,2.92E-11,0,0,0,-180 +44.08,50.42466218,-3.58724281,50,-12.42043031,2.31E-11,0,0,0,-180 +44.09,50.42466106,-3.58724281,50,-12.44128745,1.06E-11,0,0,0,-180 +44.1,50.42465994,-3.58724281,50,-12.45519222,2.33E-12,0,0,0,-180 +44.11,50.42465882,-3.58724281,50,-12.45866841,2.50E-13,0,0,0,-180 +44.12,50.4246577,-3.58724281,50,-12.45866841,2.50E-13,0,0,0,-180 +44.13,50.42465658,-3.58724281,50,-12.45866841,2.50E-13,0,0,0,-180 +44.14,50.42465546,-3.58724281,50,-12.46214459,2.33E-12,0,0,0,-180 +44.15,50.42465434,-3.58724281,50,-12.47604933,1.06E-11,0,0,0,-180 +44.16,50.42465322,-3.58724281,50,-12.49690647,2.31E-11,0,0,0,-180 +44.17,50.42465209,-3.58724281,50,-12.51081125,3.14E-11,0,0,0,-180 +44.18,50.42465097,-3.58724281,50,-12.51428745,3.35E-11,0,0,0,-180 +44.19,50.42464984,-3.58724281,50,-12.51776364,3.14E-11,0,0,0,-180 +44.2,50.42464872,-3.58724281,50,-12.5316684,2.31E-11,0,0,0,-180 +44.21,50.42464759,-3.58724281,50,-12.55252555,1.05E-11,0,0,0,-180 +44.22,50.42464646,-3.58724281,50,-12.56643031,2.08E-12,0,0,0,-180 +44.23,50.42464533,-3.58724281,50,-12.56990648,-1.41E-13,0,0,0,-180 +44.24,50.4246442,-3.58724281,50,-12.57338266,1.94E-12,0,0,0,-180 +44.25,50.42464307,-3.58724281,50,-12.58728744,1.04E-11,0,0,0,-180 +44.26,50.42464194,-3.58724281,50,-12.60466841,2.09E-11,0,0,0,-180 +44.27,50.4246408,-3.58724281,50,-12.6081446,1.88E-11,0,0,0,-180 +44.28,50.42463967,-3.58724281,50,-12.60814458,2.08E-12,0,0,0,-180 +44.29,50.42463854,-3.58724281,50,-12.62552551,-8.45E-12,0,0,0,-180 +44.3,50.4246374,-3.58724281,50,-12.64290647,1.92E-12,0,0,0,-180 +44.31,50.42463626,-3.58724281,50,-12.64290648,1.86E-11,0,0,0,-180 +44.32,50.42463513,-3.58724281,50,-12.64638267,2.07E-11,0,0,0,-180 +44.33,50.42463399,-3.58724281,50,-12.66376361,1.02E-11,0,0,0,-180 +44.34,50.42463285,-3.58724281,50,-12.68114457,4.00E-12,0,0,0,-180 +44.35,50.42463171,-3.58724281,50,-12.69852553,1.03E-11,0,0,0,-180 +44.36,50.42463057,-3.58724281,50,-12.71590647,2.08E-11,0,0,0,-180 +44.37,50.42462942,-3.58724281,50,-12.71938267,1.88E-11,0,0,0,-180 +44.38,50.42462828,-3.58724281,50,-12.71590647,1.56E-13,0,0,0,-180 +44.39,50.42462714,-3.58724281,50,-12.72285885,-2.06E-11,0,0,0,-180 +44.4,50.42462599,-3.58724281,50,-12.73676361,-2.90E-11,0,0,0,-180 +44.41,50.42462485,-3.58724281,50,-12.75066838,-2.08E-11,0,0,0,-180 +44.42,50.4246237,-3.58724281,50,-12.75762076,1.56E-14,0,0,0,-180 +44.43,50.42462255,-3.58724281,50,-12.75414456,1.88E-11,0,0,0,-180 +44.44,50.42462141,-3.58724281,50,-12.75762075,2.09E-11,0,0,0,-180 +44.45,50.42462026,-3.58724281,50,-12.77847788,8.47E-12,0,0,0,-180 +44.46,50.42461911,-3.58724281,50,-12.80628741,-8.23E-12,0,0,0,-180 +44.47,50.42461796,-3.58724281,50,-12.82714456,-2.08E-11,0,0,0,-180 +44.48,50.4246168,-3.58724281,50,-12.83062076,-1.87E-11,0,0,0,-180 +44.49,50.42461565,-3.58724281,50,-12.82714456,1.73E-17,0,0,0,-180 +44.5,50.4246145,-3.58724281,50,-12.83409693,2.08E-11,0,0,0,-180 +44.51,50.42461334,-3.58724281,50,-12.8480017,2.91E-11,0,0,0,-180 +44.52,50.42461219,-3.58724281,50,-12.86190646,2.08E-11,0,0,0,-180 +44.53,50.42461103,-3.58724281,50,-12.86885883,8.67E-18,0,0,0,-180 +44.54,50.42460987,-3.58724281,50,-12.86538264,-1.87E-11,0,0,0,-180 +44.55,50.42460872,-3.58724281,50,-12.86885883,-2.08E-11,0,0,0,-180 +44.56,50.42460756,-3.58724281,50,-12.88971598,-8.31E-12,0,0,0,-180 +44.57,50.4246064,-3.58724281,50,-12.9175255,8.31E-12,0,0,0,-180 +44.58,50.42460524,-3.58724281,50,-12.93838264,2.08E-11,0,0,0,-180 +44.59,50.42460407,-3.58724281,50,-12.94185884,1.86E-11,0,0,0,-180 +44.6,50.42460291,-3.58724281,50,-12.93838264,-1.56E-13,0,0,0,-180 +44.61,50.42460175,-3.58724281,50,-12.945335,-2.09E-11,0,0,0,-180 +44.62,50.42460058,-3.58724281,50,-12.95576357,-3.13E-11,0,0,0,-180 +44.63,50.42459942,-3.58724281,50,-12.95923977,-3.33E-11,0,0,0,-180 +44.64,50.42459825,-3.58724281,50,-12.96271597,-3.12E-11,0,0,0,-180 +44.65,50.42459709,-3.58724281,50,-12.97662074,-2.28E-11,0,0,0,-180 +44.66,50.42459592,-3.58724281,50,-12.99747787,-1.03E-11,0,0,0,-180 +44.67,50.42459475,-3.58724281,50,-13.01138262,-1.92E-12,0,0,0,-180 +44.68,50.42459358,-3.58724281,50,-13.01833499,2.23E-12,0,0,0,-180 +44.69,50.42459241,-3.58724281,50,-13.03223977,1.05E-11,0,0,0,-180 +44.7,50.42459124,-3.58724281,50,-13.04962073,2.09E-11,0,0,0,-180 +44.71,50.42459006,-3.58724281,50,-13.05309692,1.89E-11,0,0,0,-180 +44.72,50.42458889,-3.58724281,50,-13.05309691,2.23E-12,0,0,0,-180 +44.73,50.42458772,-3.58724281,50,-13.07047785,-8.22E-12,0,0,0,-180 +44.74,50.42458654,-3.58724281,50,-13.0878588,2.17E-12,0,0,0,-180 +44.75,50.42458536,-3.58724281,50,-13.08785881,1.89E-11,0,0,0,-180 +44.76,50.42458419,-3.58724281,50,-13.09133501,2.09E-11,0,0,0,-180 +44.77,50.42458301,-3.58724281,50,-13.10871595,1.04E-11,0,0,0,-180 +44.78,50.42458183,-3.58724281,50,-13.1226207,1.94E-12,0,0,0,-180 +44.79,50.42458065,-3.58724281,50,-13.12609689,-1.41E-13,0,0,0,-180 +44.8,50.42457947,-3.58724281,50,-13.12957308,2.08E-12,0,0,0,-180 +44.81,50.42457829,-3.58724281,50,-13.14347783,1.05E-11,0,0,0,-180 +44.82,50.42457711,-3.58724281,50,-13.16433498,2.30E-11,0,0,0,-180 +44.83,50.42457592,-3.58724281,50,-13.17823975,3.12E-11,0,0,0,-180 +44.84,50.42457474,-3.58724281,50,-13.18171595,3.31E-11,0,0,0,-180 +44.85,50.42457355,-3.58724281,50,-13.18519214,3.09E-11,0,0,0,-180 +44.86,50.42457237,-3.58724281,50,-13.19909689,2.26E-11,0,0,0,-180 +44.87,50.42457118,-3.58724281,50,-13.21995402,1.01E-11,0,0,0,-180 +44.88,50.42456999,-3.58724281,50,-13.23385879,1.83E-12,0,0,0,-180 +44.89,50.4245688,-3.58724281,50,-13.23733498,-2.50E-13,0,0,0,-180 +44.9,50.42456761,-3.58724281,50,-13.23733498,-2.34E-13,0,0,0,-180 +44.91,50.42456642,-3.58724281,50,-13.23733497,-1.56E-13,0,0,0,-180 +44.92,50.42456523,-3.58724281,50,-13.24081115,2.06E-12,0,0,0,-180 +44.93,50.42456404,-3.58724281,50,-13.25471591,1.05E-11,0,0,0,-180 +44.94,50.42456285,-3.58724281,50,-13.27557305,2.28E-11,0,0,0,-180 +44.95,50.42456165,-3.58724281,50,-13.28947781,3.10E-11,0,0,0,-180 +44.96,50.42456046,-3.58724281,50,-13.292954,3.30E-11,0,0,0,-180 +44.97,50.42455926,-3.58724281,50,-13.2964302,3.09E-11,0,0,0,-180 +44.98,50.42455807,-3.58724281,50,-13.31033498,2.26E-11,0,0,0,-180 +44.99,50.42455687,-3.58724281,50,-13.33119214,1.02E-11,0,0,0,-180 +45,50.42455567,-3.58724281,50,-13.34509691,1.92E-12,0,0,0,-180 +45.01,50.42455447,-3.58724281,50,-13.35204926,-2.08E-12,0,0,0,-180 +45.02,50.42455327,-3.58724281,50,-13.36595401,-1.03E-11,0,0,0,-180 +45.03,50.42455207,-3.58724281,50,-13.38333496,-2.06E-11,0,0,0,-180 +45.04,50.42455086,-3.58724281,50,-13.38681114,-1.87E-11,0,0,0,-180 +45.05,50.42454966,-3.58724281,50,-13.38333493,-1.41E-13,0,0,0,-180 +45.06,50.42454846,-3.58724281,50,-13.39028731,2.06E-11,0,0,0,-180 +45.07,50.42454725,-3.58724281,50,-13.40419208,2.91E-11,0,0,0,-180 +45.08,50.42454605,-3.58724281,50,-13.42157304,2.30E-11,0,0,0,-180 +45.09,50.42454484,-3.58724281,50,-13.43895398,1.26E-11,0,0,0,-180 +45.1,50.42454363,-3.58724281,50,-13.44243017,1.45E-11,0,0,0,-180 +45.11,50.42454242,-3.58724281,50,-13.44243018,3.10E-11,0,0,0,-180 +45.12,50.42454122,-3.58724281,50,-13.45981114,4.14E-11,0,0,0,-180 +45.13,50.42454,-3.58724281,50,-13.47719208,3.11E-11,0,0,0,-180 +45.14,50.42453879,-3.58724281,50,-13.47719208,1.45E-11,0,0,0,-180 +45.15,50.42453758,-3.58724281,50,-13.48066827,1.25E-11,0,0,0,-180 +45.16,50.42453637,-3.58724281,50,-13.49804922,2.28E-11,0,0,0,-180 +45.17,50.42453515,-3.58724281,50,-13.51195397,3.10E-11,0,0,0,-180 +45.18,50.42453394,-3.58724281,50,-13.51543016,3.31E-11,0,0,0,-180 +45.19,50.42453272,-3.58724281,50,-13.51890636,3.11E-11,0,0,0,-180 +45.2,50.42453151,-3.58724281,50,-13.53281113,2.28E-11,0,0,0,-180 +45.21,50.42453029,-3.58724281,50,-13.55366828,1.04E-11,0,0,0,-180 +45.22,50.42452907,-3.58724281,50,-13.56757303,2.09E-12,0,0,0,-180 +45.23,50.42452785,-3.58724281,50,-13.57104921,7.81E-14,0,0,0,-180 +45.24,50.42452663,-3.58724281,50,-13.5710492,1.56E-13,0,0,0,-180 +45.25,50.42452541,-3.58724281,50,-13.5745254,-1.92E-12,0,0,0,-180 +45.26,50.42452419,-3.58724281,50,-13.58843016,-1.03E-11,0,0,0,-180 +45.27,50.42452297,-3.58724281,50,-13.60928729,-2.28E-11,0,0,0,-180 +45.28,50.42452174,-3.58724281,50,-13.62666823,-2.91E-11,0,0,0,-180 +45.29,50.42452052,-3.58724281,50,-13.640573,-2.08E-11,0,0,0,-180 +45.3,50.42451929,-3.58724281,50,-13.64752539,2.78E-17,0,0,0,-180 +45.31,50.42451806,-3.58724281,50,-13.6440492,1.87E-11,0,0,0,-180 +45.32,50.42451684,-3.58724281,50,-13.64752539,2.08E-11,0,0,0,-180 +45.33,50.42451561,-3.58724281,50,-13.66490634,1.04E-11,0,0,0,-180 +45.34,50.42451438,-3.58724281,50,-13.6788111,2.08E-12,0,0,0,-180 +45.35,50.42451315,-3.58724281,50,-13.68576348,-2.06E-12,0,0,0,-180 +45.36,50.42451192,-3.58724281,50,-13.69966823,-1.03E-11,0,0,0,-180 +45.37,50.42451069,-3.58724281,50,-13.71704917,-2.06E-11,0,0,0,-180 +45.38,50.42450945,-3.58724281,50,-13.72052536,-1.85E-11,0,0,0,-180 +45.39,50.42450822,-3.58724281,50,-13.72052537,-2.00E-12,0,0,0,-180 +45.4,50.42450699,-3.58724281,50,-13.73790633,8.33E-12,0,0,0,-180 +45.41,50.42450575,-3.58724281,50,-13.75528728,-2.08E-12,0,0,0,-180 +45.42,50.42450451,-3.58724281,50,-13.75528727,-1.87E-11,0,0,0,-180 +45.43,50.42450328,-3.58724281,50,-13.75876346,-2.08E-11,0,0,0,-180 +45.44,50.42450204,-3.58724281,50,-13.77614441,-1.03E-11,0,0,0,-180 +45.45,50.4245008,-3.58724281,50,-13.79004916,-1.92E-12,0,0,0,-180 +45.46,50.42449956,-3.58724281,50,-13.79700155,2.23E-12,0,0,0,-180 +45.47,50.42449832,-3.58724281,50,-13.81090631,1.05E-11,0,0,0,-180 +45.48,50.42449708,-3.58724281,50,-13.83176345,2.29E-11,0,0,0,-180 +45.49,50.42449583,-3.58724281,50,-13.8456682,3.11E-11,0,0,0,-180 +45.5,50.42449459,-3.58724281,50,-13.84914439,3.31E-11,0,0,0,-180 +45.51,50.42449334,-3.58724281,50,-13.8491444,3.31E-11,0,0,0,-180 +45.52,50.4244921,-3.58724281,50,-13.84914441,3.32E-11,0,0,0,-180 +45.53,50.42449085,-3.58724281,50,-13.85262059,3.11E-11,0,0,0,-180 +45.54,50.42448961,-3.58724281,50,-13.86652535,2.27E-11,0,0,0,-180 +45.55,50.42448836,-3.58724281,50,-13.88738248,1.03E-11,0,0,0,-180 +45.56,50.42448711,-3.58724281,50,-13.90128724,2.08E-12,0,0,0,-180 +45.57,50.42448586,-3.58724281,50,-13.90823962,-1.94E-12,0,0,0,-180 +45.58,50.42448461,-3.58724281,50,-13.92214438,-1.02E-11,0,0,0,-180 +45.59,50.42448336,-3.58724281,50,-13.93952533,-2.08E-11,0,0,0,-180 +45.6,50.4244821,-3.58724281,50,-13.94300152,-1.89E-11,0,0,0,-180 +45.61,50.42448085,-3.58724281,50,-13.94300153,-2.31E-12,0,0,0,-180 +45.62,50.4244796,-3.58724281,50,-13.96038247,8.08E-12,0,0,0,-180 +45.63,50.42447834,-3.58724281,50,-13.97776341,-2.23E-12,0,0,0,-180 +45.64,50.42447708,-3.58724281,50,-13.97776341,-1.87E-11,0,0,0,-180 +45.65,50.42447583,-3.58724281,50,-13.98123961,-2.06E-11,0,0,0,-180 +45.66,50.42447457,-3.58724281,50,-13.99862056,-1.02E-11,0,0,0,-180 +45.67,50.42447331,-3.58724281,50,-14.01252532,-1.83E-12,0,0,0,-180 +45.68,50.42447205,-3.58724281,50,-14.0160015,2.50E-13,0,0,0,-180 +45.69,50.42447079,-3.58724281,50,-14.0194777,-1.83E-12,0,0,0,-180 +45.7,50.42446953,-3.58724281,50,-14.03338246,-1.01E-11,0,0,0,-180 +45.71,50.42446827,-3.58724281,50,-14.0542396,-2.26E-11,0,0,0,-180 +45.72,50.424467,-3.58724281,50,-14.06814436,-3.09E-11,0,0,0,-180 +45.73,50.42446574,-3.58724281,50,-14.07162055,-3.30E-11,0,0,0,-180 +45.74,50.42446447,-3.58724281,50,-14.07509673,-3.09E-11,0,0,0,-180 +45.75,50.42446321,-3.58724281,50,-14.08900148,-2.27E-11,0,0,0,-180 +45.76,50.42446194,-3.58724281,50,-14.10985862,-1.04E-11,0,0,0,-180 +45.77,50.42446067,-3.58724281,50,-14.12376339,-2.23E-12,0,0,0,-180 +45.78,50.4244594,-3.58724281,50,-14.12723959,-2.34E-13,0,0,0,-180 +45.79,50.42445813,-3.58724281,50,-14.12723959,-2.34E-13,0,0,0,-180 +45.8,50.42445686,-3.58724281,50,-14.12723957,-1.56E-13,0,0,0,-180 +45.81,50.42445559,-3.58724281,50,-14.13071576,-2.08E-12,0,0,0,-180 +45.82,50.42445432,-3.58724281,50,-14.14462053,-1.03E-11,0,0,0,-180 +45.83,50.42445305,-3.58724281,50,-14.16547768,-2.27E-11,0,0,0,-180 +45.84,50.42445177,-3.58724281,50,-14.18285862,-2.91E-11,0,0,0,-180 +45.85,50.4244505,-3.58724281,50,-14.20023956,-2.30E-11,0,0,0,-180 +45.86,50.42444922,-3.58724281,50,-14.21762051,-1.26E-11,0,0,0,-180 +45.87,50.42444794,-3.58724281,50,-14.21762051,-1.25E-11,0,0,0,-180 +45.88,50.42444666,-3.58724281,50,-14.20371575,-2.06E-11,0,0,0,-180 +45.89,50.42444539,-3.58724281,50,-14.20371575,-2.06E-11,0,0,0,-180 +45.9,50.42444411,-3.58724281,50,-14.2245729,-8.23E-12,0,0,0,-180 +45.91,50.42444283,-3.58724281,50,-14.25238243,8.31E-12,0,0,0,-180 +45.92,50.42444155,-3.58724281,50,-14.27323956,2.07E-11,0,0,0,-180 +45.93,50.42444026,-3.58724281,50,-14.27671573,1.85E-11,0,0,0,-180 +45.94,50.42443898,-3.58724281,50,-14.27671573,1.92E-12,0,0,0,-180 +45.95,50.4244377,-3.58724281,50,-14.29409669,-8.39E-12,0,0,0,-180 +45.96,50.42443641,-3.58724281,50,-14.31147765,2.08E-12,0,0,0,-180 +45.97,50.42443512,-3.58724281,50,-14.31147764,1.88E-11,0,0,0,-180 +45.98,50.42443384,-3.58724281,50,-14.31495382,2.09E-11,0,0,0,-180 +45.99,50.42443255,-3.58724281,50,-14.33233477,1.05E-11,0,0,0,-180 +46,50.42443126,-3.58724281,50,-14.34623954,2.16E-12,0,0,0,-180 +46.01,50.42442997,-3.58724281,50,-14.34971573,1.56E-14,0,0,0,-180 +46.02,50.42442868,-3.58724281,50,-14.35319192,2.08E-12,0,0,0,-180 +46.03,50.42442739,-3.58724281,50,-14.36709667,1.04E-11,0,0,0,-180 +46.04,50.4244261,-3.58724281,50,-14.38447762,2.08E-11,0,0,0,-180 +46.05,50.4244248,-3.58724281,50,-14.38795381,1.87E-11,0,0,0,-180 +46.06,50.42442351,-3.58724281,50,-14.3879538,2.08E-12,0,0,0,-180 +46.07,50.42442222,-3.58724281,50,-14.40533474,-8.31E-12,0,0,0,-180 +46.08,50.42442092,-3.58724281,50,-14.42271569,2.08E-12,0,0,0,-180 +46.09,50.42441962,-3.58724281,50,-14.42271571,1.87E-11,0,0,0,-180 +46.1,50.42441833,-3.58724281,50,-14.42619191,2.08E-11,0,0,0,-180 +46.11,50.42441703,-3.58724281,50,-14.44357286,1.04E-11,0,0,0,-180 +46.12,50.42441573,-3.58724281,50,-14.4609538,4.16E-12,0,0,0,-180 +46.13,50.42441443,-3.58724281,50,-14.47833474,1.04E-11,0,0,0,-180 +46.14,50.42441313,-3.58724281,50,-14.49571569,2.08E-11,0,0,0,-180 +46.15,50.42441182,-3.58724281,50,-14.49919187,1.87E-11,0,0,0,-180 +46.16,50.42441052,-3.58724281,50,-14.49571569,0,0,0,0,-180 +46.17,50.42440922,-3.58724281,50,-14.50266808,-2.08E-11,0,0,0,-180 +46.18,50.42440791,-3.58724281,50,-14.51657284,-2.90E-11,0,0,0,-180 +46.19,50.42440661,-3.58724281,50,-14.53395378,-2.27E-11,0,0,0,-180 +46.2,50.4244053,-3.58724281,50,-14.55481092,-1.02E-11,0,0,0,-180 +46.21,50.42440399,-3.58724281,50,-14.56871568,-2.00E-12,0,0,0,-180 +46.22,50.42440268,-3.58724281,50,-14.57219187,1.56E-14,0,0,0,-180 +46.23,50.42440137,-3.58724281,50,-14.57219186,1.56E-14,0,0,0,-180 +46.24,50.42440006,-3.58724281,50,-14.57219186,7.81E-14,0,0,0,-180 +46.25,50.42439875,-3.58724281,50,-14.57566806,-1.92E-12,0,0,0,-180 +46.26,50.42439744,-3.58724281,50,-14.58957281,-1.02E-11,0,0,0,-180 +46.27,50.42439613,-3.58724281,50,-14.61042994,-2.28E-11,0,0,0,-180 +46.28,50.42439481,-3.58724281,50,-14.6243347,-3.11E-11,0,0,0,-180 +46.29,50.4243935,-3.58724281,50,-14.62781089,-3.31E-11,0,0,0,-180 +46.3,50.42439218,-3.58724281,50,-14.63128708,-3.10E-11,0,0,0,-180 +46.31,50.42439087,-3.58724281,50,-14.64519185,-2.28E-11,0,0,0,-180 +46.32,50.42438955,-3.58724281,50,-14.66604899,-1.03E-11,0,0,0,-180 +46.33,50.42438823,-3.58724281,50,-14.67995375,-1.92E-12,0,0,0,-180 +46.34,50.42438691,-3.58724281,50,-14.68342994,1.41E-13,0,0,0,-180 +46.35,50.42438559,-3.58724281,50,-14.68342994,2.78E-17,0,0,0,-180 +46.36,50.42438427,-3.58724281,50,-14.68690611,1.94E-12,0,0,0,-180 +46.37,50.42438295,-3.58724281,50,-14.70081086,1.03E-11,0,0,0,-180 +46.38,50.42438163,-3.58724281,50,-14.72166801,2.29E-11,0,0,0,-180 +46.39,50.4243803,-3.58724281,50,-14.73557279,3.13E-11,0,0,0,-180 +46.4,50.42437898,-3.58724281,50,-14.73904898,3.35E-11,0,0,0,-180 +46.41,50.42437765,-3.58724281,50,-14.74252516,3.14E-11,0,0,0,-180 +46.42,50.42437633,-3.58724281,50,-14.75642991,2.30E-11,0,0,0,-180 +46.43,50.424375,-3.58724281,50,-14.77728705,1.04E-11,0,0,0,-180 +46.44,50.42437367,-3.58724281,50,-14.79119181,1.92E-12,0,0,0,-180 +46.45,50.42437234,-3.58724281,50,-14.794668,-2.34E-13,0,0,0,-180 +46.46,50.42437101,-3.58724281,50,-14.794668,-2.50E-13,0,0,0,-180 +46.47,50.42436968,-3.58724281,50,-14.79814419,-2.33E-12,0,0,0,-180 +46.48,50.42436835,-3.58724281,50,-14.81204895,-1.06E-11,0,0,0,-180 +46.49,50.42436702,-3.58724281,50,-14.83290609,-2.31E-11,0,0,0,-180 +46.5,50.42436568,-3.58724281,50,-14.84681085,-3.14E-11,0,0,0,-180 +46.51,50.42436435,-3.58724281,50,-14.85028704,-3.35E-11,0,0,0,-180 +46.52,50.42436301,-3.58724281,50,-14.85376322,-3.13E-11,0,0,0,-180 +46.53,50.42436168,-3.58724281,50,-14.86766797,-2.29E-11,0,0,0,-180 +46.54,50.42436034,-3.58724281,50,-14.88852512,-1.02E-11,0,0,0,-180 +46.55,50.424359,-3.58724281,50,-14.90242988,-1.84E-12,0,0,0,-180 +46.56,50.42435766,-3.58724281,50,-14.90590607,2.34E-13,0,0,0,-180 +46.57,50.42435632,-3.58724281,50,-14.90590607,1.56E-13,0,0,0,-180 +46.58,50.42435498,-3.58724281,50,-14.90938225,2.08E-12,0,0,0,-180 +46.59,50.42435364,-3.58724281,50,-14.92328701,1.02E-11,0,0,0,-180 +46.6,50.4243523,-3.58724281,50,-14.94414416,2.26E-11,0,0,0,-180 +46.61,50.42435095,-3.58724281,50,-14.95804892,3.09E-11,0,0,0,-180 +46.62,50.42434961,-3.58724281,50,-14.9615251,3.31E-11,0,0,0,-180 +46.63,50.42434826,-3.58724281,50,-14.96500129,3.11E-11,0,0,0,-180 +46.64,50.42434692,-3.58724281,50,-14.97890605,2.28E-11,0,0,0,-180 +46.65,50.42434557,-3.58724281,50,-14.99976319,1.02E-11,0,0,0,-180 +46.66,50.42434422,-3.58724281,50,-15.01366796,1.92E-12,0,0,0,-180 +46.67,50.42434287,-3.58724281,50,-15.01714414,-9.38E-14,0,0,0,-180 +46.68,50.42434152,-3.58724281,50,-15.01714412,-9.38E-14,0,0,0,-180 +46.69,50.42434017,-3.58724281,50,-15.01714412,-1.56E-13,0,0,0,-180 +46.7,50.42433882,-3.58724281,50,-15.02062032,1.92E-12,0,0,0,-180 +46.71,50.42433747,-3.58724281,50,-15.03452508,1.03E-11,0,0,0,-180 +46.72,50.42433612,-3.58724281,50,-15.05538221,2.28E-11,0,0,0,-180 +46.73,50.42433476,-3.58724281,50,-15.07276316,2.89E-11,0,0,0,-180 +46.74,50.42433341,-3.58724281,50,-15.08666794,2.06E-11,0,0,0,-180 +46.75,50.42433205,-3.58724281,50,-15.09362032,-7.81E-14,0,0,0,-180 +46.76,50.42433069,-3.58724281,50,-15.0901441,-1.87E-11,0,0,0,-180 +46.77,50.42432934,-3.58724281,50,-15.09362028,-2.08E-11,0,0,0,-180 +46.78,50.42432798,-3.58724281,50,-15.11447743,-8.31E-12,0,0,0,-180 +46.79,50.42432662,-3.58724281,50,-15.14228697,8.31E-12,0,0,0,-180 +46.8,50.42432526,-3.58724281,50,-15.16314411,2.08E-11,0,0,0,-180 +46.81,50.42432389,-3.58724281,50,-15.16662029,1.88E-11,0,0,0,-180 +46.82,50.42432253,-3.58724281,50,-15.16314409,2.50E-13,0,0,0,-180 +46.83,50.42432117,-3.58724281,50,-15.17009647,-2.04E-11,0,0,0,-180 +46.84,50.4243198,-3.58724281,50,-15.18052504,-3.08E-11,0,0,0,-180 +46.85,50.42431844,-3.58724281,50,-15.18400122,-3.30E-11,0,0,0,-180 +46.86,50.42431707,-3.58724281,50,-15.1874774,-3.11E-11,0,0,0,-180 +46.87,50.42431571,-3.58724281,50,-15.20138217,-2.28E-11,0,0,0,-180 +46.88,50.42431434,-3.58724281,50,-15.22223932,-1.04E-11,0,0,0,-180 +46.89,50.42431297,-3.58724281,50,-15.23614408,-2.08E-12,0,0,0,-180 +46.9,50.4243116,-3.58724281,50,-15.23962027,-1.56E-14,0,0,0,-180 +46.91,50.42431023,-3.58724281,50,-15.24309646,-2.16E-12,0,0,0,-180 +46.92,50.42430886,-3.58724281,50,-15.25700121,-1.05E-11,0,0,0,-180 +46.93,50.42430749,-3.58724281,50,-15.27785835,-2.30E-11,0,0,0,-180 +46.94,50.42430611,-3.58724281,50,-15.29176312,-3.13E-11,0,0,0,-180 +46.95,50.42430474,-3.58724281,50,-15.29523931,-3.33E-11,0,0,0,-180 +46.96,50.42430336,-3.58724281,50,-15.29871548,-3.12E-11,0,0,0,-180 +46.97,50.42430199,-3.58724281,50,-15.30914404,-2.08E-11,0,0,0,-180 +46.98,50.42430061,-3.58724281,50,-15.31609641,-1.56E-14,0,0,0,-180 +46.99,50.42429923,-3.58724281,50,-15.31262023,1.86E-11,0,0,0,-180 +47,50.42429786,-3.58724281,50,-15.31957263,2.27E-11,0,0,0,-180 +47.01,50.42429648,-3.58724281,50,-15.35085835,2.06E-11,0,0,0,-180 +47.02,50.4242951,-3.58724281,50,-15.38214405,2.28E-11,0,0,0,-180 +47.03,50.42429371,-3.58724281,50,-15.38909642,1.87E-11,0,0,0,-180 +47.04,50.42429233,-3.58724281,50,-15.38562022,7.81E-14,0,0,0,-180 +47.05,50.42429095,-3.58724281,50,-15.3925726,-2.06E-11,0,0,0,-180 +47.06,50.42428956,-3.58724281,50,-15.40300117,-3.10E-11,0,0,0,-180 +47.07,50.42428818,-3.58724281,50,-15.40647735,-3.32E-11,0,0,0,-180 +47.08,50.42428679,-3.58724281,50,-15.40995354,-3.11E-11,0,0,0,-180 +47.09,50.42428541,-3.58724281,50,-15.42385831,-2.27E-11,0,0,0,-180 +47.1,50.42428402,-3.58724281,50,-15.44471546,-1.03E-11,0,0,0,-180 +47.11,50.42428263,-3.58724281,50,-15.45862022,-2.08E-12,0,0,0,-180 +47.12,50.42428124,-3.58724281,50,-15.4620964,-1.41E-13,0,0,0,-180 +47.13,50.42427985,-3.58724281,50,-15.46557257,-2.22E-12,0,0,0,-180 +47.14,50.42427846,-3.58724281,50,-15.47947732,-1.04E-11,0,0,0,-180 +47.15,50.42427707,-3.58724281,50,-15.49685828,-2.06E-11,0,0,0,-180 +47.16,50.42427567,-3.58724281,50,-15.50033447,-1.86E-11,0,0,0,-180 +47.17,50.42427428,-3.58724281,50,-15.50033447,-2.08E-12,0,0,0,-180 +47.18,50.42427289,-3.58724281,50,-15.51771541,8.16E-12,0,0,0,-180 +47.19,50.42427149,-3.58724281,50,-15.53509636,-2.31E-12,0,0,0,-180 +47.2,50.42427009,-3.58724281,50,-15.53509637,-1.90E-11,0,0,0,-180 +47.21,50.4242687,-3.58724281,50,-15.53857256,-2.10E-11,0,0,0,-180 +47.22,50.4242673,-3.58724281,50,-15.5559535,-1.06E-11,0,0,0,-180 +47.23,50.4242659,-3.58724281,50,-15.56985827,-2.23E-12,0,0,0,-180 +47.24,50.4242645,-3.58724281,50,-15.57681065,2.06E-12,0,0,0,-180 +47.25,50.4242631,-3.58724281,50,-15.59071541,1.05E-11,0,0,0,-180 +47.26,50.4242617,-3.58724281,50,-15.61157255,2.28E-11,0,0,0,-180 +47.27,50.42426029,-3.58724281,50,-15.62547731,3.10E-11,0,0,0,-180 +47.28,50.42425889,-3.58724281,50,-15.62895349,3.30E-11,0,0,0,-180 +47.29,50.42425748,-3.58724281,50,-15.63242966,3.09E-11,0,0,0,-180 +47.3,50.42425608,-3.58724281,50,-15.64285822,2.05E-11,0,0,0,-180 +47.31,50.42425467,-3.58724281,50,-15.64981062,-2.50E-13,0,0,0,-180 +47.32,50.42425326,-3.58724281,50,-15.64633444,-1.90E-11,0,0,0,-180 +47.33,50.42425186,-3.58724281,50,-15.64981062,-2.10E-11,0,0,0,-180 +47.34,50.42425045,-3.58724281,50,-15.67066774,-8.47E-12,0,0,0,-180 +47.35,50.42424904,-3.58724281,50,-15.69847725,8.31E-12,0,0,0,-180 +47.36,50.42424763,-3.58724281,50,-15.7193344,2.09E-11,0,0,0,-180 +47.37,50.42424621,-3.58724281,50,-15.7228106,1.88E-11,0,0,0,-180 +47.38,50.4242448,-3.58724281,50,-15.71933441,0,0,0,0,-180 +47.39,50.42424339,-3.58724281,50,-15.72628679,-2.09E-11,0,0,0,-180 +47.4,50.42424197,-3.58724281,50,-15.74019154,-2.92E-11,0,0,0,-180 +47.41,50.42424056,-3.58724281,50,-15.7540963,-2.08E-11,0,0,0,-180 +47.42,50.42423914,-3.58724281,50,-15.76104868,1.41E-13,0,0,0,-180 +47.43,50.42423772,-3.58724281,50,-15.75757249,1.88E-11,0,0,0,-180 +47.44,50.42423631,-3.58724281,50,-15.76104868,2.08E-11,0,0,0,-180 +47.45,50.42423489,-3.58724281,50,-15.78190582,8.17E-12,0,0,0,-180 +47.46,50.42423347,-3.58724281,50,-15.80971533,-8.47E-12,0,0,0,-180 +47.47,50.42423205,-3.58724281,50,-15.83057247,-2.09E-11,0,0,0,-180 +47.48,50.42423062,-3.58724281,50,-15.83404866,-1.87E-11,0,0,0,-180 +47.49,50.4242292,-3.58724281,50,-15.83057247,-1.56E-14,0,0,0,-180 +47.5,50.42422778,-3.58724281,50,-15.83752485,2.07E-11,0,0,0,-180 +47.51,50.42422635,-3.58724281,50,-15.8514296,2.89E-11,0,0,0,-180 +47.52,50.42422493,-3.58724281,50,-15.86533435,2.06E-11,0,0,0,-180 +47.53,50.4242235,-3.58724281,50,-15.87228672,-7.81E-14,0,0,0,-180 +47.54,50.42422207,-3.58724281,50,-15.86881054,-1.87E-11,0,0,0,-180 +47.55,50.42422065,-3.58724281,50,-15.87228673,-2.08E-11,0,0,0,-180 +47.56,50.42421922,-3.58724281,50,-15.89314388,-8.41E-12,0,0,0,-180 +47.57,50.42421779,-3.58724281,50,-15.9209534,8.06E-12,0,0,0,-180 +47.58,50.42421636,-3.58724281,50,-15.94181054,2.04E-11,0,0,0,-180 +47.59,50.42421492,-3.58724281,50,-15.94528672,1.83E-11,0,0,0,-180 +47.6,50.42421349,-3.58724281,50,-15.94181051,-2.50E-13,0,0,0,-180 +47.61,50.42421206,-3.58724281,50,-15.94876289,-2.09E-11,0,0,0,-180 +47.62,50.42421062,-3.58724281,50,-15.95919147,-3.12E-11,0,0,0,-180 +47.63,50.42420919,-3.58724281,50,-15.96266766,-3.32E-11,0,0,0,-180 +47.64,50.42420775,-3.58724281,50,-15.96614385,-3.12E-11,0,0,0,-180 +47.65,50.42420632,-3.58724281,50,-15.98004861,-2.29E-11,0,0,0,-180 +47.66,50.42420488,-3.58724281,50,-16.00090575,-1.04E-11,0,0,0,-180 +47.67,50.42420344,-3.58724281,50,-16.01481049,-2.08E-12,0,0,0,-180 +47.68,50.424202,-3.58724281,50,-16.02176287,2.06E-12,0,0,0,-180 +47.69,50.42420056,-3.58724281,50,-16.03566765,1.03E-11,0,0,0,-180 +47.7,50.42419912,-3.58724281,50,-16.05304861,2.06E-11,0,0,0,-180 +47.71,50.42419767,-3.58724281,50,-16.05652478,1.85E-11,0,0,0,-180 +47.72,50.42419623,-3.58724281,50,-16.05304857,-7.81E-14,0,0,0,-180 +47.73,50.42419479,-3.58724281,50,-16.06000095,-2.08E-11,0,0,0,-180 +47.74,50.42419334,-3.58724281,50,-16.07390572,-2.91E-11,0,0,0,-180 +47.75,50.4241919,-3.58724281,50,-16.09128668,-2.29E-11,0,0,0,-180 +47.76,50.42419045,-3.58724281,50,-16.11214382,-1.04E-11,0,0,0,-180 +47.77,50.424189,-3.58724281,50,-16.12604856,-2.16E-12,0,0,0,-180 +47.78,50.42418755,-3.58724281,50,-16.12952474,-1.56E-13,0,0,0,-180 +47.79,50.4241861,-3.58724281,50,-16.12952473,-1.56E-13,0,0,0,-180 +47.8,50.42418465,-3.58724281,50,-16.13300093,2.00E-12,0,0,0,-180 +47.81,50.4241832,-3.58724281,50,-16.14690569,1.04E-11,0,0,0,-180 +47.82,50.42418175,-3.58724281,50,-16.16776282,2.29E-11,0,0,0,-180 +47.83,50.42418029,-3.58724281,50,-16.18166758,3.13E-11,0,0,0,-180 +47.84,50.42417884,-3.58724281,50,-16.18514379,3.34E-11,0,0,0,-180 +47.85,50.42417738,-3.58724281,50,-16.18861999,3.13E-11,0,0,0,-180 +47.86,50.42417593,-3.58724281,50,-16.19904855,2.09E-11,0,0,0,-180 +47.87,50.42417447,-3.58724281,50,-16.20600091,1.56E-13,0,0,0,-180 +47.88,50.42417301,-3.58724281,50,-16.20252472,-1.86E-11,0,0,0,-180 +47.89,50.42417156,-3.58724281,50,-16.20947709,-2.29E-11,0,0,0,-180 +47.9,50.4241701,-3.58724281,50,-16.2407628,-2.09E-11,0,0,0,-180 +47.91,50.42416864,-3.58724281,50,-16.27204852,-2.30E-11,0,0,0,-180 +47.92,50.42416717,-3.58724281,50,-16.2790009,-1.87E-11,0,0,0,-180 +47.93,50.42416571,-3.58724281,50,-16.2755247,1.41E-13,0,0,0,-180 +47.94,50.42416425,-3.58724281,50,-16.28247705,2.09E-11,0,0,0,-180 +47.95,50.42416278,-3.58724281,50,-16.29290562,3.12E-11,0,0,0,-180 +47.96,50.42416132,-3.58724281,50,-16.29638182,3.31E-11,0,0,0,-180 +47.97,50.42415985,-3.58724281,50,-16.29985801,3.09E-11,0,0,0,-180 +47.98,50.42415839,-3.58724281,50,-16.31376278,2.26E-11,0,0,0,-180 +47.99,50.42415692,-3.58724281,50,-16.33461992,1.01E-11,0,0,0,-180 +48,50.42415545,-3.58724281,50,-16.34852468,1.83E-12,0,0,0,-180 +48.01,50.42415398,-3.58724281,50,-16.35200087,-2.50E-13,0,0,0,-180 +48.02,50.42415251,-3.58724281,50,-16.35547706,1.83E-12,0,0,0,-180 +48.03,50.42415104,-3.58724281,50,-16.36938181,1.01E-11,0,0,0,-180 +48.04,50.42414957,-3.58724281,50,-16.39023893,2.26E-11,0,0,0,-180 +48.05,50.42414809,-3.58724281,50,-16.40414368,3.09E-11,0,0,0,-180 +48.06,50.42414662,-3.58724281,50,-16.40761988,3.30E-11,0,0,0,-180 +48.07,50.42414514,-3.58724281,50,-16.41109608,3.09E-11,0,0,0,-180 +48.08,50.42414367,-3.58724281,50,-16.42152465,2.05E-11,0,0,0,-180 +48.09,50.42414219,-3.58724281,50,-16.42847701,-2.34E-13,0,0,0,-180 +48.1,50.42414071,-3.58724281,50,-16.42500082,-1.89E-11,0,0,0,-180 +48.11,50.42413924,-3.58724281,50,-16.42847702,-2.08E-11,0,0,0,-180 +48.12,50.42413776,-3.58724281,50,-16.44933416,-8.16E-12,0,0,0,-180 +48.13,50.42413628,-3.58724281,50,-16.47714368,8.55E-12,0,0,0,-180 +48.14,50.4241348,-3.58724281,50,-16.49800081,2.10E-11,0,0,0,-180 +48.15,50.42413331,-3.58724281,50,-16.50147699,1.89E-11,0,0,0,-180 +48.16,50.42413183,-3.58724281,50,-16.49800079,-8.67E-18,0,0,0,-180 +48.17,50.42413035,-3.58724281,50,-16.50495317,-2.09E-11,0,0,0,-180 +48.18,50.42412886,-3.58724281,50,-16.51885794,-2.92E-11,0,0,0,-180 +48.19,50.42412738,-3.58724281,50,-16.5362389,-2.30E-11,0,0,0,-180 +48.2,50.42412589,-3.58724281,50,-16.55709604,-1.05E-11,0,0,0,-180 +48.21,50.4241244,-3.58724281,50,-16.57100078,-2.23E-12,0,0,0,-180 +48.22,50.42412291,-3.58724281,50,-16.57447696,-1.56E-13,0,0,0,-180 +48.23,50.42412142,-3.58724281,50,-16.57447696,-9.37E-14,0,0,0,-180 +48.24,50.42411993,-3.58724281,50,-16.57447697,-9.37E-14,0,0,0,-180 +48.25,50.42411844,-3.58724281,50,-16.57795316,-2.23E-12,0,0,0,-180 +48.26,50.42411695,-3.58724281,50,-16.59185791,-1.05E-11,0,0,0,-180 +48.27,50.42411546,-3.58724281,50,-16.61271505,-2.29E-11,0,0,0,-180 +48.28,50.42411396,-3.58724281,50,-16.62661981,-3.12E-11,0,0,0,-180 +48.29,50.42411247,-3.58724281,50,-16.63009599,-3.32E-11,0,0,0,-180 +48.3,50.42411097,-3.58724281,50,-16.63357218,-3.10E-11,0,0,0,-180 +48.31,50.42410948,-3.58724281,50,-16.64747694,-2.27E-11,0,0,0,-180 +48.32,50.42410798,-3.58724281,50,-16.66833408,-1.03E-11,0,0,0,-180 +48.33,50.42410648,-3.58724281,50,-16.68223883,-2.06E-12,0,0,0,-180 +48.34,50.42410498,-3.58724281,50,-16.68571502,1.73E-17,0,0,0,-180 +48.35,50.42410348,-3.58724281,50,-16.68571501,8.67E-18,0,0,0,-180 +48.36,50.42410198,-3.58724281,50,-16.68919121,2.08E-12,0,0,0,-180 +48.37,50.42410048,-3.58724281,50,-16.70309597,1.04E-11,0,0,0,-180 +48.38,50.42409898,-3.58724281,50,-16.7239531,2.29E-11,0,0,0,-180 +48.39,50.42409747,-3.58724281,50,-16.73785785,3.12E-11,0,0,0,-180 +48.4,50.42409597,-3.58724281,50,-16.74133404,3.32E-11,0,0,0,-180 +48.41,50.42409446,-3.58724281,50,-16.74481023,3.12E-11,0,0,0,-180 +48.42,50.42409296,-3.58724281,50,-16.75871499,2.29E-11,0,0,0,-180 +48.43,50.42409145,-3.58724281,50,-16.77957213,1.04E-11,0,0,0,-180 +48.44,50.42408994,-3.58724281,50,-16.79347689,2.08E-12,0,0,0,-180 +48.45,50.42408843,-3.58724281,50,-16.79695307,-1.73E-17,0,0,0,-180 +48.46,50.42408692,-3.58724281,50,-16.79695306,-2.60E-17,0,0,0,-180 +48.47,50.42408541,-3.58724281,50,-16.80042925,-2.08E-12,0,0,0,-180 +48.48,50.4240839,-3.58724281,50,-16.81433402,-1.04E-11,0,0,0,-180 +48.49,50.42408239,-3.58724281,50,-16.83519116,-2.29E-11,0,0,0,-180 +48.5,50.42408087,-3.58724281,50,-16.84909591,-3.12E-11,0,0,0,-180 +48.51,50.42407936,-3.58724281,50,-16.85257209,-3.32E-11,0,0,0,-180 +48.52,50.42407784,-3.58724281,50,-16.85604828,-3.11E-11,0,0,0,-180 +48.53,50.42407633,-3.58724281,50,-16.86995303,-2.27E-11,0,0,0,-180 +48.54,50.42407481,-3.58724281,50,-16.89081018,-1.02E-11,0,0,0,-180 +48.55,50.42407329,-3.58724281,50,-16.90471494,-2.00E-12,0,0,0,-180 +48.56,50.42407177,-3.58724281,50,-16.90819113,-1.73E-18,0,0,0,-180 +48.57,50.42407025,-3.58724281,50,-16.90819113,-7.81E-14,0,0,0,-180 +48.58,50.42406873,-3.58724281,50,-16.91166731,1.92E-12,0,0,0,-180 +48.59,50.42406721,-3.58724281,50,-16.92557206,1.02E-11,0,0,0,-180 +48.6,50.42406569,-3.58724281,50,-16.94642919,2.28E-11,0,0,0,-180 +48.61,50.42406416,-3.58724281,50,-16.96033395,3.11E-11,0,0,0,-180 +48.62,50.42406264,-3.58724281,50,-16.96381016,3.31E-11,0,0,0,-180 +48.63,50.42406111,-3.58724281,50,-16.96728634,3.10E-11,0,0,0,-180 +48.64,50.42405959,-3.58724281,50,-16.98119108,2.28E-11,0,0,0,-180 +48.65,50.42405806,-3.58724281,50,-17.00204822,1.03E-11,0,0,0,-180 +48.66,50.42405653,-3.58724281,50,-17.01595299,1.92E-12,0,0,0,-180 +48.67,50.424055,-3.58724281,50,-17.01942919,-1.41E-13,0,0,0,-180 +48.68,50.42405347,-3.58724281,50,-17.01942919,1.73E-17,0,0,0,-180 +48.69,50.42405194,-3.58724281,50,-17.01942916,1.41E-13,0,0,0,-180 +48.7,50.42405041,-3.58724281,50,-17.02290534,2.22E-12,0,0,0,-180 +48.71,50.42404888,-3.58724281,50,-17.0368101,1.04E-11,0,0,0,-180 +48.72,50.42404735,-3.58724281,50,-17.05766726,2.27E-11,0,0,0,-180 +48.73,50.42404581,-3.58724281,50,-17.07504822,2.89E-11,0,0,0,-180 +48.74,50.42404428,-3.58724281,50,-17.08895297,2.05E-11,0,0,0,-180 +48.75,50.42404274,-3.58724281,50,-17.09590533,-2.50E-13,0,0,0,-180 +48.76,50.4240412,-3.58724281,50,-17.09242913,-1.89E-11,0,0,0,-180 +48.77,50.42403967,-3.58724281,50,-17.09590531,-2.09E-11,0,0,0,-180 +48.78,50.42403813,-3.58724281,50,-17.11328626,-1.04E-11,0,0,0,-180 +48.79,50.42403659,-3.58724281,50,-17.13066722,-4.00E-12,0,0,0,-180 +48.8,50.42403505,-3.58724281,50,-17.14804817,-1.02E-11,0,0,0,-180 +48.81,50.42403351,-3.58724281,50,-17.16542911,-2.06E-11,0,0,0,-180 +48.82,50.42403196,-3.58724281,50,-17.1689053,-1.87E-11,0,0,0,-180 +48.83,50.42403042,-3.58724281,50,-17.16542911,-1.56E-13,0,0,0,-180 +48.84,50.42402888,-3.58724281,50,-17.17238148,2.05E-11,0,0,0,-180 +48.85,50.42402733,-3.58724281,50,-17.18628624,2.88E-11,0,0,0,-180 +48.86,50.42402579,-3.58724281,50,-17.20366719,2.26E-11,0,0,0,-180 +48.87,50.42402424,-3.58724281,50,-17.22452432,1.02E-11,0,0,0,-180 +48.88,50.42402269,-3.58724281,50,-17.23842908,1.92E-12,0,0,0,-180 +48.89,50.42402114,-3.58724281,50,-17.24190528,0,0,0,0,-180 +48.9,50.42401959,-3.58724281,50,-17.24190528,1.56E-13,0,0,0,-180 +48.91,50.42401804,-3.58724281,50,-17.24538146,-1.84E-12,0,0,0,-180 +48.92,50.42401649,-3.58724281,50,-17.25928622,-1.02E-11,0,0,0,-180 +48.93,50.42401494,-3.58724281,50,-17.27666717,-2.06E-11,0,0,0,-180 +48.94,50.42401338,-3.58724281,50,-17.28014334,-1.87E-11,0,0,0,-180 +48.95,50.42401183,-3.58724281,50,-17.28014333,-2.22E-12,0,0,0,-180 +48.96,50.42401028,-3.58724281,50,-17.29752428,8.16E-12,0,0,0,-180 +48.97,50.42400872,-3.58724281,50,-17.31490523,-2.17E-12,0,0,0,-180 +48.98,50.42400716,-3.58724281,50,-17.31490523,-1.88E-11,0,0,0,-180 +48.99,50.42400561,-3.58724281,50,-17.31838142,-2.09E-11,0,0,0,-180 +49,50.42400405,-3.58724281,50,-17.33576238,-1.05E-11,0,0,0,-180 +49.01,50.42400249,-3.58724281,50,-17.35314333,-4.23E-12,0,0,0,-180 +49.02,50.42400093,-3.58724281,50,-17.37052426,-1.04E-11,0,0,0,-180 +49.03,50.42399937,-3.58724281,50,-17.38790519,-2.07E-11,0,0,0,-180 +49.04,50.4239978,-3.58724281,50,-17.39138139,-1.85E-11,0,0,0,-180 +49.05,50.42399624,-3.58724281,50,-17.38790521,1.56E-13,0,0,0,-180 +49.06,50.42399468,-3.58724281,50,-17.3948576,2.09E-11,0,0,0,-180 +49.07,50.42399311,-3.58724281,50,-17.40876234,2.91E-11,0,0,0,-180 +49.08,50.42399155,-3.58724281,50,-17.42614328,2.29E-11,0,0,0,-180 +49.09,50.42398998,-3.58724281,50,-17.44700043,1.04E-11,0,0,0,-180 +49.1,50.42398841,-3.58724281,50,-17.46090519,2.00E-12,0,0,0,-180 +49.11,50.42398684,-3.58724281,50,-17.46438136,-1.56E-13,0,0,0,-180 +49.12,50.42398527,-3.58724281,50,-17.46438135,-1.56E-13,0,0,0,-180 +49.13,50.4239837,-3.58724281,50,-17.46438136,-7.81E-14,0,0,0,-180 +49.14,50.42398213,-3.58724281,50,-17.46785756,2.06E-12,0,0,0,-180 +49.15,50.42398056,-3.58724281,50,-17.48176231,1.04E-11,0,0,0,-180 +49.16,50.42397899,-3.58724281,50,-17.50261944,2.29E-11,0,0,0,-180 +49.17,50.42397741,-3.58724281,50,-17.51652419,3.12E-11,0,0,0,-180 +49.18,50.42397584,-3.58724281,50,-17.52000037,3.33E-11,0,0,0,-180 +49.19,50.42397426,-3.58724281,50,-17.52347656,3.12E-11,0,0,0,-180 +49.2,50.42397269,-3.58724281,50,-17.53738133,2.29E-11,0,0,0,-180 +49.21,50.42397111,-3.58724281,50,-17.55823848,1.04E-11,0,0,0,-180 +49.22,50.42396953,-3.58724281,50,-17.57214323,2.08E-12,0,0,0,-180 +49.23,50.42396795,-3.58724281,50,-17.5756194,-1.73E-17,0,0,0,-180 +49.24,50.42396637,-3.58724281,50,-17.57909559,2.06E-12,0,0,0,-180 +49.25,50.42396479,-3.58724281,50,-17.59300035,1.03E-11,0,0,0,-180 +49.26,50.42396321,-3.58724281,50,-17.61038129,2.06E-11,0,0,0,-180 +49.27,50.42396162,-3.58724281,50,-17.61385747,1.85E-11,0,0,0,-180 +49.28,50.42396004,-3.58724281,50,-17.61385748,2.00E-12,0,0,0,-180 +49.29,50.42395846,-3.58724281,50,-17.63123844,-8.33E-12,0,0,0,-180 +49.3,50.42395687,-3.58724281,50,-17.64861939,2.08E-12,0,0,0,-180 +49.31,50.42395528,-3.58724281,50,-17.64861937,1.87E-11,0,0,0,-180 +49.32,50.4239537,-3.58724281,50,-17.65209555,2.09E-11,0,0,0,-180 +49.33,50.42395211,-3.58724281,50,-17.6694765,1.05E-11,0,0,0,-180 +49.34,50.42395052,-3.58724281,50,-17.68338125,2.23E-12,0,0,0,-180 +49.35,50.42394893,-3.58724281,50,-17.69033363,-2.00E-12,0,0,0,-180 +49.36,50.42394734,-3.58724281,50,-17.70423839,-1.04E-11,0,0,0,-180 +49.37,50.42394575,-3.58724281,50,-17.72161934,-2.09E-11,0,0,0,-180 +49.38,50.42394415,-3.58724281,50,-17.72509553,-1.89E-11,0,0,0,-180 +49.39,50.42394256,-3.58724281,50,-17.72509553,-2.22E-12,0,0,0,-180 +49.4,50.42394097,-3.58724281,50,-17.74247646,8.31E-12,0,0,0,-180 +49.41,50.42393937,-3.58724281,50,-17.75985741,-1.94E-12,0,0,0,-180 +49.42,50.42393777,-3.58724281,50,-17.75985742,-1.85E-11,0,0,0,-180 +49.43,50.42393618,-3.58724281,50,-17.76333362,-2.07E-11,0,0,0,-180 +49.44,50.42393458,-3.58724281,50,-17.78071456,-1.03E-11,0,0,0,-180 +49.45,50.42393298,-3.58724281,50,-17.7946193,-1.91E-12,0,0,0,-180 +49.46,50.42393138,-3.58724281,50,-17.80157167,2.31E-12,0,0,0,-180 +49.47,50.42392978,-3.58724281,50,-17.81547643,1.06E-11,0,0,0,-180 +49.48,50.42392818,-3.58724281,50,-17.83285738,2.09E-11,0,0,0,-180 +49.49,50.42392657,-3.58724281,50,-17.83633357,1.87E-11,0,0,0,-180 +49.5,50.42392497,-3.58724281,50,-17.83633356,1.92E-12,0,0,0,-180 +49.51,50.42392337,-3.58724281,50,-17.85371451,-8.55E-12,0,0,0,-180 +49.52,50.42392176,-3.58724281,50,-17.87109545,1.83E-12,0,0,0,-180 +49.53,50.42392015,-3.58724281,50,-17.87109545,1.85E-11,0,0,0,-180 +49.54,50.42391855,-3.58724281,50,-17.87457164,2.05E-11,0,0,0,-180 +49.55,50.42391694,-3.58724281,50,-17.89195259,1.01E-11,0,0,0,-180 +49.56,50.42391533,-3.58724281,50,-17.90585734,1.84E-12,0,0,0,-180 +49.57,50.42391372,-3.58724281,50,-17.90933353,-1.56E-13,0,0,0,-180 +49.58,50.42391211,-3.58724281,50,-17.91280972,2.06E-12,0,0,0,-180 +49.59,50.4239105,-3.58724281,50,-17.92671448,1.05E-11,0,0,0,-180 +49.6,50.42390889,-3.58724281,50,-17.94757161,2.28E-11,0,0,0,-180 +49.61,50.42390727,-3.58724281,50,-17.96147637,3.10E-11,0,0,0,-180 +49.62,50.42390566,-3.58724281,50,-17.96495257,3.30E-11,0,0,0,-180 +49.63,50.42390404,-3.58724281,50,-17.96842875,3.09E-11,0,0,0,-180 +49.64,50.42390243,-3.58724281,50,-17.9823335,2.27E-11,0,0,0,-180 +49.65,50.42390081,-3.58724281,50,-18.00319062,1.04E-11,0,0,0,-180 +49.66,50.42389919,-3.58724281,50,-18.01709536,2.23E-12,0,0,0,-180 +49.67,50.42389757,-3.58724281,50,-18.02057155,2.34E-13,0,0,0,-180 +49.68,50.42389595,-3.58724281,50,-18.02057157,2.34E-13,0,0,0,-180 +49.69,50.42389433,-3.58724281,50,-18.02404777,-1.92E-12,0,0,0,-180 +49.7,50.42389271,-3.58724281,50,-18.03795253,-1.04E-11,0,0,0,-180 +49.71,50.42389109,-3.58724281,50,-18.05880966,-2.30E-11,0,0,0,-180 +49.72,50.42388946,-3.58724281,50,-18.07271441,-3.13E-11,0,0,0,-180 +49.73,50.42388784,-3.58724281,50,-18.0761906,-3.33E-11,0,0,0,-180 +49.74,50.42388621,-3.58724281,50,-18.07966678,-3.13E-11,0,0,0,-180 +49.75,50.42388459,-3.58724281,50,-18.09357154,-2.30E-11,0,0,0,-180 +49.76,50.42388296,-3.58724281,50,-18.11095249,-1.26E-11,0,0,0,-180 +49.77,50.42388133,-3.58724281,50,-18.11442866,-1.46E-11,0,0,0,-180 +49.78,50.4238797,-3.58724281,50,-18.11442865,-3.13E-11,0,0,0,-180 +49.79,50.42387808,-3.58724281,50,-18.1318096,-4.17E-11,0,0,0,-180 +49.8,50.42387644,-3.58724281,50,-18.14919056,-3.13E-11,0,0,0,-180 +49.81,50.42387481,-3.58724281,50,-18.14919056,-1.46E-11,0,0,0,-180 +49.82,50.42387318,-3.58724281,50,-18.15266675,-1.25E-11,0,0,0,-180 +49.83,50.42387155,-3.58724281,50,-18.1700477,-2.29E-11,0,0,0,-180 +49.84,50.42386991,-3.58724281,50,-18.18395245,-3.13E-11,0,0,0,-180 +49.85,50.42386828,-3.58724281,50,-18.18742863,-3.34E-11,0,0,0,-180 +49.86,50.42386664,-3.58724281,50,-18.19090481,-3.13E-11,0,0,0,-180 +49.87,50.42386501,-3.58724281,50,-18.20480956,-2.29E-11,0,0,0,-180 +49.88,50.42386337,-3.58724281,50,-18.22566671,-1.04E-11,0,0,0,-180 +49.89,50.42386173,-3.58724281,50,-18.23957148,-2.08E-12,0,0,0,-180 +49.9,50.42386009,-3.58724281,50,-18.24304767,1.73E-17,0,0,0,-180 +49.91,50.42385845,-3.58724281,50,-18.24652383,-2.08E-12,0,0,0,-180 +49.92,50.42385681,-3.58724281,50,-18.26042857,-1.04E-11,0,0,0,-180 +49.93,50.42385517,-3.58724281,50,-18.28128571,-2.29E-11,0,0,0,-180 +49.94,50.42385352,-3.58724281,50,-18.29519049,-3.12E-11,0,0,0,-180 +49.95,50.42385188,-3.58724281,50,-18.29866669,-3.32E-11,0,0,0,-180 +49.96,50.42385023,-3.58724281,50,-18.30214288,-3.12E-11,0,0,0,-180 +49.97,50.42384859,-3.58724281,50,-18.31604762,-2.29E-11,0,0,0,-180 +49.98,50.42384694,-3.58724281,50,-18.33342855,-1.25E-11,0,0,0,-180 +49.99,50.42384529,-3.58724281,50,-18.33690473,-1.45E-11,0,0,0,-180 +50,50.42384364,-3.58724281,50,-18.33690475,-3.12E-11,0,0,0,-180 +50.01,50.423842,-3.58724281,50,-18.35428571,-4.16E-11,0,0,0,-180 +50.02,50.42384034,-3.58724281,50,-18.37166665,-3.12E-11,0,0,0,-180 +50.03,50.42383869,-3.58724281,50,-18.37166662,-1.45E-11,0,0,0,-180 +50.04,50.42383704,-3.58724281,50,-18.3751428,-1.24E-11,0,0,0,-180 +50.05,50.42383539,-3.58724281,50,-18.39252377,-2.27E-11,0,0,0,-180 +50.06,50.42383373,-3.58724281,50,-18.40642853,-3.10E-11,0,0,0,-180 +50.07,50.42383208,-3.58724281,50,-18.4099047,-3.32E-11,0,0,0,-180 +50.08,50.42383042,-3.58724281,50,-18.41338088,-3.12E-11,0,0,0,-180 +50.09,50.42382877,-3.58724281,50,-18.42728565,-2.28E-11,0,0,0,-180 +50.1,50.42382711,-3.58724281,50,-18.44814279,-1.03E-11,0,0,0,-180 +50.11,50.42382545,-3.58724281,50,-18.46204754,-1.92E-12,0,0,0,-180 +50.12,50.42382379,-3.58724281,50,-18.46552372,1.56E-13,0,0,0,-180 +50.13,50.42382213,-3.58724281,50,-18.46899992,-1.98E-12,0,0,0,-180 +50.14,50.42382047,-3.58724281,50,-18.48290467,-1.03E-11,0,0,0,-180 +50.15,50.42381881,-3.58724281,50,-18.50028562,-2.06E-11,0,0,0,-180 +50.16,50.42381714,-3.58724281,50,-18.5037618,-1.85E-11,0,0,0,-180 +50.17,50.42381548,-3.58724281,50,-18.50376179,-1.98E-12,0,0,0,-180 +50.18,50.42381382,-3.58724281,50,-18.52114273,8.41E-12,0,0,0,-180 +50.19,50.42381215,-3.58724281,50,-18.53852369,-1.92E-12,0,0,0,-180 +50.2,50.42381048,-3.58724281,50,-18.53852369,-1.86E-11,0,0,0,-180 +50.21,50.42380882,-3.58724281,50,-18.54199987,-2.08E-11,0,0,0,-180 +50.22,50.42380715,-3.58724281,50,-18.55938081,-1.05E-11,0,0,0,-180 +50.23,50.42380548,-3.58724281,50,-18.57328558,-2.31E-12,0,0,0,-180 +50.24,50.42380381,-3.58724281,50,-18.58023795,1.84E-12,0,0,0,-180 +50.25,50.42380214,-3.58724281,50,-18.5941427,1.02E-11,0,0,0,-180 +50.26,50.42380047,-3.58724281,50,-18.61499984,2.29E-11,0,0,0,-180 +50.27,50.42379879,-3.58724281,50,-18.6289046,3.13E-11,0,0,0,-180 +50.28,50.42379712,-3.58724281,50,-18.63238078,3.35E-11,0,0,0,-180 +50.29,50.42379544,-3.58724281,50,-18.63238078,3.35E-11,0,0,0,-180 +50.3,50.42379377,-3.58724281,50,-18.63238077,3.35E-11,0,0,0,-180 +50.31,50.42379209,-3.58724281,50,-18.63585696,3.14E-11,0,0,0,-180 +50.32,50.42379042,-3.58724281,50,-18.64976171,2.31E-11,0,0,0,-180 +50.33,50.42378874,-3.58724281,50,-18.67061885,1.06E-11,0,0,0,-180 +50.34,50.42378706,-3.58724281,50,-18.68452361,2.33E-12,0,0,0,-180 +50.35,50.42378538,-3.58724281,50,-18.69147599,-1.83E-12,0,0,0,-180 +50.36,50.4237837,-3.58724281,50,-18.70538074,-1.01E-11,0,0,0,-180 +50.37,50.42378202,-3.58724281,50,-18.72623788,-2.26E-11,0,0,0,-180 +50.38,50.42378033,-3.58724281,50,-18.74014263,-3.09E-11,0,0,0,-180 +50.39,50.42377865,-3.58724281,50,-18.74361882,-3.30E-11,0,0,0,-180 +50.4,50.42377696,-3.58724281,50,-18.74709499,-3.09E-11,0,0,0,-180 +50.41,50.42377528,-3.58724281,50,-18.75752356,-2.06E-11,0,0,0,-180 +50.42,50.42377359,-3.58724281,50,-18.76447595,0,0,0,0,-180 +50.43,50.4237719,-3.58724281,50,-18.76099976,1.86E-11,0,0,0,-180 +50.44,50.42377022,-3.58724281,50,-18.76447594,2.06E-11,0,0,0,-180 +50.45,50.42376853,-3.58724281,50,-18.78185687,1.04E-11,0,0,0,-180 +50.46,50.42376684,-3.58724281,50,-18.79923781,4.30E-12,0,0,0,-180 +50.47,50.42376515,-3.58724281,50,-18.81661877,1.05E-11,0,0,0,-180 +50.48,50.42376346,-3.58724281,50,-18.83747592,2.29E-11,0,0,0,-180 +50.49,50.42376176,-3.58724281,50,-18.85138068,3.10E-11,0,0,0,-180 +50.5,50.42376007,-3.58724281,50,-18.85485685,3.31E-11,0,0,0,-180 +50.51,50.42375837,-3.58724281,50,-18.85485685,3.32E-11,0,0,0,-180 +50.52,50.42375668,-3.58724281,50,-18.85485684,3.32E-11,0,0,0,-180 +50.53,50.42375498,-3.58724281,50,-18.85833301,3.10E-11,0,0,0,-180 +50.54,50.42375329,-3.58724281,50,-18.87223776,2.27E-11,0,0,0,-180 +50.55,50.42375159,-3.58724281,50,-18.89309491,1.03E-11,0,0,0,-180 +50.56,50.42374989,-3.58724281,50,-18.90699969,1.98E-12,0,0,0,-180 +50.57,50.42374819,-3.58724281,50,-18.91395207,-2.23E-12,0,0,0,-180 +50.58,50.42374649,-3.58724281,50,-18.92785681,-1.05E-11,0,0,0,-180 +50.59,50.42374479,-3.58724281,50,-18.94523774,-2.09E-11,0,0,0,-180 +50.6,50.42374308,-3.58724281,50,-18.94871393,-1.87E-11,0,0,0,-180 +50.61,50.42374138,-3.58724281,50,-18.94871394,-2.08E-12,0,0,0,-180 +50.62,50.42373968,-3.58724281,50,-18.96609489,8.31E-12,0,0,0,-180 +50.63,50.42373797,-3.58724281,50,-18.98347583,-2.09E-12,0,0,0,-180 +50.64,50.42373626,-3.58724281,50,-18.98347581,-1.88E-11,0,0,0,-180 +50.65,50.42373456,-3.58724281,50,-18.98695199,-2.09E-11,0,0,0,-180 +50.66,50.42373285,-3.58724281,50,-19.00433294,-1.05E-11,0,0,0,-180 +50.67,50.42373114,-3.58724281,50,-19.0182377,-2.16E-12,0,0,0,-180 +50.68,50.42372943,-3.58724281,50,-19.02171388,-1.56E-14,0,0,0,-180 +50.69,50.42372772,-3.58724281,50,-19.02519007,-2.08E-12,0,0,0,-180 +50.7,50.42372601,-3.58724281,50,-19.03909483,-1.04E-11,0,0,0,-180 +50.71,50.4237243,-3.58724281,50,-19.05995198,-2.29E-11,0,0,0,-180 +50.72,50.42372258,-3.58724281,50,-19.07385675,-3.12E-11,0,0,0,-180 +50.73,50.42372087,-3.58724281,50,-19.07733293,-3.32E-11,0,0,0,-180 +50.74,50.42371915,-3.58724281,50,-19.08080911,-3.12E-11,0,0,0,-180 +50.75,50.42371744,-3.58724281,50,-19.09471385,-2.28E-11,0,0,0,-180 +50.76,50.42371572,-3.58724281,50,-19.11557098,-1.03E-11,0,0,0,-180 +50.77,50.423714,-3.58724281,50,-19.12947572,-1.92E-12,0,0,0,-180 +50.78,50.42371228,-3.58724281,50,-19.1329519,1.56E-13,0,0,0,-180 +50.79,50.42371056,-3.58724281,50,-19.1329519,7.81E-14,0,0,0,-180 +50.8,50.42370884,-3.58724281,50,-19.13295191,1.56E-14,0,0,0,-180 +50.81,50.42370712,-3.58724281,50,-19.1364281,-2.08E-12,0,0,0,-180 +50.82,50.4237054,-3.58724281,50,-19.15033286,-1.04E-11,0,0,0,-180 +50.83,50.42370368,-3.58724281,50,-19.17118999,-2.28E-11,0,0,0,-180 +50.84,50.42370195,-3.58724281,50,-19.18857094,-2.90E-11,0,0,0,-180 +50.85,50.42370023,-3.58724281,50,-19.2024757,-2.06E-11,0,0,0,-180 +50.86,50.4236985,-3.58724281,50,-19.20942808,1.56E-13,0,0,0,-180 +50.87,50.42369677,-3.58724281,50,-19.20595189,1.88E-11,0,0,0,-180 +50.88,50.42369505,-3.58724281,50,-19.20942806,2.08E-11,0,0,0,-180 +50.89,50.42369332,-3.58724281,50,-19.226809,1.03E-11,0,0,0,-180 +50.9,50.42369159,-3.58724281,50,-19.24418994,4.00E-12,0,0,0,-180 +50.91,50.42368986,-3.58724281,50,-19.26157089,1.03E-11,0,0,0,-180 +50.92,50.42368813,-3.58724281,50,-19.27895185,2.08E-11,0,0,0,-180 +50.93,50.42368639,-3.58724281,50,-19.28242804,1.88E-11,0,0,0,-180 +50.94,50.42368466,-3.58724281,50,-19.27895183,1.56E-13,0,0,0,-180 +50.95,50.42368293,-3.58724281,50,-19.2859042,-2.07E-11,0,0,0,-180 +50.96,50.42368119,-3.58724281,50,-19.29980895,-2.90E-11,0,0,0,-180 +50.97,50.42367946,-3.58724281,50,-19.31718991,-2.27E-11,0,0,0,-180 +50.98,50.42367772,-3.58724281,50,-19.33804706,-1.02E-11,0,0,0,-180 +50.99,50.42367598,-3.58724281,50,-19.35195181,-1.84E-12,0,0,0,-180 +51,50.42367424,-3.58724281,50,-19.35542798,1.56E-13,0,0,0,-180 +51.01,50.4236725,-3.58724281,50,-19.35542798,-1.56E-17,0,0,0,-180 +51.02,50.42367076,-3.58724281,50,-19.35542799,-1.56E-13,0,0,0,-180 +51.03,50.42366902,-3.58724281,50,-19.35890417,-2.31E-12,0,0,0,-180 +51.04,50.42366728,-3.58724281,50,-19.37280891,-1.06E-11,0,0,0,-180 +51.05,50.42366554,-3.58724281,50,-19.39366604,-2.31E-11,0,0,0,-180 +51.06,50.42366379,-3.58724281,50,-19.4075708,-3.14E-11,0,0,0,-180 +51.07,50.42366205,-3.58724281,50,-19.41104699,-3.34E-11,0,0,0,-180 +51.08,50.4236603,-3.58724281,50,-19.41452317,-3.12E-11,0,0,0,-180 +51.09,50.42365856,-3.58724281,50,-19.42842793,-2.28E-11,0,0,0,-180 +51.1,50.42365681,-3.58724281,50,-19.44928507,-1.04E-11,0,0,0,-180 +51.11,50.42365506,-3.58724281,50,-19.46318982,-2.23E-12,0,0,0,-180 +51.12,50.42365331,-3.58724281,50,-19.466666,-2.34E-13,0,0,0,-180 +51.13,50.42365156,-3.58724281,50,-19.47014219,-2.33E-12,0,0,0,-180 +51.14,50.42364981,-3.58724281,50,-19.48404695,-1.06E-11,0,0,0,-180 +51.15,50.42364806,-3.58724281,50,-19.50142789,-2.10E-11,0,0,0,-180 +51.16,50.4236463,-3.58724281,50,-19.50490407,-1.90E-11,0,0,0,-180 +51.17,50.42364455,-3.58724281,50,-19.50490407,-2.31E-12,0,0,0,-180 +51.18,50.4236428,-3.58724281,50,-19.52228501,8.16E-12,0,0,0,-180 +51.19,50.42364104,-3.58724281,50,-19.53966596,-2.08E-12,0,0,0,-180 +51.2,50.42363928,-3.58724281,50,-19.53966596,-1.86E-11,0,0,0,-180 +51.21,50.42363753,-3.58724281,50,-19.54314215,-2.06E-11,0,0,0,-180 +51.22,50.42363577,-3.58724281,50,-19.5605231,-1.04E-11,0,0,0,-180 +51.23,50.42363401,-3.58724281,50,-19.57442784,-2.22E-12,0,0,0,-180 +51.24,50.42363225,-3.58724281,50,-19.58138021,1.92E-12,0,0,0,-180 +51.25,50.42363049,-3.58724281,50,-19.59528498,1.03E-11,0,0,0,-180 +51.26,50.42362873,-3.58724281,50,-19.61614212,2.28E-11,0,0,0,-180 +51.27,50.42362696,-3.58724281,50,-19.63004686,3.10E-11,0,0,0,-180 +51.28,50.4236252,-3.58724281,50,-19.63352303,3.31E-11,0,0,0,-180 +51.29,50.42362343,-3.58724281,50,-19.63699922,3.11E-11,0,0,0,-180 +51.3,50.42362167,-3.58724281,50,-19.6474278,2.07E-11,0,0,0,-180 +51.31,50.4236199,-3.58724281,50,-19.65438018,-1.56E-13,0,0,0,-180 +51.32,50.42361813,-3.58724281,50,-19.65090397,-1.89E-11,0,0,0,-180 +51.33,50.42361637,-3.58724281,50,-19.65438015,-2.09E-11,0,0,0,-180 +51.34,50.4236146,-3.58724281,50,-19.67523729,-8.33E-12,0,0,0,-180 +51.35,50.42361283,-3.58724281,50,-19.70304682,8.30E-12,0,0,0,-180 +51.36,50.42361106,-3.58724281,50,-19.72390397,2.07E-11,0,0,0,-180 +51.37,50.42360928,-3.58724281,50,-19.72738014,1.85E-11,0,0,0,-180 +51.38,50.42360751,-3.58724281,50,-19.72390393,-1.56E-13,0,0,0,-180 +51.39,50.42360574,-3.58724281,50,-19.73085631,-2.09E-11,0,0,0,-180 +51.4,50.42360396,-3.58724281,50,-19.74476108,-2.91E-11,0,0,0,-180 +51.41,50.42360219,-3.58724281,50,-19.75866583,-2.08E-11,0,0,0,-180 +51.42,50.42360041,-3.58724281,50,-19.76561819,-2.60E-17,0,0,0,-180 +51.43,50.42359863,-3.58724281,50,-19.76214198,1.87E-11,0,0,0,-180 +51.44,50.42359686,-3.58724281,50,-19.76561817,2.08E-11,0,0,0,-180 +51.45,50.42359508,-3.58724281,50,-19.78647531,8.31E-12,0,0,0,-180 +51.46,50.4235933,-3.58724281,50,-19.81428482,-8.31E-12,0,0,0,-180 +51.47,50.42359152,-3.58724281,50,-19.83514197,-2.08E-11,0,0,0,-180 +51.48,50.42358973,-3.58724281,50,-19.83861818,-1.87E-11,0,0,0,-180 +51.49,50.42358795,-3.58724281,50,-19.83514198,0,0,0,0,-180 +51.5,50.42358617,-3.58724281,50,-19.84209433,2.08E-11,0,0,0,-180 +51.51,50.42358438,-3.58724281,50,-19.85252289,3.12E-11,0,0,0,-180 +51.52,50.4235826,-3.58724281,50,-19.85599908,3.33E-11,0,0,0,-180 +51.53,50.42358081,-3.58724281,50,-19.85947527,3.12E-11,0,0,0,-180 +51.54,50.42357903,-3.58724281,50,-19.87338001,2.29E-11,0,0,0,-180 +51.55,50.42357724,-3.58724281,50,-19.89423715,1.04E-11,0,0,0,-180 +51.56,50.42357545,-3.58724281,50,-19.90814192,2.16E-12,0,0,0,-180 +51.57,50.42357366,-3.58724281,50,-19.9150943,-1.92E-12,0,0,0,-180 +51.58,50.42357187,-3.58724281,50,-19.92899906,-1.02E-11,0,0,0,-180 +51.59,50.42357008,-3.58724281,50,-19.94638,-2.07E-11,0,0,0,-180 +51.6,50.42356828,-3.58724281,50,-19.94985617,-1.87E-11,0,0,0,-180 +51.61,50.42356649,-3.58724281,50,-19.94985616,-2.06E-12,0,0,0,-180 +51.62,50.4235647,-3.58724281,50,-19.9672371,8.39E-12,0,0,0,-180 +51.63,50.4235629,-3.58724281,50,-19.98461805,-1.92E-12,0,0,0,-180 +51.64,50.4235611,-3.58724281,50,-19.98461804,-1.85E-11,0,0,0,-180 +51.65,50.42355931,-3.58724281,50,-19.98809423,-2.07E-11,0,0,0,-180 +51.66,50.42355751,-3.58724281,50,-20.00199898,-1.24E-11,0,0,0,-180 +51.67,50.42355571,-3.58724281,50,-20.00199899,-1.23E-11,0,0,0,-180 +51.68,50.42355391,-3.58724281,50,-19.98809423,-2.06E-11,0,0,0,-180 +51.69,50.42355212,-3.58724281,50,-19.98809423,-2.07E-11,0,0,0,-180 +51.7,50.42355032,-3.58724281,50,-20.00547518,-1.03E-11,0,0,0,-180 +51.71,50.42354852,-3.58724281,50,-20.01590374,1.56E-13,0,0,0,-180 +51.72,50.42354672,-3.58724281,50,-20.00547515,1.05E-11,0,0,0,-180 +51.73,50.42354492,-3.58724281,50,-19.98809418,2.09E-11,0,0,0,-180 +51.74,50.42354313,-3.58724281,50,-19.98809417,2.09E-11,0,0,0,-180 +51.75,50.42354133,-3.58724281,50,-20.00547512,1.05E-11,0,0,0,-180 +51.76,50.42353953,-3.58724281,50,-20.01590368,1.56E-13,0,0,0,-180 +51.77,50.42353773,-3.58724281,50,-20.0054751,-1.03E-11,0,0,0,-180 +51.78,50.42353593,-3.58724281,50,-19.98809414,-2.07E-11,0,0,0,-180 +51.79,50.42353414,-3.58724281,50,-19.98809414,-2.06E-11,0,0,0,-180 +51.8,50.42353234,-3.58724281,50,-20.00547509,-1.02E-11,0,0,0,-180 +51.81,50.42353054,-3.58724281,50,-20.01590365,9.37E-14,0,0,0,-180 +51.82,50.42352874,-3.58724281,50,-20.00547507,1.05E-11,0,0,0,-180 +51.83,50.42352694,-3.58724281,50,-19.98809412,2.09E-11,0,0,0,-180 +51.84,50.42352515,-3.58724281,50,-19.98809412,2.09E-11,0,0,0,-180 +51.85,50.42352335,-3.58724281,50,-20.00547508,1.05E-11,0,0,0,-180 +51.86,50.42352155,-3.58724281,50,-20.01590364,9.37E-14,0,0,0,-180 +51.87,50.42351975,-3.58724281,50,-20.00547505,-1.02E-11,0,0,0,-180 +51.88,50.42351795,-3.58724281,50,-19.98809409,-2.06E-11,0,0,0,-180 +51.89,50.42351616,-3.58724281,50,-19.98809409,-2.07E-11,0,0,0,-180 +51.9,50.42351436,-3.58724281,50,-20.00199885,-1.24E-11,0,0,0,-180 +51.91,50.42351256,-3.58724281,50,-20.00199885,-1.23E-11,0,0,0,-180 +51.92,50.42351076,-3.58724281,50,-19.98809407,-2.06E-11,0,0,0,-180 +51.93,50.42350897,-3.58724281,50,-19.98809405,-2.07E-11,0,0,0,-180 +51.94,50.42350717,-3.58724281,50,-20.005475,-1.03E-11,0,0,0,-180 +51.95,50.42350537,-3.58724281,50,-20.01590356,1.56E-13,0,0,0,-180 +51.96,50.42350357,-3.58724281,50,-20.00547499,1.05E-11,0,0,0,-180 +51.97,50.42350177,-3.58724281,50,-19.98809403,2.09E-11,0,0,0,-180 +51.98,50.42349998,-3.58724281,50,-19.98809402,2.09E-11,0,0,0,-180 +51.99,50.42349818,-3.58724281,50,-20.00547497,1.05E-11,0,0,0,-180 +52,50.42349638,-3.58724281,50,-20.01590354,1.56E-13,0,0,0,-180 +52.01,50.42349458,-3.58724281,50,-20.00547498,-1.03E-11,0,0,0,-180 +52.02,50.42349278,-3.58724281,50,-19.98809402,-2.07E-11,0,0,0,-180 +52.03,50.42349099,-3.58724281,50,-19.988094,-2.06E-11,0,0,0,-180 +52.04,50.42348919,-3.58724281,50,-20.00547494,-1.03E-11,0,0,0,-180 +52.05,50.42348739,-3.58724281,50,-20.0159035,-1.73E-17,0,0,0,-180 +52.06,50.42348559,-3.58724281,50,-20.00547492,1.02E-11,0,0,0,-180 +52.07,50.42348379,-3.58724281,50,-19.98809397,2.06E-11,0,0,0,-180 +52.08,50.423482,-3.58724281,50,-19.98809397,2.07E-11,0,0,0,-180 +52.09,50.4234802,-3.58724281,50,-20.00547493,1.03E-11,0,0,0,-180 +52.1,50.4234784,-3.58724281,50,-20.01590349,-1.56E-13,0,0,0,-180 +52.11,50.4234766,-3.58724281,50,-20.0054749,-1.05E-11,0,0,0,-180 +52.12,50.4234748,-3.58724281,50,-19.98809394,-2.09E-11,0,0,0,-180 +52.13,50.42347301,-3.58724281,50,-19.98809393,-2.09E-11,0,0,0,-180 +52.14,50.42347121,-3.58724281,50,-20.00547487,-1.05E-11,0,0,0,-180 +52.15,50.42346941,-3.58724281,50,-20.01590344,-1.56E-13,0,0,0,-180 +52.16,50.42346761,-3.58724281,50,-20.00547487,1.03E-11,0,0,0,-180 +52.17,50.42346581,-3.58724281,50,-19.98809392,2.07E-11,0,0,0,-180 +52.18,50.42346402,-3.58724281,50,-19.98809392,2.06E-11,0,0,0,-180 +52.19,50.42346222,-3.58724281,50,-20.00547485,1.02E-11,0,0,0,-180 +52.2,50.42346042,-3.58724281,50,-20.01590341,0,0,0,0,-180 +52.21,50.42345862,-3.58724281,50,-20.00547483,-1.02E-11,0,0,0,-180 +52.22,50.42345682,-3.58724281,50,-19.98809387,-2.06E-11,0,0,0,-180 +52.23,50.42345503,-3.58724281,50,-19.98809387,-2.07E-11,0,0,0,-180 +52.24,50.42345323,-3.58724281,50,-20.00199862,-1.24E-11,0,0,0,-180 +52.25,50.42345143,-3.58724281,50,-20.00199862,-1.23E-11,0,0,0,-180 +52.26,50.42344963,-3.58724281,50,-19.98809385,-2.06E-11,0,0,0,-180 +52.27,50.42344784,-3.58724281,50,-19.98809384,-2.08E-11,0,0,0,-180 +52.28,50.42344604,-3.58724281,50,-20.0054748,-1.05E-11,0,0,0,-180 +52.29,50.42344424,-3.58724281,50,-20.01937957,-2.22E-12,0,0,0,-180 +52.3,50.42344244,-3.58724281,50,-20.01937956,-2.08E-12,0,0,0,-180 +52.31,50.42344064,-3.58724281,50,-20.00547479,-1.02E-11,0,0,0,-180 +52.32,50.42343884,-3.58724281,50,-19.98809383,-2.06E-11,0,0,0,-180 +52.33,50.42343705,-3.58724281,50,-19.98809383,-2.07E-11,0,0,0,-180 +52.34,50.42343525,-3.58724281,50,-20.00199857,-1.24E-11,0,0,0,-180 +52.35,50.42343345,-3.58724281,50,-20.00199856,-1.23E-11,0,0,0,-180 +52.36,50.42343165,-3.58724281,50,-19.98809378,-2.06E-11,0,0,0,-180 +52.37,50.42342986,-3.58724281,50,-19.98809378,-2.07E-11,0,0,0,-180 +52.38,50.42342806,-3.58724281,50,-20.00547473,-1.03E-11,0,0,0,-180 +52.39,50.42342626,-3.58724281,50,-20.01590329,1.56E-13,0,0,0,-180 +52.4,50.42342446,-3.58724281,50,-20.00547471,1.05E-11,0,0,0,-180 +52.41,50.42342266,-3.58724281,50,-19.98809375,2.08E-11,0,0,0,-180 +52.42,50.42342087,-3.58724281,50,-19.98809375,2.06E-11,0,0,0,-180 +52.43,50.42341907,-3.58724281,50,-20.00547469,1.02E-11,0,0,0,-180 +52.44,50.42341727,-3.58724281,50,-20.01590326,0,0,0,0,-180 +52.45,50.42341547,-3.58724281,50,-20.00547469,-1.02E-11,0,0,0,-180 +52.46,50.42341367,-3.58724281,50,-19.98809374,-2.06E-11,0,0,0,-180 +52.47,50.42341188,-3.58724281,50,-19.98809376,-2.07E-11,0,0,0,-180 +52.48,50.42341008,-3.58724281,50,-20.00547471,-1.03E-11,0,0,0,-180 +52.49,50.42340828,-3.58724281,50,-20.01590325,1.56E-13,0,0,0,-180 +52.5,50.42340648,-3.58724281,50,-20.00547466,1.05E-11,0,0,0,-180 +52.51,50.42340468,-3.58724281,50,-19.98809369,2.08E-11,0,0,0,-180 +52.52,50.42340289,-3.58724281,50,-19.98809369,2.06E-11,0,0,0,-180 +52.53,50.42340109,-3.58724281,50,-20.00547463,1.02E-11,0,0,0,-180 +52.54,50.42339929,-3.58724281,50,-20.0159032,-9.38E-14,0,0,0,-180 +52.55,50.42339749,-3.58724281,50,-20.00547462,-1.05E-11,0,0,0,-180 +52.56,50.42339569,-3.58724281,50,-19.98809366,-2.09E-11,0,0,0,-180 +52.57,50.4233939,-3.58724281,50,-19.98809365,-2.09E-11,0,0,0,-180 +52.58,50.4233921,-3.58724281,50,-20.0054746,-1.04E-11,0,0,0,-180 +52.59,50.4233903,-3.58724281,50,-20.01590317,1.41E-13,0,0,0,-180 +52.6,50.4233885,-3.58724281,50,-20.00547459,1.05E-11,0,0,0,-180 +52.61,50.4233867,-3.58724281,50,-19.98809363,2.08E-11,0,0,0,-180 +52.62,50.42338491,-3.58724281,50,-19.98809363,2.06E-11,0,0,0,-180 +52.63,50.42338311,-3.58724281,50,-20.00547458,1.03E-11,0,0,0,-180 +52.64,50.42338131,-3.58724281,50,-20.01590316,1.73E-17,0,0,0,-180 +52.65,50.42337951,-3.58724281,50,-20.00547459,-1.02E-11,0,0,0,-180 +52.66,50.42337771,-3.58724281,50,-19.98809363,-2.06E-11,0,0,0,-180 +52.67,50.42337592,-3.58724281,50,-19.98809362,-2.07E-11,0,0,0,-180 +52.68,50.42337412,-3.58724281,50,-20.00199836,-1.24E-11,0,0,0,-180 +52.69,50.42337232,-3.58724281,50,-20.00199834,-1.23E-11,0,0,0,-180 +52.7,50.42337052,-3.58724281,50,-19.98809357,-2.06E-11,0,0,0,-180 +52.71,50.42336873,-3.58724281,50,-19.98809357,-2.08E-11,0,0,0,-180 +52.72,50.42336693,-3.58724281,50,-20.00547451,-1.05E-11,0,0,0,-180 +52.73,50.42336513,-3.58724281,50,-20.01590308,-1.56E-13,0,0,0,-180 +52.74,50.42336333,-3.58724281,50,-20.0054745,1.03E-11,0,0,0,-180 +52.75,50.42336153,-3.58724281,50,-19.98809354,2.07E-11,0,0,0,-180 +52.76,50.42335974,-3.58724281,50,-19.98809354,2.06E-11,0,0,0,-180 +52.77,50.42335794,-3.58724281,50,-20.00547448,1.02E-11,0,0,0,-180 +52.78,50.42335614,-3.58724281,50,-20.01590305,-1.73E-17,0,0,0,-180 +52.79,50.42335434,-3.58724281,50,-20.00547448,-1.03E-11,0,0,0,-180 +52.8,50.42335254,-3.58724281,50,-19.98809353,-2.06E-11,0,0,0,-180 +52.81,50.42335075,-3.58724281,50,-19.98809353,-2.08E-11,0,0,0,-180 +52.82,50.42334895,-3.58724281,50,-20.00547446,-1.05E-11,0,0,0,-180 +52.83,50.42334715,-3.58724281,50,-20.01590302,-1.41E-13,0,0,0,-180 +52.84,50.42334535,-3.58724281,50,-20.00547445,1.04E-11,0,0,0,-180 +52.85,50.42334355,-3.58724281,50,-19.9880935,2.09E-11,0,0,0,-180 +52.86,50.42334176,-3.58724281,50,-19.9880935,2.09E-11,0,0,0,-180 +52.87,50.42333996,-3.58724281,50,-20.00547443,1.04E-11,0,0,0,-180 +52.88,50.42333816,-3.58724281,50,-20.01590299,-1.41E-13,0,0,0,-180 +52.89,50.42333636,-3.58724281,50,-20.00547441,-1.05E-11,0,0,0,-180 +52.9,50.42333456,-3.58724281,50,-19.98809345,-2.08E-11,0,0,0,-180 +52.91,50.42333277,-3.58724281,50,-19.98809344,-2.06E-11,0,0,0,-180 +52.92,50.42333097,-3.58724281,50,-20.00547439,-1.02E-11,0,0,0,-180 +52.93,50.42332917,-3.58724281,50,-20.01590296,0,0,0,0,-180 +52.94,50.42332737,-3.58724281,50,-20.00547439,1.02E-11,0,0,0,-180 +52.95,50.42332557,-3.58724281,50,-19.98809344,2.06E-11,0,0,0,-180 +52.96,50.42332378,-3.58724281,50,-19.98809343,2.08E-11,0,0,0,-180 +52.97,50.42332198,-3.58724281,50,-20.00547437,1.05E-11,0,0,0,-180 +52.98,50.42332018,-3.58724281,50,-20.01590293,1.56E-13,0,0,0,-180 +52.99,50.42331838,-3.58724281,50,-20.00547435,-1.03E-11,0,0,0,-180 +53,50.42331658,-3.58724281,50,-19.98809339,-2.07E-11,0,0,0,-180 +53.01,50.42331479,-3.58724281,50,-19.98809338,-2.06E-11,0,0,0,-180 +53.02,50.42331299,-3.58724281,50,-20.00199814,-1.23E-11,0,0,0,-180 +53.03,50.42331119,-3.58724281,50,-20.00199814,-1.25E-11,0,0,0,-180 +53.04,50.42330939,-3.58724281,50,-19.98809338,-2.09E-11,0,0,0,-180 +53.05,50.4233076,-3.58724281,50,-19.98809338,-2.09E-11,0,0,0,-180 +53.06,50.4233058,-3.58724281,50,-20.00547431,-1.04E-11,0,0,0,-180 +53.07,50.423304,-3.58724281,50,-20.01590287,1.41E-13,0,0,0,-180 +53.08,50.4233022,-3.58724281,50,-20.00547429,1.05E-11,0,0,0,-180 +53.09,50.4233004,-3.58724281,50,-19.98809334,2.08E-11,0,0,0,-180 +53.1,50.42329861,-3.58724281,50,-19.98809335,2.06E-11,0,0,0,-180 +53.11,50.42329681,-3.58724281,50,-20.00547429,1.02E-11,0,0,0,-180 +53.12,50.42329501,-3.58724281,50,-20.01590285,0,0,0,0,-180 +53.13,50.42329321,-3.58724281,50,-20.00547426,-1.02E-11,0,0,0,-180 +53.14,50.42329141,-3.58724281,50,-19.9880933,-2.06E-11,0,0,0,-180 +53.15,50.42328962,-3.58724281,50,-19.98809329,-2.08E-11,0,0,0,-180 +53.16,50.42328782,-3.58724281,50,-20.00547424,-1.05E-11,0,0,0,-180 +53.17,50.42328602,-3.58724281,50,-20.01590281,-2.34E-13,0,0,0,-180 +53.18,50.42328422,-3.58724281,50,-20.00547423,1.02E-11,0,0,0,-180 +53.19,50.42328242,-3.58724281,50,-19.98809327,2.06E-11,0,0,0,-180 +53.2,50.42328063,-3.58724281,50,-19.98809326,2.07E-11,0,0,0,-180 +53.21,50.42327883,-3.58724281,50,-20.00547421,1.03E-11,0,0,0,-180 +53.22,50.42327703,-3.58724281,50,-20.01590278,-1.56E-13,0,0,0,-180 +53.23,50.42327523,-3.58724281,50,-20.00547421,-1.05E-11,0,0,0,-180 +53.24,50.42327343,-3.58724281,50,-19.98809326,-2.08E-11,0,0,0,-180 +53.25,50.42327164,-3.58724281,50,-19.98809326,-2.06E-11,0,0,0,-180 +53.26,50.42326984,-3.58724281,50,-20.0054742,-1.02E-11,0,0,0,-180 +53.27,50.42326804,-3.58724281,50,-20.01590277,2.34E-13,0,0,0,-180 +53.28,50.42326624,-3.58724281,50,-20.00547419,1.05E-11,0,0,0,-180 +53.29,50.42326444,-3.58724281,50,-19.98809322,2.08E-11,0,0,0,-180 +53.3,50.42326265,-3.58724281,50,-19.9880932,2.06E-11,0,0,0,-180 +53.31,50.42326085,-3.58724281,50,-20.00547415,1.02E-11,0,0,0,-180 +53.32,50.42325905,-3.58724281,50,-20.01590271,0,0,0,0,-180 +53.33,50.42325725,-3.58724281,50,-20.00547413,-1.02E-11,0,0,0,-180 +53.34,50.42325545,-3.58724281,50,-19.98809318,-2.06E-11,0,0,0,-180 +53.35,50.42325366,-3.58724281,50,-19.98809317,-2.08E-11,0,0,0,-180 +53.36,50.42325186,-3.58724281,50,-20.00199793,-1.26E-11,0,0,0,-180 +53.37,50.42325006,-3.58724281,50,-20.00199792,-1.26E-11,0,0,0,-180 +53.38,50.42324826,-3.58724281,50,-19.98809315,-2.08E-11,0,0,0,-180 +53.39,50.42324647,-3.58724281,50,-19.98809314,-2.06E-11,0,0,0,-180 +53.4,50.42324467,-3.58724281,50,-20.00547409,-1.02E-11,0,0,0,-180 +53.41,50.42324287,-3.58724281,50,-20.01590266,0,0,0,0,-180 +53.42,50.42324107,-3.58724281,50,-20.0054741,1.02E-11,0,0,0,-180 +53.43,50.42323927,-3.58724281,50,-19.98809316,2.06E-11,0,0,0,-180 +53.44,50.42323748,-3.58724281,50,-19.98809316,2.08E-11,0,0,0,-180 +53.45,50.42323568,-3.58724281,50,-20.00547408,1.05E-11,0,0,0,-180 +53.46,50.42323388,-3.58724281,50,-20.01590263,2.34E-13,0,0,0,-180 +53.47,50.42323208,-3.58724281,50,-20.00547405,-1.02E-11,0,0,0,-180 +53.48,50.42323028,-3.58724281,50,-19.98809309,-2.06E-11,0,0,0,-180 +53.49,50.42322849,-3.58724281,50,-19.98809308,-2.08E-11,0,0,0,-180 +53.5,50.42322669,-3.58724281,50,-20.00547403,-1.05E-11,0,0,0,-180 +53.51,50.42322489,-3.58724281,50,-20.01590259,-1.41E-13,0,0,0,-180 +53.52,50.42322309,-3.58724281,50,-20.00547402,1.04E-11,0,0,0,-180 +53.53,50.42322129,-3.58724281,50,-19.98809306,2.09E-11,0,0,0,-180 +53.54,50.4232195,-3.58724281,50,-19.98809305,2.09E-11,0,0,0,-180 +53.55,50.4232177,-3.58724281,50,-20.005474,1.04E-11,0,0,0,-180 +53.56,50.4232159,-3.58724281,50,-20.01590257,-1.41E-13,0,0,0,-180 +53.57,50.4232141,-3.58724281,50,-20.005474,-1.05E-11,0,0,0,-180 +53.58,50.4232123,-3.58724281,50,-19.98809305,-2.08E-11,0,0,0,-180 +53.59,50.42321051,-3.58724281,50,-19.98809305,-2.06E-11,0,0,0,-180 +53.6,50.42320871,-3.58724281,50,-20.005474,-1.02E-11,0,0,0,-180 +53.61,50.42320691,-3.58724281,50,-20.01590256,2.34E-13,0,0,0,-180 +53.62,50.42320511,-3.58724281,50,-20.00547397,1.05E-11,0,0,0,-180 +53.63,50.42320331,-3.58724281,50,-19.988093,2.08E-11,0,0,0,-180 +53.64,50.42320152,-3.58724281,50,-19.98809299,2.06E-11,0,0,0,-180 +53.65,50.42319972,-3.58724281,50,-20.00547394,1.02E-11,0,0,0,-180 +53.66,50.42319792,-3.58724281,50,-20.0159025,0,0,0,0,-180 +53.67,50.42319612,-3.58724281,50,-20.00547392,-1.02E-11,0,0,0,-180 +53.68,50.42319432,-3.58724281,50,-19.98809296,-2.06E-11,0,0,0,-180 +53.69,50.42319253,-3.58724281,50,-19.98809296,-2.08E-11,0,0,0,-180 +53.7,50.42319073,-3.58724281,50,-20.00199771,-1.26E-11,0,0,0,-180 +53.71,50.42318893,-3.58724281,50,-20.00199771,-1.27E-11,0,0,0,-180 +53.72,50.42318713,-3.58724281,50,-19.98809295,-2.10E-11,0,0,0,-180 +53.73,50.42318534,-3.58724281,50,-19.98809296,-2.09E-11,0,0,0,-180 +53.74,50.42318354,-3.58724281,50,-20.0054739,-1.04E-11,0,0,0,-180 +53.75,50.42318174,-3.58724281,50,-20.01590246,1.41E-13,0,0,0,-180 +53.76,50.42317994,-3.58724281,50,-20.00547387,1.05E-11,0,0,0,-180 +53.77,50.42317814,-3.58724281,50,-19.98809291,2.08E-11,0,0,0,-180 +53.78,50.42317635,-3.58724281,50,-19.9880929,2.06E-11,0,0,0,-180 +53.79,50.42317455,-3.58724281,50,-20.00547386,1.02E-11,0,0,0,-180 +53.8,50.42317275,-3.58724281,50,-20.01590244,-2.34E-13,0,0,0,-180 +53.81,50.42317095,-3.58724281,50,-20.00547386,-1.05E-11,0,0,0,-180 +53.82,50.42316915,-3.58724281,50,-19.98809289,-2.08E-11,0,0,0,-180 +53.83,50.42316736,-3.58724281,50,-19.98809287,-2.06E-11,0,0,0,-180 +53.84,50.42316556,-3.58724281,50,-20.00547382,-1.02E-11,0,0,0,-180 +53.85,50.42316376,-3.58724281,50,-20.01590238,2.34E-13,0,0,0,-180 +53.86,50.42316196,-3.58724281,50,-20.00547381,1.05E-11,0,0,0,-180 +53.87,50.42316016,-3.58724281,50,-19.98809285,2.08E-11,0,0,0,-180 +53.88,50.42315837,-3.58724281,50,-19.98809285,2.06E-11,0,0,0,-180 +53.89,50.42315657,-3.58724281,50,-20.00547381,1.02E-11,0,0,0,-180 +53.9,50.42315477,-3.58724281,50,-20.01590237,0,0,0,0,-180 +53.91,50.42315297,-3.58724281,50,-20.00547379,-1.02E-11,0,0,0,-180 +53.92,50.42315117,-3.58724281,50,-19.98809282,-2.05E-11,0,0,0,-180 +53.93,50.42314938,-3.58724281,50,-19.98809281,-2.05E-11,0,0,0,-180 +53.94,50.42314758,-3.58724281,50,-20.00547376,-1.02E-11,0,0,0,-180 +53.95,50.42314578,-3.58724281,50,-20.01590232,0,0,0,0,-180 +53.96,50.42314398,-3.58724281,50,-20.00547374,1.02E-11,0,0,0,-180 +53.97,50.42314218,-3.58724281,50,-19.98809279,2.06E-11,0,0,0,-180 +53.98,50.42314039,-3.58724281,50,-19.98809279,2.08E-11,0,0,0,-180 +53.99,50.42313859,-3.58724281,50,-20.00547375,1.05E-11,0,0,0,-180 +54,50.42313679,-3.58724281,50,-20.01590231,2.34E-13,0,0,0,-180 +54.01,50.42313499,-3.58724281,50,-20.00547372,-1.02E-11,0,0,0,-180 +54.02,50.42313319,-3.58724281,50,-19.98809276,-2.06E-11,0,0,0,-180 +54.03,50.4231314,-3.58724281,50,-19.98809275,-2.08E-11,0,0,0,-180 +54.04,50.4231296,-3.58724281,50,-20.0054737,-1.05E-11,0,0,0,-180 +54.05,50.4231278,-3.58724281,50,-20.01590227,-2.34E-13,0,0,0,-180 +54.06,50.423126,-3.58724281,50,-20.0054737,1.02E-11,0,0,0,-180 +54.07,50.4231242,-3.58724281,50,-19.98809274,2.06E-11,0,0,0,-180 +54.08,50.42312241,-3.58724281,50,-19.98809273,2.08E-11,0,0,0,-180 +54.09,50.42312061,-3.58724281,50,-20.00547366,1.05E-11,0,0,0,-180 +54.1,50.42311881,-3.58724281,50,-20.01590223,2.34E-13,0,0,0,-180 +54.11,50.42311701,-3.58724281,50,-20.00547365,-1.02E-11,0,0,0,-180 +54.12,50.42311521,-3.58724281,50,-19.98809269,-2.06E-11,0,0,0,-180 +54.13,50.42311342,-3.58724281,50,-19.98809269,-2.08E-11,0,0,0,-180 +54.14,50.42311162,-3.58724281,50,-20.00199744,-1.26E-11,0,0,0,-180 +54.15,50.42310982,-3.58724281,50,-20.00199743,-1.26E-11,0,0,0,-180 +54.16,50.42310802,-3.58724281,50,-19.98809267,-2.08E-11,0,0,0,-180 +54.17,50.42310623,-3.58724281,50,-19.98809266,-2.06E-11,0,0,0,-180 +54.18,50.42310443,-3.58724281,50,-20.00547362,-1.02E-11,0,0,0,-180 +54.19,50.42310263,-3.58724281,50,-20.0159022,2.34E-13,0,0,0,-180 +54.2,50.42310083,-3.58724281,50,-20.00547363,1.05E-11,0,0,0,-180 +54.21,50.42309903,-3.58724281,50,-19.98809267,2.08E-11,0,0,0,-180 +54.22,50.42309724,-3.58724281,50,-19.98809265,2.06E-11,0,0,0,-180 +54.23,50.42309544,-3.58724281,50,-20.00547359,1.02E-11,0,0,0,-180 +54.24,50.42309364,-3.58724281,50,-20.01590214,-2.50E-13,0,0,0,-180 +54.25,50.42309184,-3.58724281,50,-20.00547356,-1.06E-11,0,0,0,-180 +54.26,50.42309004,-3.58724281,50,-19.9880926,-2.10E-11,0,0,0,-180 +54.27,50.42308825,-3.58724281,50,-19.9880926,-2.09E-11,0,0,0,-180 +54.28,50.42308645,-3.58724281,50,-20.00547354,-1.04E-11,0,0,0,-180 +54.29,50.42308465,-3.58724281,50,-20.01590211,1.56E-13,0,0,0,-180 +54.3,50.42308285,-3.58724281,50,-20.00547353,1.06E-11,0,0,0,-180 +54.31,50.42308105,-3.58724281,50,-19.98809257,2.10E-11,0,0,0,-180 +54.32,50.42307926,-3.58724281,50,-19.98809257,2.09E-11,0,0,0,-180 +54.33,50.42307746,-3.58724281,50,-20.00547351,1.04E-11,0,0,0,-180 +54.34,50.42307566,-3.58724281,50,-20.01590208,-1.56E-13,0,0,0,-180 +54.35,50.42307386,-3.58724281,50,-20.00547352,-1.06E-11,0,0,0,-180 +54.36,50.42307206,-3.58724281,50,-19.98809259,-2.10E-11,0,0,0,-180 +54.37,50.42307027,-3.58724281,50,-19.98809258,-2.09E-11,0,0,0,-180 +54.38,50.42306847,-3.58724281,50,-20.0054735,-1.04E-11,0,0,0,-180 +54.39,50.42306667,-3.58724281,50,-20.01590205,1.56E-13,0,0,0,-180 +54.4,50.42306487,-3.58724281,50,-20.00547347,1.06E-11,0,0,0,-180 +54.41,50.42306307,-3.58724281,50,-19.98809251,2.10E-11,0,0,0,-180 +54.42,50.42306128,-3.58724281,50,-19.98809251,2.10E-11,0,0,0,-180 +54.43,50.42305948,-3.58724281,50,-20.00547345,1.06E-11,0,0,0,-180 +54.44,50.42305768,-3.58724281,50,-20.01590202,1.56E-13,0,0,0,-180 +54.45,50.42305588,-3.58724281,50,-20.00547344,-1.04E-11,0,0,0,-180 +54.46,50.42305408,-3.58724281,50,-19.98809248,-2.09E-11,0,0,0,-180 +54.47,50.42305229,-3.58724281,50,-19.98809247,-2.10E-11,0,0,0,-180 +54.48,50.42305049,-3.58724281,50,-20.00199723,-1.27E-11,0,0,0,-180 +54.49,50.42304869,-3.58724281,50,-20.00199722,-1.26E-11,0,0,0,-180 +54.5,50.42304689,-3.58724281,50,-19.98809246,-2.08E-11,0,0,0,-180 +54.51,50.4230451,-3.58724281,50,-19.98809246,-2.06E-11,0,0,0,-180 +54.52,50.4230433,-3.58724281,50,-20.00547342,-1.02E-11,0,0,0,-180 +54.53,50.4230415,-3.58724281,50,-20.01590198,2.50E-13,0,0,0,-180 +54.54,50.4230397,-3.58724281,50,-20.0054734,1.06E-11,0,0,0,-180 +54.55,50.4230379,-3.58724281,50,-19.98809245,2.10E-11,0,0,0,-180 +54.56,50.42303611,-3.58724281,50,-19.98809244,2.09E-11,0,0,0,-180 +54.57,50.42303431,-3.58724281,50,-20.00547337,1.04E-11,0,0,0,-180 +54.58,50.42303251,-3.58724281,50,-20.01590193,-1.56E-13,0,0,0,-180 +54.59,50.42303071,-3.58724281,50,-20.00547335,-1.06E-11,0,0,0,-180 +54.6,50.42302891,-3.58724281,50,-19.98809239,-2.10E-11,0,0,0,-180 +54.61,50.42302712,-3.58724281,50,-19.98809239,-2.10E-11,0,0,0,-180 +54.62,50.42302532,-3.58724281,50,-20.00547333,-1.06E-11,0,0,0,-180 +54.63,50.42302352,-3.58724281,50,-20.0159019,-1.56E-13,0,0,0,-180 +54.64,50.42302172,-3.58724281,50,-20.00547332,1.04E-11,0,0,0,-180 +54.65,50.42301992,-3.58724281,50,-19.98809236,2.09E-11,0,0,0,-180 +54.66,50.42301813,-3.58724281,50,-19.98809236,2.10E-11,0,0,0,-180 +54.67,50.42301633,-3.58724281,50,-20.0054733,1.06E-11,0,0,0,-180 +54.68,50.42301453,-3.58724281,50,-20.01590188,2.50E-13,0,0,0,-180 +54.69,50.42301273,-3.58724281,50,-20.00547331,-1.02E-11,0,0,0,-180 +54.7,50.42301093,-3.58724281,50,-19.98809235,-2.06E-11,0,0,0,-180 +54.71,50.42300914,-3.58724281,50,-19.98809234,-2.08E-11,0,0,0,-180 +54.72,50.42300734,-3.58724281,50,-20.00547327,-1.05E-11,0,0,0,-180 +54.73,50.42300554,-3.58724281,50,-20.01590184,-2.34E-13,0,0,0,-180 +54.74,50.42300374,-3.58724281,50,-20.00547327,1.01E-11,0,0,0,-180 +54.75,50.42300194,-3.58724281,50,-19.98809232,2.05E-11,0,0,0,-180 +54.76,50.42300015,-3.58724281,50,-19.98809232,2.05E-11,0,0,0,-180 +54.77,50.42299835,-3.58724281,50,-20.00547325,1.01E-11,0,0,0,-180 +54.78,50.42299655,-3.58724281,50,-20.01590181,-2.34E-13,0,0,0,-180 +54.79,50.42299475,-3.58724281,50,-20.00547323,-1.05E-11,0,0,0,-180 +54.8,50.42299295,-3.58724281,50,-19.98809227,-2.08E-11,0,0,0,-180 +54.81,50.42299116,-3.58724281,50,-19.98809226,-2.06E-11,0,0,0,-180 +54.82,50.42298936,-3.58724281,50,-20.00199702,-1.22E-11,0,0,0,-180 +54.83,50.42298756,-3.58724281,50,-20.00199702,-1.22E-11,0,0,0,-180 +54.84,50.42298576,-3.58724281,50,-19.98809227,-2.05E-11,0,0,0,-180 +54.85,50.42298397,-3.58724281,50,-19.98809226,-2.05E-11,0,0,0,-180 +54.86,50.42298217,-3.58724281,50,-20.00547319,-1.02E-11,0,0,0,-180 +54.87,50.42298037,-3.58724281,50,-20.01590175,-1.73E-17,0,0,0,-180 +54.88,50.42297857,-3.58724281,50,-20.00547317,1.02E-11,0,0,0,-180 +54.89,50.42297677,-3.58724281,50,-19.98809221,2.05E-11,0,0,0,-180 +54.9,50.42297498,-3.58724281,50,-19.98809221,2.05E-11,0,0,0,-180 +54.91,50.42297318,-3.58724281,50,-20.00547315,1.01E-11,0,0,0,-180 +54.92,50.42297138,-3.58724281,50,-20.01590172,-2.50E-13,0,0,0,-180 +54.93,50.42296958,-3.58724281,50,-20.00547315,-1.06E-11,0,0,0,-180 +54.94,50.42296778,-3.58724281,50,-19.9880922,-2.10E-11,0,0,0,-180 +54.95,50.42296599,-3.58724281,50,-19.9880922,-2.09E-11,0,0,0,-180 +54.96,50.42296419,-3.58724281,50,-20.00547313,-1.04E-11,0,0,0,-180 +54.97,50.42296239,-3.58724281,50,-20.01590169,1.56E-13,0,0,0,-180 +54.98,50.42296059,-3.58724281,50,-20.00547312,1.06E-11,0,0,0,-180 +54.99,50.42295879,-3.58724281,50,-19.98809217,2.10E-11,0,0,0,-180 +55,50.422957,-3.58724281,50,-19.98809217,2.10E-11,0,0,0,-180 +55.01,50.4229552,-3.58724281,50,-20.0054731,1.06E-11,0,0,0,-180 +55.02,50.4229534,-3.58724281,50,-20.01590166,2.50E-13,0,0,0,-180 +55.03,50.4229516,-3.58724281,50,-20.00547308,-1.01E-11,0,0,0,-180 +55.04,50.4229498,-3.58724281,50,-19.98809212,-2.05E-11,0,0,0,-180 +55.05,50.42294801,-3.58724281,50,-19.98809211,-2.05E-11,0,0,0,-180 +55.06,50.42294621,-3.58724281,50,-20.00547306,-1.01E-11,0,0,0,-180 +55.07,50.42294441,-3.58724281,50,-20.01590162,2.34E-13,0,0,0,-180 +55.08,50.42294261,-3.58724281,50,-20.00547305,1.05E-11,0,0,0,-180 +55.09,50.42294081,-3.58724281,50,-19.98809209,2.08E-11,0,0,0,-180 +55.1,50.42293902,-3.58724281,50,-19.98809208,2.06E-11,0,0,0,-180 +55.11,50.42293722,-3.58724281,50,-20.00547303,1.02E-11,0,0,0,-180 +55.12,50.42293542,-3.58724281,50,-20.0159016,-2.50E-13,0,0,0,-180 +55.13,50.42293362,-3.58724281,50,-20.00547303,-1.06E-11,0,0,0,-180 +55.14,50.42293182,-3.58724281,50,-19.98809209,-2.10E-11,0,0,0,-180 +55.15,50.42293003,-3.58724281,50,-19.9880921,-2.10E-11,0,0,0,-180 +55.16,50.42292823,-3.58724281,50,-20.00199684,-1.27E-11,0,0,0,-180 +55.17,50.42292643,-3.58724281,50,-20.00199681,-1.26E-11,0,0,0,-180 +55.18,50.42292463,-3.58724281,50,-19.98809204,-2.08E-11,0,0,0,-180 +55.19,50.42292284,-3.58724281,50,-19.98809203,-2.06E-11,0,0,0,-180 +55.2,50.42292104,-3.58724281,50,-20.00547297,-1.02E-11,0,0,0,-180 +55.21,50.42291924,-3.58724281,50,-20.01590154,2.50E-13,0,0,0,-180 +55.22,50.42291744,-3.58724281,50,-20.00547296,1.06E-11,0,0,0,-180 +55.23,50.42291564,-3.58724281,50,-19.988092,2.10E-11,0,0,0,-180 +55.24,50.42291385,-3.58724281,50,-19.988092,2.10E-11,0,0,0,-180 +55.25,50.42291205,-3.58724281,50,-20.00547294,1.06E-11,0,0,0,-180 +55.26,50.42291025,-3.58724281,50,-20.01590151,2.50E-13,0,0,0,-180 +55.27,50.42290845,-3.58724281,50,-20.00547293,-1.01E-11,0,0,0,-180 +55.28,50.42290665,-3.58724281,50,-19.98809197,-2.05E-11,0,0,0,-180 +55.29,50.42290486,-3.58724281,50,-19.98809197,-2.05E-11,0,0,0,-180 +55.3,50.42290306,-3.58724281,50,-20.00547293,-1.01E-11,0,0,0,-180 +55.31,50.42290126,-3.58724281,50,-20.01590152,2.34E-13,0,0,0,-180 +55.32,50.42289946,-3.58724281,50,-20.00547294,1.05E-11,0,0,0,-180 +55.33,50.42289766,-3.58724281,50,-19.98809196,2.08E-11,0,0,0,-180 +55.34,50.42289587,-3.58724281,50,-19.98809194,2.06E-11,0,0,0,-180 +55.35,50.42289407,-3.58724281,50,-20.00547288,1.02E-11,0,0,0,-180 +55.36,50.42289227,-3.58724281,50,-20.01590144,-2.50E-13,0,0,0,-180 +55.37,50.42289047,-3.58724281,50,-20.00547287,-1.06E-11,0,0,0,-180 +55.38,50.42288867,-3.58724281,50,-19.98809191,-2.10E-11,0,0,0,-180 +55.39,50.42288688,-3.58724281,50,-19.9880919,-2.10E-11,0,0,0,-180 +55.4,50.42288508,-3.58724281,50,-20.00547285,-1.06E-11,0,0,0,-180 +55.41,50.42288328,-3.58724281,50,-20.01590141,-2.50E-13,0,0,0,-180 +55.42,50.42288148,-3.58724281,50,-20.00547284,1.01E-11,0,0,0,-180 +55.43,50.42287968,-3.58724281,50,-19.98809188,2.05E-11,0,0,0,-180 +55.44,50.42287789,-3.58724281,50,-19.98809187,2.05E-11,0,0,0,-180 +55.45,50.42287609,-3.58724281,50,-20.00547282,1.01E-11,0,0,0,-180 +55.46,50.42287429,-3.58724281,50,-20.01590138,-2.50E-13,0,0,0,-180 +55.47,50.42287249,-3.58724281,50,-20.00547282,-1.06E-11,0,0,0,-180 +55.48,50.42287069,-3.58724281,50,-19.98809187,-2.10E-11,0,0,0,-180 +55.49,50.4228689,-3.58724281,50,-19.98809187,-2.10E-11,0,0,0,-180 +55.5,50.4228671,-3.58724281,50,-20.00547282,-1.06E-11,0,0,0,-180 +55.51,50.4228653,-3.58724281,50,-20.01590137,-2.50E-13,0,0,0,-180 +55.52,50.4228635,-3.58724281,50,-20.00547278,1.01E-11,0,0,0,-180 +55.53,50.4228617,-3.58724281,50,-19.98809182,2.05E-11,0,0,0,-180 +55.54,50.42285991,-3.58724281,50,-19.98809181,2.05E-11,0,0,0,-180 +55.55,50.42285811,-3.58724281,50,-20.00547275,1.01E-11,0,0,0,-180 +55.56,50.42285631,-3.58724281,50,-20.01590132,-2.50E-13,0,0,0,-180 +55.57,50.42285451,-3.58724281,50,-20.00547274,-1.06E-11,0,0,0,-180 +55.58,50.42285271,-3.58724281,50,-19.98809178,-2.10E-11,0,0,0,-180 +55.59,50.42285092,-3.58724281,50,-19.98809178,-2.10E-11,0,0,0,-180 +55.6,50.42284912,-3.58724281,50,-20.00199654,-1.27E-11,0,0,0,-180 +55.61,50.42284732,-3.58724281,50,-20.00199654,-1.26E-11,0,0,0,-180 +55.62,50.42284552,-3.58724281,50,-19.98809178,-2.08E-11,0,0,0,-180 +55.63,50.42284373,-3.58724281,50,-19.98809178,-2.06E-11,0,0,0,-180 +55.64,50.42284193,-3.58724281,50,-20.00547271,-1.02E-11,0,0,0,-180 +55.65,50.42284013,-3.58724281,50,-20.01590127,1.56E-13,0,0,0,-180 +55.66,50.42283833,-3.58724281,50,-20.00547269,1.04E-11,0,0,0,-180 +55.67,50.42283653,-3.58724281,50,-19.98809173,2.07E-11,0,0,0,-180 +55.68,50.42283474,-3.58724281,50,-19.98809172,2.08E-11,0,0,0,-180 +55.69,50.42283294,-3.58724281,50,-20.00547268,1.05E-11,0,0,0,-180 +55.7,50.42283114,-3.58724281,50,-20.01590125,2.34E-13,0,0,0,-180 +55.71,50.42282934,-3.58724281,50,-20.00547268,-1.01E-11,0,0,0,-180 +55.72,50.42282754,-3.58724281,50,-19.98809171,-2.05E-11,0,0,0,-180 +55.73,50.42282575,-3.58724281,50,-19.98809169,-2.05E-11,0,0,0,-180 +55.74,50.42282395,-3.58724281,50,-20.00547264,-1.01E-11,0,0,0,-180 +55.75,50.42282215,-3.58724281,50,-20.0159012,2.50E-13,0,0,0,-180 +55.76,50.42282035,-3.58724281,50,-20.00547263,1.06E-11,0,0,0,-180 +55.77,50.42281855,-3.58724281,50,-19.98809168,2.10E-11,0,0,0,-180 +55.78,50.42281676,-3.58724281,50,-19.98809168,2.10E-11,0,0,0,-180 +55.79,50.42281496,-3.58724281,50,-20.00547263,1.06E-11,0,0,0,-180 +55.8,50.42281316,-3.58724281,50,-20.01590118,2.50E-13,0,0,0,-180 +55.81,50.42281136,-3.58724281,50,-20.0054726,-1.01E-11,0,0,0,-180 +55.82,50.42280956,-3.58724281,50,-19.98809164,-2.05E-11,0,0,0,-180 +55.83,50.42280777,-3.58724281,50,-19.98809163,-2.05E-11,0,0,0,-180 +55.84,50.42280597,-3.58724281,50,-20.00547257,-1.02E-11,0,0,0,-180 +55.85,50.42280417,-3.58724281,50,-20.01590114,1.56E-13,0,0,0,-180 +55.86,50.42280237,-3.58724281,50,-20.00547256,1.04E-11,0,0,0,-180 +55.87,50.42280057,-3.58724281,50,-19.98809161,2.07E-11,0,0,0,-180 +55.88,50.42279878,-3.58724281,50,-19.98809161,2.08E-11,0,0,0,-180 +55.89,50.42279698,-3.58724281,50,-20.00547257,1.05E-11,0,0,0,-180 +55.9,50.42279518,-3.58724281,50,-20.01590113,1.73E-18,0,0,0,-180 +55.91,50.42279338,-3.58724281,50,-20.00547254,-1.05E-11,0,0,0,-180 +55.92,50.42279158,-3.58724281,50,-19.98809158,-2.08E-11,0,0,0,-180 +55.93,50.42278979,-3.58724281,50,-19.98809158,-2.07E-11,0,0,0,-180 +55.94,50.42278799,-3.58724281,50,-20.00547253,-1.04E-11,0,0,0,-180 +55.95,50.42278619,-3.58724281,50,-20.0159011,-1.56E-13,0,0,0,-180 +55.96,50.42278439,-3.58724281,50,-20.00547251,1.02E-11,0,0,0,-180 +55.97,50.42278259,-3.58724281,50,-19.98809154,2.05E-11,0,0,0,-180 +55.98,50.4227808,-3.58724281,50,-19.98809154,2.05E-11,0,0,0,-180 +55.99,50.422779,-3.58724281,50,-20.00199629,1.22E-11,0,0,0,-180 +56,50.4227772,-3.58724281,50,-20.00199628,1.22E-11,0,0,0,-180 +56.01,50.4227754,-3.58724281,50,-19.98809152,2.05E-11,0,0,0,-180 +56.02,50.42277361,-3.58724281,50,-19.98809151,2.05E-11,0,0,0,-180 +56.03,50.42277181,-3.58724281,50,-20.00547246,1.01E-11,0,0,0,-180 +56.04,50.42277001,-3.58724281,50,-20.01590102,-2.50E-13,0,0,0,-180 +56.05,50.42276821,-3.58724281,50,-20.00547244,-1.06E-11,0,0,0,-180 +56.06,50.42276641,-3.58724281,50,-19.98809149,-2.10E-11,0,0,0,-180 +56.07,50.42276462,-3.58724281,50,-19.98809148,-2.10E-11,0,0,0,-180 +56.08,50.42276282,-3.58724281,50,-20.00547244,-1.06E-11,0,0,0,-180 +56.09,50.42276102,-3.58724281,50,-20.01590101,-2.50E-13,0,0,0,-180 +56.1,50.42275922,-3.58724281,50,-20.00547245,1.01E-11,0,0,0,-180 +56.11,50.42275742,-3.58724281,50,-19.98809149,2.05E-11,0,0,0,-180 +56.12,50.42275563,-3.58724281,50,-19.98809147,2.05E-11,0,0,0,-180 +56.13,50.42275383,-3.58724281,50,-20.00547241,1.01E-11,0,0,0,-180 +56.14,50.42275203,-3.58724281,50,-20.01590096,-2.50E-13,0,0,0,-180 +56.15,50.42275023,-3.58724281,50,-20.00547238,-1.06E-11,0,0,0,-180 +56.16,50.42274843,-3.58724281,50,-19.98809142,-2.10E-11,0,0,0,-180 +56.17,50.42274664,-3.58724281,50,-19.98809142,-2.10E-11,0,0,0,-180 +56.18,50.42274484,-3.58724281,50,-20.00547236,-1.05E-11,0,0,0,-180 +56.19,50.42274304,-3.58724281,50,-20.01590093,-1.73E-17,0,0,0,-180 +56.2,50.42274124,-3.58724281,50,-20.00547235,1.05E-11,0,0,0,-180 +56.21,50.42273944,-3.58724281,50,-19.98809139,2.10E-11,0,0,0,-180 +56.22,50.42273765,-3.58724281,50,-19.98809139,2.10E-11,0,0,0,-180 +56.23,50.42273585,-3.58724281,50,-20.00547233,1.06E-11,0,0,0,-180 +56.24,50.42273405,-3.58724281,50,-20.0159009,2.50E-13,0,0,0,-180 +56.25,50.42273225,-3.58724281,50,-20.00547234,-1.01E-11,0,0,0,-180 +56.26,50.42273045,-3.58724281,50,-19.98809141,-2.05E-11,0,0,0,-180 +56.27,50.42272866,-3.58724281,50,-19.9880914,-2.05E-11,0,0,0,-180 +56.28,50.42272686,-3.58724281,50,-20.00547232,-1.01E-11,0,0,0,-180 +56.29,50.42272506,-3.58724281,50,-20.01590087,2.50E-13,0,0,0,-180 +56.3,50.42272326,-3.58724281,50,-20.00547229,1.06E-11,0,0,0,-180 +56.31,50.42272146,-3.58724281,50,-19.98809133,2.10E-11,0,0,0,-180 +56.32,50.42271967,-3.58724281,50,-19.98809133,2.10E-11,0,0,0,-180 +56.33,50.42271787,-3.58724281,50,-20.00199608,1.26E-11,0,0,0,-180 +56.34,50.42271607,-3.58724281,50,-20.00199607,1.25E-11,0,0,0,-180 +56.35,50.42271427,-3.58724281,50,-19.98809131,2.07E-11,0,0,0,-180 +56.36,50.42271248,-3.58724281,50,-19.9880913,2.08E-11,0,0,0,-180 +56.37,50.42271068,-3.58724281,50,-20.00547224,1.05E-11,0,0,0,-180 +56.38,50.42270888,-3.58724281,50,-20.01590081,-1.56E-14,0,0,0,-180 +56.39,50.42270708,-3.58724281,50,-20.00547223,-1.05E-11,0,0,0,-180 +56.4,50.42270528,-3.58724281,50,-19.98809129,-2.10E-11,0,0,0,-180 +56.41,50.42270349,-3.58724281,50,-19.98809129,-2.10E-11,0,0,0,-180 +56.42,50.42270169,-3.58724281,50,-20.00547224,-1.06E-11,0,0,0,-180 +56.43,50.42269989,-3.58724281,50,-20.01590079,-2.50E-13,0,0,0,-180 +56.44,50.42269809,-3.58724281,50,-20.00547221,1.01E-11,0,0,0,-180 +56.45,50.42269629,-3.58724281,50,-19.98809127,2.05E-11,0,0,0,-180 +56.46,50.4226945,-3.58724281,50,-19.98809126,2.05E-11,0,0,0,-180 +56.47,50.4226927,-3.58724281,50,-20.00547219,1.02E-11,0,0,0,-180 +56.48,50.4226909,-3.58724281,50,-20.01590075,-1.56E-13,0,0,0,-180 +56.49,50.4226891,-3.58724281,50,-20.00547217,-1.04E-11,0,0,0,-180 +56.5,50.4226873,-3.58724281,50,-19.98809121,-2.06E-11,0,0,0,-180 +56.51,50.42268551,-3.58724281,50,-19.98809121,-2.05E-11,0,0,0,-180 +56.52,50.42268371,-3.58724281,50,-20.00547215,-1.01E-11,0,0,0,-180 +56.53,50.42268191,-3.58724281,50,-20.01590072,2.50E-13,0,0,0,-180 +56.54,50.42268011,-3.58724281,50,-20.00547214,1.06E-11,0,0,0,-180 +56.55,50.42267831,-3.58724281,50,-19.98809118,2.10E-11,0,0,0,-180 +56.56,50.42267652,-3.58724281,50,-19.98809119,2.10E-11,0,0,0,-180 +56.57,50.42267472,-3.58724281,50,-20.00547214,1.05E-11,0,0,0,-180 +56.58,50.42267292,-3.58724281,50,-20.01590071,1.73E-18,0,0,0,-180 +56.59,50.42267112,-3.58724281,50,-20.00547212,-1.05E-11,0,0,0,-180 +56.6,50.42266932,-3.58724281,50,-19.98809115,-2.10E-11,0,0,0,-180 +56.61,50.42266753,-3.58724281,50,-19.98809115,-2.10E-11,0,0,0,-180 +56.62,50.42266573,-3.58724281,50,-20.00547209,-1.06E-11,0,0,0,-180 +56.63,50.42266393,-3.58724281,50,-20.01590066,-2.50E-13,0,0,0,-180 +56.64,50.42266213,-3.58724281,50,-20.00547209,1.01E-11,0,0,0,-180 +56.65,50.42266033,-3.58724281,50,-19.98809114,2.05E-11,0,0,0,-180 +56.66,50.42265854,-3.58724281,50,-19.98809114,2.06E-11,0,0,0,-180 +56.67,50.42265674,-3.58724281,50,-20.00547207,1.04E-11,0,0,0,-180 +56.68,50.42265494,-3.58724281,50,-20.01590062,1.56E-13,0,0,0,-180 +56.69,50.42265314,-3.58724281,50,-20.00547205,-1.02E-11,0,0,0,-180 +56.7,50.42265134,-3.58724281,50,-19.98809109,-2.05E-11,0,0,0,-180 +56.71,50.42264955,-3.58724281,50,-19.98809108,-2.05E-11,0,0,0,-180 +56.72,50.42264775,-3.58724281,50,-20.00547203,-1.01E-11,0,0,0,-180 +56.73,50.42264595,-3.58724281,50,-20.0159006,2.50E-13,0,0,0,-180 +56.74,50.42264415,-3.58724281,50,-20.00547204,1.06E-11,0,0,0,-180 +56.75,50.42264235,-3.58724281,50,-19.98809108,2.09E-11,0,0,0,-180 +56.76,50.42264056,-3.58724281,50,-19.98809106,2.08E-11,0,0,0,-180 +56.77,50.42263876,-3.58724281,50,-20.00199581,1.23E-11,0,0,0,-180 +56.78,50.42263696,-3.58724281,50,-20.0019958,1.22E-11,0,0,0,-180 +56.79,50.42263516,-3.58724281,50,-19.98809103,2.05E-11,0,0,0,-180 +56.8,50.42263337,-3.58724281,50,-19.98809103,2.05E-11,0,0,0,-180 +56.81,50.42263157,-3.58724281,50,-20.00547197,1.02E-11,0,0,0,-180 +56.82,50.42262977,-3.58724281,50,-20.01590054,-1.56E-13,0,0,0,-180 +56.83,50.42262797,-3.58724281,50,-20.00547197,-1.04E-11,0,0,0,-180 +56.84,50.42262617,-3.58724281,50,-19.98809102,-2.06E-11,0,0,0,-180 +56.85,50.42262438,-3.58724281,50,-19.98809102,-2.05E-11,0,0,0,-180 +56.86,50.42262258,-3.58724281,50,-20.00547195,-1.01E-11,0,0,0,-180 +56.87,50.42262078,-3.58724281,50,-20.01590051,2.50E-13,0,0,0,-180 +56.88,50.42261898,-3.58724281,50,-20.00547194,1.06E-11,0,0,0,-180 +56.89,50.42261718,-3.58724281,50,-19.98809099,2.10E-11,0,0,0,-180 +56.9,50.42261539,-3.58724281,50,-19.98809099,2.10E-11,0,0,0,-180 +56.91,50.42261359,-3.58724281,50,-20.00547192,1.05E-11,0,0,0,-180 +56.92,50.42261179,-3.58724281,50,-20.01590048,0,0,0,0,-180 +56.93,50.42260999,-3.58724281,50,-20.0054719,-1.05E-11,0,0,0,-180 +56.94,50.42260819,-3.58724281,50,-19.98809094,-2.10E-11,0,0,0,-180 +56.95,50.4226064,-3.58724281,50,-19.98809093,-2.10E-11,0,0,0,-180 +56.96,50.4226046,-3.58724281,50,-20.00547188,-1.05E-11,0,0,0,-180 +56.97,50.4226028,-3.58724281,50,-20.01590044,1.73E-18,0,0,0,-180 +56.98,50.422601,-3.58724281,50,-20.00547187,1.05E-11,0,0,0,-180 +56.99,50.4225992,-3.58724281,50,-19.98809091,2.10E-11,0,0,0,-180 +57,50.42259741,-3.58724281,50,-19.9880909,2.10E-11,0,0,0,-180 +57.01,50.42259561,-3.58724281,50,-20.00547185,1.06E-11,0,0,0,-180 +57.02,50.42259381,-3.58724281,50,-20.01590042,2.50E-13,0,0,0,-180 +57.03,50.42259201,-3.58724281,50,-20.00547186,-1.01E-11,0,0,0,-180 +57.04,50.42259021,-3.58724281,50,-19.98809092,-2.05E-11,0,0,0,-180 +57.05,50.42258842,-3.58724281,50,-19.98809092,-2.06E-11,0,0,0,-180 +57.06,50.42258662,-3.58724281,50,-20.00547184,-1.04E-11,0,0,0,-180 +57.07,50.42258482,-3.58724281,50,-20.01590038,-1.56E-13,0,0,0,-180 +57.08,50.42258302,-3.58724281,50,-20.0054718,1.02E-11,0,0,0,-180 +57.09,50.42258122,-3.58724281,50,-19.98809085,2.05E-11,0,0,0,-180 +57.1,50.42257943,-3.58724281,50,-19.98809084,2.06E-11,0,0,0,-180 +57.11,50.42257763,-3.58724281,50,-20.00199559,1.25E-11,0,0,0,-180 +57.12,50.42257583,-3.58724281,50,-20.00199559,1.26E-11,0,0,0,-180 +57.13,50.42257403,-3.58724281,50,-19.98809082,2.10E-11,0,0,0,-180 +57.14,50.42257224,-3.58724281,50,-19.98809082,2.10E-11,0,0,0,-180 +57.15,50.42257044,-3.58724281,50,-20.00547176,1.05E-11,0,0,0,-180 +57.16,50.42256864,-3.58724281,50,-20.01590032,0,0,0,0,-180 +57.17,50.42256684,-3.58724281,50,-20.00547175,-1.05E-11,0,0,0,-180 +57.18,50.42256504,-3.58724281,50,-19.98809079,-2.10E-11,0,0,0,-180 +57.19,50.42256325,-3.58724281,50,-19.9880908,-2.10E-11,0,0,0,-180 +57.2,50.42256145,-3.58724281,50,-20.00547176,-1.06E-11,0,0,0,-180 +57.21,50.42255965,-3.58724281,50,-20.01590034,-2.34E-13,0,0,0,-180 +57.22,50.42255785,-3.58724281,50,-20.00547175,1.02E-11,0,0,0,-180 +57.23,50.42255605,-3.58724281,50,-19.98809077,2.08E-11,0,0,0,-180 +57.24,50.42255426,-3.58724281,50,-19.98809076,2.09E-11,0,0,0,-180 +57.25,50.42255246,-3.58724281,50,-20.0054717,1.06E-11,0,0,0,-180 +57.26,50.42255066,-3.58724281,50,-20.01590026,2.34E-13,0,0,0,-180 +57.27,50.42254886,-3.58724281,50,-20.00547169,-1.02E-11,0,0,0,-180 +57.28,50.42254706,-3.58724281,50,-19.98809073,-2.08E-11,0,0,0,-180 +57.29,50.42254527,-3.58724281,50,-19.98809072,-2.09E-11,0,0,0,-180 +57.3,50.42254347,-3.58724281,50,-20.00547167,-1.06E-11,0,0,0,-180 +57.31,50.42254167,-3.58724281,50,-20.01590023,-2.34E-13,0,0,0,-180 +57.32,50.42253987,-3.58724281,50,-20.00547165,1.02E-11,0,0,0,-180 +57.33,50.42253807,-3.58724281,50,-19.9880907,2.08E-11,0,0,0,-180 +57.34,50.42253628,-3.58724281,50,-19.98809069,2.09E-11,0,0,0,-180 +57.35,50.42253448,-3.58724281,50,-20.00547165,1.06E-11,0,0,0,-180 +57.36,50.42253268,-3.58724281,50,-20.01590022,2.34E-13,0,0,0,-180 +57.37,50.42253088,-3.58724281,50,-20.00547165,-1.02E-11,0,0,0,-180 +57.38,50.42252908,-3.58724281,50,-19.98809068,-2.08E-11,0,0,0,-180 +57.39,50.42252729,-3.58724281,50,-19.98809067,-2.09E-11,0,0,0,-180 +57.4,50.42252549,-3.58724281,50,-20.00547163,-1.06E-11,0,0,0,-180 +57.41,50.42252369,-3.58724281,50,-20.01590019,-2.34E-13,0,0,0,-180 +57.42,50.42252189,-3.58724281,50,-20.0054716,1.02E-11,0,0,0,-180 +57.43,50.42252009,-3.58724281,50,-19.98809064,2.08E-11,0,0,0,-180 +57.44,50.4225183,-3.58724281,50,-19.98809063,2.09E-11,0,0,0,-180 +57.45,50.4225165,-3.58724281,50,-20.00199538,1.27E-11,0,0,0,-180 +57.46,50.4225147,-3.58724281,50,-20.00199538,1.27E-11,0,0,0,-180 +57.47,50.4225129,-3.58724281,50,-19.98809061,2.09E-11,0,0,0,-180 +57.48,50.42251111,-3.58724281,50,-19.9880906,2.08E-11,0,0,0,-180 +57.49,50.42250931,-3.58724281,50,-20.00547155,1.02E-11,0,0,0,-180 +57.5,50.42250751,-3.58724281,50,-20.01590011,-2.34E-13,0,0,0,-180 +57.51,50.42250571,-3.58724281,50,-20.00547155,-1.06E-11,0,0,0,-180 +57.52,50.42250391,-3.58724281,50,-19.9880906,-2.09E-11,0,0,0,-180 +57.53,50.42250212,-3.58724281,50,-19.9880906,-2.08E-11,0,0,0,-180 +57.54,50.42250032,-3.58724281,50,-20.00547153,-1.03E-11,0,0,0,-180 +57.55,50.42249852,-3.58724281,50,-20.01590008,1.41E-13,0,0,0,-180 +57.56,50.42249672,-3.58724281,50,-20.00547151,1.04E-11,0,0,0,-180 +57.57,50.42249492,-3.58724281,50,-19.98809055,2.06E-11,0,0,0,-180 +57.58,50.42249313,-3.58724281,50,-19.98809054,2.05E-11,0,0,0,-180 +57.59,50.42249133,-3.58724281,50,-20.0054715,1.02E-11,0,0,0,-180 +57.6,50.42248953,-3.58724281,50,-20.01590007,-1.56E-13,0,0,0,-180 +57.61,50.42248773,-3.58724281,50,-20.0054715,-1.04E-11,0,0,0,-180 +57.62,50.42248593,-3.58724281,50,-19.98809053,-2.06E-11,0,0,0,-180 +57.63,50.42248414,-3.58724281,50,-19.98809051,-2.05E-11,0,0,0,-180 +57.64,50.42248234,-3.58724281,50,-20.00547146,-1.02E-11,0,0,0,-180 +57.65,50.42248054,-3.58724281,50,-20.01590002,1.56E-13,0,0,0,-180 +57.66,50.42247874,-3.58724281,50,-20.00547145,1.04E-11,0,0,0,-180 +57.67,50.42247694,-3.58724281,50,-19.98809051,2.06E-11,0,0,0,-180 +57.68,50.42247515,-3.58724281,50,-19.9880905,2.06E-11,0,0,0,-180 +57.69,50.42247335,-3.58724281,50,-20.00547144,1.04E-11,0,0,0,-180 +57.7,50.42247155,-3.58724281,50,-20.01589999,1.56E-13,0,0,0,-180 +57.71,50.42246975,-3.58724281,50,-20.00547141,-1.02E-11,0,0,0,-180 +57.72,50.42246795,-3.58724281,50,-19.98809046,-2.05E-11,0,0,0,-180 +57.73,50.42246616,-3.58724281,50,-19.98809045,-2.06E-11,0,0,0,-180 +57.74,50.42246436,-3.58724281,50,-20.00547139,-1.04E-11,0,0,0,-180 +57.75,50.42246256,-3.58724281,50,-20.01589996,-1.56E-13,0,0,0,-180 +57.76,50.42246076,-3.58724281,50,-20.00547138,1.02E-11,0,0,0,-180 +57.77,50.42245896,-3.58724281,50,-19.98809043,2.05E-11,0,0,0,-180 +57.78,50.42245717,-3.58724281,50,-19.98809043,2.06E-11,0,0,0,-180 +57.79,50.42245537,-3.58724281,50,-20.00199519,1.25E-11,0,0,0,-180 +57.8,50.42245357,-3.58724281,50,-20.00199519,1.26E-11,0,0,0,-180 +57.81,50.42245177,-3.58724281,50,-19.98809041,2.09E-11,0,0,0,-180 +57.82,50.42244998,-3.58724281,50,-19.98809041,2.08E-11,0,0,0,-180 +57.83,50.42244818,-3.58724281,50,-20.00547136,1.02E-11,0,0,0,-180 +57.84,50.42244638,-3.58724281,50,-20.01589992,-1.41E-13,0,0,0,-180 +57.85,50.42244458,-3.58724281,50,-20.00547134,-1.04E-11,0,0,0,-180 +57.86,50.42244278,-3.58724281,50,-19.98809037,-2.06E-11,0,0,0,-180 +57.87,50.42244099,-3.58724281,50,-19.98809036,-2.05E-11,0,0,0,-180 +57.88,50.42243919,-3.58724281,50,-20.00547131,-1.02E-11,0,0,0,-180 +57.89,50.42243739,-3.58724281,50,-20.01589987,1.56E-13,0,0,0,-180 +57.9,50.42243559,-3.58724281,50,-20.00547129,1.04E-11,0,0,0,-180 +57.91,50.42243379,-3.58724281,50,-19.98809034,2.06E-11,0,0,0,-180 +57.92,50.422432,-3.58724281,50,-19.98809033,2.06E-11,0,0,0,-180 +57.93,50.4224302,-3.58724281,50,-20.00547128,1.04E-11,0,0,0,-180 +57.94,50.4224284,-3.58724281,50,-20.01589984,1.56E-13,0,0,0,-180 +57.95,50.4224266,-3.58724281,50,-20.00547126,-1.02E-11,0,0,0,-180 +57.96,50.4224248,-3.58724281,50,-19.98809031,-2.05E-11,0,0,0,-180 +57.97,50.42242301,-3.58724281,50,-19.9880903,-2.06E-11,0,0,0,-180 +57.98,50.42242121,-3.58724281,50,-20.00547127,-1.04E-11,0,0,0,-180 +57.99,50.42241941,-3.58724281,50,-20.01589985,-1.41E-13,0,0,0,-180 +58,50.42241761,-3.58724281,50,-20.00547128,1.02E-11,0,0,0,-180 +58.01,50.42241581,-3.58724281,50,-19.9880903,2.08E-11,0,0,0,-180 +58.02,50.42241402,-3.58724281,50,-19.98809027,2.09E-11,0,0,0,-180 +58.03,50.42241222,-3.58724281,50,-20.00547121,1.05E-11,0,0,0,-180 +58.04,50.42241042,-3.58724281,50,-20.01589978,-1.73E-18,0,0,0,-180 +58.05,50.42240862,-3.58724281,50,-20.0054712,-1.05E-11,0,0,0,-180 +58.06,50.42240682,-3.58724281,50,-19.98809024,-2.09E-11,0,0,0,-180 +58.07,50.42240503,-3.58724281,50,-19.98809024,-2.08E-11,0,0,0,-180 +58.08,50.42240323,-3.58724281,50,-20.00547118,-1.03E-11,0,0,0,-180 +58.09,50.42240143,-3.58724281,50,-20.01589975,1.41E-13,0,0,0,-180 +58.1,50.42239963,-3.58724281,50,-20.00547117,1.04E-11,0,0,0,-180 +58.11,50.42239783,-3.58724281,50,-19.98809021,2.06E-11,0,0,0,-180 +58.12,50.42239604,-3.58724281,50,-19.98809021,2.05E-11,0,0,0,-180 +58.13,50.42239424,-3.58724281,50,-20.00547115,1.02E-11,0,0,0,-180 +58.14,50.42239244,-3.58724281,50,-20.01589972,-1.56E-13,0,0,0,-180 +58.15,50.42239064,-3.58724281,50,-20.00547116,-1.04E-11,0,0,0,-180 +58.16,50.42238884,-3.58724281,50,-19.98809023,-2.06E-11,0,0,0,-180 +58.17,50.42238705,-3.58724281,50,-19.98809022,-2.06E-11,0,0,0,-180 +58.18,50.42238525,-3.58724281,50,-20.00547114,-1.04E-11,0,0,0,-180 +58.19,50.42238345,-3.58724281,50,-20.01589969,-1.41E-13,0,0,0,-180 +58.2,50.42238165,-3.58724281,50,-20.00547111,1.03E-11,0,0,0,-180 +58.21,50.42237985,-3.58724281,50,-19.98809015,2.08E-11,0,0,0,-180 +58.22,50.42237806,-3.58724281,50,-19.98809015,2.09E-11,0,0,0,-180 +58.23,50.42237626,-3.58724281,50,-20.0019949,1.26E-11,0,0,0,-180 +58.24,50.42237446,-3.58724281,50,-20.00199489,1.25E-11,0,0,0,-180 +58.25,50.42237266,-3.58724281,50,-19.98809013,2.06E-11,0,0,0,-180 +58.26,50.42237087,-3.58724281,50,-19.98809012,2.06E-11,0,0,0,-180 +58.27,50.42236907,-3.58724281,50,-20.00547106,1.04E-11,0,0,0,-180 +58.28,50.42236727,-3.58724281,50,-20.01589963,1.56E-13,0,0,0,-180 +58.29,50.42236547,-3.58724281,50,-20.00547106,-1.02E-11,0,0,0,-180 +58.3,50.42236367,-3.58724281,50,-19.98809012,-2.05E-11,0,0,0,-180 +58.31,50.42236188,-3.58724281,50,-19.98809011,-2.06E-11,0,0,0,-180 +58.32,50.42236008,-3.58724281,50,-20.00547104,-1.03E-11,0,0,0,-180 +58.33,50.42235828,-3.58724281,50,-20.0158996,9.37E-14,0,0,0,-180 +58.34,50.42235648,-3.58724281,50,-20.00547103,1.06E-11,0,0,0,-180 +58.35,50.42235468,-3.58724281,50,-19.98809009,2.10E-11,0,0,0,-180 +58.36,50.42235289,-3.58724281,50,-19.98809008,2.10E-11,0,0,0,-180 +58.37,50.42235109,-3.58724281,50,-20.00547101,1.06E-11,0,0,0,-180 +58.38,50.42234929,-3.58724281,50,-20.01589957,9.37E-14,0,0,0,-180 +58.39,50.42234749,-3.58724281,50,-20.00547099,-1.03E-11,0,0,0,-180 +58.4,50.42234569,-3.58724281,50,-19.98809003,-2.06E-11,0,0,0,-180 +58.41,50.4223439,-3.58724281,50,-19.98809003,-2.05E-11,0,0,0,-180 +58.42,50.4223421,-3.58724281,50,-20.00547097,-1.02E-11,0,0,0,-180 +58.43,50.4223403,-3.58724281,50,-20.01589954,1.56E-13,0,0,0,-180 +58.44,50.4223385,-3.58724281,50,-20.00547097,1.04E-11,0,0,0,-180 +58.45,50.4223367,-3.58724281,50,-19.98809002,2.06E-11,0,0,0,-180 +58.46,50.42233491,-3.58724281,50,-19.98809002,2.06E-11,0,0,0,-180 +58.47,50.42233311,-3.58724281,50,-20.00547095,1.03E-11,0,0,0,-180 +58.48,50.42233131,-3.58724281,50,-20.01589951,-9.37E-14,0,0,0,-180 +58.49,50.42232951,-3.58724281,50,-20.00547093,-1.06E-11,0,0,0,-180 +58.5,50.42232771,-3.58724281,50,-19.98808997,-2.10E-11,0,0,0,-180 +58.51,50.42232592,-3.58724281,50,-19.98808997,-2.10E-11,0,0,0,-180 +58.52,50.42232412,-3.58724281,50,-20.00547091,-1.06E-11,0,0,0,-180 +58.53,50.42232232,-3.58724281,50,-20.01589947,-9.37E-14,0,0,0,-180 +58.54,50.42232052,-3.58724281,50,-20.00547091,1.03E-11,0,0,0,-180 +58.55,50.42231872,-3.58724281,50,-19.98808996,2.06E-11,0,0,0,-180 +58.56,50.42231693,-3.58724281,50,-19.98808996,2.06E-11,0,0,0,-180 +58.57,50.42231513,-3.58724281,50,-20.0019947,1.25E-11,0,0,0,-180 +58.58,50.42231333,-3.58724281,50,-20.00199468,1.26E-11,0,0,0,-180 +58.59,50.42231153,-3.58724281,50,-19.98808992,2.09E-11,0,0,0,-180 +58.6,50.42230974,-3.58724281,50,-19.98808991,2.08E-11,0,0,0,-180 +58.61,50.42230794,-3.58724281,50,-20.00547086,1.03E-11,0,0,0,-180 +58.62,50.42230614,-3.58724281,50,-20.01589944,-1.41E-13,0,0,0,-180 +58.63,50.42230434,-3.58724281,50,-20.00547086,-1.04E-11,0,0,0,-180 +58.64,50.42230254,-3.58724281,50,-19.9880899,-2.06E-11,0,0,0,-180 +58.65,50.42230075,-3.58724281,50,-19.98808988,-2.06E-11,0,0,0,-180 +58.66,50.42229895,-3.58724281,50,-20.00547082,-1.04E-11,0,0,0,-180 +58.67,50.42229715,-3.58724281,50,-20.01589939,-1.41E-13,0,0,0,-180 +58.68,50.42229535,-3.58724281,50,-20.00547081,1.02E-11,0,0,0,-180 +58.69,50.42229355,-3.58724281,50,-19.98808985,2.08E-11,0,0,0,-180 +58.7,50.42229176,-3.58724281,50,-19.98808985,2.09E-11,0,0,0,-180 +58.71,50.42228996,-3.58724281,50,-20.00547079,1.05E-11,0,0,0,-180 +58.72,50.42228816,-3.58724281,50,-20.01589936,-1.73E-18,0,0,0,-180 +58.73,50.42228636,-3.58724281,50,-20.00547079,-1.05E-11,0,0,0,-180 +58.74,50.42228456,-3.58724281,50,-19.98808984,-2.09E-11,0,0,0,-180 +58.75,50.42228277,-3.58724281,50,-19.98808984,-2.09E-11,0,0,0,-180 +58.76,50.42228097,-3.58724281,50,-20.00547077,-1.05E-11,0,0,0,-180 +58.77,50.42227917,-3.58724281,50,-20.01589934,-1.56E-13,0,0,0,-180 +58.78,50.42227737,-3.58724281,50,-20.00547077,1.02E-11,0,0,0,-180 +58.79,50.42227557,-3.58724281,50,-19.98808981,2.08E-11,0,0,0,-180 +58.8,50.42227378,-3.58724281,50,-19.9880898,2.09E-11,0,0,0,-180 +58.81,50.42227198,-3.58724281,50,-20.00547073,1.05E-11,0,0,0,-180 +58.82,50.42227018,-3.58724281,50,-20.01589929,1.73E-18,0,0,0,-180 +58.83,50.42226838,-3.58724281,50,-20.00547072,-1.05E-11,0,0,0,-180 +58.84,50.42226658,-3.58724281,50,-19.98808976,-2.09E-11,0,0,0,-180 +58.85,50.42226479,-3.58724281,50,-19.98808975,-2.08E-11,0,0,0,-180 +58.86,50.42226299,-3.58724281,50,-20.0054707,-1.02E-11,0,0,0,-180 +58.87,50.42226119,-3.58724281,50,-20.01589926,1.41E-13,0,0,0,-180 +58.88,50.42225939,-3.58724281,50,-20.00547068,1.04E-11,0,0,0,-180 +58.89,50.42225759,-3.58724281,50,-19.98808973,2.06E-11,0,0,0,-180 +58.9,50.4222558,-3.58724281,50,-19.98808972,2.06E-11,0,0,0,-180 +58.91,50.422254,-3.58724281,50,-20.00199448,1.24E-11,0,0,0,-180 +58.92,50.4222522,-3.58724281,50,-20.00199449,1.24E-11,0,0,0,-180 +58.93,50.4222504,-3.58724281,50,-19.98808975,2.06E-11,0,0,0,-180 +58.94,50.42224861,-3.58724281,50,-19.98808974,2.06E-11,0,0,0,-180 +58.95,50.42224681,-3.58724281,50,-20.00547066,1.04E-11,0,0,0,-180 +58.96,50.42224501,-3.58724281,50,-20.01589921,1.41E-13,0,0,0,-180 +58.97,50.42224321,-3.58724281,50,-20.00547063,-1.02E-11,0,0,0,-180 +58.98,50.42224141,-3.58724281,50,-19.98808967,-2.08E-11,0,0,0,-180 +58.99,50.42223962,-3.58724281,50,-19.98808967,-2.09E-11,0,0,0,-180 +59,50.42223782,-3.58724281,50,-20.00547061,-1.05E-11,0,0,0,-180 +59.01,50.42223602,-3.58724281,50,-20.01589917,-9.37E-14,0,0,0,-180 +59.02,50.42223422,-3.58724281,50,-20.0054706,1.03E-11,0,0,0,-180 +59.03,50.42223242,-3.58724281,50,-19.98808964,2.06E-11,0,0,0,-180 +59.04,50.42223063,-3.58724281,50,-19.98808964,2.06E-11,0,0,0,-180 +59.05,50.42222883,-3.58724281,50,-20.00547058,1.04E-11,0,0,0,-180 +59.06,50.42222703,-3.58724281,50,-20.01589914,1.41E-13,0,0,0,-180 +59.07,50.42222523,-3.58724281,50,-20.00547058,-1.02E-11,0,0,0,-180 +59.08,50.42222343,-3.58724281,50,-19.98808963,-2.07E-11,0,0,0,-180 +59.09,50.42222164,-3.58724281,50,-19.98808963,-2.07E-11,0,0,0,-180 +59.1,50.42221984,-3.58724281,50,-20.00547057,-1.02E-11,0,0,0,-180 +59.11,50.42221804,-3.58724281,50,-20.01589914,1.41E-13,0,0,0,-180 +59.12,50.42221624,-3.58724281,50,-20.00547056,1.04E-11,0,0,0,-180 +59.13,50.42221444,-3.58724281,50,-19.98808959,2.06E-11,0,0,0,-180 +59.14,50.42221265,-3.58724281,50,-19.98808958,2.06E-11,0,0,0,-180 +59.15,50.42221085,-3.58724281,50,-20.00547052,1.03E-11,0,0,0,-180 +59.16,50.42220905,-3.58724281,50,-20.01589908,-9.37E-14,0,0,0,-180 +59.17,50.42220725,-3.58724281,50,-20.0054705,-1.05E-11,0,0,0,-180 +59.18,50.42220545,-3.58724281,50,-19.98808955,-2.09E-11,0,0,0,-180 +59.19,50.42220366,-3.58724281,50,-19.98808954,-2.08E-11,0,0,0,-180 +59.2,50.42220186,-3.58724281,50,-20.00547049,-1.02E-11,0,0,0,-180 +59.21,50.42220006,-3.58724281,50,-20.01589905,1.41E-13,0,0,0,-180 +59.22,50.42219826,-3.58724281,50,-20.00547047,1.04E-11,0,0,0,-180 +59.23,50.42219646,-3.58724281,50,-19.98808952,2.06E-11,0,0,0,-180 +59.24,50.42219467,-3.58724281,50,-19.98808952,2.06E-11,0,0,0,-180 +59.25,50.42219287,-3.58724281,50,-20.00199429,1.24E-11,0,0,0,-180 +59.26,50.42219107,-3.58724281,50,-20.00199428,1.24E-11,0,0,0,-180 +59.27,50.42218927,-3.58724281,50,-19.9880895,2.06E-11,0,0,0,-180 +59.28,50.42218748,-3.58724281,50,-19.98808949,2.06E-11,0,0,0,-180 +59.29,50.42218568,-3.58724281,50,-20.00547044,1.03E-11,0,0,0,-180 +59.3,50.42218388,-3.58724281,50,-20.01589902,-9.37E-14,0,0,0,-180 +59.31,50.42218208,-3.58724281,50,-20.00547044,-1.05E-11,0,0,0,-180 +59.32,50.42218028,-3.58724281,50,-19.98808947,-2.09E-11,0,0,0,-180 +59.33,50.42217849,-3.58724281,50,-19.98808946,-2.08E-11,0,0,0,-180 +59.34,50.42217669,-3.58724281,50,-20.0054704,-1.02E-11,0,0,0,-180 +59.35,50.42217489,-3.58724281,50,-20.01589896,1.56E-13,0,0,0,-180 +59.36,50.42217309,-3.58724281,50,-20.00547039,1.05E-11,0,0,0,-180 +59.37,50.42217129,-3.58724281,50,-19.98808943,2.09E-11,0,0,0,-180 +59.38,50.4221695,-3.58724281,50,-19.98808942,2.09E-11,0,0,0,-180 +59.39,50.4221677,-3.58724281,50,-20.00547037,1.05E-11,0,0,0,-180 +59.4,50.4221659,-3.58724281,50,-20.01589894,9.37E-14,0,0,0,-180 +59.41,50.4221641,-3.58724281,50,-20.00547038,-1.03E-11,0,0,0,-180 +59.42,50.4221623,-3.58724281,50,-19.98808942,-2.06E-11,0,0,0,-180 +59.43,50.42216051,-3.58724281,50,-19.9880894,-2.06E-11,0,0,0,-180 +59.44,50.42215871,-3.58724281,50,-20.00547034,-1.04E-11,0,0,0,-180 +59.45,50.42215691,-3.58724281,50,-20.0158989,-1.41E-13,0,0,0,-180 +59.46,50.42215511,-3.58724281,50,-20.00547032,1.02E-11,0,0,0,-180 +59.47,50.42215331,-3.58724281,50,-19.98808937,2.07E-11,0,0,0,-180 +59.48,50.42215152,-3.58724281,50,-19.98808936,2.07E-11,0,0,0,-180 +59.49,50.42214972,-3.58724281,50,-20.00547032,1.02E-11,0,0,0,-180 +59.5,50.42214792,-3.58724281,50,-20.01589889,-1.56E-13,0,0,0,-180 +59.51,50.42214612,-3.58724281,50,-20.00547032,-1.05E-11,0,0,0,-180 +59.52,50.42214432,-3.58724281,50,-19.98808935,-2.09E-11,0,0,0,-180 +59.53,50.42214253,-3.58724281,50,-19.98808933,-2.09E-11,0,0,0,-180 +59.54,50.42214073,-3.58724281,50,-20.00547027,-1.05E-11,0,0,0,-180 +59.55,50.42213893,-3.58724281,50,-20.01589884,-9.37E-14,0,0,0,-180 +59.56,50.42213713,-3.58724281,50,-20.00547027,1.03E-11,0,0,0,-180 +59.57,50.42213533,-3.58724281,50,-19.98808933,2.06E-11,0,0,0,-180 +59.58,50.42213354,-3.58724281,50,-19.98808932,2.06E-11,0,0,0,-180 +59.59,50.42213174,-3.58724281,50,-20.00547025,1.03E-11,0,0,0,-180 +59.6,50.42212994,-3.58724281,50,-20.01589881,-9.37E-14,0,0,0,-180 +59.61,50.42212814,-3.58724281,50,-20.00547023,-1.05E-11,0,0,0,-180 +59.62,50.42212634,-3.58724281,50,-19.98808928,-2.09E-11,0,0,0,-180 +59.63,50.42212455,-3.58724281,50,-19.98808927,-2.08E-11,0,0,0,-180 +59.64,50.42212275,-3.58724281,50,-20.00547021,-1.02E-11,0,0,0,-180 +59.65,50.42212095,-3.58724281,50,-20.01589878,1.56E-13,0,0,0,-180 +59.66,50.42211915,-3.58724281,50,-20.0054702,1.05E-11,0,0,0,-180 +59.67,50.42211735,-3.58724281,50,-19.98808925,2.09E-11,0,0,0,-180 +59.68,50.42211556,-3.58724281,50,-19.98808925,2.09E-11,0,0,0,-180 +59.69,50.42211376,-3.58724281,50,-20.00199402,1.26E-11,0,0,0,-180 +59.7,50.42211196,-3.58724281,50,-20.00199402,1.26E-11,0,0,0,-180 +59.71,50.42211016,-3.58724281,50,-19.98808925,2.09E-11,0,0,0,-180 +59.72,50.42210837,-3.58724281,50,-19.98808924,2.09E-11,0,0,0,-180 +59.73,50.42210657,-3.58724281,50,-20.00547017,1.05E-11,0,0,0,-180 +59.74,50.42210477,-3.58724281,50,-20.01589872,9.37E-14,0,0,0,-180 +59.75,50.42210297,-3.58724281,50,-20.00547014,-1.03E-11,0,0,0,-180 +59.76,50.42210117,-3.58724281,50,-19.98808919,-2.06E-11,0,0,0,-180 +59.77,50.42209938,-3.58724281,50,-19.98808918,-2.06E-11,0,0,0,-180 +59.78,50.42209758,-3.58724281,50,-20.00547013,-1.03E-11,0,0,0,-180 +59.79,50.42209578,-3.58724281,50,-20.01589869,9.38E-14,0,0,0,-180 +59.8,50.42209398,-3.58724281,50,-20.00547011,1.05E-11,0,0,0,-180 +59.81,50.42209218,-3.58724281,50,-19.98808916,2.09E-11,0,0,0,-180 +59.82,50.42209039,-3.58724281,50,-19.98808915,2.09E-11,0,0,0,-180 +59.83,50.42208859,-3.58724281,50,-20.00547009,1.05E-11,0,0,0,-180 +59.84,50.42208679,-3.58724281,50,-20.01589866,1.56E-13,0,0,0,-180 +59.85,50.42208499,-3.58724281,50,-20.00547008,-1.02E-11,0,0,0,-180 +59.86,50.42208319,-3.58724281,50,-19.98808913,-2.07E-11,0,0,0,-180 +59.87,50.4220814,-3.58724281,50,-19.98808914,-2.07E-11,0,0,0,-180 +59.88,50.4220796,-3.58724281,50,-20.00547011,-1.02E-11,0,0,0,-180 +59.89,50.4220778,-3.58724281,50,-20.01589867,1.56E-13,0,0,0,-180 +59.9,50.422076,-3.58724281,50,-20.00547007,1.05E-11,0,0,0,-180 +59.91,50.4220742,-3.58724281,50,-19.9880891,2.09E-11,0,0,0,-180 +59.92,50.42207241,-3.58724281,50,-19.98808909,2.09E-11,0,0,0,-180 +59.93,50.42207061,-3.58724281,50,-20.00547003,1.05E-11,0,0,0,-180 +59.94,50.42206881,-3.58724281,50,-20.0158986,9.37E-14,0,0,0,-180 +59.95,50.42206701,-3.58724281,50,-20.00547002,-1.03E-11,0,0,0,-180 +59.96,50.42206521,-3.58724281,50,-19.98808906,-2.06E-11,0,0,0,-180 +59.97,50.42206342,-3.58724281,50,-19.98808906,-2.06E-11,0,0,0,-180 +59.98,50.42206162,-3.58724281,50,-20.00547,-1.03E-11,0,0,0,-180 +59.99,50.42205982,-3.58724281,50,-20.01589856,0,0,0,0,-180 +60,50.42205802,-3.58724281,50,-20.00546999,1.03E-11,0,0,0,-180 +60.01,50.42205622,-3.58724281,50,-19.98808903,2.06E-11,0,0,0,-180 +60.02,50.42205443,-3.58724281,50,-19.98808903,2.06E-11,0,0,0,-180 +60.03,50.42205263,-3.58724281,50,-20.00199379,1.24E-11,0,0,0,-180 +60.04,50.42205083,-3.58724281,50,-20.00199381,1.24E-11,0,0,0,-180 +60.05,50.42204903,-3.58724281,50,-19.98808905,2.06E-11,0,0,0,-180 +60.06,50.42204724,-3.58724281,50,-19.98808904,2.06E-11,0,0,0,-180 +60.07,50.42204544,-3.58724281,50,-20.00546996,1.03E-11,0,0,0,-180 +60.08,50.42204364,-3.58724281,50,-20.01589851,0,0,0,0,-180 +60.09,50.42204184,-3.58724281,50,-20.00546993,-1.03E-11,0,0,0,-180 +60.1,50.42204004,-3.58724281,50,-19.98808898,-2.06E-11,0,0,0,-180 +60.11,50.42203825,-3.58724281,50,-19.98808897,-2.06E-11,0,0,0,-180 +60.12,50.42203645,-3.58724281,50,-20.00546991,-1.03E-11,0,0,0,-180 +60.13,50.42203465,-3.58724281,50,-20.01589848,9.37E-14,0,0,0,-180 +60.14,50.42203285,-3.58724281,50,-20.0054699,1.05E-11,0,0,0,-180 +60.15,50.42203105,-3.58724281,50,-19.98808895,2.09E-11,0,0,0,-180 +60.16,50.42202926,-3.58724281,50,-19.98808894,2.09E-11,0,0,0,-180 +60.17,50.42202746,-3.58724281,50,-20.00546988,1.05E-11,0,0,0,-180 +60.18,50.42202566,-3.58724281,50,-20.01589845,1.56E-13,0,0,0,-180 +60.19,50.42202386,-3.58724281,50,-20.00546988,-1.02E-11,0,0,0,-180 +60.2,50.42202206,-3.58724281,50,-19.98808894,-2.07E-11,0,0,0,-180 +60.21,50.42202027,-3.58724281,50,-19.98808893,-2.08E-11,0,0,0,-180 +60.22,50.42201847,-3.58724281,50,-20.00546986,-1.05E-11,0,0,0,-180 +60.23,50.42201667,-3.58724281,50,-20.01589842,-1.56E-13,0,0,0,-180 +60.24,50.42201487,-3.58724281,50,-20.00546985,1.02E-11,0,0,0,-180 +60.25,50.42201307,-3.58724281,50,-19.98808891,2.07E-11,0,0,0,-180 +60.26,50.42201128,-3.58724281,50,-19.9880889,2.07E-11,0,0,0,-180 +60.27,50.42200948,-3.58724281,50,-20.00546983,1.02E-11,0,0,0,-180 +60.28,50.42200768,-3.58724281,50,-20.01589839,-1.56E-13,0,0,0,-180 +60.29,50.42200588,-3.58724281,50,-20.00546981,-1.05E-11,0,0,0,-180 +60.3,50.42200408,-3.58724281,50,-19.98808885,-2.08E-11,0,0,0,-180 +60.31,50.42200229,-3.58724281,50,-19.98808885,-2.07E-11,0,0,0,-180 +60.32,50.42200049,-3.58724281,50,-20.00546979,-1.02E-11,0,0,0,-180 +60.33,50.42199869,-3.58724281,50,-20.01589835,1.56E-13,0,0,0,-180 +60.34,50.42199689,-3.58724281,50,-20.00546979,1.05E-11,0,0,0,-180 +60.35,50.42199509,-3.58724281,50,-19.98808884,2.08E-11,0,0,0,-180 +60.36,50.4219933,-3.58724281,50,-19.98808884,2.07E-11,0,0,0,-180 +60.37,50.4219915,-3.58724281,50,-20.00199358,1.23E-11,0,0,0,-180 +60.38,50.4219897,-3.58724281,50,-20.00199356,1.23E-11,0,0,0,-180 +60.39,50.4219879,-3.58724281,50,-19.9880888,2.07E-11,0,0,0,-180 +60.4,50.42198611,-3.58724281,50,-19.98808879,2.07E-11,0,0,0,-180 +60.41,50.42198431,-3.58724281,50,-20.00546973,1.02E-11,0,0,0,-180 +60.42,50.42198251,-3.58724281,50,-20.0158983,-1.56E-13,0,0,0,-180 +60.43,50.42198071,-3.58724281,50,-20.00546973,-1.05E-11,0,0,0,-180 +60.44,50.42197891,-3.58724281,50,-19.98808879,-2.08E-11,0,0,0,-180 +60.45,50.42197712,-3.58724281,50,-19.98808878,-2.07E-11,0,0,0,-180 +60.46,50.42197532,-3.58724281,50,-20.00546971,-1.02E-11,0,0,0,-180 +60.47,50.42197352,-3.58724281,50,-20.01589827,1.56E-13,0,0,0,-180 +60.48,50.42197172,-3.58724281,50,-20.00546969,1.05E-11,0,0,0,-180 +60.49,50.42196992,-3.58724281,50,-19.98808875,2.08E-11,0,0,0,-180 +60.5,50.42196813,-3.58724281,50,-19.98808875,2.07E-11,0,0,0,-180 +60.51,50.42196633,-3.58724281,50,-20.00546969,1.02E-11,0,0,0,-180 +60.52,50.42196453,-3.58724281,50,-20.01589825,-1.56E-13,0,0,0,-180 +60.53,50.42196273,-3.58724281,50,-20.00546966,-1.05E-11,0,0,0,-180 +60.54,50.42196093,-3.58724281,50,-19.9880887,-2.08E-11,0,0,0,-180 +60.55,50.42195914,-3.58724281,50,-19.9880887,-2.07E-11,0,0,0,-180 +60.56,50.42195734,-3.58724281,50,-20.00546964,-1.02E-11,0,0,0,-180 +60.57,50.42195554,-3.58724281,50,-20.0158982,1.56E-13,0,0,0,-180 +60.58,50.42195374,-3.58724281,50,-20.00546963,1.05E-11,0,0,0,-180 +60.59,50.42195194,-3.58724281,50,-19.98808867,2.08E-11,0,0,0,-180 +60.6,50.42195015,-3.58724281,50,-19.98808867,2.07E-11,0,0,0,-180 +60.61,50.42194835,-3.58724281,50,-20.00546961,1.02E-11,0,0,0,-180 +60.62,50.42194655,-3.58724281,50,-20.01589817,-1.56E-13,0,0,0,-180 +60.63,50.42194475,-3.58724281,50,-20.00546961,-1.05E-11,0,0,0,-180 +60.64,50.42194295,-3.58724281,50,-19.98808866,-2.08E-11,0,0,0,-180 +60.65,50.42194116,-3.58724281,50,-19.98808866,-2.07E-11,0,0,0,-180 +60.66,50.42193936,-3.58724281,50,-20.0054696,-1.02E-11,0,0,0,-180 +60.67,50.42193756,-3.58724281,50,-20.01589817,1.56E-13,0,0,0,-180 +60.68,50.42193576,-3.58724281,50,-20.00546959,1.05E-11,0,0,0,-180 +60.69,50.42193396,-3.58724281,50,-19.98808862,2.08E-11,0,0,0,-180 +60.7,50.42193217,-3.58724281,50,-19.98808861,2.08E-11,0,0,0,-180 +60.71,50.42193037,-3.58724281,50,-20.00199336,1.25E-11,0,0,0,-180 +60.72,50.42192857,-3.58724281,50,-20.00199335,1.26E-11,0,0,0,-180 +60.73,50.42192677,-3.58724281,50,-19.98808859,2.09E-11,0,0,0,-180 +60.74,50.42192498,-3.58724281,50,-19.98808858,2.09E-11,0,0,0,-180 +60.75,50.42192318,-3.58724281,50,-20.00546952,1.04E-11,0,0,0,-180 +60.76,50.42192138,-3.58724281,50,-20.01589809,-7.81E-14,0,0,0,-180 +60.77,50.42191958,-3.58724281,50,-20.00546951,-1.05E-11,0,0,0,-180 +60.78,50.42191778,-3.58724281,50,-19.98808856,-2.09E-11,0,0,0,-180 +60.79,50.42191599,-3.58724281,50,-19.98808855,-2.09E-11,0,0,0,-180 +60.8,50.42191419,-3.58724281,50,-20.00546949,-1.04E-11,0,0,0,-180 +60.81,50.42191239,-3.58724281,50,-20.01589806,7.81E-14,0,0,0,-180 +60.82,50.42191059,-3.58724281,50,-20.0054695,1.05E-11,0,0,0,-180 +60.83,50.42190879,-3.58724281,50,-19.98808857,2.09E-11,0,0,0,-180 +60.84,50.421907,-3.58724281,50,-19.98808856,2.09E-11,0,0,0,-180 +60.85,50.4219052,-3.58724281,50,-20.00546948,1.04E-11,0,0,0,-180 +60.86,50.4219034,-3.58724281,50,-20.01589803,1.56E-14,0,0,0,-180 +60.87,50.4219016,-3.58724281,50,-20.00546945,-1.03E-11,0,0,0,-180 +60.88,50.4218998,-3.58724281,50,-19.98808849,-2.06E-11,0,0,0,-180 +60.89,50.42189801,-3.58724281,50,-19.98808849,-2.06E-11,0,0,0,-180 +60.9,50.42189621,-3.58724281,50,-20.00546943,-1.03E-11,0,0,0,-180 +60.91,50.42189441,-3.58724281,50,-20.01589799,-1.73E-18,0,0,0,-180 +60.92,50.42189261,-3.58724281,50,-20.00546942,1.03E-11,0,0,0,-180 +60.93,50.42189081,-3.58724281,50,-19.98808846,2.06E-11,0,0,0,-180 +60.94,50.42188902,-3.58724281,50,-19.98808846,2.06E-11,0,0,0,-180 +60.95,50.42188722,-3.58724281,50,-20.0054694,1.03E-11,0,0,0,-180 +60.96,50.42188542,-3.58724281,50,-20.01589796,-1.56E-14,0,0,0,-180 +60.97,50.42188362,-3.58724281,50,-20.0054694,-1.04E-11,0,0,0,-180 +60.98,50.42188182,-3.58724281,50,-19.98808845,-2.09E-11,0,0,0,-180 +60.99,50.42188003,-3.58724281,50,-19.98808845,-2.09E-11,0,0,0,-180 +61,50.42187823,-3.58724281,50,-20.00546939,-1.05E-11,0,0,0,-180 +61.01,50.42187643,-3.58724281,50,-20.01589795,-7.81E-14,0,0,0,-180 +61.02,50.42187463,-3.58724281,50,-20.00546938,1.04E-11,0,0,0,-180 +61.03,50.42187283,-3.58724281,50,-19.98808841,2.08E-11,0,0,0,-180 +61.04,50.42187104,-3.58724281,50,-19.9880884,2.07E-11,0,0,0,-180 +61.05,50.42186924,-3.58724281,50,-20.00546934,1.02E-11,0,0,0,-180 +61.06,50.42186744,-3.58724281,50,-20.0158979,-1.56E-13,0,0,0,-180 +61.07,50.42186564,-3.58724281,50,-20.00546932,-1.05E-11,0,0,0,-180 +61.08,50.42186384,-3.58724281,50,-19.98808837,-2.08E-11,0,0,0,-180 +61.09,50.42186205,-3.58724281,50,-19.98808836,-2.08E-11,0,0,0,-180 +61.1,50.42186025,-3.58724281,50,-20.0054693,-1.05E-11,0,0,0,-180 +61.11,50.42185845,-3.58724281,50,-20.01589787,-1.56E-13,0,0,0,-180 +61.12,50.42185665,-3.58724281,50,-20.0054693,1.02E-11,0,0,0,-180 +61.13,50.42185485,-3.58724281,50,-19.98808836,2.07E-11,0,0,0,-180 +61.14,50.42185306,-3.58724281,50,-19.98808835,2.08E-11,0,0,0,-180 +61.15,50.42185126,-3.58724281,50,-20.0019931,1.25E-11,0,0,0,-180 +61.16,50.42184946,-3.58724281,50,-20.00199308,1.24E-11,0,0,0,-180 +61.17,50.42184766,-3.58724281,50,-19.98808831,2.06E-11,0,0,0,-180 +61.18,50.42184587,-3.58724281,50,-19.98808831,2.06E-11,0,0,0,-180 +61.19,50.42184407,-3.58724281,50,-20.00546926,1.03E-11,0,0,0,-180 +61.2,50.42184227,-3.58724281,50,-20.01589783,-1.56E-14,0,0,0,-180 +61.21,50.42184047,-3.58724281,50,-20.00546926,-1.04E-11,0,0,0,-180 +61.22,50.42183867,-3.58724281,50,-19.98808829,-2.09E-11,0,0,0,-180 +61.23,50.42183688,-3.58724281,50,-19.98808828,-2.09E-11,0,0,0,-180 +61.24,50.42183508,-3.58724281,50,-20.00546922,-1.05E-11,0,0,0,-180 +61.25,50.42183328,-3.58724281,50,-20.01589778,-7.81E-14,0,0,0,-180 +61.26,50.42183148,-3.58724281,50,-20.00546921,1.04E-11,0,0,0,-180 +61.27,50.42182968,-3.58724281,50,-19.98808825,2.08E-11,0,0,0,-180 +61.28,50.42182789,-3.58724281,50,-19.98808825,2.08E-11,0,0,0,-180 +61.29,50.42182609,-3.58724281,50,-20.0054692,1.05E-11,0,0,0,-180 +61.3,50.42182429,-3.58724281,50,-20.01589777,1.56E-13,0,0,0,-180 +61.31,50.42182249,-3.58724281,50,-20.0054692,-1.02E-11,0,0,0,-180 +61.32,50.42182069,-3.58724281,50,-19.98808823,-2.07E-11,0,0,0,-180 +61.33,50.4218189,-3.58724281,50,-19.98808822,-2.08E-11,0,0,0,-180 +61.34,50.4218171,-3.58724281,50,-20.00546916,-1.04E-11,0,0,0,-180 +61.35,50.4218153,-3.58724281,50,-20.01589772,-1.56E-14,0,0,0,-180 +61.36,50.4218135,-3.58724281,50,-20.00546914,1.03E-11,0,0,0,-180 +61.37,50.4218117,-3.58724281,50,-19.98808819,2.06E-11,0,0,0,-180 +61.38,50.42180991,-3.58724281,50,-19.98808819,2.06E-11,0,0,0,-180 +61.39,50.42180811,-3.58724281,50,-20.00546914,1.03E-11,0,0,0,-180 +61.4,50.42180631,-3.58724281,50,-20.01589771,-1.56E-14,0,0,0,-180 +61.41,50.42180451,-3.58724281,50,-20.00546913,-1.04E-11,0,0,0,-180 +61.42,50.42180271,-3.58724281,50,-19.98808817,-2.09E-11,0,0,0,-180 +61.43,50.42180092,-3.58724281,50,-19.98808815,-2.09E-11,0,0,0,-180 +61.44,50.42179912,-3.58724281,50,-20.0054691,-1.05E-11,0,0,0,-180 +61.45,50.42179732,-3.58724281,50,-20.01589767,-7.81E-14,0,0,0,-180 +61.46,50.42179552,-3.58724281,50,-20.0054691,1.04E-11,0,0,0,-180 +61.47,50.42179372,-3.58724281,50,-19.98808815,2.08E-11,0,0,0,-180 +61.48,50.42179193,-3.58724281,50,-19.98808813,2.08E-11,0,0,0,-180 +61.49,50.42179013,-3.58724281,50,-20.00199288,1.25E-11,0,0,0,-180 +61.5,50.42178833,-3.58724281,50,-20.00199287,1.26E-11,0,0,0,-180 +61.51,50.42178653,-3.58724281,50,-19.9880881,2.09E-11,0,0,0,-180 +61.52,50.42178474,-3.58724281,50,-19.9880881,2.09E-11,0,0,0,-180 +61.53,50.42178294,-3.58724281,50,-20.00546904,1.04E-11,0,0,0,-180 +61.54,50.42178114,-3.58724281,50,-20.0158976,1.73E-18,0,0,0,-180 +61.55,50.42177934,-3.58724281,50,-20.00546903,-1.04E-11,0,0,0,-180 +61.56,50.42177754,-3.58724281,50,-19.98808807,-2.09E-11,0,0,0,-180 +61.57,50.42177575,-3.58724281,50,-19.98808807,-2.09E-11,0,0,0,-180 +61.58,50.42177395,-3.58724281,50,-20.00546902,-1.05E-11,0,0,0,-180 +61.59,50.42177215,-3.58724281,50,-20.01589759,-7.81E-14,0,0,0,-180 +61.6,50.42177035,-3.58724281,50,-20.00546903,1.04E-11,0,0,0,-180 +61.61,50.42176855,-3.58724281,50,-19.98808807,2.08E-11,0,0,0,-180 +61.62,50.42176676,-3.58724281,50,-19.98808806,2.08E-11,0,0,0,-180 +61.63,50.42176496,-3.58724281,50,-20.00546899,1.04E-11,0,0,0,-180 +61.64,50.42176316,-3.58724281,50,-20.01589754,-7.81E-14,0,0,0,-180 +61.65,50.42176136,-3.58724281,50,-20.00546896,-1.05E-11,0,0,0,-180 +61.66,50.42175956,-3.58724281,50,-19.98808801,0.00044417,0,0,0,-180 +61.67,50.42175777,-3.58724281,50,-19.988088,0.003109187,0,0,0,179.9976145 +61.68,50.42175597,-3.58724281,50,-20.00546894,0.010437987,0,0,0,179.9809161 +61.69,50.42175417,-3.587242808,50,-20.01589751,0.023318909,0,0,0,179.9403626 +61.7,50.42175237,-3.587242804,50,-20.00546893,0.040641529,0,0,0,179.8854962 +61.71,50.42175057,-3.587242797,50,-19.98808798,0.060407084,0,0,0,179.8282443 +61.72,50.42174878,-3.587242787,50,-19.98808797,0.080394725,0,0,0,179.7709924 +61.73,50.42174698,-3.587242774,50,-20.00546891,0.099716112,0,0,0,179.7137405 +61.74,50.42174518,-3.587242759,50,-20.01589748,0.119703756,0,0,0,179.6564886 +61.75,50.42174338,-3.587242741,50,-20.00546892,0.140801826,0,0,0,179.5992367 +61.76,50.42174158,-3.587242719,50,-19.98808799,0.161011558,0,0,0,179.5419847 +61.77,50.42173979,-3.587242695,50,-19.98808798,0.179888781,0,0,0,179.4847328 +61.78,50.42173799,-3.587242669,50,-20.00199271,0.199432262,0,0,0,179.4274809 +61.79,50.42173619,-3.587242639,50,-20.00199269,0.220086168,0,0,0,179.3702291 +61.8,50.42173439,-3.587242607,50,-19.98808792,0.240295905,0,0,0,179.3129771 +61.81,50.4217326,-3.587242571,50,-19.98808792,0.259617305,0,0,0,179.2557252 +61.82,50.4217308,-3.587242534,50,-20.00546886,0.279382876,0,0,0,179.1984733 +61.83,50.421729,-3.587242493,50,-20.01589742,0.299814704,0,0,0,179.1412214 +61.84,50.4217272,-3.587242449,50,-20.00546884,0.319580278,0,0,0,179.0839695 +61.85,50.4217254,-3.587242403,50,-19.98808789,0.338901684,0,0,0,179.0267176 +61.86,50.42172361,-3.587242354,50,-19.98808788,0.35911143,0,0,0,178.9694656 +61.87,50.42172181,-3.587242302,50,-20.00199264,0.379987433,0,0,0,178.9122138 +61.88,50.42172001,-3.587242247,50,-20.00199263,0.400197183,0,0,0,178.8549619 +61.89,50.42171821,-3.587242189,50,-19.98808787,0.41929651,0,0,0,178.7977099 +61.9,50.42171642,-3.587242129,50,-19.98808786,0.438617923,0,0,0,178.740458 +61.91,50.42171462,-3.587242066,50,-20.00199262,0.459493932,0,0,0,178.6832061 +61.92,50.42171282,-3.587242,50,-20.00199263,0.480814113,0,0,0,178.6259542 +61.93,50.42171102,-3.58724193,50,-19.98808787,0.500801785,0,0,0,178.5687023 +61.94,50.42170923,-3.587241859,50,-19.98808786,0.519901119,0,0,0,178.5114504 +61.95,50.42170743,-3.587241784,50,-20.00199261,0.53922254,0,0,0,178.4541985 +61.96,50.42170563,-3.587241707,50,-20.0019926,0.558988133,0,0,0,178.3969466 +61.97,50.42170383,-3.587241627,50,-19.98808783,0.579419982,0,0,0,178.3396947 +61.98,50.42170204,-3.587241544,50,-19.98461162,0.600296002,0,0,0,178.2824428 +61.99,50.42170024,-3.587241458,50,-19.9880878,0.620505768,0,0,0,178.2251908 +62,50.42169844,-3.587241369,50,-19.98461161,0.639605111,0,0,0,178.1679389 +62.01,50.42169665,-3.587241278,50,-19.9846116,0.658704455,0,0,0,178.110687 +62.02,50.42169485,-3.587241184,50,-19.98808779,0.67869214,0,0,0,178.0534352 +62.03,50.42169305,-3.587241087,50,-19.98461159,0.698901914,0,0,0,177.9961832 +62.04,50.42169126,-3.587240987,50,-19.98461159,0.718889604,0,0,0,177.9389313 +62.05,50.42168946,-3.587240885,50,-19.98808778,0.73909938,0,0,0,177.8816794 +62.06,50.42168766,-3.587240779,50,-19.98461159,0.759309156,0,0,0,177.8244275 +62.07,50.42168587,-3.587240671,50,-19.98461159,0.779296849,0,0,0,177.7671756 +62.08,50.42168407,-3.58724056,50,-19.98808776,0.79950663,0,0,0,177.7099237 +62.09,50.42168227,-3.587240446,50,-19.98461155,0.819494327,0,0,0,177.6526717 +62.1,50.42168048,-3.587240329,50,-19.98461155,0.838593684,0,0,0,177.5954199 +62.11,50.42167868,-3.58724021,50,-19.98808773,0.857915128,0,0,0,177.538168 +62.12,50.42167688,-3.587240088,50,-19.98113536,0.878791171,0,0,0,177.480916 +62.13,50.42167509,-3.587239963,50,-19.97070679,0.900111385,0,0,0,177.4236641 +62.14,50.42167329,-3.587239834,50,-19.97070679,0.920099089,0,0,0,177.3664122 +62.15,50.4216715,-3.587239704,50,-19.98113534,0.939198454,0,0,0,177.3091603 +62.16,50.4216697,-3.58723957,50,-19.98808771,0.958519905,0,0,0,177.2519084 +62.17,50.4216679,-3.587239434,50,-19.98113534,0.978285529,0,0,0,177.1946565 +62.18,50.42166611,-3.587239295,50,-19.97070676,0.99871741,0,0,0,177.1374046 +62.19,50.42166431,-3.587239153,50,-19.96723055,1.019593464,0,0,0,177.0801527 +62.2,50.42166252,-3.587239008,50,-19.96723054,1.039803263,0,0,0,177.0229008 +62.21,50.42166072,-3.58723886,50,-19.96723053,1.058902635,0,0,0,176.9656489 +62.22,50.42165893,-3.58723871,50,-19.96723052,1.078002009,0,0,0,176.9083969 +62.23,50.42165713,-3.587238557,50,-19.96723052,1.097989727,0,0,0,176.851145 +62.24,50.42165534,-3.587238401,50,-19.96723051,1.118199532,0,0,0,176.7938932 +62.25,50.42165354,-3.587238242,50,-19.96723051,1.138187254,0,0,0,176.7366413 +62.26,50.42165175,-3.587238081,50,-19.96723052,1.158397062,0,0,0,176.6793893 +62.27,50.42164995,-3.587237916,50,-19.96723054,1.178606871,0,0,0,176.6221374 +62.28,50.42164816,-3.587237749,50,-19.96723053,1.198594596,0,0,0,176.5648855 +62.29,50.42164636,-3.587237579,50,-19.9672305,1.218804408,0,0,0,176.5076336 +62.3,50.42164457,-3.587237406,50,-19.96723048,1.238792137,0,0,0,176.4503817 +62.31,50.42164277,-3.58723723,50,-19.96723047,1.257891525,0,0,0,176.3931298 +62.32,50.42164098,-3.587237052,50,-19.96375427,1.276990914,0,0,0,176.3358779 +62.33,50.42163918,-3.587236871,50,-19.9533257,1.297200734,0,0,0,176.278626 +62.34,50.42163739,-3.587236687,50,-19.94637331,1.31807681,0,0,0,176.2213741 +62.35,50.4216356,-3.5872365,50,-19.95332569,1.338508716,0,0,0,176.1641221 +62.36,50.4216338,-3.58723631,50,-19.96375426,1.358274368,0,0,0,176.1068702 +62.37,50.42163201,-3.587236118,50,-19.96375426,1.37759585,0,0,0,176.0496183 +62.38,50.42163021,-3.587235922,50,-19.95332569,1.396695248,0,0,0,175.9923665 +62.39,50.42162842,-3.587235725,50,-19.94637329,1.416682991,0,0,0,175.9351145 +62.4,50.42162663,-3.587235524,50,-19.94984947,1.438003248,0,0,0,175.8778626 +62.41,50.42162483,-3.58723532,50,-19.94637328,1.458879335,0,0,0,175.8206107 +62.42,50.42162304,-3.587235113,50,-19.93246853,1.478200824,0,0,0,175.7633588 +62.43,50.42162125,-3.587234904,50,-19.93246852,1.497078144,0,0,0,175.7061069 +62.44,50.42161946,-3.587234692,50,-19.94637327,1.516399638,0,0,0,175.648855 +62.45,50.42161766,-3.587234477,50,-19.94637327,1.536165303,0,0,0,175.591603 +62.46,50.42161587,-3.58723426,50,-19.9324685,1.556597226,0,0,0,175.5343512 +62.47,50.42161408,-3.587234039,50,-19.93246849,1.577473322,0,0,0,175.4770993 +62.48,50.42161229,-3.587233816,50,-19.94637323,1.597683164,0,0,0,175.4198474 +62.49,50.42161049,-3.587233589,50,-19.94637322,1.617004665,0,0,0,175.3625954 +62.5,50.4216087,-3.587233361,50,-19.92899227,1.636770337,0,0,0,175.3053435 +62.51,50.42160691,-3.587233129,50,-19.91856369,1.657424353,0,0,0,175.2480916 +62.52,50.42160512,-3.587232894,50,-19.92899227,1.678078371,0,0,0,175.1908397 +62.53,50.42160333,-3.587232657,50,-19.94637323,1.69828822,0,0,0,175.1335878 +62.54,50.42160153,-3.587232416,50,-19.94637323,1.717387642,0,0,0,175.0763359 +62.55,50.42159974,-3.587232173,50,-19.92899227,1.735376638,0,0,0,175.019084 +62.56,50.42159795,-3.587231928,50,-19.91508748,1.754476064,0,0,0,174.9618321 +62.57,50.42159616,-3.58723168,50,-19.91161128,1.775574261,0,0,0,174.9045802 +62.58,50.42159437,-3.587231428,50,-19.91161127,1.796672459,0,0,0,174.8473282 +62.59,50.42159258,-3.587231174,50,-19.91161127,1.816660231,0,0,0,174.7900763 +62.6,50.42159079,-3.587230917,50,-19.91161128,1.836203833,0,0,0,174.7328245 +62.61,50.421589,-3.587230657,50,-19.91161127,1.855969522,0,0,0,174.6755726 +62.62,50.42158721,-3.587230395,50,-19.91161126,1.875957298,0,0,0,174.6183206 +62.63,50.42158542,-3.587230129,50,-19.91161124,1.895278819,0,0,0,174.5610687 +62.64,50.42158363,-3.587229861,50,-19.91161124,1.914156171,0,0,0,174.5038168 +62.65,50.42158184,-3.587229591,50,-19.91161125,1.934366038,0,0,0,174.4465649 +62.66,50.42158005,-3.587229317,50,-19.91161126,1.955686334,0,0,0,174.389313 +62.67,50.42157826,-3.58722904,50,-19.91161126,1.976340374,0,0,0,174.3320611 +62.68,50.42157647,-3.587228761,50,-19.90813504,1.995883988,0,0,0,174.2748092 +62.69,50.42157468,-3.587228478,50,-19.89423026,2.014761347,0,0,0,174.2175573 +62.7,50.42157289,-3.587228194,50,-19.8768493,2.033860793,0,0,0,174.1603054 +62.71,50.42157111,-3.587227906,50,-19.87684931,2.054070669,0,0,0,174.1030535 +62.72,50.42156932,-3.587227616,50,-19.89423026,2.074946803,0,0,0,174.0458015 +62.73,50.42156753,-3.587227322,50,-19.90465882,2.095378767,0,0,0,173.9885496 +62.74,50.42156574,-3.587227026,50,-19.89423025,2.115144476,0,0,0,173.9312977 +62.75,50.42156395,-3.587226727,50,-19.8768493,2.134466014,0,0,0,173.8740458 +62.76,50.42156217,-3.587226425,50,-19.87337311,2.153565469,0,0,0,173.8167939 +62.77,50.42156038,-3.587226121,50,-19.87684929,2.173553268,0,0,0,173.759542 +62.78,50.42155859,-3.587225814,50,-19.87337309,2.194651497,0,0,0,173.7022901 +62.79,50.42155681,-3.587225503,50,-19.87337307,2.214861385,0,0,0,173.6450382 +62.8,50.42155502,-3.58722519,50,-19.87684924,2.233738759,0,0,0,173.5877863 +62.81,50.42155323,-3.587224875,50,-19.87337305,2.253060306,0,0,0,173.5305343 +62.82,50.42155145,-3.587224556,50,-19.87337306,2.273048112,0,0,0,173.4732825 +62.83,50.42154966,-3.587224235,50,-19.87684925,2.29303592,0,0,0,173.4160306 +62.84,50.42154787,-3.587223911,50,-19.86989687,2.313245815,0,0,0,173.3587787 +62.85,50.42154609,-3.587223584,50,-19.85946829,2.333233626,0,0,0,173.3015267 +62.86,50.4215443,-3.587223254,50,-19.85599209,2.352333096,0,0,0,173.2442748 +62.87,50.42154252,-3.587222922,50,-19.85599208,2.371432566,0,0,0,173.1870229 +62.88,50.42154073,-3.587222587,50,-19.85599208,2.391642467,0,0,0,173.129771 +62.89,50.42153895,-3.587222249,50,-19.85599206,2.412518627,0,0,0,173.0725191 +62.9,50.42153716,-3.587221908,50,-19.85599205,2.432950617,0,0,0,173.0152672 +62.91,50.42153538,-3.587221564,50,-19.85251587,2.452716351,0,0,0,172.9580153 +62.92,50.42153359,-3.587221218,50,-19.84208732,2.472037914,0,0,0,172.9007634 +62.93,50.42153181,-3.587220868,50,-19.83513493,2.491137392,0,0,0,172.8435115 +62.94,50.42153003,-3.587220517,50,-19.84208728,2.510903131,0,0,0,172.7862596 +62.95,50.42152824,-3.587220162,50,-19.85251584,2.531335129,0,0,0,172.7290076 +62.96,50.42152646,-3.587219804,50,-19.85251584,2.551100871,0,0,0,172.6717557 +62.97,50.42152467,-3.587219444,50,-19.83861107,2.570422442,0,0,0,172.6145039 +62.98,50.42152289,-3.587219081,50,-19.82123011,2.590632357,0,0,0,172.5572519 +62.99,50.42152111,-3.587218715,50,-19.8212301,2.611508532,0,0,0,172.5 +63,50.42151933,-3.587218346,50,-19.83513487,2.631718451,0,0,0,172.4427481 +63.01,50.42151754,-3.587217974,50,-19.83513488,2.650817942,0,0,0,172.3854962 +63.02,50.42151576,-3.5872176,50,-19.81775393,2.669695348,0,0,0,172.3282443 +63.03,50.42151398,-3.587217223,50,-19.80384915,2.689016927,0,0,0,172.2709924 +63.04,50.4215122,-3.587216843,50,-19.80037295,2.70878268,0,0,0,172.2137404 +63.05,50.42151042,-3.587216461,50,-19.80037294,2.728992607,0,0,0,172.1564886 +63.06,50.42150864,-3.587216075,50,-19.80037293,2.749202536,0,0,0,172.0992367 +63.07,50.42150686,-3.587215687,50,-19.80037293,2.768968294,0,0,0,172.0419848 +63.08,50.42150508,-3.587215296,50,-19.80037294,2.788511966,0,0,0,171.9847328 +63.09,50.4215033,-3.587214902,50,-19.80037294,2.808277726,0,0,0,171.9274809 +63.1,50.42150152,-3.587214506,50,-19.80037291,2.82848766,0,0,0,171.870229 +63.11,50.42149974,-3.587214106,50,-19.8003729,2.848697594,0,0,0,171.8129771 +63.12,50.42149796,-3.587213704,50,-19.8003729,2.868463359,0,0,0,171.7557252 +63.13,50.42149618,-3.587213299,50,-19.8003729,2.887784953,0,0,0,171.6984733 +63.14,50.4214944,-3.587212891,50,-19.8003729,2.906884463,0,0,0,171.6412214 +63.15,50.42149262,-3.587212481,50,-19.8003729,2.926872319,0,0,0,171.5839695 +63.16,50.42149084,-3.587212068,50,-19.79689671,2.947970606,0,0,0,171.5267176 +63.17,50.42148906,-3.587211651,50,-19.78299193,2.967958464,0,0,0,171.4694657 +63.18,50.42148728,-3.587211232,50,-19.76561097,2.986169634,0,0,0,171.4122137 +63.19,50.42148551,-3.587210811,50,-19.76213477,3.005047065,0,0,0,171.3549619 +63.2,50.42148373,-3.587210387,50,-19.76561096,3.025257014,0,0,0,171.29771 +63.21,50.42148195,-3.587209959,50,-19.76213477,3.045244877,0,0,0,171.240458 +63.22,50.42148018,-3.58720953,50,-19.76213478,3.065232742,0,0,0,171.1832061 +63.23,50.4214784,-3.587209097,50,-19.76561095,3.085664782,0,0,0,171.1259542 +63.24,50.42147662,-3.587208661,50,-19.75865855,3.105430564,0,0,0,171.0687023 +63.25,50.42147485,-3.587208223,50,-19.74822998,3.12453009,0,0,0,171.0114504 +63.26,50.42147307,-3.587207782,50,-19.74475379,3.143851704,0,0,0,170.9541985 +63.27,50.4214713,-3.587207338,50,-19.74475379,3.16361749,0,0,0,170.8969466 +63.28,50.42146952,-3.587206892,50,-19.74475379,3.183827449,0,0,0,170.8396947 +63.29,50.42146775,-3.587206442,50,-19.74475379,3.204037411,0,0,0,170.7824428 +63.3,50.42146597,-3.58720599,50,-19.74475377,3.224025288,0,0,0,170.7251909 +63.31,50.4214642,-3.587205535,50,-19.74127757,3.244013168,0,0,0,170.6679389 +63.32,50.42146242,-3.587205077,50,-19.730849,3.263334789,0,0,0,170.610687 +63.33,50.42146065,-3.587204616,50,-19.72389663,3.28221224,0,0,0,170.5534352 +63.34,50.42145888,-3.587204154,50,-19.72737281,3.302200124,0,0,0,170.4961832 +63.35,50.4214571,-3.587203687,50,-19.72737279,3.322632181,0,0,0,170.4389313 +63.36,50.42145533,-3.587203218,50,-19.72389659,3.342175895,0,0,0,170.3816794 +63.37,50.42145356,-3.587202747,50,-19.72737278,3.361497523,0,0,0,170.3244275 +63.38,50.42145178,-3.587202272,50,-19.7238966,3.380597066,0,0,0,170.2671756 +63.39,50.42145001,-3.587201795,50,-19.70651565,3.399474525,0,0,0,170.2099237 +63.4,50.42144824,-3.587201316,50,-19.69261088,3.419684503,0,0,0,170.1526718 +63.41,50.42144647,-3.587200833,50,-19.68913467,3.440782827,0,0,0,170.0954199 +63.42,50.4214447,-3.587200347,50,-19.68913466,3.460770722,0,0,0,170.038168 +63.43,50.42144293,-3.587199859,50,-19.68913466,3.479870274,0,0,0,169.9809161 +63.44,50.42144116,-3.587199368,50,-19.68913467,3.499191913,0,0,0,169.9236641 +63.45,50.42143939,-3.587198874,50,-19.68913466,3.518735639,0,0,0,169.8664122 +63.46,50.42143762,-3.587198378,50,-19.68913465,3.538057281,0,0,0,169.8091603 +63.47,50.42143585,-3.587197878,50,-19.68913464,3.557156838,0,0,0,169.7519084 +63.48,50.42143408,-3.587197377,50,-19.68913463,3.576922655,0,0,0,169.6946565 +63.49,50.42143231,-3.587196872,50,-19.68565843,3.597576818,0,0,0,169.6374046 +63.5,50.42143054,-3.587196364,50,-19.67175369,3.618008896,0,0,0,169.5801527 +63.51,50.42142877,-3.587195854,50,-19.65437274,3.637552632,0,0,0,169.5229008 +63.52,50.42142701,-3.58719534,50,-19.65089654,3.65643011,0,0,0,169.4656489 +63.53,50.42142524,-3.587194825,50,-19.65437272,3.675529675,0,0,0,169.408397 +63.54,50.42142347,-3.587194306,50,-19.65089653,3.695739674,0,0,0,169.351145 +63.55,50.42142171,-3.587193785,50,-19.65089652,3.716393847,0,0,0,169.2938932 +63.56,50.42141994,-3.58719326,50,-19.65437269,3.735937589,0,0,0,169.2366413 +63.57,50.42141817,-3.587192733,50,-19.6474203,3.754592987,0,0,0,169.1793893 +63.58,50.42141641,-3.587192204,50,-19.63699174,3.773914647,0,0,0,169.1221374 +63.59,50.42141464,-3.587191671,50,-19.63351556,3.793902565,0,0,0,169.0648855 +63.6,50.42141288,-3.587191136,50,-19.63351555,3.813668399,0,0,0,169.0076336 +63.61,50.42141111,-3.587190598,50,-19.63351554,3.833212148,0,0,0,168.9503817 +63.62,50.42140935,-3.587190057,50,-19.63003934,3.852977986,0,0,0,168.8931298 +63.63,50.42140758,-3.587189514,50,-19.61961077,3.872965911,0,0,0,168.8358779 +63.64,50.42140582,-3.587188967,50,-19.61265838,3.892287579,0,0,0,168.778626 +63.65,50.42140406,-3.587188418,50,-19.61613455,3.910942988,0,0,0,168.7213741 +63.66,50.42140229,-3.587187867,50,-19.61265835,3.930264658,0,0,0,168.6641222 +63.67,50.42140053,-3.587187312,50,-19.5987536,3.950252589,0,0,0,168.6068702 +63.68,50.42139877,-3.587186755,50,-19.59875361,3.970018435,0,0,0,168.5496183 +63.69,50.42139701,-3.587186195,50,-19.61265836,3.989562196,0,0,0,168.4923664 +63.7,50.42139524,-3.587185632,50,-19.61265835,4.009328045,0,0,0,168.4351145 +63.71,50.42139348,-3.587185067,50,-19.59527739,4.029538068,0,0,0,168.3778626 +63.72,50.42139172,-3.587184498,50,-19.58137264,4.049748092,0,0,0,168.3206107 +63.73,50.42138996,-3.587183927,50,-19.57789644,4.069513945,0,0,0,168.2633588 +63.74,50.4213882,-3.587183353,50,-19.57789643,4.088835626,0,0,0,168.2061069 +63.75,50.42138644,-3.587182776,50,-19.57789642,4.10749105,0,0,0,168.148855 +63.76,50.42138468,-3.587182197,50,-19.57442024,4.125702301,0,0,0,168.0916031 +63.77,50.42138292,-3.587181615,50,-19.56051548,4.144579814,0,0,0,168.0343511 +63.78,50.42138116,-3.587181031,50,-19.54313452,4.16456776,0,0,0,167.9770993 +63.79,50.42137941,-3.587180443,50,-19.54313452,4.184777795,0,0,0,167.9198474 +63.8,50.42137765,-3.587179853,50,-19.55703928,4.204765744,0,0,0,167.8625954 +63.81,50.42137589,-3.58717926,50,-19.55703926,4.225197868,0,0,0,167.8053435 +63.82,50.42137413,-3.587178664,50,-19.54313449,4.245852082,0,0,0,167.7480916 +63.83,50.42137238,-3.587178065,50,-19.53965829,4.265173775,0,0,0,167.6908397 +63.84,50.42137062,-3.587177463,50,-19.54313449,4.28316295,0,0,0,167.6335878 +63.85,50.42136886,-3.58717686,50,-19.5361821,4.302040474,0,0,0,167.5763359 +63.86,50.42136711,-3.587176253,50,-19.52575352,4.32225052,0,0,0,167.519084 +63.87,50.42136535,-3.587175643,50,-19.52227732,4.342016393,0,0,0,167.4618321 +63.88,50.4213636,-3.587175031,50,-19.51880114,4.361116007,0,0,0,167.4045802 +63.89,50.42136184,-3.587174416,50,-19.50837257,4.380437709,0,0,0,167.3473283 +63.9,50.42136009,-3.587173798,50,-19.50142018,4.400203585,0,0,0,167.2900763 +63.91,50.42135834,-3.587173178,50,-19.50489636,4.420191551,0,0,0,167.2328244 +63.92,50.42135658,-3.587172554,50,-19.50142017,4.439513258,0,0,0,167.1755726 +63.93,50.42135483,-3.587171928,50,-19.48751541,4.458168706,0,0,0,167.1183206 +63.94,50.42135308,-3.5871713,50,-19.48751541,4.477490416,0,0,0,167.0610687 +63.95,50.42135133,-3.587170668,50,-19.50142016,4.497478386,0,0,0,167.0038168 +63.96,50.42134957,-3.587170034,50,-19.50142015,4.517466358,0,0,0,166.9465649 +63.97,50.42134782,-3.587169397,50,-19.48403918,4.537676419,0,0,0,166.889313 +63.98,50.42134607,-3.587168757,50,-19.47013442,4.557664395,0,0,0,166.8320611 +63.99,50.42134432,-3.587168114,50,-19.46665824,4.576764024,0,0,0,166.7748092 +64,50.42134257,-3.587167469,50,-19.46665824,4.595641568,0,0,0,166.7175573 +64.01,50.42134082,-3.587166821,50,-19.46665823,4.6147412,0,0,0,166.6603054 +64.02,50.42133907,-3.58716617,50,-19.46318204,4.633618747,0,0,0,166.6030535 +64.03,50.42133732,-3.587165517,50,-19.44927728,4.652496296,0,0,0,166.5458015 +64.04,50.42133557,-3.587164861,50,-19.43189632,4.67181802,0,0,0,166.4885496 +64.05,50.42133383,-3.587164202,50,-19.42842012,4.691583918,0,0,0,166.4312977 +64.06,50.42133208,-3.587163541,50,-19.4318963,4.711793991,0,0,0,166.3740458 +64.07,50.42133033,-3.587162876,50,-19.4284201,4.731781978,0,0,0,166.3167939 +64.08,50.42132859,-3.587162209,50,-19.4284201,4.750659534,0,0,0,166.259542 +64.09,50.42132684,-3.587161539,50,-19.43189629,4.76887083,0,0,0,166.2022901 +64.1,50.42132509,-3.587160867,50,-19.42494391,4.787748387,0,0,0,166.1450382 +64.11,50.42132335,-3.587160192,50,-19.41451534,4.807736381,0,0,0,166.0877863 +64.12,50.4213216,-3.587159514,50,-19.41103915,4.827946463,0,0,0,166.0305344 +64.13,50.42131986,-3.587158833,50,-19.40756295,4.847934459,0,0,0,165.9732824 +64.14,50.42131811,-3.58715815,50,-19.39713437,4.868144545,0,0,0,165.9160306 +64.15,50.42131637,-3.587157463,50,-19.39018199,4.887910457,0,0,0,165.8587787 +64.16,50.42131463,-3.587156774,50,-19.39365817,4.906121762,0,0,0,165.8015267 +64.17,50.42131288,-3.587156082,50,-19.39018197,4.923888895,0,0,0,165.7442748 +64.18,50.42131114,-3.587155389,50,-19.37280103,4.94298855,0,0,0,165.6870229 +64.19,50.4213094,-3.587154691,50,-19.35889627,4.963198641,0,0,0,165.629771 +64.2,50.42130766,-3.587153992,50,-19.35542006,4.983630821,0,0,0,165.5725191 +64.21,50.42130592,-3.587153289,50,-19.35542006,5.003396742,0,0,0,165.5152672 +64.22,50.42130418,-3.587152583,50,-19.35542005,5.02205223,0,0,0,165.4580153 +64.23,50.42130244,-3.587151876,50,-19.35542004,5.041151892,0,0,0,165.4007634 +64.24,50.4213007,-3.587151165,50,-19.35542004,5.061139903,0,0,0,165.3435115 +64.25,50.42129896,-3.587150451,50,-19.35542004,5.080017481,0,0,0,165.2862596 +64.26,50.42129722,-3.587149735,50,-19.35194385,5.098228801,0,0,0,165.2290076 +64.27,50.42129548,-3.587149017,50,-19.33803908,5.118216818,0,0,0,165.1717557 +64.28,50.42129374,-3.587148295,50,-19.32065813,5.139093183,0,0,0,165.1145039 +64.29,50.42129201,-3.58714757,50,-19.31718194,5.158192854,0,0,0,165.0572519 +64.3,50.42129027,-3.587146843,50,-19.32065813,5.17618209,0,0,0,165 +64.31,50.42128853,-3.587146114,50,-19.31370575,5.195281762,0,0,0,164.9427481 +64.32,50.4212868,-3.587145381,50,-19.30327716,5.215047698,0,0,0,164.8854962 +64.33,50.42128506,-3.587144646,50,-19.29980096,5.233925288,0,0,0,164.8282443 +64.34,50.42128333,-3.587143908,50,-19.29980096,5.252358704,0,0,0,164.7709924 +64.35,50.42128159,-3.587143168,50,-19.29980097,5.271902557,0,0,0,164.7137405 +64.36,50.42127986,-3.587142425,50,-19.29632477,5.29233476,0,0,0,164.6564886 +64.37,50.42127812,-3.587141678,50,-19.28241999,5.312100703,0,0,0,164.5992367 +64.38,50.42127639,-3.58714093,50,-19.26503904,5.331200386,0,0,0,164.5419848 +64.39,50.42127466,-3.587140178,50,-19.26503905,5.350300069,0,0,0,164.4847328 +64.4,50.42127293,-3.587139424,50,-19.27894381,5.36895558,0,0,0,164.4274809 +64.41,50.42127119,-3.587138667,50,-19.2789438,5.387166919,0,0,0,164.370229 +64.42,50.42126946,-3.587137908,50,-19.26156284,5.40604452,0,0,0,164.3129771 +64.43,50.42126773,-3.587137146,50,-19.24765806,5.426254644,0,0,0,164.2557252 +64.44,50.421266,-3.587136381,50,-19.24418187,5.447131033,0,0,0,164.1984733 +64.45,50.42126427,-3.587135613,50,-19.24070568,5.467119074,0,0,0,164.1412214 +64.46,50.42126254,-3.587134842,50,-19.22680093,5.48533042,0,0,0,164.0839695 +64.47,50.42126081,-3.587134069,50,-19.20941999,5.503097592,0,0,0,164.0267176 +64.48,50.42125909,-3.587133294,50,-19.20941998,5.522197287,0,0,0,163.9694657 +64.49,50.42125736,-3.587132515,50,-19.22332472,5.542185332,0,0,0,163.9122137 +64.5,50.42125563,-3.587131734,50,-19.2233247,5.561951293,0,0,0,163.8549618 +64.51,50.4212539,-3.58713095,50,-19.20594375,5.581273082,0,0,0,163.79771 +64.52,50.42125218,-3.587130163,50,-19.192039,5.600150697,0,0,0,163.740458 +64.53,50.42125045,-3.587129374,50,-19.18856282,5.619028311,0,0,0,163.6832061 +64.54,50.42124873,-3.587128582,50,-19.18856282,5.638128014,0,0,0,163.6259542 +64.55,50.421247,-3.587127787,50,-19.18856281,5.657005633,0,0,0,163.5687023 +64.56,50.42124528,-3.58712699,50,-19.18508661,5.675883253,0,0,0,163.5114504 +64.57,50.42124355,-3.58712619,50,-19.17118184,5.695205049,0,0,0,163.4541985 +64.58,50.42124183,-3.587125387,50,-19.15380089,5.714748933,0,0,0,163.3969466 +64.59,50.42124011,-3.587124582,50,-19.15380089,5.734070731,0,0,0,163.3396947 +64.6,50.42123839,-3.587123773,50,-19.16770565,5.752948356,0,0,0,163.2824428 +64.61,50.42123666,-3.587122963,50,-19.16770564,5.771825983,0,0,0,163.2251909 +64.62,50.42123494,-3.587122149,50,-19.15032469,5.791147785,0,0,0,163.1679389 +64.63,50.42123322,-3.587121333,50,-19.13641993,5.810691675,0,0,0,163.110687 +64.64,50.4212315,-3.587120514,50,-19.13294373,5.83001348,0,0,0,163.0534351 +64.65,50.42122978,-3.587119692,50,-19.12946753,5.848891112,0,0,0,162.9961832 +64.66,50.42122806,-3.587118868,50,-19.11556276,5.867768745,0,0,0,162.9389313 +64.67,50.42122634,-3.587118041,50,-19.09818181,5.886868467,0,0,0,162.8816794 +64.68,50.42122463,-3.587117211,50,-19.09470562,5.905746101,0,0,0,162.8244275 +64.69,50.42122291,-3.587116379,50,-19.09818181,5.924623737,0,0,0,162.7671756 +64.7,50.42122119,-3.587115544,50,-19.09470561,5.943945549,0,0,0,162.7099237 +64.71,50.42121948,-3.587114706,50,-19.09470561,5.96348945,0,0,0,162.6526718 +64.72,50.42121776,-3.587113866,50,-19.0947056,5.982811267,0,0,0,162.5954198 +64.73,50.42121604,-3.587113022,50,-19.07732465,6.00168891,0,0,0,162.538168 +64.74,50.42121433,-3.587112177,50,-19.0599437,6.020566553,0,0,0,162.4809161 +64.75,50.42121262,-3.587111328,50,-19.05994369,6.039666285,0,0,0,162.4236641 +64.76,50.4212109,-3.587110477,50,-19.05994368,6.05854393,0,0,0,162.3664122 +64.77,50.42120919,-3.587109623,50,-19.05646748,6.077421577,0,0,0,162.3091603 +64.78,50.42120748,-3.587108767,50,-19.05994367,6.096521313,0,0,0,162.2519084 +64.79,50.42120576,-3.587107907,50,-19.05646748,6.115398963,0,0,0,162.1946565 +64.8,50.42120405,-3.587107046,50,-19.03908653,6.134276614,0,0,0,162.1374046 +64.81,50.42120234,-3.587106181,50,-19.02518177,6.153598441,0,0,0,162.0801527 +64.82,50.42120063,-3.587105314,50,-19.02170557,6.173142357,0,0,0,162.0229008 +64.83,50.42119892,-3.587104444,50,-19.02170557,6.192464187,0,0,0,161.9656489 +64.84,50.42119721,-3.587103571,50,-19.01822938,6.211341843,0,0,0,161.908397 +64.85,50.4211955,-3.587102696,50,-19.00432463,6.229997413,0,0,0,161.851145 +64.86,50.42119379,-3.587101818,50,-18.98694368,6.248430898,0,0,0,161.7938931 +64.87,50.42119209,-3.587100937,50,-18.98346747,6.266864383,0,0,0,161.7366413 +64.88,50.42119038,-3.587100055,50,-18.98694365,6.285964131,0,0,0,161.6793893 +64.89,50.42118867,-3.587099168,50,-18.97999126,6.30506388,0,0,0,161.6221374 +64.9,50.42118697,-3.58709828,50,-18.96956269,6.323719456,0,0,0,161.5648855 +64.91,50.42118526,-3.587097389,50,-18.9660865,6.343041298,0,0,0,161.5076336 +64.92,50.42118356,-3.587096495,50,-18.96261032,6.362807316,0,0,0,161.4503817 +64.93,50.42118185,-3.587095598,50,-18.95218176,6.381907071,0,0,0,161.3931298 +64.94,50.42118015,-3.587094699,50,-18.94522937,6.40078474,0,0,0,161.3358779 +64.95,50.42117845,-3.587093797,50,-18.94870554,6.419884497,0,0,0,161.278626 +64.96,50.42117674,-3.587092892,50,-18.94522933,6.438762169,0,0,0,161.2213741 +64.97,50.42117504,-3.587091985,50,-18.92784839,6.457639841,0,0,0,161.1641222 +64.98,50.42117334,-3.587091075,50,-18.91394364,6.476739601,0,0,0,161.1068702 +64.99,50.42117164,-3.587090162,50,-18.91046744,6.495395189,0,0,0,161.0496183 +65,50.42116994,-3.587089247,50,-18.91046743,6.513384517,0,0,0,160.9923664 +65.01,50.42116824,-3.587088329,50,-18.91046741,6.531373845,0,0,0,160.9351145 +65.02,50.42116654,-3.587087409,50,-18.90699123,6.550251525,0,0,0,160.8778626 +65.03,50.42116484,-3.587086486,50,-18.89308647,6.570239644,0,0,0,160.8206107 +65.04,50.42116314,-3.58708556,50,-18.87570552,6.590227763,0,0,0,160.7633588 +65.05,50.42116145,-3.587084631,50,-18.87222932,6.609327532,0,0,0,160.7061069 +65.06,50.42115975,-3.5870837,50,-18.87570551,6.628205217,0,0,0,160.648855 +65.07,50.42115805,-3.587082766,50,-18.86875314,6.647082903,0,0,0,160.5916031 +65.08,50.42115636,-3.587081829,50,-18.85484838,6.665072239,0,0,0,160.5343511 +65.09,50.42115466,-3.58708089,50,-18.84094361,6.68283949,0,0,0,160.4770993 +65.1,50.42115297,-3.587079949,50,-18.83399122,6.70171718,0,0,0,160.4198474 +65.11,50.42115128,-3.587079004,50,-18.8374674,6.720816958,0,0,0,160.3625954 +65.12,50.42114958,-3.587078057,50,-18.8339912,6.739472562,0,0,0,160.3053435 +65.13,50.42114789,-3.587077108,50,-18.81661025,6.75879443,0,0,0,160.2480916 +65.14,50.4211462,-3.587076155,50,-18.8027055,6.778560476,0,0,0,160.1908397 +65.15,50.42114451,-3.5870752,50,-18.79922932,6.797438171,0,0,0,160.1335878 +65.16,50.42114282,-3.587074242,50,-18.7992293,6.815649604,0,0,0,160.0763359 +65.17,50.42114113,-3.587073282,50,-18.79922929,6.834305214,0,0,0,160.019084 +65.18,50.42113944,-3.587072319,50,-18.79922929,6.853405001,0,0,0,159.9618321 +65.19,50.42113775,-3.587071353,50,-18.7957531,6.872060615,0,0,0,159.9045802 +65.2,50.42113606,-3.587070385,50,-18.78184834,6.890049967,0,0,0,159.8473283 +65.21,50.42113437,-3.587069414,50,-18.76446739,6.908039319,0,0,0,159.7900763 +65.22,50.42113269,-3.587068441,50,-18.76099119,6.926694935,0,0,0,159.7328244 +65.23,50.421131,-3.587067465,50,-18.76446738,6.946016816,0,0,0,159.6755725 +65.24,50.42112931,-3.587066486,50,-18.75751499,6.965560786,0,0,0,159.6183206 +65.25,50.42112763,-3.587065505,50,-18.74361022,6.98488267,0,0,0,159.5610687 +65.26,50.42112594,-3.58706452,50,-18.72970546,7.003760379,0,0,0,159.5038168 +65.27,50.42112426,-3.587063534,50,-18.72275309,7.022416002,0,0,0,159.4465649 +65.28,50.42112258,-3.587062544,50,-18.72622928,7.040627451,0,0,0,159.389313 +65.29,50.42112089,-3.587061552,50,-18.72275308,7.058172637,0,0,0,159.3320611 +65.3,50.42111921,-3.587060558,50,-18.70537213,7.076384089,0,0,0,159.2748092 +65.31,50.42111753,-3.587059561,50,-18.69146736,7.096150156,0,0,0,159.2175573 +65.32,50.42111585,-3.587058561,50,-18.68799116,7.116138311,0,0,0,159.1603054 +65.33,50.42111417,-3.587057558,50,-18.68799115,7.135016029,0,0,0,159.1030535 +65.34,50.42111249,-3.587056553,50,-18.68451497,7.153005398,0,0,0,159.0458015 +65.35,50.42111081,-3.587055545,50,-18.67061021,7.170994767,0,0,0,158.9885496 +65.36,50.42110913,-3.587054535,50,-18.65322926,7.1896504,0,0,0,158.9312977 +65.37,50.42110746,-3.587053522,50,-18.64975307,7.208750211,0,0,0,158.8740458 +65.38,50.42110578,-3.587052506,50,-18.65322925,7.227405847,0,0,0,158.8167939 +65.39,50.4211041,-3.587051488,50,-18.64627687,7.245395222,0,0,0,158.759542 +65.4,50.42110243,-3.587050467,50,-18.63237211,7.263384597,0,0,0,158.7022901 +65.41,50.42110075,-3.587049444,50,-18.61846734,7.282040237,0,0,0,158.6450382 +65.42,50.42109908,-3.587048418,50,-18.61151496,7.301140053,0,0,0,158.5877863 +65.43,50.42109741,-3.587047389,50,-18.61499114,7.320017784,0,0,0,158.5305344 +65.44,50.42109573,-3.587046358,50,-18.61151495,7.338895516,0,0,0,158.4732824 +65.45,50.42109406,-3.587045324,50,-18.594134,7.357995336,0,0,0,158.4160305 +65.46,50.42109239,-3.587044287,50,-18.58022924,7.376650981,0,0,0,158.3587787 +65.47,50.42109072,-3.587043248,50,-18.57675304,7.394640364,0,0,0,158.3015267 +65.48,50.42108905,-3.587042206,50,-18.57675305,7.412629749,0,0,0,158.2442748 +65.49,50.42108738,-3.587041162,50,-18.57675305,7.431285399,0,0,0,158.1870229 +65.5,50.42108571,-3.587040115,50,-18.57327685,7.450385226,0,0,0,158.129771 +65.51,50.42108404,-3.587039065,50,-18.55937208,7.469040879,0,0,0,158.0725191 +65.52,50.42108237,-3.587038013,50,-18.53851494,7.487030268,0,0,0,158.0152672 +65.53,50.42108071,-3.587036958,50,-18.52461017,7.505019658,0,0,0,157.9580153 +65.54,50.42107904,-3.587035901,50,-18.52113399,7.523675314,0,0,0,157.9007634 +65.55,50.42107738,-3.587034841,50,-18.52113399,7.542775147,0,0,0,157.8435115 +65.56,50.42107571,-3.587033778,50,-18.52113398,7.561430804,0,0,0,157.7862596 +65.57,50.42107405,-3.587032713,50,-18.51765778,7.579420199,0,0,0,157.7290076 +65.58,50.42107238,-3.587031645,50,-18.50375302,7.597409596,0,0,0,157.6717557 +65.59,50.42107072,-3.587030575,50,-18.48289589,7.616065258,0,0,0,157.6145038 +65.6,50.42106906,-3.587029502,50,-18.46899112,7.635165097,0,0,0,157.5572519 +65.61,50.4210674,-3.587028426,50,-18.46551493,7.654042849,0,0,0,157.5 +65.62,50.42106574,-3.587027348,50,-18.46551493,7.672698513,0,0,0,157.4427481 +65.63,50.42106408,-3.587026267,50,-18.46551493,7.690910003,0,0,0,157.3854962 +65.64,50.42106242,-3.587025183,50,-18.46551491,7.708677318,0,0,0,157.3282443 +65.65,50.42106076,-3.587024098,50,-18.46203872,7.727332988,0,0,0,157.2709924 +65.66,50.4210591,-3.587023009,50,-18.44813397,7.746432835,0,0,0,157.2137405 +65.67,50.42105744,-3.587021917,50,-18.42727683,7.763978065,0,0,0,157.1564885 +65.68,50.42105579,-3.587020824,50,-18.41337205,7.78107912,0,0,0,157.0992367 +65.69,50.42105413,-3.587019728,50,-18.40989586,7.799956882,0,0,0,157.0419848 +65.7,50.42105248,-3.587018629,50,-18.40989586,7.819722997,0,0,0,156.9847328 +65.71,50.42105082,-3.587017527,50,-18.40989586,7.838600761,0,0,0,156.9274809 +65.72,50.42104917,-3.587016423,50,-18.40641965,7.856812262,0,0,0,156.870229 +65.73,50.42104751,-3.587015316,50,-18.3925149,7.87546794,0,0,0,156.8129771 +65.74,50.42104586,-3.587014207,50,-18.37165778,7.894345707,0,0,0,156.7557252 +65.75,50.42104421,-3.587013094,50,-18.35775302,7.912335123,0,0,0,156.6984733 +65.76,50.42104256,-3.58701198,50,-18.35427681,7.929880364,0,0,0,156.6412214 +65.77,50.42104091,-3.587010863,50,-18.35427679,7.948091872,0,0,0,156.5839695 +65.78,50.42103926,-3.587009743,50,-18.35427679,7.966525468,0,0,0,156.5267176 +65.79,50.42103761,-3.587008621,50,-18.35080061,7.984514888,0,0,0,156.4694657 +65.8,50.42103596,-3.587007496,50,-18.33689585,8.002504309,0,0,0,156.4122137 +65.81,50.42103431,-3.587006369,50,-18.3160387,8.021159997,0,0,0,156.3549618 +65.82,50.42103267,-3.587005239,50,-18.30213394,8.040037773,0,0,0,156.29771 +65.83,50.42103102,-3.587004106,50,-18.29865775,8.058027198,0,0,0,156.240458 +65.84,50.42102938,-3.587002971,50,-18.29518157,8.075794537,0,0,0,156.1832061 +65.85,50.42102773,-3.587001834,50,-18.284753,8.094672318,0,0,0,156.1259542 +65.86,50.42102609,-3.587000693,50,-18.2778006,8.113550098,0,0,0,156.0687023 +65.87,50.42102445,-3.58699955,50,-18.28127677,8.131095351,0,0,0,156.0114504 +65.88,50.4210228,-3.586998405,50,-18.27780057,8.148418517,0,0,0,155.9541985 +65.89,50.42102116,-3.586997257,50,-18.26041964,8.166852126,0,0,0,155.8969466 +65.9,50.42101952,-3.586996107,50,-18.2465149,8.185952001,0,0,0,155.8396947 +65.91,50.42101788,-3.586994953,50,-18.23956252,8.204829789,0,0,0,155.7824428 +65.92,50.42101624,-3.586993798,50,-18.22565776,8.223485488,0,0,0,155.7251909 +65.93,50.4210146,-3.586992639,50,-18.2082768,8.241697013,0,0,0,155.6679389 +65.94,50.42101297,-3.586991478,50,-18.20480059,8.259020185,0,0,0,155.610687 +65.95,50.42101133,-3.586990315,50,-18.20827678,8.276121271,0,0,0,155.5534351 +65.96,50.42100969,-3.586989149,50,-18.2013244,8.293666534,0,0,0,155.4961833 +65.97,50.42100806,-3.586987981,50,-18.19089584,8.311655975,0,0,0,155.4389313 +65.98,50.42100642,-3.58698681,50,-18.18741965,8.330311682,0,0,0,155.3816794 +65.99,50.42100479,-3.586985637,50,-18.18394345,8.349411566,0,0,0,155.3244275 +66,50.42100315,-3.58698446,50,-18.17003868,8.368067276,0,0,0,155.2671756 +66.01,50.42100152,-3.586983282,50,-18.14918153,8.386056721,0,0,0,155.2099237 +66.02,50.42099989,-3.5869821,50,-18.13527677,8.404046167,0,0,0,155.1526718 +66.03,50.42099826,-3.586980917,50,-18.13180058,8.422479791,0,0,0,155.0954198 +66.04,50.42099663,-3.58697973,50,-18.13180059,8.440691328,0,0,0,155.038168 +66.05,50.420995,-3.586978541,50,-18.13180059,8.458236602,0,0,0,154.9809161 +66.06,50.42099337,-3.58697735,50,-18.12832439,8.476226054,0,0,0,154.9236641 +66.07,50.42099174,-3.586976156,50,-18.11441963,8.49510386,0,0,0,154.8664122 +66.08,50.42099011,-3.586974959,50,-18.09356249,8.513759578,0,0,0,154.8091603 +66.09,50.42098849,-3.58697376,50,-18.07965773,8.531526943,0,0,0,154.7519084 +66.1,50.42098686,-3.586972558,50,-18.07618152,8.548628044,0,0,0,154.6946565 +66.11,50.42098524,-3.586971354,50,-18.07270532,8.566173323,0,0,0,154.6374046 +66.12,50.42098361,-3.586970148,50,-18.06227674,8.585051134,0,0,0,154.5801527 +66.13,50.42098199,-3.586968938,50,-18.05532437,8.603928947,0,0,0,154.5229008 +66.14,50.42098037,-3.586967726,50,-18.05880057,8.62147423,0,0,0,154.4656489 +66.15,50.42097874,-3.586966512,50,-18.05532438,8.638575338,0,0,0,154.408397 +66.16,50.42097712,-3.586965295,50,-18.03794345,8.656120623,0,0,0,154.351145 +66.17,50.4209755,-3.586964076,50,-18.02056249,8.674110086,0,0,0,154.2938931 +66.18,50.42097388,-3.586962854,50,-18.00318153,8.692765815,0,0,0,154.2366412 +66.19,50.42097226,-3.58696163,50,-17.98580057,8.711643633,0,0,0,154.1793894 +66.2,50.42097065,-3.586960402,50,-17.98232438,8.729633099,0,0,0,154.1221374 +66.21,50.42096903,-3.586959173,50,-17.98580057,8.747178389,0,0,0,154.0648855 +66.22,50.42096741,-3.586957941,50,-17.9788482,8.765389946,0,0,0,154.0076336 +66.23,50.4209658,-3.586956706,50,-17.96841963,8.783823593,0,0,0,153.9503817 +66.24,50.42096418,-3.586955469,50,-17.96494342,8.801590975,0,0,0,153.8931298 +66.25,50.42096257,-3.586954229,50,-17.96146722,8.818692092,0,0,0,153.8358779 +66.26,50.42096095,-3.586952987,50,-17.94756247,8.836015299,0,0,0,153.7786259 +66.27,50.42095934,-3.586951743,50,-17.92670534,8.854004773,0,0,0,153.7213741 +66.28,50.42095773,-3.586950495,50,-17.91280058,8.87177216,0,0,0,153.6641222 +66.29,50.42095612,-3.586949246,50,-17.90932437,8.889539547,0,0,0,153.6068702 +66.3,50.42095451,-3.586947994,50,-17.90932437,8.908639467,0,0,0,153.5496183 +66.31,50.4209529,-3.586946739,50,-17.90584818,8.928183564,0,0,0,153.4923664 +66.32,50.42095129,-3.586945481,50,-17.89194342,8.945950954,0,0,0,153.4351145 +66.33,50.42094968,-3.586944221,50,-17.87456247,8.961941637,0,0,0,153.3778626 +66.34,50.42094808,-3.586942959,50,-17.87108628,8.978376498,0,0,0,153.3206107 +66.35,50.42094647,-3.586941695,50,-17.87108627,8.99636598,0,0,0,153.2633588 +66.36,50.42094486,-3.586940427,50,-17.85370532,9.01502173,0,0,0,153.2061069 +66.37,50.42094326,-3.586939158,50,-17.83632437,9.03367748,0,0,0,153.148855 +66.38,50.42094166,-3.586937885,50,-17.83632437,9.051889055,0,0,0,153.0916031 +66.39,50.42094005,-3.58693661,50,-17.83284817,9.069434364,0,0,0,153.0343511 +66.4,50.42093845,-3.586935333,50,-17.81546722,9.087201762,0,0,0,152.9770992 +66.41,50.42093685,-3.586934053,50,-17.80156246,9.10519125,0,0,0,152.9198474 +66.42,50.42093525,-3.58693277,50,-17.79808627,9.122514473,0,0,0,152.8625955 +66.43,50.42093365,-3.586931486,50,-17.79461008,9.13961561,0,0,0,152.8053435 +66.44,50.42093205,-3.586930198,50,-17.78070532,9.157383013,0,0,0,152.7480916 +66.45,50.42093045,-3.586928909,50,-17.76332437,9.175816683,0,0,0,152.6908397 +66.46,50.42092886,-3.586927616,50,-17.75984817,9.194028265,0,0,0,152.6335878 +66.47,50.42092726,-3.586926321,50,-17.75984816,9.211351494,0,0,0,152.5763359 +66.48,50.42092566,-3.586925024,50,-17.74246722,9.228452635,0,0,0,152.519084 +66.49,50.42092407,-3.586923724,50,-17.72508627,9.246220043,0,0,0,152.4618321 +66.5,50.42092248,-3.586922422,50,-17.72508627,9.264653719,0,0,0,152.4045802 +66.51,50.42092088,-3.586921117,50,-17.72161008,9.282865308,0,0,0,152.3473283 +66.52,50.42091929,-3.586919809,50,-17.70422914,9.300188542,0,0,0,152.2900763 +66.53,50.4209177,-3.5869185,50,-17.69032439,9.317289687,0,0,0,152.2328244 +66.54,50.42091611,-3.586917187,50,-17.68684819,9.335057099,0,0,0,152.1755725 +66.55,50.42091452,-3.586915873,50,-17.68337198,9.353490781,0,0,0,152.1183207 +66.56,50.42091293,-3.586914555,50,-17.66946721,9.371702374,0,0,0,152.0610687 +66.57,50.42091134,-3.586913235,50,-17.65208627,9.389025612,0,0,0,152.0038168 +66.58,50.42090976,-3.586911913,50,-17.64861008,9.406126762,0,0,0,151.9465649 +66.59,50.42090817,-3.586910588,50,-17.64861008,9.423672091,0,0,0,151.889313 +66.6,50.42090658,-3.586909261,50,-17.63122912,9.441217423,0,0,0,151.8320611 +66.61,50.420905,-3.586907931,50,-17.61384817,9.458096489,0,0,0,151.7748092 +66.62,50.42090342,-3.586906599,50,-17.61384817,9.474753466,0,0,0,151.7175572 +66.63,50.42090183,-3.586905265,50,-17.61037199,9.492520888,0,0,0,151.6603054 +66.64,50.42090025,-3.586903928,50,-17.59299105,9.511398755,0,0,0,151.6030535 +66.65,50.42089867,-3.586902588,50,-17.57908628,9.530054535,0,0,0,151.5458016 +66.66,50.42089709,-3.586901246,50,-17.57561007,9.547821961,0,0,0,151.4885496 +66.67,50.42089551,-3.586899901,50,-17.57213387,9.564701033,0,0,0,151.4312977 +66.68,50.42089393,-3.586898554,50,-17.55822911,9.581358015,0,0,0,151.3740458 +66.69,50.42089235,-3.586897205,50,-17.53737199,9.598903355,0,0,0,151.3167939 +66.7,50.42089078,-3.586895853,50,-17.52346724,9.616892873,0,0,0,151.259542 +66.71,50.4208892,-3.586894498,50,-17.51999105,9.634438214,0,0,0,151.2022901 +66.72,50.42088763,-3.586893142,50,-17.51999103,9.652205646,0,0,0,151.1450382 +66.73,50.42088605,-3.586891782,50,-17.51999102,9.670195167,0,0,0,151.0877863 +66.74,50.42088448,-3.58689042,50,-17.51651482,9.687518423,0,0,0,151.0305344 +66.75,50.4208829,-3.586889056,50,-17.50261007,9.704619591,0,0,0,150.9732824 +66.76,50.42088133,-3.586887689,50,-17.48175295,9.722164937,0,0,0,150.9160305 +66.77,50.42087976,-3.58688632,50,-17.46437199,9.739710285,0,0,0,150.8587787 +66.78,50.42087819,-3.586884948,50,-17.44699103,9.756589367,0,0,0,150.8015268 +66.79,50.42087662,-3.586883574,50,-17.42961009,9.773024271,0,0,0,150.7442748 +66.8,50.42087506,-3.586882198,50,-17.4261339,9.790125443,0,0,0,150.6870229 +66.81,50.42087349,-3.586880819,50,-17.42961009,9.80855915,0,0,0,150.629771 +66.82,50.42087192,-3.586879438,50,-17.4226577,9.827214948,0,0,0,150.5725191 +66.83,50.42087036,-3.586878053,50,-17.41222913,9.844316124,0,0,0,150.5152672 +66.84,50.42086879,-3.586876667,50,-17.40875295,9.860751033,0,0,0,150.4580153 +66.85,50.42086723,-3.586875279,50,-17.40527675,9.878518478,0,0,0,150.4007634 +66.86,50.42086566,-3.586873887,50,-17.39137198,9.896285923,0,0,0,150.3435115 +66.87,50.4208641,-3.586872493,50,-17.37051483,9.912720834,0,0,0,150.2862596 +66.88,50.42086254,-3.586871098,50,-17.35661008,9.929599926,0,0,0,150.2290077 +66.89,50.42086098,-3.586869699,50,-17.34965771,9.947367374,0,0,0,150.1717557 +66.9,50.42085942,-3.586868298,50,-17.33575296,9.964468556,0,0,0,150.1145038 +66.91,50.42085786,-3.586866895,50,-17.31837201,9.979793026,0,0,0,150.0596374 +66.92,50.42085631,-3.586865489,50,-17.31837199,9.991341984,0,0,0,150.019084 +66.93,50.42085475,-3.586864082,50,-17.33227673,9.997338715,0,0,0,150.0023855 +66.94,50.42085319,-3.586862675,50,-17.33227673,9.999115755,0,0,0,150 +66.95,50.42085163,-3.586861268,50,-17.31837198,9.999338171,0,0,0,150 +66.96,50.42085008,-3.586859861,50,-17.31489579,9.999338499,0,0,0,150 +66.97,50.42084852,-3.586858454,50,-17.31837197,9.999338828,0,0,0,150 +66.98,50.42084696,-3.586857047,50,-17.31489579,9.999339156,0,0,0,150 +66.99,50.42084541,-3.58685564,50,-17.31489577,9.999561574,0,0,0,150 +67,50.42084385,-3.586854233,50,-17.31837194,10.00045026,0,0,0,150 +67.01,50.42084229,-3.586852826,50,-17.31489574,10.00133894,0,0,0,150 +67.02,50.42084074,-3.586851418,50,-17.31837195,10.000673,0,0,0,150 +67.03,50.42083918,-3.586850011,50,-17.33227671,9.999340794,0,0,0,150 +67.04,50.42083762,-3.586848605,50,-17.3322767,9.999563212,0,0,0,150 +67.05,50.42083606,-3.586847197,50,-17.31837194,10.0004519,0,0,0,150 +67.06,50.42083451,-3.58684579,50,-17.31489575,10.00023014,0,0,0,150 +67.07,50.42083295,-3.586844383,50,-17.31837193,9.999564195,0,0,0,150 +67.08,50.42083139,-3.586842976,50,-17.31489571,9.999342433,0,0,0,150 +67.09,50.42082984,-3.586841569,50,-17.3183719,9.999342761,0,0,0,150 +67.1,50.42082828,-3.586840162,50,-17.33227667,9.999565179,0,0,0,150 +67.11,50.42082672,-3.586838755,50,-17.33227667,10.00045386,0,0,0,150 +67.12,50.42082516,-3.586837348,50,-17.3183719,10.00156464,0,0,0,150 +67.13,50.42082361,-3.58683594,50,-17.31489571,10.00156496,0,0,0,150 +67.14,50.42082205,-3.586834533,50,-17.3183719,10.00045485,0,0,0,150 +67.15,50.42082049,-3.586833126,50,-17.3148957,9.999566818,0,0,0,150 +67.16,50.42081894,-3.586831719,50,-17.31837186,9.999345056,0,0,0,150 +67.17,50.42081738,-3.586830312,50,-17.33227662,9.999345384,0,0,0,150 +67.18,50.42081582,-3.586828905,50,-17.33227663,9.999345713,0,0,0,150 +67.19,50.42081426,-3.586827498,50,-17.31837188,9.99956813,0,0,0,150 +67.2,50.42081271,-3.586826091,50,-17.31489568,10.00023472,0,0,0,150 +67.21,50.42081115,-3.586824684,50,-17.31837186,10.00045714,0,0,0,150 +67.22,50.42080959,-3.586823276,50,-17.31489567,9.999569113,0,0,0,150 +67.23,50.42080804,-3.58682187,50,-17.31489565,9.999347352,0,0,0,150 +67.24,50.42080648,-3.586820463,50,-17.31837183,10.00068022,0,0,0,150 +67.25,50.42080492,-3.586819055,50,-17.31489564,10.00134681,0,0,0,150 +67.26,50.42080337,-3.586817648,50,-17.31837185,10.00045878,0,0,0,150 +67.27,50.42080181,-3.586816241,50,-17.3322766,9.999570751,0,0,0,150 +67.28,50.42080025,-3.586814834,50,-17.33227659,9.99934899,0,0,0,150 +67.29,50.42079869,-3.586813427,50,-17.31837183,9.999349319,0,0,0,150 +67.3,50.42079714,-3.58681202,50,-17.31489563,9.999571737,0,0,0,150 +67.31,50.42079558,-3.586810613,50,-17.31837179,10.00046042,0,0,0,150 +67.32,50.42079402,-3.586809206,50,-17.31489559,10.00134911,0,0,0,150 +67.33,50.42079247,-3.586807798,50,-17.31837179,10.00046107,0,0,0,150 +67.34,50.42079091,-3.586806391,50,-17.33227656,9.998462599,0,0,0,150 +67.35,50.42078935,-3.586804985,50,-17.33227656,9.998462928,0,0,0,150 +67.36,50.42078779,-3.586803578,50,-17.3183718,10.00046206,0,0,0,150 +67.37,50.42078624,-3.58680217,50,-17.3148956,10.00135075,0,0,0,150 +67.38,50.42078468,-3.586800763,50,-17.31837177,10.00046272,0,0,0,150 +67.39,50.42078312,-3.586799356,50,-17.31489557,9.999574686,0,0,0,150 +67.4,50.42078157,-3.586797949,50,-17.31489557,9.999352925,0,0,0,150 +67.41,50.42078001,-3.586796542,50,-17.31837177,9.999353253,0,0,0,150 +67.42,50.42077845,-3.586795135,50,-17.31489558,9.99957567,0,0,0,150 +67.43,50.4207769,-3.586793728,50,-17.31837177,10.00046435,0,0,0,150 +67.44,50.42077534,-3.586792321,50,-17.3322765,10.00135304,0,0,0,150 +67.45,50.42077378,-3.586790913,50,-17.33227648,10.0006871,0,0,0,150 +67.46,50.42077222,-3.586789506,50,-17.31837173,9.999354891,0,0,0,150 +67.47,50.42077067,-3.5867881,50,-17.31489555,9.999577309,0,0,0,150 +67.48,50.42076911,-3.586786692,50,-17.31837173,10.00046599,0,0,0,150 +67.49,50.42076755,-3.586785285,50,-17.31489554,10.00024423,0,0,0,150 +67.5,50.420766,-3.586783878,50,-17.31837174,9.999578293,0,0,0,150 +67.51,50.42076444,-3.586782471,50,-17.33227649,9.99935653,0,0,0,150 +67.52,50.42076288,-3.586781064,50,-17.33227648,9.999356858,0,0,0,150 +67.53,50.42076132,-3.586779657,50,-17.31837171,9.999357186,0,0,0,150 +67.54,50.42075977,-3.58677825,50,-17.31489551,9.999579603,0,0,0,150 +67.55,50.42075821,-3.586776843,50,-17.31837168,10.00046829,0,0,0,150 +67.56,50.42075665,-3.586775436,50,-17.3148955,10.00157906,0,0,0,150 +67.57,50.4207551,-3.586774028,50,-17.31489551,10.00157939,0,0,0,150 +67.58,50.42075354,-3.586772621,50,-17.3183717,10.00046927,0,0,0,150 +67.59,50.42075198,-3.586771214,50,-17.31489549,9.999581242,0,0,0,150 +67.6,50.42075043,-3.586769807,50,-17.31837166,9.999359481,0,0,0,150 +67.61,50.42074887,-3.5867684,50,-17.33227641,9.99935981,0,0,0,150 +67.62,50.42074731,-3.586766993,50,-17.33227641,9.999582227,0,0,0,150 +67.63,50.42074575,-3.586765586,50,-17.31837167,10.00024882,0,0,0,150 +67.64,50.4207442,-3.586764179,50,-17.31489548,10.00047124,0,0,0,150 +67.65,50.42074264,-3.586762771,50,-17.31837167,9.999583208,0,0,0,150 +67.66,50.42074108,-3.586761365,50,-17.31489547,9.999361447,0,0,0,150 +67.67,50.42073953,-3.586759958,50,-17.31837164,10.00069431,0,0,0,150 +67.68,50.42073797,-3.58675855,50,-17.33227637,10.00136091,0,0,0,150 +67.69,50.42073641,-3.586757143,50,-17.33227637,10.00047288,0,0,0,150 +67.7,50.42073485,-3.586755736,50,-17.31837163,9.999584849,0,0,0,150 +67.71,50.4207333,-3.586754329,50,-17.31489545,9.999363088,0,0,0,150 +67.72,50.42073174,-3.586752922,50,-17.31837163,9.999363416,0,0,0,150 +67.73,50.42073018,-3.586751515,50,-17.31489544,9.999363743,0,0,0,150 +67.74,50.42072863,-3.586750108,50,-17.31489544,9.99958616,0,0,0,150 +67.75,50.42072707,-3.586748701,50,-17.31837161,10.00025276,0,0,0,150 +67.76,50.42072551,-3.586747294,50,-17.3148954,10.00047517,0,0,0,150 +67.77,50.42072396,-3.586745886,50,-17.31837158,9.999587143,0,0,0,150 +67.78,50.4207224,-3.58674448,50,-17.33227634,9.999365381,0,0,0,150 +67.79,50.42072084,-3.586743073,50,-17.33227635,10.00069825,0,0,0,150 +67.8,50.42071928,-3.586741665,50,-17.31837159,10.00136485,0,0,0,150 +67.81,50.42071773,-3.586740258,50,-17.31489541,10.00047681,0,0,0,150 +67.82,50.42071617,-3.586738851,50,-17.31837159,9.999588782,0,0,0,150 +67.83,50.42071461,-3.586737444,50,-17.31489537,9.99936702,0,0,0,150 +67.84,50.42071306,-3.586736037,50,-17.31837154,9.999367348,0,0,0,150 +67.85,50.4207115,-3.58673463,50,-17.3322763,9.999367676,0,0,0,150 +67.86,50.42070994,-3.586733223,50,-17.33227631,9.999590094,0,0,0,150 +67.87,50.42070838,-3.586731816,50,-17.31837156,10.00025669,0,0,0,150 +67.88,50.42070683,-3.586730409,50,-17.31489537,10.00047911,0,0,0,150 +67.89,50.42070527,-3.586729001,50,-17.31837155,9.999591077,0,0,0,150 +67.9,50.42070371,-3.586727595,50,-17.31489535,9.999369316,0,0,0,150 +67.91,50.42070216,-3.586726188,50,-17.31489533,10.00070218,0,0,0,150 +67.92,50.4207006,-3.58672478,50,-17.31837151,10.00136878,0,0,0,150 +67.93,50.42069904,-3.586723373,50,-17.31489534,10.00048075,0,0,0,150 +67.94,50.42069749,-3.586721966,50,-17.31837153,9.999592715,0,0,0,150 +67.95,50.42069593,-3.586720559,50,-17.33227627,9.999370954,0,0,0,150 +67.96,50.42069437,-3.586719152,50,-17.33227627,9.999371282,0,0,0,150 +67.97,50.42069281,-3.586717745,50,-17.31837152,9.999593701,0,0,0,150 +67.98,50.42069126,-3.586716338,50,-17.31489531,10.00048239,0,0,0,150 +67.99,50.4206897,-3.586714931,50,-17.31837148,10.00137107,0,0,0,150 +68,50.42068814,-3.586713523,50,-17.31489528,10.00070513,0,0,0,150 +68.01,50.42068659,-3.586712116,50,-17.31837149,9.999372921,0,0,0,150 +68.02,50.42068503,-3.58671071,50,-17.33227625,9.99959534,0,0,0,150 +68.03,50.42068347,-3.586709302,50,-17.33227624,10.00048403,0,0,0,150 +68.04,50.42068191,-3.586707895,50,-17.31837147,10.00026226,0,0,0,150 +68.05,50.42068036,-3.586706488,50,-17.31489528,9.999596323,0,0,0,150 +68.06,50.4206788,-3.586705081,50,-17.31837145,9.999374561,0,0,0,150 +68.07,50.42067724,-3.586703674,50,-17.31489525,9.999374888,0,0,0,150 +68.08,50.42067569,-3.586702267,50,-17.31837145,9.999375216,0,0,0,150 +68.09,50.42067413,-3.58670086,50,-17.33227621,9.999597635,0,0,0,150 +68.1,50.42067257,-3.586699453,50,-17.33227621,10.00048632,0,0,0,150 +68.11,50.42067101,-3.586698046,50,-17.31837144,10.00137501,0,0,0,150 +68.12,50.42066946,-3.586696638,50,-17.31489525,10.00070907,0,0,0,150 +68.13,50.4206679,-3.586695231,50,-17.31837144,9.999376855,0,0,0,150 +68.14,50.42066634,-3.586693825,50,-17.31489524,9.999599273,0,0,0,150 +68.15,50.42066479,-3.586692417,50,-17.31489521,10.00048796,0,0,0,150 +68.16,50.42066323,-3.58669101,50,-17.3183714,10.0002662,0,0,0,150 +68.17,50.42066167,-3.586689603,50,-17.31489522,9.999600257,0,0,0,150 +68.18,50.42066012,-3.586688196,50,-17.31837142,9.999378495,0,0,0,150 +68.19,50.42065856,-3.586686789,50,-17.33227616,9.999378822,0,0,0,150 +68.2,50.420657,-3.586685382,50,-17.33227615,9.99937915,0,0,0,150 +68.21,50.42065544,-3.586683975,50,-17.31837139,9.999601568,0,0,0,150 +68.22,50.42065389,-3.586682568,50,-17.31489519,10.00049026,0,0,0,150 +68.23,50.42065233,-3.586681161,50,-17.31837137,10.00137894,0,0,0,150 +68.24,50.42065077,-3.586679753,50,-17.31489518,10.000713,0,0,0,150 +68.25,50.42064922,-3.586678346,50,-17.31837138,9.999380789,0,0,0,150 +68.26,50.42064766,-3.58667694,50,-17.33227614,9.999603206,0,0,0,150 +68.27,50.4206461,-3.586675532,50,-17.33227612,10.00049189,0,0,0,150 +68.28,50.42064454,-3.586674125,50,-17.31837135,10.00027013,0,0,0,150 +68.29,50.42064299,-3.586672718,50,-17.31489516,9.999604192,0,0,0,150 +68.3,50.42064143,-3.586671311,50,-17.31837134,9.999382429,0,0,0,150 +68.31,50.42063987,-3.586669904,50,-17.31489515,9.999382756,0,0,0,150 +68.32,50.42063832,-3.586668497,50,-17.31489515,9.999605173,0,0,0,150 +68.33,50.42063676,-3.58666709,50,-17.31837135,10.00049386,0,0,0,150 +68.34,50.4206352,-3.586665683,50,-17.31489516,10.00138255,0,0,0,150 +68.35,50.42063365,-3.586664275,50,-17.31837133,10.00071661,0,0,0,150 +68.36,50.42063209,-3.586662868,50,-17.33227607,9.999384395,0,0,0,150 +68.37,50.42063053,-3.586661462,50,-17.33227606,9.999606813,0,0,0,150 +68.38,50.42062897,-3.586660054,50,-17.3183713,10.0004955,0,0,0,150 +68.39,50.42062742,-3.586658647,50,-17.31489511,10.00027374,0,0,0,150 +68.4,50.42062586,-3.58665724,50,-17.31837131,9.999607798,0,0,0,150 +68.41,50.4206243,-3.586655833,50,-17.31489512,9.999386035,0,0,0,150 +68.42,50.42062275,-3.586654426,50,-17.31837131,9.999386362,0,0,0,150 +68.43,50.42062119,-3.586653019,50,-17.33227604,9.999386689,0,0,0,150 +68.44,50.42061963,-3.586651612,50,-17.33227602,9.999609107,0,0,0,150 +68.45,50.42061807,-3.586650205,50,-17.31837127,10.0004978,0,0,0,150 +68.46,50.42061652,-3.586648798,50,-17.31489509,10.00138649,0,0,0,150 +68.47,50.42061496,-3.58664739,50,-17.31837127,10.00072054,0,0,0,150 +68.48,50.4206134,-3.586645983,50,-17.31489508,9.999388331,0,0,0,150 +68.49,50.42061185,-3.586644577,50,-17.31489509,9.999610748,0,0,0,150 +68.5,50.42061029,-3.586643169,50,-17.31837127,10.00049944,0,0,0,150 +68.51,50.42060873,-3.586641762,50,-17.31489506,10.00027767,0,0,0,150 +68.52,50.42060718,-3.586640355,50,-17.31837123,9.99961173,0,0,0,150 +68.53,50.42060562,-3.586638948,50,-17.33227599,9.999389968,0,0,0,150 +68.54,50.42060406,-3.586637541,50,-17.332276,9.999390296,0,0,0,150 +68.55,50.4206025,-3.586636134,50,-17.31837124,9.999612715,0,0,0,150 +68.56,50.42060095,-3.586634727,50,-17.31489504,10.0005014,0,0,0,150 +68.57,50.42059939,-3.58663332,50,-17.31837124,10.00161218,0,0,0,150 +68.58,50.42059783,-3.586631912,50,-17.31489504,10.00139042,0,0,0,150 +68.59,50.42059628,-3.586630505,50,-17.31837121,9.999614025,0,0,0,150 +68.6,50.42059472,-3.586629098,50,-17.33227595,9.998503903,0,0,0,150 +68.61,50.42059316,-3.586627692,50,-17.33227595,9.999392592,0,0,0,150 +68.62,50.4205916,-3.586626284,50,-17.3183712,10.00050337,0,0,0,150 +68.63,50.42059005,-3.586624877,50,-17.31489501,10.00028161,0,0,0,150 +68.64,50.42058849,-3.58662347,50,-17.3183712,9.999615664,0,0,0,150 +68.65,50.42058693,-3.586622063,50,-17.31489501,9.999393902,0,0,0,150 +68.66,50.42058538,-3.586620656,50,-17.314895,9.999394231,0,0,0,150 +68.67,50.42058382,-3.586619249,50,-17.31837116,9.99961665,0,0,0,150 +68.68,50.42058226,-3.586617842,50,-17.31489497,10.00050534,0,0,0,150 +68.69,50.42058071,-3.586616435,50,-17.31837117,10.00139403,0,0,0,150 +68.7,50.42057915,-3.586615027,50,-17.33227593,10.00072808,0,0,0,150 +68.71,50.42057759,-3.58661362,50,-17.33227592,9.999395869,0,0,0,150 +68.72,50.42057603,-3.586612214,50,-17.31837116,9.999618288,0,0,0,150 +68.73,50.42057448,-3.586610806,50,-17.31489497,10.00050698,0,0,0,150 +68.74,50.42057292,-3.586609399,50,-17.31837115,10.00028521,0,0,0,150 +68.75,50.42057136,-3.586607992,50,-17.31489493,9.99961927,0,0,0,150 +68.76,50.42056981,-3.586606585,50,-17.31837112,9.999397508,0,0,0,150 +68.77,50.42056825,-3.586605178,50,-17.33227589,9.999397837,0,0,0,150 +68.78,50.42056669,-3.586603771,50,-17.33227589,9.999398166,0,0,0,150 +68.79,50.42056513,-3.586602364,50,-17.31837113,9.999620583,0,0,0,150 +68.8,50.42056358,-3.586600957,50,-17.31489493,10.00050927,0,0,0,150 +68.81,50.42056202,-3.58659955,50,-17.31837112,10.00139796,0,0,0,150 +68.82,50.42056046,-3.586598142,50,-17.31489492,10.00073202,0,0,0,150 +68.83,50.42055891,-3.586596735,50,-17.31837109,9.999399803,0,0,0,150 +68.84,50.42055735,-3.586595329,50,-17.33227584,9.999622221,0,0,0,150 +68.85,50.42055579,-3.586593921,50,-17.33227585,10.00051091,0,0,0,150 +68.86,50.42055423,-3.586592514,50,-17.3183711,10.00028915,0,0,0,150 +68.87,50.42055268,-3.586591107,50,-17.3148949,9.999623205,0,0,0,150 +68.88,50.42055112,-3.5865897,50,-17.31837108,9.999401442,0,0,0,150 +68.89,50.42054956,-3.586588293,50,-17.31489489,9.999401771,0,0,0,150 +68.9,50.42054801,-3.586586886,50,-17.31489487,9.999624189,0,0,0,150 +68.91,50.42054645,-3.586585479,50,-17.31837105,10.00051288,0,0,0,150 +68.92,50.42054489,-3.586584072,50,-17.31489487,10.00140157,0,0,0,150 +68.93,50.42054334,-3.586582664,50,-17.31837107,10.00073562,0,0,0,150 +68.94,50.42054178,-3.586581257,50,-17.33227582,9.999403409,0,0,0,150 +68.95,50.42054022,-3.586579851,50,-17.33227581,9.999625828,0,0,0,150 +68.96,50.42053866,-3.586578443,50,-17.31837104,10.00051452,0,0,0,150 +68.97,50.42053711,-3.586577036,50,-17.31489485,10.00029276,0,0,0,150 +68.98,50.42053555,-3.586575629,50,-17.31837102,9.999626812,0,0,0,150 +68.99,50.42053399,-3.586574222,50,-17.31489482,9.999405048,0,0,0,150 +69,50.42053244,-3.586572815,50,-17.31837102,9.999405376,0,0,0,150 +69.01,50.42053088,-3.586571408,50,-17.33227579,9.999405704,0,0,0,150 +69.02,50.42052932,-3.586570001,50,-17.33227578,9.999628122,0,0,0,150 +69.03,50.42052776,-3.586568594,50,-17.31837101,10.00029472,0,0,0,150 +69.04,50.42052621,-3.586567187,50,-17.31489481,10.00051714,0,0,0,150 +69.05,50.42052465,-3.586565779,50,-17.31837099,9.999629107,0,0,0,150 +69.06,50.42052309,-3.586564373,50,-17.3148948,9.999407343,0,0,0,150 +69.07,50.42052154,-3.586562966,50,-17.3148948,10.00074021,0,0,0,150 +69.08,50.42051998,-3.586561558,50,-17.31837099,10.00140681,0,0,0,150 +69.09,50.42051842,-3.586560151,50,-17.31489481,10.00051878,0,0,0,150 +69.1,50.42051687,-3.586558744,50,-17.31837099,9.999630745,0,0,0,150 +69.11,50.42051531,-3.586557337,50,-17.33227573,9.999408981,0,0,0,150 +69.12,50.42051375,-3.58655593,50,-17.33227572,9.999409309,0,0,0,150 +69.13,50.42051219,-3.586554523,50,-17.31837095,9.999409638,0,0,0,150 +69.14,50.42051064,-3.586553116,50,-17.31489476,9.999632057,0,0,0,150 +69.15,50.42050908,-3.586551709,50,-17.31837095,10.00029866,0,0,0,150 +69.16,50.42050752,-3.586550302,50,-17.31489476,10.00052108,0,0,0,150 +69.17,50.42050597,-3.586548894,50,-17.31837096,9.99963304,0,0,0,150 +69.18,50.42050441,-3.586547488,50,-17.33227571,9.999411277,0,0,0,150 +69.19,50.42050285,-3.586546081,50,-17.3322757,10.00074415,0,0,0,150 +69.2,50.42050129,-3.586544673,50,-17.31837094,10.00141075,0,0,0,150 +69.21,50.42049974,-3.586543266,50,-17.31489473,10.00052271,0,0,0,150 +69.22,50.42049818,-3.586541859,50,-17.3183709,9.999634679,0,0,0,150 +69.23,50.42049662,-3.586540452,50,-17.31489471,9.999412917,0,0,0,150 +69.24,50.42049507,-3.586539045,50,-17.31837091,9.999413245,0,0,0,150 +69.25,50.42049351,-3.586537638,50,-17.33227568,9.999635663,0,0,0,150 +69.26,50.42049195,-3.586536231,50,-17.33227567,10.00030226,0,0,0,150 +69.27,50.42049039,-3.586534824,50,-17.31837089,10.00052468,0,0,0,150 +69.28,50.42048884,-3.586533416,50,-17.31489469,9.999636646,0,0,0,150 +69.29,50.42048728,-3.58653201,50,-17.31837088,9.999414883,0,0,0,150 +69.3,50.42048572,-3.586530603,50,-17.3148947,10.00074776,0,0,0,150 +69.31,50.42048417,-3.586529195,50,-17.31489469,10.00141436,0,0,0,150 +69.32,50.42048261,-3.586527788,50,-17.31837088,10.00052632,0,0,0,150 +69.33,50.42048105,-3.586526381,50,-17.31489469,9.999638285,0,0,0,150 +69.34,50.4204795,-3.586524974,50,-17.31837088,9.999416523,0,0,0,150 +69.35,50.42047794,-3.586523567,50,-17.33227561,9.999416851,0,0,0,150 +69.36,50.42047638,-3.58652216,50,-17.33227559,9.999417179,0,0,0,150 +69.37,50.42047482,-3.586520753,50,-17.31837084,9.999417506,0,0,0,150 +69.38,50.42047327,-3.586519346,50,-17.31489466,9.999417833,0,0,0,150 +69.39,50.42047171,-3.586517939,50,-17.31837085,9.99941816,0,0,0,150 +69.4,50.42047015,-3.586516532,50,-17.31489466,9.99964058,0,0,0,150 +69.41,50.4204686,-3.586515125,50,-17.31837084,10.00052927,0,0,0,150 +69.42,50.42046704,-3.586513718,50,-17.33227557,10.00164005,0,0,0,150 +69.43,50.42046548,-3.58651231,50,-17.33227555,10.00164038,0,0,0,150 +69.44,50.42046392,-3.586510903,50,-17.3183708,10.00053025,0,0,0,150 +69.45,50.42046237,-3.586509496,50,-17.31489463,9.99964222,0,0,0,150 +69.46,50.42046081,-3.586508089,50,-17.31837082,9.999420458,0,0,0,150 +69.47,50.42045925,-3.586506682,50,-17.31489463,9.999420785,0,0,0,150 +69.48,50.4204577,-3.586505275,50,-17.31489463,9.999421112,0,0,0,150 +69.49,50.42045614,-3.586503868,50,-17.31837081,9.999421439,0,0,0,150 +69.5,50.42045458,-3.586502461,50,-17.31489459,9.999421766,0,0,0,150 +69.51,50.42045303,-3.586501054,50,-17.31837076,9.999422095,0,0,0,150 +69.52,50.42045147,-3.586499647,50,-17.33227552,9.999644515,0,0,0,150 +69.53,50.42044991,-3.58649824,50,-17.33227553,10.00053321,0,0,0,150 +69.54,50.42044835,-3.586496833,50,-17.31837079,10.0014219,0,0,0,150 +69.55,50.4204468,-3.586495425,50,-17.31489459,10.00075595,0,0,0,150 +69.56,50.42044524,-3.586494018,50,-17.31837078,9.999423734,0,0,0,150 +69.57,50.42044368,-3.586492612,50,-17.31489458,9.999646153,0,0,0,150 +69.58,50.42044213,-3.586491204,50,-17.31837074,10.00053484,0,0,0,150 +69.59,50.42044057,-3.586489797,50,-17.33227548,10.00031308,0,0,0,150 +69.6,50.42043901,-3.58648839,50,-17.33227548,9.999647137,0,0,0,150 +69.61,50.42043745,-3.586486983,50,-17.31837074,9.999425374,0,0,0,150 +69.62,50.4204359,-3.586485576,50,-17.31489456,9.999425701,0,0,0,150 +69.63,50.42043434,-3.586484169,50,-17.31837074,9.99964812,0,0,0,150 +69.64,50.42043278,-3.586482762,50,-17.31489455,10.00053681,0,0,0,150 +69.65,50.42043123,-3.586481355,50,-17.31489453,10.00142551,0,0,0,150 +69.66,50.42042967,-3.586479947,50,-17.3183707,10.00075956,0,0,0,150 +69.67,50.42042811,-3.58647854,50,-17.31489451,9.99942734,0,0,0,150 +69.68,50.42042656,-3.586477134,50,-17.31837071,9.999649759,0,0,0,150 +69.69,50.420425,-3.586475726,50,-17.33227547,10.00053845,0,0,0,150 +69.7,50.42042344,-3.586474319,50,-17.33227546,10.00031669,0,0,0,150 +69.71,50.42042188,-3.586472912,50,-17.3183707,9.999650743,0,0,0,150 +69.72,50.42042033,-3.586471505,50,-17.31489451,9.999428981,0,0,0,150 +69.73,50.42041877,-3.586470098,50,-17.31837069,9.999429309,0,0,0,150 +69.74,50.42041721,-3.586468691,50,-17.31489447,9.999429636,0,0,0,150 +69.75,50.42041566,-3.586467284,50,-17.31837066,9.999652054,0,0,0,150 +69.76,50.4204141,-3.586465877,50,-17.33227543,10.00031865,0,0,0,150 +69.77,50.42041254,-3.58646447,50,-17.33227543,10.00054107,0,0,0,150 +69.78,50.42041098,-3.586463062,50,-17.31837066,9.999653038,0,0,0,150 +69.79,50.42040943,-3.586461656,50,-17.31489447,9.999431274,0,0,0,150 +69.8,50.42040787,-3.586460249,50,-17.31837066,10.00076415,0,0,0,150 +69.81,50.42040631,-3.586458841,50,-17.31489446,10.00143075,0,0,0,150 +69.82,50.42040476,-3.586457434,50,-17.31489444,10.00054271,0,0,0,150 +69.83,50.4204032,-3.586456027,50,-17.31837062,9.999654677,0,0,0,150 +69.84,50.42040164,-3.58645462,50,-17.31489445,9.999432915,0,0,0,150 +69.85,50.42040009,-3.586453213,50,-17.31837064,9.999433242,0,0,0,150 +69.86,50.42039853,-3.586451806,50,-17.33227538,9.999433569,0,0,0,150 +69.87,50.42039697,-3.586450399,50,-17.33227538,9.999433896,0,0,0,150 +69.88,50.42039541,-3.586448992,50,-17.31837062,9.999434224,0,0,0,150 +69.89,50.42039386,-3.586447585,50,-17.31489441,9.999434552,0,0,0,150 +69.9,50.4203923,-3.586446178,50,-17.31837059,9.999656972,0,0,0,150 +69.91,50.42039074,-3.586444771,50,-17.3148944,10.00054567,0,0,0,150 +69.92,50.42038919,-3.586443364,50,-17.31837061,10.00143436,0,0,0,150 +69.93,50.42038763,-3.586441956,50,-17.33227536,10.00076841,0,0,0,150 +69.94,50.42038607,-3.586440549,50,-17.33227535,9.999436192,0,0,0,150 +69.95,50.42038451,-3.586439143,50,-17.31837058,9.999658612,0,0,0,150 +69.96,50.42038296,-3.586437735,50,-17.31489439,10.0005473,0,0,0,150 +69.97,50.4203814,-3.586436328,50,-17.31837056,10.00032554,0,0,0,150 +69.98,50.42037984,-3.586434921,50,-17.31489436,9.999659594,0,0,0,150 +69.99,50.42037829,-3.586433514,50,-17.31489437,9.999437831,0,0,0,150 +70,50.42037673,-3.586432107,50,-17.31837057,9.999438158,0,0,0,150 +70.01,50.42037517,-3.5864307,50,-17.31489438,9.999660577,0,0,0,150 +70.02,50.42037362,-3.586429293,50,-17.31837055,10.00054927,0,0,0,150 +70.03,50.42037206,-3.586427886,50,-17.33227529,10.00143796,0,0,0,150 +70.04,50.4203705,-3.586426478,50,-17.33227529,10.00077202,0,0,0,150 +70.05,50.42036894,-3.586425071,50,-17.31837053,9.999439798,0,0,0,150 +70.06,50.42036739,-3.586423665,50,-17.31489433,9.999662217,0,0,0,150 +70.07,50.42036583,-3.586422257,50,-17.31837053,10.00055091,0,0,0,150 +70.08,50.42036427,-3.58642085,50,-17.31489435,10.00032915,0,0,0,150 +70.09,50.42036272,-3.586419443,50,-17.31837053,9.9996632,0,0,0,150 +70.1,50.42036116,-3.586418036,50,-17.33227526,9.999441437,0,0,0,150 +70.11,50.4203596,-3.586416629,50,-17.33227524,9.999441765,0,0,0,150 +70.12,50.42035804,-3.586415222,50,-17.31837049,9.999442093,0,0,0,150 +70.13,50.42035649,-3.586413815,50,-17.31489431,9.999664512,0,0,0,150 +70.14,50.42035493,-3.586412408,50,-17.31837049,10.00033111,0,0,0,150 +70.15,50.42035337,-3.586411001,50,-17.3148943,10.00055353,0,0,0,150 +70.16,50.42035182,-3.586409593,50,-17.31489431,9.999665495,0,0,0,150 +70.17,50.42035026,-3.586408187,50,-17.31837049,9.999443731,0,0,0,150 +70.18,50.4203487,-3.58640678,50,-17.31489429,10.00077661,0,0,0,150 +70.19,50.42034715,-3.586405372,50,-17.31837046,10.00144321,0,0,0,150 +70.2,50.42034559,-3.586403965,50,-17.33227521,10.00055517,0,0,0,150 +70.21,50.42034403,-3.586402558,50,-17.33227521,9.999667135,0,0,0,150 +70.22,50.42034247,-3.586401151,50,-17.31837045,9.999445371,0,0,0,150 +70.23,50.42034092,-3.586399744,50,-17.31489426,9.999445698,0,0,0,150 +70.24,50.42033936,-3.586398337,50,-17.31837046,9.999446026,0,0,0,150 +70.25,50.4203378,-3.58639693,50,-17.31489426,9.999446354,0,0,0,150 +70.26,50.42033625,-3.586395523,50,-17.31837043,9.999446682,0,0,0,150 +70.27,50.42033469,-3.586394116,50,-17.33227517,9.99944701,0,0,0,150 +70.28,50.42033313,-3.586392709,50,-17.33227517,9.99966943,0,0,0,150 +70.29,50.42033157,-3.586391302,50,-17.31837043,10.00055812,0,0,0,150 +70.3,50.42033002,-3.586389895,50,-17.31489423,10.00144682,0,0,0,150 +70.31,50.42032846,-3.586388487,50,-17.31837042,10.00078087,0,0,0,150 +70.32,50.4203269,-3.58638708,50,-17.31489423,9.999448649,0,0,0,150 +70.33,50.42032535,-3.586385674,50,-17.31837042,9.999671068,0,0,0,150 +70.34,50.42032379,-3.586384266,50,-17.33227515,10.00055976,0,0,0,150 +70.35,50.42032223,-3.586382859,50,-17.33227513,10.000338,0,0,0,150 +70.36,50.42032067,-3.586381452,50,-17.31837038,9.999672053,0,0,0,150 +70.37,50.42031912,-3.586380045,50,-17.3148942,9.999450289,0,0,0,150 +70.38,50.42031756,-3.586378638,50,-17.31837038,9.999450616,0,0,0,150 +70.39,50.420316,-3.586377231,50,-17.31489419,9.999673035,0,0,0,150 +70.4,50.42031445,-3.586375824,50,-17.3148942,10.00056173,0,0,0,150 +70.41,50.42031289,-3.586374417,50,-17.31837038,10.00145042,0,0,0,150 +70.42,50.42031133,-3.586373009,50,-17.31489417,10.00078448,0,0,0,150 +70.43,50.42030978,-3.586371602,50,-17.31837034,9.999452254,0,0,0,150 +70.44,50.42030822,-3.586370196,50,-17.3322751,9.999674673,0,0,0,150 +70.45,50.42030666,-3.586368788,50,-17.33227511,10.00056337,0,0,0,150 +70.46,50.4203051,-3.586367381,50,-17.31837035,10.0003416,0,0,0,150 +70.47,50.42030355,-3.586365974,50,-17.31489415,9.999675659,0,0,0,150 +70.48,50.42030199,-3.586364567,50,-17.31837035,9.999453895,0,0,0,150 +70.49,50.42030043,-3.58636316,50,-17.31489414,9.999454223,0,0,0,150 +70.5,50.42029888,-3.586361753,50,-17.31837031,9.999454549,0,0,0,150 +70.51,50.42029732,-3.586360346,50,-17.33227506,9.999676968,0,0,0,150 +70.52,50.42029576,-3.586358939,50,-17.33227507,10.00034357,0,0,0,150 +70.53,50.4202942,-3.586357532,50,-17.31837032,10.00056599,0,0,0,150 +70.54,50.42029265,-3.586356124,50,-17.31489412,9.999677953,0,0,0,150 +70.55,50.42029109,-3.586354718,50,-17.31837031,9.999456189,0,0,0,150 +70.56,50.42028953,-3.586353311,50,-17.31489412,10.00078907,0,0,0,150 +70.57,50.42028798,-3.586351903,50,-17.31837029,10.00145567,0,0,0,150 +70.58,50.42028642,-3.586350496,50,-17.33227502,10.00056763,0,0,0,150 +70.59,50.42028486,-3.586349089,50,-17.33227502,9.999679593,0,0,0,150 +70.6,50.4202833,-3.586347682,50,-17.31837028,9.999457829,0,0,0,150 +70.61,50.42028175,-3.586346275,50,-17.3148941,9.999458156,0,0,0,150 +70.62,50.42028019,-3.586344868,50,-17.31837027,9.999458483,0,0,0,150 +70.63,50.42027863,-3.586343461,50,-17.31489408,9.999458811,0,0,0,150 +70.64,50.42027708,-3.586342054,50,-17.31489407,9.999459139,0,0,0,150 +70.65,50.42027552,-3.586340647,50,-17.31837025,9.999459468,0,0,0,150 +70.66,50.42027396,-3.58633924,50,-17.31489404,9.999681888,0,0,0,150 +70.67,50.42027241,-3.586337833,50,-17.31837024,10.00057058,0,0,0,150 +70.68,50.42027085,-3.586336426,50,-17.33227501,10.00145928,0,0,0,150 +70.69,50.42026929,-3.586335018,50,-17.332275,10.00079333,0,0,0,150 +70.7,50.42026773,-3.586333611,50,-17.31837023,9.999461106,0,0,0,150 +70.71,50.42026618,-3.586332205,50,-17.31489403,9.999683527,0,0,0,150 +70.72,50.42026462,-3.586330797,50,-17.31837021,10.00057222,0,0,0,150 +70.73,50.42026306,-3.58632939,50,-17.31489402,10.00035046,0,0,0,150 +70.74,50.42026151,-3.586327983,50,-17.31837021,9.999684509,0,0,0,150 +70.75,50.42025995,-3.586326576,50,-17.33227497,9.999462745,0,0,0,150 +70.76,50.42025839,-3.586325169,50,-17.33227497,9.999463073,0,0,0,150 +70.77,50.42025683,-3.586323762,50,-17.31837021,9.999685494,0,0,0,150 +70.78,50.42025528,-3.586322355,50,-17.31489401,10.0003521,0,0,0,150 +70.79,50.42025372,-3.586320948,50,-17.31837019,10.00057452,0,0,0,150 +70.8,50.42025216,-3.58631954,50,-17.314894,9.999464384,0,0,0,150 +70.81,50.42025061,-3.586318134,50,-17.31489398,9.998576344,0,0,0,150 +70.82,50.42024905,-3.586316727,50,-17.31837016,9.999687131,0,0,0,150 +70.83,50.42024749,-3.58631532,50,-17.31489398,10.0012421,0,0,0,150 +70.84,50.42024594,-3.586313912,50,-17.31837018,10.00079825,0,0,0,150 +70.85,50.42024438,-3.586312505,50,-17.33227493,9.999466025,0,0,0,150 +70.86,50.42024282,-3.586311099,50,-17.33227492,9.999688445,0,0,0,150 +70.87,50.42024126,-3.586309691,50,-17.31837016,10.00057714,0,0,0,150 +70.88,50.42023971,-3.586308284,50,-17.31489395,10.00035537,0,0,0,150 +70.89,50.42023815,-3.586306877,50,-17.31837012,9.999689426,0,0,0,150 +70.9,50.42023659,-3.58630547,50,-17.31489393,9.999467662,0,0,0,150 +70.91,50.42023504,-3.586304063,50,-17.31837013,9.99946799,0,0,0,150 +70.92,50.42023348,-3.586302656,50,-17.3322749,9.999690411,0,0,0,150 +70.93,50.42023192,-3.586301249,50,-17.33227489,10.00057911,0,0,0,150 +70.94,50.42023036,-3.586299842,50,-17.31837011,10.0014678,0,0,0,150 +70.95,50.42022881,-3.586298434,50,-17.31489391,10.00080185,0,0,0,150 +70.96,50.42022725,-3.586297027,50,-17.3183701,9.999469631,0,0,0,150 +70.97,50.42022569,-3.586295621,50,-17.31489392,9.999692051,0,0,0,150 +70.98,50.42022414,-3.586294213,50,-17.31489391,10.00058075,0,0,0,150 +70.99,50.42022258,-3.586292806,50,-17.3183701,10.00035898,0,0,0,150 +71,50.42022102,-3.586291399,50,-17.31489392,9.999693032,0,0,0,150 +71.01,50.42021947,-3.586289992,50,-17.3183701,9.999471268,0,0,0,150 +71.02,50.42021791,-3.586288585,50,-17.33227483,9.999471596,0,0,0,150 +71.03,50.42021635,-3.586287178,50,-17.33227481,9.999471925,0,0,0,150 +71.04,50.42021479,-3.586285771,50,-17.31837006,9.999472254,0,0,0,150 +71.05,50.42021324,-3.586284364,50,-17.31489388,9.999472581,0,0,0,150 +71.06,50.42021168,-3.586282957,50,-17.31837008,9.999472908,0,0,0,150 +71.07,50.42021012,-3.58628155,50,-17.31489389,9.999695327,0,0,0,150 +71.08,50.42020857,-3.586280143,50,-17.31837007,10.00058402,0,0,0,150 +71.09,50.42020701,-3.586278736,50,-17.3322748,10.00147272,0,0,0,150 +71.1,50.42020545,-3.586277328,50,-17.33227477,10.00080677,0,0,0,150 +71.11,50.42020389,-3.586275921,50,-17.31837002,9.999474548,0,0,0,150 +71.12,50.42020234,-3.586274515,50,-17.31489385,9.999696967,0,0,0,150 +71.13,50.42020078,-3.586273107,50,-17.31837004,10.00058566,0,0,0,150 +71.14,50.42019922,-3.5862717,50,-17.31489385,10.0003639,0,0,0,150 +71.15,50.42019767,-3.586270293,50,-17.31489385,9.999697951,0,0,0,150 +71.16,50.42019611,-3.586268886,50,-17.31837003,9.999476187,0,0,0,150 +71.17,50.42019455,-3.586267479,50,-17.31489382,9.999476514,0,0,0,150 +71.18,50.420193,-3.586266072,50,-17.31836998,9.999476841,0,0,0,150 +71.19,50.42019144,-3.586264665,50,-17.33227474,9.999699261,0,0,0,150 +71.2,50.42018988,-3.586263258,50,-17.33227476,10.00036587,0,0,0,150 +71.21,50.42018832,-3.586261851,50,-17.31837001,10.00058829,0,0,0,150 +71.22,50.42018677,-3.586260443,50,-17.31489381,9.999700246,0,0,0,150 +71.23,50.42018521,-3.586259037,50,-17.31837,9.999478482,0,0,0,150 +71.24,50.42018365,-3.58625763,50,-17.3148938,10.00081136,0,0,0,150 +71.25,50.4201821,-3.586256222,50,-17.31836997,10.00147797,0,0,0,150 +71.26,50.42018054,-3.586254815,50,-17.3322747,10.00058992,0,0,0,150 +71.27,50.42017898,-3.586253408,50,-17.3322747,9.999701884,0,0,0,150 +71.28,50.42017742,-3.586252001,50,-17.31836996,9.99948012,0,0,0,150 +71.29,50.42017587,-3.586250594,50,-17.31489378,9.999480448,0,0,0,150 +71.3,50.42017431,-3.586249187,50,-17.31836997,9.999480776,0,0,0,150 +71.31,50.42017275,-3.58624778,50,-17.31489377,9.999481104,0,0,0,150 +71.32,50.4201712,-3.586246373,50,-17.31489376,9.999481431,0,0,0,150 +71.33,50.42016964,-3.586244966,50,-17.31836992,9.999703851,0,0,0,150 +71.34,50.42016808,-3.586243559,50,-17.31489373,10.00059255,0,0,0,150 +71.35,50.42016653,-3.586242152,50,-17.31836993,10.00148125,0,0,0,150 +71.36,50.42016497,-3.586240744,50,-17.33227469,10.0008153,0,0,0,150 +71.37,50.42016341,-3.586239337,50,-17.33227468,9.99948307,0,0,0,150 +71.38,50.42016185,-3.586237931,50,-17.31836992,9.99970549,0,0,0,150 +71.39,50.4201603,-3.586236523,50,-17.31489373,10.00059419,0,0,0,150 +71.4,50.42015874,-3.586235116,50,-17.31836992,10.00037242,0,0,0,150 +71.41,50.42015718,-3.586233709,50,-17.31489371,9.999706474,0,0,0,150 +71.42,50.42015563,-3.586232302,50,-17.31836988,9.99948471,0,0,0,150 +71.43,50.42015407,-3.586230895,50,-17.33227464,9.999485037,0,0,0,150 +71.44,50.42015251,-3.586229488,50,-17.33227464,9.999485365,0,0,0,150 +71.45,50.42015095,-3.586228081,50,-17.31836988,9.999707785,0,0,0,150 +71.46,50.4201494,-3.586226674,50,-17.31489369,10.00037439,0,0,0,150 +71.47,50.42014784,-3.586225267,50,-17.31836988,10.00059681,0,0,0,150 +71.48,50.42014628,-3.586223859,50,-17.31489368,9.999708769,0,0,0,150 +71.49,50.42014473,-3.586222453,50,-17.31489366,9.999487005,0,0,0,150 +71.5,50.42014317,-3.586221046,50,-17.31836984,10.00081989,0,0,0,150 +71.51,50.42014161,-3.586219638,50,-17.31489367,10.00148649,0,0,0,150 +71.52,50.42014006,-3.586218231,50,-17.31836986,10.00059845,0,0,0,150 +71.53,50.4201385,-3.586216824,50,-17.3322746,9.999710408,0,0,0,150 +71.54,50.42013694,-3.586215417,50,-17.3322746,9.999488643,0,0,0,150 +71.55,50.42013538,-3.58621401,50,-17.31836984,9.999488971,0,0,0,150 +71.56,50.42013383,-3.586212603,50,-17.31489363,9.999489299,0,0,0,150 +71.57,50.42013227,-3.586211196,50,-17.31836981,9.999489627,0,0,0,150 +71.58,50.42013071,-3.586209789,50,-17.31489363,9.999489954,0,0,0,150 +71.59,50.42012916,-3.586208382,50,-17.31836983,9.999490283,0,0,0,150 +71.6,50.4201276,-3.586206975,50,-17.33227458,9.999712703,0,0,0,150 +71.61,50.42012604,-3.586205568,50,-17.33227457,10.00037931,0,0,0,150 +71.62,50.42012448,-3.586204161,50,-17.31836981,10.00060173,0,0,0,150 +71.63,50.42012293,-3.586202753,50,-17.31489361,9.999713686,0,0,0,150 +71.64,50.42012137,-3.586201347,50,-17.31836978,9.99949192,0,0,0,150 +71.65,50.42011981,-3.58619994,50,-17.31489358,10.0008248,0,0,0,150 +71.66,50.42011826,-3.586198532,50,-17.31836978,10.00149141,0,0,0,150 +71.67,50.4201167,-3.586197125,50,-17.33227455,10.00060337,0,0,0,150 +71.68,50.42011514,-3.586195718,50,-17.33227454,9.999715327,0,0,0,150 +71.69,50.42011358,-3.586194311,50,-17.31836977,9.999493562,0,0,0,150 +71.7,50.42011203,-3.586192904,50,-17.31489357,9.999493888,0,0,0,150 +71.71,50.42011047,-3.586191497,50,-17.31836975,9.999494216,0,0,0,150 +71.72,50.42010891,-3.58619009,50,-17.31489356,9.999494543,0,0,0,150 +71.73,50.42010736,-3.586188683,50,-17.31489356,9.999494872,0,0,0,150 +71.74,50.4201058,-3.586187276,50,-17.31836975,9.999717293,0,0,0,150 +71.75,50.42010424,-3.586185869,50,-17.31489357,10.00060599,0,0,0,150 +71.76,50.42010269,-3.586184462,50,-17.31836975,10.00149469,0,0,0,150 +71.77,50.42010113,-3.586183054,50,-17.33227449,10.00060665,0,0,0,150 +71.78,50.42009957,-3.586181647,50,-17.33227448,9.998608141,0,0,0,150 +71.79,50.42009801,-3.586180241,50,-17.31836972,9.998608469,0,0,0,150 +71.8,50.42009646,-3.586178834,50,-17.31489352,10.00060763,0,0,0,150 +71.81,50.4200949,-3.586177426,50,-17.31836971,10.00149633,0,0,0,150 +71.82,50.42009334,-3.586176019,50,-17.31489352,10.00060828,0,0,0,150 +71.83,50.42009179,-3.586174612,50,-17.31836972,9.999720242,0,0,0,150 +71.84,50.42009023,-3.586173205,50,-17.33227447,9.999498478,0,0,0,150 +71.85,50.42008867,-3.586171798,50,-17.33227445,9.999498807,0,0,0,150 +71.86,50.42008711,-3.586170391,50,-17.31836968,9.999499135,0,0,0,150 +71.87,50.42008556,-3.586168984,50,-17.31489349,9.999499462,0,0,0,150 +71.88,50.420084,-3.586167577,50,-17.31836967,9.999499789,0,0,0,150 +71.89,50.42008244,-3.58616617,50,-17.31489348,9.999722209,0,0,0,150 +71.9,50.42008089,-3.586164763,50,-17.31489349,10.00061091,0,0,0,150 +71.91,50.42007933,-3.586163356,50,-17.31836968,10.00149961,0,0,0,150 +71.92,50.42007777,-3.586161948,50,-17.31489349,10.00083366,0,0,0,150 +71.93,50.42007622,-3.586160541,50,-17.31836965,9.999501429,0,0,0,150 +71.94,50.42007466,-3.586159135,50,-17.33227439,9.999723849,0,0,0,150 +71.95,50.4200731,-3.586157727,50,-17.33227439,10.00061255,0,0,0,150 +71.96,50.42007154,-3.58615632,50,-17.31836965,10.00039078,0,0,0,150 +71.97,50.42006999,-3.586154913,50,-17.31489345,9.999724833,0,0,0,150 +71.98,50.42006843,-3.586153506,50,-17.31836964,9.999503068,0,0,0,150 +71.99,50.42006687,-3.586152099,50,-17.31489346,9.999503395,0,0,0,150 +72,50.42006532,-3.586150692,50,-17.31836964,9.999503723,0,0,0,150 +72.01,50.42006376,-3.586149285,50,-17.33227437,9.999504051,0,0,0,150 +72.02,50.4200622,-3.586147878,50,-17.33227435,9.999504379,0,0,0,150 +72.03,50.42006064,-3.586146471,50,-17.3183696,9.999504707,0,0,0,150 +72.04,50.42005909,-3.586145064,50,-17.31489342,9.999727128,0,0,0,150 +72.05,50.42005753,-3.586143657,50,-17.3183696,10.00061583,0,0,0,150 +72.06,50.42005597,-3.58614225,50,-17.31489341,10.00150453,0,0,0,150 +72.07,50.42005442,-3.586140842,50,-17.31489342,10.00083857,0,0,0,150 +72.08,50.42005286,-3.586139435,50,-17.3183696,9.999506345,0,0,0,150 +72.09,50.4200513,-3.586138029,50,-17.31489339,9.999728766,0,0,0,150 +72.1,50.42004975,-3.586136621,50,-17.31836956,10.00061746,0,0,0,150 +72.11,50.42004819,-3.586135214,50,-17.33227432,10.0003957,0,0,0,150 +72.12,50.42004663,-3.586133807,50,-17.33227433,9.99972975,0,0,0,150 +72.13,50.42004507,-3.5861324,50,-17.31836957,9.999507986,0,0,0,150 +72.14,50.42004352,-3.586130993,50,-17.31489338,9.999508313,0,0,0,150 +72.15,50.42004196,-3.586129586,50,-17.31836957,9.99950864,0,0,0,150 +72.16,50.4200404,-3.586128179,50,-17.31489337,9.999508968,0,0,0,150 +72.17,50.42003885,-3.586126772,50,-17.31836953,9.999509296,0,0,0,150 +72.18,50.42003729,-3.586125365,50,-17.33227428,9.999509624,0,0,0,150 +72.19,50.42003573,-3.586123958,50,-17.33227429,9.999732045,0,0,0,150 +72.2,50.42003417,-3.586122551,50,-17.31836954,10.00062074,0,0,0,150 +72.21,50.42003262,-3.586121144,50,-17.31489334,10.00150944,0,0,0,150 +72.22,50.42003106,-3.586119736,50,-17.31836953,10.00084349,0,0,0,150 +72.23,50.4200295,-3.586118329,50,-17.31489334,9.999511264,0,0,0,150 +72.24,50.42002795,-3.586116923,50,-17.31836952,9.999733685,0,0,0,150 +72.25,50.42002639,-3.586115515,50,-17.33227425,10.00062238,0,0,0,150 +72.26,50.42002483,-3.586114108,50,-17.33227424,10.00040062,0,0,0,150 +72.27,50.42002327,-3.586112701,50,-17.3183695,9.999734667,0,0,0,150 +72.28,50.42002172,-3.586111294,50,-17.31489332,9.999512901,0,0,0,150 +72.29,50.42002016,-3.586109887,50,-17.3183695,9.99951323,0,0,0,150 +72.3,50.4200186,-3.58610848,50,-17.3148933,9.999735651,0,0,0,150 +72.31,50.42001705,-3.586107073,50,-17.3148933,10.00040226,0,0,0,150 +72.32,50.42001549,-3.586105666,50,-17.31836947,10.00062468,0,0,0,150 +72.33,50.42001393,-3.586104258,50,-17.31489327,9.999736634,0,0,0,150 +72.34,50.42001238,-3.586102852,50,-17.31836946,9.99951487,0,0,0,150 +72.35,50.42001082,-3.586101445,50,-17.33227423,10.00084776,0,0,0,150 +72.36,50.42000926,-3.586100037,50,-17.33227423,10.00129227,0,0,0,150 +72.37,50.4200077,-3.58609863,50,-17.31836946,9.999737945,0,0,0,150 +72.38,50.42000615,-3.586097223,50,-17.31489326,9.998627808,0,0,0,150 +72.39,50.42000459,-3.586095817,50,-17.31836945,9.999516507,0,0,0,150 +72.4,50.42000303,-3.586094409,50,-17.31489324,10.0006273,0,0,0,150 +72.41,50.42000148,-3.586093002,50,-17.31836942,10.00040554,0,0,0,150 +72.42,50.41999992,-3.586091595,50,-17.33227418,9.999739586,0,0,0,150 +72.43,50.41999836,-3.586090188,50,-17.33227419,9.99951782,0,0,0,150 +72.44,50.4199968,-3.586088781,50,-17.31836943,9.999518147,0,0,0,150 +72.45,50.41999525,-3.586087374,50,-17.31489323,9.999740568,0,0,0,150 +72.46,50.41999369,-3.586085967,50,-17.31836941,10.00040718,0,0,0,150 +72.47,50.41999213,-3.58608456,50,-17.31489322,10.0006296,0,0,0,150 +72.48,50.41999058,-3.586083152,50,-17.3148932,9.999741552,0,0,0,150 +72.49,50.41998902,-3.586081746,50,-17.31836938,9.999519787,0,0,0,150 +72.5,50.41998746,-3.586080339,50,-17.3148932,10.00085267,0,0,0,150 +72.51,50.41998591,-3.586078931,50,-17.3183694,10.00151928,0,0,0,150 +72.52,50.41998435,-3.586077524,50,-17.33227415,10.00063123,0,0,0,150 +72.53,50.41998279,-3.586076117,50,-17.33227414,9.999743191,0,0,0,150 +72.54,50.41998123,-3.58607471,50,-17.31836937,9.999521426,0,0,0,150 +72.55,50.41997968,-3.586073303,50,-17.31489317,9.999521753,0,0,0,150 +72.56,50.41997812,-3.586071896,50,-17.31836936,9.999522081,0,0,0,150 +72.57,50.41997656,-3.586070489,50,-17.31489317,9.99952241,0,0,0,150 +72.58,50.41997501,-3.586069082,50,-17.31836936,9.999522737,0,0,0,150 +72.59,50.41997345,-3.586067675,50,-17.33227412,9.999523065,0,0,0,150 +72.6,50.41997189,-3.586066268,50,-17.33227412,9.999523392,0,0,0,150 +72.61,50.41997033,-3.586064861,50,-17.31836935,9.99952372,0,0,0,150 +72.62,50.41996878,-3.586063454,50,-17.31489315,9.999524048,0,0,0,150 +72.63,50.41996722,-3.586062047,50,-17.31836932,9.999746469,0,0,0,150 +72.64,50.41996566,-3.58606064,50,-17.31489312,10.00063517,0,0,0,150 +72.65,50.41996411,-3.586059233,50,-17.31489312,10.00152387,0,0,0,150 +72.66,50.41996255,-3.586057825,50,-17.31836932,10.00085792,0,0,0,150 +72.67,50.41996099,-3.586056418,50,-17.31489314,9.999525687,0,0,0,150 +72.68,50.41995944,-3.586055012,50,-17.31836932,9.999748109,0,0,0,150 +72.69,50.41995788,-3.586053604,50,-17.33227405,10.00063681,0,0,0,150 +72.7,50.41995632,-3.586052197,50,-17.33227404,10.00041504,0,0,0,150 +72.71,50.41995476,-3.58605079,50,-17.31836929,9.999749092,0,0,0,150 +72.72,50.41995321,-3.586049383,50,-17.3148931,9.999527325,0,0,0,150 +72.73,50.41995165,-3.586047976,50,-17.31836929,9.999527653,0,0,0,150 +72.74,50.41995009,-3.586046569,50,-17.3148931,9.999527982,0,0,0,150 +72.75,50.41994854,-3.586045162,50,-17.31836929,9.99952831,0,0,0,150 +72.76,50.41994698,-3.586043755,50,-17.33227404,9.999528639,0,0,0,150 +72.77,50.41994542,-3.586042348,50,-17.33227401,9.999528966,0,0,0,150 +72.78,50.41994386,-3.586040941,50,-17.31836924,9.999751387,0,0,0,150 +72.79,50.41994231,-3.586039534,50,-17.31489306,10.00064009,0,0,0,150 +72.8,50.41994075,-3.586038127,50,-17.31836926,10.00152879,0,0,0,150 +72.81,50.41993919,-3.586036719,50,-17.31489306,10.00086284,0,0,0,150 +72.82,50.41993764,-3.586035312,50,-17.31836925,9.999530604,0,0,0,150 +72.83,50.41993608,-3.586033906,50,-17.33227401,9.999753026,0,0,0,150 +72.84,50.41993452,-3.586032498,50,-17.332274,10.00064173,0,0,0,150 +72.85,50.41993296,-3.586031091,50,-17.31836922,10.00041996,0,0,0,150 +72.86,50.41993141,-3.586029684,50,-17.31489302,9.99975401,0,0,0,150 +72.87,50.41992985,-3.586028277,50,-17.31836921,9.999532244,0,0,0,150 +72.88,50.41992829,-3.58602687,50,-17.31489303,9.999532571,0,0,0,150 +72.89,50.41992674,-3.586025463,50,-17.31489302,9.999532899,0,0,0,150 +72.9,50.41992518,-3.586024056,50,-17.31836921,9.999533227,0,0,0,150 +72.91,50.41992362,-3.586022649,50,-17.31489302,9.999533555,0,0,0,150 +72.92,50.41992207,-3.586021242,50,-17.3183692,9.999755976,0,0,0,150 +72.93,50.41992051,-3.586019835,50,-17.33227393,10.00064468,0,0,0,150 +72.94,50.41991895,-3.586018428,50,-17.33227392,10.00153338,0,0,0,150 +72.95,50.41991739,-3.58601702,50,-17.31836919,10.00064533,0,0,0,150 +72.96,50.41991584,-3.586015613,50,-17.314893,9.99864682,0,0,0,150 +72.97,50.41991428,-3.586014207,50,-17.31836919,9.998647148,0,0,0,150 +72.98,50.41991272,-3.5860128,50,-17.314893,10.00064632,0,0,0,150 +72.99,50.41991117,-3.586011392,50,-17.31836918,10.00153502,0,0,0,150 +73,50.41990961,-3.586009985,50,-17.33227391,10.00064697,0,0,0,150 +73.01,50.41990805,-3.586008578,50,-17.33227388,9.999758927,0,0,0,150 +73.02,50.41990649,-3.586007171,50,-17.31836913,9.999537162,0,0,0,150 +73.03,50.41990494,-3.586005764,50,-17.31489296,9.999537489,0,0,0,150 +73.04,50.41990338,-3.586004357,50,-17.31836915,9.999537817,0,0,0,150 +73.05,50.41990182,-3.58600295,50,-17.31489296,9.999538144,0,0,0,150 +73.06,50.41990027,-3.586001543,50,-17.31489296,9.999538472,0,0,0,150 +73.07,50.41989871,-3.586000136,50,-17.31836914,9.999760893,0,0,0,150 +73.08,50.41989715,-3.585998729,50,-17.31489293,10.0006496,0,0,0,150 +73.09,50.4198956,-3.585997322,50,-17.31836909,10.0015383,0,0,0,150 +73.1,50.41989404,-3.585995914,50,-17.33227385,10.00087234,0,0,0,150 +73.11,50.41989248,-3.585994507,50,-17.33227386,9.999540111,0,0,0,150 +73.12,50.41989092,-3.585993101,50,-17.31836912,9.999762534,0,0,0,150 +73.13,50.41988937,-3.585991693,50,-17.31489292,10.00065124,0,0,0,150 +73.14,50.41988781,-3.585990286,50,-17.31836911,10.00042947,0,0,0,150 +73.15,50.41988625,-3.585988879,50,-17.3148929,9.999763516,0,0,0,150 +73.16,50.4198847,-3.585987472,50,-17.31836907,9.999541749,0,0,0,150 +73.17,50.41988314,-3.585986065,50,-17.33227381,9.999542077,0,0,0,150 +73.18,50.41988158,-3.585984658,50,-17.33227382,9.999542406,0,0,0,150 +73.19,50.41988002,-3.585983251,50,-17.31836908,9.999542735,0,0,0,150 +73.2,50.41987847,-3.585981844,50,-17.31489289,9.999543063,0,0,0,150 +73.21,50.41987691,-3.585980437,50,-17.31836908,9.99954339,0,0,0,150 +73.22,50.41987535,-3.58597903,50,-17.31489288,9.999765811,0,0,0,150 +73.23,50.4198738,-3.585977623,50,-17.31489287,10.00043242,0,0,0,150 +73.24,50.41987224,-3.585976216,50,-17.31836903,10.00065484,0,0,0,150 +73.25,50.41987068,-3.585974808,50,-17.31489284,9.999766794,0,0,0,150 +73.26,50.41986913,-3.585973402,50,-17.31836904,9.999545028,0,0,0,150 +73.27,50.41986757,-3.585971995,50,-17.3322738,10.00087792,0,0,0,150 +73.28,50.41986601,-3.585970587,50,-17.33227379,10.00154453,0,0,0,150 +73.29,50.41986445,-3.58596918,50,-17.31836903,10.00065648,0,0,0,150 +73.3,50.4198629,-3.585967773,50,-17.31489283,9.999768434,0,0,0,150 +73.31,50.41986134,-3.585966366,50,-17.31836901,9.999546669,0,0,0,150 +73.32,50.41985978,-3.585964959,50,-17.3148928,9.999546996,0,0,0,150 +73.33,50.41985823,-3.585963552,50,-17.318369,9.999547323,0,0,0,150 +73.34,50.41985667,-3.585962145,50,-17.33227377,9.99954765,0,0,0,150 +73.35,50.41985511,-3.585960738,50,-17.33227376,9.999547978,0,0,0,150 +73.36,50.41985355,-3.585959331,50,-17.31836899,9.999548307,0,0,0,150 +73.37,50.419852,-3.585957924,50,-17.31489278,9.999548636,0,0,0,150 +73.38,50.41985044,-3.585956517,50,-17.31836896,9.999548964,0,0,0,150 +73.39,50.41984888,-3.58595511,50,-17.31489278,9.999549291,0,0,0,150 +73.4,50.41984733,-3.585953703,50,-17.31489279,9.999771712,0,0,0,150 +73.41,50.41984577,-3.585952296,50,-17.31836898,10.00066041,0,0,0,150 +73.42,50.41984421,-3.585950889,50,-17.31489279,10.00154912,0,0,0,150 +73.43,50.41984266,-3.585949481,50,-17.31836897,10.00088316,0,0,0,150 +73.44,50.4198411,-3.585948074,50,-17.33227371,9.999550929,0,0,0,150 +73.45,50.41983954,-3.585946668,50,-17.33227371,9.999773351,0,0,0,150 +73.46,50.41983798,-3.58594526,50,-17.31836895,10.00066205,0,0,0,150 +73.47,50.41983643,-3.585943853,50,-17.31489274,10.00044029,0,0,0,150 +73.48,50.41983487,-3.585942446,50,-17.31836892,9.999774334,0,0,0,150 +73.49,50.41983331,-3.585941039,50,-17.31489274,9.999552568,0,0,0,150 +73.5,50.41983176,-3.585939632,50,-17.31836894,9.999552896,0,0,0,150 +73.51,50.4198302,-3.585938225,50,-17.33227369,9.999553224,0,0,0,150 +73.52,50.41982864,-3.585936818,50,-17.33227367,9.999553552,0,0,0,150 +73.53,50.41982708,-3.585935411,50,-17.31836891,9.99955388,0,0,0,150 +73.54,50.41982553,-3.585934004,50,-17.31489271,9.999554208,0,0,0,150 +73.55,50.41982397,-3.585932597,50,-17.31836889,9.999776629,0,0,0,150 +73.56,50.41982241,-3.58593119,50,-17.3148927,10.00044324,0,0,0,150 +73.57,50.41982086,-3.585929783,50,-17.31489271,10.00066566,0,0,0,150 +73.58,50.4198193,-3.585928375,50,-17.3183689,9.999777612,0,0,0,150 +73.59,50.41981774,-3.585926969,50,-17.31489271,9.999555846,0,0,0,150 +73.6,50.41981619,-3.585925562,50,-17.31836888,10.00088874,0,0,0,150 +73.61,50.41981463,-3.585924154,50,-17.33227362,10.00155535,0,0,0,150 +73.62,50.41981307,-3.585922747,50,-17.33227362,10.0006673,0,0,0,150 +73.63,50.41981151,-3.58592134,50,-17.31836886,9.999779252,0,0,0,150 +73.64,50.41980996,-3.585919933,50,-17.31489267,9.999557487,0,0,0,150 +73.65,50.4198084,-3.585918526,50,-17.31836886,9.999557815,0,0,0,150 +73.66,50.41980684,-3.585917119,50,-17.31489268,9.999558142,0,0,0,150 +73.67,50.41980529,-3.585915712,50,-17.31836886,9.999558469,0,0,0,150 +73.68,50.41980373,-3.585914305,50,-17.33227359,9.999558796,0,0,0,150 +73.69,50.41980217,-3.585912898,50,-17.33227357,9.999781218,0,0,0,150 +73.7,50.41980061,-3.585911491,50,-17.31836882,10.00044783,0,0,0,150 +73.71,50.41979906,-3.585910084,50,-17.31489264,10.00067025,0,0,0,150 +73.72,50.4197975,-3.585908676,50,-17.31836883,9.999782204,0,0,0,150 +73.73,50.41979594,-3.58590727,50,-17.31489264,9.999560437,0,0,0,150 +73.74,50.41979439,-3.585905863,50,-17.31489264,10.00089333,0,0,0,150 +73.75,50.41979283,-3.585904455,50,-17.31836882,10.00155994,0,0,0,150 +73.76,50.41979127,-3.585903048,50,-17.31489261,10.00067189,0,0,0,150 +73.77,50.41978972,-3.585901641,50,-17.31836878,9.999783842,0,0,0,150 +73.78,50.41978816,-3.585900234,50,-17.33227354,9.999562075,0,0,0,150 +73.79,50.4197866,-3.585898827,50,-17.33227355,9.999562402,0,0,0,150 +73.8,50.41978504,-3.58589742,50,-17.31836879,9.99956273,0,0,0,150 +73.81,50.41978349,-3.585896013,50,-17.3148926,9.999563058,0,0,0,150 +73.82,50.41978193,-3.585894606,50,-17.31836879,9.999563387,0,0,0,150 +73.83,50.41978037,-3.585893199,50,-17.3148926,9.999563716,0,0,0,150 +73.84,50.41977882,-3.585891792,50,-17.31836876,9.999564043,0,0,0,150 +73.85,50.41977726,-3.585890385,50,-17.3322735,9.99956437,0,0,0,150 +73.86,50.4197757,-3.585888978,50,-17.3322735,9.999564697,0,0,0,150 +73.87,50.41977414,-3.585887571,50,-17.31836876,9.999787119,0,0,0,150 +73.88,50.41977259,-3.585886164,50,-17.31489256,10.00067582,0,0,0,150 +73.89,50.41977103,-3.585884757,50,-17.31836875,10.00156453,0,0,0,150 +73.9,50.41976947,-3.585883349,50,-17.31489256,10.00089857,0,0,0,150 +73.91,50.41976792,-3.585881942,50,-17.31836874,9.999566338,0,0,0,150 +73.92,50.41976636,-3.585880536,50,-17.33227347,9.999788759,0,0,0,150 +73.93,50.4197648,-3.585879128,50,-17.33227346,10.00067746,0,0,0,150 +73.94,50.41976324,-3.585877721,50,-17.31836872,10.0004557,0,0,0,150 +73.95,50.41976169,-3.585876314,50,-17.31489254,9.999789743,0,0,0,150 +73.96,50.41976013,-3.585874907,50,-17.31836872,9.999567976,0,0,0,150 +73.97,50.41975857,-3.5858735,50,-17.31489252,9.999568304,0,0,0,150 +73.98,50.41975702,-3.585872093,50,-17.31836871,9.999568632,0,0,0,150 +73.99,50.41975546,-3.585870686,50,-17.33227344,9.999568959,0,0,0,150 +74,50.4197539,-3.585869279,50,-17.33227343,9.999569288,0,0,0,150 +74.01,50.41975234,-3.585867872,50,-17.31836868,9.999569616,0,0,0,150 +74.02,50.41975079,-3.585866465,50,-17.31489251,9.999792038,0,0,0,150 +74.03,50.41974923,-3.585865058,50,-17.31836869,10.00045865,0,0,0,150 +74.04,50.41974767,-3.585863651,50,-17.31489249,10.00068107,0,0,0,150 +74.05,50.41974612,-3.585862243,50,-17.31489249,9.999793021,0,0,0,150 +74.06,50.41974456,-3.585860837,50,-17.31836868,9.999571253,0,0,0,150 +74.07,50.419743,-3.58585943,50,-17.31489248,10.00068205,0,0,0,150 +74.08,50.41974145,-3.585858022,50,-17.31836864,10.00068238,0,0,0,150 +74.09,50.41973989,-3.585856615,50,-17.33227339,9.999572239,0,0,0,150 +74.1,50.41973833,-3.585855209,50,-17.3322734,9.999794661,0,0,0,150 +74.11,50.41973677,-3.585853801,50,-17.31836865,10.00068336,0,0,0,150 +74.12,50.41973522,-3.585852394,50,-17.31489245,10.0004616,0,0,0,150 +74.13,50.41973366,-3.585850987,50,-17.31836864,9.999795643,0,0,0,150 +74.14,50.4197321,-3.58584958,50,-17.31489244,9.999573877,0,0,0,150 +74.15,50.41973055,-3.585848173,50,-17.31836862,9.999574205,0,0,0,150 +74.16,50.41972899,-3.585846766,50,-17.33227336,9.999574533,0,0,0,150 +74.17,50.41972743,-3.585845359,50,-17.33227336,9.999574861,0,0,0,150 +74.18,50.41972587,-3.585843952,50,-17.31836862,9.999575188,0,0,0,150 +74.19,50.41972432,-3.585842545,50,-17.31489243,9.999575516,0,0,0,150 +74.2,50.41972276,-3.585841138,50,-17.3183686,9.999797938,0,0,0,150 +74.21,50.4197212,-3.585839731,50,-17.3148924,10.00046455,0,0,0,150 +74.22,50.41971965,-3.585838324,50,-17.31489239,10.00068697,0,0,0,150 +74.23,50.41971809,-3.585836916,50,-17.31836858,9.999798922,0,0,0,150 +74.24,50.41971653,-3.58583551,50,-17.31489239,9.999577155,0,0,0,150 +74.25,50.41971498,-3.585834103,50,-17.31836858,10.00091005,0,0,0,150 +74.26,50.41971342,-3.585832695,50,-17.33227334,10.00157666,0,0,0,150 +74.27,50.41971186,-3.585831288,50,-17.33227333,10.00068861,0,0,0,150 +74.28,50.4197103,-3.585829881,50,-17.31836857,9.999800562,0,0,0,150 +74.29,50.41970875,-3.585828474,50,-17.31489236,9.999578795,0,0,0,150 +74.3,50.41970719,-3.585827067,50,-17.31836855,9.999579122,0,0,0,150 +74.31,50.41970563,-3.58582566,50,-17.31489235,9.999579449,0,0,0,150 +74.32,50.41970408,-3.585824253,50,-17.31836854,9.999579777,0,0,0,150 +74.33,50.41970252,-3.585822846,50,-17.3322733,9.999580105,0,0,0,150 +74.34,50.41970096,-3.585821439,50,-17.3322733,9.999802529,0,0,0,150 +74.35,50.4196994,-3.585820032,50,-17.31836854,10.00046914,0,0,0,150 +74.36,50.41969785,-3.585818625,50,-17.31489233,10.00069156,0,0,0,150 +74.37,50.41969629,-3.585817217,50,-17.3183685,9.999581417,0,0,0,150 +74.38,50.41969473,-3.585815811,50,-17.31489232,9.998693366,0,0,0,150 +74.39,50.41969318,-3.585814404,50,-17.31489233,9.999582071,0,0,0,150 +74.4,50.41969162,-3.585812997,50,-17.31836851,10.00047078,0,0,0,150 +74.41,50.41969006,-3.585811589,50,-17.31489232,9.999804823,0,0,0,150 +74.42,50.41968851,-3.585810183,50,-17.31836851,9.999583056,0,0,0,150 +74.43,50.41968695,-3.585808776,50,-17.33227326,10.00091595,0,0,0,150 +74.44,50.41968539,-3.585807368,50,-17.33227324,10.00158256,0,0,0,150 +74.45,50.41968383,-3.585805961,50,-17.31836847,10.00069451,0,0,0,150 +74.46,50.41968228,-3.585804554,50,-17.31489228,9.999806462,0,0,0,150 +74.47,50.41968072,-3.585803147,50,-17.31836848,9.999584695,0,0,0,150 +74.48,50.41967916,-3.58580174,50,-17.31489228,9.999585022,0,0,0,150 +74.49,50.41967761,-3.585800333,50,-17.31836847,9.99958535,0,0,0,150 +74.5,50.41967605,-3.585798926,50,-17.33227323,9.999585678,0,0,0,150 +74.51,50.41967449,-3.585797519,50,-17.33227322,9.999586006,0,0,0,150 +74.52,50.41967293,-3.585796112,50,-17.31836845,9.99980843,0,0,0,150 +74.53,50.41967138,-3.585794705,50,-17.31489224,10.00047504,0,0,0,150 +74.54,50.41966982,-3.585793298,50,-17.31836843,10.00069746,0,0,0,150 +74.55,50.41966826,-3.58579189,50,-17.31489225,9.999809412,0,0,0,150 +74.56,50.41966671,-3.585790484,50,-17.31489225,9.999587645,0,0,0,150 +74.57,50.41966515,-3.585789077,50,-17.31836843,10.00092054,0,0,0,150 +74.58,50.41966359,-3.585787669,50,-17.31489225,10.00136506,0,0,0,150 +74.59,50.41966204,-3.585786262,50,-17.31836842,9.999810723,0,0,0,150 +74.6,50.41966048,-3.585784855,50,-17.33227315,9.998700579,0,0,0,150 +74.61,50.41965892,-3.585783449,50,-17.33227315,9.999589286,0,0,0,150 +74.62,50.41965736,-3.585782041,50,-17.31836841,10.00070009,0,0,0,150 +74.63,50.41965581,-3.585780634,50,-17.31489223,10.00047832,0,0,0,150 +74.64,50.41965425,-3.585779227,50,-17.31836841,9.999812362,0,0,0,150 +74.65,50.41965269,-3.58577782,50,-17.31489222,9.999590595,0,0,0,150 +74.66,50.41965114,-3.585776413,50,-17.3183684,9.999590923,0,0,0,150 +74.67,50.41964958,-3.585775006,50,-17.33227313,9.999591252,0,0,0,150 +74.68,50.41964802,-3.585773599,50,-17.3322731,9.999591581,0,0,0,150 +74.69,50.41964646,-3.585772192,50,-17.31836835,9.999591908,0,0,0,150 +74.7,50.41964491,-3.585770785,50,-17.31489218,9.99981433,0,0,0,150 +74.71,50.41964335,-3.585769378,50,-17.31836838,10.00048094,0,0,0,150 +74.72,50.41964179,-3.585767971,50,-17.31489218,10.00070336,0,0,0,150 +74.73,50.41964024,-3.585766563,50,-17.31489218,9.999815313,0,0,0,150 +74.74,50.41963868,-3.585765157,50,-17.31836836,9.999593546,0,0,0,150 +74.75,50.41963712,-3.58576375,50,-17.31489215,10.00092644,0,0,0,150 +74.76,50.41963557,-3.585762342,50,-17.31836831,10.00159305,0,0,0,150 +74.77,50.41963401,-3.585760935,50,-17.33227307,10.000705,0,0,0,150 +74.78,50.41963245,-3.585759528,50,-17.33227309,9.999816953,0,0,0,150 +74.79,50.41963089,-3.585758121,50,-17.31836834,9.999595187,0,0,0,150 +74.8,50.41962934,-3.585756714,50,-17.31489215,9.999595514,0,0,0,150 +74.81,50.41962778,-3.585755307,50,-17.31836833,9.999595841,0,0,0,150 +74.82,50.41962622,-3.5857539,50,-17.31489213,9.999596168,0,0,0,150 +74.83,50.41962467,-3.585752493,50,-17.31836829,9.999596495,0,0,0,150 +74.84,50.41962311,-3.585751086,50,-17.33227303,9.999596824,0,0,0,150 +74.85,50.41962155,-3.585749679,50,-17.33227304,9.999597153,0,0,0,150 +74.86,50.41961999,-3.585748272,50,-17.3183683,9.999597481,0,0,0,150 +74.87,50.41961844,-3.585746865,50,-17.31489212,9.999597809,0,0,0,150 +74.88,50.41961688,-3.585745458,50,-17.3183683,9.99982023,0,0,0,150 +74.89,50.41961532,-3.585744051,50,-17.3148921,10.00048684,0,0,0,150 +74.9,50.41961377,-3.585742644,50,-17.31489209,10.00070927,0,0,0,150 +74.91,50.41961221,-3.585741236,50,-17.31836825,9.999821213,0,0,0,150 +74.92,50.41961065,-3.58573983,50,-17.31489206,9.999599447,0,0,0,150 +74.93,50.4196091,-3.585738423,50,-17.31836826,10.00093234,0,0,0,150 +74.94,50.41960754,-3.585737015,50,-17.33227302,10.00159896,0,0,0,150 +74.95,50.41960598,-3.585735608,50,-17.33227301,10.0007109,0,0,0,150 +74.96,50.41960442,-3.585734201,50,-17.31836825,9.999822853,0,0,0,150 +74.97,50.41960287,-3.585732794,50,-17.31489206,9.999601087,0,0,0,150 +74.98,50.41960131,-3.585731387,50,-17.31836823,9.999601414,0,0,0,150 +74.99,50.41959975,-3.58572998,50,-17.31489203,9.999601741,0,0,0,150 +75,50.4195982,-3.585728573,50,-17.31836822,9.999602069,0,0,0,150 +75.01,50.41959664,-3.585727166,50,-17.33227299,9.999602397,0,0,0,150 +75.02,50.41959508,-3.585725759,50,-17.33227299,9.999602725,0,0,0,150 +75.03,50.41959352,-3.585724352,50,-17.31836822,9.999603053,0,0,0,150 +75.04,50.41959197,-3.585722945,50,-17.31489202,9.999603381,0,0,0,150 +75.05,50.41959041,-3.585721538,50,-17.31836821,9.999603709,0,0,0,150 +75.06,50.41958885,-3.585720131,50,-17.314892,9.999826131,0,0,0,150 +75.07,50.4195873,-3.585718724,50,-17.31489199,10.00049274,0,0,0,150 +75.08,50.41958574,-3.585717317,50,-17.31836818,10.00071517,0,0,0,150 +75.09,50.41958418,-3.585715909,50,-17.31489201,9.999827114,0,0,0,150 +75.1,50.41958263,-3.585714503,50,-17.31836819,9.999605347,0,0,0,150 +75.11,50.41958107,-3.585713096,50,-17.33227293,10.00071615,0,0,0,150 +75.12,50.41957951,-3.585711688,50,-17.33227293,10.00071648,0,0,0,150 +75.13,50.41957795,-3.585710281,50,-17.31836817,9.999606331,0,0,0,150 +75.14,50.4195764,-3.585708875,50,-17.31489197,9.999828754,0,0,0,150 +75.15,50.41957484,-3.585707467,50,-17.31836814,10.00071746,0,0,0,150 +75.16,50.41957328,-3.58570606,50,-17.31489196,10.00049569,0,0,0,150 +75.17,50.41957173,-3.585704653,50,-17.31836816,9.999829737,0,0,0,150 +75.18,50.41957017,-3.585703246,50,-17.33227291,9.99960797,0,0,0,150 +75.19,50.41956861,-3.585701839,50,-17.33227289,9.999608299,0,0,0,150 +75.2,50.41956705,-3.585700432,50,-17.31836813,9.999608627,0,0,0,150 +75.21,50.4195655,-3.585699025,50,-17.31489193,9.999608954,0,0,0,150 +75.22,50.41956394,-3.585697618,50,-17.31836812,9.999609281,0,0,0,150 +75.23,50.41956238,-3.585696211,50,-17.31489193,9.999609609,0,0,0,150 +75.24,50.41956083,-3.585694804,50,-17.31836812,9.999832032,0,0,0,150 +75.25,50.41955927,-3.585693397,50,-17.33227288,10.00049865,0,0,0,150 +75.26,50.41955771,-3.58569199,50,-17.33227287,10.00072107,0,0,0,150 +75.27,50.41955615,-3.585690582,50,-17.3183681,9.999833016,0,0,0,150 +75.28,50.4195546,-3.585689176,50,-17.3148919,9.999611249,0,0,0,150 +75.29,50.41955304,-3.585687769,50,-17.31836808,10.00072205,0,0,0,150 +75.3,50.41955148,-3.585686361,50,-17.31489189,10.00072238,0,0,0,150 +75.31,50.41954993,-3.585684954,50,-17.31489189,9.999612232,0,0,0,150 +75.32,50.41954837,-3.585683548,50,-17.31836808,9.999834655,0,0,0,150 +75.33,50.41954681,-3.58568214,50,-17.3148919,10.00072336,0,0,0,150 +75.34,50.41954526,-3.585680733,50,-17.31836808,10.0005016,0,0,0,150 +75.35,50.4195437,-3.585679326,50,-17.33227281,9.999835637,0,0,0,150 +75.36,50.41954214,-3.585677919,50,-17.3322728,9.999613871,0,0,0,150 +75.37,50.41954058,-3.585676512,50,-17.31836805,9.9996142,0,0,0,150 +75.38,50.41953903,-3.585675105,50,-17.31489186,9.999614528,0,0,0,150 +75.39,50.41953747,-3.585673698,50,-17.31836805,9.999614855,0,0,0,150 +75.4,50.41953591,-3.585672291,50,-17.31489186,9.999615182,0,0,0,150 +75.41,50.41953436,-3.585670884,50,-17.31836805,9.999615509,0,0,0,150 +75.42,50.4195328,-3.585669477,50,-17.3322728,9.999615837,0,0,0,150 +75.43,50.41953124,-3.58566807,50,-17.33227277,9.999616166,0,0,0,150 +75.44,50.41952968,-3.585666663,50,-17.31836801,9.999616494,0,0,0,150 +75.45,50.41952813,-3.585665256,50,-17.31489182,9.999838918,0,0,0,150 +75.46,50.41952657,-3.585663849,50,-17.31836802,10.00072763,0,0,0,150 +75.47,50.41952501,-3.585662442,50,-17.31489182,10.00161633,0,0,0,150 +75.48,50.41952346,-3.585661034,50,-17.31489182,10.00095038,0,0,0,150 +75.49,50.4195219,-3.585659627,50,-17.31836801,9.999618132,0,0,0,150 +75.5,50.41952034,-3.585658221,50,-17.31489182,9.999840556,0,0,0,150 +75.51,50.41951879,-3.585656813,50,-17.31836798,10.00072926,0,0,0,150 +75.52,50.41951723,-3.585655406,50,-17.33227272,10.0005075,0,0,0,150 +75.53,50.41951567,-3.585653999,50,-17.33227273,9.999841538,0,0,0,150 +75.54,50.41951411,-3.585652592,50,-17.31836798,9.999619771,0,0,0,150 +75.55,50.41951256,-3.585651185,50,-17.31489179,9.9996201,0,0,0,150 +75.56,50.419511,-3.585649778,50,-17.31836797,9.999620429,0,0,0,150 +75.57,50.41950944,-3.585648371,50,-17.31489179,9.999620756,0,0,0,150 +75.58,50.41950789,-3.585646964,50,-17.31836796,9.999621083,0,0,0,150 +75.59,50.41950633,-3.585645557,50,-17.33227269,9.999843505,0,0,0,150 +75.6,50.41950477,-3.58564415,50,-17.33227268,10.00051012,0,0,0,150 +75.61,50.41950321,-3.585642743,50,-17.31836795,10.00073254,0,0,0,150 +75.62,50.41950166,-3.585641335,50,-17.31489176,9.999622395,0,0,0,150 +75.63,50.4195001,-3.585639929,50,-17.31836794,9.998734341,0,0,0,150 +75.64,50.41949854,-3.585638522,50,-17.31489175,9.999623051,0,0,0,150 +75.65,50.41949699,-3.585637115,50,-17.31836794,10.00051176,0,0,0,150 +75.66,50.41949543,-3.585635707,50,-17.33227268,9.9998458,0,0,0,150 +75.67,50.41949387,-3.585634301,50,-17.33227265,9.999624032,0,0,0,150 +75.68,50.41949231,-3.585632894,50,-17.31836789,10.00095693,0,0,0,150 +75.69,50.41949076,-3.585631486,50,-17.31489172,10.00162355,0,0,0,150 +75.7,50.4194892,-3.585630079,50,-17.31836791,10.00073549,0,0,0,150 +75.71,50.41948764,-3.585628672,50,-17.31489171,9.99984744,0,0,0,150 +75.72,50.41948609,-3.585627265,50,-17.31489171,9.999625672,0,0,0,150 +75.73,50.41948453,-3.585625858,50,-17.3183679,9.999626,0,0,0,150 +75.74,50.41948297,-3.585624451,50,-17.3148917,9.999626328,0,0,0,150 +75.75,50.41948142,-3.585623044,50,-17.31836786,9.999626656,0,0,0,150 +75.76,50.41947986,-3.585621637,50,-17.33227261,9.999626983,0,0,0,150 +75.77,50.4194783,-3.58562023,50,-17.33227262,9.999627311,0,0,0,150 +75.78,50.41947674,-3.585618823,50,-17.31836788,9.999627639,0,0,0,150 +75.79,50.41947519,-3.585617416,50,-17.31489168,9.999627967,0,0,0,150 +75.8,50.41947363,-3.585616009,50,-17.31836786,9.99985039,0,0,0,150 +75.81,50.41947207,-3.585614602,50,-17.31489166,10.0007391,0,0,0,150 +75.82,50.41947052,-3.585613195,50,-17.31836784,10.00162781,0,0,0,150 +75.83,50.41946896,-3.585611787,50,-17.33227258,10.00073976,0,0,0,150 +75.84,50.4194674,-3.58561038,50,-17.33227258,9.998741224,0,0,0,150 +75.85,50.41946584,-3.585608974,50,-17.31836784,9.998741552,0,0,0,150 +75.86,50.41946429,-3.585607567,50,-17.31489165,10.00051864,0,0,0,150 +75.87,50.41946273,-3.585606159,50,-17.31836783,10.00074107,0,0,0,150 +75.88,50.41946117,-3.585604752,50,-17.31489163,9.999630917,0,0,0,150 +75.89,50.41945962,-3.585603346,50,-17.31489163,9.999853342,0,0,0,150 +75.9,50.41945806,-3.585601938,50,-17.3183678,10.00074205,0,0,0,150 +75.91,50.4194565,-3.585600531,50,-17.3148916,10.00052028,0,0,0,150 +75.92,50.41945495,-3.585599124,50,-17.31836779,9.999854324,0,0,0,150 +75.93,50.41945339,-3.585597717,50,-17.33227256,9.999632555,0,0,0,150 +75.94,50.41945183,-3.58559631,50,-17.33227256,9.999632884,0,0,0,150 +75.95,50.41945027,-3.585594903,50,-17.31836779,9.999633212,0,0,0,150 +75.96,50.41944872,-3.585593496,50,-17.31489159,9.999633541,0,0,0,150 +75.97,50.41944716,-3.585592089,50,-17.31836777,9.999633869,0,0,0,150 +75.98,50.4194456,-3.585590682,50,-17.31489157,9.999856292,0,0,0,150 +75.99,50.41944405,-3.585589275,50,-17.31836776,10.00052291,0,0,0,150 +76,50.41944249,-3.585587868,50,-17.33227252,10.00074533,0,0,0,150 +76.01,50.41944093,-3.58558646,50,-17.33227252,9.999857274,0,0,0,150 +76.02,50.41943937,-3.585585054,50,-17.31836777,9.999635507,0,0,0,150 +76.03,50.41943782,-3.585583647,50,-17.31489156,10.00074631,0,0,0,150 +76.04,50.41943626,-3.585582239,50,-17.31836774,10.00052455,0,0,0,150 +76.05,50.4194347,-3.585580832,50,-17.31489154,9.998748109,0,0,0,150 +76.06,50.41943315,-3.585579426,50,-17.31489154,9.998748436,0,0,0,150 +76.07,50.41943159,-3.585578019,50,-17.31836772,10.00074762,0,0,0,150 +76.08,50.41943003,-3.585576611,50,-17.31489154,10.00163633,0,0,0,150 +76.09,50.41942848,-3.585575204,50,-17.31836773,10.00074828,0,0,0,150 +76.1,50.41942692,-3.585573797,50,-17.33227248,9.999860225,0,0,0,150 +76.11,50.41942536,-3.58557239,50,-17.33227247,9.999638457,0,0,0,150 +76.12,50.4194238,-3.585570983,50,-17.31836771,9.999638785,0,0,0,150 +76.13,50.41942225,-3.585569576,50,-17.3148915,9.999639113,0,0,0,150 +76.14,50.41942069,-3.585568169,50,-17.31836768,9.999639441,0,0,0,150 +76.15,50.41941913,-3.585566762,50,-17.31489149,9.999639769,0,0,0,150 +76.16,50.41941758,-3.585565355,50,-17.31836769,9.999640096,0,0,0,150 +76.17,50.41941602,-3.585563948,50,-17.33227245,9.999640424,0,0,0,150 +76.18,50.41941446,-3.585562541,50,-17.33227244,9.999640752,0,0,0,150 +76.19,50.4194129,-3.585561134,50,-17.31836767,9.999863176,0,0,0,150 +76.2,50.41941135,-3.585559727,50,-17.31489146,10.00052979,0,0,0,150 +76.21,50.41940979,-3.58555832,50,-17.31836766,10.00075222,0,0,0,150 +76.22,50.41940823,-3.585556912,50,-17.31489147,9.99986416,0,0,0,150 +76.23,50.41940668,-3.585555506,50,-17.31836766,9.999642391,0,0,0,150 +76.24,50.41940512,-3.585554099,50,-17.33227241,10.00097529,0,0,0,150 +76.25,50.41940356,-3.585552691,50,-17.33227241,10.00164191,0,0,0,150 +76.26,50.419402,-3.585551284,50,-17.31836765,10.00075385,0,0,0,150 +76.27,50.41940045,-3.585549877,50,-17.31489144,9.999865798,0,0,0,150 +76.28,50.41939889,-3.58554847,50,-17.31836761,9.99964403,0,0,0,150 +76.29,50.41939733,-3.585547063,50,-17.31489143,9.999644359,0,0,0,150 +76.3,50.41939578,-3.585545656,50,-17.31489144,9.999644687,0,0,0,150 +76.31,50.41939422,-3.585544249,50,-17.31836762,9.999645014,0,0,0,150 +76.32,50.41939266,-3.585542842,50,-17.31489143,9.999645341,0,0,0,150 +76.33,50.41939111,-3.585541435,50,-17.31836762,9.999645669,0,0,0,150 +76.34,50.41938955,-3.585540028,50,-17.33227236,9.999645997,0,0,0,150 +76.35,50.41938799,-3.585538621,50,-17.33227233,9.999646325,0,0,0,150 +76.36,50.41938643,-3.585537214,50,-17.31836758,9.999646654,0,0,0,150 +76.37,50.41938488,-3.585535807,50,-17.3148914,9.999646981,0,0,0,150 +76.38,50.41938332,-3.5855344,50,-17.3183676,9.999647308,0,0,0,150 +76.39,50.41938176,-3.585532993,50,-17.31489141,9.999647636,0,0,0,150 +76.4,50.41938021,-3.585531586,50,-17.31836759,9.99987006,0,0,0,150 +76.41,50.41937865,-3.585530179,50,-17.33227233,10.00075877,0,0,0,150 +76.42,50.41937709,-3.585528772,50,-17.3322723,10.00164748,0,0,0,150 +76.43,50.41937553,-3.585527364,50,-17.31836753,10.00098152,0,0,0,150 +76.44,50.41937398,-3.585525957,50,-17.31489136,9.999649275,0,0,0,150 +76.45,50.41937242,-3.585524551,50,-17.31836756,9.999871699,0,0,0,150 +76.46,50.41937086,-3.585523143,50,-17.31489137,10.00076041,0,0,0,150 +76.47,50.41936931,-3.585521736,50,-17.31489137,10.00053864,0,0,0,150 +76.48,50.41936775,-3.585520329,50,-17.31836755,9.999872684,0,0,0,150 +76.49,50.41936619,-3.585518922,50,-17.31489136,9.999650915,0,0,0,150 +76.5,50.41936464,-3.585517515,50,-17.31836752,9.999651242,0,0,0,150 +76.51,50.41936308,-3.585516108,50,-17.33227225,9.999651569,0,0,0,150 +76.52,50.41936152,-3.585514701,50,-17.33227225,9.999651897,0,0,0,150 +76.53,50.41935996,-3.585513294,50,-17.31836752,9.999652226,0,0,0,150 +76.54,50.41935841,-3.585511887,50,-17.31489134,9.999652554,0,0,0,150 +76.55,50.41935685,-3.58551048,50,-17.31836752,9.999652883,0,0,0,150 +76.56,50.41935529,-3.585509073,50,-17.31489133,9.99965321,0,0,0,150 +76.57,50.41935374,-3.585507666,50,-17.3183675,9.999653537,0,0,0,150 +76.58,50.41935218,-3.585506259,50,-17.33227222,9.99987596,0,0,0,150 +76.59,50.41935062,-3.585504852,50,-17.33227221,10.00054258,0,0,0,150 +76.6,50.41934906,-3.585503445,50,-17.31836747,10.000765,0,0,0,150 +76.61,50.41934751,-3.585502037,50,-17.3148913,9.999876945,0,0,0,150 +76.62,50.41934595,-3.585500631,50,-17.31836749,9.999655176,0,0,0,150 +76.63,50.41934439,-3.585499224,50,-17.31489129,10.00076598,0,0,0,150 +76.64,50.41934284,-3.585497816,50,-17.31489128,10.00076631,0,0,0,150 +76.65,50.41934128,-3.585496409,50,-17.31836745,9.99965616,0,0,0,150 +76.66,50.41933972,-3.585495003,50,-17.31489125,9.999878585,0,0,0,150 +76.67,50.41933817,-3.585493595,50,-17.31836743,10.0007673,0,0,0,150 +76.68,50.41933661,-3.585492188,50,-17.3322722,10.00054553,0,0,0,150 +76.69,50.41933505,-3.585490781,50,-17.33227221,9.999879566,0,0,0,150 +76.7,50.41933349,-3.585489374,50,-17.31836745,9.999657798,0,0,0,150 +76.71,50.41933194,-3.585487967,50,-17.31489126,9.999658126,0,0,0,150 +76.72,50.41933038,-3.58548656,50,-17.31836744,9.999658455,0,0,0,150 +76.73,50.41932882,-3.585485153,50,-17.31489124,9.999658783,0,0,0,150 +76.74,50.41932727,-3.585483746,50,-17.3183674,9.999659111,0,0,0,150 +76.75,50.41932571,-3.585482339,50,-17.33227215,9.999659437,0,0,0,150 +76.76,50.41932415,-3.585480932,50,-17.33227216,9.999659765,0,0,0,150 +76.77,50.41932259,-3.585479525,50,-17.31836741,9.999660093,0,0,0,150 +76.78,50.41932104,-3.585478118,50,-17.31489121,9.999660421,0,0,0,150 +76.79,50.41931948,-3.585476711,50,-17.3183674,9.999882846,0,0,0,150 +76.8,50.41931792,-3.585475304,50,-17.3148912,10.00054946,0,0,0,150 +76.81,50.41931637,-3.585473897,50,-17.31489119,10.00077189,0,0,0,150 +76.82,50.41931481,-3.585472489,50,-17.31836736,9.999883828,0,0,0,150 +76.83,50.41931325,-3.585471083,50,-17.31489118,9.99966206,0,0,0,150 +76.84,50.4193117,-3.585469676,50,-17.31836738,10.00077287,0,0,0,150 +76.85,50.41931014,-3.585468268,50,-17.33227213,10.0007732,0,0,0,150 +76.86,50.41930858,-3.585466861,50,-17.33227212,9.999663044,0,0,0,150 +76.87,50.41930702,-3.585465455,50,-17.31836736,9.999885468,0,0,0,150 +76.88,50.41930547,-3.585464047,50,-17.31489117,10.00077418,0,0,0,150 +76.89,50.41930391,-3.58546264,50,-17.31836734,10.00055241,0,0,0,150 +76.9,50.41930235,-3.585461233,50,-17.31489114,9.999886451,0,0,0,150 +76.91,50.4193008,-3.585459826,50,-17.31836733,9.999664683,0,0,0,150 +76.92,50.41929924,-3.585458419,50,-17.3322721,9.999665011,0,0,0,150 +76.93,50.41929768,-3.585457012,50,-17.33227209,9.999887435,0,0,0,150 +76.94,50.41929612,-3.585455605,50,-17.31836732,10.00099824,0,0,0,150 +76.95,50.41929457,-3.585454198,50,-17.3183673,10.00344163,0,0,0,150 +76.96,50.41929301,-3.58545279,50,-17.33574824,10.0069955,0,0,0,150 +76.97,50.41929145,-3.585451382,50,-17.34965299,10.01165986,0,0,0,150 +76.98,50.41928989,-3.585449973,50,-17.35312919,10.01743469,0,0,0,150 +76.99,50.41928833,-3.585448563,50,-17.35312919,10.02320952,0,0,0,150 +77,50.41928677,-3.585447152,50,-17.35660538,10.02809597,0,0,0,150 +77.01,50.41928521,-3.585445741,50,-17.37051011,10.03276033,0,0,0,150 +77.02,50.41928365,-3.585444329,50,-17.39136722,10.03764678,0,0,0,150 +77.03,50.41928208,-3.585442916,50,-17.40527196,10.04231113,0,0,0,150 +77.04,50.41928052,-3.585441503,50,-17.40874816,10.04719759,0,0,0,150 +77.05,50.41927895,-3.585440089,50,-17.41222435,10.05297242,0,0,0,150 +77.06,50.41927739,-3.585438674,50,-17.4226529,10.05852517,0,0,0,150 +77.07,50.41927582,-3.585437258,50,-17.42960526,10.06274533,0,0,0,150 +77.08,50.41927425,-3.585435842,50,-17.42612907,10.06718759,0,0,0,150 +77.09,50.41927269,-3.585434426,50,-17.42960526,10.07318453,0,0,0,150 +77.1,50.41927112,-3.585433007,50,-17.4469862,10.07873727,0,0,0,150 +77.11,50.41926955,-3.585431589,50,-17.46436713,10.08251324,0,0,0,150 +77.12,50.41926798,-3.58543017,50,-17.48174806,10.08651131,0,0,0,150 +77.13,50.41926641,-3.585428751,50,-17.49912898,10.09184196,0,0,0,150 +77.14,50.41926483,-3.58542733,50,-17.50260517,10.09695052,0,0,0,150 +77.15,50.41926326,-3.585425909,50,-17.49912899,10.10139278,0,0,0,150 +77.16,50.41926169,-3.585424488,50,-17.50608137,10.10672343,0,0,0,150 +77.17,50.41926011,-3.585423065,50,-17.51650993,10.11316457,0,0,0,150 +77.18,50.41925854,-3.585421642,50,-17.51998611,10.11916151,0,0,0,150 +77.19,50.41925696,-3.585420217,50,-17.52346228,10.12404797,0,0,0,150 +77.2,50.41925539,-3.585418793,50,-17.53736702,10.12849023,0,0,0,150 +77.21,50.41925381,-3.585417367,50,-17.55822414,10.1327104,0,0,0,150 +77.22,50.41925223,-3.585415941,50,-17.57212889,10.13693057,0,0,0,150 +77.23,50.41925065,-3.585414515,50,-17.57560509,10.14203913,0,0,0,150 +77.24,50.41924907,-3.585413087,50,-17.57560509,10.14759188,0,0,0,150 +77.25,50.41924749,-3.585411659,50,-17.57560507,10.15247835,0,0,0,150 +77.26,50.41924591,-3.58541023,50,-17.57908124,10.15736481,0,0,0,150 +77.27,50.41924433,-3.585408801,50,-17.59298598,10.16313966,0,0,0,150 +77.28,50.41924275,-3.58540737,50,-17.61384311,10.16891451,0,0,0,150 +77.29,50.41924116,-3.585405939,50,-17.62774786,10.17357887,0,0,0,150 +77.3,50.41923958,-3.585404507,50,-17.63122406,10.17757695,0,0,0,150 +77.31,50.41923799,-3.585403075,50,-17.63470024,10.18201922,0,0,0,150 +77.32,50.41923641,-3.585401642,50,-17.64512879,10.18690569,0,0,0,150 +77.33,50.41923482,-3.585400208,50,-17.65208116,10.19157006,0,0,0,150 +77.34,50.41923323,-3.585398774,50,-17.64860497,10.19645653,0,0,0,150 +77.35,50.41923165,-3.585397339,50,-17.65208115,10.20223138,0,0,0,150 +77.36,50.41923006,-3.585395903,50,-17.67293827,10.20800623,0,0,0,150 +77.37,50.41922847,-3.585394466,50,-17.70074776,10.2128927,0,0,0,150 +77.38,50.41922688,-3.585393029,50,-17.72160488,10.21755707,0,0,0,150 +77.39,50.41922528,-3.585391591,50,-17.72160487,10.22266564,0,0,0,150 +77.4,50.41922369,-3.585390152,50,-17.70770012,10.2279963,0,0,0,150 +77.41,50.4192221,-3.585388713,50,-17.70770013,10.23310487,0,0,0,150 +77.42,50.41922051,-3.585387272,50,-17.72508108,10.23776924,0,0,0,150 +77.43,50.41921891,-3.585385832,50,-17.74246201,10.24243362,0,0,0,150 +77.44,50.41921732,-3.58538439,50,-17.75636675,10.24754219,0,0,0,150 +77.45,50.41921572,-3.585382948,50,-17.7633191,10.25287285,0,0,0,150 +77.46,50.41921412,-3.585381505,50,-17.7598429,10.25798142,0,0,0,150 +77.47,50.41921253,-3.585380061,50,-17.76331909,10.2626458,0,0,0,150 +77.48,50.41921093,-3.585378617,50,-17.78070003,10.26753227,0,0,0,150 +77.49,50.41920933,-3.585377172,50,-17.79460478,10.27330713,0,0,0,150 +77.5,50.41920773,-3.585375726,50,-17.80155715,10.27908199,0,0,0,150 +77.51,50.41920613,-3.585374279,50,-17.81546189,10.28374637,0,0,0,150 +77.52,50.41920453,-3.585372832,50,-17.83284283,10.28752236,0,0,0,150 +77.53,50.41920292,-3.585371384,50,-17.83631901,10.29129836,0,0,0,150 +77.54,50.41920132,-3.585369936,50,-17.83284281,10.29596274,0,0,0,150 +77.55,50.41919972,-3.585368487,50,-17.83979518,10.3017376,0,0,0,150 +77.56,50.41919811,-3.585367037,50,-17.85369993,10.30773456,0,0,0,150 +77.57,50.41919651,-3.585365586,50,-17.86760468,10.31328733,0,0,0,150 +77.58,50.4191949,-3.585364135,50,-17.87455705,10.31839591,0,0,0,150 +77.59,50.41919329,-3.585362682,50,-17.87108086,10.32306029,0,0,0,150 +77.6,50.41919169,-3.58536123,50,-17.87455704,10.32772467,0,0,0,150 +77.61,50.41919008,-3.585359776,50,-17.89193797,10.33283325,0,0,0,150 +77.62,50.41918847,-3.585358322,50,-17.90584271,10.33816392,0,0,0,150 +77.63,50.41918686,-3.585356867,50,-17.91279509,10.3432725,0,0,0,150 +77.64,50.41918525,-3.585355411,50,-17.92669984,10.34793689,0,0,0,150 +77.65,50.41918364,-3.585353955,50,-17.94408077,10.35282337,0,0,0,150 +77.66,50.41918202,-3.585352498,50,-17.94755695,10.35837614,0,0,0,150 +77.67,50.41918041,-3.58535104,50,-17.94408077,10.36326262,0,0,0,150 +77.68,50.4191788,-3.585349581,50,-17.95103314,10.36703862,0,0,0,150 +77.69,50.41917718,-3.585348123,50,-17.96493787,10.37170301,0,0,0,150 +77.7,50.41917557,-3.585346663,50,-17.9823188,10.37792208,0,0,0,150 +77.71,50.41917395,-3.585345202,50,-17.99969974,10.38414115,0,0,0,150 +77.72,50.41917233,-3.585343741,50,-17.99969974,10.38924973,0,0,0,150 +77.73,50.41917071,-3.585342278,50,-17.98579499,10.39324783,0,0,0,150 +77.74,50.4191691,-3.585340816,50,-17.98579499,10.39746802,0,0,0,150 +77.75,50.41916748,-3.585339353,50,-18.00665209,10.4027987,0,0,0,150 +77.76,50.41916586,-3.585337888,50,-18.03446157,10.40812938,0,0,0,150 +77.77,50.41916424,-3.585336424,50,-18.05531869,10.41301587,0,0,0,150 +77.78,50.41916261,-3.585334958,50,-18.05879488,10.41812446,0,0,0,150 +77.79,50.41916099,-3.585333492,50,-18.0553187,10.42323304,0,0,0,150 +77.8,50.41915937,-3.585332025,50,-18.06227108,10.42767534,0,0,0,150 +77.81,50.41915774,-3.585330557,50,-18.07269965,10.43211764,0,0,0,150 +77.82,50.41915612,-3.58532909,50,-18.07617584,10.43789252,0,0,0,150 +77.83,50.41915449,-3.58532762,50,-18.07965201,10.44388949,0,0,0,150 +77.84,50.41915287,-3.58532615,50,-18.09355675,10.44833179,0,0,0,150 +77.85,50.41915124,-3.58532468,50,-18.11441387,10.45232989,0,0,0,150 +77.86,50.41914961,-3.585323209,50,-18.1283186,10.45721639,0,0,0,150 +77.87,50.41914798,-3.585321737,50,-18.13179478,10.46254707,0,0,0,150 +77.88,50.41914635,-3.585320265,50,-18.13179477,10.46765567,0,0,0,150 +77.89,50.41914472,-3.585318791,50,-18.13179478,10.47254216,0,0,0,150 +77.9,50.41914309,-3.585317318,50,-18.13527097,10.47809495,0,0,0,150 +77.91,50.41914146,-3.585315843,50,-18.14917572,10.48431402,0,0,0,150 +77.92,50.41913983,-3.585314367,50,-18.16655665,10.48964471,0,0,0,150 +77.93,50.41913819,-3.585312891,50,-18.17003283,10.49364282,0,0,0,150 +77.94,50.41913656,-3.585311414,50,-18.17003283,10.49741883,0,0,0,150 +77.95,50.41913493,-3.585309937,50,-18.18741375,10.50208323,0,0,0,150 +77.96,50.41913329,-3.585308459,50,-18.20479468,10.50785812,0,0,0,150 +77.97,50.41913165,-3.58530698,50,-18.20479467,10.51363301,0,0,0,150 +77.98,50.41913002,-3.5853055,50,-18.20827086,10.51829741,0,0,0,150 +77.99,50.41912838,-3.58530402,50,-18.22565179,10.52229552,0,0,0,150 +78,50.41912674,-3.585302539,50,-18.23955653,10.52695992,0,0,0,150 +78.01,50.4191251,-3.585301058,50,-18.24650891,10.53251271,0,0,0,150 +78.02,50.41912346,-3.585299575,50,-18.26041365,10.53762131,0,0,0,150 +78.03,50.41912182,-3.585298092,50,-18.27779459,10.54228572,0,0,0,150 +78.04,50.41912017,-3.585296609,50,-18.28127078,10.54806061,0,0,0,150 +78.05,50.41911853,-3.585295124,50,-18.27779459,10.5540576,0,0,0,150 +78.06,50.41911689,-3.585293638,50,-18.28474695,10.558722,0,0,0,150 +78.07,50.41911524,-3.585292153,50,-18.29517549,10.56360851,0,0,0,150 +78.08,50.4191136,-3.585290666,50,-18.29865167,10.5693834,0,0,0,150 +78.09,50.41911195,-3.585289178,50,-18.30212787,10.57404781,0,0,0,150 +78.1,50.41911031,-3.58528769,50,-18.31603263,10.57760173,0,0,0,150 +78.11,50.41910866,-3.585286202,50,-18.33688974,10.58159985,0,0,0,150 +78.12,50.41910701,-3.585284712,50,-18.35079447,10.58626425,0,0,0,150 +78.13,50.41910536,-3.585283223,50,-18.35427065,10.59181705,0,0,0,150 +78.14,50.41910371,-3.585281732,50,-18.35427067,10.59803614,0,0,0,150 +78.15,50.41910206,-3.58528024,50,-18.35774686,10.60358894,0,0,0,150 +78.16,50.41910041,-3.585278748,50,-18.3716516,10.60847545,0,0,0,150 +78.17,50.41909876,-3.585277255,50,-18.38903251,10.61336196,0,0,0,150 +78.18,50.4190971,-3.585275761,50,-18.39250869,10.61802637,0,0,0,150 +78.19,50.41909545,-3.585274267,50,-18.38903252,10.62291288,0,0,0,150 +78.2,50.4190938,-3.585272772,50,-18.39598489,10.62868778,0,0,0,150 +78.21,50.41909214,-3.585271276,50,-18.40988962,10.63446268,0,0,0,150 +78.22,50.41909049,-3.585269779,50,-18.42727055,10.6391271,0,0,0,150 +78.23,50.41908883,-3.585268282,50,-18.44812768,10.64290312,0,0,0,150 +78.24,50.41908717,-3.585266784,50,-18.46203243,10.64667915,0,0,0,150 +78.25,50.41908551,-3.585265286,50,-18.4655086,10.65134356,0,0,0,150 +78.26,50.41908385,-3.585263787,50,-18.4655086,10.65734056,0,0,0,150 +78.27,50.41908219,-3.585262287,50,-18.4655086,10.66400386,0,0,0,150 +78.28,50.41908053,-3.585260786,50,-18.46550859,10.67000086,0,0,0,150 +78.29,50.41907887,-3.585259284,50,-18.46898477,10.67466528,0,0,0,150 +78.3,50.41907721,-3.585257782,50,-18.48288951,10.6784413,0,0,0,150 +78.31,50.41907555,-3.585256279,50,-18.50374665,10.68221733,0,0,0,150 +78.32,50.41907388,-3.585254776,50,-18.5176514,10.68688175,0,0,0,150 +78.33,50.41907222,-3.585253272,50,-18.52112756,10.69265666,0,0,0,150 +78.34,50.41907055,-3.585251767,50,-18.52460374,10.69843157,0,0,0,150 +78.35,50.41906889,-3.585250261,50,-18.53850848,10.70331808,0,0,0,150 +78.36,50.41906722,-3.585248755,50,-18.55936561,10.70798251,0,0,0,150 +78.37,50.41906555,-3.585247248,50,-18.57327035,10.71309112,0,0,0,150 +78.38,50.41906388,-3.58524574,50,-18.57674655,10.71842184,0,0,0,150 +78.39,50.41906221,-3.585244232,50,-18.57674654,10.72353045,0,0,0,150 +78.4,50.41906054,-3.585242722,50,-18.57674653,10.72819488,0,0,0,150 +78.41,50.41905887,-3.585241213,50,-18.57674652,10.7328593,0,0,0,150 +78.42,50.4190572,-3.585239702,50,-18.5802227,10.73796792,0,0,0,150 +78.43,50.41905553,-3.585238191,50,-18.59412745,10.74329864,0,0,0,150 +78.44,50.41905386,-3.585236679,50,-18.61498458,10.74840726,0,0,0,150 +78.45,50.41905218,-3.585235166,50,-18.63236552,10.75307168,0,0,0,150 +78.46,50.41905051,-3.585233653,50,-18.64627025,10.75795821,0,0,0,150 +78.47,50.41904883,-3.585232139,50,-18.65322261,10.76373312,0,0,0,150 +78.48,50.41904715,-3.585230624,50,-18.64974642,10.76950804,0,0,0,150 +78.49,50.41904548,-3.585229108,50,-18.65322261,10.77439456,0,0,0,150 +78.5,50.4190438,-3.585227592,50,-18.67060354,10.77905899,0,0,0,150 +78.51,50.41904212,-3.585226075,50,-18.68450828,10.78394552,0,0,0,150 +78.52,50.41904044,-3.585224557,50,-18.68798446,10.78838785,0,0,0,150 +78.53,50.41903876,-3.585223039,50,-18.68798447,10.79238599,0,0,0,150 +78.54,50.41903708,-3.58522152,50,-18.69146065,10.79705042,0,0,0,150 +78.55,50.4190354,-3.585220001,50,-18.7053654,10.80282534,0,0,0,150 +78.56,50.41903372,-3.58521848,50,-18.72622252,10.80860026,0,0,0,150 +78.57,50.41903203,-3.585216959,50,-18.74012725,10.81348679,0,0,0,150 +78.58,50.41903035,-3.585215437,50,-18.74360343,10.81815122,0,0,0,150 +78.59,50.41902866,-3.585213915,50,-18.74707961,10.82303775,0,0,0,150 +78.6,50.41902698,-3.585212391,50,-18.75750818,10.82792428,0,0,0,150 +78.61,50.41902529,-3.585210868,50,-18.76446055,10.83325501,0,0,0,150 +78.62,50.4190236,-3.585209343,50,-18.76098435,10.83858574,0,0,0,150 +78.63,50.41902192,-3.585207817,50,-18.76446053,10.84302807,0,0,0,150 +78.64,50.41902023,-3.585206292,50,-18.78184146,10.84791461,0,0,0,150 +78.65,50.41901854,-3.585204765,50,-18.7992224,10.85391163,0,0,0,150 +78.66,50.41901685,-3.585203237,50,-18.81660334,10.85924236,0,0,0,150 +78.67,50.41901516,-3.585201709,50,-18.83398427,10.8634626,0,0,0,150 +78.68,50.41901346,-3.58520018,50,-18.83398426,10.86812704,0,0,0,150 +78.69,50.41901177,-3.585198651,50,-18.8200795,10.87367987,0,0,0,150 +78.7,50.41901008,-3.58519712,50,-18.82355567,10.8787885,0,0,0,150 +78.71,50.41900839,-3.585195589,50,-18.85136517,10.88323084,0,0,0,150 +78.72,50.41900669,-3.585194058,50,-18.87222231,10.88811738,0,0,0,150 +78.73,50.41900499,-3.585192525,50,-18.87222231,10.89300392,0,0,0,150 +78.74,50.4190033,-3.585190992,50,-18.87569848,10.89744626,0,0,0,150 +78.75,50.4190016,-3.585189459,50,-18.89307941,10.9025549,0,0,0,150 +78.76,50.4189999,-3.585187924,50,-18.90698416,10.90832983,0,0,0,150 +78.77,50.4189982,-3.585186389,50,-18.91046034,10.91388266,0,0,0,150 +78.78,50.4189965,-3.585184853,50,-18.91046032,10.9189913,0,0,0,150 +78.79,50.4189948,-3.585183316,50,-18.91046031,10.92365575,0,0,0,150 +78.8,50.4189931,-3.585181779,50,-18.9139365,10.92832019,0,0,0,150 +78.81,50.4189914,-3.585180241,50,-18.92784126,10.93320673,0,0,0,150 +78.82,50.4189897,-3.585178702,50,-18.94869838,10.93787118,0,0,0,150 +78.83,50.41898799,-3.585177163,50,-18.96260311,10.94275772,0,0,0,150 +78.84,50.41898629,-3.585175623,50,-18.96607929,10.94853266,0,0,0,150 +78.85,50.41898458,-3.585174082,50,-18.96955547,10.95430759,0,0,0,150 +78.86,50.41898288,-3.58517254,50,-18.97998403,10.95919414,0,0,0,150 +78.87,50.41898117,-3.585170998,50,-18.98693642,10.96385859,0,0,0,150 +78.88,50.41897946,-3.585169455,50,-18.98346024,10.96874513,0,0,0,150 +78.89,50.41897776,-3.585167911,50,-18.98693641,10.97340958,0,0,0,150 +78.9,50.41897605,-3.585166367,50,-19.00779351,10.97807403,0,0,0,150 +78.91,50.41897434,-3.585164822,50,-19.035603,10.98296058,0,0,0,150 +78.92,50.41897263,-3.585163276,50,-19.05646012,10.98762503,0,0,0,150 +78.93,50.41897091,-3.58516173,50,-19.05646012,10.99251158,0,0,0,150 +78.94,50.4189692,-3.585160183,50,-19.04255536,10.99828652,0,0,0,150 +78.95,50.41896749,-3.585158635,50,-19.04255536,11.00406146,0,0,0,150 +78.96,50.41896578,-3.585157086,50,-19.05993629,11.00894801,0,0,0,150 +78.97,50.41896406,-3.585155537,50,-19.07731723,11.01361246,0,0,0,150 +78.98,50.41896235,-3.585153987,50,-19.09122197,11.01849902,0,0,0,150 +78.99,50.41896063,-3.585152436,50,-19.09817434,11.02316347,0,0,0,150 +79,50.41895891,-3.585150885,50,-19.09469815,11.02805002,0,0,0,150 +79.01,50.4189572,-3.585149333,50,-19.09817433,11.03382497,0,0,0,150 +79.02,50.41895548,-3.58514778,50,-19.11555526,11.03959991,0,0,0,150 +79.03,50.41895376,-3.585146226,50,-19.12946,11.04426437,0,0,0,150 +79.04,50.41895204,-3.585144672,50,-19.13641237,11.04826253,0,0,0,150 +79.05,50.41895032,-3.585143117,50,-19.15031712,11.05292699,0,0,0,150 +79.06,50.4189486,-3.585141562,50,-19.16769806,11.05870194,0,0,0,150 +79.07,50.41894687,-3.585140005,50,-19.17117424,11.06447688,0,0,0,150 +79.08,50.41894515,-3.585138448,50,-19.16769805,11.06914134,0,0,0,150 +79.09,50.41894343,-3.58513689,50,-19.17465042,11.07313951,0,0,0,150 +79.1,50.4189417,-3.585135332,50,-19.18855516,11.07780397,0,0,0,150 +79.11,50.41893998,-3.585133773,50,-19.20245989,11.08357892,0,0,0,150 +79.12,50.41893825,-3.585132213,50,-19.20941225,11.08935387,0,0,0,150 +79.13,50.41893652,-3.585130652,50,-19.20593605,11.09424043,0,0,0,150 +79.14,50.4189348,-3.585129091,50,-19.20941225,11.09890489,0,0,0,150 +79.15,50.41893307,-3.585127529,50,-19.22679319,11.10379145,0,0,0,150 +79.16,50.41893134,-3.585125966,50,-19.24069794,11.10845592,0,0,0,150 +79.17,50.41892961,-3.585124403,50,-19.24765031,11.11334248,0,0,0,150 +79.18,50.41892788,-3.585122839,50,-19.26155505,11.11889533,0,0,0,150 +79.19,50.41892615,-3.585121274,50,-19.27893597,11.124004,0,0,0,150 +79.2,50.41892441,-3.585119708,50,-19.28241215,11.12844636,0,0,0,150 +79.21,50.41892268,-3.585118143,50,-19.27893597,11.13333293,0,0,0,150 +79.22,50.41892095,-3.585116575,50,-19.28588835,11.13821949,0,0,0,150 +79.23,50.41891921,-3.585115008,50,-19.29979309,11.14266186,0,0,0,150 +79.24,50.41891748,-3.58511344,50,-19.31717401,11.14777053,0,0,0,150 +79.25,50.41891574,-3.585111871,50,-19.33455493,11.15354548,0,0,0,150 +79.26,50.418914,-3.585110301,50,-19.33455494,11.15909835,0,0,0,150 +79.27,50.41891226,-3.585108731,50,-19.32065018,11.16420701,0,0,0,150 +79.28,50.41891053,-3.585107159,50,-19.32412635,11.16887148,0,0,0,150 +79.29,50.41890879,-3.585105588,50,-19.35541204,11.17353595,0,0,0,150 +79.3,50.41890705,-3.585104015,50,-19.38669773,11.17864462,0,0,0,150 +79.31,50.4189053,-3.585102442,50,-19.39017391,11.18397538,0,0,0,150 +79.32,50.41890356,-3.585100868,50,-19.37626915,11.18908405,0,0,0,150 +79.33,50.41890182,-3.585099293,50,-19.37626914,11.19374852,0,0,0,150 +79.34,50.41890008,-3.585097718,50,-19.39365008,11.198413,0,0,0,150 +79.35,50.41889833,-3.585096142,50,-19.40755482,11.20352167,0,0,0,150 +79.36,50.41889659,-3.585094565,50,-19.411031,11.20907453,0,0,0,150 +79.37,50.41889484,-3.585092988,50,-19.41450718,11.2148495,0,0,0,150 +79.38,50.4188931,-3.585091409,50,-19.42841192,11.21973607,0,0,0,150 +79.39,50.41889135,-3.58508983,50,-19.44926905,11.22329006,0,0,0,150 +79.4,50.4188896,-3.585088251,50,-19.4631738,11.22728824,0,0,0,150 +79.41,50.41888785,-3.585086671,50,-19.46664998,11.23284111,0,0,0,150 +79.42,50.4188861,-3.58508509,50,-19.46664997,11.23861608,0,0,0,150 +79.43,50.41888435,-3.585083508,50,-19.46664996,11.24350265,0,0,0,150 +79.44,50.4188826,-3.585081926,50,-19.47012615,11.24838923,0,0,0,150 +79.45,50.41888085,-3.585080343,50,-19.4840309,11.2541642,0,0,0,150 +79.46,50.4188791,-3.585078759,50,-19.50488801,11.25971707,0,0,0,150 +79.47,50.41887734,-3.585077174,50,-19.51879274,11.26393736,0,0,0,150 +79.48,50.41887559,-3.585075589,50,-19.52226892,11.26837974,0,0,0,150 +79.49,50.41887383,-3.585074004,50,-19.52574511,11.27437681,0,0,0,150 +79.5,50.41887208,-3.585072416,50,-19.53617367,11.28015178,0,0,0,150 +79.51,50.41887032,-3.585070829,50,-19.54312604,11.28459417,0,0,0,150 +79.52,50.41886856,-3.585069241,50,-19.53964985,11.28881445,0,0,0,150 +79.53,50.41886681,-3.585067652,50,-19.54312604,11.29325684,0,0,0,150 +79.54,50.41886505,-3.585066063,50,-19.56050696,11.29792132,0,0,0,150 +79.55,50.41886329,-3.585064473,50,-19.57788789,11.3028079,0,0,0,150 +79.56,50.41886153,-3.585062882,50,-19.59526882,11.30747239,0,0,0,150 +79.57,50.41885977,-3.585061291,50,-19.61264976,11.31235897,0,0,0,150 +79.58,50.418858,-3.585059699,50,-19.61612594,11.31835605,0,0,0,150 +79.59,50.41885624,-3.585058106,50,-19.61264973,11.32479732,0,0,0,150 +79.6,50.41885448,-3.585056512,50,-19.61960209,11.3301281,0,0,0,150 +79.61,50.41885271,-3.585054917,50,-19.63003066,11.33457049,0,0,0,150 +79.62,50.41885095,-3.585053323,50,-19.63350686,11.33945708,0,0,0,150 +79.63,50.41884918,-3.585051726,50,-19.63698304,11.34434367,0,0,0,150 +79.64,50.41884742,-3.58505013,50,-19.65088778,11.34856396,0,0,0,150 +79.65,50.41884565,-3.585048533,50,-19.67174489,11.35300635,0,0,0,150 +79.66,50.41884388,-3.585046935,50,-19.68564963,11.35833714,0,0,0,150 +79.67,50.41884211,-3.585045337,50,-19.68912582,11.36411212,0,0,0,150 +79.68,50.41884034,-3.585043737,50,-19.68912582,11.36922081,0,0,0,150 +79.69,50.41883857,-3.585042137,50,-19.692602,11.3736632,0,0,0,150 +79.7,50.4188368,-3.585040537,50,-19.70650674,11.37877189,0,0,0,150 +79.71,50.41883503,-3.585038935,50,-19.72388767,11.38432478,0,0,0,150 +79.72,50.41883325,-3.585037333,50,-19.72736386,11.38898927,0,0,0,150 +79.73,50.41883148,-3.58503573,50,-19.72736385,11.39298747,0,0,0,150 +79.74,50.41882971,-3.585034127,50,-19.74474478,11.39765196,0,0,0,150 +79.75,50.41882793,-3.585032523,50,-19.7621257,11.40342695,0,0,0,150 +79.76,50.41882615,-3.585030918,50,-19.76212569,11.40920194,0,0,0,150 +79.77,50.41882438,-3.585029312,50,-19.76560187,11.41408853,0,0,0,150 +79.78,50.4188226,-3.585027706,50,-19.78298281,11.41875303,0,0,0,150 +79.79,50.41882082,-3.585026099,50,-19.79688756,11.42386172,0,0,0,150 +79.8,50.41881904,-3.585024491,50,-19.80036375,11.42919252,0,0,0,150 +79.81,50.41881726,-3.585022883,50,-19.80036374,11.43430121,0,0,0,150 +79.82,50.41881548,-3.585021273,50,-19.8038399,11.43896571,0,0,0,150 +79.83,50.4188137,-3.585019664,50,-19.81774464,11.44363021,0,0,0,150 +79.84,50.41881192,-3.585018053,50,-19.83512559,11.44873891,0,0,0,150 +79.85,50.41881013,-3.585016442,50,-19.83860178,11.45406971,0,0,0,150 +79.86,50.41880835,-3.58501483,50,-19.83860177,11.45917841,0,0,0,150 +79.87,50.41880657,-3.585013217,50,-19.8559827,11.46384291,0,0,0,150 +79.88,50.41880478,-3.585011604,50,-19.87336363,11.46850741,0,0,0,150 +79.89,50.41880299,-3.58500999,50,-19.87336362,11.47361611,0,0,0,150 +79.9,50.41880121,-3.585008375,50,-19.8768398,11.47916901,0,0,0,150 +79.91,50.41879942,-3.58500676,50,-19.89422072,11.48494401,0,0,0,150 +79.92,50.41879763,-3.585005143,50,-19.90812546,11.49005271,0,0,0,150 +79.93,50.41879584,-3.585003526,50,-19.91160165,11.49427302,0,0,0,150 +79.94,50.41879405,-3.585001909,50,-19.91160167,11.49849332,0,0,0,150 +79.95,50.41879226,-3.58500029,50,-19.91507786,11.50315783,0,0,0,150 +79.96,50.41879047,-3.584998672,50,-19.92898259,11.50871073,0,0,0,150 +79.97,50.41878868,-3.584997052,50,-19.94636351,11.51492993,0,0,0,150 +79.98,50.41878688,-3.584995431,50,-19.94983968,11.52026073,0,0,0,150 +79.99,50.41878509,-3.58499381,50,-19.94983967,11.52425895,0,0,0,150 +80,50.4187833,-3.584992188,50,-19.9672206,11.52825716,0,0,0,150 +80.01,50.4187815,-3.584990566,50,-19.98460153,11.53358797,0,0,0,150 +80.02,50.4187797,-3.584988943,50,-19.98460153,11.53958507,0,0,0,150 +80.03,50.41877791,-3.584987318,50,-19.98807771,11.54424958,0,0,0,150 +80.04,50.41877611,-3.584985694,50,-20.00545865,11.54802569,0,0,0,150 +80.05,50.41877431,-3.584984069,50,-20.01936341,11.5531344,0,0,0,150 +80.06,50.41877251,-3.584982443,50,-20.02283959,11.5595757,0,0,0,150 +80.07,50.41877071,-3.584980816,50,-20.02631576,11.56535071,0,0,0,150 +80.08,50.41876891,-3.584979188,50,-20.0402205,11.56934893,0,0,0,150 +80.09,50.41876711,-3.58497756,50,-20.05760143,11.57312505,0,0,0,150 +80.1,50.4187653,-3.584975932,50,-20.06107761,11.57867796,0,0,0,150 +80.11,50.4187635,-3.584974302,50,-20.05760142,11.58467507,0,0,0,150 +80.12,50.4187617,-3.584972671,50,-20.06455378,11.58911748,0,0,0,150 +80.13,50.41875989,-3.584971041,50,-20.07845853,11.5931157,0,0,0,150 +80.14,50.41875809,-3.584969409,50,-20.09583945,11.59800232,0,0,0,150 +80.15,50.41875628,-3.584967777,50,-20.11322037,11.60355523,0,0,0,150 +80.16,50.41875447,-3.584966144,50,-20.11322037,11.60955234,0,0,0,150 +80.17,50.41875266,-3.58496451,50,-20.09931562,11.61532735,0,0,0,150 +80.18,50.41875086,-3.584962875,50,-20.10279181,11.61999187,0,0,0,150 +80.19,50.41874905,-3.58496124,50,-20.1340775,11.6239901,0,0,0,150 +80.2,50.41874724,-3.584959604,50,-20.16536318,11.62865462,0,0,0,150 +80.21,50.41874542,-3.584957968,50,-20.16883936,11.63442963,0,0,0,150 +80.22,50.41874361,-3.58495633,50,-20.1549346,11.64020465,0,0,0,150 +80.23,50.4187418,-3.584954692,50,-20.1549346,11.64486917,0,0,0,150 +80.24,50.41873999,-3.584953053,50,-20.17231553,11.64886739,0,0,0,150 +80.25,50.41873817,-3.584951414,50,-20.18622026,11.65353192,0,0,0,150 +80.26,50.41873636,-3.584949774,50,-20.18969643,11.65930694,0,0,0,150 +80.27,50.41873454,-3.584948133,50,-20.19317262,11.66508196,0,0,0,150 +80.28,50.41873273,-3.584946491,50,-20.20707737,11.66974648,0,0,0,150 +80.29,50.41873091,-3.584944849,50,-20.2279345,11.67374471,0,0,0,150 +80.3,50.41872909,-3.584943206,50,-20.24183925,11.67840923,0,0,0,150 +80.31,50.41872727,-3.584941563,50,-20.24531542,11.68396216,0,0,0,150 +80.32,50.41872545,-3.584939918,50,-20.2453154,11.68907088,0,0,0,150 +80.33,50.41872363,-3.584938273,50,-20.24879158,11.69351331,0,0,0,150 +80.34,50.41872181,-3.584936628,50,-20.26269634,11.69862204,0,0,0,150 +80.35,50.41871999,-3.584934981,50,-20.28007727,11.70417496,0,0,0,150 +80.36,50.41871816,-3.584933334,50,-20.28355343,11.70906159,0,0,0,150 +80.37,50.41871634,-3.584931686,50,-20.28007722,11.71394822,0,0,0,150 +80.38,50.41871452,-3.584930038,50,-20.2870296,11.71972324,0,0,0,150 +80.39,50.41871269,-3.584928388,50,-20.30093436,11.72549827,0,0,0,150 +80.4,50.41871087,-3.584926738,50,-20.31831529,11.7301628,0,0,0,150 +80.41,50.41870904,-3.584925087,50,-20.33917241,11.73416103,0,0,0,150 +80.42,50.41870721,-3.584923436,50,-20.35307717,11.73860347,0,0,0,150 +80.43,50.41870538,-3.584921784,50,-20.35655335,11.7437122,0,0,0,150 +80.44,50.41870355,-3.584920131,50,-20.35655333,11.74904303,0,0,0,150 +80.45,50.41870172,-3.584918478,50,-20.35655332,11.75415176,0,0,0,150 +80.46,50.41869989,-3.584916823,50,-20.35655331,11.7588163,0,0,0,150 +80.47,50.41869806,-3.584915169,50,-20.36002948,11.76348083,0,0,0,150 +80.48,50.41869623,-3.584913513,50,-20.37393422,11.76858957,0,0,0,150 +80.49,50.4186944,-3.584911857,50,-20.39479135,11.7741425,0,0,0,150 +80.5,50.41869256,-3.5849102,50,-20.4086961,11.77991753,0,0,0,150 +80.51,50.41869073,-3.584908542,50,-20.41217228,11.78480417,0,0,0,150 +80.52,50.41868889,-3.584906883,50,-20.41564846,11.78858031,0,0,0,150 +80.53,50.41868706,-3.584905225,50,-20.42955321,11.79324485,0,0,0,150 +80.54,50.41868522,-3.584903565,50,-20.44693414,11.79924199,0,0,0,150 +80.55,50.41868338,-3.584901904,50,-20.44693412,11.80479492,0,0,0,150 +80.56,50.41868154,-3.584900243,50,-20.43650554,11.80990366,0,0,0,150 +80.57,50.41867971,-3.584898581,50,-20.4504103,11.8154566,0,0,0,150 +80.58,50.41867787,-3.584896918,50,-20.48517218,11.82034324,0,0,0,150 +80.59,50.41867602,-3.584895254,50,-20.49907693,11.82389728,0,0,0,150 +80.6,50.41867418,-3.584893591,50,-20.48864835,11.82789553,0,0,0,150 +80.61,50.41867234,-3.584891926,50,-20.48864832,11.83367057,0,0,0,150 +80.62,50.4186705,-3.584890261,50,-20.50602925,11.84011191,0,0,0,150 +80.63,50.41866865,-3.584888594,50,-20.51993401,11.84544275,0,0,0,150 +80.64,50.41866681,-3.584886927,50,-20.5234102,11.84988519,0,0,0,150 +80.65,50.41866496,-3.58488526,50,-20.52688637,11.85477184,0,0,0,150 +80.66,50.41866312,-3.584883591,50,-20.5407911,11.85965849,0,0,0,150 +80.67,50.41866127,-3.584881922,50,-20.55817204,11.86410093,0,0,0,150 +80.68,50.41865942,-3.584880253,50,-20.55817204,11.86920968,0,0,0,150 +80.69,50.41865757,-3.584878582,50,-20.54774348,11.87476262,0,0,0,150 +80.7,50.41865573,-3.584876911,50,-20.56164821,11.87942717,0,0,0,150 +80.71,50.41865388,-3.584875239,50,-20.59641006,11.88342542,0,0,0,150 +80.72,50.41865202,-3.584873567,50,-20.61031481,11.88808997,0,0,0,150 +80.73,50.41865017,-3.584871894,50,-20.59988626,11.89386502,0,0,0,150 +80.74,50.41864832,-3.58487022,50,-20.59988626,11.89964007,0,0,0,150 +80.75,50.41864647,-3.584868545,50,-20.61726719,11.90452672,0,0,0,150 +80.76,50.41864461,-3.58486687,50,-20.63117192,11.90919127,0,0,0,150 +80.77,50.41864276,-3.584865194,50,-20.63464809,11.91430002,0,0,0,150 +80.78,50.4186409,-3.584863517,50,-20.63812428,11.91963087,0,0,0,150 +80.79,50.41863905,-3.58486184,50,-20.65202902,11.92473962,0,0,0,150 +80.8,50.41863719,-3.584860161,50,-20.67288613,11.92940418,0,0,0,150 +80.81,50.41863533,-3.584858483,50,-20.68679088,11.93406873,0,0,0,150 +80.82,50.41863347,-3.584856803,50,-20.69026707,11.93917749,0,0,0,150 +80.83,50.41863161,-3.584855123,50,-20.69026706,11.94450834,0,0,0,150 +80.84,50.41862975,-3.584853442,50,-20.69026704,11.9496171,0,0,0,150 +80.85,50.41862789,-3.58485176,50,-20.69374323,11.95428165,0,0,0,150 +80.86,50.41862603,-3.584850078,50,-20.70764798,11.95916831,0,0,0,150 +80.87,50.41862417,-3.584848395,50,-20.72502891,11.96494337,0,0,0,150 +80.88,50.4186223,-3.584846711,50,-20.72850508,11.97071842,0,0,0,150 +80.89,50.41862044,-3.584845026,50,-20.72850508,11.97538298,0,0,0,150 +80.9,50.41861858,-3.584843341,50,-20.74588602,11.97938124,0,0,0,150 +80.91,50.41861671,-3.584841655,50,-20.76326695,11.9840458,0,0,0,150 +80.92,50.41861484,-3.584839969,50,-20.76326693,11.98959876,0,0,0,150 +80.93,50.41861298,-3.584838281,50,-20.7667431,11.99470752,0,0,0,150 +80.94,50.41861111,-3.584836593,50,-20.78412404,11.99914998,0,0,0,150 +80.95,50.41860924,-3.584834905,50,-20.79802879,12.00425875,0,0,0,150 +80.96,50.41860737,-3.584833215,50,-20.80150497,12.00981171,0,0,0,150 +80.97,50.4186055,-3.584831525,50,-20.80498114,12.01469837,0,0,0,150 +80.98,50.41860363,-3.584829834,50,-20.81888588,12.01936293,0,0,0,150 +80.99,50.41860176,-3.584828143,50,-20.83626681,12.0242496,0,0,0,150 +81,50.41859988,-3.58482645,50,-20.83974301,12.02913627,0,0,0,150 +81.01,50.41859801,-3.584824758,50,-20.83626681,12.03468923,0,0,0,150 +81.02,50.41859614,-3.584823064,50,-20.84321917,12.0406864,0,0,0,150 +81.03,50.41859426,-3.584821369,50,-20.85712391,12.04535096,0,0,0,150 +81.04,50.41859239,-3.584819674,50,-20.87450483,12.04912713,0,0,0,150 +81.05,50.41859051,-3.584817979,50,-20.89536195,12.0540138,0,0,0,150 +81.06,50.41858863,-3.584816282,50,-20.90926671,12.05978887,0,0,0,150 +81.07,50.41858675,-3.584814585,50,-20.9127429,12.06511974,0,0,0,150 +81.08,50.41858487,-3.584812887,50,-20.91274289,12.06934011,0,0,0,150 +81.09,50.41858299,-3.584811188,50,-20.91274288,12.07289418,0,0,0,150 +81.1,50.41858111,-3.58480949,50,-20.91274286,12.07778085,0,0,0,150 +81.11,50.41857923,-3.58480779,50,-20.91621904,12.08466642,0,0,0,150 +81.12,50.41857735,-3.584806089,50,-20.93012378,12.09132989,0,0,0,150 +81.13,50.41857547,-3.584804387,50,-20.9509809,12.09621656,0,0,0,150 +81.14,50.41857358,-3.584802685,50,-20.96488564,12.09999274,0,0,0,150 +81.15,50.4185717,-3.584800982,50,-20.96836182,12.10376891,0,0,0,150 +81.16,50.41856981,-3.584799279,50,-20.971838,12.10843349,0,0,0,150 +81.17,50.41856793,-3.584797575,50,-20.98226657,12.11420856,0,0,0,150 +81.18,50.41856604,-3.58479587,50,-20.98921893,12.11998364,0,0,0,150 +81.19,50.41856415,-3.584794164,50,-20.98574273,12.12487031,0,0,0,150 +81.2,50.41856227,-3.584792458,50,-20.98921891,12.12975699,0,0,0,150 +81.21,50.41856038,-3.584790751,50,-21.00659985,12.13553207,0,0,0,150 +81.22,50.41855849,-3.584789043,50,-21.02398078,12.14108504,0,0,0,150 +81.23,50.4185566,-3.584787334,50,-21.04136171,12.14508332,0,0,0,150 +81.24,50.41855471,-3.584785625,50,-21.05874263,12.1486374,0,0,0,150 +81.25,50.41855281,-3.584783916,50,-21.06221881,12.15352408,0,0,0,150 +81.26,50.41855092,-3.584782205,50,-21.05874262,12.15929916,0,0,0,150 +81.27,50.41854903,-3.584780494,50,-21.06569499,12.16485215,0,0,0,150 +81.28,50.41854713,-3.584778782,50,-21.07959974,12.16996093,0,0,0,150 +81.29,50.41854524,-3.584777069,50,-21.09350449,12.17462551,0,0,0,150 +81.3,50.41854334,-3.584775356,50,-21.10045685,12.17929009,0,0,0,150 +81.31,50.41854144,-3.584773642,50,-21.09698065,12.18417678,0,0,0,150 +81.32,50.41853955,-3.584771927,50,-21.10045683,12.18906346,0,0,0,150 +81.33,50.41853765,-3.584770212,50,-21.11783775,12.19461644,0,0,0,150 +81.34,50.41853575,-3.584768496,50,-21.13174248,12.20061363,0,0,0,150 +81.35,50.41853385,-3.584766778,50,-21.13869485,12.20527821,0,0,0,150 +81.36,50.41853195,-3.584765061,50,-21.15259961,12.2090544,0,0,0,150 +81.37,50.41853005,-3.584763343,50,-21.16998055,12.21394109,0,0,0,150 +81.38,50.41852814,-3.584761624,50,-21.17345674,12.21971618,0,0,0,150 +81.39,50.41852624,-3.584759904,50,-21.16998053,12.22526917,0,0,0,150 +81.4,50.41852434,-3.584758184,50,-21.17693288,12.23037795,0,0,0,150 +81.41,50.41852243,-3.584756462,50,-21.19083762,12.23504254,0,0,0,150 +81.42,50.41852053,-3.584754741,50,-21.20474238,12.23970713,0,0,0,150 +81.43,50.41851862,-3.584753018,50,-21.21169475,12.24481592,0,0,0,150 +81.44,50.41851671,-3.584751295,50,-21.20821855,12.25014682,0,0,0,150 +81.45,50.41851481,-3.584749571,50,-21.21169472,12.25525561,0,0,0,150 +81.46,50.4185129,-3.584747846,50,-21.22907565,12.2599202,0,0,0,150 +81.47,50.41851099,-3.584746121,50,-21.24298041,12.26458479,0,0,0,150 +81.48,50.41850908,-3.584744395,50,-21.24993277,12.26947149,0,0,0,150 +81.49,50.41850717,-3.584742668,50,-21.26383751,12.27413608,0,0,0,150 +81.5,50.41850526,-3.584740941,50,-21.28121844,12.27880067,0,0,0,150 +81.51,50.41850334,-3.584739213,50,-21.28469463,12.28390947,0,0,0,150 +81.52,50.41850143,-3.584737484,50,-21.28121843,12.28946247,0,0,0,150 +81.53,50.41849952,-3.584735755,50,-21.28817079,12.29545966,0,0,0,150 +81.54,50.4184976,-3.584734024,50,-21.30207553,12.30123476,0,0,0,150 +81.55,50.41849569,-3.584732293,50,-21.31945646,12.30589936,0,0,0,150 +81.56,50.41849377,-3.584730561,50,-21.33683738,12.30989766,0,0,0,150 +81.57,50.41849185,-3.584728829,50,-21.33683738,12.31434016,0,0,0,150 +81.58,50.41848993,-3.584727096,50,-21.32293263,12.31944896,0,0,0,150 +81.59,50.41848802,-3.584725362,50,-21.32293262,12.32477986,0,0,0,150 +81.6,50.4184861,-3.584723628,50,-21.34378974,12.32988866,0,0,0,150 +81.61,50.41848418,-3.584721892,50,-21.37159924,12.33455326,0,0,0,150 +81.62,50.41848226,-3.584720157,50,-21.39245635,12.33921786,0,0,0,150 +81.63,50.41848033,-3.58471842,50,-21.39593253,12.34432666,0,0,0,150 +81.64,50.41847841,-3.584716683,50,-21.39245632,12.34965757,0,0,0,150 +81.65,50.41847649,-3.584714945,50,-21.39940869,12.35476637,0,0,0,150 +81.66,50.41847456,-3.584713206,50,-21.40983726,12.35943098,0,0,0,150 +81.67,50.41847264,-3.584711467,50,-21.41331344,12.36431768,0,0,0,150 +81.68,50.41847071,-3.584709727,50,-21.41678962,12.37009279,0,0,0,150 +81.69,50.41846879,-3.584707986,50,-21.43069435,12.37586789,0,0,0,150 +81.7,50.41846686,-3.584706244,50,-21.45155146,12.3807546,0,0,0,150 +81.71,50.41846493,-3.584704502,50,-21.46545621,12.38541921,0,0,0,150 +81.72,50.418463,-3.584702759,50,-21.4689324,12.39030592,0,0,0,150 +81.73,50.41846107,-3.584701015,50,-21.46893239,12.39497053,0,0,0,150 +81.74,50.41845914,-3.584699271,50,-21.46893238,12.39963513,0,0,0,150 +81.75,50.41845721,-3.584697526,50,-21.47240855,12.40474395,0,0,0,150 +81.76,50.41845528,-3.58469578,50,-21.4863133,12.41007486,0,0,0,150 +81.77,50.41845335,-3.584694034,50,-21.50717043,12.41518367,0,0,0,150 +81.78,50.41845141,-3.584692286,50,-21.52107517,12.41984828,0,0,0,150 +81.79,50.41844948,-3.584690539,50,-21.52455134,12.42451289,0,0,0,150 +81.8,50.41844754,-3.58468879,50,-21.52802752,12.42962171,0,0,0,150 +81.81,50.41844561,-3.584687041,50,-21.53845608,12.43495262,0,0,0,150 +81.82,50.41844367,-3.584685291,50,-21.54540845,12.44006143,0,0,0,150 +81.83,50.41844173,-3.58468354,50,-21.54193225,12.44472605,0,0,0,150 +81.84,50.4184398,-3.584681789,50,-21.54540843,12.44939066,0,0,0,150 +81.85,50.41843786,-3.584680037,50,-21.56278935,12.45449948,0,0,0,150 +81.86,50.41843592,-3.584678284,50,-21.58017028,12.4600525,0,0,0,150 +81.87,50.41843398,-3.584676531,50,-21.59755121,12.46582762,0,0,0,150 +81.88,50.41843204,-3.584674776,50,-21.61493215,12.47071433,0,0,0,150 +81.89,50.41843009,-3.584673021,50,-21.61840833,12.47449055,0,0,0,150 +81.9,50.41842815,-3.584671266,50,-21.61493213,12.47915517,0,0,0,150 +81.91,50.41842621,-3.58466951,50,-21.62188449,12.48515239,0,0,0,150 +81.92,50.41842426,-3.584667752,50,-21.63578924,12.49070541,0,0,0,150 +81.93,50.41842232,-3.584665995,50,-21.64969398,12.49537003,0,0,0,150 +81.94,50.41842037,-3.584664236,50,-21.65664635,12.49959045,0,0,0,150 +81.95,50.41841842,-3.584662477,50,-21.65317015,12.50381087,0,0,0,150 +81.96,50.41841648,-3.584660718,50,-21.65664634,12.5089197,0,0,0,150 +81.97,50.41841453,-3.584658957,50,-21.67402726,12.51469482,0,0,0,150 +81.98,50.41841258,-3.584657196,50,-21.68793201,12.52024785,0,0,0,150 +81.99,50.41841063,-3.584655434,50,-21.69140819,12.52535667,0,0,0,150 +82,50.41840868,-3.584653671,50,-21.69488436,12.5300213,0,0,0,150 +82.01,50.41840673,-3.584651908,50,-21.70878909,12.53490802,0,0,0,150 +82.02,50.41840478,-3.584650144,50,-21.72964622,12.54068315,0,0,0,150 +82.03,50.41840282,-3.584648379,50,-21.74355097,12.54645828,0,0,0,150 +82.04,50.41840087,-3.584646613,50,-21.74702714,12.55112291,0,0,0,150 +82.05,50.41839891,-3.584644847,50,-21.74702712,12.55489913,0,0,0,150 +82.06,50.41839696,-3.58464308,50,-21.74702713,12.55889746,0,0,0,150 +82.07,50.418395,-3.584641313,50,-21.75050332,12.56422839,0,0,0,150 +82.08,50.41839305,-3.584639545,50,-21.76440805,12.57022562,0,0,0,150 +82.09,50.41839109,-3.584637775,50,-21.78526515,12.57489025,0,0,0,150 +82.1,50.41838913,-3.584636006,50,-21.7991699,12.57888858,0,0,0,150 +82.11,50.41838717,-3.584634236,50,-21.8026461,12.58466372,0,0,0,150 +82.12,50.41838521,-3.584632465,50,-21.80264609,12.59132725,0,0,0,150 +82.13,50.41838325,-3.584630692,50,-21.80612225,12.59621399,0,0,0,150 +82.14,50.41838129,-3.58462892,50,-21.82002699,12.59999022,0,0,0,150 +82.15,50.41837933,-3.584627147,50,-21.84088411,12.60487695,0,0,0,150 +82.16,50.41837736,-3.584625373,50,-21.85478886,12.61042999,0,0,0,150 +82.17,50.4183754,-3.584623598,50,-21.85826504,12.61531672,0,0,0,150 +82.18,50.41837343,-3.584621823,50,-21.85826504,12.61998136,0,0,0,150 +82.19,50.41837147,-3.584620047,50,-21.85826504,12.6248681,0,0,0,150 +82.2,50.4183695,-3.58461827,50,-21.86174121,12.62953274,0,0,0,150 +82.21,50.41836754,-3.584616493,50,-21.87564593,12.63441947,0,0,0,150 +82.22,50.41836557,-3.584614715,50,-21.89650304,12.64019461,0,0,0,150 +82.23,50.4183636,-3.584612936,50,-21.91040779,12.64596975,0,0,0,150 +82.24,50.41836163,-3.584611156,50,-21.91388398,12.6508565,0,0,0,150 +82.25,50.41835966,-3.584609376,50,-21.91388398,12.65552114,0,0,0,150 +82.26,50.41835769,-3.584607595,50,-21.91736014,12.66040788,0,0,0,150 +82.27,50.41835572,-3.584605813,50,-21.93126488,12.66507252,0,0,0,150 +82.28,50.41835375,-3.584604031,50,-21.952122,12.66973716,0,0,0,150 +82.29,50.41835177,-3.584602248,50,-21.96602675,12.6746239,0,0,0,150 +82.3,50.4183498,-3.584600464,50,-21.96950294,12.67928855,0,0,0,150 +82.31,50.41834782,-3.58459868,50,-21.97297912,12.68417529,0,0,0,150 +82.32,50.41834585,-3.584596895,50,-21.98340766,12.68995044,0,0,0,150 +82.33,50.41834387,-3.584595109,50,-21.99036002,12.69572559,0,0,0,150 +82.34,50.41834189,-3.584593322,50,-21.98688383,12.70061233,0,0,0,150 +82.35,50.41833992,-3.584591535,50,-21.99036001,12.70549908,0,0,0,150 +82.36,50.41833794,-3.584589747,50,-22.00774096,12.71127423,0,0,0,150 +82.37,50.41833596,-3.584587958,50,-22.0216457,12.71704938,0,0,0,150 +82.38,50.41833398,-3.584586168,50,-22.02859806,12.72171403,0,0,0,150 +82.39,50.418332,-3.584584378,50,-22.04250279,12.72549027,0,0,0,150 +82.4,50.41833002,-3.584582587,50,-22.05988372,12.72926652,0,0,0,150 +82.41,50.41832803,-3.584580796,50,-22.06335991,12.73393117,0,0,0,150 +82.42,50.41832605,-3.584579004,50,-22.0633599,12.73970632,0,0,0,150 +82.43,50.41832407,-3.584577211,50,-22.08074082,12.74548148,0,0,0,150 +82.44,50.41832208,-3.584575417,50,-22.09812174,12.75036823,0,0,0,150 +82.45,50.41832009,-3.584573623,50,-22.09812173,12.75503288,0,0,0,150 +82.46,50.41831811,-3.584571828,50,-22.10159792,12.75991964,0,0,0,150 +82.47,50.41831612,-3.584570032,50,-22.11897885,12.76458429,0,0,0,150 +82.48,50.41831413,-3.584568236,50,-22.13288358,12.76947105,0,0,0,150 +82.49,50.41831214,-3.584566439,50,-22.13635975,12.77524621,0,0,0,150 +82.5,50.41831015,-3.584564641,50,-22.13635974,12.78102137,0,0,0,150 +82.51,50.41830816,-3.584562842,50,-22.13635975,12.78568602,0,0,0,150 +82.52,50.41830617,-3.584561043,50,-22.13983595,12.78968437,0,0,0,150 +82.53,50.41830418,-3.584559243,50,-22.1537407,12.79434903,0,0,0,150 +82.54,50.41830219,-3.584557443,50,-22.17112162,12.80012419,0,0,0,150 +82.55,50.41830019,-3.584555641,50,-22.17459778,12.80612146,0,0,0,150 +82.56,50.4182982,-3.584553839,50,-22.17459776,12.81167452,0,0,0,150 +82.57,50.41829621,-3.584552036,50,-22.1919787,12.81678338,0,0,0,150 +82.58,50.41829421,-3.584550232,50,-22.20935963,12.82122594,0,0,0,150 +82.59,50.41829221,-3.584548428,50,-22.20935961,12.8252243,0,0,0,150 +82.6,50.41829022,-3.584546623,50,-22.21283579,12.82988896,0,0,0,150 +82.61,50.41828822,-3.584544818,50,-22.23021673,12.83544202,0,0,0,150 +82.62,50.41828622,-3.584543011,50,-22.24412147,12.84055089,0,0,0,150 +82.63,50.41828422,-3.584541204,50,-22.24759765,12.84499345,0,0,0,150 +82.64,50.41828222,-3.584539397,50,-22.25107382,12.84988022,0,0,0,150 +82.65,50.41828022,-3.584537588,50,-22.26497857,12.85476698,0,0,0,150 +82.66,50.41827822,-3.584535779,50,-22.28583568,12.85920954,0,0,0,150 +82.67,50.41827621,-3.58453397,50,-22.29974042,12.86431841,0,0,0,150 +82.68,50.41827421,-3.584532159,50,-22.30321661,12.87009359,0,0,0,150 +82.69,50.4182722,-3.584530348,50,-22.3032166,12.87564666,0,0,0,150 +82.7,50.4182702,-3.584528536,50,-22.30321659,12.88097763,0,0,0,150 +82.71,50.41826819,-3.584526723,50,-22.30669277,12.8863086,0,0,0,150 +82.72,50.41826619,-3.58452491,50,-22.32059751,12.89119537,0,0,0,150 +82.73,50.41826418,-3.584523095,50,-22.34145462,12.89497163,0,0,0,150 +82.74,50.41826217,-3.584521281,50,-22.35535936,12.8985258,0,0,0,150 +82.75,50.41826016,-3.584519466,50,-22.35883555,12.90363467,0,0,0,150 +82.76,50.41825815,-3.58451765,50,-22.35883554,12.91007615,0,0,0,150 +82.77,50.41825614,-3.584515833,50,-22.36231172,12.91607343,0,0,0,150 +82.78,50.41825413,-3.584514015,50,-22.37621646,12.9209602,0,0,0,150 +82.79,50.41825212,-3.584512197,50,-22.39359738,12.92562488,0,0,0,150 +82.8,50.4182501,-3.584510378,50,-22.39707356,12.93051165,0,0,0,150 +82.81,50.41824809,-3.584508558,50,-22.39707355,12.93517633,0,0,0,150 +82.82,50.41824608,-3.584506738,50,-22.41445448,12.9400631,0,0,0,150 +82.83,50.41824406,-3.584504917,50,-22.43183541,12.94583828,0,0,0,150 +82.84,50.41824204,-3.584503095,50,-22.43183541,12.95161347,0,0,0,150 +82.85,50.41824003,-3.584501272,50,-22.43531159,12.95650024,0,0,0,150 +82.86,50.41823801,-3.584499449,50,-22.45269252,12.96116492,0,0,0,150 +82.87,50.41823599,-3.584497625,50,-22.46659726,12.9660517,0,0,0,150 +82.88,50.41823397,-3.5844958,50,-22.47007344,12.97071638,0,0,0,150 +82.89,50.41823195,-3.584493975,50,-22.47007343,12.97538106,0,0,0,150 +82.9,50.41822993,-3.584492149,50,-22.47354961,12.98026784,0,0,0,150 +82.91,50.41822791,-3.584490322,50,-22.48745435,12.98493252,0,0,0,150 +82.92,50.41822589,-3.584488495,50,-22.50483528,12.9898193,0,0,0,150 +82.93,50.41822386,-3.584486667,50,-22.50831146,12.99559449,0,0,0,150 +82.94,50.41822184,-3.584484838,50,-22.50831145,13.00136968,0,0,0,150 +82.95,50.41821982,-3.584483008,50,-22.52569236,13.00603436,0,0,0,150 +82.96,50.41821779,-3.584481178,50,-22.54307328,13.01003274,0,0,0,150 +82.97,50.41821576,-3.584479347,50,-22.54307327,13.01469743,0,0,0,150 +82.98,50.41821374,-3.584477516,50,-22.54654947,13.02047262,0,0,0,150 +82.99,50.41821171,-3.584475683,50,-22.56393041,13.02624781,0,0,0,150 +83,50.41820968,-3.58447385,50,-22.57783514,13.0309125,0,0,0,150 +83.01,50.41820765,-3.584472016,50,-22.58131132,13.03491088,0,0,0,150 +83.02,50.41820562,-3.584470182,50,-22.58131131,13.03957557,0,0,0,150 +83.03,50.41820359,-3.584468347,50,-22.58478749,13.04535076,0,0,0,150 +83.04,50.41820156,-3.584466511,50,-22.59869223,13.05112596,0,0,0,150 +83.05,50.41819953,-3.584464674,50,-22.61607315,13.05601275,0,0,0,150 +83.06,50.41819749,-3.584462837,50,-22.61954932,13.06067744,0,0,0,150 +83.07,50.41819546,-3.584460999,50,-22.61954931,13.06556423,0,0,0,150 +83.08,50.41819343,-3.58445916,50,-22.63693025,13.07022892,0,0,0,150 +83.09,50.41819139,-3.584457321,50,-22.65431119,13.07511572,0,0,0,150 +83.1,50.41818935,-3.584455481,50,-22.65431118,13.08089092,0,0,0,150 +83.11,50.41818732,-3.58445364,50,-22.65778735,13.08644401,0,0,0,150 +83.12,50.41818528,-3.584451798,50,-22.67516828,13.0904424,0,0,0,150 +83.13,50.41818324,-3.584449956,50,-22.68907301,13.09399659,0,0,0,150 +83.14,50.4181812,-3.584448114,50,-22.69254918,13.09888339,0,0,0,150 +83.15,50.41817916,-3.58444627,50,-22.69602537,13.10465859,0,0,0,150 +83.16,50.41817712,-3.584444426,50,-22.70993013,13.1104338,0,0,0,150 +83.17,50.41817508,-3.584442581,50,-22.72731106,13.1164311,0,0,0,150 +83.18,50.41817303,-3.584440735,50,-22.73078722,13.12220631,0,0,0,150 +83.19,50.41817099,-3.584438888,50,-22.72731101,13.126871,0,0,0,150 +83.2,50.41816895,-3.584437041,50,-22.73426338,13.1306473,0,0,0,150 +83.21,50.4181669,-3.584435193,50,-22.74816815,13.13464569,0,0,0,150 +83.22,50.41816486,-3.584433345,50,-22.76554908,13.1399767,0,0,0,150 +83.23,50.41816281,-3.584431496,50,-22.78293,13.14597401,0,0,0,150 +83.24,50.41816076,-3.584429645,50,-22.78292998,13.15086081,0,0,0,150 +83.25,50.41815871,-3.584427795,50,-22.76902521,13.15552551,0,0,0,150 +83.26,50.41815667,-3.584425944,50,-22.7725014,13.16152282,0,0,0,150 +83.27,50.41815462,-3.584424091,50,-22.8037871,13.16707593,0,0,0,150 +83.28,50.41815257,-3.584422238,50,-22.83507278,13.17085223,0,0,0,150 +83.29,50.41815051,-3.584420385,50,-22.83854894,13.17485063,0,0,0,150 +83.3,50.41814846,-3.584418531,50,-22.82464417,13.18040374,0,0,0,150 +83.31,50.41814641,-3.584416676,50,-22.82464416,13.18617896,0,0,0,150 +83.32,50.41814436,-3.58441482,50,-22.84202509,13.19106576,0,0,0,150 +83.33,50.4181423,-3.584412964,50,-22.85940602,13.19573047,0,0,0,150 +83.34,50.41814025,-3.584411107,50,-22.87331076,13.20061728,0,0,0,150 +83.35,50.41813819,-3.584409249,50,-22.88026312,13.20528199,0,0,0,150 +83.36,50.41813613,-3.584407391,50,-22.87678694,13.2099467,0,0,0,150 +83.37,50.41813408,-3.584405532,50,-22.88026311,13.21505561,0,0,0,150 +83.38,50.41813202,-3.584403672,50,-22.89764403,13.22060873,0,0,0,150 +83.39,50.41812996,-3.584401812,50,-22.91154878,13.22638395,0,0,0,150 +83.4,50.4181279,-3.58439995,50,-22.91502496,13.23149286,0,0,0,150 +83.41,50.41812584,-3.584398088,50,-22.91850114,13.23593547,0,0,0,150 +83.42,50.41812378,-3.584396226,50,-22.93240588,13.24104439,0,0,0,150 +83.43,50.41812172,-3.584394362,50,-22.94978681,13.24659751,0,0,0,150 +83.44,50.41811965,-3.584392498,50,-22.95326299,13.25126222,0,0,0,150 +83.45,50.41811759,-3.584390633,50,-22.95326299,13.25526063,0,0,0,150 +83.46,50.41811553,-3.584388768,50,-22.9706439,13.25970325,0,0,0,150 +83.47,50.41811346,-3.584386902,50,-22.98802483,13.26481217,0,0,0,150 +83.48,50.41811139,-3.584385035,50,-22.98802483,13.27036529,0,0,0,150 +83.49,50.41810933,-3.584383168,50,-22.99150101,13.27614052,0,0,0,150 +83.5,50.41810726,-3.584381299,50,-23.00888193,13.28124944,0,0,0,150 +83.51,50.41810519,-3.58437943,50,-23.02278667,13.28569206,0,0,0,150 +83.52,50.41810312,-3.584377561,50,-23.02626284,13.29057888,0,0,0,150 +83.53,50.41810105,-3.58437569,50,-23.02626282,13.2954657,0,0,0,150 +83.54,50.41809898,-3.584373819,50,-23.02626281,13.29990832,0,0,0,150 +83.55,50.41809691,-3.584371948,50,-23.02973901,13.30501724,0,0,0,150 +83.56,50.41809484,-3.584370075,50,-23.04364375,13.31079247,0,0,0,150 +83.57,50.41809277,-3.584368202,50,-23.06450087,13.3163456,0,0,0,150 +83.58,50.41809069,-3.584366328,50,-23.07840562,13.32145453,0,0,0,150 +83.59,50.41808862,-3.584364453,50,-23.08188179,13.32611925,0,0,0,150 +83.6,50.41808654,-3.584362578,50,-23.08535796,13.33100608,0,0,0,150 +83.61,50.41808447,-3.584360702,50,-23.09926269,13.33678131,0,0,0,150 +83.62,50.41808239,-3.584358825,50,-23.12011981,13.34233445,0,0,0,150 +83.63,50.41808031,-3.584356947,50,-23.13402456,13.34633287,0,0,0,150 +83.64,50.41807823,-3.584355069,50,-23.13750074,13.34988709,0,0,0,150 +83.65,50.41807615,-3.584353191,50,-23.13750072,13.35477391,0,0,0,150 +83.66,50.41807407,-3.584351311,50,-23.13750071,13.36054915,0,0,0,150 +83.67,50.41807199,-3.584349431,50,-23.13750072,13.36610229,0,0,0,150 +83.68,50.41806991,-3.58434755,50,-23.1409769,13.37121122,0,0,0,150 +83.69,50.41806783,-3.584345668,50,-23.15488163,13.37587595,0,0,0,150 +83.7,50.41806575,-3.584343786,50,-23.17573874,13.38054068,0,0,0,150 +83.71,50.41806366,-3.584341903,50,-23.18964347,13.38564962,0,0,0,150 +83.72,50.41806158,-3.584340019,50,-23.19311965,13.39098066,0,0,0,150 +83.73,50.41805949,-3.584338135,50,-23.19659583,13.39608959,0,0,0,150 +83.74,50.41805741,-3.584336249,50,-23.21050057,13.40075433,0,0,0,150 +83.75,50.41805532,-3.584334364,50,-23.2313577,13.40541906,0,0,0,150 +83.76,50.41805323,-3.584332477,50,-23.24526243,13.410528,0,0,0,150 +83.77,50.41805114,-3.58433059,50,-23.2487386,13.41585904,0,0,0,150 +83.78,50.41804905,-3.584328702,50,-23.2487386,13.42096798,0,0,0,150 +83.79,50.41804696,-3.584326813,50,-23.24873859,13.42563272,0,0,0,150 +83.8,50.41804487,-3.584324924,50,-23.25221478,13.43051956,0,0,0,150 +83.81,50.41804278,-3.584323034,50,-23.26611951,13.43629481,0,0,0,150 +83.82,50.41804069,-3.584321143,50,-23.28350043,13.44207006,0,0,0,150 +83.83,50.41803859,-3.584319251,50,-23.28697661,13.44673479,0,0,0,150 +83.84,50.4180365,-3.584317359,50,-23.28697661,13.45073323,0,0,0,150 +83.85,50.41803441,-3.584315466,50,-23.30435754,13.45539797,0,0,0,150 +83.86,50.41803231,-3.584313573,50,-23.32173846,13.46117322,0,0,0,150 +83.87,50.41803021,-3.584311678,50,-23.32173844,13.46694847,0,0,0,150 +83.88,50.41802812,-3.584309783,50,-23.32521462,13.47161321,0,0,0,150 +83.89,50.41802602,-3.584307887,50,-23.34259555,13.47561165,0,0,0,150 +83.9,50.41802392,-3.584305991,50,-23.3565003,13.48027639,0,0,0,150 +83.91,50.41802182,-3.584304094,50,-23.35997648,13.48582955,0,0,0,150 +83.92,50.41801972,-3.584302196,50,-23.35997647,13.4909385,0,0,0,150 +83.93,50.41801762,-3.584300297,50,-23.36345265,13.49538114,0,0,0,150 +83.94,50.41801552,-3.584298399,50,-23.37735739,13.50026799,0,0,0,150 +83.95,50.41801342,-3.584296498,50,-23.3982145,13.50537694,0,0,0,150 +83.96,50.41801131,-3.584294598,50,-23.41211924,13.51048589,0,0,0,150 +83.97,50.41800921,-3.584292697,50,-23.41559541,13.51603905,0,0,0,150 +83.98,50.4180071,-3.584290794,50,-23.41907159,13.52137011,0,0,0,150 +83.99,50.418005,-3.584288892,50,-23.42950015,13.52625696,0,0,0,150 +84,50.41800289,-3.584286988,50,-23.43645251,13.53136591,0,0,0,150 +84.01,50.41800078,-3.584285084,50,-23.43297631,13.53669697,0,0,0,150 +84.02,50.41799868,-3.584283179,50,-23.43645249,13.54180593,0,0,0,150 +84.03,50.41799657,-3.584281273,50,-23.45383341,13.54624857,0,0,0,150 +84.04,50.41799446,-3.584279367,50,-23.47121434,13.55024702,0,0,0,150 +84.05,50.41799235,-3.58427746,50,-23.48859528,13.55491177,0,0,0,150 +84.06,50.41799024,-3.584275553,50,-23.5059762,13.56068704,0,0,0,150 +84.07,50.41798812,-3.584273644,50,-23.50945238,13.56668441,0,0,0,150 +84.08,50.41798601,-3.584271735,50,-23.50597618,13.57201547,0,0,0,150 +84.09,50.4179839,-3.584269825,50,-23.51292854,13.57623602,0,0,0,150 +84.1,50.41798178,-3.584267914,50,-23.5233571,13.57979027,0,0,0,150 +84.11,50.41797967,-3.584266004,50,-23.52683327,13.58467713,0,0,0,150 +84.12,50.41797755,-3.584264092,50,-23.53030946,13.59156291,0,0,0,150 +84.13,50.41797544,-3.584262179,50,-23.5442142,13.59800449,0,0,0,150 +84.14,50.41797332,-3.584260265,50,-23.56507131,13.60200294,0,0,0,150 +84.15,50.4179712,-3.584258351,50,-23.57897604,13.60489088,0,0,0,150 +84.16,50.41796908,-3.584256437,50,-23.58245222,13.60955564,0,0,0,150 +84.17,50.41796696,-3.584254522,50,-23.58245221,13.61621932,0,0,0,150 +84.18,50.41796484,-3.584252605,50,-23.5859284,13.6222167,0,0,0,150 +84.19,50.41796272,-3.584250688,50,-23.59983314,13.62665936,0,0,0,150 +84.2,50.4179606,-3.584248771,50,-23.61721407,13.63087992,0,0,0,150 +84.21,50.41795847,-3.584246852,50,-23.62069025,13.63532258,0,0,0,150 +84.22,50.41795635,-3.584244934,50,-23.61721404,13.63998734,0,0,0,150 +84.23,50.41795423,-3.584243014,50,-23.62416639,13.64531842,0,0,0,150 +84.24,50.4179521,-3.584241094,50,-23.63807114,13.6515379,0,0,0,150 +84.25,50.41794998,-3.584239173,50,-23.65545208,13.65775739,0,0,0,150 +84.26,50.41794785,-3.58423725,50,-23.6763092,13.66242215,0,0,0,150 +84.27,50.41794572,-3.584235328,50,-23.69021392,13.66597641,0,0,0,150 +84.28,50.41794359,-3.584233405,50,-23.69369009,13.67019697,0,0,0,150 +84.29,50.41794146,-3.584231481,50,-23.69369009,13.67552805,0,0,0,150 +84.3,50.41793933,-3.584229557,50,-23.6936901,13.68152543,0,0,0,150 +84.31,50.4179372,-3.584227631,50,-23.69369009,13.68730072,0,0,0,150 +84.32,50.41793507,-3.584225705,50,-23.69716625,13.69196549,0,0,0,150 +84.33,50.41793294,-3.584223778,50,-23.71107098,13.69596395,0,0,0,150 +84.34,50.41793081,-3.584221851,50,-23.7319281,13.70040662,0,0,0,150 +84.35,50.41792867,-3.584219923,50,-23.74583285,13.7055156,0,0,0,150 +84.36,50.41792654,-3.584217994,50,-23.74930904,13.71106878,0,0,0,150 +84.37,50.4179244,-3.584216065,50,-23.75278521,13.71706618,0,0,0,150 +84.38,50.41792227,-3.584214134,50,-23.76668994,13.72284147,0,0,0,150 +84.39,50.41792013,-3.584212203,50,-23.78754705,13.72750624,0,0,0,150 +84.4,50.41791799,-3.584210271,50,-23.80145179,13.73128261,0,0,0,150 +84.41,50.41791585,-3.584208339,50,-23.80492796,13.73505897,0,0,0,150 +84.42,50.41791371,-3.584206406,50,-23.80492796,13.73972375,0,0,0,150 +84.43,50.41791157,-3.584204473,50,-23.80492795,13.74549904,0,0,0,150 +84.44,50.41790943,-3.584202538,50,-23.80492794,13.75127433,0,0,0,150 +84.45,50.41790729,-3.584200603,50,-23.80840412,13.75616122,0,0,0,150 +84.46,50.41790515,-3.584198667,50,-23.82230886,13.7610481,0,0,0,150 +84.47,50.41790301,-3.584196731,50,-23.84316598,13.76682339,0,0,0,150 +84.48,50.41790086,-3.584194793,50,-23.85707073,13.77259869,0,0,0,150 +84.49,50.41789872,-3.584192855,50,-23.8605469,13.77726347,0,0,0,150 +84.5,50.41789657,-3.584190916,50,-23.86402308,13.78126195,0,0,0,150 +84.51,50.41789443,-3.584188977,50,-23.87792781,13.78592673,0,0,0,150 +84.52,50.41789228,-3.584187037,50,-23.89878491,13.79147992,0,0,0,150 +84.53,50.41789013,-3.584185096,50,-23.91268964,13.79636681,0,0,0,150 +84.54,50.41788798,-3.584183154,50,-23.91616583,13.80014319,0,0,0,150 +84.55,50.41788583,-3.584181213,50,-23.91616583,13.80480797,0,0,0,150 +84.56,50.41788368,-3.58417927,50,-23.91616581,13.81080538,0,0,0,150 +84.57,50.41788153,-3.584177326,50,-23.9161658,13.81635858,0,0,0,150 +84.58,50.41787938,-3.584175382,50,-23.91964199,13.82146757,0,0,0,150 +84.59,50.41787723,-3.584173437,50,-23.93354673,13.82702077,0,0,0,150 +84.6,50.41787508,-3.584171491,50,-23.95440385,13.83212977,0,0,0,150 +84.61,50.41787292,-3.584169544,50,-23.97178478,13.83657245,0,0,0,150 +84.62,50.41787077,-3.584167598,50,-23.98568951,13.84145935,0,0,0,150 +84.63,50.41786861,-3.584165649,50,-23.99264187,13.84634624,0,0,0,150 +84.64,50.41786645,-3.584163701,50,-23.98916567,13.85078893,0,0,0,150 +84.65,50.4178643,-3.584161752,50,-23.99264185,13.85589793,0,0,0,150 +84.66,50.41786214,-3.584159802,50,-24.01002277,13.86145114,0,0,0,150 +84.67,50.41785998,-3.584157851,50,-24.0239275,13.86633803,0,0,0,150 +84.68,50.41785782,-3.5841559,50,-24.02740369,13.87100283,0,0,0,150 +84.69,50.41785566,-3.584153948,50,-24.0274037,13.87611183,0,0,0,150 +84.7,50.4178535,-3.584151995,50,-24.03087987,13.88166504,0,0,0,150 +84.71,50.41785134,-3.584150042,50,-24.0447846,13.88744035,0,0,0,150 +84.72,50.41784918,-3.584148087,50,-24.0656417,13.89232725,0,0,0,150 +84.73,50.41784701,-3.584146132,50,-24.07954645,13.89610364,0,0,0,150 +84.74,50.41784485,-3.584144177,50,-24.08302264,13.90076844,0,0,0,150 +84.75,50.41784268,-3.584142221,50,-24.08649881,13.90654375,0,0,0,150 +84.76,50.41784052,-3.584140263,50,-24.09692735,13.91143066,0,0,0,150 +84.77,50.41783835,-3.584138306,50,-24.10387971,13.91587335,0,0,0,150 +84.78,50.41783618,-3.584136348,50,-24.10040353,13.92120446,0,0,0,150 +84.79,50.41783402,-3.584134388,50,-24.10387971,13.92653557,0,0,0,150 +84.8,50.41783185,-3.584132429,50,-24.12126063,13.93142248,0,0,0,150 +84.81,50.41782968,-3.584130468,50,-24.13864155,13.93653149,0,0,0,150 +84.82,50.41782751,-3.584128507,50,-24.15602248,13.9418626,0,0,0,150 +84.83,50.41782534,-3.584126545,50,-24.17340341,13.94697162,0,0,0,150 +84.84,50.41782316,-3.584124582,50,-24.17687958,13.95163642,0,0,0,150 +84.85,50.41782099,-3.584122619,50,-24.17340337,13.95630123,0,0,0,150 +84.86,50.41781882,-3.584120655,50,-24.18035574,13.96118814,0,0,0,150 +84.87,50.41781664,-3.58411869,50,-24.1907843,13.96585295,0,0,0,150 +84.88,50.41781447,-3.584116725,50,-24.19426049,13.97073986,0,0,0,150 +84.89,50.41781229,-3.584114759,50,-24.19773667,13.97651518,0,0,0,150 +84.9,50.41781012,-3.584112792,50,-24.2116414,13.98229051,0,0,0,150 +84.91,50.41780794,-3.584110824,50,-24.2324985,13.98695532,0,0,0,150 +84.92,50.41780576,-3.584108856,50,-24.24640324,13.99095382,0,0,0,150 +84.93,50.41780358,-3.584106887,50,-24.24987943,13.99561863,0,0,0,150 +84.94,50.4178014,-3.584104918,50,-24.24987942,14.00139396,0,0,0,150 +84.95,50.41779922,-3.584102947,50,-24.24987941,14.00739139,0,0,0,150 +84.96,50.41779704,-3.584100976,50,-24.25335559,14.01272252,0,0,0,150 +84.97,50.41779486,-3.584099004,50,-24.26726032,14.01694312,0,0,0,150 +84.98,50.41779268,-3.584097031,50,-24.28811743,14.02049742,0,0,0,150 +84.99,50.41779049,-3.584095059,50,-24.30202216,14.02516224,0,0,0,150 +85,50.41778831,-3.584093085,50,-24.30549835,14.03115967,0,0,0,150 +85.01,50.41778612,-3.58409111,50,-24.30897454,14.0367129,0,0,0,150 +85.02,50.41778394,-3.584089135,50,-24.32287928,14.04159982,0,0,0,150 +85.03,50.41778175,-3.584087159,50,-24.34373638,14.04670885,0,0,0,150 +85.04,50.41777956,-3.584085182,50,-24.35764111,14.05203998,0,0,0,150 +85.05,50.41777737,-3.584083205,50,-24.36111729,14.05714901,0,0,0,150 +85.06,50.41777518,-3.584081226,50,-24.36111728,14.06181383,0,0,0,150 +85.07,50.41777299,-3.584079248,50,-24.36111727,14.06647865,0,0,0,150 +85.08,50.4177708,-3.584077268,50,-24.36111726,14.07136557,0,0,0,150 +85.09,50.41776861,-3.584075288,50,-24.36459344,14.0760304,0,0,0,150 +85.1,50.41776642,-3.584073307,50,-24.37849819,14.08091732,0,0,0,150 +85.11,50.41776423,-3.584071326,50,-24.39935531,14.08669266,0,0,0,150 +85.12,50.41776203,-3.584069343,50,-24.41326005,14.09246801,0,0,0,150 +85.13,50.41775984,-3.58406736,50,-24.41673622,14.09713283,0,0,0,150 +85.14,50.41775764,-3.584065376,50,-24.42021239,14.10113135,0,0,0,150 +85.15,50.41775545,-3.584063392,50,-24.43411712,14.10579617,0,0,0,150 +85.16,50.41775325,-3.584061407,50,-24.45149804,14.11157152,0,0,0,150 +85.17,50.41775105,-3.584059421,50,-24.45149803,14.11734686,0,0,0,150 +85.18,50.41774885,-3.584057434,50,-24.44106946,14.1222338,0,0,0,150 +85.19,50.41774666,-3.584055447,50,-24.4549742,14.12689862,0,0,0,150 +85.2,50.41774446,-3.584053459,50,-24.48973606,14.13178556,0,0,0,150 +85.21,50.41774225,-3.58405147,50,-24.5036408,14.13645039,0,0,0,150 +85.22,50.41774005,-3.584049481,50,-24.49321224,14.14111522,0,0,0,150 +85.23,50.41773785,-3.584047491,50,-24.49321223,14.14622426,0,0,0,150 +85.24,50.41773565,-3.5840455,50,-24.51059315,14.1515554,0,0,0,150 +85.25,50.41773344,-3.584043509,50,-24.52449789,14.15666444,0,0,0,150 +85.26,50.41773124,-3.584041516,50,-24.52797407,14.16132928,0,0,0,150 +85.27,50.41772903,-3.584039524,50,-24.53145024,14.16599411,0,0,0,150 +85.28,50.41772683,-3.58403753,50,-24.54535497,14.17110315,0,0,0,150 +85.29,50.41772462,-3.584035536,50,-24.56621209,14.1766564,0,0,0,150 +85.3,50.41772241,-3.584033541,50,-24.58011683,14.18265386,0,0,0,150 +85.31,50.4177202,-3.584031545,50,-24.58359301,14.18842922,0,0,0,150 +85.32,50.41771799,-3.584029548,50,-24.583593,14.19309406,0,0,0,150 +85.33,50.41771578,-3.584027551,50,-24.58359299,14.19687048,0,0,0,150 +85.34,50.41771357,-3.584025553,50,-24.58359298,14.20064691,0,0,0,150 +85.35,50.41771136,-3.584023555,50,-24.58706915,14.20531175,0,0,0,150 +85.36,50.41770915,-3.584021556,50,-24.60097388,14.2110871,0,0,0,150 +85.37,50.41770694,-3.584019556,50,-24.621831,14.21686246,0,0,0,150 +85.38,50.41770472,-3.584017555,50,-24.63921194,14.22174941,0,0,0,150 +85.39,50.41770251,-3.584015554,50,-24.65311668,14.22663636,0,0,0,150 +85.4,50.41770029,-3.584013552,50,-24.66006903,14.23241172,0,0,0,150 +85.41,50.41769807,-3.584011549,50,-24.65659283,14.23818708,0,0,0,150 +85.42,50.41769586,-3.584009545,50,-24.66006901,14.24285193,0,0,0,150 +85.43,50.41769364,-3.584007541,50,-24.67744995,14.24662836,0,0,0,150 +85.44,50.41769142,-3.584005536,50,-24.69135469,14.25062689,0,0,0,150 +85.45,50.4176892,-3.584003531,50,-24.69483086,14.25595805,0,0,0,150 +85.46,50.41768698,-3.584001525,50,-24.69483084,14.26195552,0,0,0,150 +85.47,50.41768476,-3.583999517,50,-24.69830701,14.26684247,0,0,0,150 +85.48,50.41768254,-3.58399751,50,-24.71221176,14.27128522,0,0,0,150 +85.49,50.41768032,-3.583995502,50,-24.73306888,14.27661638,0,0,0,150 +85.5,50.41767809,-3.583993492,50,-24.74697363,14.28194754,0,0,0,150 +85.51,50.41767587,-3.583991483,50,-24.75044981,14.2868345,0,0,0,150 +85.52,50.41767364,-3.583989472,50,-24.75392597,14.29194356,0,0,0,150 +85.53,50.41767142,-3.583987461,50,-24.7643545,14.29727472,0,0,0,150 +85.54,50.41766919,-3.583985449,50,-24.77130686,14.30238378,0,0,0,150 +85.55,50.41766696,-3.583983436,50,-24.76783066,14.30704864,0,0,0,150 +85.56,50.41766474,-3.583981423,50,-24.77130685,14.31171349,0,0,0,150 +85.57,50.41766251,-3.583979409,50,-24.78868778,14.31660045,0,0,0,150 +85.58,50.41766028,-3.583977394,50,-24.80606871,14.3212653,0,0,0,150 +85.59,50.41765805,-3.583975379,50,-24.82344964,14.32615226,0,0,0,150 +85.6,50.41765582,-3.583973363,50,-24.84083056,14.33192764,0,0,0,150 +85.61,50.41765358,-3.583971346,50,-24.84430674,14.33770302,0,0,0,150 +85.62,50.41765135,-3.583969328,50,-24.84083053,14.34236788,0,0,0,150 +85.63,50.41764912,-3.58396731,50,-24.84778289,14.34636643,0,0,0,150 +85.64,50.41764688,-3.583965291,50,-24.85821144,14.35103129,0,0,0,150 +85.65,50.41764465,-3.583963272,50,-24.86168763,14.35658456,0,0,0,150 +85.66,50.41764241,-3.583961251,50,-24.86516381,14.36169363,0,0,0,150 +85.67,50.41764018,-3.58395923,50,-24.87906855,14.36613639,0,0,0,150 +85.68,50.41763794,-3.583957209,50,-24.89992567,14.37124546,0,0,0,150 +85.69,50.4176357,-3.583955186,50,-24.9138304,14.37702085,0,0,0,150 +85.7,50.41763346,-3.583953163,50,-24.91730656,14.38257413,0,0,0,150 +85.71,50.41763122,-3.583951139,50,-24.91730653,14.3876832,0,0,0,150 +85.72,50.41762898,-3.583949114,50,-24.92078271,14.39234807,0,0,0,150 +85.73,50.41762674,-3.583947089,50,-24.93468747,14.39701293,0,0,0,150 +85.74,50.4176245,-3.583945063,50,-24.95206841,14.4018999,0,0,0,150 +85.75,50.41762225,-3.583943036,50,-24.95554459,14.40656477,0,0,0,150 +85.76,50.41762001,-3.583941009,50,-24.95206838,14.41122964,0,0,0,150 +85.77,50.41761777,-3.583938981,50,-24.95902074,14.41633871,0,0,0,150 +85.78,50.41761552,-3.583936952,50,-24.97292547,14.4216699,0,0,0,150 +85.79,50.41761328,-3.583934923,50,-24.99030639,14.42677898,0,0,0,150 +85.8,50.41761103,-3.583932892,50,-25.01116351,14.43144385,0,0,0,150 +85.81,50.41760878,-3.583930862,50,-25.02506826,14.43633082,0,0,0,150 +85.82,50.41760653,-3.58392883,50,-25.02854444,14.44210622,0,0,0,150 +85.83,50.41760428,-3.583926798,50,-25.02854441,14.44788161,0,0,0,150 +85.84,50.41760203,-3.583924764,50,-25.02854439,14.45276859,0,0,0,150 +85.85,50.41759978,-3.583922731,50,-25.02854439,14.45743346,0,0,0,150 +85.86,50.41759753,-3.583920696,50,-25.03202059,14.46232044,0,0,0,150 +85.87,50.41759528,-3.583918661,50,-25.04592533,14.46676322,0,0,0,150 +85.88,50.41759303,-3.583916625,50,-25.06678242,14.47076178,0,0,0,150 +85.89,50.41759077,-3.583914589,50,-25.08068715,14.47542666,0,0,0,150 +85.9,50.41758852,-3.583912552,50,-25.08416333,14.48142416,0,0,0,150 +85.91,50.41758626,-3.583910514,50,-25.08763952,14.48786587,0,0,0,150 +85.92,50.41758401,-3.583908475,50,-25.10154425,14.49297496,0,0,0,150 +85.93,50.41758175,-3.583906435,50,-25.12240135,14.49675142,0,0,0,150 +85.94,50.41757949,-3.583904396,50,-25.1363061,14.50141631,0,0,0,150 +85.95,50.41757723,-3.583902355,50,-25.13978228,14.50741381,0,0,0,150 +85.96,50.41757497,-3.583900313,50,-25.13978226,14.51296711,0,0,0,150 +85.97,50.41757271,-3.583898271,50,-25.13978225,14.5178541,0,0,0,150 +85.98,50.41757045,-3.583896228,50,-25.13978225,14.52274109,0,0,0,150 +85.99,50.41756819,-3.583894184,50,-25.14325842,14.52718387,0,0,0,150 +86,50.41756593,-3.58389214,50,-25.15716315,14.53118244,0,0,0,150 +86.01,50.41756367,-3.583890095,50,-25.17802027,14.53584733,0,0,0,150 +86.02,50.4175614,-3.58388805,50,-25.19192501,14.54162273,0,0,0,150 +86.03,50.41755914,-3.583886003,50,-25.19540118,14.54739814,0,0,0,150 +86.04,50.41755687,-3.583883956,50,-25.19887735,14.55228514,0,0,0,150 +86.05,50.41755461,-3.583881908,50,-25.21278209,14.55717213,0,0,0,150 +86.06,50.41755234,-3.58387986,50,-25.23363921,14.56272544,0,0,0,150 +86.07,50.41755007,-3.58387781,50,-25.24754394,14.56761243,0,0,0,150 +86.08,50.4175478,-3.58387576,50,-25.25102012,14.5713889,0,0,0,150 +86.09,50.41754553,-3.58387371,50,-25.25102011,14.57605379,0,0,0,150 +86.1,50.41754326,-3.583871659,50,-25.2510201,14.58205131,0,0,0,150 +86.11,50.41754099,-3.583869606,50,-25.25449627,14.58760463,0,0,0,150 +86.12,50.41753872,-3.583867554,50,-25.26840101,14.59249162,0,0,0,150 +86.13,50.41753645,-3.5838655,50,-25.28578194,14.59760072,0,0,0,150 +86.14,50.41753417,-3.583863446,50,-25.28925812,14.60270983,0,0,0,150 +86.15,50.4175319,-3.583861391,50,-25.28925811,14.60715262,0,0,0,150 +86.16,50.41752963,-3.583859335,50,-25.30663903,14.61137331,0,0,0,150 +86.17,50.41752735,-3.58385728,50,-25.32401994,14.61626031,0,0,0,150 +86.18,50.41752507,-3.583855222,50,-25.32401994,14.62136942,0,0,0,150 +86.19,50.4175228,-3.583853165,50,-25.32749613,14.62647852,0,0,0,150 +86.2,50.41752052,-3.583851107,50,-25.34487704,14.63203184,0,0,0,150 +86.21,50.41751824,-3.583849047,50,-25.35878177,14.63736305,0,0,0,150 +86.22,50.41751596,-3.583846988,50,-25.36225795,14.64225006,0,0,0,150 +86.23,50.41751368,-3.583844927,50,-25.36225795,14.64735917,0,0,0,150 +86.24,50.4175114,-3.583842866,50,-25.36573413,14.65269039,0,0,0,150 +86.25,50.41750912,-3.583840804,50,-25.37963887,14.6577995,0,0,0,150 +86.26,50.41750684,-3.583838741,50,-25.40049597,14.6624644,0,0,0,150 +86.27,50.41750455,-3.583836678,50,-25.4144007,14.66735141,0,0,0,150 +86.28,50.41750227,-3.583834614,50,-25.41787687,14.67312684,0,0,0,150 +86.29,50.41749998,-3.583832549,50,-25.42135305,14.67868016,0,0,0,150 +86.3,50.4174977,-3.583830483,50,-25.43178161,14.68267875,0,0,0,150 +86.31,50.41749541,-3.583828417,50,-25.43873397,14.68623314,0,0,0,150 +86.32,50.41749312,-3.583826351,50,-25.43525778,14.69112015,0,0,0,150 +86.33,50.41749084,-3.583824283,50,-25.43873396,14.69667348,0,0,0,150 +86.34,50.41748855,-3.583822215,50,-25.45611488,14.70156049,0,0,0,150 +86.35,50.41748626,-3.583820146,50,-25.47349579,14.7064475,0,0,0,150 +86.36,50.41748397,-3.583818077,50,-25.49087671,14.71222294,0,0,0,150 +86.37,50.41748168,-3.583816006,50,-25.50825764,14.71799837,0,0,0,150 +86.38,50.41747938,-3.583813935,50,-25.51173383,14.72266329,0,0,0,150 +86.39,50.41747709,-3.583811863,50,-25.50825763,14.72666188,0,0,0,150 +86.4,50.4174748,-3.583809791,50,-25.51520998,14.7313268,0,0,0,150 +86.41,50.4174725,-3.583807718,50,-25.52563854,14.73710224,0,0,0,150 +86.42,50.41747021,-3.583805644,50,-25.52911471,14.74287767,0,0,0,150 +86.43,50.41746791,-3.583803569,50,-25.53259088,14.74776469,0,0,0,150 +86.44,50.41746562,-3.583801494,50,-25.54649562,14.75242961,0,0,0,150 +86.45,50.41746332,-3.583799418,50,-25.56735275,14.75731663,0,0,0,150 +86.46,50.41746102,-3.583797341,50,-25.58125748,14.76198155,0,0,0,150 +86.47,50.41745872,-3.583795264,50,-25.58473364,14.76664647,0,0,0,150 +86.48,50.41745642,-3.583793186,50,-25.58473363,14.77175559,0,0,0,150 +86.49,50.41745412,-3.583791107,50,-25.58820982,14.77730893,0,0,0,150 +86.5,50.41745182,-3.583789028,50,-25.60211456,14.78308438,0,0,0,150 +86.51,50.41744952,-3.583786947,50,-25.61949547,14.78797141,0,0,0,150 +86.52,50.41744721,-3.583784866,50,-25.62297164,14.79174791,0,0,0,150 +86.53,50.41744491,-3.583782785,50,-25.62297163,14.79663493,0,0,0,150 +86.54,50.41744261,-3.583780703,50,-25.64035255,14.8032988,0,0,0,150 +86.55,50.4174403,-3.583778619,50,-25.65773349,14.80907425,0,0,0,150 +86.56,50.41743799,-3.583776535,50,-25.6577335,14.81262865,0,0,0,150 +86.57,50.41743569,-3.583774451,50,-25.66120967,14.81573884,0,0,0,150 +86.58,50.41743338,-3.583772366,50,-25.67859058,14.82018166,0,0,0,150 +86.59,50.41743107,-3.583770281,50,-25.69249531,14.82595711,0,0,0,150 +86.6,50.41742876,-3.583768194,50,-25.69597148,14.83195467,0,0,0,150 +86.61,50.41742645,-3.583766107,50,-25.69597147,14.83750802,0,0,0,150 +86.62,50.41742414,-3.583764019,50,-25.69597146,14.84283927,0,0,0,150 +86.63,50.41742183,-3.58376193,50,-25.69944764,14.84817051,0,0,0,150 +86.64,50.41741952,-3.583759841,50,-25.71335238,14.85327965,0,0,0,150 +86.65,50.41741721,-3.58375775,50,-25.7342095,14.85794458,0,0,0,150 +86.66,50.41741489,-3.58375566,50,-25.74811425,14.86260951,0,0,0,150 +86.67,50.41741258,-3.583753568,50,-25.75159042,14.86771865,0,0,0,150 +86.68,50.41741026,-3.583751476,50,-25.75506659,14.8730499,0,0,0,150 +86.69,50.41740795,-3.583749383,50,-25.76897131,14.87815905,0,0,0,150 +86.7,50.41740563,-3.583747289,50,-25.78982841,14.88260188,0,0,0,150 +86.71,50.41740331,-3.583745195,50,-25.80373315,14.8866005,0,0,0,150 +86.72,50.41740099,-3.5837431,50,-25.80720934,14.89126543,0,0,0,150 +86.73,50.41739867,-3.583741005,50,-25.80720933,14.8970409,0,0,0,150 +86.74,50.41739635,-3.583738908,50,-25.80720932,14.90281636,0,0,0,150 +86.75,50.41739403,-3.583736811,50,-25.80720931,14.9074813,0,0,0,150 +86.76,50.41739171,-3.583734713,50,-25.81068548,14.91147992,0,0,0,150 +86.77,50.41738939,-3.583732615,50,-25.82459021,14.91614486,0,0,0,150 +86.78,50.41738707,-3.583730516,50,-25.8454473,14.92192033,0,0,0,150 +86.79,50.41738474,-3.583728416,50,-25.85935204,14.9279179,0,0,0,150 +86.8,50.41738242,-3.583726315,50,-25.86282823,14.93347126,0,0,0,150 +86.81,50.41738009,-3.583724214,50,-25.86630442,14.93858041,0,0,0,150 +86.82,50.41737777,-3.583722111,50,-25.88020916,14.94324536,0,0,0,150 +86.83,50.41737544,-3.583720009,50,-25.90106627,14.9479103,0,0,0,150 +86.84,50.41737311,-3.583717905,50,-25.91497101,14.95279735,0,0,0,150 +86.85,50.41737078,-3.583715801,50,-25.91844718,14.95724019,0,0,0,150 +86.86,50.41736845,-3.583713696,50,-25.91844715,14.96123882,0,0,0,150 +86.87,50.41736612,-3.583711591,50,-25.91844714,14.96590377,0,0,0,150 +86.88,50.41736379,-3.583709485,50,-25.92192332,14.97190135,0,0,0,150 +86.89,50.41736146,-3.583707378,50,-25.93582807,14.97856524,0,0,0,150 +86.9,50.41735913,-3.58370527,50,-25.95320899,14.98434072,0,0,0,150 +86.91,50.41735679,-3.583703161,50,-25.95668517,14.98833935,0,0,0,150 +86.92,50.41735446,-3.583701052,50,-25.95668515,14.99167167,0,0,0,150 +86.93,50.41735213,-3.583698943,50,-25.97406606,14.9954482,0,0,0,150 +86.94,50.41734979,-3.583696832,50,-25.99144698,14.99855841,0,0,0,150 +86.95,50.41734745,-3.583694722,50,-25.9879708,14.99966968,0,0,0,150 +86.96,50.41734512,-3.583692611,50,-25.97754224,14.9992262,0,0,0,150 +86.97,50.41734278,-3.583690501,50,-25.97406604,14.99878273,0,0,0,150 +86.98,50.41734045,-3.583688391,50,-25.97406601,14.99922768,0,0,0,150 +86.99,50.41733811,-3.58368628,50,-25.97754218,14.99989473,0,0,0,150 +87,50.41733578,-3.58368417,50,-25.98797075,15.00011758,0,0,0,150 +87.01,50.41733344,-3.583682059,50,-25.99492312,15.00011831,0,0,0,150 +87.02,50.4173311,-3.583679949,50,-25.98797072,15.00011905,0,0,0,150 +87.03,50.41732877,-3.583677838,50,-25.97754215,15.00011979,0,0,0,150 +87.04,50.41732643,-3.583675728,50,-25.97406596,15.00012053,0,0,0,150 +87.05,50.4173241,-3.583673617,50,-25.97406596,15.00012126,0,0,0,150 +87.06,50.41732176,-3.583671507,50,-25.97406595,15.000122,0,0,0,150 +87.07,50.41731943,-3.583669396,50,-25.97406593,15.00012274,0,0,0,150 +87.08,50.41731709,-3.583667286,50,-25.9775421,15.00012348,0,0,0,150 +87.09,50.41731476,-3.583665175,50,-25.98797064,15.00012421,0,0,0,150 +87.1,50.41731242,-3.583663065,50,-25.994923,15.00012495,0,0,0,150 +87.11,50.41731008,-3.583660954,50,-25.98797063,15.00012569,0,0,0,150 +87.12,50.41730775,-3.583658844,50,-25.97754207,15.00012643,0,0,0,150 +87.13,50.41730541,-3.583656733,50,-25.97406586,15.00012716,0,0,0,150 +87.14,50.41730308,-3.583654623,50,-25.97406584,15.0001279,0,0,0,150 +87.15,50.41730074,-3.583652512,50,-25.97406584,15.00012864,0,0,0,150 +87.16,50.41729841,-3.583650402,50,-25.97406584,14.99990727,0,0,0,150 +87.17,50.41729607,-3.583648291,50,-25.97754201,14.99924169,0,0,0,150 +87.18,50.41729374,-3.583646181,50,-25.98797055,14.99879822,0,0,0,150 +87.19,50.4172914,-3.583644071,50,-25.99492291,14.99924317,0,0,0,150 +87.2,50.41728906,-3.58364196,50,-25.98797055,14.99991022,0,0,0,150 +87.21,50.41728673,-3.58363985,50,-25.97754198,15.00013307,0,0,0,150 +87.22,50.41728439,-3.583637739,50,-25.97406577,15.0001338,0,0,0,150 +87.23,50.41728206,-3.583635629,50,-25.97406575,15.00013454,0,0,0,150 +87.24,50.41727972,-3.583633518,50,-25.97754192,15.00013528,0,0,0,150 +87.25,50.41727739,-3.583631408,50,-25.98797049,15.00013602,0,0,0,150 +87.26,50.41727505,-3.583629297,50,-25.99492285,15.00013675,0,0,0,150 +87.27,50.41727271,-3.583627187,50,-25.98797047,15.00013749,0,0,0,150 +87.28,50.41727038,-3.583625076,50,-25.97754189,15.00013823,0,0,0,150 +87.29,50.41726804,-3.583622966,50,-25.97406569,15.00013897,0,0,0,150 +87.3,50.41726571,-3.583620855,50,-25.97406569,15.0001397,0,0,0,150 +87.31,50.41726337,-3.583618745,50,-25.97406568,15.00014044,0,0,0,150 +87.32,50.41726104,-3.583616634,50,-25.97406567,15.00014118,0,0,0,150 +87.33,50.4172587,-3.583614524,50,-25.97754184,15.00014191,0,0,0,150 +87.34,50.41725637,-3.583612413,50,-25.98797038,15.00014265,0,0,0,150 +87.35,50.41725403,-3.583610303,50,-25.99492275,15.00014339,0,0,0,150 +87.36,50.41725169,-3.583608192,50,-25.98797038,15.00014413,0,0,0,150 +87.37,50.41724936,-3.583606082,50,-25.97754181,15.00014487,0,0,0,150 +87.38,50.41724702,-3.583603971,50,-25.9740656,15.0001456,0,0,0,150 +87.39,50.41724469,-3.583601861,50,-25.97406558,15.00014634,0,0,0,150 +87.4,50.41724235,-3.58359975,50,-25.97406557,15.00014708,0,0,0,150 +87.41,50.41724002,-3.58359764,50,-25.97406558,14.99992571,0,0,0,150 +87.42,50.41723768,-3.583595529,50,-25.97754176,14.99926013,0,0,0,150 +87.43,50.41723535,-3.583593419,50,-25.9879703,14.99881665,0,0,0,150 +87.44,50.41723301,-3.583591309,50,-25.99492265,14.99926161,0,0,0,150 +87.45,50.41723067,-3.583589198,50,-25.98797026,14.99992866,0,0,0,150 +87.46,50.41722834,-3.583587088,50,-25.9775417,15.0001515,0,0,0,150 +87.47,50.417226,-3.583584977,50,-25.97406551,15.00015224,0,0,0,150 +87.48,50.41722367,-3.583582867,50,-25.9740655,15.00015298,0,0,0,150 +87.49,50.41722133,-3.583580756,50,-25.97754167,15.00015372,0,0,0,150 +87.5,50.417219,-3.583578646,50,-25.98797022,15.00015445,0,0,0,150 +87.51,50.41721666,-3.583576535,50,-25.99492259,15.00015519,0,0,0,150 +87.52,50.41721432,-3.583574425,50,-25.98797021,15.00015593,0,0,0,150 +87.53,50.41721199,-3.583572314,50,-25.97754163,15.00015667,0,0,0,150 +87.54,50.41720965,-3.583570204,50,-25.97406542,15.00015741,0,0,0,150 +87.55,50.41720732,-3.583568093,50,-25.97406541,15.00015814,0,0,0,150 +87.56,50.41720498,-3.583565983,50,-25.97406541,15.00015888,0,0,0,150 +87.57,50.41720265,-3.583563872,50,-25.97406542,15.00015962,0,0,0,150 +87.58,50.41720031,-3.583561762,50,-25.97754159,15.00016036,0,0,0,150 +87.59,50.41719798,-3.583559651,50,-25.98797012,15.00016109,0,0,0,150 +87.6,50.41719564,-3.583557541,50,-25.99492248,15.00016183,0,0,0,150 +87.61,50.4171933,-3.58355543,50,-25.98797011,15.00016257,0,0,0,150 +87.62,50.41719097,-3.58355332,50,-25.97754155,15.00016331,0,0,0,150 +87.63,50.41718863,-3.583551209,50,-25.97406535,15.00016404,0,0,0,150 +87.64,50.4171863,-3.583549099,50,-25.97406532,14.99994267,0,0,0,150 +87.65,50.41718396,-3.583546988,50,-25.97406531,14.99927709,0,0,0,150 +87.66,50.41718163,-3.583544878,50,-25.97406531,14.99883362,0,0,0,150 +87.67,50.41717929,-3.583542768,50,-25.97754149,14.99927857,0,0,0,150 +87.68,50.41717696,-3.583540657,50,-25.98797003,14.99994562,0,0,0,150 +87.69,50.41717462,-3.583538547,50,-25.99492239,15.00016847,0,0,0,150 +87.7,50.41717228,-3.583536436,50,-25.98797,15.00016921,0,0,0,150 +87.71,50.41716995,-3.583534326,50,-25.97754144,15.00016994,0,0,0,150 +87.72,50.41716761,-3.583532215,50,-25.97406525,15.00017068,0,0,0,150 +87.73,50.41716528,-3.583530105,50,-25.97406524,15.00017142,0,0,0,150 +87.74,50.41716294,-3.583527994,50,-25.97754141,15.00017216,0,0,0,150 +87.75,50.41716061,-3.583525884,50,-25.98796995,15.00017289,0,0,0,150 +87.76,50.41715827,-3.583523773,50,-25.99492232,15.00017363,0,0,0,150 +87.77,50.41715593,-3.583521663,50,-25.98796995,15.00017437,0,0,0,150 +87.78,50.4171536,-3.583519552,50,-25.97754137,15.00017511,0,0,0,150 +87.79,50.41715126,-3.583517442,50,-25.97406516,15.00017584,0,0,0,150 +87.8,50.41714893,-3.583515331,50,-25.97406515,15.00017658,0,0,0,150 +87.81,50.41714659,-3.583513221,50,-25.97406516,15.00017732,0,0,0,150 +87.82,50.41714426,-3.58351111,50,-25.97406516,15.00017806,0,0,0,150 +87.83,50.41714192,-3.583509,50,-25.97754132,14.99995669,0,0,0,150 +87.84,50.41713959,-3.583506889,50,-25.98796985,14.9992911,0,0,0,150 +87.85,50.41713725,-3.583504779,50,-25.99492222,14.99884763,0,0,0,150 +87.86,50.41713491,-3.583502669,50,-25.98796985,14.99929258,0,0,0,150 +87.87,50.41713258,-3.583500558,50,-25.97754128,14.99995964,0,0,0,150 +87.88,50.41713024,-3.583498448,50,-25.97406508,15.00018248,0,0,0,150 +87.89,50.41712791,-3.583496337,50,-25.97406506,15.00018322,0,0,0,150 +87.9,50.41712557,-3.583494227,50,-25.97406505,15.00018396,0,0,0,150 +87.91,50.41712324,-3.583492116,50,-25.97406505,15.00018469,0,0,0,150 +87.92,50.4171209,-3.583490006,50,-25.97754123,15.00018543,0,0,0,150 +87.93,50.41711857,-3.583487895,50,-25.98796977,15.00018617,0,0,0,150 +87.94,50.41711623,-3.583485785,50,-25.99492212,15.00018691,0,0,0,150 +87.95,50.41711389,-3.583483674,50,-25.98796974,15.00018765,0,0,0,150 +87.96,50.41711156,-3.583481564,50,-25.97754118,15.00018838,0,0,0,150 +87.97,50.41710922,-3.583479453,50,-25.974065,15.00018912,0,0,0,150 +87.98,50.41710689,-3.583477343,50,-25.97406499,15.00018986,0,0,0,150 +87.99,50.41710455,-3.583475232,50,-25.97406496,15.00019059,0,0,0,150 +88,50.41710222,-3.583473122,50,-25.97406494,15.00019133,0,0,0,150 +88.01,50.41709988,-3.583471011,50,-25.97754112,15.00019207,0,0,0,150 +88.02,50.41709755,-3.583468901,50,-25.98796969,14.9999707,0,0,0,150 +88.03,50.41709521,-3.58346679,50,-25.99492206,14.99930512,0,0,0,150 +88.04,50.41709287,-3.58346468,50,-25.98796966,14.99886164,0,0,0,150 +88.05,50.41709054,-3.58346257,50,-25.97754107,14.99930659,0,0,0,150 +88.06,50.4170882,-3.583460459,50,-25.97406488,14.99997365,0,0,0,150 +88.07,50.41708587,-3.583458349,50,-25.97406488,15.00019649,0,0,0,150 +88.08,50.41708353,-3.583456238,50,-25.97754106,15.00019723,0,0,0,150 +88.09,50.4170812,-3.583454128,50,-25.98796961,15.00019797,0,0,0,150 +88.1,50.41707886,-3.583452017,50,-25.99492196,15.00019871,0,0,0,150 +88.11,50.41707652,-3.583449907,50,-25.98796958,15.00019945,0,0,0,150 +88.12,50.41707419,-3.583447796,50,-25.97754101,15.00020018,0,0,0,150 +88.13,50.41707185,-3.583445686,50,-25.97406482,15.00020092,0,0,0,150 +88.14,50.41706952,-3.583443575,50,-25.9740648,15.00020166,0,0,0,150 +88.15,50.41706718,-3.583441465,50,-25.97406478,15.0002024,0,0,0,150 +88.16,50.41706485,-3.583439354,50,-25.97406477,15.00020313,0,0,0,150 +88.17,50.41706251,-3.583437244,50,-25.97754096,15.00020387,0,0,0,150 +88.18,50.41706018,-3.583435133,50,-25.98796953,15.00020461,0,0,0,150 +88.19,50.41705784,-3.583433023,50,-25.99492188,15.00020535,0,0,0,150 +88.2,50.4170555,-3.583430912,50,-25.98796948,15.00020608,0,0,0,150 +88.21,50.41705317,-3.583428802,50,-25.9775409,15.00020682,0,0,0,150 +88.22,50.41705083,-3.583426691,50,-25.97406472,15.00020756,0,0,0,150 +88.23,50.4170485,-3.583424581,50,-25.97406473,14.99998619,0,0,0,150 +88.24,50.41704616,-3.58342247,50,-25.9775409,14.99932061,0,0,0,150 +88.25,50.41704383,-3.58342036,50,-25.98796943,14.99887713,0,0,0,150 +88.26,50.41704149,-3.58341825,50,-25.99492179,14.99932208,0,0,0,150 +88.27,50.41703915,-3.583416139,50,-25.98796942,14.99998914,0,0,0,150 +88.28,50.41703682,-3.583414029,50,-25.97754085,15.00021198,0,0,0,150 +88.29,50.41703448,-3.583411918,50,-25.97406465,15.00021272,0,0,0,150 +88.3,50.41703215,-3.583409808,50,-25.97406463,15.00021346,0,0,0,150 +88.31,50.41702981,-3.583407697,50,-25.97406462,15.0002142,0,0,0,150 +88.32,50.41702748,-3.583405587,50,-25.97406461,15.00021494,0,0,0,150 +88.33,50.41702514,-3.583403476,50,-25.9775408,15.00021567,0,0,0,150 +88.34,50.41702281,-3.583401366,50,-25.98796935,15.00021641,0,0,0,150 +88.35,50.41702047,-3.583399255,50,-25.9949217,15.00021715,0,0,0,150 +88.36,50.41701813,-3.583397145,50,-25.98796931,15.00021788,0,0,0,150 +88.37,50.4170158,-3.583395034,50,-25.97754075,15.00021862,0,0,0,150 +88.38,50.41701346,-3.583392924,50,-25.97406456,15.00021936,0,0,0,150 +88.39,50.41701113,-3.583390813,50,-25.97406454,15.0002201,0,0,0,150 +88.4,50.41700879,-3.583388703,50,-25.97754071,15.00022083,0,0,0,150 +88.41,50.41700646,-3.583386592,50,-25.98796926,15.00022157,0,0,0,150 +88.42,50.41700412,-3.583384482,50,-25.99492164,15.00022231,0,0,0,150 +88.43,50.41700178,-3.583382371,50,-25.98796926,15.00022305,0,0,0,150 +88.44,50.41699945,-3.583380261,50,-25.97754068,15.00000168,0,0,0,150 +88.45,50.41699711,-3.58337815,50,-25.97406447,14.9993361,0,0,0,150 +88.46,50.41699478,-3.58337604,50,-25.97406446,14.99889262,0,0,0,150 +88.47,50.41699244,-3.58337393,50,-25.97406447,14.99933757,0,0,0,150 +88.48,50.41699011,-3.583371819,50,-25.97406446,15.00000463,0,0,0,150 +88.49,50.41698777,-3.583369709,50,-25.97754063,15.00022747,0,0,0,150 +88.5,50.41698544,-3.583367598,50,-25.98796916,15.00022821,0,0,0,150 +88.51,50.4169831,-3.583365488,50,-25.99492153,15.00022895,0,0,0,150 +88.52,50.41698076,-3.583363377,50,-25.98796915,15.00022969,0,0,0,150 +88.53,50.41697843,-3.583361267,50,-25.97754059,15.00023042,0,0,0,150 +88.54,50.41697609,-3.583359156,50,-25.97406439,15.00023116,0,0,0,150 +88.55,50.41697376,-3.583357046,50,-25.97406436,15.0002319,0,0,0,150 +88.56,50.41697142,-3.583354935,50,-25.97406435,15.00023264,0,0,0,150 +88.57,50.41696909,-3.583352825,50,-25.97406436,15.00023337,0,0,0,150 +88.58,50.41696675,-3.583350714,50,-25.97754055,15.00023411,0,0,0,150 +88.59,50.41696442,-3.583348604,50,-25.98796909,15.00023485,0,0,0,150 +88.6,50.41696208,-3.583346493,50,-25.99492143,15.00023559,0,0,0,150 +88.61,50.41695974,-3.583344383,50,-25.98796905,15.00023633,0,0,0,150 +88.62,50.41695741,-3.583342272,50,-25.97754049,15.00023706,0,0,0,150 +88.63,50.41695507,-3.583340162,50,-25.97406431,15.0002378,0,0,0,150 +88.64,50.41695274,-3.583338051,50,-25.9740643,15.00023854,0,0,0,150 +88.65,50.4169504,-3.583335941,50,-25.97406427,15.00001717,0,0,0,150 +88.66,50.41694807,-3.58333383,50,-25.97406425,14.99935158,0,0,0,150 +88.67,50.41694573,-3.58333172,50,-25.97754042,14.9989081,0,0,0,150 +88.68,50.4169434,-3.58332961,50,-25.98796899,14.99935306,0,0,0,150 +88.69,50.41694106,-3.583327499,50,-25.99492135,15.00002012,0,0,0,150 +88.7,50.41693872,-3.583325389,50,-25.98796897,15.00024296,0,0,0,150 +88.71,50.41693639,-3.583323278,50,-25.97754039,15.0002437,0,0,0,150 +88.72,50.41693405,-3.583321168,50,-25.97406419,15.00024444,0,0,0,150 +88.73,50.41693172,-3.583319057,50,-25.97406419,15.00024517,0,0,0,150 +88.74,50.41692938,-3.583316947,50,-25.97754036,15.00024591,0,0,0,150 +88.75,50.41692705,-3.583314836,50,-25.9879689,15.00024665,0,0,0,150 +88.76,50.41692471,-3.583312726,50,-25.99492126,15.00024739,0,0,0,150 +88.77,50.41692237,-3.583310615,50,-25.98796889,15.00024813,0,0,0,150 +88.78,50.41692004,-3.583308505,50,-25.97754033,15.00024886,0,0,0,150 +88.79,50.4169177,-3.583306394,50,-25.97406412,15.0002496,0,0,0,150 +88.8,50.41691537,-3.583304284,50,-25.9740641,15.00025034,0,0,0,150 +88.81,50.41691303,-3.583302173,50,-25.97406409,15.00025108,0,0,0,150 +88.82,50.4169107,-3.583300063,50,-25.9740641,15.0000297,0,0,0,150 +88.83,50.41690836,-3.583297952,50,-25.97754028,14.99936412,0,0,0,150 +88.84,50.41690603,-3.583295842,50,-25.98796882,14.99892064,0,0,0,150 +88.85,50.41690369,-3.583293732,50,-25.99492117,14.9993656,0,0,0,150 +88.86,50.41690135,-3.583291621,50,-25.98796879,15.00003266,0,0,0,150 +88.87,50.41689902,-3.583289511,50,-25.97754023,15.0002555,0,0,0,150 +88.88,50.41689668,-3.5832874,50,-25.97406405,15.00025624,0,0,0,150 +88.89,50.41689435,-3.58328529,50,-25.97406403,15.00025698,0,0,0,150 +88.9,50.41689201,-3.583283179,50,-25.97406401,15.00025771,0,0,0,150 +88.91,50.41688968,-3.583281069,50,-25.97406399,15.00025845,0,0,0,150 +88.92,50.41688734,-3.583278958,50,-25.97754016,15.00025919,0,0,0,150 +88.93,50.41688501,-3.583276848,50,-25.98796872,15.00003782,0,0,0,150 +88.94,50.41688267,-3.583274737,50,-25.99492109,14.99937223,0,0,0,150 +88.95,50.41688033,-3.583272627,50,-25.98796871,14.99892876,0,0,0,150 +88.96,50.416878,-3.583270517,50,-25.97754013,14.99937371,0,0,0,150 +88.97,50.41687566,-3.583268406,50,-25.97406393,15.00004077,0,0,0,150 +88.98,50.41687333,-3.583266296,50,-25.97406392,15.00026361,0,0,0,150 +88.99,50.41687099,-3.583264185,50,-25.97754011,15.00026435,0,0,0,150 +89,50.41686866,-3.583262075,50,-25.98796865,15.00026509,0,0,0,150 +89.01,50.41686632,-3.583259964,50,-25.994921,15.00026583,0,0,0,150 +89.02,50.41686398,-3.583257854,50,-25.98796862,15.00004446,0,0,0,150 +89.03,50.41686165,-3.583255743,50,-25.97754007,14.99937887,0,0,0,150 +89.04,50.41685931,-3.583253633,50,-25.97406388,14.99893539,0,0,0,150 +89.05,50.41685698,-3.583251523,50,-25.97406385,14.99938035,0,0,0,150 +89.06,50.41685464,-3.583249412,50,-25.97406383,15.00004741,0,0,0,150 +89.07,50.41685231,-3.583247302,50,-25.97406382,15.00027025,0,0,0,150 +89.08,50.41684997,-3.583245191,50,-25.97754001,15.00027099,0,0,0,150 +89.09,50.41684764,-3.583243081,50,-25.98796857,15.00027173,0,0,0,150 +89.1,50.4168453,-3.58324097,50,-25.99492092,15.00027246,0,0,0,150 +89.11,50.41684296,-3.58323886,50,-25.98796852,15.0002732,0,0,0,150 +89.12,50.41684063,-3.583236749,50,-25.97753995,15.00027394,0,0,0,150 +89.13,50.41683829,-3.583234639,50,-25.97406377,15.00005257,0,0,0,150 +89.14,50.41683596,-3.583232528,50,-25.97406376,14.99938698,0,0,0,150 +89.15,50.41683362,-3.583230418,50,-25.97406375,14.99894351,0,0,0,150 +89.16,50.41683129,-3.583228308,50,-25.97406373,14.99938846,0,0,0,150 +89.17,50.41682895,-3.583226197,50,-25.97753991,15.00005552,0,0,0,150 +89.18,50.41682662,-3.583224087,50,-25.98796846,15.00027836,0,0,0,150 +89.19,50.41682428,-3.583221976,50,-25.99492083,15.0002791,0,0,0,150 +89.2,50.41682194,-3.583219866,50,-25.98796844,15.00027984,0,0,0,150 +89.21,50.41681961,-3.583217755,50,-25.97753986,15.00028058,0,0,0,150 +89.22,50.41681727,-3.583215645,50,-25.97406366,15.00005921,0,0,0,150 +89.23,50.41681494,-3.583213534,50,-25.97406366,14.99939362,0,0,0,150 +89.24,50.4168126,-3.583211424,50,-25.97753985,14.99895014,0,0,0,150 +89.25,50.41681027,-3.583209314,50,-25.9879684,14.9993951,0,0,0,150 +89.26,50.41680793,-3.583207203,50,-25.99492074,15.00006216,0,0,0,150 +89.27,50.41680559,-3.583205093,50,-25.98796835,15.000285,0,0,0,150 +89.28,50.41680326,-3.583202982,50,-25.9775398,15.00028574,0,0,0,150 +89.29,50.41680092,-3.583200872,50,-25.97406361,15.00028648,0,0,0,150 +89.3,50.41679859,-3.583198761,50,-25.97406359,15.00028722,0,0,0,150 +89.31,50.41679625,-3.583196651,50,-25.97406357,15.00028795,0,0,0,150 +89.32,50.41679392,-3.58319454,50,-25.97406357,15.00028869,0,0,0,150 +89.33,50.41679158,-3.58319243,50,-25.97753975,15.00028943,0,0,0,150 +89.34,50.41678925,-3.583190319,50,-25.9879683,15.00029017,0,0,0,150 +89.35,50.41678691,-3.583188209,50,-25.99492065,15.0002909,0,0,0,150 +89.36,50.41678457,-3.583186098,50,-25.98796826,15.00029164,0,0,0,150 +89.37,50.41678224,-3.583183988,50,-25.97753969,15.00007027,0,0,0,150 +89.38,50.4167799,-3.583181877,50,-25.9740635,14.99940468,0,0,0,150 +89.39,50.41677757,-3.583179767,50,-25.9740635,14.99896121,0,0,0,150 +89.4,50.41677523,-3.583177657,50,-25.97753968,14.99940616,0,0,0,150 +89.41,50.4167729,-3.583175546,50,-25.98796822,15.00007322,0,0,0,150 +89.42,50.41677056,-3.583173436,50,-25.99492057,15.00029607,0,0,0,150 +89.43,50.41676822,-3.583171325,50,-25.9879682,15.00029681,0,0,0,150 +89.44,50.41676589,-3.583169215,50,-25.97753963,15.00029754,0,0,0,150 +89.45,50.41676355,-3.583167104,50,-25.97406343,15.00029828,0,0,0,150 +89.46,50.41676122,-3.583164994,50,-25.97406341,15.00029902,0,0,0,150 +89.47,50.41675888,-3.583162883,50,-25.9740634,15.00029976,0,0,0,150 +89.48,50.41675655,-3.583160773,50,-25.97406341,15.00030049,0,0,0,150 +89.49,50.41675421,-3.583158662,50,-25.97753959,15.00030123,0,0,0,150 +89.5,50.41675188,-3.583156552,50,-25.98796813,15.00030197,0,0,0,150 +89.51,50.41674954,-3.583154441,50,-25.99492047,15.00030271,0,0,0,150 +89.52,50.4167472,-3.583152331,50,-25.98796809,15.00030344,0,0,0,150 +89.53,50.41674487,-3.58315022,50,-25.97753953,15.00030418,0,0,0,150 +89.54,50.41674253,-3.58314811,50,-25.97406334,15.00030492,0,0,0,150 +89.55,50.4167402,-3.583145999,50,-25.97406334,15.00030565,0,0,0,150 +89.56,50.41673786,-3.583143889,50,-25.97406332,15.00030639,0,0,0,150 +89.57,50.41673553,-3.583141778,50,-25.9740633,15.00030713,0,0,0,150 +89.58,50.41673319,-3.583139668,50,-25.97753947,15.00008576,0,0,0,150 +89.59,50.41673086,-3.583137557,50,-25.98796803,14.99942017,0,0,0,150 +89.6,50.41672852,-3.583135447,50,-25.9949204,14.99897669,0,0,0,150 +89.61,50.41672618,-3.583133337,50,-25.98796801,14.99942165,0,0,0,150 +89.62,50.41672385,-3.583131226,50,-25.97753943,15.00008871,0,0,0,150 +89.63,50.41672151,-3.583129116,50,-25.97406323,15.00031155,0,0,0,150 +89.64,50.41671918,-3.583127005,50,-25.97406324,15.00031229,0,0,0,150 +89.65,50.41671684,-3.583124895,50,-25.97753942,15.00031303,0,0,0,150 +89.66,50.41671451,-3.583122784,50,-25.98796796,15.00031377,0,0,0,150 +89.67,50.41671217,-3.583120674,50,-25.99492031,15.0000924,0,0,0,150 +89.68,50.41670983,-3.583118563,50,-25.98796793,14.99942681,0,0,0,150 +89.69,50.4167075,-3.583116453,50,-25.97753937,14.99898333,0,0,0,150 +89.7,50.41670516,-3.583114343,50,-25.97406318,14.99942829,0,0,0,150 +89.71,50.41670283,-3.583112232,50,-25.97406316,15.00009535,0,0,0,150 +89.72,50.41670049,-3.583110122,50,-25.97406313,15.00031819,0,0,0,150 +89.73,50.41669816,-3.583108011,50,-25.97406313,15.00031893,0,0,0,150 +89.74,50.41669582,-3.583105901,50,-25.97753931,15.00031967,0,0,0,150 +89.75,50.41669349,-3.58310379,50,-25.98796787,15.00032041,0,0,0,150 +89.76,50.41669115,-3.58310168,50,-25.99492023,15.00009904,0,0,0,150 +89.77,50.41668881,-3.583099569,50,-25.98796783,14.99943345,0,0,0,150 +89.78,50.41668648,-3.583097459,50,-25.97753926,14.99898997,0,0,0,150 +89.79,50.41668414,-3.583095349,50,-25.97406308,14.99943492,0,0,0,150 +89.8,50.41668181,-3.583093238,50,-25.97406308,15.00010199,0,0,0,150 +89.81,50.41667947,-3.583091128,50,-25.97406306,15.00032483,0,0,0,150 +89.82,50.41667714,-3.583089017,50,-25.97406303,15.00032557,0,0,0,150 +89.83,50.4166748,-3.583086907,50,-25.97753921,15.0001042,0,0,0,150 +89.84,50.41667247,-3.583084796,50,-25.98796777,14.99943861,0,0,0,150 +89.85,50.41667013,-3.583082686,50,-25.99492015,14.99899513,0,0,0,150 +89.86,50.41666779,-3.583080576,50,-25.98796776,14.99944008,0,0,0,150 +89.87,50.41666546,-3.583078465,50,-25.97753917,15.00010715,0,0,0,150 +89.88,50.41666312,-3.583076355,50,-25.97406297,15.00032999,0,0,0,150 +89.89,50.41666079,-3.583074244,50,-25.97406297,15.00033073,0,0,0,150 +89.9,50.41665845,-3.583072134,50,-25.97753915,15.00033147,0,0,0,150 +89.91,50.41665612,-3.583070023,50,-25.98796769,15.00033221,0,0,0,150 +89.92,50.41665378,-3.583067913,50,-25.99492005,15.00011084,0,0,0,150 +89.93,50.41665144,-3.583065802,50,-25.98796767,14.99944525,0,0,0,150 +89.94,50.41664911,-3.583063692,50,-25.97753911,14.99900177,0,0,0,150 +89.95,50.41664677,-3.583061582,50,-25.97406292,14.99944672,0,0,0,150 +89.96,50.41664444,-3.583059471,50,-25.97406289,15.00011379,0,0,0,150 +89.97,50.4166421,-3.583057361,50,-25.97406287,15.00033663,0,0,0,150 +89.98,50.41663977,-3.58305525,50,-25.97406286,15.00033737,0,0,0,150 +89.99,50.41663743,-3.58305314,50,-25.97753905,15.00033811,0,0,0,150 +90,50.4166351,-3.583051029,50,-25.98796761,15.00033884,0,0,0,150 +90.01,50.41663276,-3.583048919,50,-25.99491997,15.00033958,0,0,0,150 +90.02,50.41663042,-3.583046808,50,-25.98796758,15.00034032,0,0,0,150 +90.03,50.41662809,-3.583044698,50,-25.977539,15.00034106,0,0,0,150 +90.04,50.41662575,-3.583042587,50,-25.97406281,15.0003418,0,0,0,150 +90.05,50.41662342,-3.583040477,50,-25.97406281,15.00034253,0,0,0,150 +90.06,50.41662108,-3.583038366,50,-25.97406279,15.00034327,0,0,0,150 +90.07,50.41661875,-3.583036256,50,-25.97406277,15.00034401,0,0,0,150 +90.08,50.41661641,-3.583034145,50,-25.97753895,15.00034475,0,0,0,150 +90.09,50.41661408,-3.583032035,50,-25.98796752,15.00012337,0,0,0,150 +90.1,50.41661174,-3.583029924,50,-25.99491988,14.99945779,0,0,0,150 +90.11,50.4166094,-3.583027814,50,-25.98796749,14.99901431,0,0,0,150 +90.12,50.41660707,-3.583025704,50,-25.9775389,14.99945926,0,0,0,150 +90.13,50.41660473,-3.583023593,50,-25.97406271,15.00012632,0,0,0,150 +90.14,50.4166024,-3.583021483,50,-25.97406272,15.00034917,0,0,0,150 +90.15,50.41660006,-3.583019372,50,-25.9775389,15.00034991,0,0,0,150 +90.16,50.41659773,-3.583017262,50,-25.98796743,15.00035065,0,0,0,150 +90.17,50.41659539,-3.583015151,50,-25.99491978,15.00035138,0,0,0,150 +90.18,50.41659305,-3.583013041,50,-25.9879674,15.00035212,0,0,0,150 +90.19,50.41659072,-3.58301093,50,-25.97753884,15.00035286,0,0,0,150 +90.2,50.41658838,-3.58300882,50,-25.97406265,15.00013149,0,0,0,150 +90.21,50.41658605,-3.583006709,50,-25.97406264,14.9994659,0,0,0,150 +90.22,50.41658371,-3.583004599,50,-25.97406262,14.99902242,0,0,0,150 +90.23,50.41658138,-3.583002489,50,-25.9740626,14.99946737,0,0,0,150 +90.24,50.41657904,-3.583000378,50,-25.97753878,15.00013444,0,0,0,150 +90.25,50.41657671,-3.582998268,50,-25.98796735,15.00035728,0,0,0,150 +90.26,50.41657437,-3.582996157,50,-25.99491972,15.00035802,0,0,0,150 +90.27,50.41657203,-3.582994047,50,-25.98796732,15.00013665,0,0,0,150 +90.28,50.4165697,-3.582991936,50,-25.97753873,14.99947106,0,0,0,150 +90.29,50.41656736,-3.582989826,50,-25.97406254,14.99902758,0,0,0,150 +90.3,50.41656503,-3.582987716,50,-25.97406255,14.99947254,0,0,0,150 +90.31,50.41656269,-3.582985605,50,-25.97406255,15.0001396,0,0,0,150 +90.32,50.41656036,-3.582983495,50,-25.97406252,15.00036245,0,0,0,150 +90.33,50.41655802,-3.582981384,50,-25.97753868,15.00036318,0,0,0,150 +90.34,50.41655569,-3.582979274,50,-25.98796723,15.00014181,0,0,0,150 +90.35,50.41655335,-3.582977163,50,-25.99491961,14.99947622,0,0,0,150 +90.36,50.41655101,-3.582975053,50,-25.98796723,14.99903274,0,0,0,150 +90.37,50.41654868,-3.582972943,50,-25.97753866,14.9994777,0,0,0,150 +90.38,50.41654634,-3.582970832,50,-25.97406245,15.00014476,0,0,0,150 +90.39,50.41654401,-3.582968722,50,-25.97406244,15.00036761,0,0,0,150 +90.4,50.41654167,-3.582966611,50,-25.97753862,15.00036835,0,0,0,150 +90.41,50.41653934,-3.582964501,50,-25.98796717,15.00014698,0,0,0,150 +90.42,50.416537,-3.58296239,50,-25.99491952,14.99948139,0,0,0,150 +90.43,50.41653466,-3.58296028,50,-25.98796714,14.99903791,0,0,0,150 +90.44,50.41653233,-3.58295817,50,-25.97753858,14.99948286,0,0,0,150 +90.45,50.41652999,-3.582956059,50,-25.97406239,15.00014993,0,0,0,150 +90.46,50.41652766,-3.582953949,50,-25.97406239,15.00037277,0,0,0,150 +90.47,50.41652532,-3.582951838,50,-25.97406237,15.00037351,0,0,0,150 +90.48,50.41652299,-3.582949728,50,-25.97406234,15.00037425,0,0,0,150 +90.49,50.41652065,-3.582947617,50,-25.97753851,15.00037499,0,0,0,150 +90.5,50.41651832,-3.582945507,50,-25.98796708,15.00037572,0,0,0,150 +90.51,50.41651598,-3.582943396,50,-25.99491945,15.00037646,0,0,0,150 +90.52,50.41651364,-3.582941286,50,-25.98796705,15.0003772,0,0,0,150 +90.53,50.41651131,-3.582939175,50,-25.97753848,15.00037794,0,0,0,150 +90.54,50.41650897,-3.582937065,50,-25.97406229,15.00037867,0,0,0,150 +90.55,50.41650664,-3.582934954,50,-25.97406229,15.00037941,0,0,0,150 +90.56,50.4165043,-3.582932844,50,-25.97753846,15.00038015,0,0,0,150 +90.57,50.41650197,-3.582930733,50,-25.987967,15.00038089,0,0,0,150 +90.58,50.41649963,-3.582928623,50,-25.99491935,15.00015952,0,0,0,150 +90.59,50.41649729,-3.582926512,50,-25.98796697,14.99949392,0,0,0,150 +90.6,50.41649496,-3.582924402,50,-25.97753841,14.99905044,0,0,0,150 +90.61,50.41649262,-3.582922292,50,-25.97406222,14.9994954,0,0,0,150 +90.62,50.41649029,-3.582920181,50,-25.97406221,15.00016247,0,0,0,150 +90.63,50.41648795,-3.582918071,50,-25.97406219,15.00038531,0,0,0,150 +90.64,50.41648562,-3.58291596,50,-25.97406217,15.00038605,0,0,0,150 +90.65,50.41648328,-3.58291385,50,-25.97753836,15.00038679,0,0,0,150 +90.66,50.41648095,-3.582911739,50,-25.98796691,15.00038753,0,0,0,150 +90.67,50.41647861,-3.582909629,50,-25.99491927,15.00038826,0,0,0,150 +90.68,50.41647627,-3.582907518,50,-25.98796687,15.000389,0,0,0,150 +90.69,50.41647394,-3.582905408,50,-25.97753831,15.00016763,0,0,0,150 +90.7,50.4164716,-3.582903297,50,-25.97406213,14.99950204,0,0,0,150 +90.71,50.41646927,-3.582901187,50,-25.97406213,14.99905856,0,0,0,150 +90.72,50.41646693,-3.582899077,50,-25.9740621,14.99950351,0,0,0,150 +90.73,50.4164646,-3.582896966,50,-25.97406208,15.00017058,0,0,0,150 +90.74,50.41646226,-3.582894856,50,-25.97753825,15.00017131,0,0,0,150 +90.75,50.41645993,-3.582892745,50,-25.98796681,14.99950572,0,0,0,150 +90.76,50.41645759,-3.582890635,50,-25.99491918,14.99906224,0,0,0,150 +90.77,50.41645525,-3.582888525,50,-25.9879668,14.9995072,0,0,0,150 +90.78,50.41645292,-3.582886414,50,-25.97753822,15.00017427,0,0,0,150 +90.79,50.41645058,-3.582884304,50,-25.97406202,15.00039711,0,0,0,150 +90.8,50.41644825,-3.582882193,50,-25.97406202,15.00039785,0,0,0,150 +90.81,50.41644591,-3.582880083,50,-25.9775382,15.00017648,0,0,0,150 +90.82,50.41644358,-3.582877972,50,-25.98796674,14.99951089,0,0,0,150 +90.83,50.41644124,-3.582875862,50,-25.99491909,14.99906741,0,0,0,150 +90.84,50.4164389,-3.582873752,50,-25.98796671,14.99951236,0,0,0,150 +90.85,50.41643657,-3.582871641,50,-25.97753815,15.00017943,0,0,0,150 +90.86,50.41643423,-3.582869531,50,-25.97406197,15.00018017,0,0,0,150 +90.87,50.4164319,-3.58286742,50,-25.97406196,14.99951458,0,0,0,150 +90.88,50.41642956,-3.58286531,50,-25.97406193,14.99907109,0,0,0,150 +90.89,50.41642723,-3.5828632,50,-25.97406191,14.99951605,0,0,0,150 +90.9,50.41642489,-3.582861089,50,-25.97753809,15.00018312,0,0,0,150 +90.91,50.41642256,-3.582858979,50,-25.98796665,15.00040596,0,0,0,150 +90.92,50.41642022,-3.582856868,50,-25.99491901,15.0004067,0,0,0,150 +90.93,50.41641788,-3.582854758,50,-25.98796662,15.00040744,0,0,0,150 +90.94,50.41641555,-3.582852647,50,-25.97753804,15.00040818,0,0,0,150 +90.95,50.41641321,-3.582850537,50,-25.97406186,15.00040891,0,0,0,150 +90.96,50.41641088,-3.582848426,50,-25.97406185,15.00040965,0,0,0,150 +90.97,50.41640854,-3.582846316,50,-25.97406184,15.00041039,0,0,0,150 +90.98,50.41640621,-3.582844205,50,-25.97406182,15.00041113,0,0,0,150 +90.99,50.41640387,-3.582842095,50,-25.977538,15.00041186,0,0,0,150 +91,50.41640154,-3.582839984,50,-25.98796656,15.0004126,0,0,0,150 +91.01,50.4163992,-3.582837874,50,-25.99491892,15.00041334,0,0,0,150 +91.02,50.41639686,-3.582835763,50,-25.98796653,15.00041408,0,0,0,150 +91.03,50.41639453,-3.582833653,50,-25.97753795,15.00041481,0,0,0,150 +91.04,50.41639219,-3.582831542,50,-25.97406175,15.00041555,0,0,0,150 +91.05,50.41638986,-3.582829432,50,-25.97406175,15.00019418,0,0,0,150 +91.06,50.41638752,-3.582827321,50,-25.97753794,14.99952859,0,0,0,150 +91.07,50.41638519,-3.582825211,50,-25.98796648,14.9990851,0,0,0,150 +91.08,50.41638285,-3.582823101,50,-25.99491883,14.99953006,0,0,0,150 +91.09,50.41638051,-3.58282099,50,-25.98796645,15.00019713,0,0,0,150 +91.1,50.41637818,-3.58281888,50,-25.9775379,15.00019787,0,0,0,150 +91.11,50.41637584,-3.582816769,50,-25.97406171,14.99953228,0,0,0,150 +91.12,50.41637351,-3.582814659,50,-25.97406169,14.99908879,0,0,0,150 +91.13,50.41637117,-3.582812549,50,-25.97406167,14.99953375,0,0,0,150 +91.14,50.41636884,-3.582810438,50,-25.97406165,15.00020082,0,0,0,150 +91.15,50.4163665,-3.582808328,50,-25.97753783,15.00042367,0,0,0,150 +91.16,50.41636417,-3.582806217,50,-25.98796639,15.0004244,0,0,0,150 +91.17,50.41636183,-3.582804107,50,-25.99491875,15.00020303,0,0,0,150 +91.18,50.41635949,-3.582801996,50,-25.98796636,14.99953744,0,0,0,150 +91.19,50.41635716,-3.582799886,50,-25.97753778,14.99909396,0,0,0,150 +91.2,50.41635482,-3.582797776,50,-25.97406159,14.99953891,0,0,0,150 +91.21,50.41635249,-3.582795665,50,-25.97406158,15.00020598,0,0,0,150 +91.22,50.41635015,-3.582793555,50,-25.97406158,15.00020672,0,0,0,150 +91.23,50.41634782,-3.582791444,50,-25.97406157,14.99954112,0,0,0,150 +91.24,50.41634548,-3.582789334,50,-25.97753774,14.99909764,0,0,0,150 +91.25,50.41634315,-3.582787224,50,-25.98796628,14.9995426,0,0,0,150 +91.26,50.41634081,-3.582785113,50,-25.99491865,15.00020967,0,0,0,150 +91.27,50.41633847,-3.582783003,50,-25.98796627,15.00043251,0,0,0,150 +91.28,50.41633614,-3.582780892,50,-25.9775377,15.00043325,0,0,0,150 +91.29,50.4163338,-3.582778782,50,-25.97406149,15.00043399,0,0,0,150 +91.3,50.41633147,-3.582776671,50,-25.97406148,15.00043473,0,0,0,150 +91.31,50.41632913,-3.582774561,50,-25.97406149,15.00043547,0,0,0,150 +91.32,50.4163268,-3.58277245,50,-25.97406149,15.0004362,0,0,0,150 +91.33,50.41632446,-3.58277034,50,-25.97753765,15.00043694,0,0,0,150 +91.34,50.41632213,-3.582768229,50,-25.98796618,15.00043768,0,0,0,150 +91.35,50.41631979,-3.582766119,50,-25.99491855,15.00021631,0,0,0,150 +91.36,50.41631745,-3.582764008,50,-25.98796617,14.99955071,0,0,0,150 +91.37,50.41631512,-3.582761898,50,-25.97753761,14.99910723,0,0,0,150 +91.38,50.41631278,-3.582759788,50,-25.97406141,14.99955219,0,0,0,150 +91.39,50.41631045,-3.582757677,50,-25.9740614,15.00021926,0,0,0,150 +91.4,50.41630811,-3.582755567,50,-25.97753757,15.0004421,0,0,0,150 +91.41,50.41630578,-3.582753456,50,-25.98796612,15.00044284,0,0,0,150 +91.42,50.41630344,-3.582751346,50,-25.99491849,15.00044358,0,0,0,150 +91.43,50.4163011,-3.582749235,50,-25.9879661,15.00044432,0,0,0,150 +91.44,50.41629877,-3.582747125,50,-25.97753752,15.00022294,0,0,0,150 +91.45,50.41629643,-3.582745014,50,-25.97406132,14.99955735,0,0,0,150 +91.46,50.4162941,-3.582742904,50,-25.97406133,14.99911387,0,0,0,150 +91.47,50.41629176,-3.582740794,50,-25.97406133,14.99955883,0,0,0,150 +91.48,50.41628943,-3.582738683,50,-25.97406131,15.00022589,0,0,0,150 +91.49,50.41628709,-3.582736573,50,-25.97753747,15.00022663,0,0,0,150 +91.5,50.41628476,-3.582734462,50,-25.98796601,14.99956104,0,0,0,150 +91.51,50.41628242,-3.582732352,50,-25.99491839,14.99911755,0,0,0,150 +91.52,50.41628008,-3.582730242,50,-25.98796602,14.99956251,0,0,0,150 +91.53,50.41627775,-3.582728131,50,-25.97753745,15.00022958,0,0,0,150 +91.54,50.41627541,-3.582726021,50,-25.97406123,15.00023032,0,0,0,150 +91.55,50.41627308,-3.58272391,50,-25.97406122,14.99956473,0,0,0,150 +91.56,50.41627074,-3.5827218,50,-25.97406122,14.99912124,0,0,0,150 +91.57,50.41626841,-3.58271969,50,-25.97406122,14.9995662,0,0,0,150 +91.58,50.41626607,-3.582717579,50,-25.97753738,15.00023327,0,0,0,150 +91.59,50.41626374,-3.582715469,50,-25.98796592,15.00045612,0,0,0,150 +91.6,50.4162614,-3.582713358,50,-25.99491829,15.00045685,0,0,0,150 +91.61,50.41625906,-3.582711248,50,-25.98796592,15.00045759,0,0,0,150 +91.62,50.41625673,-3.582709137,50,-25.97753735,15.00045833,0,0,0,150 +91.63,50.41625439,-3.582707027,50,-25.97406114,15.00023696,0,0,0,150 +91.64,50.41625206,-3.582704916,50,-25.97406112,14.99957136,0,0,0,150 +91.65,50.41624972,-3.582702806,50,-25.9775373,14.99912788,0,0,0,150 +91.66,50.41624739,-3.582700696,50,-25.98796586,14.99957284,0,0,0,150 +91.67,50.41624505,-3.582698585,50,-25.99491823,15.00023991,0,0,0,150 +91.68,50.41624271,-3.582696475,50,-25.98796584,15.00046276,0,0,0,150 +91.69,50.41624038,-3.582694364,50,-25.97753726,15.00046349,0,0,0,150 +91.7,50.41623804,-3.582692254,50,-25.97406106,15.00046423,0,0,0,150 +91.71,50.41623571,-3.582690143,50,-25.97406107,15.00046497,0,0,0,150 +91.72,50.41623337,-3.582688033,50,-25.97753725,15.00046571,0,0,0,150 +91.73,50.41623104,-3.582685922,50,-25.98796579,15.00046644,0,0,0,150 +91.74,50.4162287,-3.582683812,50,-25.99491813,15.00046718,0,0,0,150 +91.75,50.41622636,-3.582681701,50,-25.98796576,15.00046792,0,0,0,150 +91.76,50.41622403,-3.582679591,50,-25.9775372,15.00024655,0,0,0,150 +91.77,50.41622169,-3.58267748,50,-25.97406102,14.99958095,0,0,0,150 +91.78,50.41621936,-3.58267537,50,-25.974061,14.99913747,0,0,0,150 +91.79,50.41621702,-3.58267326,50,-25.97406098,14.99958243,0,0,0,150 +91.8,50.41621469,-3.582671149,50,-25.97406096,15.0002495,0,0,0,150 +91.81,50.41621235,-3.582669039,50,-25.97753713,15.00025023,0,0,0,150 +91.82,50.41621002,-3.582666928,50,-25.98796569,14.99958464,0,0,0,150 +91.83,50.41620768,-3.582664818,50,-25.99491806,14.99914115,0,0,0,150 +91.84,50.41620534,-3.582662708,50,-25.98796568,14.99958611,0,0,0,150 +91.85,50.41620301,-3.582660597,50,-25.9775371,15.00025318,0,0,0,150 +91.86,50.41620067,-3.582658487,50,-25.9740609,15.00025392,0,0,0,150 +91.87,50.41619834,-3.582656376,50,-25.97406089,14.99958833,0,0,0,150 +91.88,50.416196,-3.582654266,50,-25.97406089,14.99914484,0,0,0,150 +91.89,50.41619367,-3.582652156,50,-25.97406087,14.9995898,0,0,0,150 +91.9,50.41619133,-3.582650045,50,-25.97753704,15.00025687,0,0,0,150 +91.91,50.416189,-3.582647935,50,-25.98796559,15.00047972,0,0,0,150 +91.92,50.41618666,-3.582645824,50,-25.99491797,15.00048046,0,0,0,150 +91.93,50.41618432,-3.582643714,50,-25.98796559,15.00025908,0,0,0,150 +91.94,50.41618199,-3.582641603,50,-25.97753701,14.99959349,0,0,0,150 +91.95,50.41617965,-3.582639493,50,-25.9740608,14.99915001,0,0,0,150 +91.96,50.41617732,-3.582637383,50,-25.97406079,14.99959496,0,0,0,150 +91.97,50.41617498,-3.582635272,50,-25.97753698,15.00026203,0,0,0,150 +91.98,50.41617265,-3.582633162,50,-25.98796554,15.00048488,0,0,0,150 +91.99,50.41617031,-3.582631051,50,-25.99491789,15.00048562,0,0,0,150 +92,50.41616797,-3.582628941,50,-25.98796549,15.00048636,0,0,0,150 +92.01,50.41616564,-3.58262683,50,-25.97753692,15.0004871,0,0,0,150 +92.02,50.4161633,-3.58262472,50,-25.97406074,15.00048783,0,0,0,150 +92.03,50.41616097,-3.582622609,50,-25.97406073,15.00048857,0,0,0,150 +92.04,50.41615863,-3.582620499,50,-25.97406072,15.00048931,0,0,0,150 +92.05,50.4161563,-3.582618388,50,-25.97406069,15.00049005,0,0,0,150 +92.06,50.41615396,-3.582616278,50,-25.97753687,15.00026867,0,0,0,150 +92.07,50.41615163,-3.582614167,50,-25.98796543,14.99960308,0,0,0,150 +92.08,50.41614929,-3.582612057,50,-25.99491781,14.99915959,0,0,0,150 +92.09,50.41614695,-3.582609947,50,-25.98796542,14.99960455,0,0,0,150 +92.1,50.41614462,-3.582607836,50,-25.97753683,15.00027162,0,0,0,150 +92.11,50.41614228,-3.582605726,50,-25.97406063,15.00027236,0,0,0,150 +92.12,50.41613995,-3.582603615,50,-25.97406063,14.99960676,0,0,0,150 +92.13,50.41613761,-3.582601505,50,-25.97406064,14.99916328,0,0,0,150 +92.14,50.41613528,-3.582599395,50,-25.97406062,14.99960824,0,0,0,150 +92.15,50.41613294,-3.582597284,50,-25.97753678,15.00027531,0,0,0,150 +92.16,50.41613061,-3.582595174,50,-25.98796532,15.00027605,0,0,0,150 +92.17,50.41612827,-3.582593063,50,-25.9949177,14.99961045,0,0,0,150 +92.18,50.41612593,-3.582590953,50,-25.98796532,14.99916697,0,0,0,150 +92.19,50.4161236,-3.582588843,50,-25.97753674,14.99961193,0,0,0,150 +92.2,50.41612126,-3.582586732,50,-25.97406054,15.000279,0,0,0,150 +92.21,50.41611893,-3.582584622,50,-25.97406054,15.00027974,0,0,0,150 +92.22,50.41611659,-3.582582511,50,-25.97406054,14.99961414,0,0,0,150 +92.23,50.41611426,-3.582580401,50,-25.97406053,14.99917065,0,0,0,150 +92.24,50.41611192,-3.582578291,50,-25.97753669,14.99961561,0,0,0,150 +92.25,50.41610959,-3.58257618,50,-25.98796523,15.00028268,0,0,0,150 +92.26,50.41610725,-3.58257407,50,-25.99491759,15.00050553,0,0,0,150 +92.27,50.41610491,-3.582571959,50,-25.98796522,15.00050627,0,0,0,150 +92.28,50.41610258,-3.582569849,50,-25.97753666,15.00050701,0,0,0,150 +92.29,50.41610024,-3.582567738,50,-25.97406045,15.00050775,0,0,0,150 +92.3,50.41609791,-3.582565628,50,-25.97406043,15.00050848,0,0,0,150 +92.31,50.41609557,-3.582563517,50,-25.97753661,15.00050922,0,0,0,150 +92.32,50.41609324,-3.582561407,50,-25.98796518,15.00050996,0,0,0,150 +92.33,50.4160909,-3.582559296,50,-25.99491754,15.0005107,0,0,0,150 +92.34,50.41608856,-3.582557186,50,-25.98796515,15.00028932,0,0,0,150 +92.35,50.41608623,-3.582555075,50,-25.97753656,14.99962373,0,0,0,150 +92.36,50.41608389,-3.582552965,50,-25.97406037,14.99918024,0,0,0,150 +92.37,50.41608156,-3.582550855,50,-25.97406038,14.9996252,0,0,0,150 +92.38,50.41607922,-3.582548744,50,-25.97406038,15.00029227,0,0,0,150 +92.39,50.41607689,-3.582546634,50,-25.97406036,15.00029301,0,0,0,150 +92.4,50.41607455,-3.582544523,50,-25.97753652,14.99962741,0,0,0,150 +92.41,50.41607222,-3.582542413,50,-25.98796506,14.99918393,0,0,0,150 +92.42,50.41606988,-3.582540303,50,-25.99491742,14.99940678,0,0,0,150 +92.43,50.41606754,-3.582538192,50,-25.98796505,14.99940752,0,0,0,150 +92.44,50.41606521,-3.582536082,50,-25.97753649,14.99918614,0,0,0,150 +92.45,50.41606287,-3.582533972,50,-25.97406029,14.9996311,0,0,0,150 +92.46,50.41606054,-3.582531861,50,-25.97406027,15.00029817,0,0,0,150 +92.47,50.4160582,-3.582529751,50,-25.97406026,15.00052102,0,0,0,150 +92.48,50.41605587,-3.58252764,50,-25.97406025,15.00052176,0,0,0,150 +92.49,50.41605353,-3.58252553,50,-25.97753644,15.00030039,0,0,0,150 +92.5,50.4160512,-3.582523419,50,-25.98796498,14.99963479,0,0,0,150 +92.51,50.41604886,-3.582521309,50,-25.99491733,14.9991913,0,0,0,150 +92.52,50.41604652,-3.582519199,50,-25.98796495,14.99963627,0,0,0,150 +92.53,50.41604419,-3.582517088,50,-25.9775364,15.00030334,0,0,0,150 +92.54,50.41604185,-3.582514978,50,-25.97406021,15.00052618,0,0,0,150 +92.55,50.41603952,-3.582512867,50,-25.97406018,15.00052692,0,0,0,150 +92.56,50.41603718,-3.582510757,50,-25.97753634,15.00052766,0,0,0,150 +92.57,50.41603485,-3.582508646,50,-25.9879649,15.0005284,0,0,0,150 +92.58,50.41603251,-3.582506536,50,-25.99491727,15.00052914,0,0,0,150 +92.59,50.41603017,-3.582504425,50,-25.98796489,15.00052987,0,0,0,150 +92.6,50.41602784,-3.582502315,50,-25.97753631,15.0003085,0,0,0,150 +92.61,50.4160255,-3.582500204,50,-25.9740601,14.9996429,0,0,0,150 +92.62,50.41602317,-3.582498094,50,-25.97406011,14.99919942,0,0,0,150 +92.63,50.41602083,-3.582495984,50,-25.97406011,14.99964438,0,0,0,150 +92.64,50.4160185,-3.582493873,50,-25.97406009,15.00031145,0,0,0,150 +92.65,50.41601616,-3.582491763,50,-25.97753626,15.00031219,0,0,0,150 +92.66,50.41601383,-3.582489652,50,-25.9879648,14.99964659,0,0,0,150 +92.67,50.41601149,-3.582487542,50,-25.99491716,14.9992031,0,0,0,150 +92.68,50.41600915,-3.582485432,50,-25.98796479,14.99964806,0,0,0,150 +92.69,50.41600682,-3.582483321,50,-25.97753624,15.00031514,0,0,0,150 +92.7,50.41600448,-3.582481211,50,-25.97406003,15.00031587,0,0,0,150 +92.71,50.41600215,-3.5824791,50,-25.97406,14.99965028,0,0,0,150 +92.72,50.41599981,-3.58247699,50,-25.97405999,14.99920679,0,0,0,150 +92.73,50.41599748,-3.58247488,50,-25.97405999,14.99965175,0,0,0,150 +92.74,50.41599514,-3.582472769,50,-25.97753618,15.00031882,0,0,0,150 +92.75,50.41599281,-3.582470659,50,-25.98796472,15.00054167,0,0,0,150 +92.76,50.41599047,-3.582468548,50,-25.99491707,15.00054241,0,0,0,150 +92.77,50.41598813,-3.582466438,50,-25.98796468,15.00032104,0,0,0,150 +92.78,50.4159858,-3.582464327,50,-25.97753613,14.99965544,0,0,0,150 +92.79,50.41598346,-3.582462217,50,-25.97405994,14.99921195,0,0,0,150 +92.8,50.41598113,-3.582460107,50,-25.97405992,14.99965691,0,0,0,150 +92.81,50.41597879,-3.582457996,50,-25.97753609,15.00032399,0,0,0,150 +92.82,50.41597646,-3.582455886,50,-25.98796464,15.00054684,0,0,0,150 +92.83,50.41597412,-3.582453775,50,-25.99491701,15.00054758,0,0,0,150 +92.84,50.41597178,-3.582451665,50,-25.98796463,15.00054831,0,0,0,150 +92.85,50.41596945,-3.582449554,50,-25.97753605,15.00054905,0,0,0,150 +92.86,50.41596711,-3.582447444,50,-25.97405985,15.00032768,0,0,0,150 +92.87,50.41596478,-3.582445333,50,-25.97405983,14.99966208,0,0,0,150 +92.88,50.41596244,-3.582443223,50,-25.97405983,14.99921859,0,0,0,150 +92.89,50.41596011,-3.582441113,50,-25.97405983,14.99966355,0,0,0,150 +92.9,50.41595777,-3.582439002,50,-25.97753601,15.00033062,0,0,0,150 +92.91,50.41595544,-3.582436892,50,-25.98796455,15.00033136,0,0,0,150 +92.92,50.4159531,-3.582434781,50,-25.9949169,14.99966577,0,0,0,150 +92.93,50.41595076,-3.582432671,50,-25.98796452,14.99922228,0,0,0,150 +92.94,50.41594843,-3.582430561,50,-25.97753596,14.99966724,0,0,0,150 +92.95,50.41594609,-3.58242845,50,-25.97405976,15.00033431,0,0,0,150 +92.96,50.41594376,-3.58242634,50,-25.97405974,15.00033505,0,0,0,150 +92.97,50.41594142,-3.582424229,50,-25.97753592,14.99966945,0,0,0,150 +92.98,50.41593909,-3.582422119,50,-25.98796448,14.99922597,0,0,0,150 +92.99,50.41593675,-3.582420009,50,-25.99491685,14.99967093,0,0,0,150 +93,50.41593441,-3.582417898,50,-25.98796446,15.000338,0,0,0,150 +93.01,50.41593208,-3.582415788,50,-25.97753587,15.00056085,0,0,0,150 +93.02,50.41592974,-3.582413677,50,-25.97405968,15.00056159,0,0,0,150 +93.03,50.41592741,-3.582411567,50,-25.97405968,15.00056232,0,0,0,150 +93.04,50.41592507,-3.582409456,50,-25.97405967,15.00056306,0,0,0,150 +93.05,50.41592274,-3.582407346,50,-25.97405967,15.00034169,0,0,0,150 +93.06,50.4159204,-3.582405235,50,-25.97753584,14.99967609,0,0,0,150 +93.07,50.41591807,-3.582403125,50,-25.98796438,14.9992326,0,0,0,150 +93.08,50.41591573,-3.582401015,50,-25.99491673,14.99967757,0,0,0,150 +93.09,50.41591339,-3.582398904,50,-25.98796435,15.00034464,0,0,0,150 +93.1,50.41591106,-3.582396794,50,-25.97753579,15.00056749,0,0,0,150 +93.11,50.41590872,-3.582394683,50,-25.97405958,15.00056823,0,0,0,150 +93.12,50.41590639,-3.582392573,50,-25.97405957,15.00034685,0,0,0,150 +93.13,50.41590405,-3.582390462,50,-25.97405958,14.99968125,0,0,0,150 +93.14,50.41590172,-3.582388352,50,-25.97405958,14.99923777,0,0,0,150 +93.15,50.41589938,-3.582386242,50,-25.97753575,14.99946062,0,0,0,150 +93.16,50.41589705,-3.582384131,50,-25.98796428,14.99946135,0,0,0,150 +93.17,50.41589471,-3.582382021,50,-25.99491663,14.99923998,0,0,0,150 +93.18,50.41589237,-3.582379911,50,-25.98796427,14.99968494,0,0,0,150 +93.19,50.41589004,-3.5823778,50,-25.97753571,15.00035201,0,0,0,150 +93.2,50.4158877,-3.58237569,50,-25.97405951,15.00035275,0,0,0,150 +93.21,50.41588537,-3.582373579,50,-25.97405948,14.99968715,0,0,0,150 +93.22,50.41588303,-3.582371469,50,-25.97753565,14.99924367,0,0,0,150 +93.23,50.4158807,-3.582369359,50,-25.98796421,14.99968863,0,0,0,150 +93.24,50.41587836,-3.582367248,50,-25.99491658,15.0003557,0,0,0,150 +93.25,50.41587602,-3.582365138,50,-25.98796419,15.00057855,0,0,0,150 +93.26,50.41587369,-3.582363027,50,-25.97753561,15.00057929,0,0,0,150 +93.27,50.41587135,-3.582360917,50,-25.97405942,15.00058003,0,0,0,150 +93.28,50.41586902,-3.582358806,50,-25.97405941,15.00058076,0,0,0,150 +93.29,50.41586668,-3.582356696,50,-25.97405942,15.0005815,0,0,0,150 +93.3,50.41586435,-3.582354585,50,-25.97405941,15.00058224,0,0,0,150 +93.31,50.41586201,-3.582352475,50,-25.97753558,15.00036087,0,0,0,150 +93.32,50.41585968,-3.582350364,50,-25.98796411,14.99969527,0,0,0,150 +93.33,50.41585734,-3.582348254,50,-25.99491647,14.99925178,0,0,0,150 +93.34,50.415855,-3.582346144,50,-25.9879641,14.99969674,0,0,0,150 +93.35,50.41585267,-3.582344033,50,-25.97753554,15.00036382,0,0,0,150 +93.36,50.41585033,-3.582341923,50,-25.97405934,15.00036455,0,0,0,150 +93.37,50.415848,-3.582339812,50,-25.97405931,14.99969895,0,0,0,150 +93.38,50.41584566,-3.582337702,50,-25.9740593,14.99925546,0,0,0,150 +93.39,50.41584333,-3.582335592,50,-25.9740593,14.99947832,0,0,0,150 +93.4,50.41584099,-3.582333481,50,-25.97753548,14.99947905,0,0,0,150 +93.41,50.41583866,-3.582331371,50,-25.98796402,14.99925768,0,0,0,150 +93.42,50.41583632,-3.582329261,50,-25.99491638,14.99970264,0,0,0,150 +93.43,50.41583398,-3.58232715,50,-25.987964,15.00036972,0,0,0,150 +93.44,50.41583165,-3.58232504,50,-25.97753544,15.00037045,0,0,0,150 +93.45,50.41582931,-3.582322929,50,-25.97405925,14.99970485,0,0,0,150 +93.46,50.41582698,-3.582320819,50,-25.97405922,14.99926137,0,0,0,150 +93.47,50.41582464,-3.582318709,50,-25.97753539,14.99970633,0,0,0,150 +93.48,50.41582231,-3.582316598,50,-25.98796394,15.0003734,0,0,0,150 +93.49,50.41581997,-3.582314488,50,-25.99491631,15.00059625,0,0,0,150 +93.5,50.41581763,-3.582312377,50,-25.98796394,15.00059699,0,0,0,150 +93.51,50.4158153,-3.582310267,50,-25.97753537,15.00059773,0,0,0,150 +93.52,50.41581296,-3.582308156,50,-25.97405916,15.00059847,0,0,0,150 +93.53,50.41581063,-3.582306046,50,-25.97405914,15.0005992,0,0,0,150 +93.54,50.41580829,-3.582303935,50,-25.97405914,15.00059994,0,0,0,150 +93.55,50.41580596,-3.582301825,50,-25.97405914,15.00037857,0,0,0,150 +93.56,50.41580362,-3.582299714,50,-25.97753531,14.99971297,0,0,0,150 +93.57,50.41580129,-3.582297604,50,-25.98796384,14.99926948,0,0,0,150 +93.58,50.41579895,-3.582295494,50,-25.99491621,14.99949233,0,0,0,150 +93.59,50.41579661,-3.582293383,50,-25.98796384,14.99949307,0,0,0,150 +93.6,50.41579428,-3.582291273,50,-25.97753528,14.99927169,0,0,0,150 +93.61,50.41579194,-3.582289163,50,-25.97405907,14.99971665,0,0,0,150 +93.62,50.41578961,-3.582287052,50,-25.97405905,15.00038373,0,0,0,150 +93.63,50.41578727,-3.582284942,50,-25.97405904,15.00038447,0,0,0,150 +93.64,50.41578494,-3.582282831,50,-25.97405904,14.99971886,0,0,0,150 +93.65,50.4157826,-3.582280721,50,-25.97753522,14.99927538,0,0,0,150 +93.66,50.41578027,-3.582278611,50,-25.98796376,14.99972034,0,0,0,150 +93.67,50.41577793,-3.5822765,50,-25.99491612,15.00038742,0,0,0,150 +93.68,50.41577559,-3.58227439,50,-25.98796374,15.00038815,0,0,0,150 +93.69,50.41577326,-3.582272279,50,-25.97753517,14.99972255,0,0,0,150 +93.7,50.41577092,-3.582270169,50,-25.97405898,14.99927907,0,0,0,150 +93.71,50.41576859,-3.582268059,50,-25.97405896,14.99972403,0,0,0,150 +93.72,50.41576625,-3.582265948,50,-25.97753513,15.0003911,0,0,0,150 +93.73,50.41576392,-3.582263838,50,-25.98796367,15.00061395,0,0,0,150 +93.74,50.41576158,-3.582261727,50,-25.99491605,15.00061469,0,0,0,150 +93.75,50.41575924,-3.582259617,50,-25.98796368,15.00061543,0,0,0,150 +93.76,50.41575691,-3.582257506,50,-25.97753511,15.00061617,0,0,0,150 +93.77,50.41575457,-3.582255396,50,-25.97405889,15.00039479,0,0,0,150 +93.78,50.41575224,-3.582253285,50,-25.97405888,14.99972919,0,0,0,150 +93.79,50.4157499,-3.582251175,50,-25.97405888,14.9992857,0,0,0,150 +93.8,50.41574757,-3.582249065,50,-25.97405889,14.99973067,0,0,0,150 +93.81,50.41574523,-3.582246954,50,-25.97753505,15.00039774,0,0,0,150 +93.82,50.4157429,-3.582244844,50,-25.98796358,15.00039848,0,0,0,150 +93.83,50.41574056,-3.582242733,50,-25.99491594,14.99973288,0,0,0,150 +93.84,50.41573822,-3.582240623,50,-25.98796357,14.99928939,0,0,0,150 +93.85,50.41573589,-3.582238513,50,-25.97753501,14.99951224,0,0,0,150 +93.86,50.41573355,-3.582236402,50,-25.97405881,14.99951298,0,0,0,150 +93.87,50.41573122,-3.582234292,50,-25.97405879,14.9992916,0,0,0,150 +93.88,50.41572888,-3.582232182,50,-25.97405878,14.99973656,0,0,0,150 +93.89,50.41572655,-3.582230071,50,-25.97405877,15.00040364,0,0,0,150 +93.9,50.41572421,-3.582227961,50,-25.97753496,15.00062649,0,0,0,150 +93.91,50.41572188,-3.58222585,50,-25.98796351,15.00062723,0,0,0,150 +93.92,50.41571954,-3.58222374,50,-25.99491586,15.00062797,0,0,0,150 +93.93,50.4157172,-3.582221629,50,-25.98796347,15.00062871,0,0,0,150 +93.94,50.41571487,-3.582219519,50,-25.97753491,15.00062944,0,0,0,150 +93.95,50.41571253,-3.582217408,50,-25.97405872,15.00063018,0,0,0,150 +93.96,50.4157102,-3.582215298,50,-25.97405872,15.0004088,0,0,0,150 +93.97,50.41570786,-3.582213187,50,-25.97753489,14.9997432,0,0,0,150 +93.98,50.41570553,-3.582211077,50,-25.98796342,14.99929971,0,0,0,150 +93.99,50.41570319,-3.582208967,50,-25.99491577,14.99952257,0,0,0,150 +94,50.41570085,-3.582206856,50,-25.9879634,14.9995233,0,0,0,150 +94.01,50.41569852,-3.582204746,50,-25.97753484,14.99930193,0,0,0,150 +94.02,50.41569618,-3.582202636,50,-25.97405864,14.99974689,0,0,0,150 +94.03,50.41569385,-3.582200525,50,-25.97405862,15.00041397,0,0,0,150 +94.04,50.41569151,-3.582198415,50,-25.97405862,15.00041471,0,0,0,150 +94.05,50.41568918,-3.582196304,50,-25.97405862,14.9997491,0,0,0,150 +94.06,50.41568684,-3.582194194,50,-25.97753479,14.99930561,0,0,0,150 +94.07,50.41568451,-3.582192084,50,-25.98796333,14.99952846,0,0,0,150 +94.08,50.41568217,-3.582189973,50,-25.99491568,14.9995292,0,0,0,150 +94.09,50.41567983,-3.582187863,50,-25.9879633,14.99930783,0,0,0,150 +94.1,50.4156775,-3.582185753,50,-25.97753474,14.99975279,0,0,0,150 +94.11,50.41567516,-3.582183642,50,-25.97405855,15.00041987,0,0,0,150 +94.12,50.41567283,-3.582181532,50,-25.97405854,15.00064272,0,0,0,150 +94.13,50.41567049,-3.582179421,50,-25.97753471,15.00064346,0,0,0,150 +94.14,50.41566816,-3.582177311,50,-25.98796325,15.00064419,0,0,0,150 +94.15,50.41566582,-3.5821752,50,-25.99491562,15.00064493,0,0,0,150 +94.16,50.41566348,-3.58217309,50,-25.98796324,15.00064567,0,0,0,150 +94.17,50.41566115,-3.582170979,50,-25.97753467,15.00064641,0,0,0,150 +94.18,50.41565881,-3.582168869,50,-25.97405846,15.00042503,0,0,0,150 +94.19,50.41565648,-3.582166758,50,-25.97405845,14.99975943,0,0,0,150 +94.2,50.41565414,-3.582164648,50,-25.97405846,14.99931594,0,0,0,150 +94.21,50.41565181,-3.582162538,50,-25.97405846,14.99953879,0,0,0,150 +94.22,50.41564947,-3.582160427,50,-25.97753462,14.99953953,0,0,0,150 +94.23,50.41564714,-3.582158317,50,-25.98796315,14.99931815,0,0,0,150 +94.24,50.4156448,-3.582156207,50,-25.99491551,14.999541,0,0,0,150 +94.25,50.41564246,-3.582154096,50,-25.98796314,14.99954174,0,0,0,150 +94.26,50.41564013,-3.582151986,50,-25.97753458,14.99932036,0,0,0,150 +94.27,50.41563779,-3.582149876,50,-25.97405838,14.99976533,0,0,0,150 +94.28,50.41563546,-3.582147765,50,-25.97405837,15.00043241,0,0,0,150 +94.29,50.41563312,-3.582145655,50,-25.97405835,15.00065526,0,0,0,150 +94.3,50.41563079,-3.582143544,50,-25.97405835,15.000656,0,0,0,150 +94.31,50.41562845,-3.582141434,50,-25.97753453,15.00043462,0,0,0,150 +94.32,50.41562612,-3.582139323,50,-25.98796307,14.99976902,0,0,0,150 +94.33,50.41562378,-3.582137213,50,-25.99491542,14.99932553,0,0,0,150 +94.34,50.41562144,-3.582135103,50,-25.98796303,14.99977049,0,0,0,150 +94.35,50.41561911,-3.582132992,50,-25.97753448,15.00043757,0,0,0,150 +94.36,50.41561677,-3.582130882,50,-25.9740583,15.00066042,0,0,0,150 +94.37,50.41561444,-3.582128771,50,-25.97405828,15.00066116,0,0,0,150 +94.38,50.4156121,-3.582126661,50,-25.97753444,15.00043978,0,0,0,150 +94.39,50.41560977,-3.58212455,50,-25.98796298,14.99977418,0,0,0,150 +94.4,50.41560743,-3.58212244,50,-25.99491536,14.99933069,0,0,0,150 +94.41,50.41560509,-3.58212033,50,-25.98796299,14.99955354,0,0,0,150 +94.42,50.41560276,-3.582118219,50,-25.97753442,14.99955428,0,0,0,150 +94.43,50.41560042,-3.582116109,50,-25.9740582,14.9993329,0,0,0,150 +94.44,50.41559809,-3.582113999,50,-25.97405819,14.99977787,0,0,0,150 +94.45,50.41559575,-3.582111888,50,-25.97405819,15.00044495,0,0,0,150 +94.46,50.41559342,-3.582109778,50,-25.97405819,15.00044568,0,0,0,150 +94.47,50.41559108,-3.582107667,50,-25.97753435,14.99978008,0,0,0,150 +94.48,50.41558875,-3.582105557,50,-25.98796289,14.99933659,0,0,0,150 +94.49,50.41558641,-3.582103447,50,-25.99491526,14.99978155,0,0,0,150 +94.5,50.41558407,-3.582101336,50,-25.98796289,15.00044863,0,0,0,150 +94.51,50.41558174,-3.582099226,50,-25.97753432,15.00067149,0,0,0,150 +94.52,50.4155794,-3.582097115,50,-25.97405811,15.00067222,0,0,0,150 +94.53,50.41557707,-3.582095005,50,-25.97405809,15.00067296,0,0,0,150 +94.54,50.41557473,-3.582092894,50,-25.97405808,15.0006737,0,0,0,150 +94.55,50.4155724,-3.582090784,50,-25.97405808,15.00045232,0,0,0,150 +94.56,50.41557006,-3.582088673,50,-25.97753427,14.99978672,0,0,0,150 +94.57,50.41556773,-3.582086563,50,-25.98796281,14.99934323,0,0,0,150 +94.58,50.41556539,-3.582084453,50,-25.99491515,14.99956608,0,0,0,150 +94.59,50.41556305,-3.582082342,50,-25.98796278,14.99956682,0,0,0,150 +94.6,50.41556072,-3.582080232,50,-25.97753423,14.99934544,0,0,0,150 +94.61,50.41555838,-3.582078122,50,-25.97405804,14.9997904,0,0,0,150 +94.62,50.41555605,-3.582076011,50,-25.97405802,15.00045748,0,0,0,150 +94.63,50.41555371,-3.582073901,50,-25.97753418,15.00045822,0,0,0,150 +94.64,50.41555138,-3.58207179,50,-25.98796272,14.99979262,0,0,0,150 +94.65,50.41554904,-3.58206968,50,-25.99491509,14.99934913,0,0,0,150 +94.66,50.4155467,-3.58206757,50,-25.98796272,14.99957198,0,0,0,150 +94.67,50.41554437,-3.582065459,50,-25.97753415,14.99957272,0,0,0,150 +94.68,50.41554203,-3.582063349,50,-25.97405795,14.99935134,0,0,0,150 +94.69,50.4155397,-3.582061239,50,-25.97405793,14.9997963,0,0,0,150 +94.7,50.41553736,-3.582059128,50,-25.97405792,15.00046338,0,0,0,150 +94.71,50.41553503,-3.582057018,50,-25.97405791,15.00068624,0,0,0,150 +94.72,50.41553269,-3.582054907,50,-25.97753409,15.00068697,0,0,0,150 +94.73,50.41553036,-3.582052797,50,-25.98796264,15.00068771,0,0,0,150 +94.74,50.41552802,-3.582050686,50,-25.994915,15.00068845,0,0,0,150 +94.75,50.41552568,-3.582048576,50,-25.98796262,15.00046707,0,0,0,150 +94.76,50.41552335,-3.582046465,50,-25.97753405,14.99980147,0,0,0,150 +94.77,50.41552101,-3.582044355,50,-25.97405785,14.99935798,0,0,0,150 +94.78,50.41551868,-3.582042245,50,-25.97405783,14.99958083,0,0,0,150 +94.79,50.41551634,-3.582040134,50,-25.97405782,14.99958156,0,0,0,150 +94.8,50.41551401,-3.582038024,50,-25.97405782,14.99936019,0,0,0,150 +94.81,50.41551167,-3.582035914,50,-25.97753401,14.99958304,0,0,0,150 +94.82,50.41550934,-3.582033803,50,-25.98796255,14.99958378,0,0,0,150 +94.83,50.415507,-3.582031693,50,-25.9949149,14.9993624,0,0,0,150 +94.84,50.41550466,-3.582029583,50,-25.98796251,14.99980737,0,0,0,150 +94.85,50.41550233,-3.582027472,50,-25.97753396,15.00047445,0,0,0,150 +94.86,50.41549999,-3.582025362,50,-25.97405777,15.0006973,0,0,0,150 +94.87,50.41549766,-3.582023251,50,-25.97405776,15.00069804,0,0,0,150 +94.88,50.41549532,-3.582021141,50,-25.97753393,15.00069877,0,0,0,150 +94.89,50.41549299,-3.58201903,50,-25.98796247,15.00069951,0,0,0,150 +94.9,50.41549065,-3.58201692,50,-25.99491483,15.00070025,0,0,0,150 +94.91,50.41548831,-3.582014809,50,-25.98796245,15.00070099,0,0,0,150 +94.92,50.41548598,-3.582012699,50,-25.97753389,15.00047961,0,0,0,150 +94.93,50.41548364,-3.582010588,50,-25.97405769,14.999814,0,0,0,150 +94.94,50.41548131,-3.582008478,50,-25.97405766,14.99937051,0,0,0,150 +94.95,50.41547897,-3.582006368,50,-25.97405765,14.99959337,0,0,0,150 +94.96,50.41547664,-3.582004257,50,-25.97405766,14.9995941,0,0,0,150 +94.97,50.4154743,-3.582002147,50,-25.97753385,14.99937273,0,0,0,150 +94.98,50.41547197,-3.582000037,50,-25.98796239,14.99959558,0,0,0,150 +94.99,50.41546963,-3.581997926,50,-25.99491473,14.99959631,0,0,0,150 +95,50.41546729,-3.581995816,50,-25.98796234,14.99937494,0,0,0,150 +95.01,50.41546496,-3.581993706,50,-25.97753379,14.99959779,0,0,0,150 +95.02,50.41546262,-3.581991595,50,-25.97405761,14.99959853,0,0,0,150 +95.03,50.41546029,-3.581989485,50,-25.97405759,14.99937715,0,0,0,150 +95.04,50.41545795,-3.581987375,50,-25.97405756,14.99982212,0,0,0,150 +95.05,50.41545562,-3.581985264,50,-25.97405755,15.0004892,0,0,0,150 +95.06,50.41545328,-3.581983154,50,-25.97753374,15.00071205,0,0,0,150 +95.07,50.41545095,-3.581981043,50,-25.98796229,15.00071279,0,0,0,150 +95.08,50.41544861,-3.581978933,50,-25.99491464,15.00071352,0,0,0,150 +95.09,50.41544627,-3.581976822,50,-25.98796225,15.00071426,0,0,0,150 +95.1,50.41544394,-3.581974712,50,-25.97753369,15.00049289,0,0,0,150 +95.11,50.4154416,-3.581972601,50,-25.97405751,14.99982728,0,0,0,150 +95.12,50.41543927,-3.581970491,50,-25.9740575,14.99938379,0,0,0,150 +95.13,50.41543693,-3.581968381,50,-25.97753366,14.99960664,0,0,0,150 +95.14,50.4154346,-3.58196627,50,-25.9879622,14.99960738,0,0,0,150 +95.15,50.41543226,-3.58196416,50,-25.99491456,14.999386,0,0,0,150 +95.16,50.41542992,-3.58196205,50,-25.98796219,14.99960885,0,0,0,150 +95.17,50.41542759,-3.581959939,50,-25.97753363,14.99960959,0,0,0,150 +95.18,50.41542525,-3.581957829,50,-25.97405742,14.99938821,0,0,0,150 +95.19,50.41542292,-3.581955719,50,-25.9740574,14.99983318,0,0,0,150 +95.2,50.41542058,-3.581953608,50,-25.97405739,15.00050026,0,0,0,150 +95.21,50.41541825,-3.581951498,50,-25.9740574,15.00072311,0,0,0,150 +95.22,50.41541591,-3.581949387,50,-25.97753358,15.00072385,0,0,0,150 +95.23,50.41541358,-3.581947277,50,-25.98796212,15.00072459,0,0,0,150 +95.24,50.41541124,-3.581945166,50,-25.99491446,15.00072532,0,0,0,150 +95.25,50.4154089,-3.581943056,50,-25.98796208,15.00072606,0,0,0,150 +95.26,50.41540657,-3.581940945,50,-25.97753353,15.0007268,0,0,0,150 +95.27,50.41540423,-3.581938835,50,-25.97405734,15.00050542,0,0,0,150 +95.28,50.4154019,-3.581936724,50,-25.97405732,14.99983982,0,0,0,150 +95.29,50.41539956,-3.581934614,50,-25.97753348,14.99939633,0,0,0,150 +95.3,50.41539723,-3.581932504,50,-25.98796203,14.99961918,0,0,0,150 +95.31,50.41539489,-3.581930393,50,-25.9949144,14.99961992,0,0,0,150 +95.32,50.41539255,-3.581928283,50,-25.98796202,14.99939854,0,0,0,150 +95.33,50.41539022,-3.581926173,50,-25.97753345,14.99962139,0,0,0,150 +95.34,50.41538788,-3.581924062,50,-25.97405725,14.99962213,0,0,0,150 +95.35,50.41538555,-3.581921952,50,-25.97405724,14.99940075,0,0,0,150 +95.36,50.41538321,-3.581919842,50,-25.97405724,14.9996236,0,0,0,150 +95.37,50.41538088,-3.581917731,50,-25.97405723,14.99962434,0,0,0,150 +95.38,50.41537854,-3.581915621,50,-25.9775334,14.99940296,0,0,0,150 +95.39,50.41537621,-3.581913511,50,-25.98796194,14.99984793,0,0,0,150 +95.4,50.41537387,-3.5819114,50,-25.99491429,15.00051501,0,0,0,150 +95.41,50.41537153,-3.58190929,50,-25.98796193,15.00073787,0,0,0,150 +95.42,50.4153692,-3.581907179,50,-25.97753337,15.0007386,0,0,0,150 +95.43,50.41536686,-3.581905069,50,-25.97405717,15.00073934,0,0,0,150 +95.44,50.41536453,-3.581902958,50,-25.97405714,15.00074008,0,0,0,150 +95.45,50.41536219,-3.581900848,50,-25.97405713,15.0005187,0,0,0,150 +95.46,50.41535986,-3.581898737,50,-25.97405713,14.99985309,0,0,0,150 +95.47,50.41535752,-3.581896627,50,-25.97753331,14.9994096,0,0,0,150 +95.48,50.41535519,-3.581894517,50,-25.98796185,14.99963245,0,0,0,150 +95.49,50.41535285,-3.581892406,50,-25.9949142,14.99963319,0,0,0,150 +95.5,50.41535051,-3.581890296,50,-25.98796183,14.99941181,0,0,0,150 +95.51,50.41534818,-3.581888186,50,-25.97753327,14.99963467,0,0,0,150 +95.52,50.41534584,-3.581886075,50,-25.97405708,14.9996354,0,0,0,150 +95.53,50.41534351,-3.581883965,50,-25.97405706,14.99941402,0,0,0,150 +95.54,50.41534117,-3.581881855,50,-25.97753323,14.99985899,0,0,0,150 +95.55,50.41533884,-3.581879744,50,-25.98796177,15.00052607,0,0,0,150 +95.56,50.4153365,-3.581877634,50,-25.99491413,15.00074893,0,0,0,150 +95.57,50.41533416,-3.581875523,50,-25.98796176,15.00074966,0,0,0,150 +95.58,50.41533183,-3.581873413,50,-25.97753321,15.0007504,0,0,0,150 +95.59,50.41532949,-3.581871302,50,-25.974057,15.00075114,0,0,0,150 +95.6,50.41532716,-3.581869192,50,-25.97405697,15.00052976,0,0,0,150 +95.61,50.41532482,-3.581867081,50,-25.97405696,14.99986416,0,0,0,150 +95.62,50.41532249,-3.581864971,50,-25.97405696,14.99942066,0,0,0,150 +95.63,50.41532015,-3.581862861,50,-25.97753315,14.99964351,0,0,0,150 +95.64,50.41531782,-3.58186075,50,-25.98796169,14.99964425,0,0,0,150 +95.65,50.41531548,-3.58185864,50,-25.99491404,14.99942288,0,0,0,150 +95.66,50.41531314,-3.58185653,50,-25.98796165,14.99964573,0,0,0,150 +95.67,50.41531081,-3.581854419,50,-25.9775331,14.99964647,0,0,0,150 +95.68,50.41530847,-3.581852309,50,-25.97405691,14.99942509,0,0,0,150 +95.69,50.41530614,-3.581850199,50,-25.97405689,14.99987005,0,0,0,150 +95.7,50.4153038,-3.581848088,50,-25.97405687,15.00053714,0,0,0,150 +95.71,50.41530147,-3.581845978,50,-25.97405687,15.00053788,0,0,0,150 +95.72,50.41529913,-3.581843867,50,-25.97753305,14.99987227,0,0,0,150 +95.73,50.4152968,-3.581841757,50,-25.9879616,14.99942877,0,0,0,150 +95.74,50.41529446,-3.581839647,50,-25.99491395,14.99987374,0,0,0,150 +95.75,50.41529212,-3.581837536,50,-25.98796156,15.00054082,0,0,0,150 +95.76,50.41528979,-3.581835426,50,-25.97753299,15.00076368,0,0,0,150 +95.77,50.41528745,-3.581833315,50,-25.9740568,15.00076441,0,0,0,150 +95.78,50.41528512,-3.581831205,50,-25.9740568,15.00054304,0,0,0,150 +95.79,50.41528278,-3.581829094,50,-25.97753297,14.99987743,0,0,0,150 +95.8,50.41528045,-3.581826984,50,-25.9879615,14.99943394,0,0,0,150 +95.81,50.41527811,-3.581824874,50,-25.99491387,14.99965679,0,0,0,150 +95.82,50.41527577,-3.581822763,50,-25.9879615,14.99965753,0,0,0,150 +95.83,50.41527344,-3.581820653,50,-25.97753294,14.99943615,0,0,0,150 +95.84,50.4152711,-3.581818543,50,-25.97405673,14.999659,0,0,0,150 +95.85,50.41526877,-3.581816432,50,-25.97405671,14.99965974,0,0,0,150 +95.86,50.41526643,-3.581814322,50,-25.9740567,14.99943836,0,0,0,150 +95.87,50.4152641,-3.581812212,50,-25.97405671,14.99988333,0,0,0,150 +95.88,50.41526176,-3.581810101,50,-25.97753289,15.00055041,0,0,0,150 +95.89,50.41525943,-3.581807991,50,-25.98796142,15.00077327,0,0,0,150 +95.9,50.41525709,-3.58180588,50,-25.99491377,15.000774,0,0,0,150 +95.91,50.41525475,-3.58180377,50,-25.98796139,15.00077474,0,0,0,150 +95.92,50.41525242,-3.581801659,50,-25.97753283,15.00077548,0,0,0,150 +95.93,50.41525008,-3.581799549,50,-25.97405664,15.0005541,0,0,0,150 +95.94,50.41524775,-3.581797438,50,-25.97405663,14.99966638,0,0,0,150 +95.95,50.41524541,-3.581795328,50,-25.97405661,14.99855654,0,0,0,150 +95.96,50.41524308,-3.581793218,50,-25.9740566,14.99855728,0,0,0,150 +95.97,50.41524074,-3.581791108,50,-25.97753278,14.99944647,0,0,0,150 +95.98,50.41523841,-3.581788997,50,-25.98796133,14.99966933,0,0,0,150 +95.99,50.41523607,-3.581786887,50,-25.99491369,14.99944795,0,0,0,150 +96,50.41523373,-3.581784777,50,-25.9879613,14.99989292,0,0,0,150 +96.01,50.4152314,-3.581782666,50,-25.97753273,15.00056,0,0,0,150 +96.02,50.41522906,-3.581780556,50,-25.97405655,15.00078286,0,0,0,150 +96.03,50.41522673,-3.581778445,50,-25.97405655,15.00078359,0,0,0,150 +96.04,50.41522439,-3.581776335,50,-25.97753272,15.00078433,0,0,0,150 +96.05,50.41522206,-3.581774224,50,-25.98796125,15.00078507,0,0,0,150 +96.06,50.41521972,-3.581772114,50,-25.9949136,15.00056369,0,0,0,150 +96.07,50.41521738,-3.581770003,50,-25.98796124,14.99989808,0,0,0,150 +96.08,50.41521505,-3.581767893,50,-25.97753268,14.99945459,0,0,0,150 +96.09,50.41521271,-3.581765783,50,-25.97405648,14.99967744,0,0,0,150 +96.1,50.41521038,-3.581763672,50,-25.97405645,14.99967818,0,0,0,150 +96.11,50.41520804,-3.581761562,50,-25.97405644,14.9994568,0,0,0,150 +96.12,50.41520571,-3.581759452,50,-25.97405644,14.99967965,0,0,0,150 +96.13,50.41520337,-3.581757341,50,-25.97753262,14.99968039,0,0,0,150 +96.14,50.41520104,-3.581755231,50,-25.98796116,14.99945901,0,0,0,150 +96.15,50.4151987,-3.581753121,50,-25.99491351,14.99968186,0,0,0,150 +96.16,50.41519636,-3.58175101,50,-25.98796113,14.9996826,0,0,0,150 +96.17,50.41519403,-3.5817489,50,-25.97753257,14.99946122,0,0,0,150 +96.18,50.41519169,-3.58174679,50,-25.97405639,14.99990619,0,0,0,150 +96.19,50.41518936,-3.581744679,50,-25.97405638,15.00057328,0,0,0,150 +96.2,50.41518702,-3.581742569,50,-25.97405636,15.00079613,0,0,0,150 +96.21,50.41518469,-3.581740458,50,-25.97405633,15.00079687,0,0,0,150 +96.22,50.41518235,-3.581738348,50,-25.97753251,15.0007976,0,0,0,150 +96.23,50.41518002,-3.581736237,50,-25.98796107,15.00079834,0,0,0,150 +96.24,50.41517768,-3.581734127,50,-25.99491344,15.00057696,0,0,0,150 +96.25,50.41517534,-3.581732016,50,-25.98796105,14.99991135,0,0,0,150 +96.26,50.41517301,-3.581729906,50,-25.97753247,14.99946786,0,0,0,150 +96.27,50.41517067,-3.581727796,50,-25.97405627,14.99969072,0,0,0,150 +96.28,50.41516834,-3.581725685,50,-25.97405627,14.99946934,0,0,0,150 +96.29,50.415166,-3.581723575,50,-25.97405627,14.99858161,0,0,0,150 +96.3,50.41516367,-3.581721465,50,-25.97405625,14.99858235,0,0,0,150 +96.31,50.41516133,-3.581719355,50,-25.97753242,14.99969366,0,0,0,150 +96.32,50.415159,-3.581717244,50,-25.98796097,15.00058286,0,0,0,150 +96.33,50.41515666,-3.581715134,50,-25.99491334,15.00080572,0,0,0,150 +96.34,50.41515432,-3.581713023,50,-25.98796096,15.00080646,0,0,0,150 +96.35,50.41515199,-3.581710913,50,-25.97753238,15.00080719,0,0,0,150 +96.36,50.41514965,-3.581708802,50,-25.97405618,15.00080793,0,0,0,150 +96.37,50.41514732,-3.581706692,50,-25.97405617,15.00058655,0,0,0,150 +96.38,50.41514498,-3.581704581,50,-25.97753235,14.99992094,0,0,0,150 +96.39,50.41514265,-3.581702471,50,-25.9879609,14.99947745,0,0,0,150 +96.4,50.41514031,-3.581700361,50,-25.99491325,14.9997003,0,0,0,150 +96.41,50.41513797,-3.58169825,50,-25.98796086,14.99970104,0,0,0,150 +96.42,50.41513564,-3.58169614,50,-25.97753231,14.99947966,0,0,0,150 +96.43,50.4151333,-3.58169403,50,-25.97405613,14.99970252,0,0,0,150 +96.44,50.41513097,-3.581691919,50,-25.97405612,14.99970325,0,0,0,150 +96.45,50.41512863,-3.581689809,50,-25.97405609,14.99948187,0,0,0,150 +96.46,50.4151263,-3.581687699,50,-25.97405607,14.99992684,0,0,0,150 +96.47,50.41512396,-3.581685588,50,-25.97753225,15.00059393,0,0,0,150 +96.48,50.41512163,-3.581683478,50,-25.98796081,15.00059467,0,0,0,150 +96.49,50.41511929,-3.581681367,50,-25.99491318,14.99992905,0,0,0,150 +96.5,50.41511695,-3.581679257,50,-25.98796078,14.99948556,0,0,0,150 +96.51,50.41511462,-3.581677147,50,-25.9775322,14.99993053,0,0,0,150 +96.52,50.41511228,-3.581675036,50,-25.97405601,15.00059762,0,0,0,150 +96.53,50.41510995,-3.581672926,50,-25.97405601,15.00059835,0,0,0,150 +96.54,50.41510761,-3.581670815,50,-25.97753219,14.99993274,0,0,0,150 +96.55,50.41510528,-3.581668705,50,-25.98796073,14.99948925,0,0,0,150 +96.56,50.41510294,-3.581666595,50,-25.99491309,14.9997121,0,0,0,150 +96.57,50.4151006,-3.581664484,50,-25.98796071,14.99971284,0,0,0,150 +96.58,50.41509827,-3.581662374,50,-25.97753214,14.99949146,0,0,0,150 +96.59,50.41509593,-3.581660264,50,-25.97405595,14.99971431,0,0,0,150 +96.6,50.4150936,-3.581658153,50,-25.97405593,14.99971505,0,0,0,150 +96.61,50.41509126,-3.581656043,50,-25.97405591,14.99949367,0,0,0,150 +96.62,50.41508893,-3.581653933,50,-25.9740559,14.99993864,0,0,0,150 +96.63,50.41508659,-3.581651822,50,-25.97753209,15.00060573,0,0,0,150 +96.64,50.41508426,-3.581649712,50,-25.98796065,15.00082858,0,0,0,150 +96.65,50.41508192,-3.581647601,50,-25.994913,15.00082932,0,0,0,150 +96.66,50.41507958,-3.581645491,50,-25.98796061,15.00060794,0,0,0,150 +96.67,50.41507725,-3.58164338,50,-25.97753203,14.99994233,0,0,0,150 +96.68,50.41507491,-3.58164127,50,-25.97405585,14.99949884,0,0,0,150 +96.69,50.41507258,-3.58163916,50,-25.97405586,14.99972169,0,0,0,150 +96.7,50.41507024,-3.581637049,50,-25.97753202,14.99972243,0,0,0,150 +96.71,50.41506791,-3.581634939,50,-25.98796055,14.99950105,0,0,0,150 +96.72,50.41506557,-3.581632829,50,-25.99491291,14.9997239,0,0,0,150 +96.73,50.41506323,-3.581630718,50,-25.98796054,14.99972464,0,0,0,150 +96.74,50.4150609,-3.581628608,50,-25.97753198,14.99950326,0,0,0,150 +96.75,50.41505856,-3.581626498,50,-25.97405578,14.99994823,0,0,0,150 +96.76,50.41505623,-3.581624387,50,-25.97405576,15.00061532,0,0,0,150 +96.77,50.41505389,-3.581622277,50,-25.97405575,15.00083817,0,0,0,150 +96.78,50.41505156,-3.581620166,50,-25.97405574,15.00083891,0,0,0,150 +96.79,50.41504922,-3.581618056,50,-25.97753193,15.00083964,0,0,0,150 +96.8,50.41504689,-3.581615945,50,-25.98796048,15.00084038,0,0,0,150 +96.81,50.41504455,-3.581613835,50,-25.99491283,15.000619,0,0,0,150 +96.82,50.41504221,-3.581611724,50,-25.98796044,14.99973128,0,0,0,150 +96.83,50.41503988,-3.581609614,50,-25.97753188,14.99862143,0,0,0,150 +96.84,50.41503754,-3.581607504,50,-25.97405569,14.99862217,0,0,0,150 +96.85,50.41503521,-3.581605394,50,-25.97405569,14.99951137,0,0,0,150 +96.86,50.41503287,-3.581603283,50,-25.97405567,14.99973423,0,0,0,150 +96.87,50.41503054,-3.581601173,50,-25.97405564,14.99951285,0,0,0,150 +96.88,50.4150282,-3.581599063,50,-25.97753181,14.99995782,0,0,0,150 +96.89,50.41502587,-3.581596952,50,-25.98796037,15.0006249,0,0,0,150 +96.9,50.41502353,-3.581594842,50,-25.99491273,15.00062564,0,0,0,150 +96.91,50.41502119,-3.581592731,50,-25.98796034,14.99996003,0,0,0,150 +96.92,50.41501886,-3.581590621,50,-25.97753178,14.99951654,0,0,0,150 +96.93,50.41501652,-3.581588511,50,-25.9740556,14.99973939,0,0,0,150 +96.94,50.41501419,-3.5815864,50,-25.97405559,14.99907378,0,0,0,150 +96.95,50.41501185,-3.58158429,50,-25.97753176,14.99507642,0,0,0,150.0023855 +96.96,50.41500952,-3.58158218,50,-25.99143647,14.98552615,0,0,0,150.019084 +96.97,50.41500718,-3.581580072,50,-26.01229358,14.96909027,0,0,0,150.0596374 +96.98,50.41500484,-3.581577967,50,-26.02619832,14.94710149,0,0,0,150.1145038 +96.99,50.4150025,-3.581575866,50,-26.02967449,14.9224473,0,0,0,150.1717557 +97,50.41500016,-3.581573768,50,-26.03315066,14.89668253,0,0,0,150.2290077 +97.01,50.41499782,-3.581571674,50,-26.04705539,14.87025141,0,0,0,150.2862596 +97.02,50.41499548,-3.581569584,50,-26.0679125,14.84359817,0,0,0,150.3435115 +97.03,50.41499313,-3.581567497,50,-26.08529342,14.81716704,0,0,0,150.4007634 +97.04,50.41499079,-3.581565415,50,-26.10267433,14.79118015,0,0,0,150.4580153 +97.05,50.41498844,-3.581563335,50,-26.12353142,14.76519325,0,0,0,150.5152672 +97.06,50.41498609,-3.58156126,50,-26.13743616,14.73898423,0,0,0,150.5725191 +97.07,50.41498374,-3.581559188,50,-26.14091233,14.71321945,0,0,0,150.629771 +97.08,50.41498139,-3.58155712,50,-26.14438849,14.68789889,0,0,0,150.6870229 +97.09,50.41497904,-3.581555055,50,-26.15829322,14.66191198,0,0,0,150.7442748 +97.1,50.41497669,-3.581552994,50,-26.17915034,14.63481449,0,0,0,150.8015268 +97.11,50.41497433,-3.581550937,50,-26.19653126,14.607717,0,0,0,150.8587787 +97.12,50.41497198,-3.581548884,50,-26.21391217,14.58173009,0,0,0,150.9160305 +97.13,50.41496962,-3.581546834,50,-26.23476927,14.55663164,0,0,0,150.9732824 +97.14,50.41496726,-3.581544788,50,-26.25215018,14.53153319,0,0,0,151.0305344 +97.15,50.4149649,-3.581542745,50,-26.26953109,14.50554627,0,0,0,151.0877863 +97.16,50.41496254,-3.581540706,50,-26.28691201,14.47844876,0,0,0,151.1450382 +97.17,50.41496017,-3.581538671,50,-26.29038819,14.45135126,0,0,0,151.2022901 +97.18,50.41495781,-3.58153664,50,-26.29038818,14.42514221,0,0,0,151.259542 +97.19,50.41495545,-3.581534612,50,-26.31124527,14.39893317,0,0,0,151.3167939 +97.2,50.41495308,-3.581532588,50,-26.34253091,14.37183565,0,0,0,151.3740458 +97.21,50.41495071,-3.581530568,50,-26.35991183,14.34496025,0,0,0,151.4312977 +97.22,50.41494834,-3.581528552,50,-26.36338802,14.31963967,0,0,0,151.4885496 +97.23,50.41494597,-3.581526539,50,-26.3668642,14.29476331,0,0,0,151.5458016 +97.24,50.4149436,-3.581524529,50,-26.38076892,14.26855426,0,0,0,151.6030535 +97.25,50.41494123,-3.581522524,50,-26.40162601,14.24145673,0,0,0,151.6603054 +97.26,50.41493885,-3.581520522,50,-26.41900692,14.21458132,0,0,0,151.7175572 +97.27,50.41493648,-3.581518524,50,-26.43638785,14.18815014,0,0,0,151.7748092 +97.28,50.4149341,-3.58151653,50,-26.45724496,14.16216319,0,0,0,151.8320611 +97.29,50.41493172,-3.581514539,50,-26.47114968,14.13595413,0,0,0,151.889313 +97.3,50.41492934,-3.581512552,50,-26.47462585,14.10885659,0,0,0,151.9465649 +97.31,50.41492696,-3.581510569,50,-26.47810202,14.08175905,0,0,0,152.0038168 +97.32,50.41492458,-3.58150859,50,-26.49200675,14.05554998,0,0,0,152.0610687 +97.33,50.4149222,-3.581506614,50,-26.51286386,14.02956302,0,0,0,152.1183207 +97.34,50.41491981,-3.581504642,50,-26.53024478,14.00313182,0,0,0,152.1755725 +97.35,50.41491743,-3.581502674,50,-26.54762571,13.97625639,0,0,0,152.2328244 +97.36,50.41491504,-3.581500709,50,-26.5684828,13.94915884,0,0,0,152.2900763 +97.37,50.41491265,-3.581498749,50,-26.58238751,13.92272764,0,0,0,152.3473283 +97.38,50.41491026,-3.581496792,50,-26.58586367,13.89696279,0,0,0,152.4045802 +97.39,50.41490787,-3.581494838,50,-26.58933985,13.87053158,0,0,0,152.4618321 +97.4,50.41490548,-3.581492889,50,-26.60672076,13.84343402,0,0,0,152.519084 +97.41,50.41490309,-3.581490943,50,-26.63800643,13.81655857,0,0,0,152.5763359 +97.42,50.41490069,-3.581489001,50,-26.65886356,13.79012736,0,0,0,152.6335878 +97.43,50.41489829,-3.581487063,50,-26.65886356,13.76391826,0,0,0,152.6908397 +97.44,50.4148959,-3.581485128,50,-26.66233972,13.73704281,0,0,0,152.7480916 +97.45,50.4148935,-3.581483197,50,-26.67972062,13.70972312,0,0,0,152.8053435 +97.46,50.4148911,-3.581481271,50,-26.69710152,13.68351401,0,0,0,152.8625955 +97.47,50.4148887,-3.581479347,50,-26.71448243,13.65752702,0,0,0,152.9198474 +97.48,50.4148863,-3.581477427,50,-26.73533954,13.63020732,0,0,0,152.9770992 +97.49,50.41488389,-3.581475512,50,-26.74924427,13.60310974,0,0,0,153.0343511 +97.5,50.41488149,-3.5814736,50,-26.75272044,13.57712274,0,0,0,153.0916031 +97.51,50.41487908,-3.581471691,50,-26.75619662,13.55069151,0,0,0,153.148855 +97.52,50.41487668,-3.581469787,50,-26.77010135,13.52359392,0,0,0,153.2061069 +97.53,50.41487427,-3.581467886,50,-26.79095845,13.49649633,0,0,0,153.2633588 +97.54,50.41487186,-3.581465989,50,-26.80486318,13.46917662,0,0,0,153.3206107 +97.55,50.41486945,-3.581464096,50,-26.81181554,13.44207903,0,0,0,153.3778626 +97.56,50.41486704,-3.581462207,50,-26.82572026,13.4158699,0,0,0,153.4351145 +97.57,50.41486463,-3.581460321,50,-26.84657735,13.38988288,0,0,0,153.4923664 +97.58,50.41486221,-3.581458439,50,-26.86395826,13.36345163,0,0,0,153.5496183 +97.59,50.4148598,-3.581456561,50,-26.88133919,13.33657614,0,0,0,153.6068702 +97.6,50.41485738,-3.581454686,50,-26.9021963,13.30925642,0,0,0,153.6641222 +97.61,50.41485496,-3.581452816,50,-26.91610103,13.28193669,0,0,0,153.7213741 +97.62,50.41485254,-3.581450949,50,-26.9195772,13.2550612,0,0,0,153.7786259 +97.63,50.41485012,-3.581449086,50,-26.91957718,13.22840782,0,0,0,153.8358779 +97.64,50.4148477,-3.581447227,50,-26.92305335,13.20153232,0,0,0,153.8931298 +97.65,50.41484528,-3.581445371,50,-26.93695808,13.17421258,0,0,0,153.9503817 +97.66,50.41484286,-3.58144352,50,-26.95781518,13.14689284,0,0,0,154.0076336 +97.67,50.41484043,-3.581441672,50,-26.97519609,13.12001733,0,0,0,154.0648855 +97.68,50.41483801,-3.581439828,50,-26.992577,13.09358606,0,0,0,154.1221374 +97.69,50.41483558,-3.581437988,50,-27.01343411,13.0673769,0,0,0,154.1793894 +97.7,50.41483315,-3.581436151,50,-27.02733884,13.04027926,0,0,0,154.2366412 +97.71,50.41483072,-3.581434318,50,-27.03081502,13.01207104,0,0,0,154.2938931 +97.72,50.41482829,-3.58143249,50,-27.03429119,12.98475129,0,0,0,154.351145 +97.73,50.41482586,-3.581430665,50,-27.04819592,12.95876424,0,0,0,154.408397 +97.74,50.41482343,-3.581428843,50,-27.06905302,12.93233295,0,0,0,154.4656489 +97.75,50.41482099,-3.581427026,50,-27.08643394,12.9052353,0,0,0,154.5229008 +97.76,50.41481856,-3.581425212,50,-27.10381484,12.87813766,0,0,0,154.5801527 +97.77,50.41481612,-3.581423402,50,-27.12467193,12.85081789,0,0,0,154.6374046 +97.78,50.41481368,-3.581421596,50,-27.13857665,12.82349812,0,0,0,154.6946565 +97.79,50.41481124,-3.581419794,50,-27.14205284,12.79640047,0,0,0,154.7519084 +97.8,50.4148088,-3.581417995,50,-27.14205284,12.7690807,0,0,0,154.8091603 +97.81,50.41480636,-3.581416201,50,-27.14552902,12.74176092,0,0,0,154.8664122 +97.82,50.41480392,-3.58141441,50,-27.15943374,12.71466326,0,0,0,154.9236641 +97.83,50.41480148,-3.581412623,50,-27.18029082,12.68734348,0,0,0,154.9809161 +97.84,50.41479903,-3.58141084,50,-27.19767173,12.66002369,0,0,0,155.038168 +97.85,50.41479659,-3.581409061,50,-27.21505266,12.63292603,0,0,0,155.0954198 +97.86,50.41479414,-3.581407285,50,-27.23590977,12.60560624,0,0,0,155.1526718 +97.87,50.41479169,-3.581405514,50,-27.2498145,12.57828645,0,0,0,155.2099237 +97.88,50.41478924,-3.581403746,50,-27.25329067,12.55118877,0,0,0,155.2671756 +97.89,50.41478679,-3.581401982,50,-27.25329064,12.52386897,0,0,0,155.3244275 +97.9,50.41478434,-3.581400222,50,-27.25676682,12.49677129,0,0,0,155.3816794 +97.91,50.41478189,-3.581398466,50,-27.27067155,12.47033996,0,0,0,155.4389313 +97.92,50.41477944,-3.581396713,50,-27.29152865,12.44346439,0,0,0,155.4961833 +97.93,50.41477698,-3.581394964,50,-27.30890955,12.41592247,0,0,0,155.5534351 +97.94,50.41477453,-3.58139322,50,-27.32629047,12.38882478,0,0,0,155.610687 +97.95,50.41477207,-3.581391478,50,-27.34714758,12.36150497,0,0,0,155.6679389 +97.96,50.41476961,-3.581389741,50,-27.36105231,12.33307456,0,0,0,155.7251909 +97.97,50.41476715,-3.581388008,50,-27.36452848,12.3050884,0,0,0,155.7824428 +97.98,50.41476469,-3.581386279,50,-27.36452846,12.27843493,0,0,0,155.8396947 +97.99,50.41476223,-3.581384553,50,-27.36800463,12.25155934,0,0,0,155.8969466 +98,50.41475977,-3.581382831,50,-27.38190937,12.2240174,0,0,0,155.9541985 +98.01,50.41475731,-3.581381114,50,-27.40276647,12.19691969,0,0,0,156.0114504 +98.02,50.41475484,-3.581379399,50,-27.42014738,12.16982198,0,0,0,156.0687023 +98.03,50.41475238,-3.581377689,50,-27.43752829,12.14205791,0,0,0,156.1259542 +98.04,50.41474991,-3.581375983,50,-27.45838539,12.11429384,0,0,0,156.1832061 +98.05,50.41474744,-3.58137428,50,-27.47229011,12.08675189,0,0,0,156.240458 +98.06,50.41474497,-3.581372582,50,-27.47576629,12.05943205,0,0,0,156.29771 +98.07,50.4147425,-3.581370887,50,-27.47576629,12.03233433,0,0,0,156.3549618 +98.08,50.41474003,-3.581369196,50,-27.47924247,12.00479237,0,0,0,156.4122137 +98.09,50.41473756,-3.581367509,50,-27.49314718,11.97680617,0,0,0,156.4694657 +98.1,50.41473509,-3.581365826,50,-27.51400427,11.9492642,0,0,0,156.5267176 +98.11,50.41473261,-3.581364147,50,-27.53138519,11.92216646,0,0,0,156.5839695 +98.12,50.41473014,-3.581362471,50,-27.54876612,11.89484661,0,0,0,156.6412214 +98.13,50.41472766,-3.5813608,50,-27.56962322,11.86752675,0,0,0,156.6984733 +98.14,50.41472518,-3.581359132,50,-27.58352794,11.84042901,0,0,0,156.7557252 +98.15,50.4147227,-3.581357468,50,-27.5870041,11.81266491,0,0,0,156.8129771 +98.16,50.41472022,-3.581355808,50,-27.58700409,11.78379022,0,0,0,156.870229 +98.17,50.41471774,-3.581354152,50,-27.58700408,11.75513765,0,0,0,156.9274809 +98.18,50.41471526,-3.581352501,50,-27.59048025,11.72803989,0,0,0,156.9847328 +98.19,50.41471278,-3.581350852,50,-27.60786115,11.70183061,0,0,0,157.0419848 +98.2,50.4147103,-3.581349208,50,-27.63914681,11.67517709,0,0,0,157.0992367 +98.21,50.41470781,-3.581347567,50,-27.66000393,11.64741297,0,0,0,157.1564885 +98.22,50.41470532,-3.58134593,50,-27.66000393,11.61876039,0,0,0,157.2137405 +98.23,50.41470284,-3.581344298,50,-27.6634801,11.59055203,0,0,0,157.2709924 +98.24,50.41470035,-3.581342669,50,-27.68086101,11.56323215,0,0,0,157.3282443 +98.25,50.41469786,-3.581341044,50,-27.69476573,11.53569014,0,0,0,157.3854962 +98.26,50.41469537,-3.581339423,50,-27.70171808,11.50770389,0,0,0,157.4427481 +98.27,50.41469288,-3.581337806,50,-27.71562279,11.48016188,0,0,0,157.5 +98.28,50.41469039,-3.581336193,50,-27.73647988,11.4530641,0,0,0,157.5572519 +98.29,50.41468789,-3.581334583,50,-27.75038461,11.42552209,0,0,0,157.6145038 +98.3,50.4146854,-3.581332978,50,-27.7538608,11.39731371,0,0,0,157.6717557 +98.31,50.4146829,-3.581331376,50,-27.75733699,11.36910534,0,0,0,157.7290076 +98.32,50.41468041,-3.581329779,50,-27.77124172,11.34156331,0,0,0,157.7862596 +98.33,50.41467791,-3.581328185,50,-27.79209882,11.31446552,0,0,0,157.8435115 +98.34,50.41467541,-3.581326595,50,-27.80600354,11.28692349,0,0,0,157.9007634 +98.35,50.41467291,-3.581325009,50,-27.80947971,11.2587151,0,0,0,157.9580153 +98.36,50.41467041,-3.581323427,50,-27.80947971,11.2302846,0,0,0,158.0152672 +98.37,50.41466791,-3.581321849,50,-27.81295588,11.2020762,0,0,0,158.0725191 +98.38,50.41466541,-3.581320275,50,-27.8268606,11.17453416,0,0,0,158.129771 +98.39,50.41466291,-3.581318705,50,-27.84771768,11.14743635,0,0,0,158.1870229 +98.4,50.4146604,-3.581317138,50,-27.86509859,11.12011642,0,0,0,158.2442748 +98.41,50.4146579,-3.581315576,50,-27.88247952,11.09257437,0,0,0,158.3015267 +98.42,50.41465539,-3.581314017,50,-27.89986044,11.06458809,0,0,0,158.3587787 +98.43,50.41465288,-3.581312462,50,-27.89986042,11.03593544,0,0,0,158.4160305 +98.44,50.41465037,-3.581310912,50,-27.88943184,11.00772703,0,0,0,158.4732824 +98.45,50.41464787,-3.581309365,50,-27.90333657,10.98040709,0,0,0,158.5305344 +98.46,50.41464536,-3.581307822,50,-27.93809842,10.95286503,0,0,0,158.5877863 +98.47,50.41464284,-3.581306283,50,-27.95547934,10.92465661,0,0,0,158.6450382 +98.48,50.41464033,-3.581304748,50,-27.95547932,10.89622607,0,0,0,158.7022901 +98.49,50.41463782,-3.581303217,50,-27.96243167,10.86779552,0,0,0,158.759542 +98.5,50.4146353,-3.58130169,50,-27.97286022,10.8395871,0,0,0,158.8167939 +98.51,50.41463279,-3.581300167,50,-27.97633639,10.81204502,0,0,0,158.8740458 +98.52,50.41463027,-3.581298648,50,-27.97981256,10.78494718,0,0,0,158.9312977 +98.53,50.41462776,-3.581297132,50,-27.9937173,10.75740509,0,0,0,158.9885496 +98.54,50.41462524,-3.581295621,50,-28.01457439,10.72919666,0,0,0,159.0458015 +98.55,50.41462272,-3.581294113,50,-28.02847911,10.70098821,0,0,0,159.1030535 +98.56,50.4146202,-3.58129261,50,-28.03543147,10.673224,0,0,0,159.1603054 +98.57,50.41461768,-3.58129111,50,-28.04933621,10.64523768,0,0,0,159.2175573 +98.58,50.41461516,-3.581289614,50,-28.0701933,10.61636287,0,0,0,159.2748092 +98.59,50.41461263,-3.581288123,50,-28.08409803,10.58726595,0,0,0,159.3320611 +98.6,50.41461011,-3.581286635,50,-28.0875742,10.55883537,0,0,0,159.389313 +98.61,50.41460758,-3.581285152,50,-28.09105037,10.53129327,0,0,0,159.4465649 +98.62,50.41460506,-3.581283672,50,-28.10147891,10.5041954,0,0,0,159.5038168 +98.63,50.41460253,-3.581282196,50,-28.10843127,10.47665329,0,0,0,159.5610687 +98.64,50.4146,-3.581280724,50,-28.10495508,10.44844482,0,0,0,159.6183206 +98.65,50.41459748,-3.581279256,50,-28.11190743,10.42001424,0,0,0,159.6755725 +98.66,50.41459495,-3.581277792,50,-28.14319309,10.39180576,0,0,0,159.7328244 +98.67,50.41459242,-3.581276332,50,-28.17447874,10.36426364,0,0,0,159.7900763 +98.68,50.41458988,-3.581274876,50,-28.18143109,10.33694364,0,0,0,159.8473283 +98.69,50.41458735,-3.581273423,50,-28.17795489,10.30851304,0,0,0,159.9045802 +98.7,50.41458482,-3.581271975,50,-28.18490725,10.27897185,0,0,0,159.9618321 +98.71,50.41458228,-3.581270531,50,-28.1953358,10.24987489,0,0,0,160.019084 +98.72,50.41457975,-3.581269091,50,-28.19881198,10.22211063,0,0,0,160.0763359 +98.73,50.41457721,-3.581267655,50,-28.20228814,10.19479062,0,0,0,160.1335878 +98.74,50.41457468,-3.581266222,50,-28.21619287,10.16658212,0,0,0,160.1908397 +98.75,50.41457214,-3.581264794,50,-28.23704996,10.13815151,0,0,0,160.2480916 +98.76,50.4145696,-3.58126337,50,-28.25095468,10.11083148,0,0,0,160.3053435 +98.77,50.41456706,-3.581261949,50,-28.25443086,10.08328933,0,0,0,160.3625954 +98.78,50.41456452,-3.581260532,50,-28.25790704,10.05397023,0,0,0,160.4198474 +98.79,50.41456198,-3.58125912,50,-28.27181177,10.02465113,0,0,0,160.4770993 +98.8,50.41455944,-3.581257712,50,-28.29266886,9.997108976,0,0,0,160.5343511 +98.81,50.41455689,-3.581256307,50,-28.30657359,9.969788936,0,0,0,160.5916031 +98.82,50.41455435,-3.581254906,50,-28.31004976,9.9413583,0,0,0,160.648855 +98.83,50.4145518,-3.58125351,50,-28.31352593,9.91292766,0,0,0,160.7061069 +98.84,50.41454926,-3.581252117,50,-28.32395448,9.884719137,0,0,0,160.7633588 +98.85,50.41454671,-3.581250728,50,-28.33090684,9.856066376,0,0,0,160.8206107 +98.86,50.41454416,-3.581249344,50,-28.32743064,9.827635729,0,0,0,160.8778626 +98.87,50.41454162,-3.581247963,50,-28.33438301,9.799427197,0,0,0,160.9351145 +98.88,50.41453907,-3.581246586,50,-28.36566865,9.770552305,0,0,0,160.9923664 +98.89,50.41453652,-3.581245214,50,-28.39695429,9.741455293,0,0,0,161.0496183 +98.9,50.41453396,-3.581243845,50,-28.40043047,9.713024636,0,0,0,161.1068702 +98.91,50.41453141,-3.581242481,50,-28.38652572,9.685482449,0,0,0,161.1641222 +98.92,50.41452886,-3.58124112,50,-28.38652571,9.658162377,0,0,0,161.2213741 +98.93,50.41452631,-3.581239763,50,-28.40390662,9.62973171,0,0,0,161.278626 +98.94,50.41452375,-3.58123841,50,-28.42128753,9.600412566,0,0,0,161.3358779 +98.95,50.4145212,-3.581237062,50,-28.43866844,9.571981892,0,0,0,161.3931298 +98.96,50.41451864,-3.581235717,50,-28.45952554,9.544439691,0,0,0,161.4503817 +98.97,50.41451608,-3.581234376,50,-28.46995408,9.516009012,0,0,0,161.5076336 +98.98,50.41451352,-3.581233039,50,-28.46300169,9.486689855,0,0,0,161.5648855 +98.99,50.41451096,-3.581231707,50,-28.45952549,9.458037053,0,0,0,161.6221374 +99,50.41450841,-3.581230378,50,-28.47690641,9.429828484,0,0,0,161.6793893 +99.01,50.41450584,-3.581229053,50,-28.49428734,9.401175675,0,0,0,161.7366413 +99.02,50.41450328,-3.581227733,50,-28.49428731,9.372744982,0,0,0,161.7938931 +99.03,50.41450072,-3.581226416,50,-28.49776347,9.344536403,0,0,0,161.851145 +99.04,50.41449816,-3.581225103,50,-28.51514438,9.315661466,0,0,0,161.908397 +99.05,50.41449559,-3.581223795,50,-28.52904912,9.286564408,0,0,0,161.9656489 +99.06,50.41449303,-3.58122249,50,-28.5325253,9.258133703,0,0,0,162.0229008 +99.07,50.41449046,-3.58122119,50,-28.53600148,9.23059147,0,0,0,162.0801527 +99.08,50.4144879,-3.581219893,50,-28.5499062,9.203271353,0,0,0,162.1374046 +99.09,50.41448533,-3.5812186,50,-28.5707633,9.174840641,0,0,0,162.1946565 +99.1,50.41448276,-3.581217311,50,-28.58466802,9.145299331,0,0,0,162.2519084 +99.11,50.41448019,-3.581216027,50,-28.58814418,9.115980136,0,0,0,162.3091603 +99.12,50.41447762,-3.581214746,50,-28.58814416,9.087549412,0,0,0,162.3664122 +99.13,50.41447505,-3.58121347,50,-28.59162034,9.059785043,0,0,0,162.4236641 +99.14,50.41447248,-3.581212197,50,-28.60552508,9.031798552,0,0,0,162.4809161 +99.15,50.41446991,-3.581210928,50,-28.62290599,9.002701465,0,0,0,162.538168 +99.16,50.41446733,-3.581209664,50,-28.62638215,8.972715898,0,0,0,162.5954198 +99.17,50.41446476,-3.581208403,50,-28.62638213,8.942952448,0,0,0,162.6526718 +99.18,50.41446219,-3.581207148,50,-28.64376304,8.914521708,0,0,0,162.7099237 +99.19,50.41445961,-3.581205895,50,-28.66114397,8.88720156,0,0,0,162.7671756 +99.2,50.41445703,-3.581204647,50,-28.66114396,8.859659289,0,0,0,162.8244275 +99.21,50.41445446,-3.581203402,50,-28.66462014,8.831450658,0,0,0,162.8816794 +99.22,50.41445188,-3.581202162,50,-28.68200104,8.802797788,0,0,0,162.9389313 +99.23,50.4144493,-3.581200925,50,-28.69590576,8.773700677,0,0,0,162.9961832 +99.24,50.41444672,-3.581199693,50,-28.69938194,8.744603562,0,0,0,163.0534351 +99.25,50.41444414,-3.581198465,50,-28.69938194,8.715728563,0,0,0,163.110687 +99.26,50.41444156,-3.58119724,50,-28.70285811,8.686853561,0,0,0,163.1679389 +99.27,50.41443898,-3.581196021,50,-28.71676283,8.658422794,0,0,0,163.2251909 +99.28,50.4144364,-3.581194804,50,-28.73761992,8.630214144,0,0,0,163.2824428 +99.29,50.41443381,-3.581193592,50,-28.75152464,8.601117014,0,0,0,163.3396947 +99.3,50.41443123,-3.581192384,50,-28.75500081,8.571353524,0,0,0,163.3969466 +99.31,50.41442864,-3.58119118,50,-28.75500079,8.542478507,0,0,0,163.4541985 +99.32,50.41442606,-3.581189981,50,-28.75500078,8.514936202,0,0,0,163.5114504 +99.33,50.41442347,-3.581188784,50,-28.75847696,8.486727537,0,0,0,163.5687023 +99.34,50.41442089,-3.581187592,50,-28.7723817,8.456964035,0,0,0,163.6259542 +99.35,50.4144183,-3.581186405,50,-28.7932388,8.427644767,0,0,0,163.6832061 +99.36,50.41441571,-3.581185221,50,-28.80714352,8.399213974,0,0,0,163.740458 +99.37,50.41441312,-3.581184041,50,-28.81061969,8.370561058,0,0,0,163.79771 +99.38,50.41441053,-3.581182866,50,-28.81409585,8.342130259,0,0,0,163.8549618 +99.39,50.41440794,-3.581181694,50,-28.82800057,8.313921576,0,0,0,163.9122137 +99.4,50.41440535,-3.581180526,50,-28.84538148,8.285046532,0,0,0,163.9694657 +99.41,50.41440275,-3.581179363,50,-28.84885767,8.255727246,0,0,0,164.0267176 +99.42,50.41440016,-3.581178203,50,-28.84538149,8.226185839,0,0,0,164.0839695 +99.43,50.41439757,-3.581177048,50,-28.85233384,8.196644429,0,0,0,164.1412214 +99.44,50.41439497,-3.581175897,50,-28.86623855,8.168213611,0,0,0,164.1984733 +99.45,50.41439238,-3.58117475,50,-28.88014327,8.140671268,0,0,0,164.2557252 +99.46,50.41438978,-3.581173606,50,-28.88709563,8.112240445,0,0,0,164.3129771 +99.47,50.41438718,-3.581172467,50,-28.88361943,8.082699023,0,0,0,164.370229 +99.48,50.41438459,-3.581171332,50,-28.8870956,8.053379717,0,0,0,164.4274809 +99.49,50.41438199,-3.581170201,50,-28.90447651,8.024726765,0,0,0,164.4847328 +99.5,50.41437939,-3.581169074,50,-28.91838125,7.996295928,0,0,0,164.5419848 +99.51,50.41437679,-3.581167951,50,-28.92185742,7.96764297,0,0,0,164.5992367 +99.52,50.41437419,-3.581166832,50,-28.92533358,7.938323651,0,0,0,164.6564886 +99.53,50.41437159,-3.581165717,50,-28.93923831,7.908782211,0,0,0,164.7137405 +99.54,50.41436899,-3.581164607,50,-28.95661922,7.880129244,0,0,0,164.7709924 +99.55,50.41436638,-3.5811635,50,-28.9600954,7.851698393,0,0,0,164.8282443 +99.56,50.41436378,-3.581162397,50,-28.95661922,7.822156943,0,0,0,164.8854962 +99.57,50.41436118,-3.581161299,50,-28.96357158,7.792615489,0,0,0,164.9427481 +99.58,50.41435857,-3.581160205,50,-28.97747629,7.764184629,0,0,0,165 +99.59,50.41435597,-3.581159114,50,-28.99138101,7.735753766,0,0,0,165.0572519 +99.6,50.41435336,-3.581158028,50,-28.99833337,7.707100782,0,0,0,165.1145039 +99.61,50.41435075,-3.581156946,50,-28.99485716,7.678892033,0,0,0,165.1717557 +99.62,50.41434815,-3.581155867,50,-28.99833334,7.650016922,0,0,0,165.2290076 +99.63,50.41434554,-3.581154793,50,-29.01571425,7.619586972,0,0,0,165.2862596 +99.64,50.41434293,-3.581153723,50,-29.02961897,7.589157018,0,0,0,165.3435115 +99.65,50.41434032,-3.581152658,50,-29.03309514,7.560504017,0,0,0,165.4007634 +99.66,50.41433771,-3.581151596,50,-29.03657131,7.532961612,0,0,0,165.4580153 +99.67,50.4143351,-3.581150538,50,-29.05047604,7.504530726,0,0,0,165.5152672 +99.68,50.41433249,-3.581149484,50,-29.06785695,7.474989239,0,0,0,165.5725191 +99.69,50.41432987,-3.581148435,50,-29.07133313,7.445669867,0,0,0,165.629771 +99.7,50.41432726,-3.581147389,50,-29.06785694,7.417016851,0,0,0,165.6870229 +99.71,50.41432465,-3.581146348,50,-29.07480929,7.388363832,0,0,0,165.7442748 +99.72,50.41432203,-3.58114531,50,-29.08523783,7.359044452,0,0,0,165.8015267 +99.73,50.41431942,-3.581144277,50,-29.08871399,7.32928083,0,0,0,165.8587787 +99.74,50.4143168,-3.581143248,50,-29.09219017,7.299961443,0,0,0,165.9160306 +99.75,50.41431419,-3.581142223,50,-29.10609489,7.271308411,0,0,0,165.9732824 +99.76,50.41431157,-3.581141202,50,-29.12347581,7.242655377,0,0,0,166.0305344 +99.77,50.41430895,-3.581140185,50,-29.12347579,7.213113861,0,0,0,166.0877863 +99.78,50.41430633,-3.581139172,50,-29.10957103,7.182683864,0,0,0,166.1450382 +99.79,50.41430372,-3.581138164,50,-29.109571,7.153142342,0,0,0,166.2022901 +99.8,50.4143011,-3.58113716,50,-29.1304281,7.125599893,0,0,0,166.259542 +99.81,50.41429848,-3.581136159,50,-29.15823758,7.098057441,0,0,0,166.3167939 +99.82,50.41429586,-3.581135162,50,-29.17909469,7.06851591,0,0,0,166.3740458 +99.83,50.41429323,-3.58113417,50,-29.17909468,7.038085897,0,0,0,166.4312977 +99.84,50.41429061,-3.581133182,50,-29.16518992,7.008544359,0,0,0,166.4885496 +99.85,50.41428799,-3.581132198,50,-29.16518991,6.979669177,0,0,0,166.5458015 +99.86,50.41428537,-3.581131218,50,-29.18257082,6.950349753,0,0,0,166.6030535 +99.87,50.41428274,-3.581130242,50,-29.19647554,6.920808207,0,0,0,166.6603054 +99.88,50.41428012,-3.581129271,50,-29.19995171,6.892155135,0,0,0,166.7175573 +99.89,50.41427749,-3.581128303,50,-29.20342788,6.8639463,0,0,0,166.7748092 +99.9,50.41427487,-3.581127339,50,-29.21385643,6.835071102,0,0,0,166.8320611 +99.91,50.41427224,-3.58112638,50,-29.22080879,6.805751662,0,0,0,166.889313 +99.92,50.41426961,-3.581125424,50,-29.21733259,6.7762101,0,0,0,166.9465649 +99.93,50.41426699,-3.581124473,50,-29.22080876,6.746446415,0,0,0,167.0038168 +99.94,50.41426436,-3.581123526,50,-29.23818966,6.717126965,0,0,0,167.0610687 +99.95,50.41426173,-3.581122583,50,-29.25209437,6.688251751,0,0,0,167.1183206 +99.96,50.4142591,-3.581121644,50,-29.25557054,6.658932296,0,0,0,167.1755726 +99.97,50.41425647,-3.581120709,50,-29.25557054,6.629390717,0,0,0,167.2328244 +99.98,50.41425384,-3.581119779,50,-29.25904672,6.600515494,0,0,0,167.2900763 +99.99,50.41425121,-3.581118852,50,-29.27295145,6.571418149,0,0,0,167.3473283 +100,50.41424858,-3.581117929,50,-29.29033236,6.54143232,0,0,0,167.4045802 +100.01,50.41424594,-3.581117012,50,-29.29380853,6.512112848,0,0,0,167.4618321 +100.02,50.41424331,-3.581116097,50,-29.29033234,6.483681854,0,0,0,167.519084 +100.03,50.41424068,-3.581115187,50,-29.29728469,6.454584496,0,0,0,167.5763359 +100.04,50.41423804,-3.581114281,50,-29.30771323,6.424598655,0,0,0,167.6335878 +100.05,50.41423541,-3.581113379,50,-29.31118939,6.394834931,0,0,0,167.6908397 +100.06,50.41423277,-3.581112482,50,-29.31118937,6.366181803,0,0,0,167.7480916 +100.07,50.41423014,-3.581111588,50,-29.31118935,6.337750793,0,0,0,167.8053435 +100.08,50.4142275,-3.581110698,50,-29.31466554,6.308209179,0,0,0,167.8625954 +100.09,50.41422487,-3.581109813,50,-29.32857028,6.278445442,0,0,0,167.9198474 +100.1,50.41422223,-3.581108932,50,-29.34942737,6.249125941,0,0,0,167.9770993 +100.11,50.41421959,-3.581108054,50,-29.3633321,6.219362197,0,0,0,168.0343511 +100.12,50.41421695,-3.581107182,50,-29.36680826,6.189820571,0,0,0,168.0916031 +100.13,50.41421431,-3.581106313,50,-29.36680823,6.161389542,0,0,0,168.148855 +100.14,50.41421167,-3.581105448,50,-29.36680821,6.13273639,0,0,0,168.2061069 +100.15,50.41420903,-3.581104587,50,-29.36680822,6.103194754,0,0,0,168.2633588 +100.16,50.41420639,-3.581103731,50,-29.36680822,6.073653115,0,0,0,168.3206107 +100.17,50.41420375,-3.581102878,50,-29.37028438,6.044111472,0,0,0,168.3778626 +100.18,50.41420111,-3.58110203,50,-29.3841891,6.014125585,0,0,0,168.4351145 +100.19,50.41419847,-3.581101186,50,-29.4050462,5.983917575,0,0,0,168.4923664 +100.2,50.41419582,-3.581100346,50,-29.41895093,5.954153802,0,0,0,168.5496183 +100.21,50.41419318,-3.581099511,50,-29.4189509,5.925500628,0,0,0,168.6068702 +100.22,50.41419053,-3.581098679,50,-29.40852233,5.897069571,0,0,0,168.6641222 +100.23,50.41418789,-3.581097851,50,-29.40504614,5.867527909,0,0,0,168.7213741 +100.24,50.41418525,-3.581097028,50,-29.42242707,5.837764124,0,0,0,168.778626 +100.25,50.4141826,-3.581096209,50,-29.43980798,5.808444576,0,0,0,168.8358779 +100.26,50.41417995,-3.581095393,50,-29.43980795,5.778680784,0,0,0,168.8931298 +100.27,50.41417731,-3.581094583,50,-29.4432841,5.749139109,0,0,0,168.9503817 +100.28,50.41417466,-3.581093776,50,-29.45718883,5.720708032,0,0,0,169.0076336 +100.29,50.41417201,-3.581092973,50,-29.45718883,5.691832711,0,0,0,169.0648855 +100.3,50.41416936,-3.581092174,50,-29.4432841,5.661624666,0,0,0,169.1221374 +100.31,50.41416672,-3.58109138,50,-29.44328408,5.631860859,0,0,0,169.1793893 +100.32,50.41416407,-3.58109059,50,-29.46414115,5.60342977,0,0,0,169.2366413 +100.33,50.41416142,-3.581089803,50,-29.49195061,5.574554436,0,0,0,169.2938932 +100.34,50.41415877,-3.581089021,50,-29.51280771,5.544124257,0,0,0,169.351145 +100.35,50.41415611,-3.581088243,50,-29.51280771,5.513471955,0,0,0,169.408397 +100.36,50.41415346,-3.58108747,50,-29.49542676,5.483930252,0,0,0,169.4656489 +100.37,50.41415081,-3.5810867,50,-29.48499819,5.455054906,0,0,0,169.5229008 +100.38,50.41414816,-3.581085935,50,-29.49542675,5.425513196,0,0,0,169.5801527 +100.39,50.41414551,-3.581085173,50,-29.51280767,5.395083001,0,0,0,169.6374046 +100.4,50.41414285,-3.581084417,50,-29.51628384,5.365319163,0,0,0,169.6946565 +100.41,50.4141402,-3.581083664,50,-29.51280762,5.337110165,0,0,0,169.7519084 +100.42,50.41413755,-3.581082915,50,-29.51975996,5.309123284,0,0,0,169.8091603 +100.43,50.41413489,-3.58108217,50,-29.53018851,5.279803678,0,0,0,169.8664122 +100.44,50.41413224,-3.581081429,50,-29.53366469,5.249151347,0,0,0,169.9236641 +100.45,50.41412958,-3.581080693,50,-29.53714087,5.218499013,0,0,0,169.9809161 +100.46,50.41412693,-3.581079961,50,-29.55104559,5.188957275,0,0,0,170.038168 +100.47,50.41412427,-3.581079233,50,-29.56842649,5.160304017,0,0,0,170.0954199 +100.48,50.41412161,-3.581078509,50,-29.56842648,5.131650757,0,0,0,170.1526718 +100.49,50.41411895,-3.581077789,50,-29.55452174,5.102109011,0,0,0,170.2099237 +100.5,50.4141163,-3.581077073,50,-29.55452174,5.07145666,0,0,0,170.2671756 +100.51,50.41411364,-3.581076362,50,-29.57190264,5.040804304,0,0,0,170.3244275 +100.52,50.41411098,-3.581075655,50,-29.58580735,5.011262548,0,0,0,170.3816794 +100.53,50.41410832,-3.581074952,50,-29.58928353,4.982609271,0,0,0,170.4389313 +100.54,50.41410566,-3.581074253,50,-29.58928352,4.954178111,0,0,0,170.4961832 +100.55,50.414103,-3.581073558,50,-29.5892835,4.925524828,0,0,0,170.5534352 +100.56,50.41410034,-3.581072867,50,-29.58928347,4.89598306,0,0,0,170.610687 +100.57,50.41409768,-3.58107218,50,-29.59275965,4.865330684,0,0,0,170.6679389 +100.58,50.41409502,-3.581071498,50,-29.60666438,4.834678306,0,0,0,170.7251909 +100.59,50.41409236,-3.58107082,50,-29.62404529,4.804914407,0,0,0,170.7824428 +100.6,50.41408969,-3.581070146,50,-29.62752145,4.775372624,0,0,0,170.8396947 +100.61,50.41408703,-3.581069476,50,-29.62404526,4.745608719,0,0,0,170.8969466 +100.62,50.41408437,-3.581068811,50,-29.62752144,4.716066931,0,0,0,170.9541985 +100.63,50.4140817,-3.581068149,50,-29.62752142,4.686525139,0,0,0,171.0114504 +100.64,50.41407904,-3.581067492,50,-29.62404522,4.656761223,0,0,0,171.0687023 +100.65,50.41407638,-3.581066839,50,-29.63099757,4.627441545,0,0,0,171.1259542 +100.66,50.41407371,-3.58106619,50,-29.64490229,4.598788226,0,0,0,171.1832061 +100.67,50.41407105,-3.581065545,50,-29.658807,4.570134904,0,0,0,171.240458 +100.68,50.41406838,-3.581064904,50,-29.66575936,4.540593096,0,0,0,171.29771 +100.69,50.41406571,-3.581064267,50,-29.66228318,4.509940682,0,0,0,171.3549619 +100.7,50.41406305,-3.581063635,50,-29.66575936,4.479288264,0,0,0,171.4122137 +100.71,50.41406038,-3.581063007,50,-29.67966408,4.449524325,0,0,0,171.4694657 +100.72,50.41405771,-3.581062383,50,-29.67966406,4.419982503,0,0,0,171.5267176 +100.73,50.41405504,-3.581061763,50,-29.66575931,4.390218557,0,0,0,171.5839695 +100.74,50.41405238,-3.581061148,50,-29.6657593,4.36067673,0,0,0,171.6412214 +100.75,50.41404971,-3.581060536,50,-29.68314021,4.331134899,0,0,0,171.6984733 +100.76,50.41404704,-3.581059929,50,-29.69704494,4.301370943,0,0,0,171.7557252 +100.77,50.41404437,-3.581059326,50,-29.70052112,4.272051227,0,0,0,171.8129771 +100.78,50.4140417,-3.581058727,50,-29.70052109,4.243175748,0,0,0,171.870229 +100.79,50.41403903,-3.581058132,50,-29.70052107,4.213633904,0,0,0,171.9274809 +100.8,50.41403636,-3.581057541,50,-29.70052105,4.183203572,0,0,0,171.9847328 +100.81,50.41403369,-3.581056955,50,-29.70399721,4.153217479,0,0,0,172.0419848 +100.82,50.41403102,-3.581056373,50,-29.71790194,4.123897746,0,0,0,172.0992367 +100.83,50.41402835,-3.581055794,50,-29.73528287,4.094133768,0,0,0,172.1564886 +100.84,50.41402567,-3.581055221,50,-29.73528287,4.064369786,0,0,0,172.2137404 +100.85,50.414023,-3.581054651,50,-29.72137811,4.035050043,0,0,0,172.2709924 +100.86,50.41402033,-3.581054085,50,-29.72137809,4.005063934,0,0,0,172.3282443 +100.87,50.41401766,-3.581053524,50,-29.73528282,3.974633579,0,0,0,172.3854962 +100.88,50.41401498,-3.581052967,50,-29.73875898,3.945091705,0,0,0,172.4427481 +100.89,50.41401231,-3.581052414,50,-29.73528277,3.916216191,0,0,0,172.5 +100.9,50.41400964,-3.581051865,50,-29.74223513,3.886674311,0,0,0,172.5572519 +100.91,50.41400696,-3.58105132,50,-29.75266368,3.856021821,0,0,0,172.6145039 +100.92,50.41400429,-3.58105078,50,-29.75613986,3.825369328,0,0,0,172.6717557 +100.93,50.41400161,-3.581050244,50,-29.75961604,3.795827437,0,0,0,172.7290076 +100.94,50.41399894,-3.581049712,50,-29.77004457,3.767174028,0,0,0,172.7862596 +100.95,50.41399626,-3.581049184,50,-29.77699691,3.738520616,0,0,0,172.8435115 +100.96,50.41399358,-3.58104866,50,-29.77352071,3.708978715,0,0,0,172.9007634 +100.97,50.41399091,-3.58104814,50,-29.7735207,3.678326206,0,0,0,172.9580153 +100.98,50.41398823,-3.581047625,50,-29.77699688,3.647673693,0,0,0,173.0152672 +100.99,50.41398555,-3.581047114,50,-29.77352068,3.618131783,0,0,0,173.0725191 +101,50.41398288,-3.581046607,50,-29.77699685,3.589256233,0,0,0,173.129771 +101.01,50.4139802,-3.581046104,50,-29.79437775,3.559714316,0,0,0,173.1870229 +101.02,50.41397752,-3.581045605,50,-29.80480629,3.529061788,0,0,0,173.2442748 +101.03,50.41397484,-3.581045111,50,-29.79437773,3.498409258,0,0,0,173.3015267 +101.04,50.41397216,-3.581044621,50,-29.7769968,3.46864521,0,0,0,173.3587787 +101.05,50.41396949,-3.581044135,50,-29.77699679,3.43910328,0,0,0,173.4160306 +101.06,50.41396681,-3.581043653,50,-29.79437769,3.409561347,0,0,0,173.4732825 +101.07,50.41396413,-3.581043176,50,-29.8082824,3.380685773,0,0,0,173.5305343 +101.08,50.41396145,-3.581042702,50,-29.81523476,3.351365954,0,0,0,173.5877863 +101.09,50.41395877,-3.581042232,50,-29.8291395,3.320491282,0,0,0,173.6450382 +101.1,50.41395609,-3.581041768,50,-29.8465204,3.290060851,0,0,0,173.7022901 +101.11,50.4139534,-3.581041307,50,-29.84652038,3.261407386,0,0,0,173.759542 +101.12,50.41395072,-3.58104085,50,-29.82913945,3.232531797,0,0,0,173.8167939 +101.13,50.41394804,-3.581040397,50,-29.8152347,3.202101354,0,0,0,173.8740458 +101.14,50.41394536,-3.581039949,50,-29.81523469,3.171226666,0,0,0,173.9312977 +101.15,50.41394268,-3.581039505,50,-29.82913941,3.140796217,0,0,0,173.9885496 +101.16,50.41394,-3.581039065,50,-29.84652031,3.110810007,0,0,0,174.0458015 +101.17,50.41393731,-3.58103863,50,-29.84999648,3.081490159,0,0,0,174.1030535 +101.18,50.41393463,-3.581038198,50,-29.84652029,3.052614549,0,0,0,174.1603054 +101.19,50.41393195,-3.581037771,50,-29.84999645,3.023072571,0,0,0,174.2175573 +101.2,50.41392926,-3.581037347,50,-29.84999643,2.992642105,0,0,0,174.2748092 +101.21,50.41392658,-3.581036929,50,-29.84652025,2.962655879,0,0,0,174.3320611 +101.22,50.4139239,-3.581036514,50,-29.85347261,2.933336015,0,0,0,174.389313 +101.23,50.41392121,-3.581036103,50,-29.86390115,2.903349782,0,0,0,174.4465649 +101.24,50.41391853,-3.581035697,50,-29.86737731,2.872919301,0,0,0,174.5038168 +101.25,50.41391584,-3.581035295,50,-29.86737729,2.843155182,0,0,0,174.5610687 +101.26,50.41391316,-3.581034897,50,-29.86737729,2.813613181,0,0,0,174.6183206 +101.27,50.41391047,-3.581034503,50,-29.86737727,2.783849057,0,0,0,174.6755726 +101.28,50.41390779,-3.581034114,50,-29.86737726,2.75430705,0,0,0,174.7328245 +101.29,50.4139051,-3.581033728,50,-29.87085344,2.72476504,0,0,0,174.7900763 +101.3,50.41390242,-3.581033347,50,-29.88128197,2.694778783,0,0,0,174.8473282 +101.31,50.41389973,-3.58103297,50,-29.88823431,2.664570401,0,0,0,174.9045802 +101.32,50.41389704,-3.581032597,50,-29.88475811,2.634584138,0,0,0,174.9618321 +101.33,50.41389436,-3.581032229,50,-29.88475811,2.605042114,0,0,0,175.019084 +101.34,50.41389167,-3.581031864,50,-29.88823428,2.575500086,0,0,0,175.0763359 +101.35,50.41388898,-3.581031504,50,-29.88475808,2.545513813,0,0,0,175.1335878 +101.36,50.4138863,-3.581031148,50,-29.88823426,2.515083293,0,0,0,175.1908397 +101.37,50.41388361,-3.581030796,50,-29.90213899,2.484208526,0,0,0,175.2480916 +101.38,50.41388092,-3.581030449,50,-29.90213896,2.453777999,0,0,0,175.3053435 +101.39,50.41387823,-3.581030106,50,-29.8882342,2.42490232,0,0,0,175.3625954 +101.4,50.41387555,-3.581029767,50,-29.88823419,2.396470881,0,0,0,175.4198474 +101.41,50.41387286,-3.581029431,50,-29.9056151,2.366706709,0,0,0,175.4770993 +101.42,50.41387017,-3.581029101,50,-29.91951983,2.336054047,0,0,0,175.5343512 +101.43,50.41386748,-3.581028774,50,-29.922996,2.305623503,0,0,0,175.591603 +101.44,50.41386479,-3.581028452,50,-29.92299598,2.275637199,0,0,0,175.648855 +101.45,50.4138621,-3.581028134,50,-29.92299597,2.246095134,0,0,0,175.7061069 +101.46,50.41385941,-3.58102782,50,-29.92299596,2.216330945,0,0,0,175.7633588 +101.47,50.41385672,-3.58102751,50,-29.92299595,2.185900388,0,0,0,175.8206107 +101.48,50.41385403,-3.581027205,50,-29.92299593,2.156136193,0,0,0,175.8778626 +101.49,50.41385134,-3.581026904,50,-29.92299592,2.127482602,0,0,0,175.9351145 +101.5,50.41384865,-3.581026606,50,-29.92299591,2.09794052,0,0,0,175.9923665 +101.51,50.41384596,-3.581026313,50,-29.92299589,2.067065705,0,0,0,176.0496183 +101.52,50.41384327,-3.581026025,50,-29.92299587,2.036635131,0,0,0,176.1068702 +101.53,50.41384058,-3.58102574,50,-29.92299585,2.006870919,0,0,0,176.1641221 +101.54,50.41383789,-3.58102546,50,-29.92299585,1.977106703,0,0,0,176.2213741 +101.55,50.4138352,-3.581025184,50,-29.92647203,1.947564605,0,0,0,176.278626 +101.56,50.41383251,-3.581024912,50,-29.94037675,1.917800382,0,0,0,176.3358779 +101.57,50.41382982,-3.581024644,50,-29.95775765,1.887147669,0,0,0,176.3931298 +101.58,50.41382712,-3.581024381,50,-29.95775762,1.856494952,0,0,0,176.4503817 +101.59,50.41382443,-3.581024122,50,-29.94037669,1.826730719,0,0,0,176.5076336 +101.6,50.41382174,-3.581023867,50,-29.92994814,1.797188604,0,0,0,176.5648855 +101.61,50.41381905,-3.581023616,50,-29.94037668,1.767424364,0,0,0,176.6221374 +101.62,50.41381636,-3.58102337,50,-29.95775758,1.737882243,0,0,0,176.6793893 +101.63,50.41381366,-3.581023127,50,-29.96123375,1.708340119,0,0,0,176.7366413 +101.64,50.41381097,-3.581022889,50,-29.95775756,1.678353747,0,0,0,176.7938932 +101.65,50.41380828,-3.581022655,50,-29.96123373,1.64814525,0,0,0,176.851145 +101.66,50.41380558,-3.581022425,50,-29.96123371,1.618158872,0,0,0,176.9083969 +101.67,50.41380289,-3.5810222,50,-29.95775751,1.588394613,0,0,0,176.9656489 +101.68,50.4138002,-3.581021978,50,-29.96123368,1.557963984,0,0,0,177.0229008 +101.69,50.4137975,-3.581021761,50,-29.96123367,1.526866984,0,0,0,177.0801527 +101.7,50.41379481,-3.581021549,50,-29.95775748,1.49665847,0,0,0,177.1374046 +101.71,50.41379212,-3.58102134,50,-29.96123364,1.467782685,0,0,0,177.1946565 +101.72,50.41378942,-3.581021136,50,-29.96123361,1.439129019,0,0,0,177.2519084 +101.73,50.41378673,-3.581020935,50,-29.95775742,1.40958686,0,0,0,177.3091603 +101.74,50.41378404,-3.581020739,50,-29.96470978,1.378934088,0,0,0,177.3664122 +101.75,50.41378134,-3.581020547,50,-29.97513833,1.348281313,0,0,0,177.4236641 +101.76,50.41377865,-3.58102036,50,-29.9786145,1.318517022,0,0,0,177.480916 +101.77,50.41377595,-3.581020176,50,-29.97861447,1.288974851,0,0,0,177.538168 +101.78,50.41377326,-3.581019997,50,-29.97861445,1.258988432,0,0,0,177.5954199 +101.79,50.41377056,-3.581019822,50,-29.97861445,1.228779886,0,0,0,177.6526717 +101.8,50.41376787,-3.581019651,50,-29.97861445,1.198571338,0,0,0,177.7099237 +101.81,50.41376517,-3.581019485,50,-29.97861443,1.168140664,0,0,0,177.7671756 +101.82,50.41376248,-3.581019322,50,-29.97861441,1.137487866,0,0,0,177.8244275 +101.83,50.41375978,-3.581019165,50,-29.9786144,1.107723551,0,0,0,177.8816794 +101.84,50.41375709,-3.581019011,50,-29.97861438,1.079291967,0,0,0,177.9389313 +101.85,50.41375439,-3.581018861,50,-29.97861437,1.050416135,0,0,0,177.9961832 +101.86,50.4137517,-3.581018715,50,-29.97861435,1.019985444,0,0,0,178.0534352 +101.87,50.413749,-3.581018574,50,-29.97861434,0.989110505,0,0,0,178.110687 +101.88,50.41374631,-3.581018437,50,-29.97861432,0.958679808,0,0,0,178.1679389 +101.89,50.41374361,-3.581018304,50,-29.97861431,0.928693351,0,0,0,178.2251908 +101.9,50.41374092,-3.581018176,50,-29.9786143,0.899151136,0,0,0,178.2824428 +101.91,50.41373822,-3.581018051,50,-29.98209048,0.869608917,0,0,0,178.3396947 +101.92,50.41373553,-3.581017931,50,-29.99251902,0.83962245,0,0,0,178.3969466 +101.93,50.41373283,-3.581017815,50,-29.99947136,0.809413857,0,0,0,178.4541985 +101.94,50.41373013,-3.581017703,50,-29.99599515,0.779427384,0,0,0,178.5114504 +101.95,50.41372744,-3.581017596,50,-29.99599514,0.74966303,0,0,0,178.5687023 +101.96,50.41372474,-3.581017492,50,-29.99947131,0.719232304,0,0,0,178.6259542 +101.97,50.41372204,-3.581017393,50,-29.99251893,0.68835733,0,0,0,178.6832061 +101.98,50.41371935,-3.581017299,50,-29.98209038,0.658815089,0,0,0,178.740458 +101.99,50.41371665,-3.581017208,50,-29.98209036,0.630161333,0,0,0,178.7977099 +102,50.41371396,-3.581017121,50,-29.99251889,0.600396961,0,0,0,178.8549619 +102.01,50.41371126,-3.581017039,50,-29.99947124,0.569744095,0,0,0,178.9122138 +102.02,50.41370856,-3.581016961,50,-29.99599505,0.539313348,0,0,0,178.9694656 +102.03,50.41370587,-3.581016887,50,-29.99599505,0.509326844,0,0,0,179.0267176 +102.04,50.41370317,-3.581016818,50,-29.99947122,0.479784583,0,0,0,179.0839695 +102.05,50.41370047,-3.581016752,50,-29.99599502,0.450020195,0,0,0,179.1412214 +102.06,50.41369778,-3.581016691,50,-29.995995,0.419367313,0,0,0,179.1984733 +102.07,50.41369508,-3.581016634,50,-29.99947116,0.388714426,0,0,0,179.2557252 +102.08,50.41369238,-3.581016582,50,-29.99599496,0.358950028,0,0,0,179.3129771 +102.09,50.41368969,-3.581016533,50,-29.99599494,0.329407749,0,0,0,179.3702291 +102.1,50.41368699,-3.581016489,50,-29.99947113,0.299643343,0,0,0,179.4274809 +102.11,50.41368429,-3.581016449,50,-29.99599494,0.270101056,0,0,0,179.4847328 +102.12,50.4136816,-3.581016413,50,-29.99599492,0.240336644,0,0,0,179.5419847 +102.13,50.4136789,-3.581016381,50,-29.99947107,0.209683739,0,0,0,179.5992367 +102.14,50.4136762,-3.581016354,50,-29.99599487,0.179030829,0,0,0,179.6564886 +102.15,50.41367351,-3.581016331,50,-29.99947104,0.149488529,0,0,0,179.7137405 +102.16,50.41367081,-3.581016312,50,-30.01337577,0.120612593,0,0,0,179.7709924 +102.17,50.41366811,-3.581016297,50,-30.01337577,0.091292409,0,0,0,179.8282443 +102.18,50.41366541,-3.581016286,50,-29.99947103,0.062194344,0,0,0,179.8854962 +102.19,50.41366272,-3.58101628,50,-29.99599482,0.03665024,0,0,0,179.9403626 +102.2,50.41366002,-3.581016277,50,-29.99947098,0.017991936,0,0,0,179.9809161 +102.21,50.41365732,-3.581016276,50,-29.99599478,0.006885803,0,0,0,179.9976145 +102.22,50.41365463,-3.581016276,50,-29.99599478,0.001776981,0,0,0,-180 +102.23,50.41365193,-3.581016276,50,-29.99947096,0.000222123,0,0,0,-180 +102.24,50.41364923,-3.581016276,50,-29.99599475,-2.48E-11,0,0,0,-180 +102.25,50.41364654,-3.581016276,50,-29.99599472,-2.49E-11,0,0,0,-180 +102.26,50.41364384,-3.581016276,50,-29.99947089,-2.50E-13,0,0,0,-180 +102.27,50.41364114,-3.581016276,50,-29.99599471,2.44E-11,0,0,0,-180 +102.28,50.41363845,-3.581016276,50,-29.9959947,2.45E-11,0,0,0,-180 +102.29,50.41363575,-3.581016276,50,-29.99947086,0,0,0,0,-180 +102.3,50.41363305,-3.581016276,50,-29.99599465,-2.45E-11,0,0,0,-180 +102.31,50.41363036,-3.581016276,50,-29.99947082,-2.71E-11,0,0,0,-180 +102.32,50.41362766,-3.581016276,50,-30.01337555,-1.62E-11,0,0,0,-180 +102.33,50.41362496,-3.581016276,50,-30.01337554,-1.63E-11,0,0,0,-180 +102.34,50.41362226,-3.581016276,50,-29.99947079,-2.73E-11,0,0,0,-180 +102.35,50.41361957,-3.581016276,50,-29.99599459,-2.48E-11,0,0,0,-180 +102.36,50.41361687,-3.581016276,50,-29.99947076,-2.34E-13,0,0,0,-180 +102.37,50.41361417,-3.581016276,50,-29.99599456,2.44E-11,0,0,0,-180 +102.38,50.41361148,-3.581016276,50,-29.99599455,2.45E-11,0,0,0,-180 +102.39,50.41360878,-3.581016276,50,-29.99947071,1.73E-17,0,0,0,-180 +102.4,50.41360608,-3.581016276,50,-29.99599451,-2.45E-11,0,0,0,-180 +102.41,50.41360339,-3.581016276,50,-29.9959945,-2.44E-11,0,0,0,-180 +102.42,50.41360069,-3.581016276,50,-29.99947069,2.34E-13,0,0,0,-180 +102.43,50.41359799,-3.581016276,50,-29.99599449,2.48E-11,0,0,0,-180 +102.44,50.4135953,-3.581016276,50,-29.99947065,2.73E-11,0,0,0,-180 +102.45,50.4135926,-3.581016276,50,-30.01337536,1.62E-11,0,0,0,-180 +102.46,50.4135899,-3.581016276,50,-30.01337535,1.62E-11,0,0,0,-180 +102.47,50.4135872,-3.581016276,50,-29.9994706,2.71E-11,0,0,0,-180 +102.48,50.41358451,-3.581016276,50,-29.99599442,2.45E-11,0,0,0,-180 +102.49,50.41358181,-3.581016276,50,-29.99947059,-2.78E-17,0,0,0,-180 +102.5,50.41357911,-3.581016276,50,-29.99599438,-2.45E-11,0,0,0,-180 +102.51,50.41357642,-3.581016276,50,-29.99599436,-2.45E-11,0,0,0,-180 +102.52,50.41357372,-3.581016276,50,-29.99947053,-2.60E-17,0,0,0,-180 +102.53,50.41357102,-3.581016276,50,-29.99599435,2.45E-11,0,0,0,-180 +102.54,50.41356833,-3.581016276,50,-29.99599433,2.45E-11,0,0,0,-180 +102.55,50.41356563,-3.581016276,50,-29.99947049,1.73E-17,0,0,0,-180 +102.56,50.41356293,-3.581016276,50,-29.99599429,-2.45E-11,0,0,0,-180 +102.57,50.41356024,-3.581016276,50,-29.99947045,-2.72E-11,0,0,0,-180 +102.58,50.41355754,-3.581016276,50,-30.01337518,-1.64E-11,0,0,0,-180 +102.59,50.41355484,-3.581016276,50,-30.01337518,-1.66E-11,0,0,0,-180 +102.6,50.41355214,-3.581016276,50,-29.99947043,-2.76E-11,0,0,0,-180 +102.61,50.41354945,-3.581016276,50,-29.99599424,-2.48E-11,0,0,0,-180 +102.62,50.41354675,-3.581016276,50,-29.9994704,-1.56E-13,0,0,0,-180 +102.63,50.41354405,-3.581016276,50,-29.99599419,2.46E-11,0,0,0,-180 +102.64,50.41354136,-3.581016276,50,-29.99599418,2.48E-11,0,0,0,-180 +102.65,50.41353866,-3.581016276,50,-29.99947036,1.41E-13,0,0,0,-180 +102.66,50.41353596,-3.581016276,50,-29.99599415,-2.46E-11,0,0,0,-180 +102.67,50.41353327,-3.581016276,50,-29.99947033,-2.75E-11,0,0,0,-180 +102.68,50.41353057,-3.581016276,50,-30.01337505,-1.65E-11,0,0,0,-180 +102.69,50.41352787,-3.581016276,50,-30.01337504,-1.64E-11,0,0,0,-180 +102.7,50.41352517,-3.581016276,50,-29.99947029,-2.72E-11,0,0,0,-180 +102.71,50.41352248,-3.581016276,50,-29.99599408,-2.45E-11,0,0,0,-180 +102.72,50.41351978,-3.581016276,50,-29.99947025,-2.60E-17,0,0,0,-180 +102.73,50.41351708,-3.581016276,50,-29.99599405,2.45E-11,0,0,0,-180 +102.74,50.41351439,-3.581016276,50,-29.99599405,2.45E-11,0,0,0,-180 +102.75,50.41351169,-3.581016276,50,-29.99947023,1.73E-17,0,0,0,-180 +102.76,50.41350899,-3.581016276,50,-29.99599402,-2.45E-11,0,0,0,-180 +102.77,50.4135063,-3.581016276,50,-29.99599399,-2.45E-11,0,0,0,-180 +102.78,50.4135036,-3.581016276,50,-29.99947016,2.78E-17,0,0,0,-180 +102.79,50.4135009,-3.581016276,50,-29.99599398,2.45E-11,0,0,0,-180 +102.8,50.41349821,-3.581016276,50,-29.99599397,2.45E-11,0,0,0,-180 +102.81,50.41349551,-3.581016276,50,-29.99947014,2.78E-17,0,0,0,-180 +102.82,50.41349281,-3.581016276,50,-29.99599392,-2.45E-11,0,0,0,-180 +102.83,50.41349012,-3.581016276,50,-29.99947009,-2.72E-11,0,0,0,-180 +102.84,50.41348742,-3.581016276,50,-30.01337483,-1.63E-11,0,0,0,-180 +102.85,50.41348472,-3.581016276,50,-30.01337483,-1.63E-11,0,0,0,-180 +102.86,50.41348202,-3.581016276,50,-29.99947007,-2.72E-11,0,0,0,-180 +102.87,50.41347933,-3.581016276,50,-29.99599385,-2.45E-11,0,0,0,-180 +102.88,50.41347663,-3.581016276,50,-29.99947002,-1.73E-17,0,0,0,-180 +102.89,50.41347393,-3.581016276,50,-29.99599383,2.45E-11,0,0,0,-180 +102.9,50.41347124,-3.581016276,50,-29.99599382,2.45E-11,0,0,0,-180 +102.91,50.41346854,-3.581016276,50,-29.99947,-2.78E-17,0,0,0,-180 +102.92,50.41346584,-3.581016276,50,-29.9959938,-2.45E-11,0,0,0,-180 +102.93,50.41346315,-3.581016276,50,-29.99599378,-2.45E-11,0,0,0,-180 +102.94,50.41346045,-3.581016276,50,-29.99946995,9.37E-14,0,0,0,-180 +102.95,50.41345775,-3.581016276,50,-29.99599375,2.47E-11,0,0,0,-180 +102.96,50.41345506,-3.581016276,50,-29.99946992,2.75E-11,0,0,0,-180 +102.97,50.41345236,-3.581016276,50,-30.01337464,1.65E-11,0,0,0,-180 +102.98,50.41344966,-3.581016276,50,-30.01337463,1.64E-11,0,0,0,-180 +102.99,50.41344696,-3.581016276,50,-29.99946988,2.72E-11,0,0,0,-180 +103,50.41344427,-3.581016276,50,-29.99599368,2.45E-11,0,0,0,-180 +103.01,50.41344157,-3.581016276,50,-29.99946985,-9.37E-14,0,0,0,-180 +103.02,50.41343887,-3.581016276,50,-29.99599365,-2.47E-11,0,0,0,-180 +103.03,50.41343618,-3.581016276,50,-29.99599364,-2.48E-11,0,0,0,-180 +103.04,50.41343348,-3.581016276,50,-29.99946981,-1.56E-13,0,0,0,-180 +103.05,50.41343078,-3.581016276,50,-29.99599362,2.45E-11,0,0,0,-180 +103.06,50.41342809,-3.581016276,50,-29.99599361,2.45E-11,0,0,0,-180 +103.07,50.41342539,-3.581016276,50,-29.99946977,-1.56E-13,0,0,0,-180 +103.08,50.41342269,-3.581016276,50,-29.99599356,-2.48E-11,0,0,0,-180 +103.09,50.41342,-3.581016276,50,-29.99946973,-2.74E-11,0,0,0,-180 +103.1,50.4134173,-3.581016276,50,-30.01337446,-1.65E-11,0,0,0,-180 +103.11,50.4134146,-3.581016276,50,-30.01337446,-1.66E-11,0,0,0,-180 +103.12,50.4134119,-3.581016276,50,-29.99946971,-2.75E-11,0,0,0,-180 +103.13,50.41340921,-3.581016276,50,-29.9959935,-2.47E-11,0,0,0,-180 +103.14,50.41340651,-3.581016276,50,-29.99946966,-9.37E-14,0,0,0,-180 +103.15,50.41340381,-3.581016276,50,-29.99599346,2.45E-11,0,0,0,-180 +103.16,50.41340112,-3.581016276,50,-29.99599346,2.45E-11,0,0,0,-180 +103.17,50.41339842,-3.581016276,50,-29.99946964,-2.60E-17,0,0,0,-180 +103.18,50.41339572,-3.581016276,50,-29.99599344,-2.45E-11,0,0,0,-180 +103.19,50.41339303,-3.581016276,50,-29.9994696,-2.72E-11,0,0,0,-180 +103.2,50.41339033,-3.581016276,50,-30.01337432,-1.63E-11,0,0,0,-180 +103.21,50.41338763,-3.581016276,50,-30.01337431,-1.64E-11,0,0,0,-180 +103.22,50.41338493,-3.581016276,50,-29.99946956,-2.74E-11,0,0,0,-180 +103.23,50.41338224,-3.581016276,50,-29.99599336,-2.48E-11,0,0,0,-180 +103.24,50.41337954,-3.581016276,50,-29.99946953,-1.56E-13,0,0,0,-180 +103.25,50.41337684,-3.581016276,50,-29.99599333,2.45E-11,0,0,0,-180 +103.26,50.41337415,-3.581016276,50,-29.99599332,2.46E-11,0,0,0,-180 +103.27,50.41337145,-3.581016276,50,-29.99946949,7.81E-14,0,0,0,-180 +103.28,50.41336875,-3.581016276,50,-29.99599329,-2.45E-11,0,0,0,-180 +103.29,50.41336606,-3.581016276,50,-29.99599326,-2.45E-11,0,0,0,-180 +103.3,50.41336336,-3.581016276,50,-29.99946944,-2.60E-17,0,0,0,-180 +103.31,50.41336066,-3.581016276,50,-29.99599325,2.45E-11,0,0,0,-180 +103.32,50.41335797,-3.581016276,50,-29.99599325,2.45E-11,0,0,0,-180 +103.33,50.41335527,-3.581016276,50,-29.99946941,-7.81E-14,0,0,0,-180 +103.34,50.41335257,-3.581016276,50,-29.9959932,-2.46E-11,0,0,0,-180 +103.35,50.41334988,-3.581016276,50,-29.99946937,-2.74E-11,0,0,0,-180 +103.36,50.41334718,-3.581016276,50,-30.0133741,-1.65E-11,0,0,0,-180 +103.37,50.41334448,-3.581016276,50,-30.01337409,-1.66E-11,0,0,0,-180 +103.38,50.41334178,-3.581016276,50,-29.99946934,-2.75E-11,0,0,0,-180 +103.39,50.41333909,-3.581016276,50,-29.99599314,-2.47E-11,0,0,0,-180 +103.4,50.41333639,-3.581016276,50,-29.9994693,-9.37E-14,0,0,0,-180 +103.41,50.41333369,-3.581016276,50,-29.9959931,2.45E-11,0,0,0,-180 +103.42,50.413331,-3.581016276,50,-29.99599309,2.45E-11,0,0,0,-180 +103.43,50.4133283,-3.581016276,50,-29.99946927,-7.81E-14,0,0,0,-180 +103.44,50.4133256,-3.581016276,50,-29.99599308,-2.46E-11,0,0,0,-180 +103.45,50.41332291,-3.581016276,50,-29.99599306,-2.46E-11,0,0,0,-180 +103.46,50.41332021,-3.581016276,50,-29.99946922,-7.81E-14,0,0,0,-180 +103.47,50.41331751,-3.581016276,50,-29.99599303,2.45E-11,0,0,0,-180 +103.48,50.41331482,-3.581016276,50,-29.9994692,2.72E-11,0,0,0,-180 +103.49,50.41331212,-3.581016276,50,-30.01337392,1.63E-11,0,0,0,-180 +103.5,50.41330942,-3.581016276,50,-30.0133739,1.63E-11,0,0,0,-180 +103.51,50.41330672,-3.581016276,50,-29.99946914,2.72E-11,0,0,0,-180 +103.52,50.41330403,-3.581016276,50,-29.99599294,2.45E-11,0,0,0,-180 +103.53,50.41330133,-3.581016276,50,-29.99946912,-7.81E-14,0,0,0,-180 +103.54,50.41329863,-3.581016276,50,-29.99599293,-2.46E-11,0,0,0,-180 +103.55,50.41329594,-3.581016276,50,-29.99599292,-2.46E-11,0,0,0,-180 +103.56,50.41329324,-3.581016276,50,-29.99946909,-7.81E-14,0,0,0,-180 +103.57,50.41329054,-3.581016276,50,-29.99599288,2.45E-11,0,0,0,-180 +103.58,50.41328785,-3.581016276,50,-29.99599287,2.45E-11,0,0,0,-180 +103.59,50.41328515,-3.581016276,50,-29.99946904,-7.81E-14,0,0,0,-180 +103.6,50.41328245,-3.581016276,50,-29.99599285,-2.46E-11,0,0,0,-180 +103.61,50.41327976,-3.581016276,50,-29.99946902,-2.73E-11,0,0,0,-180 +103.62,50.41327706,-3.581016276,50,-30.01337373,-1.64E-11,0,0,0,-180 +103.63,50.41327436,-3.581016276,50,-30.01337372,-1.63E-11,0,0,0,-180 +103.64,50.41327166,-3.581016276,50,-29.99946897,-2.72E-11,0,0,0,-180 +103.65,50.41326897,-3.581016276,50,-29.99599277,-2.45E-11,0,0,0,-180 +103.66,50.41326627,-3.581016276,50,-29.99946893,7.81E-14,0,0,0,-180 +103.67,50.41326357,-3.581016276,50,-29.99599274,2.46E-11,0,0,0,-180 +103.68,50.41326088,-3.581016276,50,-29.99599274,2.46E-11,0,0,0,-180 +103.69,50.41325818,-3.581016276,50,-29.99946891,7.81E-14,0,0,0,-180 +103.7,50.41325548,-3.581016276,50,-29.9959927,-2.45E-11,0,0,0,-180 +103.71,50.41325279,-3.581016276,50,-29.99599268,-2.45E-11,0,0,0,-180 +103.72,50.41325009,-3.581016276,50,-29.99946885,7.81E-14,0,0,0,-180 +103.73,50.41324739,-3.581016276,50,-29.99599266,2.46E-11,0,0,0,-180 +103.74,50.4132447,-3.581016276,50,-29.99946884,2.73E-11,0,0,0,-180 +103.75,50.413242,-3.581016276,50,-30.01337356,1.64E-11,0,0,0,-180 +103.76,50.4132393,-3.581016276,50,-30.01337354,1.63E-11,0,0,0,-180 +103.77,50.4132366,-3.581016276,50,-29.99946878,2.72E-11,0,0,0,-180 +103.78,50.41323391,-3.581016276,50,-29.99599258,2.45E-11,0,0,0,-180 +103.79,50.41323121,-3.581016276,50,-29.99946875,-7.82E-14,0,0,0,-180 +103.8,50.41322851,-3.581016276,50,-29.99599256,-2.46E-11,0,0,0,-180 +103.81,50.41322582,-3.581016276,50,-29.99599256,-2.46E-11,0,0,0,-180 +103.82,50.41322312,-3.581016276,50,-29.99946873,-2.78E-17,0,0,0,-180 +103.83,50.41322042,-3.581016276,50,-29.99599252,2.46E-11,0,0,0,-180 +103.84,50.41321773,-3.581016276,50,-29.9959925,2.45E-11,0,0,0,-180 +103.85,50.41321503,-3.581016276,50,-29.99946868,-1.56E-13,0,0,0,-180 +103.86,50.41321233,-3.581016276,50,-29.99599249,-2.48E-11,0,0,0,-180 +103.87,50.41320964,-3.581016276,50,-29.99946866,-2.74E-11,0,0,0,-180 +103.88,50.41320694,-3.581016276,50,-30.01337337,-1.64E-11,0,0,0,-180 +103.89,50.41320424,-3.581016276,50,-30.01337335,-1.64E-11,0,0,0,-180 +103.9,50.41320154,-3.581016276,50,-29.9994686,-2.73E-11,0,0,0,-180 +103.91,50.41319885,-3.581016276,50,-29.99599241,-2.46E-11,0,0,0,-180 +103.92,50.41319615,-3.581016276,50,-29.99946858,-7.82E-14,0,0,0,-180 +103.93,50.41319345,-3.581016276,50,-29.99599238,2.45E-11,0,0,0,-180 +103.94,50.41319076,-3.581016276,50,-29.99599237,2.45E-11,0,0,0,-180 +103.95,50.41318806,-3.581016276,50,-29.99946854,-7.82E-14,0,0,0,-180 +103.96,50.41318536,-3.581016276,50,-29.99599234,-2.46E-11,0,0,0,-180 +103.97,50.41318267,-3.581016276,50,-29.99599232,-2.46E-11,0,0,0,-180 +103.98,50.41317997,-3.581016276,50,-29.99946848,-2.78E-17,0,0,0,-180 +103.99,50.41317727,-3.581016276,50,-29.99599229,2.46E-11,0,0,0,-180 +104,50.41317458,-3.581016276,50,-29.99946847,2.73E-11,0,0,0,-180 +104.01,50.41317188,-3.581016276,50,-30.0133732,1.64E-11,0,0,0,-180 +104.02,50.41316918,-3.581016276,50,-30.01337318,1.64E-11,0,0,0,-180 +104.03,50.41316648,-3.581016276,50,-29.99946842,2.73E-11,0,0,0,-180 +104.04,50.41316379,-3.581016276,50,-29.99599222,2.46E-11,0,0,0,-180 +104.05,50.41316109,-3.581016276,50,-29.9994684,7.81E-14,0,0,0,-180 +104.06,50.41315839,-3.581016276,50,-29.99599221,-2.45E-11,0,0,0,-180 +104.07,50.4131557,-3.581016276,50,-29.99599219,-2.45E-11,0,0,0,-180 +104.08,50.413153,-3.581016276,50,-29.99946835,7.81E-14,0,0,0,-180 +104.09,50.4131503,-3.581016276,50,-29.99599215,2.46E-11,0,0,0,-180 +104.1,50.41314761,-3.581016276,50,-29.99599214,2.46E-11,0,0,0,-180 +104.11,50.41314491,-3.581016276,50,-29.99946832,-2.78E-17,0,0,0,-180 +104.12,50.41314221,-3.581016276,50,-29.99599212,-2.46E-11,0,0,0,-180 +104.13,50.41313952,-3.581016276,50,-29.99946829,-2.73E-11,0,0,0,-180 +104.14,50.41313682,-3.581016276,50,-30.01337301,-1.64E-11,0,0,0,-180 +104.15,50.41313412,-3.581016276,50,-30.01337299,-1.64E-11,0,0,0,-180 +104.16,50.41313142,-3.581016276,50,-29.99946825,-2.73E-11,0,0,0,-180 +104.17,50.41312873,-3.581016276,50,-29.99599205,-2.46E-11,0,0,0,-180 +104.18,50.41312603,-3.581016276,50,-29.99946822,-7.82E-14,0,0,0,-180 +104.19,50.41312333,-3.581016276,50,-29.99599201,2.45E-11,0,0,0,-180 +104.2,50.41312064,-3.581016276,50,-29.99599199,2.45E-11,0,0,0,-180 +104.21,50.41311794,-3.581016276,50,-29.99946816,-7.82E-14,0,0,0,-180 +104.22,50.41311524,-3.581016276,50,-29.99599197,-2.46E-11,0,0,0,-180 +104.23,50.41311255,-3.581016276,50,-29.99599196,-2.46E-11,0,0,0,-180 +104.24,50.41310985,-3.581016276,50,-29.99946814,-2.78E-17,0,0,0,-180 +104.25,50.41310715,-3.581016276,50,-29.99599194,2.46E-11,0,0,0,-180 +104.26,50.41310446,-3.581016276,50,-29.9994681,2.73E-11,0,0,0,-180 +104.27,50.41310176,-3.581016276,50,-30.01337283,1.64E-11,0,0,0,-180 +104.28,50.41309906,-3.581016276,50,-30.01337281,1.64E-11,0,0,0,-180 +104.29,50.41309636,-3.581016276,50,-29.99946806,2.73E-11,0,0,0,-180 +104.3,50.41309367,-3.581016276,50,-29.99599186,2.46E-11,0,0,0,-180 +104.31,50.41309097,-3.581016276,50,-29.99946803,0,0,0,0,-180 +104.32,50.41308827,-3.581016276,50,-29.99599184,-2.46E-11,0,0,0,-180 +104.33,50.41308558,-3.581016276,50,-29.99599183,-2.46E-11,0,0,0,-180 +104.34,50.41308288,-3.581016276,50,-29.99946799,2.78E-17,0,0,0,-180 +104.35,50.41308018,-3.581016276,50,-29.99599178,2.46E-11,0,0,0,-180 +104.36,50.41307749,-3.581016276,50,-29.99599177,2.46E-11,0,0,0,-180 +104.37,50.41307479,-3.581016276,50,-29.99946795,2.78E-17,0,0,0,-180 +104.38,50.41307209,-3.581016276,50,-29.99599176,-2.46E-11,0,0,0,-180 +104.39,50.4130694,-3.581016276,50,-29.99946793,-2.73E-11,0,0,0,-180 +104.4,50.4130667,-3.581016276,50,-30.01337264,-1.64E-11,0,0,0,-180 +104.41,50.413064,-3.581016276,50,-30.01337262,-1.64E-11,0,0,0,-180 +104.42,50.4130613,-3.581016276,50,-29.99946788,-2.73E-11,0,0,0,-180 +104.43,50.41305861,-3.581016276,50,-29.99599168,-2.46E-11,0,0,0,-180 +104.44,50.41305591,-3.581016276,50,-29.99946785,2.78E-17,0,0,0,-180 +104.45,50.41305321,-3.581016276,50,-29.99599165,2.46E-11,0,0,0,-180 +104.46,50.41305052,-3.581016276,50,-29.99599164,2.46E-11,0,0,0,-180 +104.47,50.41304782,-3.581016276,50,-29.99946782,2.78E-17,0,0,0,-180 +104.48,50.41304512,-3.581016276,50,-29.99599161,-2.46E-11,0,0,0,-180 +104.49,50.41304243,-3.581016276,50,-29.9959916,-2.46E-11,0,0,0,-180 +104.5,50.41303973,-3.581016276,50,-29.99946777,2.78E-17,0,0,0,-180 +104.51,50.41303703,-3.581016276,50,-29.99599157,2.46E-11,0,0,0,-180 +104.52,50.41303434,-3.581016276,50,-29.99946775,2.73E-11,0,0,0,-180 +104.53,50.41303164,-3.581016276,50,-30.01337247,1.64E-11,0,0,0,-180 +104.54,50.41302894,-3.581016276,50,-30.01337245,1.64E-11,0,0,0,-180 +104.55,50.41302624,-3.581016276,50,-29.99946769,2.73E-11,0,0,0,-180 +104.56,50.41302355,-3.581016276,50,-29.99599149,2.46E-11,0,0,0,-180 +104.57,50.41302085,-3.581016276,50,-29.99946768,2.78E-17,0,0,0,-180 +104.58,50.41301815,-3.581016276,50,-29.99599149,-2.46E-11,0,0,0,-180 +104.59,50.41301546,-3.581016276,50,-29.99599146,-2.46E-11,0,0,0,-180 +104.6,50.41301276,-3.581016276,50,-29.99946762,0,0,0,0,-180 +104.61,50.41301006,-3.581016276,50,-29.99599142,2.46E-11,0,0,0,-180 +104.62,50.41300737,-3.581016276,50,-29.9959914,2.46E-11,0,0,0,-180 +104.63,50.41300467,-3.581016276,50,-29.99946758,-2.78E-17,0,0,0,-180 +104.64,50.41300197,-3.581016276,50,-29.99599139,-2.46E-11,0,0,0,-180 +104.65,50.41299928,-3.581016276,50,-29.99946757,-2.73E-11,0,0,0,-180 +104.66,50.41299658,-3.581016276,50,-30.01337229,-1.64E-11,0,0,0,-180 +104.67,50.41299388,-3.581016276,50,-30.01337228,-1.64E-11,0,0,0,-180 +104.68,50.41299118,-3.581016276,50,-29.99946753,-2.73E-11,0,0,0,-180 +104.69,50.41298849,-3.581016276,50,-29.99599132,-2.46E-11,0,0,0,-180 +104.7,50.41298579,-3.581016276,50,-29.99946748,-2.78E-17,0,0,0,-180 +104.71,50.41298309,-3.581016276,50,-29.99599128,2.46E-11,0,0,0,-180 +104.72,50.4129804,-3.581016276,50,-29.99599126,2.46E-11,0,0,0,-180 +104.73,50.4129777,-3.581016276,50,-29.99946744,-2.78E-17,0,0,0,-180 +104.74,50.412975,-3.581016276,50,-29.99599125,-2.46E-11,0,0,0,-180 +104.75,50.41297231,-3.581016276,50,-29.99599125,-2.46E-11,0,0,0,-180 +104.76,50.41296961,-3.581016276,50,-29.99946741,-2.78E-17,0,0,0,-180 +104.77,50.41296691,-3.581016276,50,-29.9959912,2.46E-11,0,0,0,-180 +104.78,50.41296422,-3.581016276,50,-29.99946737,2.73E-11,0,0,0,-180 +104.79,50.41296152,-3.581016276,50,-30.0133721,1.63E-11,0,0,0,-180 +104.8,50.41295882,-3.581016276,50,-30.01337209,1.62E-11,0,0,0,-180 +104.81,50.41295612,-3.581016276,50,-29.99946734,2.72E-11,0,0,0,-180 +104.82,50.41295343,-3.581016276,50,-29.99599114,2.45E-11,0,0,0,-180 +104.83,50.41295073,-3.581016276,50,-29.99946731,-1.56E-14,0,0,0,-180 +104.84,50.41294803,-3.581016276,50,-29.99599111,-2.46E-11,0,0,0,-180 +104.85,50.41294534,-3.581016276,50,-29.9959911,-2.46E-11,0,0,0,-180 +104.86,50.41294264,-3.581016276,50,-29.99946726,2.78E-17,0,0,0,-180 +104.87,50.41293994,-3.581016276,50,-29.99599106,2.46E-11,0,0,0,-180 +104.88,50.41293725,-3.581016276,50,-29.99599105,2.46E-11,0,0,0,-180 +104.89,50.41293455,-3.581016276,50,-29.99946723,2.78E-17,0,0,0,-180 +104.9,50.41293185,-3.581016276,50,-29.99599103,-2.46E-11,0,0,0,-180 +104.91,50.41292916,-3.581016276,50,-29.99946719,-2.73E-11,0,0,0,-180 +104.92,50.41292646,-3.581016276,50,-30.01337191,-1.63E-11,0,0,0,-180 +104.93,50.41292376,-3.581016276,50,-30.0133719,-1.62E-11,0,0,0,-180 +104.94,50.41292106,-3.581016276,50,-29.99946716,-2.70E-11,0,0,0,-180 +104.95,50.41291837,-3.581016276,50,-29.99599096,-2.42E-11,0,0,0,-180 +104.96,50.41291567,-3.581016276,50,-29.99946712,2.50E-13,0,0,0,-180 +104.97,50.41291297,-3.581016276,50,-29.99599092,2.47E-11,0,0,0,-180 +104.98,50.41291028,-3.581016276,50,-29.9959909,2.46E-11,0,0,0,-180 +104.99,50.41290758,-3.581016276,50,-29.99946708,-2.78E-17,0,0,0,-180 +105,50.41290488,-3.581016276,50,-29.99599089,-2.46E-11,0,0,0,-180 +105.01,50.41290219,-3.581016276,50,-29.99599088,-2.46E-11,0,0,0,-180 +105.02,50.41289949,-3.581016276,50,-29.99946704,-2.78E-17,0,0,0,-180 +105.03,50.41289679,-3.581016276,50,-29.99599083,2.46E-11,0,0,0,-180 +105.04,50.4128941,-3.581016276,50,-29.999467,2.74E-11,0,0,0,-180 +105.05,50.4128914,-3.581016276,50,-30.01337173,1.66E-11,0,0,0,-180 +105.06,50.4128887,-3.581016276,50,-30.01337172,1.66E-11,0,0,0,-180 +105.07,50.412886,-3.581016276,50,-29.99946698,2.74E-11,0,0,0,-180 +105.08,50.41288331,-3.581016276,50,-29.99599078,2.46E-11,0,0,0,-180 +105.09,50.41288061,-3.581016276,50,-29.99946695,2.78E-17,0,0,0,-180 +105.1,50.41287791,-3.581016276,50,-29.99599075,-2.46E-11,0,0,0,-180 +105.11,50.41287522,-3.581016276,50,-29.99599073,-2.46E-11,0,0,0,-180 +105.12,50.41287252,-3.581016276,50,-29.99946689,-1.56E-14,0,0,0,-180 +105.13,50.41286982,-3.581016276,50,-29.99599069,2.45E-11,0,0,0,-180 +105.14,50.41286713,-3.581016276,50,-29.99599069,2.45E-11,0,0,0,-180 +105.15,50.41286443,-3.581016276,50,-29.99946686,-1.56E-13,0,0,0,-180 +105.16,50.41286173,-3.581016276,50,-29.99599067,-2.47E-11,0,0,0,-180 +105.17,50.41285904,-3.581016276,50,-29.99946683,-2.74E-11,0,0,0,-180 +105.18,50.41285634,-3.581016276,50,-30.01337155,-1.64E-11,0,0,0,-180 +105.19,50.41285364,-3.581016276,50,-30.01337153,-1.64E-11,0,0,0,-180 +105.2,50.41285094,-3.581016276,50,-29.99946678,-2.74E-11,0,0,0,-180 +105.21,50.41284825,-3.581016276,50,-29.9959906,-2.47E-11,0,0,0,-180 +105.22,50.41284555,-3.581016276,50,-29.99946678,-1.56E-13,0,0,0,-180 +105.23,50.41284285,-3.581016276,50,-29.99599057,2.45E-11,0,0,0,-180 +105.24,50.41284016,-3.581016276,50,-29.99599054,2.45E-11,0,0,0,-180 +105.25,50.41283746,-3.581016276,50,-29.99946671,-1.57E-14,0,0,0,-180 +105.26,50.41283476,-3.581016276,50,-29.99599053,-2.46E-11,0,0,0,-180 +105.27,50.41283207,-3.581016276,50,-29.99599052,-2.46E-11,0,0,0,-180 +105.28,50.41282937,-3.581016276,50,-29.99946668,-1.57E-14,0,0,0,-180 +105.29,50.41282667,-3.581016276,50,-29.99599047,2.45E-11,0,0,0,-180 +105.3,50.41282398,-3.581016276,50,-29.99946664,2.72E-11,0,0,0,-180 +105.31,50.41282128,-3.581016276,50,-30.01337138,1.63E-11,0,0,0,-180 +105.32,50.41281858,-3.581016276,50,-30.01337137,1.63E-11,0,0,0,-180 +105.33,50.41281588,-3.581016276,50,-29.99946661,2.73E-11,0,0,0,-180 +105.34,50.41281319,-3.581016276,50,-29.9959904,2.47E-11,0,0,0,-180 +105.35,50.41281049,-3.581016276,50,-29.99946657,1.56E-13,0,0,0,-180 +105.36,50.41280779,-3.581016276,50,-29.99599038,-2.45E-11,0,0,0,-180 +105.37,50.4128051,-3.581016276,50,-29.99599037,-2.45E-11,0,0,0,-180 +105.38,50.4128024,-3.581016276,50,-29.99946654,1.56E-14,0,0,0,-180 +105.39,50.4127997,-3.581016276,50,-29.99599034,2.46E-11,0,0,0,-180 +105.4,50.41279701,-3.581016276,50,-29.99599032,2.47E-11,0,0,0,-180 +105.41,50.41279431,-3.581016276,50,-29.99946649,1.56E-13,0,0,0,-180 +105.42,50.41279161,-3.581016276,50,-29.9959903,-2.45E-11,0,0,0,-180 +105.43,50.41278892,-3.581016276,50,-29.99946646,-2.73E-11,0,0,0,-180 +105.44,50.41278622,-3.581016276,50,-30.01337118,-1.64E-11,0,0,0,-180 +105.45,50.41278352,-3.581016276,50,-30.01337117,-1.64E-11,0,0,0,-180 +105.46,50.41278082,-3.581016276,50,-29.99946643,-2.73E-11,0,0,0,-180 +105.47,50.41277813,-3.581016276,50,-29.99599023,-2.45E-11,0,0,0,-180 +105.48,50.41277543,-3.581016276,50,-29.9994664,1.56E-13,0,0,0,-180 +105.49,50.41277273,-3.581016276,50,-29.9959902,2.47E-11,0,0,0,-180 +105.5,50.41277004,-3.581016276,50,-29.99599018,2.46E-11,0,0,0,-180 +105.51,50.41276734,-3.581016276,50,-29.99946636,1.57E-14,0,0,0,-180 +105.52,50.41276464,-3.581016276,50,-29.99599017,-2.45E-11,0,0,0,-180 +105.53,50.41276195,-3.581016276,50,-29.99599015,-2.45E-11,0,0,0,-180 +105.54,50.41275925,-3.581016276,50,-29.99946631,1.56E-13,0,0,0,-180 +105.55,50.41275655,-3.581016276,50,-29.99599011,2.47E-11,0,0,0,-180 +105.56,50.41275386,-3.581016276,50,-29.99946628,2.73E-11,0,0,0,-180 +105.57,50.41275116,-3.581016276,50,-30.01337101,1.63E-11,0,0,0,-180 +105.58,50.41274846,-3.581016276,50,-30.013371,1.63E-11,0,0,0,-180 +105.59,50.41274576,-3.581016276,50,-29.99946625,2.72E-11,0,0,0,-180 +105.6,50.41274307,-3.581016276,50,-29.99599004,2.45E-11,0,0,0,-180 +105.61,50.41274037,-3.581016276,50,-29.99946621,-2.78E-17,0,0,0,-180 +105.62,50.41273767,-3.581016276,50,-29.99599001,-2.45E-11,0,0,0,-180 +105.63,50.41273498,-3.581016276,50,-29.99599,-2.45E-11,0,0,0,-180 +105.64,50.41273228,-3.581016276,50,-29.99946618,1.56E-13,0,0,0,-180 +105.65,50.41272958,-3.581016276,50,-29.99598999,2.47E-11,0,0,0,-180 +105.66,50.41272689,-3.581016276,50,-29.99598996,2.47E-11,0,0,0,-180 +105.67,50.41272419,-3.581016276,50,-29.99946612,1.56E-13,0,0,0,-180 +105.68,50.41272149,-3.581016276,50,-29.99598993,-2.45E-11,0,0,0,-180 +105.69,50.4127188,-3.581016276,50,-29.9994661,-2.72E-11,0,0,0,-180 +105.7,50.4127161,-3.581016276,50,-30.01337083,-1.63E-11,0,0,0,-180 +105.71,50.4127134,-3.581016276,50,-30.01337081,-1.62E-11,0,0,0,-180 +105.72,50.4127107,-3.581016276,50,-29.99946607,-2.72E-11,0,0,0,-180 +105.73,50.41270801,-3.581016276,50,-29.99598987,-2.45E-11,0,0,0,-180 +105.74,50.41270531,-3.581016276,50,-29.99946604,-2.60E-17,0,0,0,-180 +105.75,50.41270261,-3.581016276,50,-29.99598983,2.45E-11,0,0,0,-180 +105.76,50.41269992,-3.581016276,50,-29.99598981,2.45E-11,0,0,0,-180 +105.77,50.41269722,-3.581016276,50,-29.99946598,-1.56E-13,0,0,0,-180 +105.78,50.41269452,-3.581016276,50,-29.9959898,-2.47E-11,0,0,0,-180 +105.79,50.41269183,-3.581016276,50,-29.99598979,-2.47E-11,0,0,0,-180 +105.8,50.41268913,-3.581016276,50,-29.99946596,-1.56E-13,0,0,0,-180 +105.81,50.41268643,-3.581016276,50,-29.99598974,2.45E-11,0,0,0,-180 +105.82,50.41268374,-3.581016276,50,-29.99946591,2.73E-11,0,0,0,-180 +105.83,50.41268104,-3.581016276,50,-30.01337064,1.63E-11,0,0,0,-180 +105.84,50.41267834,-3.581016276,50,-30.01337063,1.63E-11,0,0,0,-180 +105.85,50.41267564,-3.581016276,50,-29.99946589,2.72E-11,0,0,0,-180 +105.86,50.41267295,-3.581016276,50,-29.99598969,2.45E-11,0,0,0,-180 +105.87,50.41267025,-3.581016276,50,-29.99946585,2.78E-17,0,0,0,-180 +105.88,50.41266755,-3.581016276,50,-29.99598966,-2.45E-11,0,0,0,-180 +105.89,50.41266486,-3.581016276,50,-29.99598965,-2.45E-11,0,0,0,-180 +105.9,50.41266216,-3.581016276,50,-29.99946582,1.41E-13,0,0,0,-180 +105.91,50.41265946,-3.581016276,50,-29.9959896,2.46E-11,0,0,0,-180 +105.92,50.41265677,-3.581016276,50,-29.99598959,2.45E-11,0,0,0,-180 +105.93,50.41265407,-3.581016276,50,-29.99946576,-1.56E-13,0,0,0,-180 +105.94,50.41265137,-3.581016276,50,-29.99598957,-2.47E-11,0,0,0,-180 +105.95,50.41264868,-3.581016276,50,-29.99946575,-2.74E-11,0,0,0,-180 +105.96,50.41264598,-3.581016276,50,-30.01337047,-1.66E-11,0,0,0,-180 +105.97,50.41264328,-3.581016276,50,-30.01337045,-1.66E-11,0,0,0,-180 +105.98,50.41264058,-3.581016276,50,-29.99946569,-2.74E-11,0,0,0,-180 +105.99,50.41263789,-3.581016276,50,-29.99598949,-2.47E-11,0,0,0,-180 +106,50.41263519,-3.581016276,50,-29.99946567,-1.56E-13,0,0,0,-180 +106.01,50.41263249,-3.581016276,50,-29.99598948,2.45E-11,0,0,0,-180 +106.02,50.4126298,-3.581016276,50,-29.99598946,2.46E-11,0,0,0,-180 +106.03,50.4126271,-3.581016276,50,-29.99946563,1.41E-13,0,0,0,-180 +106.04,50.4126244,-3.581016276,50,-29.99598943,-2.45E-11,0,0,0,-180 +106.05,50.41262171,-3.581016276,50,-29.99598942,-2.46E-11,0,0,0,-180 +106.06,50.41261901,-3.581016276,50,-29.99946559,-1.41E-13,0,0,0,-180 +106.07,50.41261631,-3.581016276,50,-29.99598939,2.45E-11,0,0,0,-180 +106.08,50.41261362,-3.581016276,50,-29.99946556,2.72E-11,0,0,0,-180 +106.09,50.41261092,-3.581016276,50,-30.01337028,1.63E-11,0,0,0,-180 +106.1,50.41260822,-3.581016276,50,-30.01337027,1.63E-11,0,0,0,-180 +106.11,50.41260552,-3.581016276,50,-29.99946552,2.72E-11,0,0,0,-180 +106.12,50.41260283,-3.581016276,50,-29.99598932,2.46E-11,0,0,0,-180 +106.13,50.41260013,-3.581016276,50,-29.99946548,1.41E-13,0,0,0,-180 +106.14,50.41259743,-3.581016276,50,-29.99598929,-2.45E-11,0,0,0,-180 +106.15,50.41259474,-3.581016276,50,-29.99598929,-2.46E-11,0,0,0,-180 +106.16,50.41259204,-3.581016276,50,-29.99946546,-1.41E-13,0,0,0,-180 +106.17,50.41258934,-3.581016276,50,-29.99598925,2.45E-11,0,0,0,-180 +106.18,50.41258665,-3.581016276,50,-29.99598922,2.45E-11,0,0,0,-180 +106.19,50.41258395,-3.581016276,50,-29.99946539,-9.38E-14,0,0,0,-180 +106.2,50.41258125,-3.581016276,50,-29.99598921,-2.48E-11,0,0,0,-180 +106.21,50.41257856,-3.581016276,50,-29.99946539,-2.75E-11,0,0,0,-180 +106.22,50.41257586,-3.581016276,50,-30.01337011,-1.64E-11,0,0,0,-180 +106.23,50.41257316,-3.581016276,50,-30.01337008,-1.63E-11,0,0,0,-180 +106.24,50.41257046,-3.581016276,50,-29.99946532,-2.72E-11,0,0,0,-180 +106.25,50.41256777,-3.581016276,50,-29.99598912,-2.46E-11,0,0,0,-180 +106.26,50.41256507,-3.581016276,50,-29.9994653,-1.41E-13,0,0,0,-180 +106.27,50.41256237,-3.581016276,50,-29.99598911,2.45E-11,0,0,0,-180 +106.28,50.41255968,-3.581016276,50,-29.9959891,2.46E-11,0,0,0,-180 +106.29,50.41255698,-3.581016276,50,-29.99946528,1.41E-13,0,0,0,-180 +106.3,50.41255428,-3.581016276,50,-29.99598907,-2.45E-11,0,0,0,-180 +106.31,50.41255159,-3.581016276,50,-29.99598906,-2.46E-11,0,0,0,-180 +106.32,50.41254889,-3.581016276,50,-29.99946522,-1.41E-13,0,0,0,-180 +106.33,50.41254619,-3.581016276,50,-29.99598902,2.45E-11,0,0,0,-180 +106.34,50.4125435,-3.581016276,50,-29.9994652,2.73E-11,0,0,0,-180 +106.35,50.4125408,-3.581016276,50,-30.01336991,1.65E-11,0,0,0,-180 +106.36,50.4125381,-3.581016276,50,-30.0133699,1.65E-11,0,0,0,-180 +106.37,50.4125354,-3.581016276,50,-29.99946515,2.73E-11,0,0,0,-180 +106.38,50.41253271,-3.581016276,50,-29.99598896,2.45E-11,0,0,0,-180 +106.39,50.41253001,-3.581016276,50,-29.99946512,-1.41E-13,0,0,0,-180 +106.4,50.41252731,-3.581016276,50,-29.99598893,-2.46E-11,0,0,0,-180 +106.41,50.41252462,-3.581016276,50,-29.99598892,-2.45E-11,0,0,0,-180 +106.42,50.41252192,-3.581016276,50,-29.99946509,1.41E-13,0,0,0,-180 +106.43,50.41251922,-3.581016276,50,-29.99598889,2.46E-11,0,0,0,-180 +106.44,50.41251653,-3.581016276,50,-29.99598887,2.45E-11,0,0,0,-180 +106.45,50.41251383,-3.581016276,50,-29.99946503,-1.41E-13,0,0,0,-180 +106.46,50.41251113,-3.581016276,50,-29.99598884,-2.46E-11,0,0,0,-180 +106.47,50.41250844,-3.581016276,50,-29.99946502,-2.72E-11,0,0,0,-180 +106.48,50.41250574,-3.581016276,50,-30.01336975,-1.62E-11,0,0,0,-180 +106.49,50.41250304,-3.581016276,50,-30.01336973,-1.62E-11,0,0,0,-180 +106.5,50.41250034,-3.581016276,50,-29.99946496,-2.72E-11,0,0,0,-180 +106.51,50.41249765,-3.581016276,50,-29.99598877,-2.46E-11,0,0,0,-180 +106.52,50.41249495,-3.581016276,50,-29.99946495,-1.56E-13,0,0,0,-180 +106.53,50.41249225,-3.581016276,50,-29.99598876,2.44E-11,0,0,0,-180 +106.54,50.41248956,-3.581016276,50,-29.99598874,2.44E-11,0,0,0,-180 +106.55,50.41248686,-3.581016276,50,-29.99946489,-1.56E-13,0,0,0,-180 +106.56,50.41248416,-3.581016276,50,-29.99598869,-2.46E-11,0,0,0,-180 +106.57,50.41248147,-3.581016276,50,-29.99598869,-2.45E-11,0,0,0,-180 +106.58,50.41247877,-3.581016276,50,-29.99946486,1.41E-13,0,0,0,-180 +106.59,50.41247607,-3.581016276,50,-29.99598867,2.46E-11,0,0,0,-180 +106.6,50.41247338,-3.581016276,50,-29.99946483,2.72E-11,0,0,0,-180 +106.61,50.41247068,-3.581016276,50,-30.01336955,1.62E-11,0,0,0,-180 +106.62,50.41246798,-3.581016276,50,-30.01336954,1.62E-11,0,0,0,-180 +106.63,50.41246528,-3.581016276,50,-29.99946479,2.72E-11,0,0,0,-180 +106.64,50.41246259,-3.581016276,50,-29.9959886,2.46E-11,0,0,0,-180 +106.65,50.41245989,-3.581016276,50,-29.99946476,1.56E-13,0,0,0,-180 +106.66,50.41245719,-3.581016276,50,-29.99598856,-2.44E-11,0,0,0,-180 +106.67,50.4124545,-3.581016276,50,-29.99598854,-2.44E-11,0,0,0,-180 +106.68,50.4124518,-3.581016276,50,-29.99946471,1.56E-13,0,0,0,-180 +106.69,50.4124491,-3.581016276,50,-29.99598852,2.46E-11,0,0,0,-180 +106.7,50.41244641,-3.581016276,50,-29.99598851,2.45E-11,0,0,0,-180 +106.71,50.41244371,-3.581016276,50,-29.99946469,-2.34E-13,0,0,0,-180 +106.72,50.41244101,-3.581016276,50,-29.99598849,-2.49E-11,0,0,0,-180 +106.73,50.41243832,-3.581016276,50,-29.99946466,-2.76E-11,0,0,0,-180 +106.74,50.41243562,-3.581016276,50,-30.01336937,-1.66E-11,0,0,0,-180 +106.75,50.41243292,-3.581016276,50,-30.01336935,-1.66E-11,0,0,0,-180 +106.76,50.41243022,-3.581016276,50,-29.9994646,-2.73E-11,0,0,0,-180 +106.77,50.41242753,-3.581016276,50,-29.9959884,-2.45E-11,0,0,0,-180 +106.78,50.41242483,-3.581016276,50,-29.99946458,2.34E-13,0,0,0,-180 +106.79,50.41242213,-3.581016276,50,-29.99598839,2.49E-11,0,0,0,-180 +106.8,50.41241944,-3.581016276,50,-29.99598838,2.49E-11,0,0,0,-180 +106.81,50.41241674,-3.581016276,50,-29.99946454,2.34E-13,0,0,0,-180 +106.82,50.41241404,-3.581016276,50,-29.99598833,-2.45E-11,0,0,0,-180 +106.83,50.41241135,-3.581016276,50,-29.99598832,-2.46E-11,0,0,0,-180 +106.84,50.41240865,-3.581016276,50,-29.99946449,-1.56E-13,0,0,0,-180 +106.85,50.41240595,-3.581016276,50,-29.99598831,2.44E-11,0,0,0,-180 +106.86,50.41240326,-3.581016276,50,-29.99946448,2.71E-11,0,0,0,-180 +106.87,50.41240056,-3.581016276,50,-30.01336919,1.62E-11,0,0,0,-180 +106.88,50.41239786,-3.581016276,50,-30.01336917,1.62E-11,0,0,0,-180 +106.89,50.41239516,-3.581016276,50,-29.99946442,2.72E-11,0,0,0,-180 +106.9,50.41239247,-3.581016276,50,-29.99598824,2.46E-11,0,0,0,-180 +106.91,50.41238977,-3.581016276,50,-29.99946441,1.56E-13,0,0,0,-180 +106.92,50.41238707,-3.581016276,50,-29.9959882,-2.44E-11,0,0,0,-180 +106.93,50.41238438,-3.581016276,50,-29.99598818,-2.44E-11,0,0,0,-180 +106.94,50.41238168,-3.581016276,50,-29.99946435,2.50E-13,0,0,0,-180 +106.95,50.41237898,-3.581016276,50,-29.99598816,2.49E-11,0,0,0,-180 +106.96,50.41237629,-3.581016276,50,-29.99598814,2.49E-11,0,0,0,-180 +106.97,50.41237359,-3.581016276,50,-29.99946431,2.50E-13,0,0,0,-180 +106.98,50.41237089,-3.581016276,50,-29.99598812,-2.44E-11,0,0,0,-180 +106.99,50.4123682,-3.581016276,50,-29.99946429,-2.71E-11,0,0,0,-180 +107,50.4123655,-3.581016276,50,-30.01336901,-1.62E-11,0,0,0,-180 +107.01,50.4123628,-3.581016276,50,-30.01336899,-1.62E-11,0,0,0,-180 +107.02,50.4123601,-3.581016276,50,-29.99946423,-2.72E-11,0,0,0,-180 +107.03,50.41235741,-3.581016276,50,-29.99598804,-2.46E-11,0,0,0,-180 +107.04,50.41235471,-3.581016276,50,-29.99946422,-1.56E-13,0,0,0,-180 +107.05,50.41235201,-3.581016276,50,-29.99598803,2.44E-11,0,0,0,-180 +107.06,50.41234932,-3.581016276,50,-29.99598801,2.44E-11,0,0,0,-180 +107.07,50.41234662,-3.581016276,50,-29.99946417,-2.50E-13,0,0,0,-180 +107.08,50.41234392,-3.581016276,50,-29.99598796,-2.49E-11,0,0,0,-180 +107.09,50.41234123,-3.581016276,50,-29.99598795,-2.49E-11,0,0,0,-180 +107.1,50.41233853,-3.581016276,50,-29.99946412,-2.50E-13,0,0,0,-180 +107.11,50.41233583,-3.581016276,50,-29.99598794,2.44E-11,0,0,0,-180 +107.12,50.41233314,-3.581016276,50,-29.99946412,2.71E-11,0,0,0,-180 +107.13,50.41233044,-3.581016276,50,-30.01336884,1.62E-11,0,0,0,-180 +107.14,50.41232774,-3.581016276,50,-30.01336882,1.62E-11,0,0,0,-180 +107.15,50.41232504,-3.581016276,50,-29.99946408,2.71E-11,0,0,0,-180 +107.16,50.41232235,-3.581016276,50,-29.99598787,2.44E-11,0,0,0,-180 +107.17,50.41231965,-3.581016276,50,-29.99946403,-2.50E-13,0,0,0,-180 +107.18,50.41231695,-3.581016276,50,-29.99598782,-2.49E-11,0,0,0,-180 +107.19,50.41231426,-3.581016276,50,-29.99598781,-2.49E-11,0,0,0,-180 +107.2,50.41231156,-3.581016276,50,-29.99946398,-2.50E-13,0,0,0,-180 +107.21,50.41230886,-3.581016276,50,-29.9959878,2.44E-11,0,0,0,-180 +107.22,50.41230617,-3.581016276,50,-29.99598779,2.44E-11,0,0,0,-180 +107.23,50.41230347,-3.581016276,50,-29.99946396,-2.50E-13,0,0,0,-180 +107.24,50.41230077,-3.581016276,50,-29.99598774,-2.49E-11,0,0,0,-180 +107.25,50.41229808,-3.581016276,50,-29.99946391,-2.76E-11,0,0,0,-180 +107.26,50.41229538,-3.581016276,50,-30.01336864,-1.67E-11,0,0,0,-180 +107.27,50.41229268,-3.581016276,50,-30.01336863,-1.67E-11,0,0,0,-180 +107.28,50.41228998,-3.581016276,50,-29.99946389,-2.76E-11,0,0,0,-180 +107.29,50.41228729,-3.581016276,50,-29.99598769,-2.49E-11,0,0,0,-180 +107.3,50.41228459,-3.581016276,50,-29.99946385,-2.50E-13,0,0,0,-180 +107.31,50.41228189,-3.581016276,50,-29.99598765,2.44E-11,0,0,0,-180 +107.32,50.4122792,-3.581016276,50,-29.99598764,2.44E-11,0,0,0,-180 +107.33,50.4122765,-3.581016276,50,-29.99946381,-2.50E-13,0,0,0,-180 +107.34,50.4122738,-3.581016276,50,-29.9959876,-2.49E-11,0,0,0,-180 +107.35,50.41227111,-3.581016276,50,-29.9959876,-2.49E-11,0,0,0,-180 +107.36,50.41226841,-3.581016276,50,-29.99946378,-2.50E-13,0,0,0,-180 +107.37,50.41226571,-3.581016276,50,-29.99598758,2.44E-11,0,0,0,-180 +107.38,50.41226302,-3.581016276,50,-29.99946374,2.72E-11,0,0,0,-180 +107.39,50.41226032,-3.581016276,50,-30.01336845,1.64E-11,0,0,0,-180 +107.4,50.41225762,-3.581016276,50,-30.01336845,1.66E-11,0,0,0,-180 +107.41,50.41225492,-3.581016276,50,-29.99946371,2.76E-11,0,0,0,-180 +107.42,50.41225223,-3.581016276,50,-29.99598751,2.49E-11,0,0,0,-180 +107.43,50.41224953,-3.581016276,50,-29.99946367,2.50E-13,0,0,0,-180 +107.44,50.41224683,-3.581016276,50,-29.99598746,-2.44E-11,0,0,0,-180 +107.45,50.41224414,-3.581016276,50,-29.99598745,-2.45E-11,0,0,0,-180 +107.46,50.41224144,-3.581016276,50,-29.99946363,0,0,0,0,-180 +107.47,50.41223874,-3.581016276,50,-29.99598744,2.45E-11,0,0,0,-180 +107.48,50.41223605,-3.581016276,50,-29.99598743,2.44E-11,0,0,0,-180 +107.49,50.41223335,-3.581016276,50,-29.99946359,-2.50E-13,0,0,0,-180 +107.5,50.41223065,-3.581016276,50,-29.99598738,-2.49E-11,0,0,0,-180 +107.51,50.41222796,-3.581016276,50,-29.99946356,-2.76E-11,0,0,0,-180 +107.52,50.41222526,-3.581016276,50,-30.01336828,-1.67E-11,0,0,0,-180 +107.53,50.41222256,-3.581016276,50,-30.01336827,-1.67E-11,0,0,0,-180 +107.54,50.41221986,-3.581016276,50,-29.99946352,-2.76E-11,0,0,0,-180 +107.55,50.41221717,-3.581016276,50,-29.99598732,-2.48E-11,0,0,0,-180 +107.56,50.41221447,-3.581016276,50,-29.99946349,-1.56E-13,0,0,0,-180 +107.57,50.41221177,-3.581016276,50,-29.99598729,2.46E-11,0,0,0,-180 +107.58,50.41220908,-3.581016276,50,-29.99598727,2.48E-11,0,0,0,-180 +107.59,50.41220638,-3.581016276,50,-29.99946344,2.34E-13,0,0,0,-180 +107.6,50.41220368,-3.581016276,50,-29.99598724,-2.44E-11,0,0,0,-180 +107.61,50.41220099,-3.581016276,50,-29.99598723,-2.45E-11,0,0,0,-180 +107.62,50.41219829,-3.581016276,50,-29.99946341,0,0,0,0,-180 +107.63,50.41219559,-3.581016276,50,-29.99598721,2.45E-11,0,0,0,-180 +107.64,50.4121929,-3.581016276,50,-29.99946338,2.71E-11,0,0,0,-180 +107.65,50.4121902,-3.581016276,50,-30.0133681,1.62E-11,0,0,0,-180 +107.66,50.4121875,-3.581016276,50,-30.01336808,1.62E-11,0,0,0,-180 +107.67,50.4121848,-3.581016276,50,-29.99946334,2.71E-11,0,0,0,-180 +107.68,50.41218211,-3.581016276,50,-29.99598714,2.45E-11,0,0,0,-180 +107.69,50.41217941,-3.581016276,50,-29.99946331,1.56E-17,0,0,0,-180 +107.7,50.41217671,-3.581016276,50,-29.99598711,-2.45E-11,0,0,0,-180 +107.71,50.41217402,-3.581016276,50,-29.99598709,-2.44E-11,0,0,0,-180 +107.72,50.41217132,-3.581016276,50,-29.99946326,2.34E-13,0,0,0,-180 +107.73,50.41216862,-3.581016276,50,-29.99598707,2.48E-11,0,0,0,-180 +107.74,50.41216593,-3.581016276,50,-29.99598707,2.46E-11,0,0,0,-180 +107.75,50.41216323,-3.581016276,50,-29.99946323,-1.56E-13,0,0,0,-180 +107.76,50.41216053,-3.581016276,50,-29.99598702,-2.48E-11,0,0,0,-180 +107.77,50.41215784,-3.581016276,50,-29.99946319,-2.76E-11,0,0,0,-180 +107.78,50.41215514,-3.581016276,50,-30.01336792,-1.66E-11,0,0,0,-180 +107.79,50.41215244,-3.581016276,50,-30.01336792,-1.64E-11,0,0,0,-180 +107.8,50.41214974,-3.581016276,50,-29.99946316,-2.72E-11,0,0,0,-180 +107.81,50.41214705,-3.581016276,50,-29.99598695,-2.45E-11,0,0,0,-180 +107.82,50.41214435,-3.581016276,50,-29.99946312,2.60E-17,0,0,0,-180 +107.83,50.41214165,-3.581016276,50,-29.99598692,2.45E-11,0,0,0,-180 +107.84,50.41213896,-3.581016276,50,-29.99598692,2.44E-11,0,0,0,-180 +107.85,50.41213626,-3.581016276,50,-29.99946309,-2.34E-13,0,0,0,-180 +107.86,50.41213356,-3.581016276,50,-29.99598689,-2.48E-11,0,0,0,-180 +107.87,50.41213087,-3.581016276,50,-29.99598687,-2.46E-11,0,0,0,-180 +107.88,50.41212817,-3.581016276,50,-29.99946304,1.56E-13,0,0,0,-180 +107.89,50.41212547,-3.581016276,50,-29.99598684,2.48E-11,0,0,0,-180 +107.9,50.41212278,-3.581016276,50,-29.99946301,2.76E-11,0,0,0,-180 +107.91,50.41212008,-3.581016276,50,-30.01336773,1.66E-11,0,0,0,-180 +107.92,50.41211738,-3.581016276,50,-30.01336772,1.64E-11,0,0,0,-180 +107.93,50.41211468,-3.581016276,50,-29.99946298,2.72E-11,0,0,0,-180 +107.94,50.41211199,-3.581016276,50,-29.99598678,2.45E-11,0,0,0,-180 +107.95,50.41210929,-3.581016276,50,-29.99946294,0,0,0,0,-180 +107.96,50.41210659,-3.581016276,50,-29.99598674,-2.45E-11,0,0,0,-180 +107.97,50.4121039,-3.581016276,50,-29.99598673,-2.45E-11,0,0,0,-180 +107.98,50.4121012,-3.581016276,50,-29.99946291,0,0,0,0,-180 +107.99,50.4120985,-3.581016276,50,-29.99598671,2.45E-11,0,0,0,-180 +108,50.41209581,-3.581016276,50,-29.99598669,2.45E-11,0,0,0,-180 +108.01,50.41209311,-3.581016276,50,-29.99946285,0,0,0,0,-180 +108.02,50.41209041,-3.581016276,50,-29.99598665,-2.45E-11,0,0,0,-180 +108.03,50.41208772,-3.581016276,50,-29.99946282,-2.72E-11,0,0,0,-180 +108.04,50.41208502,-3.581016276,50,-30.01336755,-1.64E-11,0,0,0,-180 +108.05,50.41208232,-3.581016276,50,-30.01336755,-1.65E-11,0,0,0,-180 +108.06,50.41207962,-3.581016276,50,-29.9994628,-2.75E-11,0,0,0,-180 +108.07,50.41207693,-3.581016276,50,-29.99598659,-2.46E-11,0,0,0,-180 +108.08,50.41207423,-3.581016276,50,-29.99946275,1.56E-13,0,0,0,-180 +108.09,50.41207153,-3.581016276,50,-29.99598655,2.48E-11,0,0,0,-180 +108.1,50.41206884,-3.581016276,50,-29.99598655,2.48E-11,0,0,0,-180 +108.11,50.41206614,-3.581016276,50,-29.99946273,1.56E-13,0,0,0,-180 +108.12,50.41206344,-3.581016276,50,-29.99598653,-2.46E-11,0,0,0,-180 +108.13,50.41206075,-3.581016276,50,-29.99598651,-2.48E-11,0,0,0,-180 +108.14,50.41205805,-3.581016276,50,-29.99946267,-1.41E-13,0,0,0,-180 +108.15,50.41205535,-3.581016276,50,-29.99598648,2.46E-11,0,0,0,-180 +108.16,50.41205266,-3.581016276,50,-29.99946265,2.75E-11,0,0,0,-180 +108.17,50.41204996,-3.581016276,50,-30.01336737,1.66E-11,0,0,0,-180 +108.18,50.41204726,-3.581016276,50,-30.01336736,1.65E-11,0,0,0,-180 +108.19,50.41204456,-3.581016276,50,-29.99946261,2.74E-11,0,0,0,-180 +108.2,50.41204187,-3.581016276,50,-29.99598642,2.48E-11,0,0,0,-180 +108.21,50.41203917,-3.581016276,50,-29.99946258,1.41E-13,0,0,0,-180 +108.22,50.41203647,-3.581016276,50,-29.99598638,-2.46E-11,0,0,0,-180 +108.23,50.41203378,-3.581016276,50,-29.99598637,-2.47E-11,0,0,0,-180 +108.24,50.41203108,-3.581016276,50,-29.99946254,-1.41E-13,0,0,0,-180 +108.25,50.41202838,-3.581016276,50,-29.99598635,2.46E-11,0,0,0,-180 +108.26,50.41202569,-3.581016276,50,-29.99598633,2.47E-11,0,0,0,-180 +108.27,50.41202299,-3.581016276,50,-29.99946249,1.56E-13,0,0,0,-180 +108.28,50.41202029,-3.581016276,50,-29.99598629,-2.45E-11,0,0,0,-180 +108.29,50.4120176,-3.581016276,50,-29.99946246,-2.72E-11,0,0,0,-180 +108.3,50.4120149,-3.581016276,50,-30.01336719,-1.63E-11,0,0,0,-180 +108.31,50.4120122,-3.581016276,50,-30.01336718,-1.63E-11,0,0,0,-180 +108.32,50.4120095,-3.581016276,50,-29.99946243,-2.73E-11,0,0,0,-180 +108.33,50.41200681,-3.581016276,50,-29.99598623,-2.47E-11,0,0,0,-180 +108.34,50.41200411,-3.581016276,50,-29.9994624,-1.56E-13,0,0,0,-180 +108.35,50.41200141,-3.581016276,50,-29.99598621,2.45E-11,0,0,0,-180 +108.36,50.41199872,-3.581016276,50,-29.9959862,2.45E-11,0,0,0,-180 +108.37,50.41199602,-3.581016276,50,-29.99946236,-1.56E-13,0,0,0,-180 +108.38,50.41199332,-3.581016276,50,-29.99598615,-2.48E-11,0,0,0,-180 +108.39,50.41199063,-3.581016276,50,-29.99598613,-2.46E-11,0,0,0,-180 +108.4,50.41198793,-3.581016276,50,-29.99946231,1.41E-13,0,0,0,-180 +108.41,50.41198523,-3.581016276,50,-29.99598612,2.48E-11,0,0,0,-180 +108.42,50.41198254,-3.581016276,50,-29.99946229,2.74E-11,0,0,0,-180 +108.43,50.41197984,-3.581016276,50,-30.01336701,1.65E-11,0,0,0,-180 +108.44,50.41197714,-3.581016276,50,-30.01336699,1.66E-11,0,0,0,-180 +108.45,50.41197444,-3.581016276,50,-29.99946223,2.75E-11,0,0,0,-180 +108.46,50.41197175,-3.581016276,50,-29.99598604,2.47E-11,0,0,0,-180 +108.47,50.41196905,-3.581016276,50,-29.99946222,9.38E-14,0,0,0,-180 +108.48,50.41196635,-3.581016276,50,-29.99598603,-2.45E-11,0,0,0,-180 +108.49,50.41196366,-3.581016276,50,-29.99598601,-2.45E-11,0,0,0,-180 +108.5,50.41196096,-3.581016276,50,-29.99946217,0,0,0,0,-180 +108.51,50.41195826,-3.581016276,50,-29.99598597,2.45E-11,0,0,0,-180 +108.52,50.41195557,-3.581016276,50,-29.99598596,2.45E-11,0,0,0,-180 +108.53,50.41195287,-3.581016276,50,-29.99946214,-9.38E-14,0,0,0,-180 +108.54,50.41195017,-3.581016276,50,-29.99598594,-2.47E-11,0,0,0,-180 +108.55,50.41194748,-3.581016276,50,-29.99946211,-2.75E-11,0,0,0,-180 +108.56,50.41194478,-3.581016276,50,-30.01336682,-1.66E-11,0,0,0,-180 +108.57,50.41194208,-3.581016276,50,-30.01336681,-1.65E-11,0,0,0,-180 +108.58,50.41193938,-3.581016276,50,-29.99946206,-2.73E-11,0,0,0,-180 +108.59,50.41193669,-3.581016276,50,-29.99598586,-2.45E-11,0,0,0,-180 +108.6,50.41193399,-3.581016276,50,-29.99946203,1.56E-13,0,0,0,-180 +108.61,50.41193129,-3.581016276,50,-29.99598584,2.48E-11,0,0,0,-180 +108.62,50.4119286,-3.581016276,50,-29.99598583,2.47E-11,0,0,0,-180 +108.63,50.4119259,-3.581016276,50,-29.999462,9.37E-14,0,0,0,-180 +108.64,50.4119232,-3.581016276,50,-29.99598579,-2.45E-11,0,0,0,-180 +108.65,50.41192051,-3.581016276,50,-29.99598577,-2.45E-11,0,0,0,-180 +108.66,50.41191781,-3.581016276,50,-29.99946194,9.37E-14,0,0,0,-180 +108.67,50.41191511,-3.581016276,50,-29.99598575,2.47E-11,0,0,0,-180 +108.68,50.41191242,-3.581016276,50,-29.99946193,2.75E-11,0,0,0,-180 +108.69,50.41190972,-3.581016276,50,-30.01336665,1.66E-11,0,0,0,-180 +108.7,50.41190702,-3.581016276,50,-30.01336663,1.65E-11,0,0,0,-180 +108.71,50.41190432,-3.581016276,50,-29.99946187,2.73E-11,0,0,0,-180 +108.72,50.41190163,-3.581016276,50,-29.99598567,2.45E-11,0,0,0,-180 +108.73,50.41189893,-3.581016276,50,-29.99946185,-1.56E-13,0,0,0,-180 +108.74,50.41189623,-3.581016276,50,-29.99598567,-2.48E-11,0,0,0,-180 +108.75,50.41189354,-3.581016276,50,-29.99598565,-2.47E-11,0,0,0,-180 +108.76,50.41189084,-3.581016276,50,-29.99946181,-9.37E-14,0,0,0,-180 +108.77,50.41188814,-3.581016276,50,-29.99598561,2.45E-11,0,0,0,-180 +108.78,50.41188545,-3.581016276,50,-29.9959856,2.45E-11,0,0,0,-180 +108.79,50.41188275,-3.581016276,50,-29.99946177,-7.81E-14,0,0,0,-180 +108.8,50.41188005,-3.581016276,50,-29.99598557,-2.46E-11,0,0,0,-180 +108.81,50.41187736,-3.581016276,50,-29.99946174,-2.74E-11,0,0,0,-180 +108.82,50.41187466,-3.581016276,50,-30.01336646,-1.65E-11,0,0,0,-180 +108.83,50.41187196,-3.581016276,50,-30.01336644,-1.66E-11,0,0,0,-180 +108.84,50.41186926,-3.581016276,50,-29.9994617,-2.75E-11,0,0,0,-180 +108.85,50.41186657,-3.581016276,50,-29.9959855,-2.47E-11,0,0,0,-180 +108.86,50.41186387,-3.581016276,50,-29.99946167,-9.37E-14,0,0,0,-180 +108.87,50.41186117,-3.581016276,50,-29.99598547,2.45E-11,0,0,0,-180 +108.88,50.41185848,-3.581016276,50,-29.99598546,2.45E-11,0,0,0,-180 +108.89,50.41185578,-3.581016276,50,-29.99946163,-7.81E-14,0,0,0,-180 +108.9,50.41185308,-3.581016276,50,-29.99598543,-2.46E-11,0,0,0,-180 +108.91,50.41185039,-3.581016276,50,-29.99598541,-2.46E-11,0,0,0,-180 +108.92,50.41184769,-3.581016276,50,-29.99946158,-7.81E-14,0,0,0,-180 +108.93,50.41184499,-3.581016276,50,-29.99598538,2.45E-11,0,0,0,-180 +108.94,50.4118423,-3.581016276,50,-29.99946156,2.72E-11,0,0,0,-180 +108.95,50.4118396,-3.581016276,50,-30.01336629,1.63E-11,0,0,0,-180 +108.96,50.4118369,-3.581016276,50,-30.01336627,1.64E-11,0,0,0,-180 +108.97,50.4118342,-3.581016276,50,-29.99946151,2.73E-11,0,0,0,-180 +108.98,50.41183151,-3.581016276,50,-29.99598531,2.46E-11,0,0,0,-180 +108.99,50.41182881,-3.581016276,50,-29.99946149,7.81E-14,0,0,0,-180 +109,50.41182611,-3.581016276,50,-29.99598531,-2.45E-11,0,0,0,-180 +109.01,50.41182342,-3.581016276,50,-29.99598528,-2.45E-11,0,0,0,-180 +109.02,50.41182072,-3.581016276,50,-29.99946144,7.81E-14,0,0,0,-180 +109.03,50.41181802,-3.581016276,50,-29.99598524,2.46E-11,0,0,0,-180 +109.04,50.41181533,-3.581016276,50,-29.99598524,2.46E-11,0,0,0,-180 +109.05,50.41181263,-3.581016276,50,-29.99946142,7.81E-14,0,0,0,-180 +109.06,50.41180993,-3.581016276,50,-29.99598521,-2.45E-11,0,0,0,-180 +109.07,50.41180724,-3.581016276,50,-29.99946137,-2.72E-11,0,0,0,-180 +109.08,50.41180454,-3.581016276,50,-30.01336609,-1.63E-11,0,0,0,-180 +109.09,50.41180184,-3.581016276,50,-30.01336608,-1.64E-11,0,0,0,-180 +109.1,50.41179914,-3.581016276,50,-29.99946134,-2.73E-11,0,0,0,-180 +109.11,50.41179645,-3.581016276,50,-29.99598514,-2.46E-11,0,0,0,-180 +109.12,50.41179375,-3.581016276,50,-29.99946131,-7.81E-14,0,0,0,-180 +109.13,50.41179105,-3.581016276,50,-29.99598511,2.45E-11,0,0,0,-180 +109.14,50.41178836,-3.581016276,50,-29.99598509,2.45E-11,0,0,0,-180 +109.15,50.41178566,-3.581016276,50,-29.99946127,-7.81E-14,0,0,0,-180 +109.16,50.41178296,-3.581016276,50,-29.99598506,-2.46E-11,0,0,0,-180 +109.17,50.41178027,-3.581016276,50,-29.99598505,-2.46E-11,0,0,0,-180 +109.18,50.41177757,-3.581016276,50,-29.99946122,-7.81E-14,0,0,0,-180 +109.19,50.41177487,-3.581016276,50,-29.99598504,2.45E-11,0,0,0,-180 +109.2,50.41177218,-3.581016276,50,-29.99946121,2.72E-11,0,0,0,-180 +109.21,50.41176948,-3.581016276,50,-30.01336592,1.63E-11,0,0,0,-180 +109.22,50.41176678,-3.581016276,50,-30.01336589,1.64E-11,0,0,0,-180 +109.23,50.41176408,-3.581016276,50,-29.99946114,2.73E-11,0,0,0,-180 +109.24,50.41176139,-3.581016276,50,-29.99598495,2.46E-11,0,0,0,-180 +109.25,50.41175869,-3.581016276,50,-29.99946112,1.56E-17,0,0,0,-180 +109.26,50.41175599,-3.581016276,50,-29.99598494,-2.46E-11,0,0,0,-180 +109.27,50.4117533,-3.581016276,50,-29.99598492,-2.46E-11,0,0,0,-180 +109.28,50.4117506,-3.581016276,50,-29.99946108,-7.81E-14,0,0,0,-180 +109.29,50.4117479,-3.581016276,50,-29.99598488,2.45E-11,0,0,0,-180 +109.3,50.41174521,-3.581016276,50,-29.99598486,2.45E-11,0,0,0,-180 +109.31,50.41174251,-3.581016276,50,-29.99946104,-7.81E-14,0,0,0,-180 +109.32,50.41173981,-3.581016276,50,-29.99598485,-2.46E-11,0,0,0,-180 +109.33,50.41173712,-3.581016276,50,-29.99946102,-2.73E-11,0,0,0,-180 +109.34,50.41173442,-3.581016276,50,-30.01336573,-1.64E-11,0,0,0,-180 +109.35,50.41173172,-3.581016276,50,-30.01336571,-1.64E-11,0,0,0,-180 +109.36,50.41172902,-3.581016276,50,-29.99946097,-2.73E-11,0,0,0,-180 +109.37,50.41172633,-3.581016276,50,-29.99598478,-2.46E-11,0,0,0,-180 +109.38,50.41172363,-3.581016276,50,-29.99946095,-7.81E-14,0,0,0,-180 +109.39,50.41172093,-3.581016276,50,-29.99598475,2.45E-11,0,0,0,-180 +109.4,50.41171824,-3.581016276,50,-29.99598472,2.45E-11,0,0,0,-180 +109.41,50.41171554,-3.581016276,50,-29.9994609,-7.81E-14,0,0,0,-180 +109.42,50.41171284,-3.581016276,50,-29.99598471,-2.46E-11,0,0,0,-180 +109.43,50.41171015,-3.581016276,50,-29.99598469,-2.46E-11,0,0,0,-180 +109.44,50.41170745,-3.581016276,50,-29.99946086,1.73E-17,0,0,0,-180 +109.45,50.41170475,-3.581016276,50,-29.99598467,2.46E-11,0,0,0,-180 +109.46,50.41170206,-3.581016276,50,-29.99946084,2.73E-11,0,0,0,-180 +109.47,50.41169936,-3.581016276,50,-30.01336556,1.64E-11,0,0,0,-180 +109.48,50.41169666,-3.581016276,50,-30.01336554,1.63E-11,0,0,0,-180 +109.49,50.41169396,-3.581016276,50,-29.99946078,2.72E-11,0,0,0,-180 +109.5,50.41169127,-3.581016276,50,-29.99598458,2.45E-11,0,0,0,-180 +109.51,50.41168857,-3.581016276,50,-29.99946077,-7.81E-14,0,0,0,-180 +109.52,50.41168587,-3.581016276,50,-29.99598458,-2.46E-11,0,0,0,-180 +109.53,50.41168318,-3.581016276,50,-29.99598456,-2.46E-11,0,0,0,-180 +109.54,50.41168048,-3.581016276,50,-29.99946071,1.73E-17,0,0,0,-180 +109.55,50.41167778,-3.581016276,50,-29.99598452,2.46E-11,0,0,0,-180 +109.56,50.41167509,-3.581016276,50,-29.99598451,2.46E-11,0,0,0,-180 +109.57,50.41167239,-3.581016276,50,-29.99946069,1.04E-17,0,0,0,-180 +109.58,50.41166969,-3.581016276,50,-29.99598449,-2.46E-11,0,0,0,-180 +109.59,50.411667,-3.581016276,50,-29.99946064,-2.73E-11,0,0,0,-180 +109.6,50.4116643,-3.581016276,50,-30.01336536,-1.64E-11,0,0,0,-180 +109.61,50.4116616,-3.581016276,50,-30.01336536,-1.64E-11,0,0,0,-180 +109.62,50.4116589,-3.581016276,50,-29.99946062,-2.73E-11,0,0,0,-180 +109.63,50.41165621,-3.581016276,50,-29.99598442,-2.46E-11,0,0,0,-180 +109.64,50.41165351,-3.581016276,50,-29.99946057,-1.04E-17,0,0,0,-180 +109.65,50.41165081,-3.581016276,50,-29.99598437,2.46E-11,0,0,0,-180 +109.66,50.41164812,-3.581016276,50,-29.99598436,2.46E-11,0,0,0,-180 +109.67,50.41164542,-3.581016276,50,-29.99946053,7.81E-14,0,0,0,-180 +109.68,50.41164272,-3.581016276,50,-29.99598435,-2.45E-11,0,0,0,-180 +109.69,50.41164003,-3.581016276,50,-29.99598434,-2.45E-11,0,0,0,-180 +109.7,50.41163733,-3.581016276,50,-29.9994605,7.81E-14,0,0,0,-180 +109.71,50.41163463,-3.581016276,50,-29.99598429,2.46E-11,0,0,0,-180 +109.72,50.41163194,-3.581016276,50,-29.99946046,2.73E-11,0,0,0,-180 +109.73,50.41162924,-3.581016276,50,-30.01336519,1.64E-11,0,0,0,-180 +109.74,50.41162654,-3.581016276,50,-30.01336518,1.64E-11,0,0,0,-180 +109.75,50.41162384,-3.581016276,50,-29.99946043,2.73E-11,0,0,0,-180 +109.76,50.41162115,-3.581016276,50,-29.99598423,2.46E-11,0,0,0,-180 +109.77,50.41161845,-3.581016276,50,-29.9994604,0,0,0,0,-180 +109.78,50.41161575,-3.581016276,50,-29.9959842,-2.46E-11,0,0,0,-180 +109.79,50.41161306,-3.581016276,50,-29.99598419,-2.46E-11,0,0,0,-180 +109.8,50.41161036,-3.581016276,50,-29.99946035,0,0,0,0,-180 +109.81,50.41160766,-3.581016276,50,-29.99598415,2.46E-11,0,0,0,-180 +109.82,50.41160497,-3.581016276,50,-29.99598414,2.46E-11,0,0,0,-180 +109.83,50.41160227,-3.581016276,50,-29.99946032,-1.04E-17,0,0,0,-180 +109.84,50.41159957,-3.581016276,50,-29.99598413,-2.46E-11,0,0,0,-180 +109.85,50.41159688,-3.581016276,50,-29.99946029,-2.73E-11,0,0,0,-180 +109.86,50.41159418,-3.581016276,50,-30.013365,-1.64E-11,0,0,0,-180 +109.87,50.41159148,-3.581016276,50,-30.01336499,-1.64E-11,0,0,0,-180 +109.88,50.41158878,-3.581016276,50,-29.99946025,-2.73E-11,0,0,0,-180 +109.89,50.41158609,-3.581016276,50,-29.99598406,-2.46E-11,0,0,0,-180 +109.9,50.41158339,-3.581016276,50,-29.99946022,-1.56E-17,0,0,0,-180 +109.91,50.41158069,-3.581016276,50,-29.99598401,2.46E-11,0,0,0,-180 +109.92,50.411578,-3.581016276,50,-29.995984,2.46E-11,0,0,0,-180 +109.93,50.4115753,-3.581016276,50,-29.99946017,1.73E-17,0,0,0,-180 +109.94,50.4115726,-3.581016276,50,-29.99598399,-2.46E-11,0,0,0,-180 +109.95,50.41156991,-3.581016276,50,-29.99598397,-2.46E-11,0,0,0,-180 +109.96,50.41156721,-3.581016276,50,-29.99946013,1.73E-17,0,0,0,-180 +109.97,50.41156451,-3.581016276,50,-29.99598393,2.46E-11,0,0,0,-180 +109.98,50.41156182,-3.581016276,50,-29.9994601,2.73E-11,0,0,0,-180 +109.99,50.41155912,-3.581016276,50,-30.01336483,1.64E-11,0,0,0,-180 +110,50.41155642,-3.581016276,50,-30.01336481,1.64E-11,0,0,0,-180 +110.01,50.41155372,-3.581016276,50,-29.99946006,2.73E-11,0,0,0,-180 +110.02,50.41155103,-3.581016276,50,-29.99598387,2.46E-11,0,0,0,-180 +110.03,50.41154833,-3.581016276,50,-29.99946004,-1.73E-17,0,0,0,-180 +110.04,50.41154563,-3.581016276,50,-29.99598384,-2.46E-11,0,0,0,-180 +110.05,50.41154294,-3.581016276,50,-29.99598382,-2.47E-11,0,0,0,-180 +110.06,50.41154024,-3.581016276,50,-29.99945998,-2.34E-13,0,0,0,-180 +110.07,50.41153754,-3.581016276,50,-29.99598379,2.43E-11,0,0,0,-180 +110.08,50.41153485,-3.581016276,50,-29.99598378,2.45E-11,0,0,0,-180 +110.09,50.41153215,-3.581016276,50,-29.99945995,1.56E-13,0,0,0,-180 +110.1,50.41152945,-3.581016276,50,-29.99598376,-2.42E-11,0,0,0,-180 +110.11,50.41152676,-3.581016276,50,-29.99945993,-2.70E-11,0,0,0,-180 +110.12,50.41152406,-3.581016276,50,-30.01336464,-1.62E-11,0,0,0,-180 +110.13,50.41152136,-3.581016276,50,-30.01336463,-1.63E-11,0,0,0,-180 +110.14,50.41151866,-3.581016276,50,-29.99945988,-2.73E-11,0,0,0,-180 +110.15,50.41151597,-3.581016276,50,-29.99598369,-2.46E-11,0,0,0,-180 +110.16,50.41151327,-3.581016276,50,-29.99945986,1.04E-17,0,0,0,-180 +110.17,50.41151057,-3.581016276,50,-29.99598365,2.46E-11,0,0,0,-180 +110.18,50.41150788,-3.581016276,50,-29.99598363,2.46E-11,0,0,0,-180 +110.19,50.41150518,-3.581016276,50,-29.9994598,1.56E-17,0,0,0,-180 +110.2,50.41150248,-3.581016276,50,-29.99598362,-2.46E-11,0,0,0,-180 +110.21,50.41149979,-3.581016276,50,-29.99598361,-2.46E-11,0,0,0,-180 +110.22,50.41149709,-3.581016276,50,-29.99945978,-1.73E-17,0,0,0,-180 +110.23,50.41149439,-3.581016276,50,-29.99598356,2.46E-11,0,0,0,-180 +110.24,50.4114917,-3.581016276,50,-29.99945973,2.73E-11,0,0,0,-180 +110.25,50.411489,-3.581016276,50,-30.01336447,1.63E-11,0,0,0,-180 +110.26,50.4114863,-3.581016276,50,-30.01336446,1.62E-11,0,0,0,-180 +110.27,50.4114836,-3.581016276,50,-29.99945971,2.70E-11,0,0,0,-180 +110.28,50.41148091,-3.581016276,50,-29.99598349,2.42E-11,0,0,0,-180 +110.29,50.41147821,-3.581016276,50,-29.99945966,-2.50E-13,0,0,0,-180 +110.3,50.41147551,-3.581016276,50,-29.99598347,-2.47E-11,0,0,0,-180 +110.31,50.41147282,-3.581016276,50,-29.99598346,-2.46E-11,0,0,0,-180 +110.32,50.41147012,-3.581016276,50,-29.99945964,-1.04E-17,0,0,0,-180 +110.33,50.41146742,-3.581016276,50,-29.99598344,2.46E-11,0,0,0,-180 +110.34,50.41146473,-3.581016276,50,-29.99598342,2.46E-11,0,0,0,-180 +110.35,50.41146203,-3.581016276,50,-29.99945959,0,0,0,0,-180 +110.36,50.41145933,-3.581016276,50,-29.99598339,-2.46E-11,0,0,0,-180 +110.37,50.41145664,-3.581016276,50,-29.99945956,-2.73E-11,0,0,0,-180 +110.38,50.41145394,-3.581016276,50,-30.01336427,-1.63E-11,0,0,0,-180 +110.39,50.41145124,-3.581016276,50,-30.01336426,-1.63E-11,0,0,0,-180 +110.4,50.41144854,-3.581016276,50,-29.99945953,-2.72E-11,0,0,0,-180 +110.41,50.41144585,-3.581016276,50,-29.99598333,-2.45E-11,0,0,0,-180 +110.42,50.41144315,-3.581016276,50,-29.99945949,1.56E-14,0,0,0,-180 +110.43,50.41144045,-3.581016276,50,-29.99598328,2.46E-11,0,0,0,-180 +110.44,50.41143776,-3.581016276,50,-29.99598328,2.46E-11,0,0,0,-180 +110.45,50.41143506,-3.581016276,50,-29.99945946,1.73E-17,0,0,0,-180 +110.46,50.41143236,-3.581016276,50,-29.99598326,-2.46E-11,0,0,0,-180 +110.47,50.41142967,-3.581016276,50,-29.99598324,-2.47E-11,0,0,0,-180 +110.48,50.41142697,-3.581016276,50,-29.9994594,-2.50E-13,0,0,0,-180 +110.49,50.41142427,-3.581016276,50,-29.9959832,2.42E-11,0,0,0,-180 +110.5,50.41142158,-3.581016276,50,-29.99945937,2.70E-11,0,0,0,-180 +110.51,50.41141888,-3.581016276,50,-30.0133641,1.62E-11,0,0,0,-180 +110.52,50.41141618,-3.581016276,50,-30.01336409,1.63E-11,0,0,0,-180 +110.53,50.41141348,-3.581016276,50,-29.99945935,2.73E-11,0,0,0,-180 +110.54,50.41141079,-3.581016276,50,-29.99598314,2.46E-11,0,0,0,-180 +110.55,50.41140809,-3.581016276,50,-29.99945931,1.56E-14,0,0,0,-180 +110.56,50.41140539,-3.581016276,50,-29.99598311,-2.45E-11,0,0,0,-180 +110.57,50.4114027,-3.581016276,50,-29.9959831,-2.45E-11,0,0,0,-180 +110.58,50.4114,-3.581016276,50,-29.99945927,1.56E-13,0,0,0,-180 +110.59,50.4113973,-3.581016276,50,-29.99598307,2.47E-11,0,0,0,-180 +110.6,50.41139461,-3.581016276,50,-29.99598305,2.46E-11,0,0,0,-180 +110.61,50.41139191,-3.581016276,50,-29.99945922,1.56E-17,0,0,0,-180 +110.62,50.41138921,-3.581016276,50,-29.99598302,-2.46E-11,0,0,0,-180 +110.63,50.41138652,-3.581016276,50,-29.9994592,-2.74E-11,0,0,0,-180 +110.64,50.41138382,-3.581016276,50,-30.01336391,-1.66E-11,0,0,0,-180 +110.65,50.41138112,-3.581016276,50,-30.0133639,-1.66E-11,0,0,0,-180 +110.66,50.41137842,-3.581016276,50,-29.99945916,-2.74E-11,0,0,0,-180 +110.67,50.41137573,-3.581016276,50,-29.99598296,-2.46E-11,0,0,0,-180 +110.68,50.41137303,-3.581016276,50,-29.99945913,1.73E-17,0,0,0,-180 +110.69,50.41137033,-3.581016276,50,-29.99598293,2.46E-11,0,0,0,-180 +110.7,50.41136764,-3.581016276,50,-29.99598291,2.47E-11,0,0,0,-180 +110.71,50.41136494,-3.581016276,50,-29.99945909,1.56E-13,0,0,0,-180 +110.72,50.41136224,-3.581016276,50,-29.99598289,-2.45E-11,0,0,0,-180 +110.73,50.41135955,-3.581016276,50,-29.99598288,-2.45E-11,0,0,0,-180 +110.74,50.41135685,-3.581016276,50,-29.99945904,1.56E-14,0,0,0,-180 +110.75,50.41135415,-3.581016276,50,-29.99598284,2.46E-11,0,0,0,-180 +110.76,50.41135146,-3.581016276,50,-29.99945901,2.74E-11,0,0,0,-180 +110.77,50.41134876,-3.581016276,50,-30.01336374,1.66E-11,0,0,0,-180 +110.78,50.41134606,-3.581016276,50,-30.01336373,1.66E-11,0,0,0,-180 +110.79,50.41134336,-3.581016276,50,-29.99945898,2.74E-11,0,0,0,-180 +110.8,50.41134067,-3.581016276,50,-29.99598277,2.46E-11,0,0,0,-180 +110.81,50.41133797,-3.581016276,50,-29.99945894,1.56E-14,0,0,0,-180 +110.82,50.41133527,-3.581016276,50,-29.99598275,-2.45E-11,0,0,0,-180 +110.83,50.41133258,-3.581016276,50,-29.99598275,-2.45E-11,0,0,0,-180 +110.84,50.41132988,-3.581016276,50,-29.99945891,1.56E-13,0,0,0,-180 +110.85,50.41132718,-3.581016276,50,-29.9959827,2.47E-11,0,0,0,-180 +110.86,50.41132449,-3.581016276,50,-29.99598268,2.46E-11,0,0,0,-180 +110.87,50.41132179,-3.581016276,50,-29.99945886,1.56E-14,0,0,0,-180 +110.88,50.41131909,-3.581016276,50,-29.99598267,-2.45E-11,0,0,0,-180 +110.89,50.4113164,-3.581016276,50,-29.99945884,-2.72E-11,0,0,0,-180 +110.9,50.4113137,-3.581016276,50,-30.01336356,-1.62E-11,0,0,0,-180 +110.91,50.411311,-3.581016276,50,-30.01336353,-1.63E-11,0,0,0,-180 +110.92,50.4113083,-3.581016276,50,-29.99945878,-2.73E-11,0,0,0,-180 +110.93,50.41130561,-3.581016276,50,-29.99598259,-2.47E-11,0,0,0,-180 +110.94,50.41130291,-3.581016276,50,-29.99945877,-1.56E-13,0,0,0,-180 +110.95,50.41130021,-3.581016276,50,-29.99598258,2.45E-11,0,0,0,-180 +110.96,50.41129752,-3.581016276,50,-29.99598256,2.45E-11,0,0,0,-180 +110.97,50.41129482,-3.581016276,50,-29.99945872,1.73E-17,0,0,0,-180 +110.98,50.41129212,-3.581016276,50,-29.99598252,-2.45E-11,0,0,0,-180 +110.99,50.41128943,-3.581016276,50,-29.99598251,-2.45E-11,0,0,0,-180 +111,50.41128673,-3.581016276,50,-29.99945867,1.56E-13,0,0,0,-180 +111.01,50.41128403,-3.581016276,50,-29.99598248,2.47E-11,0,0,0,-180 +111.02,50.41128134,-3.581016276,50,-29.99945865,2.73E-11,0,0,0,-180 +111.03,50.41127864,-3.581016276,50,-30.01336337,1.63E-11,0,0,0,-180 +111.04,50.41127594,-3.581016276,50,-30.01336335,1.62E-11,0,0,0,-180 +111.05,50.41127324,-3.581016276,50,-29.99945861,2.72E-11,0,0,0,-180 +111.06,50.41127055,-3.581016276,50,-29.99598241,2.45E-11,0,0,0,-180 +111.07,50.41126785,-3.581016276,50,-29.99945857,0,0,0,0,-180 +111.08,50.41126515,-3.581016276,50,-29.99598238,-2.45E-11,0,0,0,-180 +111.09,50.41126246,-3.581016276,50,-29.99598238,-2.45E-11,0,0,0,-180 +111.1,50.41125976,-3.581016276,50,-29.99945855,1.56E-13,0,0,0,-180 +111.11,50.41125706,-3.581016276,50,-29.99598234,2.47E-11,0,0,0,-180 +111.12,50.41125437,-3.581016276,50,-29.9994585,2.74E-11,0,0,0,-180 +111.13,50.41125167,-3.581016276,50,-30.01336322,1.66E-11,0,0,0,-180 +111.14,50.41124897,-3.581016276,50,-30.01336322,1.66E-11,0,0,0,-180 +111.15,50.41124627,-3.581016276,50,-29.99945848,2.74E-11,0,0,0,-180 +111.16,50.41124358,-3.581016276,50,-29.99598228,2.47E-11,0,0,0,-180 +111.17,50.41124088,-3.581016276,50,-29.99945844,1.56E-13,0,0,0,-180 +111.18,50.41123818,-3.581016276,50,-29.99598224,-2.45E-11,0,0,0,-180 +111.19,50.41123549,-3.581016276,50,-29.99598223,-2.45E-11,0,0,0,-180 +111.2,50.41123279,-3.581016276,50,-29.99945841,0,0,0,0,-180 +111.21,50.41123009,-3.581016276,50,-29.99598221,2.45E-11,0,0,0,-180 +111.22,50.4112274,-3.581016276,50,-29.99598219,2.45E-11,0,0,0,-180 +111.23,50.4112247,-3.581016276,50,-29.99945835,-1.41E-13,0,0,0,-180 +111.24,50.411222,-3.581016276,50,-29.99598216,-2.46E-11,0,0,0,-180 +111.25,50.41121931,-3.581016276,50,-29.99945833,-2.72E-11,0,0,0,-180 +111.26,50.41121661,-3.581016276,50,-30.01336305,-1.62E-11,0,0,0,-180 +111.27,50.41121391,-3.581016276,50,-30.01336303,-1.63E-11,0,0,0,-180 +111.28,50.41121121,-3.581016276,50,-29.99945829,-2.72E-11,0,0,0,-180 +111.29,50.41120852,-3.581016276,50,-29.99598209,-2.45E-11,0,0,0,-180 +111.3,50.41120582,-3.581016276,50,-29.99945825,1.56E-13,0,0,0,-180 +111.31,50.41120312,-3.581016276,50,-29.99598206,2.47E-11,0,0,0,-180 +111.32,50.41120043,-3.581016276,50,-29.99598205,2.47E-11,0,0,0,-180 +111.33,50.41119773,-3.581016276,50,-29.99945822,1.56E-13,0,0,0,-180 +111.34,50.41119503,-3.581016276,50,-29.99598202,-2.45E-11,0,0,0,-180 +111.35,50.41119234,-3.581016276,50,-29.99598201,-2.46E-11,0,0,0,-180 +111.36,50.41118964,-3.581016276,50,-29.99945818,-1.41E-13,0,0,0,-180 +111.37,50.41118694,-3.581016276,50,-29.99598198,2.45E-11,0,0,0,-180 +111.38,50.41118425,-3.581016276,50,-29.99598197,2.45E-11,0,0,0,-180 +111.39,50.41118155,-3.581016276,50,-29.99945814,-1.73E-17,0,0,0,-180 +111.4,50.41117885,-3.581016276,50,-29.99598195,-2.45E-11,0,0,0,-180 +111.41,50.41117616,-3.581016276,50,-29.99945811,-2.72E-11,0,0,0,-180 +111.42,50.41117346,-3.581016276,50,-30.01336282,-1.62E-11,0,0,0,-180 +111.43,50.41117076,-3.581016276,50,-30.0133628,-1.62E-11,0,0,0,-180 +111.44,50.41116806,-3.581016276,50,-29.99945805,-2.72E-11,0,0,0,-180 +111.45,50.41116537,-3.581016276,50,-29.99598186,-2.45E-11,0,0,0,-180 +111.46,50.41116267,-3.581016276,50,-29.99945804,9.38E-14,0,0,0,-180 +111.47,50.41115997,-3.581016276,50,-29.99598185,2.48E-11,0,0,0,-180 +111.48,50.41115728,-3.581016276,50,-29.99598183,2.48E-11,0,0,0,-180 +111.49,50.41115458,-3.581016276,50,-29.99945799,9.38E-14,0,0,0,-180 +111.5,50.41115188,-3.581016276,50,-29.99598179,-2.45E-11,0,0,0,-180 +111.51,50.41114919,-3.581016276,50,-29.99598179,-2.45E-11,0,0,0,-180 +111.52,50.41114649,-3.581016276,50,-29.99945797,1.41E-13,0,0,0,-180 +111.53,50.41114379,-3.581016276,50,-29.99598176,2.46E-11,0,0,0,-180 +111.54,50.4111411,-3.581016276,50,-29.99945792,2.72E-11,0,0,0,-180 +111.55,50.4111384,-3.581016276,50,-30.01336263,1.63E-11,0,0,0,-180 +111.56,50.4111357,-3.581016276,50,-30.01336263,1.64E-11,0,0,0,-180 +111.57,50.411133,-3.581016276,50,-29.99945789,2.75E-11,0,0,0,-180 +111.58,50.41113031,-3.581016276,50,-29.99598169,2.47E-11,0,0,0,-180 +111.59,50.41112761,-3.581016276,50,-29.99945786,-8.67E-18,0,0,0,-180 +111.6,50.41112491,-3.581016276,50,-29.99598166,-2.47E-11,0,0,0,-180 +111.61,50.41112222,-3.581016276,50,-29.99598164,-2.48E-11,0,0,0,-180 +111.62,50.41111952,-3.581016276,50,-29.99945781,-9.37E-14,0,0,0,-180 +111.63,50.41111682,-3.581016276,50,-29.99598161,2.45E-11,0,0,0,-180 +111.64,50.41111413,-3.581016276,50,-29.99945778,2.72E-11,0,0,0,-180 +111.65,50.41111143,-3.581016276,50,-30.0133625,1.62E-11,0,0,0,-180 +111.66,50.41110873,-3.581016276,50,-30.0133625,1.62E-11,0,0,0,-180 +111.67,50.41110603,-3.581016276,50,-29.99945775,2.72E-11,0,0,0,-180 +111.68,50.41110334,-3.581016276,50,-29.99598154,2.46E-11,0,0,0,-180 +111.69,50.41110064,-3.581016276,50,-29.9994577,1.41E-13,0,0,0,-180 +111.7,50.41109794,-3.581016276,50,-29.9959815,-2.45E-11,0,0,0,-180 +111.71,50.41109525,-3.581016276,50,-29.99598149,-2.46E-11,0,0,0,-180 +111.72,50.41109255,-3.581016276,50,-29.99945767,-1.41E-13,0,0,0,-180 +111.73,50.41108985,-3.581016276,50,-29.99598148,2.45E-11,0,0,0,-180 +111.74,50.41108716,-3.581016276,50,-29.99598147,2.46E-11,0,0,0,-180 +111.75,50.41108446,-3.581016276,50,-29.99945763,1.41E-13,0,0,0,-180 +111.76,50.41108176,-3.581016276,50,-29.99598143,-2.45E-11,0,0,0,-180 +111.77,50.41107907,-3.581016276,50,-29.9994576,-2.73E-11,0,0,0,-180 +111.78,50.41107637,-3.581016276,50,-30.01336233,-1.65E-11,0,0,0,-180 +111.79,50.41107367,-3.581016276,50,-30.01336232,-1.65E-11,0,0,0,-180 +111.8,50.41107097,-3.581016276,50,-29.99945756,-2.73E-11,0,0,0,-180 +111.81,50.41106828,-3.581016276,50,-29.99598135,-2.45E-11,0,0,0,-180 +111.82,50.41106558,-3.581016276,50,-29.99945752,1.41E-13,0,0,0,-180 +111.83,50.41106288,-3.581016276,50,-29.99598133,2.46E-11,0,0,0,-180 +111.84,50.41106019,-3.581016276,50,-29.99598133,2.45E-11,0,0,0,-180 +111.85,50.41105749,-3.581016276,50,-29.9994575,-1.41E-13,0,0,0,-180 +111.86,50.41105479,-3.581016276,50,-29.99598129,-2.46E-11,0,0,0,-180 +111.87,50.4110521,-3.581016276,50,-29.99598127,-2.45E-11,0,0,0,-180 +111.88,50.4110494,-3.581016276,50,-29.99945745,2.34E-13,0,0,0,-180 +111.89,50.4110467,-3.581016276,50,-29.99598125,2.48E-11,0,0,0,-180 +111.9,50.41104401,-3.581016276,50,-29.99598124,2.48E-11,0,0,0,-180 +111.91,50.41104131,-3.581016276,50,-29.99945741,1.73E-17,0,0,0,-180 +111.92,50.41103861,-3.581016276,50,-29.99598121,-2.48E-11,0,0,0,-180 +111.93,50.41103592,-3.581016276,50,-29.99945738,-2.76E-11,0,0,0,-180 +111.94,50.41103322,-3.581016276,50,-30.0133621,-1.66E-11,0,0,0,-180 +111.95,50.41103052,-3.581016276,50,-30.01336208,-1.66E-11,0,0,0,-180 +111.96,50.41102782,-3.581016276,50,-29.99945733,-2.73E-11,0,0,0,-180 +111.97,50.41102513,-3.581016276,50,-29.99598113,-2.45E-11,0,0,0,-180 +111.98,50.41102243,-3.581016276,50,-29.99945731,1.41E-13,0,0,0,-180 +111.99,50.41101973,-3.581016276,50,-29.99598113,2.46E-11,0,0,0,-180 +112,50.41101704,-3.581016276,50,-29.9959811,2.45E-11,0,0,0,-180 +112.01,50.41101434,-3.581016276,50,-29.99945726,-2.34E-13,0,0,0,-180 +112.02,50.41101164,-3.581016276,50,-29.99598106,-2.49E-11,0,0,0,-180 +112.03,50.41100895,-3.581016276,50,-29.99598106,-2.49E-11,0,0,0,-180 +112.04,50.41100625,-3.581016276,50,-29.99945724,-2.34E-13,0,0,0,-180 +112.05,50.41100355,-3.581016276,50,-29.99598103,2.45E-11,0,0,0,-180 +112.06,50.41100086,-3.581016276,50,-29.99945719,2.73E-11,0,0,0,-180 +112.07,50.41099816,-3.581016276,50,-30.01336191,1.65E-11,0,0,0,-180 +112.08,50.41099546,-3.581016276,50,-30.01336191,1.65E-11,0,0,0,-180 +112.09,50.41099276,-3.581016276,50,-29.99945717,2.73E-11,0,0,0,-180 +112.1,50.41099007,-3.581016276,50,-29.99598096,2.45E-11,0,0,0,-180 +112.11,50.41098737,-3.581016276,50,-29.99945712,-2.34E-13,0,0,0,-180 +112.12,50.41098467,-3.581016276,50,-29.99598092,-2.49E-11,0,0,0,-180 +112.13,50.41098198,-3.581016276,50,-29.9959809,-2.49E-11,0,0,0,-180 +112.14,50.41097928,-3.581016276,50,-29.99945708,-2.34E-13,0,0,0,-180 +112.15,50.41097658,-3.581016276,50,-29.99598089,2.45E-11,0,0,0,-180 +112.16,50.41097389,-3.581016276,50,-29.99945707,2.73E-11,0,0,0,-180 +112.17,50.41097119,-3.581016276,50,-30.01336178,1.66E-11,0,0,0,-180 +112.18,50.41096849,-3.581016276,50,-30.01336176,1.66E-11,0,0,0,-180 +112.19,50.41096579,-3.581016276,50,-29.99945702,2.76E-11,0,0,0,-180 +112.2,50.4109631,-3.581016276,50,-29.99598081,2.49E-11,0,0,0,-180 +112.21,50.4109604,-3.581016276,50,-29.99945698,2.34E-13,0,0,0,-180 +112.22,50.4109577,-3.581016276,50,-29.99250461,-2.72E-11,0,0,0,-180 +112.23,50.41095501,-3.581016276,50,-29.97859987,-3.83E-11,0,0,0,-180 +112.24,50.41095231,-3.581016276,50,-29.96469512,-2.75E-11,0,0,0,-180 +112.25,50.41094962,-3.581016276,50,-29.95426655,2.58E-12,0,0,0,-180 +112.26,50.41094693,-3.581016276,50,-29.94383799,3.82E-11,0,0,0,-180 +112.27,50.41094423,-3.581016276,50,-29.92298089,5.46E-11,0,0,0,-180 +112.28,50.41094155,-3.581016276,50,-29.90212377,3.81E-11,0,0,0,-180 +112.29,50.41093886,-3.581016276,50,-29.89169521,2.58E-12,0,0,0,-180 +112.3,50.41093617,-3.581016276,50,-29.88126664,-2.74E-11,0,0,0,-180 +112.31,50.41093349,-3.581016276,50,-29.86736189,-3.83E-11,0,0,0,-180 +112.32,50.4109308,-3.581016276,50,-29.84998097,-3.01E-11,0,0,0,-180 +112.33,50.41092812,-3.581016276,50,-29.82912388,-1.37E-11,0,0,0,-180 +112.34,50.41092544,-3.581016276,50,-29.81174296,-5.47E-12,0,0,0,-180 +112.35,50.41092276,-3.581016276,50,-29.79436202,-1.37E-11,0,0,0,-180 +112.36,50.41092008,-3.581016276,50,-29.77350489,-3.01E-11,0,0,0,-180 +112.37,50.41091741,-3.581016276,50,-29.75612396,-3.83E-11,0,0,0,-180 +112.38,50.41091473,-3.581016276,50,-29.73874304,-3.02E-11,0,0,0,-180 +112.39,50.41091206,-3.581016276,50,-29.71788594,-1.38E-11,0,0,0,-180 +112.4,50.41090939,-3.581016276,50,-29.7039812,-2.89E-12,0,0,0,-180 +112.41,50.41090672,-3.581016276,50,-29.69702882,2.64E-12,0,0,0,-180 +112.42,50.41090405,-3.581016276,50,-29.68312407,1.36E-11,0,0,0,-180 +112.43,50.41090138,-3.581016276,50,-29.66226697,2.99E-11,0,0,0,-180 +112.44,50.41089872,-3.581016276,50,-29.64488604,3.80E-11,0,0,0,-180 +112.45,50.41089605,-3.581016276,50,-29.6275051,2.98E-11,0,0,0,-180 +112.46,50.41089339,-3.581016276,50,-29.60664799,1.34E-11,0,0,0,-180 +112.47,50.41089073,-3.581016276,50,-29.58926707,5.22E-12,0,0,0,-180 +112.48,50.41088807,-3.581016276,50,-29.57188614,1.34E-11,0,0,0,-180 +112.49,50.41088541,-3.581016276,50,-29.55102902,2.99E-11,0,0,0,-180 +112.5,50.41088276,-3.581016276,50,-29.53364809,3.83E-11,0,0,0,-180 +112.51,50.4108801,-3.581016276,50,-29.51626717,3.02E-11,0,0,0,-180 +112.52,50.41087745,-3.581016276,50,-29.49541007,1.38E-11,0,0,0,-180 +112.53,50.4108748,-3.581016276,50,-29.48150534,2.81E-12,0,0,0,-180 +112.54,50.41087215,-3.581016276,50,-29.47802914,0,0,0,0,-180 +112.55,50.4108695,-3.581016276,50,-29.47455293,2.66E-12,0,0,0,-180 +112.56,50.41086685,-3.581016276,50,-29.45717199,1.08E-11,0,0,0,-180 +112.57,50.4108642,-3.581016276,50,-29.42241015,1.62E-11,0,0,0,-180 +112.58,50.41086156,-3.581016276,50,-29.38764833,1.08E-11,0,0,0,-180 +112.59,50.41085892,-3.581016276,50,-29.37026741,2.56E-12,0,0,0,-180 +112.6,50.41085628,-3.581016276,50,-29.3667912,-1.56E-13,0,0,0,-180 +112.61,50.41085364,-3.581016276,50,-29.36679117,-7.81E-14,0,0,0,-180 +112.62,50.410851,-3.581016276,50,-29.36331497,-2.75E-12,0,0,0,-180 +112.63,50.41084836,-3.581016276,50,-29.34593407,-1.09E-11,0,0,0,-180 +112.64,50.41084572,-3.581016276,50,-29.31117223,-1.64E-11,0,0,0,-180 +112.65,50.41084309,-3.581016276,50,-29.27641039,-1.09E-11,0,0,0,-180 +112.66,50.41084046,-3.581016276,50,-29.25902946,-2.58E-12,0,0,0,-180 +112.67,50.41083783,-3.581016276,50,-29.25555328,1.41E-13,0,0,0,-180 +112.68,50.4108352,-3.581016276,50,-29.25207708,-2.73E-12,0,0,0,-180 +112.69,50.41083257,-3.581016276,50,-29.23817233,-1.38E-11,0,0,0,-180 +112.7,50.41082994,-3.581016276,50,-29.21731521,-3.02E-11,0,0,0,-180 +112.71,50.41082732,-3.581016276,50,-29.19993428,-3.83E-11,0,0,0,-180 +112.72,50.41082469,-3.581016276,50,-29.18255334,-3.00E-11,0,0,0,-180 +112.73,50.41082207,-3.581016276,50,-29.15822005,-1.10E-11,0,0,0,-180 +112.74,50.41081945,-3.581016276,50,-29.13041058,1.08E-11,0,0,0,-180 +112.75,50.41081683,-3.581016276,50,-29.1060773,2.99E-11,0,0,0,-180 +112.76,50.41081422,-3.581016276,50,-29.09217256,4.10E-11,0,0,0,-180 +112.77,50.4108116,-3.581016276,50,-29.08869636,4.39E-11,0,0,0,-180 +112.78,50.41080899,-3.581016276,50,-29.08522017,4.12E-11,0,0,0,-180 +112.79,50.41080637,-3.581016276,50,-29.07131543,3.02E-11,0,0,0,-180 +112.8,50.41080376,-3.581016276,50,-29.04698214,1.10E-11,0,0,0,-180 +112.81,50.41080115,-3.581016276,50,-29.01917266,-1.07E-11,0,0,0,-180 +112.82,50.41079854,-3.581016276,50,-28.99483936,-2.97E-11,0,0,0,-180 +112.83,50.41079594,-3.581016276,50,-28.98093462,-4.06E-11,0,0,0,-180 +112.84,50.41079333,-3.581016276,50,-28.97745843,-4.35E-11,0,0,0,-180 +112.85,50.41079073,-3.581016276,50,-28.97398225,-4.09E-11,0,0,0,-180 +112.86,50.41078812,-3.581016276,50,-28.95660132,-3.28E-11,0,0,0,-180 +112.87,50.41078552,-3.581016276,50,-28.92183947,-2.73E-11,0,0,0,-180 +112.88,50.41078292,-3.581016276,50,-28.8905538,-2.99E-11,0,0,0,-180 +112.89,50.41078033,-3.581016276,50,-28.88360143,-2.45E-11,0,0,0,-180 +112.9,50.41077773,-3.581016276,50,-28.88360142,-2.64E-12,0,0,0,-180 +112.91,50.41077513,-3.581016276,50,-28.8627443,1.38E-11,0,0,0,-180 +112.92,50.41077254,-3.581016276,50,-28.83145864,1.11E-11,0,0,0,-180 +112.93,50.41076995,-3.581016276,50,-28.81407772,2.88E-12,0,0,0,-180 +112.94,50.41076736,-3.581016276,50,-28.80712535,-2.73E-12,0,0,0,-180 +112.95,50.41076477,-3.581016276,50,-28.79322062,-1.38E-11,0,0,0,-180 +112.96,50.41076218,-3.581016276,50,-28.77236352,-3.03E-11,0,0,0,-180 +112.97,50.4107596,-3.581016276,50,-28.75498259,-3.85E-11,0,0,0,-180 +112.98,50.41075701,-3.581016276,50,-28.73760165,-3.03E-11,0,0,0,-180 +112.99,50.41075443,-3.581016276,50,-28.71674453,-1.38E-11,0,0,0,-180 +113,50.41075185,-3.581016276,50,-28.70283977,-2.73E-12,0,0,0,-180 +113.01,50.41074927,-3.581016276,50,-28.69588739,2.88E-12,0,0,0,-180 +113.02,50.41074669,-3.581016276,50,-28.68198266,1.38E-11,0,0,0,-180 +113.03,50.41074411,-3.581016276,50,-28.66112558,3.01E-11,0,0,0,-180 +113.04,50.41074154,-3.581016276,50,-28.64374465,3.81E-11,0,0,0,-180 +113.05,50.41073896,-3.581016276,50,-28.62636372,2.99E-11,0,0,0,-180 +113.06,50.41073639,-3.581016276,50,-28.60550661,1.36E-11,0,0,0,-180 +113.07,50.41073382,-3.581016276,50,-28.59160187,2.72E-12,0,0,0,-180 +113.08,50.41073125,-3.581016276,50,-28.58464949,-2.73E-12,0,0,0,-180 +113.09,50.41072868,-3.581016276,50,-28.56726855,-1.09E-11,0,0,0,-180 +113.1,50.41072611,-3.581016276,50,-28.53598288,-1.37E-11,0,0,0,-180 +113.11,50.41072355,-3.581016276,50,-28.51512578,2.73E-12,0,0,0,-180 +113.12,50.41072099,-3.581016276,50,-28.51512578,2.46E-11,0,0,0,-180 +113.13,50.41071842,-3.581016276,50,-28.50817341,3.01E-11,0,0,0,-180 +113.14,50.41071586,-3.581016276,50,-28.47688775,2.74E-11,0,0,0,-180 +113.15,50.4107133,-3.581016276,50,-28.44212591,3.29E-11,0,0,0,-180 +113.16,50.41071075,-3.581016276,50,-28.42474498,4.12E-11,0,0,0,-180 +113.17,50.41070819,-3.581016276,50,-28.42126879,4.39E-11,0,0,0,-180 +113.18,50.41070564,-3.581016276,50,-28.4177926,4.10E-11,0,0,0,-180 +113.19,50.41070308,-3.581016276,50,-28.40388786,2.99E-11,0,0,0,-180 +113.2,50.41070053,-3.581016276,50,-28.37955456,1.08E-11,0,0,0,-180 +113.21,50.41069798,-3.581016276,50,-28.35174509,-1.09E-11,0,0,0,-180 +113.22,50.41069543,-3.581016276,50,-28.3274118,-2.99E-11,0,0,0,-180 +113.23,50.41069289,-3.581016276,50,-28.31350705,-4.08E-11,0,0,0,-180 +113.24,50.41069034,-3.581016276,50,-28.31003085,-4.35E-11,0,0,0,-180 +113.25,50.4106878,-3.581016276,50,-28.30655466,-4.08E-11,0,0,0,-180 +113.26,50.41068525,-3.581016276,50,-28.28917373,-3.26E-11,0,0,0,-180 +113.27,50.41068271,-3.581016276,50,-28.25441189,-2.73E-11,0,0,0,-180 +113.28,50.41068017,-3.581016276,50,-28.22312624,-3.00E-11,0,0,0,-180 +113.29,50.41067764,-3.581016276,50,-28.21617387,-2.45E-11,0,0,0,-180 +113.3,50.4106751,-3.581016276,50,-28.21617385,-2.58E-12,0,0,0,-180 +113.31,50.41067256,-3.581016276,50,-28.19531675,1.37E-11,0,0,0,-180 +113.32,50.41067003,-3.581016276,50,-28.16403109,1.10E-11,0,0,0,-180 +113.33,50.4106675,-3.581016276,50,-28.14665017,2.73E-12,0,0,0,-180 +113.34,50.41066497,-3.581016276,50,-28.13969778,-2.73E-12,0,0,0,-180 +113.35,50.41066244,-3.581016276,50,-28.12579304,-1.37E-11,0,0,0,-180 +113.36,50.41065991,-3.581016276,50,-28.10493594,-3.01E-11,0,0,0,-180 +113.37,50.41065739,-3.581016276,50,-28.08755502,-3.83E-11,0,0,0,-180 +113.38,50.41065486,-3.581016276,50,-28.07017409,-3.01E-11,0,0,0,-180 +113.39,50.41065234,-3.581016276,50,-28.04931698,-1.37E-11,0,0,0,-180 +113.4,50.41064982,-3.581016276,50,-28.03541224,-2.81E-12,0,0,0,-180 +113.41,50.4106473,-3.581016276,50,-28.02845987,2.58E-12,0,0,0,-180 +113.42,50.41064478,-3.581016276,50,-28.01455512,1.35E-11,0,0,0,-180 +113.43,50.41064226,-3.581016276,50,-27.99369801,3.00E-11,0,0,0,-180 +113.44,50.41063975,-3.581016276,50,-27.97631709,3.82E-11,0,0,0,-180 +113.45,50.41063723,-3.581016276,50,-27.95893617,2.99E-11,0,0,0,-180 +113.46,50.41063472,-3.581016276,50,-27.93807905,1.34E-11,0,0,0,-180 +113.47,50.41063221,-3.581016276,50,-27.9241743,2.48E-12,0,0,0,-180 +113.48,50.4106297,-3.581016276,50,-27.91722194,-2.98E-12,0,0,0,-180 +113.49,50.41062719,-3.581016276,50,-27.89984102,-1.12E-11,0,0,0,-180 +113.5,50.41062468,-3.581016276,50,-27.86855535,-1.39E-11,0,0,0,-180 +113.51,50.41062218,-3.581016276,50,-27.84769823,2.48E-12,0,0,0,-180 +113.52,50.41061968,-3.581016276,50,-27.84769822,2.44E-11,0,0,0,-180 +113.53,50.41061717,-3.581016276,50,-27.84074586,2.99E-11,0,0,0,-180 +113.54,50.41061467,-3.581016276,50,-27.80946021,2.73E-11,0,0,0,-180 +113.55,50.41061217,-3.581016276,50,-27.77469838,3.28E-11,0,0,0,-180 +113.56,50.41060968,-3.581016276,50,-27.75731745,4.10E-11,0,0,0,-180 +113.57,50.41060718,-3.581016276,50,-27.75384125,4.37E-11,0,0,0,-180 +113.58,50.41060469,-3.581016276,50,-27.75036505,4.09E-11,0,0,0,-180 +113.59,50.41060219,-3.581016276,50,-27.73646031,2.99E-11,0,0,0,-180 +113.6,50.4105997,-3.581016276,50,-27.71212702,1.09E-11,0,0,0,-180 +113.61,50.41059721,-3.581016276,50,-27.68431755,-1.10E-11,0,0,0,-180 +113.62,50.41059472,-3.581016276,50,-27.65998426,-3.01E-11,0,0,0,-180 +113.63,50.41059224,-3.581016276,50,-27.64607951,-4.09E-11,0,0,0,-180 +113.64,50.41058975,-3.581016276,50,-27.64260332,-4.36E-11,0,0,0,-180 +113.65,50.41058727,-3.581016276,50,-27.63912713,-4.09E-11,0,0,0,-180 +113.66,50.41058478,-3.581016276,50,-27.6217462,-3.27E-11,0,0,0,-180 +113.67,50.4105823,-3.581016276,50,-27.58698437,-2.72E-11,0,0,0,-180 +113.68,50.41057982,-3.581016276,50,-27.55569873,-2.99E-11,0,0,0,-180 +113.69,50.41057735,-3.581016276,50,-27.54874635,-2.45E-11,0,0,0,-180 +113.7,50.41057487,-3.581016276,50,-27.54874632,-2.73E-12,0,0,0,-180 +113.71,50.41057239,-3.581016276,50,-27.52788921,1.35E-11,0,0,0,-180 +113.72,50.41056992,-3.581016276,50,-27.49660356,1.07E-11,0,0,0,-180 +113.73,50.41056745,-3.581016276,50,-27.47922264,2.48E-12,0,0,0,-180 +113.74,50.41056498,-3.581016276,50,-27.47227027,-2.98E-12,0,0,0,-180 +113.75,50.41056251,-3.581016276,50,-27.45836551,-1.39E-11,0,0,0,-180 +113.76,50.41056004,-3.581016276,50,-27.4375084,-3.03E-11,0,0,0,-180 +113.77,50.41055758,-3.581016276,50,-27.4201275,-3.84E-11,0,0,0,-180 +113.78,50.41055511,-3.581016276,50,-27.40274657,-3.01E-11,0,0,0,-180 +113.79,50.41055265,-3.581016276,50,-27.38188945,-1.35E-11,0,0,0,-180 +113.8,50.41055019,-3.581016276,50,-27.36798471,-2.58E-12,0,0,0,-180 +113.81,50.41054773,-3.581016276,50,-27.36103235,2.81E-12,0,0,0,-180 +113.82,50.41054527,-3.581016276,50,-27.34712761,1.37E-11,0,0,0,-180 +113.83,50.41054281,-3.581016276,50,-27.3262705,3.00E-11,0,0,0,-180 +113.84,50.41054036,-3.581016276,50,-27.30888957,3.81E-11,0,0,0,-180 +113.85,50.4105379,-3.581016276,50,-27.29150864,2.99E-11,0,0,0,-180 +113.86,50.41053545,-3.581016276,50,-27.27065154,1.36E-11,0,0,0,-180 +113.87,50.410533,-3.581016276,50,-27.25674681,2.72E-12,0,0,0,-180 +113.88,50.41053055,-3.581016276,50,-27.24979442,-2.72E-12,0,0,0,-180 +113.89,50.4105281,-3.581016276,50,-27.23588967,-1.36E-11,0,0,0,-180 +113.9,50.41052565,-3.581016276,50,-27.21503256,-2.99E-11,0,0,0,-180 +113.91,50.41052321,-3.581016276,50,-27.19765165,-3.81E-11,0,0,0,-180 +113.92,50.41052076,-3.581016276,50,-27.18027073,-3.00E-11,0,0,0,-180 +113.93,50.41051832,-3.581016276,50,-27.15593744,-1.08E-11,0,0,0,-180 +113.94,50.41051588,-3.581016276,50,-27.12812796,1.11E-11,0,0,0,-180 +113.95,50.41051344,-3.581016276,50,-27.10727085,2.76E-11,0,0,0,-180 +113.96,50.41051101,-3.581016276,50,-27.10379466,2.48E-11,0,0,0,-180 +113.97,50.41050857,-3.581016276,50,-27.10379465,2.89E-12,0,0,0,-180 +113.98,50.41050613,-3.581016276,50,-27.08293755,-1.37E-11,0,0,0,-180 +113.99,50.4105037,-3.581016276,50,-27.0516519,-1.11E-11,0,0,0,-180 +114,50.41050127,-3.581016276,50,-27.03427097,-2.95E-12,0,0,0,-180 +114.01,50.41049884,-3.581016276,50,-27.0273186,2.58E-12,0,0,0,-180 +114.02,50.41049641,-3.581016276,50,-27.00993768,1.09E-11,0,0,0,-180 +114.03,50.41049398,-3.581016276,50,-26.97865203,1.38E-11,0,0,0,-180 +114.04,50.41049156,-3.581016276,50,-26.95779491,-2.58E-12,0,0,0,-180 +114.05,50.41048914,-3.581016276,50,-26.9577949,-2.45E-11,0,0,0,-180 +114.06,50.41048671,-3.581016276,50,-26.95431871,-2.72E-11,0,0,0,-180 +114.07,50.41048429,-3.581016276,50,-26.9334616,-1.08E-11,0,0,0,-180 +114.08,50.41048187,-3.581016276,50,-26.90565211,1.11E-11,0,0,0,-180 +114.09,50.41047945,-3.581016276,50,-26.88131881,3.02E-11,0,0,0,-180 +114.1,50.41047704,-3.581016276,50,-26.86393789,3.83E-11,0,0,0,-180 +114.11,50.41047462,-3.581016276,50,-26.84655699,3.01E-11,0,0,0,-180 +114.12,50.41047221,-3.581016276,50,-26.82569989,1.37E-11,0,0,0,-180 +114.13,50.4104698,-3.581016276,50,-26.81179515,2.73E-12,0,0,0,-180 +114.14,50.41046739,-3.581016276,50,-26.80831896,1.56E-14,0,0,0,-180 +114.15,50.41046498,-3.581016276,50,-26.80484277,2.81E-12,0,0,0,-180 +114.16,50.41046257,-3.581016276,50,-26.78746185,1.11E-11,0,0,0,-180 +114.17,50.41046016,-3.581016276,50,-26.7561762,1.38E-11,0,0,0,-180 +114.18,50.41045776,-3.581016276,50,-26.7353191,-2.64E-12,0,0,0,-180 +114.19,50.41045536,-3.581016276,50,-26.73184289,-2.18E-11,0,0,0,-180 +114.2,50.41045295,-3.581016276,50,-26.71446196,-1.35E-11,0,0,0,-180 +114.21,50.41045055,-3.581016276,50,-26.67970012,1.39E-11,0,0,0,-180 +114.22,50.41044816,-3.581016276,50,-26.66231919,2.21E-11,0,0,0,-180 +114.23,50.41044576,-3.581016276,50,-26.658843,2.98E-12,0,0,0,-180 +114.24,50.41044336,-3.581016276,50,-26.6379859,-1.34E-11,0,0,0,-180 +114.25,50.41044097,-3.581016276,50,-26.60670026,-1.07E-11,0,0,0,-180 +114.26,50.41043858,-3.581016276,50,-26.58931933,-2.48E-12,0,0,0,-180 +114.27,50.41043619,-3.581016276,50,-26.58584313,2.34E-13,0,0,0,-180 +114.28,50.4104338,-3.581016276,50,-26.58236693,-2.58E-12,0,0,0,-180 +114.29,50.41043141,-3.581016276,50,-26.5684622,-1.37E-11,0,0,0,-180 +114.3,50.41042902,-3.581016276,50,-26.54760512,-3.02E-11,0,0,0,-180 +114.31,50.41042664,-3.581016276,50,-26.53022419,-3.84E-11,0,0,0,-180 +114.32,50.41042425,-3.581016276,50,-26.51284325,-3.02E-11,0,0,0,-180 +114.33,50.41042187,-3.581016276,50,-26.49198613,-1.37E-11,0,0,0,-180 +114.34,50.41041949,-3.581016276,50,-26.47460521,-5.47E-12,0,0,0,-180 +114.35,50.41041711,-3.581016276,50,-26.4572243,-1.37E-11,0,0,0,-180 +114.36,50.41041473,-3.581016276,50,-26.4363672,-3.01E-11,0,0,0,-180 +114.37,50.41041236,-3.581016276,50,-26.41898628,-3.83E-11,0,0,0,-180 +114.38,50.41040998,-3.581016276,50,-26.40160534,-3.01E-11,0,0,0,-180 +114.39,50.41040761,-3.581016276,50,-26.38074823,-1.37E-11,0,0,0,-180 +114.4,50.41040524,-3.581016276,50,-26.3668435,-2.73E-12,0,0,0,-180 +114.41,50.41040287,-3.581016276,50,-26.35989114,2.72E-12,0,0,0,-180 +114.42,50.4104005,-3.581016276,50,-26.3459864,1.36E-11,0,0,0,-180 +114.43,50.41039813,-3.581016276,50,-26.32512928,2.99E-11,0,0,0,-180 +114.44,50.41039577,-3.581016276,50,-26.30774835,3.81E-11,0,0,0,-180 +114.45,50.4103934,-3.581016276,50,-26.29036743,3.01E-11,0,0,0,-180 +114.46,50.41039104,-3.581016276,50,-26.26951033,1.38E-11,0,0,0,-180 +114.47,50.41038868,-3.581016276,50,-26.25560559,2.87E-12,0,0,0,-180 +114.48,50.41038632,-3.581016276,50,-26.24865321,-2.73E-12,0,0,0,-180 +114.49,50.41038396,-3.581016276,50,-26.23127228,-1.11E-11,0,0,0,-180 +114.5,50.4103816,-3.581016276,50,-26.19998664,-1.39E-11,0,0,0,-180 +114.51,50.41037925,-3.581016276,50,-26.17912953,2.48E-12,0,0,0,-180 +114.52,50.4103769,-3.581016276,50,-26.17912953,2.44E-11,0,0,0,-180 +114.53,50.41037454,-3.581016276,50,-26.17217716,2.99E-11,0,0,0,-180 +114.54,50.41037219,-3.581016276,50,-26.1408915,2.73E-11,0,0,0,-180 +114.55,50.41036984,-3.581016276,50,-26.10612966,3.27E-11,0,0,0,-180 +114.56,50.4103675,-3.581016276,50,-26.08874874,4.09E-11,0,0,0,-180 +114.57,50.41036515,-3.581016276,50,-26.08527254,4.36E-11,0,0,0,-180 +114.58,50.41036281,-3.581016276,50,-26.08179635,4.09E-11,0,0,0,-180 +114.59,50.41036046,-3.581016276,50,-26.06789161,3.01E-11,0,0,0,-180 +114.6,50.41035812,-3.581016276,50,-26.04355832,1.09E-11,0,0,0,-180 +114.61,50.41035578,-3.581016276,50,-26.01574885,-1.09E-11,0,0,0,-180 +114.62,50.41035344,-3.581016276,50,-25.99141557,-3.01E-11,0,0,0,-180 +114.63,50.41035111,-3.581016276,50,-25.97751084,-4.10E-11,0,0,0,-180 +114.64,50.41034877,-3.581016276,50,-25.97403464,-4.38E-11,0,0,0,-180 +114.65,50.41034644,-3.581016276,50,-25.97055843,-4.10E-11,0,0,0,-180 +114.66,50.4103441,-3.581016276,50,-25.95665369,-3.01E-11,0,0,0,-180 +114.67,50.41034177,-3.581016276,50,-25.93232041,-1.09E-11,0,0,0,-180 +114.68,50.41033944,-3.581016276,50,-25.90451096,1.11E-11,0,0,0,-180 +114.69,50.41033711,-3.581016276,50,-25.88017767,3.02E-11,0,0,0,-180 +114.7,50.41033479,-3.581016276,50,-25.86279674,3.83E-11,0,0,0,-180 +114.71,50.41033246,-3.581016276,50,-25.84541581,2.99E-11,0,0,0,-180 +114.72,50.41033014,-3.581016276,50,-25.82455871,1.34E-11,0,0,0,-180 +114.73,50.41032782,-3.581016276,50,-25.81065397,2.50E-12,0,0,0,-180 +114.74,50.4103255,-3.581016276,50,-25.80717778,-1.56E-13,0,0,0,-180 +114.75,50.41032318,-3.581016276,50,-25.80370159,2.72E-12,0,0,0,-180 +114.76,50.41032086,-3.581016276,50,-25.78632067,1.10E-11,0,0,0,-180 +114.77,50.41031854,-3.581016276,50,-25.75503501,1.37E-11,0,0,0,-180 +114.78,50.41031623,-3.581016276,50,-25.7341779,-2.87E-12,0,0,0,-180 +114.79,50.41031392,-3.581016276,50,-25.73070171,-2.20E-11,0,0,0,-180 +114.8,50.4103116,-3.581016276,50,-25.71332079,-1.38E-11,0,0,0,-180 +114.81,50.41030929,-3.581016276,50,-25.67855895,1.36E-11,0,0,0,-180 +114.82,50.41030699,-3.581016276,50,-25.66117804,2.17E-11,0,0,0,-180 +114.83,50.41030468,-3.581016276,50,-25.65770186,2.58E-12,0,0,0,-180 +114.84,50.41030237,-3.581016276,50,-25.63684475,-1.38E-11,0,0,0,-180 +114.85,50.41030007,-3.581016276,50,-25.60555908,-1.10E-11,0,0,0,-180 +114.86,50.41029777,-3.581016276,50,-25.58817815,-2.73E-12,0,0,0,-180 +114.87,50.41029547,-3.581016276,50,-25.58470197,0,0,0,0,-180 +114.88,50.41029317,-3.581016276,50,-25.58122579,-2.73E-12,0,0,0,-180 +114.89,50.41029087,-3.581016276,50,-25.56732106,-1.37E-11,0,0,0,-180 +114.9,50.41028857,-3.581016276,50,-25.54646394,-3.01E-11,0,0,0,-180 +114.91,50.41028628,-3.581016276,50,-25.52908301,-3.83E-11,0,0,0,-180 +114.92,50.41028398,-3.581016276,50,-25.51170209,-3.02E-11,0,0,0,-180 +114.93,50.41028169,-3.581016276,50,-25.49084499,-1.38E-11,0,0,0,-180 +114.94,50.4102794,-3.581016276,50,-25.47346406,-5.61E-12,0,0,0,-180 +114.95,50.41027711,-3.581016276,50,-25.45608315,-1.37E-11,0,0,0,-180 +114.96,50.41027482,-3.581016276,50,-25.43522605,-2.99E-11,0,0,0,-180 +114.97,50.41027254,-3.581016276,50,-25.41784512,-3.81E-11,0,0,0,-180 +114.98,50.41027025,-3.581016276,50,-25.4004642,-3.01E-11,0,0,0,-180 +114.99,50.41026797,-3.581016276,50,-25.3796071,-1.38E-11,0,0,0,-180 +115,50.41026569,-3.581016276,50,-25.36570236,-2.97E-12,0,0,0,-180 +115.01,50.41026341,-3.581016276,50,-25.35874999,2.48E-12,0,0,0,-180 +115.02,50.41026113,-3.581016276,50,-25.34484525,1.34E-11,0,0,0,-180 +115.03,50.41025885,-3.581016276,50,-25.32398814,2.99E-11,0,0,0,-180 +115.04,50.41025658,-3.581016276,50,-25.30660722,3.82E-11,0,0,0,-180 +115.05,50.4102543,-3.581016276,50,-25.28922629,3.00E-11,0,0,0,-180 +115.06,50.41025203,-3.581016276,50,-25.26836919,1.35E-11,0,0,0,-180 +115.07,50.41024976,-3.581016276,50,-25.25446445,2.58E-12,0,0,0,-180 +115.08,50.41024749,-3.581016276,50,-25.24751209,-2.81E-12,0,0,0,-180 +115.09,50.41024522,-3.581016276,50,-25.23360735,-1.37E-11,0,0,0,-180 +115.1,50.41024295,-3.581016276,50,-25.21275024,-3.00E-11,0,0,0,-180 +115.11,50.41024069,-3.581016276,50,-25.19536931,-3.80E-11,0,0,0,-180 +115.12,50.41023842,-3.581016276,50,-25.17798839,-2.98E-11,0,0,0,-180 +115.13,50.41023616,-3.581016276,50,-25.15713128,-1.34E-11,0,0,0,-180 +115.14,50.4102339,-3.581016276,50,-25.13975036,-5.37E-12,0,0,0,-180 +115.15,50.41023164,-3.581016276,50,-25.12236945,-1.37E-11,0,0,0,-180 +115.16,50.41022938,-3.581016276,50,-25.10151235,-3.01E-11,0,0,0,-180 +115.17,50.41022713,-3.581016276,50,-25.08413142,-3.83E-11,0,0,0,-180 +115.18,50.41022487,-3.581016276,50,-25.0667505,-3.02E-11,0,0,0,-180 +115.19,50.41022262,-3.581016276,50,-25.04589339,-1.38E-11,0,0,0,-180 +115.2,50.41022037,-3.581016276,50,-25.03198865,-2.87E-12,0,0,0,-180 +115.21,50.41021812,-3.581016276,50,-25.02503629,2.73E-12,0,0,0,-180 +115.22,50.41021587,-3.581016276,50,-25.01113155,1.38E-11,0,0,0,-180 +115.23,50.41021362,-3.581016276,50,-24.99027444,3.02E-11,0,0,0,-180 +115.24,50.41021138,-3.581016276,50,-24.97289352,3.83E-11,0,0,0,-180 +115.25,50.41020913,-3.581016276,50,-24.95551261,3.00E-11,0,0,0,-180 +115.26,50.41020689,-3.581016276,50,-24.93465551,1.37E-11,0,0,0,-180 +115.27,50.41020465,-3.581016276,50,-24.91727458,5.61E-12,0,0,0,-180 +115.28,50.41020241,-3.581016276,50,-24.89989364,1.38E-11,0,0,0,-180 +115.29,50.41020017,-3.581016276,50,-24.87903652,3.01E-11,0,0,0,-180 +115.3,50.41019794,-3.581016276,50,-24.86513179,4.09E-11,0,0,0,-180 +115.31,50.4101957,-3.581016276,50,-24.86165562,4.36E-11,0,0,0,-180 +115.32,50.41019347,-3.581016276,50,-24.85817944,4.10E-11,0,0,0,-180 +115.33,50.41019123,-3.581016276,50,-24.84079852,3.30E-11,0,0,0,-180 +115.34,50.410189,-3.581016276,50,-24.80603669,2.75E-11,0,0,0,-180 +115.35,50.41018677,-3.581016276,50,-24.77127487,3.29E-11,0,0,0,-180 +115.36,50.41018455,-3.581016276,50,-24.75389394,4.10E-11,0,0,0,-180 +115.37,50.41018232,-3.581016276,50,-24.75041774,4.38E-11,0,0,0,-180 +115.38,50.4101801,-3.581016276,50,-24.74694154,4.10E-11,0,0,0,-180 +115.39,50.41017787,-3.581016276,50,-24.7330368,3.01E-11,0,0,0,-180 +115.4,50.41017565,-3.581016276,50,-24.7087035,1.09E-11,0,0,0,-180 +115.41,50.41017343,-3.581016276,50,-24.68089402,-1.11E-11,0,0,0,-180 +115.42,50.41017121,-3.581016276,50,-24.65656075,-3.02E-11,0,0,0,-180 +115.43,50.410169,-3.581016276,50,-24.64265603,-4.11E-11,0,0,0,-180 +115.44,50.41016678,-3.581016276,50,-24.63917984,-4.38E-11,0,0,0,-180 +115.45,50.41016457,-3.581016276,50,-24.63570363,-4.12E-11,0,0,0,-180 +115.46,50.41016235,-3.581016276,50,-24.62179889,-3.02E-11,0,0,0,-180 +115.47,50.41016014,-3.581016276,50,-24.59746562,-1.09E-11,0,0,0,-180 +115.48,50.41015793,-3.581016276,50,-24.56965615,1.11E-11,0,0,0,-180 +115.49,50.41015572,-3.581016276,50,-24.54532286,3.03E-11,0,0,0,-180 +115.5,50.41015352,-3.581016276,50,-24.52794194,3.85E-11,0,0,0,-180 +115.51,50.41015131,-3.581016276,50,-24.51056104,3.03E-11,0,0,0,-180 +115.52,50.41014911,-3.581016276,50,-24.48970395,1.38E-11,0,0,0,-180 +115.53,50.41014691,-3.581016276,50,-24.4757992,2.73E-12,0,0,0,-180 +115.54,50.41014471,-3.581016276,50,-24.47232299,-1.41E-13,0,0,0,-180 +115.55,50.41014251,-3.581016276,50,-24.46884679,2.59E-12,0,0,0,-180 +115.56,50.41014031,-3.581016276,50,-24.45494205,1.37E-11,0,0,0,-180 +115.57,50.41013811,-3.581016276,50,-24.43408496,3.02E-11,0,0,0,-180 +115.58,50.41013592,-3.581016276,50,-24.41670404,3.84E-11,0,0,0,-180 +115.59,50.41013372,-3.581016276,50,-24.39932311,3.02E-11,0,0,0,-180 +115.6,50.41013153,-3.581016276,50,-24.37498983,1.10E-11,0,0,0,-180 +115.61,50.41012934,-3.581016276,50,-24.34718036,-1.09E-11,0,0,0,-180 +115.62,50.41012715,-3.581016276,50,-24.32284707,-3.01E-11,0,0,0,-180 +115.63,50.41012497,-3.581016276,50,-24.30894234,-4.10E-11,0,0,0,-180 +115.64,50.41012278,-3.581016276,50,-24.30546616,-4.37E-11,0,0,0,-180 +115.65,50.4101206,-3.581016276,50,-24.30198997,-4.10E-11,0,0,0,-180 +115.66,50.41011841,-3.581016276,50,-24.28460904,-3.28E-11,0,0,0,-180 +115.67,50.41011623,-3.581016276,50,-24.2498472,-2.73E-11,0,0,0,-180 +115.68,50.41011405,-3.581016276,50,-24.21856155,-2.99E-11,0,0,0,-180 +115.69,50.41011188,-3.581016276,50,-24.21160918,-2.45E-11,0,0,0,-180 +115.7,50.4101097,-3.581016276,50,-24.21160919,-2.73E-12,0,0,0,-180 +115.71,50.41010752,-3.581016276,50,-24.19075208,1.35E-11,0,0,0,-180 +115.72,50.41010535,-3.581016276,50,-24.15946642,1.08E-11,0,0,0,-180 +115.73,50.41010318,-3.581016276,50,-24.14208549,2.73E-12,0,0,0,-180 +115.74,50.41010101,-3.581016276,50,-24.1386093,1.56E-13,0,0,0,-180 +115.75,50.41009884,-3.581016276,50,-24.13513313,2.97E-12,0,0,0,-180 +115.76,50.41009667,-3.581016276,50,-24.11775221,1.12E-11,0,0,0,-180 +115.77,50.4100945,-3.581016276,50,-24.08646656,1.39E-11,0,0,0,-180 +115.78,50.41009234,-3.581016276,50,-24.06560944,-2.58E-12,0,0,0,-180 +115.79,50.41009018,-3.581016276,50,-24.06213324,-2.19E-11,0,0,0,-180 +115.8,50.41008801,-3.581016276,50,-24.04475233,-1.38E-11,0,0,0,-180 +115.81,50.41008585,-3.581016276,50,-24.00999051,1.35E-11,0,0,0,-180 +115.82,50.4100837,-3.581016276,50,-23.9926096,2.18E-11,0,0,0,-180 +115.83,50.41008154,-3.581016276,50,-23.98913341,2.72E-12,0,0,0,-180 +115.84,50.41007938,-3.581016276,50,-23.97175249,-1.10E-11,0,0,0,-180 +115.85,50.41007723,-3.581016276,50,-23.95089537,5.38E-12,0,0,0,-180 +115.86,50.41007508,-3.581016276,50,-23.93699063,3.80E-11,0,0,0,-180 +115.87,50.41007292,-3.581016276,50,-23.91613354,5.44E-11,0,0,0,-180 +115.88,50.41007078,-3.581016276,50,-23.89527644,3.80E-11,0,0,0,-180 +115.89,50.41006863,-3.581016276,50,-23.88484788,2.64E-12,0,0,0,-180 +115.9,50.41006648,-3.581016276,50,-23.87441932,-2.74E-11,0,0,0,-180 +115.91,50.41006434,-3.581016276,50,-23.86051458,-3.83E-11,0,0,0,-180 +115.92,50.41006219,-3.581016276,50,-23.84313366,-3.01E-11,0,0,0,-180 +115.93,50.41006005,-3.581016276,50,-23.82227656,-1.37E-11,0,0,0,-180 +115.94,50.41005791,-3.581016276,50,-23.80489564,-5.55E-12,0,0,0,-180 +115.95,50.41005577,-3.581016276,50,-23.78751471,-1.38E-11,0,0,0,-180 +115.96,50.41005363,-3.581016276,50,-23.76665761,-3.02E-11,0,0,0,-180 +115.97,50.4100515,-3.581016276,50,-23.74927669,-3.83E-11,0,0,0,-180 +115.98,50.41004936,-3.581016276,50,-23.73189578,-2.99E-11,0,0,0,-180 +115.99,50.41004723,-3.581016276,50,-23.71103869,-1.34E-11,0,0,0,-180 +116,50.4100451,-3.581016276,50,-23.69713396,-2.48E-12,0,0,0,-180 +116.01,50.41004297,-3.581016276,50,-23.69365775,2.50E-13,0,0,0,-180 +116.02,50.41004084,-3.581016276,50,-23.69018155,-2.48E-12,0,0,0,-180 +116.03,50.41003871,-3.581016276,50,-23.67280063,-1.07E-11,0,0,0,-180 +116.04,50.41003658,-3.581016276,50,-23.63803881,-1.62E-11,0,0,0,-180 +116.05,50.41003446,-3.581016276,50,-23.60327699,-1.09E-11,0,0,0,-180 +116.06,50.41003234,-3.581016276,50,-23.58589606,-2.73E-12,0,0,0,-180 +116.07,50.41003022,-3.581016276,50,-23.58241988,-7.81E-14,0,0,0,-180 +116.08,50.4100281,-3.581016276,50,-23.57894368,-2.89E-12,0,0,0,-180 +116.09,50.41002598,-3.581016276,50,-23.56503894,-1.38E-11,0,0,0,-180 +116.1,50.41002386,-3.581016276,50,-23.54418184,-3.02E-11,0,0,0,-180 +116.11,50.41002175,-3.581016276,50,-23.52680093,-3.83E-11,0,0,0,-180 +116.12,50.41001963,-3.581016276,50,-23.50942001,-3.01E-11,0,0,0,-180 +116.13,50.41001752,-3.581016276,50,-23.4885629,-1.37E-11,0,0,0,-180 +116.14,50.41001541,-3.581016276,50,-23.47118197,-5.47E-12,0,0,0,-180 +116.15,50.4100133,-3.581016276,50,-23.45380105,-1.37E-11,0,0,0,-180 +116.16,50.41001119,-3.581016276,50,-23.43294396,-3.01E-11,0,0,0,-180 +116.17,50.41000909,-3.581016276,50,-23.41556304,-3.82E-11,0,0,0,-180 +116.18,50.41000698,-3.581016276,50,-23.39818212,-2.99E-11,0,0,0,-180 +116.19,50.41000488,-3.581016276,50,-23.37732501,-1.35E-11,0,0,0,-180 +116.2,50.41000278,-3.581016276,50,-23.36342028,-2.73E-12,0,0,0,-180 +116.21,50.41000068,-3.581016276,50,-23.35646791,2.58E-12,0,0,0,-180 +116.22,50.40999858,-3.581016276,50,-23.34256319,1.34E-11,0,0,0,-180 +116.23,50.40999648,-3.581016276,50,-23.32170608,2.98E-11,0,0,0,-180 +116.24,50.40999439,-3.581016276,50,-23.30432515,3.81E-11,0,0,0,-180 +116.25,50.40999229,-3.581016276,50,-23.28694422,3.01E-11,0,0,0,-180 +116.26,50.4099902,-3.581016276,50,-23.26608712,1.37E-11,0,0,0,-180 +116.27,50.40998811,-3.581016276,50,-23.25218239,2.72E-12,0,0,0,-180 +116.28,50.40998602,-3.581016276,50,-23.24523002,-2.87E-12,0,0,0,-180 +116.29,50.40998393,-3.581016276,50,-23.23132528,-1.38E-11,0,0,0,-180 +116.3,50.40998184,-3.581016276,50,-23.21046819,-3.01E-11,0,0,0,-180 +116.31,50.40997976,-3.581016276,50,-23.19308726,-3.81E-11,0,0,0,-180 +116.32,50.40997767,-3.581016276,50,-23.17570634,-2.99E-11,0,0,0,-180 +116.33,50.40997559,-3.581016276,50,-23.15484925,-1.36E-11,0,0,0,-180 +116.34,50.40997351,-3.581016276,50,-23.13746834,-5.45E-12,0,0,0,-180 +116.35,50.40997143,-3.581016276,50,-23.12008742,-1.37E-11,0,0,0,-180 +116.36,50.40996935,-3.581016276,50,-23.09923031,-3.00E-11,0,0,0,-180 +116.37,50.40996728,-3.581016276,50,-23.08184937,-3.80E-11,0,0,0,-180 +116.38,50.4099652,-3.581016276,50,-23.06446845,-2.98E-11,0,0,0,-180 +116.39,50.40996313,-3.581016276,50,-23.04361136,-1.34E-11,0,0,0,-180 +116.4,50.40996106,-3.581016276,50,-23.02970663,-2.64E-12,0,0,0,-180 +116.41,50.40995899,-3.581016276,50,-23.02275426,2.75E-12,0,0,0,-180 +116.42,50.40995692,-3.581016276,50,-23.00884953,1.37E-11,0,0,0,-180 +116.43,50.40995485,-3.581016276,50,-22.98799243,3.02E-11,0,0,0,-180 +116.44,50.40995279,-3.581016276,50,-22.9706115,3.84E-11,0,0,0,-180 +116.45,50.40995072,-3.581016276,50,-22.95323058,3.02E-11,0,0,0,-180 +116.46,50.40994866,-3.581016276,50,-22.93237349,1.37E-11,0,0,0,-180 +116.47,50.4099466,-3.581016276,50,-22.91846875,2.59E-12,0,0,0,-180 +116.48,50.40994454,-3.581016276,50,-22.91151636,-2.88E-12,0,0,0,-180 +116.49,50.40994248,-3.581016276,50,-22.89761163,-1.37E-11,0,0,0,-180 +116.5,50.40994042,-3.581016276,50,-22.87675453,-2.99E-11,0,0,0,-180 +116.51,50.40993837,-3.581016276,50,-22.85937361,-3.81E-11,0,0,0,-180 +116.52,50.40993631,-3.581016276,50,-22.84199268,-2.99E-11,0,0,0,-180 +116.53,50.40993426,-3.581016276,50,-22.82113558,-1.37E-11,0,0,0,-180 +116.54,50.40993221,-3.581016276,50,-22.80375467,-5.61E-12,0,0,0,-180 +116.55,50.40993016,-3.581016276,50,-22.78637377,-1.38E-11,0,0,0,-180 +116.56,50.40992811,-3.581016276,50,-22.76551667,-3.02E-11,0,0,0,-180 +116.57,50.40992607,-3.581016276,50,-22.74813574,-3.84E-11,0,0,0,-180 +116.58,50.40992402,-3.581016276,50,-22.73075481,-3.02E-11,0,0,0,-180 +116.59,50.40992198,-3.581016276,50,-22.70989771,-1.38E-11,0,0,0,-180 +116.6,50.40991994,-3.581016276,50,-22.69599298,-2.81E-12,0,0,0,-180 +116.61,50.4099179,-3.581016276,50,-22.68904062,2.72E-12,0,0,0,-180 +116.62,50.40991586,-3.581016276,50,-22.67513588,1.37E-11,0,0,0,-180 +116.63,50.40991382,-3.581016276,50,-22.65427876,3.01E-11,0,0,0,-180 +116.64,50.40991179,-3.581016276,50,-22.63689784,3.83E-11,0,0,0,-180 +116.65,50.40990975,-3.581016276,50,-22.61951694,3.02E-11,0,0,0,-180 +116.66,50.40990772,-3.581016276,50,-22.59865984,1.38E-11,0,0,0,-180 +116.67,50.40990569,-3.581016276,50,-22.58475511,2.89E-12,0,0,0,-180 +116.68,50.40990366,-3.581016276,50,-22.57780273,-2.64E-12,0,0,0,-180 +116.69,50.40990163,-3.581016276,50,-22.56389799,-1.36E-11,0,0,0,-180 +116.7,50.4098996,-3.581016276,50,-22.54304089,-2.99E-11,0,0,0,-180 +116.71,50.40989758,-3.581016276,50,-22.52565998,-3.81E-11,0,0,0,-180 +116.72,50.40989555,-3.581016276,50,-22.50827906,-3.01E-11,0,0,0,-180 +116.73,50.40989353,-3.581016276,50,-22.48742196,-1.38E-11,0,0,0,-180 +116.74,50.40989151,-3.581016276,50,-22.47004103,-5.70E-12,0,0,0,-180 +116.75,50.40988949,-3.581016276,50,-22.45266011,-1.39E-11,0,0,0,-180 +116.76,50.40988747,-3.581016276,50,-22.43180301,-3.03E-11,0,0,0,-180 +116.77,50.40988546,-3.581016276,50,-22.41442209,-3.85E-11,0,0,0,-180 +116.78,50.40988344,-3.581016276,50,-22.39704116,-3.03E-11,0,0,0,-180 +116.79,50.40988143,-3.581016276,50,-22.37618407,-1.38E-11,0,0,0,-180 +116.8,50.40987942,-3.581016276,50,-22.36227934,-2.83E-12,0,0,0,-180 +116.81,50.40987741,-3.581016276,50,-22.35532698,2.64E-12,0,0,0,-180 +116.82,50.4098754,-3.581016276,50,-22.34142224,1.35E-11,0,0,0,-180 +116.83,50.40987339,-3.581016276,50,-22.32056513,2.99E-11,0,0,0,-180 +116.84,50.40987139,-3.581016276,50,-22.30318422,3.82E-11,0,0,0,-180 +116.85,50.40986938,-3.581016276,50,-22.28580332,3.01E-11,0,0,0,-180 +116.86,50.40986738,-3.581016276,50,-22.26494623,1.37E-11,0,0,0,-180 +116.87,50.40986538,-3.581016276,50,-22.25104148,2.73E-12,0,0,0,-180 +116.88,50.40986338,-3.581016276,50,-22.24408909,-2.73E-12,0,0,0,-180 +116.89,50.40986138,-3.581016276,50,-22.23018435,-1.37E-11,0,0,0,-180 +116.9,50.40985938,-3.581016276,50,-22.20932725,-3.01E-11,0,0,0,-180 +116.91,50.40985739,-3.581016276,50,-22.19194633,-3.83E-11,0,0,0,-180 +116.92,50.40985539,-3.581016276,50,-22.17456541,-3.02E-11,0,0,0,-180 +116.93,50.4098534,-3.581016276,50,-22.1537083,-1.38E-11,0,0,0,-180 +116.94,50.40985141,-3.581016276,50,-22.13632739,-5.61E-12,0,0,0,-180 +116.95,50.40984942,-3.581016276,50,-22.11894649,-1.37E-11,0,0,0,-180 +116.96,50.40984743,-3.581016276,50,-22.0980894,-2.99E-11,0,0,0,-180 +116.97,50.40984545,-3.581016276,50,-22.08070849,-3.80E-11,0,0,0,-180 +116.98,50.40984346,-3.581016276,50,-22.06332756,-2.98E-11,0,0,0,-180 +116.99,50.40984148,-3.581016276,50,-22.04247044,-1.34E-11,0,0,0,-180 +117,50.4098395,-3.581016276,50,-22.02856569,-2.48E-12,0,0,0,-180 +117.01,50.40983752,-3.581016276,50,-22.02161331,2.98E-12,0,0,0,-180 +117.02,50.40983554,-3.581016276,50,-22.00770859,1.39E-11,0,0,0,-180 +117.03,50.40983356,-3.581016276,50,-21.9868515,3.03E-11,0,0,0,-180 +117.04,50.40983159,-3.581016276,50,-21.9694706,3.84E-11,0,0,0,-180 +117.05,50.40982961,-3.581016276,50,-21.95208969,3.01E-11,0,0,0,-180 +117.06,50.40982764,-3.581016276,50,-21.93123259,1.35E-11,0,0,0,-180 +117.07,50.40982567,-3.581016276,50,-21.91732784,2.58E-12,0,0,0,-180 +117.08,50.4098237,-3.581016276,50,-21.91037546,-2.81E-12,0,0,0,-180 +117.09,50.40982173,-3.581016276,50,-21.89647073,-1.37E-11,0,0,0,-180 +117.1,50.40981976,-3.581016276,50,-21.87561363,-3.01E-11,0,0,0,-180 +117.11,50.4098178,-3.581016276,50,-21.8582327,-3.83E-11,0,0,0,-180 +117.12,50.40981583,-3.581016276,50,-21.84085177,-3.01E-11,0,0,0,-180 +117.13,50.40981387,-3.581016276,50,-21.81999468,-1.37E-11,0,0,0,-180 +117.14,50.40981191,-3.581016276,50,-21.80261378,-5.47E-12,0,0,0,-180 +117.15,50.40980995,-3.581016276,50,-21.78523287,-1.37E-11,0,0,0,-180 +117.16,50.40980799,-3.581016276,50,-21.76437577,-3.01E-11,0,0,0,-180 +117.17,50.40980604,-3.581016276,50,-21.74699484,-3.82E-11,0,0,0,-180 +117.18,50.40980408,-3.581016276,50,-21.72961392,-2.99E-11,0,0,0,-180 +117.19,50.40980213,-3.581016276,50,-21.70875682,-1.35E-11,0,0,0,-180 +117.2,50.40980018,-3.581016276,50,-21.69485208,-2.73E-12,0,0,0,-180 +117.21,50.40979823,-3.581016276,50,-21.68789972,2.58E-12,0,0,0,-180 +117.22,50.40979628,-3.581016276,50,-21.67399498,1.34E-11,0,0,0,-180 +117.23,50.40979433,-3.581016276,50,-21.65313788,2.98E-11,0,0,0,-180 +117.24,50.40979239,-3.581016276,50,-21.63575696,3.80E-11,0,0,0,-180 +117.25,50.40979044,-3.581016276,50,-21.61837604,2.98E-11,0,0,0,-180 +117.26,50.4097885,-3.581016276,50,-21.59751894,1.34E-11,0,0,0,-180 +117.27,50.40978656,-3.581016276,50,-21.5836142,2.48E-12,0,0,0,-180 +117.28,50.40978462,-3.581016276,50,-21.57666184,-2.97E-12,0,0,0,-180 +117.29,50.40978268,-3.581016276,50,-21.5627571,-1.38E-11,0,0,0,-180 +117.3,50.40978074,-3.581016276,50,-21.54190001,-3.01E-11,0,0,0,-180 +117.31,50.40977881,-3.581016276,50,-21.5245191,-3.81E-11,0,0,0,-180 +117.32,50.40977687,-3.581016276,50,-21.50713818,-2.99E-11,0,0,0,-180 +117.33,50.40977494,-3.581016276,50,-21.48628107,-1.36E-11,0,0,0,-180 +117.34,50.40977301,-3.581016276,50,-21.46890015,-5.45E-12,0,0,0,-180 +117.35,50.40977108,-3.581016276,50,-21.45151923,-1.37E-11,0,0,0,-180 +117.36,50.40976915,-3.581016276,50,-21.43066214,-3.01E-11,0,0,0,-180 +117.37,50.40976723,-3.581016276,50,-21.41328123,-3.83E-11,0,0,0,-180 +117.38,50.4097653,-3.581016276,50,-21.3959003,-3.01E-11,0,0,0,-180 +117.39,50.40976338,-3.581016276,50,-21.37504319,-1.37E-11,0,0,0,-180 +117.4,50.40976146,-3.581016276,50,-21.36113846,-2.73E-12,0,0,0,-180 +117.41,50.40975954,-3.581016276,50,-21.3541861,2.72E-12,0,0,0,-180 +117.42,50.40975762,-3.581016276,50,-21.34028137,1.36E-11,0,0,0,-180 +117.43,50.4097557,-3.581016276,50,-21.31942426,2.99E-11,0,0,0,-180 +117.44,50.40975379,-3.581016276,50,-21.30204335,3.81E-11,0,0,0,-180 +117.45,50.40975187,-3.581016276,50,-21.28466244,3.01E-11,0,0,0,-180 +117.46,50.40974996,-3.581016276,50,-21.26380534,1.38E-11,0,0,0,-180 +117.47,50.40974805,-3.581016276,50,-21.24990059,2.97E-12,0,0,0,-180 +117.48,50.40974614,-3.581016276,50,-21.24294822,-2.48E-12,0,0,0,-180 +117.49,50.40974423,-3.581016276,50,-21.22904349,-1.34E-11,0,0,0,-180 +117.5,50.40974232,-3.581016276,50,-21.2081864,-2.98E-11,0,0,0,-180 +117.51,50.40974042,-3.581016276,50,-21.19080547,-3.80E-11,0,0,0,-180 +117.52,50.40973851,-3.581016276,50,-21.17342454,-2.98E-11,0,0,0,-180 +117.53,50.40973661,-3.581016276,50,-21.15256744,-1.34E-11,0,0,0,-180 +117.54,50.40973471,-3.581016276,50,-21.13518653,-5.30E-12,0,0,0,-180 +117.55,50.40973281,-3.581016276,50,-21.11780563,-1.36E-11,0,0,0,-180 +117.56,50.40973091,-3.581016276,50,-21.09694853,-3.00E-11,0,0,0,-180 +117.57,50.40972902,-3.581016276,50,-21.07956762,-3.81E-11,0,0,0,-180 +117.58,50.40972712,-3.581016276,50,-21.0621867,-2.99E-11,0,0,0,-180 +117.59,50.40972523,-3.581016276,50,-21.04132959,-1.36E-11,0,0,0,-180 +117.6,50.40972334,-3.581016276,50,-21.02742485,-2.72E-12,0,0,0,-180 +117.61,50.40972145,-3.581016276,50,-21.02394867,1.73E-18,0,0,0,-180 +117.62,50.40971956,-3.581016276,50,-21.02047248,-2.73E-12,0,0,0,-180 +117.63,50.40971767,-3.581016276,50,-21.00309156,-1.10E-11,0,0,0,-180 +117.64,50.40971578,-3.581016276,50,-20.96832972,-1.65E-11,0,0,0,-180 +117.65,50.4097139,-3.581016276,50,-20.93356789,-1.11E-11,0,0,0,-180 +117.66,50.40971202,-3.581016276,50,-20.91618698,-2.89E-12,0,0,0,-180 +117.67,50.40971014,-3.581016276,50,-20.9127108,-7.81E-14,0,0,0,-180 +117.68,50.40970826,-3.581016276,50,-20.90923462,-2.73E-12,0,0,0,-180 +117.69,50.40970638,-3.581016276,50,-20.89532989,-1.36E-11,0,0,0,-180 +117.7,50.4097045,-3.581016276,50,-20.87447279,-2.99E-11,0,0,0,-180 +117.71,50.40970263,-3.581016276,50,-20.85709186,-3.80E-11,0,0,0,-180 +117.72,50.40970075,-3.581016276,50,-20.83971094,-2.98E-11,0,0,0,-180 +117.73,50.40969888,-3.581016276,50,-20.81885384,-1.35E-11,0,0,0,-180 +117.74,50.40969701,-3.581016276,50,-20.80494912,-2.73E-12,0,0,0,-180 +117.75,50.40969514,-3.581016276,50,-20.79799675,2.58E-12,0,0,0,-180 +117.76,50.40969327,-3.581016276,50,-20.78061582,1.07E-11,0,0,0,-180 +117.77,50.4096914,-3.581016276,50,-20.74585399,1.62E-11,0,0,0,-180 +117.78,50.40968954,-3.581016276,50,-20.71456835,1.36E-11,0,0,0,-180 +117.79,50.40968768,-3.581016276,50,-20.70761599,1.90E-11,0,0,0,-180 +117.8,50.40968582,-3.581016276,50,-20.70761599,4.09E-11,0,0,0,-180 +117.81,50.40968395,-3.581016276,50,-20.69023507,5.45E-11,0,0,0,-180 +117.82,50.4096821,-3.581016276,50,-20.66937796,3.82E-11,0,0,0,-180 +117.83,50.40968024,-3.581016276,50,-20.65547322,5.45E-12,0,0,0,-180 +117.84,50.40967838,-3.581016276,50,-20.63461613,-1.09E-11,0,0,0,-180 +117.85,50.40967653,-3.581016276,50,-20.61723522,2.73E-12,0,0,0,-180 +117.86,50.40967468,-3.581016276,50,-20.61375902,2.19E-11,0,0,0,-180 +117.87,50.40967282,-3.581016276,50,-20.59637811,1.37E-11,0,0,0,-180 +117.88,50.40967097,-3.581016276,50,-20.56161629,-1.37E-11,0,0,0,-180 +117.89,50.40966913,-3.581016276,50,-20.54423538,-2.19E-11,0,0,0,-180 +117.9,50.40966728,-3.581016276,50,-20.54075918,-2.73E-12,0,0,0,-180 +117.91,50.40966543,-3.581016276,50,-20.51990207,1.37E-11,0,0,0,-180 +117.92,50.40966359,-3.581016276,50,-20.48861642,1.09E-11,0,0,0,-180 +117.93,50.40966175,-3.581016276,50,-20.47123551,2.58E-12,0,0,0,-180 +117.94,50.40965991,-3.581016276,50,-20.46775933,-1.41E-13,0,0,0,-180 +117.95,50.40965807,-3.581016276,50,-20.46428315,2.73E-12,0,0,0,-180 +117.96,50.40965623,-3.581016276,50,-20.44690224,1.11E-11,0,0,0,-180 +117.97,50.40965439,-3.581016276,50,-20.41561658,1.39E-11,0,0,0,-180 +117.98,50.40965256,-3.581016276,50,-20.39475947,-2.48E-12,0,0,0,-180 +117.99,50.40965073,-3.581016276,50,-20.39475946,-2.44E-11,0,0,0,-180 +118,50.40964889,-3.581016276,50,-20.38780711,-2.98E-11,0,0,0,-180 +118.01,50.40964706,-3.581016276,50,-20.35652147,-2.71E-11,0,0,0,-180 +118.02,50.40964523,-3.581016276,50,-20.32175964,-3.27E-11,0,0,0,-180 +118.03,50.40964341,-3.581016276,50,-20.30437873,-4.10E-11,0,0,0,-180 +118.04,50.40964158,-3.581016276,50,-20.30090254,-4.39E-11,0,0,0,-180 +118.05,50.40963976,-3.581016276,50,-20.29742635,-4.12E-11,0,0,0,-180 +118.06,50.40963793,-3.581016276,50,-20.28352161,-3.02E-11,0,0,0,-180 +118.07,50.40963611,-3.581016276,50,-20.25918834,-1.10E-11,0,0,0,-180 +118.08,50.40963429,-3.581016276,50,-20.23137888,1.07E-11,0,0,0,-180 +118.09,50.40963247,-3.581016276,50,-20.20704558,2.97E-11,0,0,0,-180 +118.1,50.40963066,-3.581016276,50,-20.18966464,3.79E-11,0,0,0,-180 +118.11,50.40962884,-3.581016276,50,-20.17228372,2.99E-11,0,0,0,-180 +118.12,50.40962703,-3.581016276,50,-20.15142664,1.37E-11,0,0,0,-180 +118.13,50.40962522,-3.581016276,50,-20.13752193,2.87E-12,0,0,0,-180 +118.14,50.40962341,-3.581016276,50,-20.13404574,7.81E-14,0,0,0,-180 +118.15,50.4096216,-3.581016276,50,-20.13056955,2.75E-12,0,0,0,-180 +118.16,50.40961979,-3.581016276,50,-20.11666482,1.37E-11,0,0,0,-180 +118.17,50.40961798,-3.581016276,50,-20.09580772,3.01E-11,0,0,0,-180 +118.18,50.40961618,-3.581016276,50,-20.0784268,3.82E-11,0,0,0,-180 +118.19,50.40961437,-3.581016276,50,-20.06104589,2.99E-11,0,0,0,-180 +118.2,50.40961257,-3.581016276,50,-20.03671262,1.07E-11,0,0,0,-180 +118.21,50.40961077,-3.581016276,50,-20.00890316,-1.12E-11,0,0,0,-180 +118.22,50.40960897,-3.581016276,50,-19.98804605,-2.76E-11,0,0,0,-180 +118.23,50.40960718,-3.581016276,50,-19.98456985,-2.49E-11,0,0,0,-180 +118.24,50.40960538,-3.581016276,50,-19.98456984,-2.98E-12,0,0,0,-180 +118.25,50.40960358,-3.581016276,50,-19.96371275,1.34E-11,0,0,0,-180 +118.26,50.40960179,-3.581016276,50,-19.93242712,1.07E-11,0,0,0,-180 +118.27,50.4096,-3.581016276,50,-19.91157002,5.22E-12,0,0,0,-180 +118.28,50.40959821,-3.581016276,50,-19.89418909,1.34E-11,0,0,0,-180 +118.29,50.40959642,-3.581016276,50,-19.87333198,2.99E-11,0,0,0,-180 +118.3,50.40959464,-3.581016276,50,-19.85942726,4.09E-11,0,0,0,-180 +118.31,50.40959285,-3.581016276,50,-19.8559511,4.38E-11,0,0,0,-180 +118.32,50.40959107,-3.581016276,50,-19.85247491,4.11E-11,0,0,0,-180 +118.33,50.40958928,-3.581016276,50,-19.83509397,3.30E-11,0,0,0,-180 +118.34,50.4095875,-3.581016276,50,-19.80033213,2.74E-11,0,0,0,-180 +118.35,50.40958572,-3.581016276,50,-19.76904649,2.99E-11,0,0,0,-180 +118.36,50.40958395,-3.581016276,50,-19.76209413,2.43E-11,0,0,0,-180 +118.37,50.40958217,-3.581016276,50,-19.76209413,2.58E-12,0,0,0,-180 +118.38,50.40958039,-3.581016276,50,-19.74123704,-1.36E-11,0,0,0,-180 +118.39,50.40957862,-3.581016276,50,-19.7099514,-1.08E-11,0,0,0,-180 +118.4,50.40957685,-3.581016276,50,-19.69257047,-2.66E-12,0,0,0,-180 +118.41,50.40957508,-3.581016276,50,-19.68561809,2.73E-12,0,0,0,-180 +118.42,50.40957331,-3.581016276,50,-19.67171337,1.36E-11,0,0,0,-180 +118.43,50.40957154,-3.581016276,50,-19.65085628,2.99E-11,0,0,0,-180 +118.44,50.40956978,-3.581016276,50,-19.63347537,3.81E-11,0,0,0,-180 +118.45,50.40956801,-3.581016276,50,-19.61609444,3.01E-11,0,0,0,-180 +118.46,50.40956625,-3.581016276,50,-19.59523734,1.38E-11,0,0,0,-180 +118.47,50.40956449,-3.581016276,50,-19.58133262,2.97E-12,0,0,0,-180 +118.48,50.40956273,-3.581016276,50,-19.57438024,-2.48E-12,0,0,0,-180 +118.49,50.40956097,-3.581016276,50,-19.5604755,-1.34E-11,0,0,0,-180 +118.5,50.40955921,-3.581016276,50,-19.5396184,-2.98E-11,0,0,0,-180 +118.51,50.40955746,-3.581016276,50,-19.52223749,-3.80E-11,0,0,0,-180 +118.52,50.4095557,-3.581016276,50,-19.50485658,-2.99E-11,0,0,0,-180 +118.53,50.40955395,-3.581016276,50,-19.48399948,-1.36E-11,0,0,0,-180 +118.54,50.4095522,-3.581016276,50,-19.46661856,-5.38E-12,0,0,0,-180 +118.55,50.40955045,-3.581016276,50,-19.44923765,-1.35E-11,0,0,0,-180 +118.56,50.4095487,-3.581016276,50,-19.42838056,-2.99E-11,0,0,0,-180 +118.57,50.40954696,-3.581016276,50,-19.41099964,-3.82E-11,0,0,0,-180 +118.58,50.40954521,-3.581016276,50,-19.39361872,-3.01E-11,0,0,0,-180 +118.59,50.40954347,-3.581016276,50,-19.37276162,-1.37E-11,0,0,0,-180 +118.6,50.40954173,-3.581016276,50,-19.3588569,-2.73E-12,0,0,0,-180 +118.61,50.40953999,-3.581016276,50,-19.35538071,1.04E-17,0,0,0,-180 +118.62,50.40953825,-3.581016276,50,-19.35190451,-2.73E-12,0,0,0,-180 +118.63,50.40953651,-3.581016276,50,-19.33452359,-1.09E-11,0,0,0,-180 +118.64,50.40953477,-3.581016276,50,-19.29976178,-1.64E-11,0,0,0,-180 +118.65,50.40953304,-3.581016276,50,-19.26499997,-1.09E-11,0,0,0,-180 +118.66,50.40953131,-3.581016276,50,-19.24761904,-2.58E-12,0,0,0,-180 +118.67,50.40952958,-3.581016276,50,-19.24414284,1.41E-13,0,0,0,-180 +118.68,50.40952785,-3.581016276,50,-19.24066664,-2.73E-12,0,0,0,-180 +118.69,50.40952612,-3.581016276,50,-19.22676192,-1.38E-11,0,0,0,-180 +118.7,50.40952439,-3.581016276,50,-19.20590483,-3.02E-11,0,0,0,-180 +118.71,50.40952267,-3.581016276,50,-19.18852392,-3.83E-11,0,0,0,-180 +118.72,50.40952094,-3.581016276,50,-19.171143,-2.99E-11,0,0,0,-180 +118.73,50.40951922,-3.581016276,50,-19.15028591,-1.34E-11,0,0,0,-180 +118.74,50.4095175,-3.581016276,50,-19.13638118,-2.48E-12,0,0,0,-180 +118.75,50.40951578,-3.581016276,50,-19.12942881,2.97E-12,0,0,0,-180 +118.76,50.40951406,-3.581016276,50,-19.11204789,1.11E-11,0,0,0,-180 +118.77,50.40951234,-3.581016276,50,-19.08076225,1.38E-11,0,0,0,-180 +118.78,50.40951063,-3.581016276,50,-19.05990515,-2.64E-12,0,0,0,-180 +118.79,50.40950892,-3.581016276,50,-19.05642896,-2.17E-11,0,0,0,-180 +118.8,50.4095072,-3.581016276,50,-19.03904804,-1.35E-11,0,0,0,-180 +118.81,50.40950549,-3.581016276,50,-19.00428621,1.38E-11,0,0,0,-180 +118.82,50.40950379,-3.581016276,50,-18.9869053,2.19E-11,0,0,0,-180 +118.83,50.40950208,-3.581016276,50,-18.9869053,-1.73E-17,0,0,0,-180 +118.84,50.40950037,-3.581016276,50,-18.97995294,-2.73E-11,0,0,0,-180 +118.85,50.40949867,-3.581016276,50,-18.96604821,-3.83E-11,0,0,0,-180 +118.86,50.40949696,-3.581016276,50,-18.94866728,-3.01E-11,0,0,0,-180 +118.87,50.40949526,-3.581016276,50,-18.92433399,-1.09E-11,0,0,0,-180 +118.88,50.40949356,-3.581016276,50,-18.89652454,1.09E-11,0,0,0,-180 +118.89,50.40949186,-3.581016276,50,-18.87219127,3.01E-11,0,0,0,-180 +118.9,50.40949017,-3.581016276,50,-18.85481035,3.82E-11,0,0,0,-180 +118.91,50.40948847,-3.581016276,50,-18.83742944,2.99E-11,0,0,0,-180 +118.92,50.40948678,-3.581016276,50,-18.81657235,1.35E-11,0,0,0,-180 +118.93,50.40948509,-3.581016276,50,-18.80266762,2.73E-12,0,0,0,-180 +118.94,50.4094834,-3.581016276,50,-18.79919142,1.41E-13,0,0,0,-180 +118.95,50.40948171,-3.581016276,50,-18.79571523,2.88E-12,0,0,0,-180 +118.96,50.40948002,-3.581016276,50,-18.7818105,1.37E-11,0,0,0,-180 +118.97,50.40947833,-3.581016276,50,-18.7609534,2.99E-11,0,0,0,-180 +118.98,50.40947665,-3.581016276,50,-18.74357249,3.80E-11,0,0,0,-180 +118.99,50.40947496,-3.581016276,50,-18.72619157,2.98E-11,0,0,0,-180 +119,50.40947328,-3.581016276,50,-18.70533447,1.34E-11,0,0,0,-180 +119.01,50.4094716,-3.581016276,50,-18.68795356,5.30E-12,0,0,0,-180 +119.02,50.40946992,-3.581016276,50,-18.67057265,1.36E-11,0,0,0,-180 +119.03,50.40946824,-3.581016276,50,-18.64971555,3.00E-11,0,0,0,-180 +119.04,50.40946657,-3.581016276,50,-18.63233464,3.81E-11,0,0,0,-180 +119.05,50.40946489,-3.581016276,50,-18.61495372,2.99E-11,0,0,0,-180 +119.06,50.40946322,-3.581016276,50,-18.59409662,1.36E-11,0,0,0,-180 +119.07,50.40946155,-3.581016276,50,-18.5801919,2.72E-12,0,0,0,-180 +119.08,50.40945988,-3.581016276,50,-18.57323953,-2.73E-12,0,0,0,-180 +119.09,50.40945821,-3.581016276,50,-18.55585861,-1.09E-11,0,0,0,-180 +119.1,50.40945654,-3.581016276,50,-18.52457296,-1.37E-11,0,0,0,-180 +119.11,50.40945488,-3.581016276,50,-18.50371586,2.73E-12,0,0,0,-180 +119.12,50.40945322,-3.581016276,50,-18.50371586,2.46E-11,0,0,0,-180 +119.13,50.40945155,-3.581016276,50,-18.50023969,2.73E-11,0,0,0,-180 +119.14,50.40944989,-3.581016276,50,-18.47938259,1.10E-11,0,0,0,-180 +119.15,50.40944823,-3.581016276,50,-18.45157312,-1.09E-11,0,0,0,-180 +119.16,50.40944657,-3.581016276,50,-18.42723984,-2.99E-11,0,0,0,-180 +119.17,50.40944492,-3.581016276,50,-18.40985893,-3.81E-11,0,0,0,-180 +119.18,50.40944326,-3.581016276,50,-18.39247802,-3.01E-11,0,0,0,-180 +119.19,50.40944161,-3.581016276,50,-18.37162093,-1.38E-11,0,0,0,-180 +119.2,50.40943996,-3.581016276,50,-18.35771619,-2.97E-12,0,0,0,-180 +119.21,50.40943831,-3.581016276,50,-18.35076382,2.48E-12,0,0,0,-180 +119.22,50.40943666,-3.581016276,50,-18.33685908,1.34E-11,0,0,0,-180 +119.23,50.40943501,-3.581016276,50,-18.31600198,2.98E-11,0,0,0,-180 +119.24,50.40943337,-3.581016276,50,-18.29862107,3.80E-11,0,0,0,-180 +119.25,50.40943172,-3.581016276,50,-18.28124016,2.99E-11,0,0,0,-180 +119.26,50.40943008,-3.581016276,50,-18.26038308,1.37E-11,0,0,0,-180 +119.27,50.40942844,-3.581016276,50,-18.24647835,2.88E-12,0,0,0,-180 +119.28,50.4094268,-3.581016276,50,-18.23952598,-2.58E-12,0,0,0,-180 +119.29,50.40942516,-3.581016276,50,-18.22562125,-1.36E-11,0,0,0,-180 +119.3,50.40942352,-3.581016276,50,-18.20476414,-3.00E-11,0,0,0,-180 +119.31,50.40942189,-3.581016276,50,-18.18738321,-3.81E-11,0,0,0,-180 +119.32,50.40942025,-3.581016276,50,-18.1700023,-2.99E-11,0,0,0,-180 +119.33,50.40941862,-3.581016276,50,-18.14914521,-1.36E-11,0,0,0,-180 +119.34,50.40941699,-3.581016276,50,-18.1317643,-5.44E-12,0,0,0,-180 +119.35,50.40941536,-3.581016276,50,-18.11438339,-1.36E-11,0,0,0,-180 +119.36,50.40941373,-3.581016276,50,-18.09352629,-2.99E-11,0,0,0,-180 +119.37,50.40941211,-3.581016276,50,-18.07614537,-3.81E-11,0,0,0,-180 +119.38,50.40941048,-3.581016276,50,-18.06224064,-2.73E-11,0,0,0,-180 +119.39,50.40940886,-3.581016276,50,-18.05181209,2.73E-12,0,0,0,-180 +119.4,50.40940724,-3.581016276,50,-18.04138354,3.82E-11,0,0,0,-180 +119.41,50.40940561,-3.581016276,50,-18.02052643,5.45E-11,0,0,0,-180 +119.42,50.409404,-3.581016276,50,-17.99966933,3.81E-11,0,0,0,-180 +119.43,50.40940238,-3.581016276,50,-17.98924079,2.73E-12,0,0,0,-180 +119.44,50.40940076,-3.581016276,50,-17.97881225,-2.72E-11,0,0,0,-180 +119.45,50.40939915,-3.581016276,50,-17.96490751,-3.81E-11,0,0,0,-180 +119.46,50.40939753,-3.581016276,50,-17.94752659,-3.01E-11,0,0,0,-180 +119.47,50.40939592,-3.581016276,50,-17.92319332,-1.11E-11,0,0,0,-180 +119.48,50.40939431,-3.581016276,50,-17.89538387,1.07E-11,0,0,0,-180 +119.49,50.4093927,-3.581016276,50,-17.87105059,2.99E-11,0,0,0,-180 +119.5,50.4093911,-3.581016276,50,-17.85366967,3.82E-11,0,0,0,-180 +119.51,50.40938949,-3.581016276,50,-17.83628876,3.00E-11,0,0,0,-180 +119.52,50.40938789,-3.581016276,50,-17.81543166,1.35E-11,0,0,0,-180 +119.53,50.40938629,-3.581016276,50,-17.80152694,2.58E-12,0,0,0,-180 +119.54,50.40938469,-3.581016276,50,-17.79805077,-7.81E-14,0,0,0,-180 +119.55,50.40938309,-3.581016276,50,-17.79457458,2.72E-12,0,0,0,-180 +119.56,50.40938149,-3.581016276,50,-17.78066984,1.37E-11,0,0,0,-180 +119.57,50.40937989,-3.581016276,50,-17.75981273,3.00E-11,0,0,0,-180 +119.58,50.4093783,-3.581016276,50,-17.7424318,3.81E-11,0,0,0,-180 +119.59,50.4093767,-3.581016276,50,-17.72505089,2.99E-11,0,0,0,-180 +119.6,50.40937511,-3.581016276,50,-17.7041938,1.35E-11,0,0,0,-180 +119.61,50.40937352,-3.581016276,50,-17.68681289,5.30E-12,0,0,0,-180 +119.62,50.40937193,-3.581016276,50,-17.66943197,1.35E-11,0,0,0,-180 +119.63,50.40937034,-3.581016276,50,-17.64857488,3.00E-11,0,0,0,-180 +119.64,50.40936876,-3.581016276,50,-17.63119396,3.83E-11,0,0,0,-180 +119.65,50.40936717,-3.581016276,50,-17.61381306,3.02E-11,0,0,0,-180 +119.66,50.40936559,-3.581016276,50,-17.59295598,1.38E-11,0,0,0,-180 +119.67,50.40936401,-3.581016276,50,-17.57905124,2.87E-12,0,0,0,-180 +119.68,50.40936243,-3.581016276,50,-17.57209886,-2.73E-12,0,0,0,-180 +119.69,50.40936085,-3.581016276,50,-17.55819412,-1.38E-11,0,0,0,-180 +119.7,50.40935927,-3.581016276,50,-17.53733702,-3.03E-11,0,0,0,-180 +119.71,50.4093577,-3.581016276,50,-17.51995611,-3.85E-11,0,0,0,-180 +119.72,50.40935612,-3.581016276,50,-17.5025752,-3.03E-11,0,0,0,-180 +119.73,50.40935455,-3.581016276,50,-17.48171812,-1.39E-11,0,0,0,-180 +119.74,50.40935298,-3.581016276,50,-17.46433721,-5.70E-12,0,0,0,-180 +119.75,50.40935141,-3.581016276,50,-17.44695629,-1.38E-11,0,0,0,-180 +119.76,50.40934984,-3.581016276,50,-17.42609917,-3.02E-11,0,0,0,-180 +119.77,50.40934828,-3.581016276,50,-17.40871827,-3.84E-11,0,0,0,-180 +119.78,50.40934671,-3.581016276,50,-17.39133737,-3.02E-11,0,0,0,-180 +119.79,50.40934515,-3.581016276,50,-17.37048028,-1.38E-11,0,0,0,-180 +119.8,50.40934359,-3.581016276,50,-17.35657554,-2.81E-12,0,0,0,-180 +119.81,50.40934203,-3.581016276,50,-17.35309935,-1.56E-14,0,0,0,-180 +119.82,50.40934047,-3.581016276,50,-17.34962316,-2.73E-12,0,0,0,-180 +119.83,50.40933891,-3.581016276,50,-17.33224224,-1.09E-11,0,0,0,-180 +119.84,50.40933735,-3.581016276,50,-17.29748042,-1.64E-11,0,0,0,-180 +119.85,50.4093358,-3.581016276,50,-17.2627186,-1.09E-11,0,0,0,-180 +119.86,50.40933425,-3.581016276,50,-17.2453377,-2.72E-12,0,0,0,-180 +119.87,50.4093327,-3.581016276,50,-17.24186151,7.81E-14,0,0,0,-180 +119.88,50.40933115,-3.581016276,50,-17.24186151,1.56E-13,0,0,0,-180 +119.89,50.4093296,-3.581016276,50,-17.23838532,2.89E-12,0,0,0,-180 +119.9,50.40932805,-3.581016276,50,-17.22100441,1.10E-11,0,0,0,-180 +119.91,50.4093265,-3.581016276,50,-17.18624258,1.65E-11,0,0,0,-180 +119.92,50.40932496,-3.581016276,50,-17.15148075,1.11E-11,0,0,0,-180 +119.93,50.40932342,-3.581016276,50,-17.13409984,2.97E-12,0,0,0,-180 +119.94,50.40932188,-3.581016276,50,-17.13062365,2.34E-13,0,0,0,-180 +119.95,50.40932034,-3.581016276,50,-17.12714747,2.89E-12,0,0,0,-180 +119.96,50.4093188,-3.581016276,50,-17.11324273,1.37E-11,0,0,0,-180 +119.97,50.40931726,-3.581016276,50,-17.09238564,3.00E-11,0,0,0,-180 +119.98,50.40931573,-3.581016276,50,-17.07500473,3.83E-11,0,0,0,-180 +119.99,50.40931419,-3.581016276,50,-17.05762383,3.02E-11,0,0,0,-180 +120,50.40931266,-3.581016276,50,-17.03329055,1.11E-11,0,0,0,-180 +120.01,50.40931113,-3.581016276,50,-17.00548108,-1.08E-11,0,0,0,-180 +120.02,50.4093096,-3.581016276,50,-16.98114781,-3.00E-11,0,0,0,-180 +120.03,50.40930808,-3.581016276,50,-16.96724308,-4.09E-11,0,0,0,-180 +120.04,50.40930655,-3.581016276,50,-16.96376689,-4.36E-11,0,0,0,-180 +120.05,50.40930503,-3.581016276,50,-16.96029069,-4.09E-11,0,0,0,-180 +120.06,50.4093035,-3.581016276,50,-16.94638596,-3.01E-11,0,0,0,-180 +120.07,50.40930198,-3.581016276,50,-16.9220527,-1.09E-11,0,0,0,-180 +120.08,50.40930046,-3.581016276,50,-16.89424324,1.09E-11,0,0,0,-180 +120.09,50.40929894,-3.581016276,50,-16.86990996,3.01E-11,0,0,0,-180 +120.1,50.40929743,-3.581016276,50,-16.85600523,4.10E-11,0,0,0,-180 +120.11,50.40929591,-3.581016276,50,-16.85252904,4.37E-11,0,0,0,-180 +120.12,50.4092944,-3.581016276,50,-16.84905285,4.09E-11,0,0,0,-180 +120.13,50.40929288,-3.581016276,50,-16.83514813,2.99E-11,0,0,0,-180 +120.14,50.40929137,-3.581016276,50,-16.81081485,1.08E-11,0,0,0,-180 +120.15,50.40928986,-3.581016276,50,-16.78300539,-1.09E-11,0,0,0,-180 +120.16,50.40928835,-3.581016276,50,-16.75867211,-2.99E-11,0,0,0,-180 +120.17,50.40928685,-3.581016276,50,-16.7412912,-3.81E-11,0,0,0,-180 +120.18,50.40928534,-3.581016276,50,-16.72391029,-3.01E-11,0,0,0,-180 +120.19,50.40928384,-3.581016276,50,-16.70305319,-1.38E-11,0,0,0,-180 +120.2,50.40928234,-3.581016276,50,-16.68914846,-2.97E-12,0,0,0,-180 +120.21,50.40928084,-3.581016276,50,-16.68219609,2.48E-12,0,0,0,-180 +120.22,50.40927934,-3.581016276,50,-16.66829135,1.34E-11,0,0,0,-180 +120.23,50.40927784,-3.581016276,50,-16.64743426,2.99E-11,0,0,0,-180 +120.24,50.40927635,-3.581016276,50,-16.63005334,3.82E-11,0,0,0,-180 +120.25,50.40927485,-3.581016276,50,-16.61267244,3.00E-11,0,0,0,-180 +120.26,50.40927336,-3.581016276,50,-16.59181535,1.35E-11,0,0,0,-180 +120.27,50.40927187,-3.581016276,50,-16.57791062,2.58E-12,0,0,0,-180 +120.28,50.40927038,-3.581016276,50,-16.57443443,-9.37E-14,0,0,0,-180 +120.29,50.40926889,-3.581016276,50,-16.57095824,2.62E-12,0,0,0,-180 +120.3,50.4092674,-3.581016276,50,-16.55357732,1.07E-11,0,0,0,-180 +120.31,50.40926591,-3.581016276,50,-16.51881551,1.61E-11,0,0,0,-180 +120.32,50.40926443,-3.581016276,50,-16.4840537,1.07E-11,0,0,0,-180 +120.33,50.40926295,-3.581016276,50,-16.46667278,2.64E-12,0,0,0,-180 +120.34,50.40926147,-3.581016276,50,-16.46319658,-1.57E-14,0,0,0,-180 +120.35,50.40925999,-3.581016276,50,-16.4597204,2.73E-12,0,0,0,-180 +120.36,50.40925851,-3.581016276,50,-16.44233949,1.10E-11,0,0,0,-180 +120.37,50.40925703,-3.581016276,50,-16.41105386,1.37E-11,0,0,0,-180 +120.38,50.40925556,-3.581016276,50,-16.39019676,-2.58E-12,0,0,0,-180 +120.39,50.40925409,-3.581016276,50,-16.39019674,-2.45E-11,0,0,0,-180 +120.4,50.40925261,-3.581016276,50,-16.38324437,-3.00E-11,0,0,0,-180 +120.41,50.40925114,-3.581016276,50,-16.35195874,-2.72E-11,0,0,0,-180 +120.42,50.40924967,-3.581016276,50,-16.31719692,-3.26E-11,0,0,0,-180 +120.43,50.40924821,-3.581016276,50,-16.29981601,-4.08E-11,0,0,0,-180 +120.44,50.40924674,-3.581016276,50,-16.29633983,-4.35E-11,0,0,0,-180 +120.45,50.40924528,-3.581016276,50,-16.29286364,-4.08E-11,0,0,0,-180 +120.46,50.40924381,-3.581016276,50,-16.27895891,-2.98E-11,0,0,0,-180 +120.47,50.40924235,-3.581016276,50,-16.25462564,-1.07E-11,0,0,0,-180 +120.48,50.40924089,-3.581016276,50,-16.22681618,1.11E-11,0,0,0,-180 +120.49,50.40923943,-3.581016276,50,-16.20248289,3.01E-11,0,0,0,-180 +120.5,50.40923798,-3.581016276,50,-16.18857816,4.09E-11,0,0,0,-180 +120.51,50.40923652,-3.581016276,50,-16.18510198,4.36E-11,0,0,0,-180 +120.52,50.40923507,-3.581016276,50,-16.1816258,4.09E-11,0,0,0,-180 +120.53,50.40923361,-3.581016276,50,-16.16772106,3.01E-11,0,0,0,-180 +120.54,50.40923216,-3.581016276,50,-16.14338779,1.09E-11,0,0,0,-180 +120.55,50.40923071,-3.581016276,50,-16.11557835,-1.09E-11,0,0,0,-180 +120.56,50.40922926,-3.581016276,50,-16.09124508,-3.01E-11,0,0,0,-180 +120.57,50.40922782,-3.581016276,50,-16.07386414,-3.83E-11,0,0,0,-180 +120.58,50.40922637,-3.581016276,50,-16.05648321,-3.01E-11,0,0,0,-180 +120.59,50.40922493,-3.581016276,50,-16.03562612,-1.37E-11,0,0,0,-180 +120.6,50.40922349,-3.581016276,50,-16.02172141,-2.73E-12,0,0,0,-180 +120.61,50.40922205,-3.581016276,50,-16.01824524,-1.56E-14,0,0,0,-180 +120.62,50.40922061,-3.581016276,50,-16.01476904,-2.81E-12,0,0,0,-180 +120.63,50.40921917,-3.581016276,50,-15.99738813,-1.11E-11,0,0,0,-180 +120.64,50.40921773,-3.581016276,50,-15.9626263,-1.65E-11,0,0,0,-180 +120.65,50.4092163,-3.581016276,50,-15.92786447,-1.09E-11,0,0,0,-180 +120.66,50.40921487,-3.581016276,50,-15.91048355,-2.58E-12,0,0,0,-180 +120.67,50.40921344,-3.581016276,50,-15.90700738,2.34E-13,0,0,0,-180 +120.68,50.40921201,-3.581016276,50,-15.90700738,2.34E-13,0,0,0,-180 +120.69,50.40921058,-3.581016276,50,-15.9035312,2.89E-12,0,0,0,-180 +120.7,50.40920915,-3.581016276,50,-15.88615029,1.10E-11,0,0,0,-180 +120.71,50.40920772,-3.581016276,50,-15.85138847,1.63E-11,0,0,0,-180 +120.72,50.4092063,-3.581016276,50,-15.81662665,1.09E-11,0,0,0,-180 +120.73,50.40920488,-3.581016276,50,-15.79924573,2.64E-12,0,0,0,-180 +120.74,50.40920346,-3.581016276,50,-15.79576954,-1.56E-13,0,0,0,-180 +120.75,50.40920204,-3.581016276,50,-15.79229333,2.58E-12,0,0,0,-180 +120.76,50.40920062,-3.581016276,50,-15.7783886,1.36E-11,0,0,0,-180 +120.77,50.4091992,-3.581016276,50,-15.75753152,3.00E-11,0,0,0,-180 +120.78,50.40919779,-3.581016276,50,-15.74015063,3.81E-11,0,0,0,-180 +120.79,50.40919637,-3.581016276,50,-15.72276972,2.99E-11,0,0,0,-180 +120.8,50.40919496,-3.581016276,50,-15.69843643,1.09E-11,0,0,0,-180 +120.81,50.40919355,-3.581016276,50,-15.67062697,-1.09E-11,0,0,0,-180 +120.82,50.40919214,-3.581016276,50,-15.64976988,-2.72E-11,0,0,0,-180 +120.83,50.40919074,-3.581016276,50,-15.6462937,-2.45E-11,0,0,0,-180 +120.84,50.40918933,-3.581016276,50,-15.64629369,-2.89E-12,0,0,0,-180 +120.85,50.40918792,-3.581016276,50,-15.6254366,1.34E-11,0,0,0,-180 +120.86,50.40918652,-3.581016276,50,-15.59415096,1.07E-11,0,0,0,-180 +120.87,50.40918512,-3.581016276,50,-15.57677004,2.63E-12,0,0,0,-180 +120.88,50.40918372,-3.581016276,50,-15.56981767,-2.83E-12,0,0,0,-180 +120.89,50.40918232,-3.581016276,50,-15.55591295,-1.38E-11,0,0,0,-180 +120.9,50.40918092,-3.581016276,50,-15.53505586,-3.02E-11,0,0,0,-180 +120.91,50.40917953,-3.581016276,50,-15.51767496,-3.83E-11,0,0,0,-180 +120.92,50.40917813,-3.581016276,50,-15.50029405,-3.00E-11,0,0,0,-180 +120.93,50.40917674,-3.581016276,50,-15.47943695,-1.37E-11,0,0,0,-180 +120.94,50.40917535,-3.581016276,50,-15.46205602,-5.63E-12,0,0,0,-180 +120.95,50.40917396,-3.581016276,50,-15.4446751,-1.39E-11,0,0,0,-180 +120.96,50.40917257,-3.581016276,50,-15.423818,-3.03E-11,0,0,0,-180 +120.97,50.40917119,-3.581016276,50,-15.4064371,-3.84E-11,0,0,0,-180 +120.98,50.4091698,-3.581016276,50,-15.38905619,-3.01E-11,0,0,0,-180 +120.99,50.40916842,-3.581016276,50,-15.3681991,-1.35E-11,0,0,0,-180 +121,50.40916704,-3.581016276,50,-15.35429438,-2.58E-12,0,0,0,-180 +121.01,50.40916566,-3.581016276,50,-15.3508182,7.81E-14,0,0,0,-180 +121.02,50.40916428,-3.581016276,50,-15.34734202,-2.72E-12,0,0,0,-180 +121.03,50.4091629,-3.581016276,50,-15.32996109,-1.09E-11,0,0,0,-180 +121.04,50.40916152,-3.581016276,50,-15.29867544,-1.37E-11,0,0,0,-180 +121.05,50.40916015,-3.581016276,50,-15.27781835,2.73E-12,0,0,0,-180 +121.06,50.40915878,-3.581016276,50,-15.27434217,2.19E-11,0,0,0,-180 +121.07,50.4091574,-3.581016276,50,-15.25696127,1.37E-11,0,0,0,-180 +121.08,50.40915603,-3.581016276,50,-15.22219944,-1.37E-11,0,0,0,-180 +121.09,50.40915467,-3.581016276,50,-15.20481852,-2.19E-11,0,0,0,-180 +121.1,50.4091533,-3.581016276,50,-15.20134233,-2.72E-12,0,0,0,-180 +121.11,50.40915193,-3.581016276,50,-15.18048524,1.38E-11,0,0,0,-180 +121.12,50.40915057,-3.581016276,50,-15.14919962,1.11E-11,0,0,0,-180 +121.13,50.40914921,-3.581016276,50,-15.13181872,2.88E-12,0,0,0,-180 +121.14,50.40914785,-3.581016276,50,-15.12834252,1.56E-17,0,0,0,-180 +121.15,50.40914649,-3.581016276,50,-15.12486632,2.58E-12,0,0,0,-180 +121.16,50.40914513,-3.581016276,50,-15.11096159,1.34E-11,0,0,0,-180 +121.17,50.40914377,-3.581016276,50,-15.0901045,2.98E-11,0,0,0,-180 +121.18,50.40914242,-3.581016276,50,-15.07272358,3.80E-11,0,0,0,-180 +121.19,50.40914106,-3.581016276,50,-15.05534268,2.98E-11,0,0,0,-180 +121.2,50.40913971,-3.581016276,50,-15.0344856,1.34E-11,0,0,0,-180 +121.21,50.40913836,-3.581016276,50,-15.01710468,5.31E-12,0,0,0,-180 +121.22,50.40913701,-3.581016276,50,-14.99972377,1.37E-11,0,0,0,-180 +121.23,50.40913566,-3.581016276,50,-14.97886668,3.02E-11,0,0,0,-180 +121.24,50.40913432,-3.581016276,50,-14.96148576,3.84E-11,0,0,0,-180 +121.25,50.40913297,-3.581016276,50,-14.94410484,3.02E-11,0,0,0,-180 +121.26,50.40913163,-3.581016276,50,-14.92324774,1.37E-11,0,0,0,-180 +121.27,50.40913029,-3.581016276,50,-14.90934302,2.73E-12,0,0,0,-180 +121.28,50.40912895,-3.581016276,50,-14.90239066,-2.73E-12,0,0,0,-180 +121.29,50.40912761,-3.581016276,50,-14.88848593,-1.37E-11,0,0,0,-180 +121.3,50.40912627,-3.581016276,50,-14.86762884,-3.01E-11,0,0,0,-180 +121.31,50.40912494,-3.581016276,50,-14.85024793,-3.83E-11,0,0,0,-180 +121.32,50.4091236,-3.581016276,50,-14.83286702,-3.01E-11,0,0,0,-180 +121.33,50.40912227,-3.581016276,50,-14.81200992,-1.37E-11,0,0,0,-180 +121.34,50.40912094,-3.581016276,50,-14.79810518,-2.73E-12,0,0,0,-180 +121.35,50.40911961,-3.581016276,50,-14.79115282,2.72E-12,0,0,0,-180 +121.36,50.40911828,-3.581016276,50,-14.7737719,1.09E-11,0,0,0,-180 +121.37,50.40911695,-3.581016276,50,-14.74248626,1.35E-11,0,0,0,-180 +121.38,50.40911563,-3.581016276,50,-14.72162917,-2.87E-12,0,0,0,-180 +121.39,50.40911431,-3.581016276,50,-14.72162918,-2.46E-11,0,0,0,-180 +121.4,50.40911298,-3.581016276,50,-14.71467682,-2.99E-11,0,0,0,-180 +121.41,50.40911166,-3.581016276,50,-14.68339118,-2.71E-11,0,0,0,-180 +121.42,50.40911034,-3.581016276,50,-14.64862936,-3.26E-11,0,0,0,-180 +121.43,50.40910903,-3.581016276,50,-14.63124844,-4.08E-11,0,0,0,-180 +121.44,50.40910771,-3.581016276,50,-14.62777226,-4.36E-11,0,0,0,-180 +121.45,50.4091064,-3.581016276,50,-14.62429606,-4.10E-11,0,0,0,-180 +121.46,50.40910508,-3.581016276,50,-14.61039133,-3.02E-11,0,0,0,-180 +121.47,50.40910377,-3.581016276,50,-14.58605807,-1.11E-11,0,0,0,-180 +121.48,50.40910246,-3.581016276,50,-14.55824862,1.08E-11,0,0,0,-180 +121.49,50.40910115,-3.581016276,50,-14.53391534,3.00E-11,0,0,0,-180 +121.5,50.40909985,-3.581016276,50,-14.5200106,4.09E-11,0,0,0,-180 +121.51,50.40909854,-3.581016276,50,-14.51653441,4.36E-11,0,0,0,-180 +121.52,50.40909724,-3.581016276,50,-14.51305824,4.09E-11,0,0,0,-180 +121.53,50.40909593,-3.581016276,50,-14.49915352,3.01E-11,0,0,0,-180 +121.54,50.40909463,-3.581016276,50,-14.47482025,1.09E-11,0,0,0,-180 +121.55,50.40909333,-3.581016276,50,-14.44701078,-1.09E-11,0,0,0,-180 +121.56,50.40909203,-3.581016276,50,-14.42267748,-3.01E-11,0,0,0,-180 +121.57,50.40909074,-3.581016276,50,-14.40529657,-3.82E-11,0,0,0,-180 +121.58,50.40908944,-3.581016276,50,-14.38791567,-2.99E-11,0,0,0,-180 +121.59,50.40908815,-3.581016276,50,-14.36705858,-1.35E-11,0,0,0,-180 +121.6,50.40908686,-3.581016276,50,-14.35315385,-2.64E-12,0,0,0,-180 +121.61,50.40908557,-3.581016276,50,-14.34967767,9.37E-14,0,0,0,-180 +121.62,50.40908428,-3.581016276,50,-14.34620149,-2.58E-12,0,0,0,-180 +121.63,50.40908299,-3.581016276,50,-14.32882058,-1.08E-11,0,0,0,-180 +121.64,50.4090817,-3.581016276,50,-14.29753494,-1.37E-11,0,0,0,-180 +121.65,50.40908042,-3.581016276,50,-14.27667783,2.58E-12,0,0,0,-180 +121.66,50.40907914,-3.581016276,50,-14.27320165,2.17E-11,0,0,0,-180 +121.67,50.40907785,-3.581016276,50,-14.25582075,1.35E-11,0,0,0,-180 +121.68,50.40907657,-3.581016276,50,-14.22105895,-1.37E-11,0,0,0,-180 +121.69,50.4090753,-3.581016276,50,-14.20367803,-2.17E-11,0,0,0,-180 +121.7,50.40907402,-3.581016276,50,-14.20020184,-2.50E-12,0,0,0,-180 +121.71,50.40907274,-3.581016276,50,-14.17934474,1.39E-11,0,0,0,-180 +121.72,50.40907147,-3.581016276,50,-14.1480591,1.11E-11,0,0,0,-180 +121.73,50.4090702,-3.581016276,50,-14.1306782,2.81E-12,0,0,0,-180 +121.74,50.40906893,-3.581016276,50,-14.12720202,2.78E-17,0,0,0,-180 +121.75,50.40906766,-3.581016276,50,-14.12372582,2.64E-12,0,0,0,-180 +121.76,50.40906639,-3.581016276,50,-14.10982108,1.34E-11,0,0,0,-180 +121.77,50.40906512,-3.581016276,50,-14.088964,2.97E-11,0,0,0,-180 +121.78,50.40906386,-3.581016276,50,-14.0715831,3.79E-11,0,0,0,-180 +121.79,50.40906259,-3.581016276,50,-14.05420218,2.99E-11,0,0,0,-180 +121.8,50.40906133,-3.581016276,50,-14.03334508,1.37E-11,0,0,0,-180 +121.81,50.40906007,-3.581016276,50,-14.01596417,5.61E-12,0,0,0,-180 +121.82,50.40905881,-3.581016276,50,-13.99858326,1.37E-11,0,0,0,-180 +121.83,50.40905755,-3.581016276,50,-13.97772616,3.01E-11,0,0,0,-180 +121.84,50.4090563,-3.581016276,50,-13.96034527,3.83E-11,0,0,0,-180 +121.85,50.40905504,-3.581016276,50,-13.94296437,3.02E-11,0,0,0,-180 +121.86,50.40905379,-3.581016276,50,-13.92210727,1.38E-11,0,0,0,-180 +121.87,50.40905254,-3.581016276,50,-13.90820253,2.97E-12,0,0,0,-180 +121.88,50.40905129,-3.581016276,50,-13.90125016,-2.48E-12,0,0,0,-180 +121.89,50.40905004,-3.581016276,50,-13.88734544,-1.34E-11,0,0,0,-180 +121.9,50.40904879,-3.581016276,50,-13.86648835,-2.98E-11,0,0,0,-180 +121.91,50.40904755,-3.581016276,50,-13.84910743,-3.80E-11,0,0,0,-180 +121.92,50.4090463,-3.581016276,50,-13.83172651,-2.98E-11,0,0,0,-180 +121.93,50.40904506,-3.581016276,50,-13.81086941,-1.34E-11,0,0,0,-180 +121.94,50.40904382,-3.581016276,50,-13.79696469,-2.48E-12,0,0,0,-180 +121.95,50.40904258,-3.581016276,50,-13.79001233,2.97E-12,0,0,0,-180 +121.96,50.40904134,-3.581016276,50,-13.77263141,1.11E-11,0,0,0,-180 +121.97,50.4090401,-3.581016276,50,-13.74134576,1.38E-11,0,0,0,-180 +121.98,50.40903887,-3.581016276,50,-13.72048868,-2.64E-12,0,0,0,-180 +121.99,50.40903764,-3.581016276,50,-13.72048869,-2.45E-11,0,0,0,-180 +122,50.4090364,-3.581016276,50,-13.71353633,-2.99E-11,0,0,0,-180 +122.01,50.40903517,-3.581016276,50,-13.68225069,-2.73E-11,0,0,0,-180 +122.02,50.40903394,-3.581016276,50,-13.65096506,-3.01E-11,0,0,0,-180 +122.03,50.40903272,-3.581016276,50,-13.64401269,-2.46E-11,0,0,0,-180 +122.04,50.40903149,-3.581016276,50,-13.64401268,-2.72E-12,0,0,0,-180 +122.05,50.40903026,-3.581016276,50,-13.62315559,1.37E-11,0,0,0,-180 +122.06,50.40902904,-3.581016276,50,-13.59186995,1.11E-11,0,0,0,-180 +122.07,50.40902782,-3.581016276,50,-13.57448903,2.89E-12,0,0,0,-180 +122.08,50.4090266,-3.581016276,50,-13.56753665,-2.64E-12,0,0,0,-180 +122.09,50.40902538,-3.581016276,50,-13.55363192,-1.36E-11,0,0,0,-180 +122.1,50.40902416,-3.581016276,50,-13.53277484,-2.99E-11,0,0,0,-180 +122.11,50.40902295,-3.581016276,50,-13.51539395,-3.81E-11,0,0,0,-180 +122.12,50.40902173,-3.581016276,50,-13.49801304,-3.01E-11,0,0,0,-180 +122.13,50.40902052,-3.581016276,50,-13.47715595,-1.38E-11,0,0,0,-180 +122.14,50.40901931,-3.581016276,50,-13.45977503,-5.70E-12,0,0,0,-180 +122.15,50.4090181,-3.581016276,50,-13.44239412,-1.39E-11,0,0,0,-180 +122.16,50.40901689,-3.581016276,50,-13.42153702,-3.03E-11,0,0,0,-180 +122.17,50.40901569,-3.581016276,50,-13.40415609,-3.84E-11,0,0,0,-180 +122.18,50.40901448,-3.581016276,50,-13.38677519,-3.01E-11,0,0,0,-180 +122.19,50.40901328,-3.581016276,50,-13.36591812,-1.35E-11,0,0,0,-180 +122.2,50.40901208,-3.581016276,50,-13.3520134,-2.59E-12,0,0,0,-180 +122.21,50.40901088,-3.581016276,50,-13.3485372,1.56E-17,0,0,0,-180 +122.22,50.40900968,-3.581016276,50,-13.34506101,-2.87E-12,0,0,0,-180 +122.23,50.40900848,-3.581016276,50,-13.33115628,-1.38E-11,0,0,0,-180 +122.24,50.40900728,-3.581016276,50,-13.31029918,-3.02E-11,0,0,0,-180 +122.25,50.40900609,-3.581016276,50,-13.29291828,-3.83E-11,0,0,0,-180 +122.26,50.40900489,-3.581016276,50,-13.27553738,-3.01E-11,0,0,0,-180 +122.27,50.4090037,-3.581016276,50,-13.2512041,-1.09E-11,0,0,0,-180 +122.28,50.40900251,-3.581016276,50,-13.22339464,1.09E-11,0,0,0,-180 +122.29,50.40900132,-3.581016276,50,-13.19906136,3.01E-11,0,0,0,-180 +122.3,50.40900014,-3.581016276,50,-13.18515664,4.09E-11,0,0,0,-180 +122.31,50.40899895,-3.581016276,50,-13.18168045,4.36E-11,0,0,0,-180 +122.32,50.40899777,-3.581016276,50,-13.17820426,4.09E-11,0,0,0,-180 +122.33,50.40899658,-3.581016276,50,-13.16082335,3.27E-11,0,0,0,-180 +122.34,50.4089954,-3.581016276,50,-13.12606155,2.72E-11,0,0,0,-180 +122.35,50.40899422,-3.581016276,50,-13.09477592,2.99E-11,0,0,0,-180 +122.36,50.40899305,-3.581016276,50,-13.08782354,2.45E-11,0,0,0,-180 +122.37,50.40899187,-3.581016276,50,-13.08782353,2.73E-12,0,0,0,-180 +122.38,50.40899069,-3.581016276,50,-13.06696644,-1.35E-11,0,0,0,-180 +122.39,50.40898952,-3.581016276,50,-13.0356808,-1.07E-11,0,0,0,-180 +122.4,50.40898835,-3.581016276,50,-13.01829989,-2.48E-12,0,0,0,-180 +122.41,50.40898718,-3.581016276,50,-13.01482371,2.34E-13,0,0,0,-180 +122.42,50.40898601,-3.581016276,50,-13.01134753,-2.58E-12,0,0,0,-180 +122.43,50.40898484,-3.581016276,50,-12.99396663,-1.09E-11,0,0,0,-180 +122.44,50.40898367,-3.581016276,50,-12.96268098,-1.38E-11,0,0,0,-180 +122.45,50.40898251,-3.581016276,50,-12.94182388,2.58E-12,0,0,0,-180 +122.46,50.40898135,-3.581016276,50,-12.9383477,2.18E-11,0,0,0,-180 +122.47,50.40898018,-3.581016276,50,-12.9209668,1.37E-11,0,0,0,-180 +122.48,50.40897902,-3.581016276,50,-12.88620498,-1.36E-11,0,0,0,-180 +122.49,50.40897787,-3.581016276,50,-12.86882406,-2.17E-11,0,0,0,-180 +122.5,50.40897671,-3.581016276,50,-12.86534788,-2.56E-12,0,0,0,-180 +122.51,50.40897555,-3.581016276,50,-12.84449079,1.38E-11,0,0,0,-180 +122.52,50.4089744,-3.581016276,50,-12.81320516,1.11E-11,0,0,0,-180 +122.53,50.40897325,-3.581016276,50,-12.79582425,2.89E-12,0,0,0,-180 +122.54,50.4089721,-3.581016276,50,-12.79234807,7.81E-14,0,0,0,-180 +122.55,50.40897095,-3.581016276,50,-12.78887188,2.75E-12,0,0,0,-180 +122.56,50.4089698,-3.581016276,50,-12.77496714,1.37E-11,0,0,0,-180 +122.57,50.40896865,-3.581016276,50,-12.75411005,3.01E-11,0,0,0,-180 +122.58,50.40896751,-3.581016276,50,-12.73672915,3.82E-11,0,0,0,-180 +122.59,50.40896636,-3.581016276,50,-12.71934824,2.99E-11,0,0,0,-180 +122.6,50.40896522,-3.581016276,50,-12.69849114,1.34E-11,0,0,0,-180 +122.61,50.40896408,-3.581016276,50,-12.68111023,5.22E-12,0,0,0,-180 +122.62,50.40896294,-3.581016276,50,-12.66372932,1.34E-11,0,0,0,-180 +122.63,50.4089618,-3.581016276,50,-12.64287223,2.98E-11,0,0,0,-180 +122.64,50.40896067,-3.581016276,50,-12.62549132,3.80E-11,0,0,0,-180 +122.65,50.40895953,-3.581016276,50,-12.6081104,2.98E-11,0,0,0,-180 +122.66,50.4089584,-3.581016276,50,-12.58725331,1.34E-11,0,0,0,-180 +122.67,50.40895727,-3.581016276,50,-12.57334859,2.58E-12,0,0,0,-180 +122.68,50.40895614,-3.581016276,50,-12.56639624,-2.73E-12,0,0,0,-180 +122.69,50.40895501,-3.581016276,50,-12.55249151,-1.35E-11,0,0,0,-180 +122.7,50.40895388,-3.581016276,50,-12.53163441,-2.99E-11,0,0,0,-180 +122.71,50.40895276,-3.581016276,50,-12.5142535,-3.82E-11,0,0,0,-180 +122.72,50.40895163,-3.581016276,50,-12.49687259,-3.01E-11,0,0,0,-180 +122.73,50.40895051,-3.581016276,50,-12.47601549,-1.37E-11,0,0,0,-180 +122.74,50.40894939,-3.581016276,50,-12.46211075,-2.75E-12,0,0,0,-180 +122.75,50.40894827,-3.581016276,50,-12.45515838,2.64E-12,0,0,0,-180 +122.76,50.40894715,-3.581016276,50,-12.44125365,1.34E-11,0,0,0,-180 +122.77,50.40894603,-3.581016276,50,-12.42039657,2.98E-11,0,0,0,-180 +122.78,50.40894492,-3.581016276,50,-12.40301567,3.80E-11,0,0,0,-180 +122.79,50.4089438,-3.581016276,50,-12.38563477,3.00E-11,0,0,0,-180 +122.8,50.40894269,-3.581016276,50,-12.36477769,1.37E-11,0,0,0,-180 +122.81,50.40894158,-3.581016276,50,-12.34739678,5.45E-12,0,0,0,-180 +122.82,50.40894047,-3.581016276,50,-12.33001585,1.36E-11,0,0,0,-180 +122.83,50.40893936,-3.581016276,50,-12.30915875,2.99E-11,0,0,0,-180 +122.84,50.40893826,-3.581016276,50,-12.29177784,3.80E-11,0,0,0,-180 +122.85,50.40893715,-3.581016276,50,-12.27439693,2.98E-11,0,0,0,-180 +122.86,50.40893605,-3.581016276,50,-12.25353984,1.34E-11,0,0,0,-180 +122.87,50.40893495,-3.581016276,50,-12.23963512,2.48E-12,0,0,0,-180 +122.88,50.40893385,-3.581016276,50,-12.23268276,-2.98E-12,0,0,0,-180 +122.89,50.40893275,-3.581016276,50,-12.21877803,-1.39E-11,0,0,0,-180 +122.9,50.40893165,-3.581016276,50,-12.19792093,-3.03E-11,0,0,0,-180 +122.91,50.40893056,-3.581016276,50,-12.18054002,-3.84E-11,0,0,0,-180 +122.92,50.40892946,-3.581016276,50,-12.16315911,-3.01E-11,0,0,0,-180 +122.93,50.40892837,-3.581016276,50,-12.14230202,-1.35E-11,0,0,0,-180 +122.94,50.40892728,-3.581016276,50,-12.12839729,-2.58E-12,0,0,0,-180 +122.95,50.40892619,-3.581016276,50,-12.12144493,2.81E-12,0,0,0,-180 +122.96,50.4089251,-3.581016276,50,-12.10406402,1.10E-11,0,0,0,-180 +122.97,50.40892401,-3.581016276,50,-12.07277838,1.37E-11,0,0,0,-180 +122.98,50.40892293,-3.581016276,50,-12.05192129,-2.66E-12,0,0,0,-180 +122.99,50.40892185,-3.581016276,50,-12.05192129,-2.45E-11,0,0,0,-180 +123,50.40892076,-3.581016276,50,-12.04496892,-2.99E-11,0,0,0,-180 +123.01,50.40891968,-3.581016276,50,-12.01368329,-2.72E-11,0,0,0,-180 +123.02,50.4089186,-3.581016276,50,-11.98239766,-2.99E-11,0,0,0,-180 +123.03,50.40891753,-3.581016276,50,-11.97544528,-2.45E-11,0,0,0,-180 +123.04,50.40891645,-3.581016276,50,-11.97544527,-2.66E-12,0,0,0,-180 +123.05,50.40891537,-3.581016276,50,-11.95458819,1.37E-11,0,0,0,-180 +123.06,50.4089143,-3.581016276,50,-11.92330255,1.09E-11,0,0,0,-180 +123.07,50.40891323,-3.581016276,50,-11.90592165,2.58E-12,0,0,0,-180 +123.08,50.40891216,-3.581016276,50,-11.89896929,-2.88E-12,0,0,0,-180 +123.09,50.40891109,-3.581016276,50,-11.88506456,-1.37E-11,0,0,0,-180 +123.1,50.40891002,-3.581016276,50,-11.86420746,-2.99E-11,0,0,0,-180 +123.11,50.40890896,-3.581016276,50,-11.84682655,-3.80E-11,0,0,0,-180 +123.12,50.40890789,-3.581016276,50,-11.82944564,-2.98E-11,0,0,0,-180 +123.13,50.40890683,-3.581016276,50,-11.80858855,-1.34E-11,0,0,0,-180 +123.14,50.40890577,-3.581016276,50,-11.79120765,-5.31E-12,0,0,0,-180 +123.15,50.40890471,-3.581016276,50,-11.77382674,-1.37E-11,0,0,0,-180 +123.16,50.40890365,-3.581016276,50,-11.75296964,-3.02E-11,0,0,0,-180 +123.17,50.4089026,-3.581016276,50,-11.73906491,-4.12E-11,0,0,0,-180 +123.18,50.40890154,-3.581016276,50,-11.73558873,-4.37E-11,0,0,0,-180 +123.19,50.40890049,-3.581016276,50,-11.73211256,-4.09E-11,0,0,0,-180 +123.2,50.40889943,-3.581016276,50,-11.71473164,-3.27E-11,0,0,0,-180 +123.21,50.40889838,-3.581016276,50,-11.67996981,-2.73E-11,0,0,0,-180 +123.22,50.40889733,-3.581016276,50,-11.645208,-3.28E-11,0,0,0,-180 +123.23,50.40889629,-3.581016276,50,-11.6278271,-4.10E-11,0,0,0,-180 +123.24,50.40889524,-3.581016276,50,-11.62435092,-4.37E-11,0,0,0,-180 +123.25,50.4088942,-3.581016276,50,-11.62087473,-4.10E-11,0,0,0,-180 +123.26,50.40889315,-3.581016276,50,-11.60696999,-3.01E-11,0,0,0,-180 +123.27,50.40889211,-3.581016276,50,-11.5861129,-1.36E-11,0,0,0,-180 +123.28,50.40889107,-3.581016276,50,-11.56873199,-5.31E-12,0,0,0,-180 +123.29,50.40889003,-3.581016276,50,-11.55135109,-1.35E-11,0,0,0,-180 +123.3,50.40888899,-3.581016276,50,-11.530494,-3.00E-11,0,0,0,-180 +123.31,50.40888796,-3.581016276,50,-11.51311308,-3.82E-11,0,0,0,-180 +123.32,50.40888692,-3.581016276,50,-11.49573217,-2.99E-11,0,0,0,-180 +123.33,50.40888589,-3.581016276,50,-11.47487509,-1.35E-11,0,0,0,-180 +123.34,50.40888486,-3.581016276,50,-11.45749418,-5.45E-12,0,0,0,-180 +123.35,50.40888383,-3.581016276,50,-11.44011327,-1.37E-11,0,0,0,-180 +123.36,50.4088828,-3.581016276,50,-11.41925618,-3.01E-11,0,0,0,-180 +123.37,50.40888178,-3.581016276,50,-11.40535145,-4.09E-11,0,0,0,-180 +123.38,50.40888075,-3.581016276,50,-11.40187526,-4.35E-11,0,0,0,-180 +123.39,50.40887973,-3.581016276,50,-11.39839906,-4.08E-11,0,0,0,-180 +123.4,50.4088787,-3.581016276,50,-11.38101816,-3.26E-11,0,0,0,-180 +123.41,50.40887768,-3.581016276,50,-11.34625636,-2.71E-11,0,0,0,-180 +123.42,50.40887666,-3.581016276,50,-11.31149455,-3.26E-11,0,0,0,-180 +123.43,50.40887565,-3.581016276,50,-11.29411363,-4.09E-11,0,0,0,-180 +123.44,50.40887463,-3.581016276,50,-11.29063744,-4.37E-11,0,0,0,-180 +123.45,50.40887362,-3.581016276,50,-11.28716126,-4.10E-11,0,0,0,-180 +123.46,50.4088726,-3.581016276,50,-11.27325655,-3.01E-11,0,0,0,-180 +123.47,50.40887159,-3.581016276,50,-11.24892327,-1.09E-11,0,0,0,-180 +123.48,50.40887058,-3.581016276,50,-11.2211138,1.09E-11,0,0,0,-180 +123.49,50.40886957,-3.581016276,50,-11.19678053,3.01E-11,0,0,0,-180 +123.5,50.40886857,-3.581016276,50,-11.18287581,4.10E-11,0,0,0,-180 +123.51,50.40886756,-3.581016276,50,-11.17939963,4.37E-11,0,0,0,-180 +123.52,50.40886656,-3.581016276,50,-11.17592344,4.10E-11,0,0,0,-180 +123.53,50.40886555,-3.581016276,50,-11.16201871,3.01E-11,0,0,0,-180 +123.54,50.40886455,-3.581016276,50,-11.13768544,1.09E-11,0,0,0,-180 +123.55,50.40886355,-3.581016276,50,-11.10987598,-1.11E-11,0,0,0,-180 +123.56,50.40886255,-3.581016276,50,-11.08554271,-3.02E-11,0,0,0,-180 +123.57,50.40886156,-3.581016276,50,-11.06816181,-3.83E-11,0,0,0,-180 +123.58,50.40886056,-3.581016276,50,-11.05425708,-2.73E-11,0,0,0,-180 +123.59,50.40885957,-3.581016276,50,-11.04382852,2.72E-12,0,0,0,-180 +123.6,50.40885858,-3.581016276,50,-11.03339997,3.81E-11,0,0,0,-180 +123.61,50.40885758,-3.581016276,50,-11.01254288,5.45E-11,0,0,0,-180 +123.62,50.4088566,-3.581016276,50,-10.99168581,3.80E-11,0,0,0,-180 +123.63,50.40885561,-3.581016276,50,-10.98125728,2.48E-12,0,0,0,-180 +123.64,50.40885462,-3.581016276,50,-10.97082874,-2.76E-11,0,0,0,-180 +123.65,50.40885364,-3.581016276,50,-10.95692399,-3.84E-11,0,0,0,-180 +123.66,50.40885265,-3.581016276,50,-10.93954307,-3.01E-11,0,0,0,-180 +123.67,50.40885167,-3.581016276,50,-10.91520979,-1.08E-11,0,0,0,-180 +123.68,50.40885069,-3.581016276,50,-10.88740033,1.11E-11,0,0,0,-180 +123.69,50.40884971,-3.581016276,50,-10.86306706,3.02E-11,0,0,0,-180 +123.7,50.40884874,-3.581016276,50,-10.84916235,4.10E-11,0,0,0,-180 +123.71,50.40884776,-3.581016276,50,-10.84568618,4.37E-11,0,0,0,-180 +123.72,50.40884679,-3.581016276,50,-10.84220999,4.10E-11,0,0,0,-180 +123.73,50.40884581,-3.581016276,50,-10.82830525,3.01E-11,0,0,0,-180 +123.74,50.40884484,-3.581016276,50,-10.80397197,1.09E-11,0,0,0,-180 +123.75,50.40884387,-3.581016276,50,-10.77616251,-1.10E-11,0,0,0,-180 +123.76,50.4088429,-3.581016276,50,-10.75182925,-3.02E-11,0,0,0,-180 +123.77,50.40884194,-3.581016276,50,-10.73444836,-3.84E-11,0,0,0,-180 +123.78,50.40884097,-3.581016276,50,-10.71706746,-3.02E-11,0,0,0,-180 +123.79,50.40884001,-3.581016276,50,-10.69621035,-1.37E-11,0,0,0,-180 +123.8,50.40883905,-3.581016276,50,-10.68230561,-2.59E-12,0,0,0,-180 +123.81,50.40883809,-3.581016276,50,-10.67882943,1.41E-13,0,0,0,-180 +123.82,50.40883713,-3.581016276,50,-10.67535326,-2.73E-12,0,0,0,-180 +123.83,50.40883617,-3.581016276,50,-10.66144853,-1.38E-11,0,0,0,-180 +123.84,50.40883521,-3.581016276,50,-10.64059144,-3.03E-11,0,0,0,-180 +123.85,50.40883426,-3.581016276,50,-10.62321054,-3.85E-11,0,0,0,-180 +123.86,50.4088333,-3.581016276,50,-10.60582963,-3.03E-11,0,0,0,-180 +123.87,50.40883235,-3.581016276,50,-10.58149634,-1.12E-11,0,0,0,-180 +123.88,50.4088314,-3.581016276,50,-10.55368688,1.07E-11,0,0,0,-180 +123.89,50.40883045,-3.581016276,50,-10.52935362,2.99E-11,0,0,0,-180 +123.9,50.40882951,-3.581016276,50,-10.51544889,4.09E-11,0,0,0,-180 +123.91,50.40882856,-3.581016276,50,-10.5119727,4.37E-11,0,0,0,-180 +123.92,50.40882762,-3.581016276,50,-10.50849652,4.09E-11,0,0,0,-180 +123.93,50.40882667,-3.581016276,50,-10.49459181,2.99E-11,0,0,0,-180 +123.94,50.40882573,-3.581016276,50,-10.47025855,1.09E-11,0,0,0,-180 +123.95,50.40882479,-3.581016276,50,-10.44244909,-1.10E-11,0,0,0,-180 +123.96,50.40882385,-3.581016276,50,-10.4181158,-3.01E-11,0,0,0,-180 +123.97,50.40882292,-3.581016276,50,-10.40073488,-3.83E-11,0,0,0,-180 +123.98,50.40882198,-3.581016276,50,-10.38683016,-2.74E-11,0,0,0,-180 +123.99,50.40882105,-3.581016276,50,-10.37640161,2.48E-12,0,0,0,-180 +124,50.40882012,-3.581016276,50,-10.36597307,3.79E-11,0,0,0,-180 +124.01,50.40881918,-3.581016276,50,-10.34511599,5.43E-11,0,0,0,-180 +124.02,50.40881826,-3.581016276,50,-10.3242589,3.80E-11,0,0,0,-180 +124.03,50.40881733,-3.581016276,50,-10.31383034,2.72E-12,0,0,0,-180 +124.04,50.4088164,-3.581016276,50,-10.30340179,-2.72E-11,0,0,0,-180 +124.05,50.40881548,-3.581016276,50,-10.28949707,-3.81E-11,0,0,0,-180 +124.06,50.40881455,-3.581016276,50,-10.27211617,-3.01E-11,0,0,0,-180 +124.07,50.40881363,-3.581016276,50,-10.2477829,-1.11E-11,0,0,0,-180 +124.08,50.40881271,-3.581016276,50,-10.21997343,1.07E-11,0,0,0,-180 +124.09,50.40881179,-3.581016276,50,-10.19564017,2.98E-11,0,0,0,-180 +124.1,50.40881088,-3.581016276,50,-10.18173544,4.08E-11,0,0,0,-180 +124.11,50.40880996,-3.581016276,50,-10.17825926,4.35E-11,0,0,0,-180 +124.12,50.40880905,-3.581016276,50,-10.17478308,4.08E-11,0,0,0,-180 +124.13,50.40880813,-3.581016276,50,-10.16087835,2.99E-11,0,0,0,-180 +124.14,50.40880722,-3.581016276,50,-10.13654507,1.09E-11,0,0,0,-180 +124.15,50.40880631,-3.581016276,50,-10.10873562,-1.09E-11,0,0,0,-180 +124.16,50.4088054,-3.581016276,50,-10.08440235,-3.00E-11,0,0,0,-180 +124.17,50.4088045,-3.581016276,50,-10.06702145,-3.81E-11,0,0,0,-180 +124.18,50.40880359,-3.581016276,50,-10.05311672,-2.72E-11,0,0,0,-180 +124.19,50.40880269,-3.581016276,50,-10.04268817,2.81E-12,0,0,0,-180 +124.2,50.40880179,-3.581016276,50,-10.03225962,3.83E-11,0,0,0,-180 +124.21,50.40880088,-3.581016276,50,-10.01140253,5.47E-11,0,0,0,-180 +124.22,50.40879999,-3.581016276,50,-9.990545438,3.83E-11,0,0,0,-180 +124.23,50.40879909,-3.581016276,50,-9.980116891,2.81E-12,0,0,0,-180 +124.24,50.40879819,-3.581016276,50,-9.969688349,-2.72E-11,0,0,0,-180 +124.25,50.4087973,-3.581016276,50,-9.955783633,-3.81E-11,0,0,0,-180 +124.26,50.4087964,-3.581016276,50,-9.938402731,-3.00E-11,0,0,0,-180 +124.27,50.40879551,-3.581016276,50,-9.917545633,-1.37E-11,0,0,0,-180 +124.28,50.40879462,-3.581016276,50,-9.900164715,-5.55E-12,0,0,0,-180 +124.29,50.40879373,-3.581016276,50,-9.879307623,-1.11E-11,0,0,0,-180 +124.3,50.40879284,-3.581016276,50,-9.848021983,-1.39E-11,0,0,0,-180 +124.31,50.40879196,-3.581016276,50,-9.827164893,2.48E-12,0,0,0,-180 +124.32,50.40879108,-3.581016276,50,-9.8271649,2.44E-11,0,0,0,-180 +124.33,50.40879019,-3.581016276,50,-9.823688719,2.71E-11,0,0,0,-180 +124.34,50.40878931,-3.581016276,50,-9.802831627,1.07E-11,0,0,0,-180 +124.35,50.40878843,-3.581016276,50,-9.775022182,-1.11E-11,0,0,0,-180 +124.36,50.40878755,-3.581016276,50,-9.750688917,-3.01E-11,0,0,0,-180 +124.37,50.40878668,-3.581016276,50,-9.736784177,-4.09E-11,0,0,0,-180 +124.38,50.4087858,-3.581016276,50,-9.733307976,-4.36E-11,0,0,0,-180 +124.39,50.40878493,-3.581016276,50,-9.729831793,-4.10E-11,0,0,0,-180 +124.4,50.40878405,-3.581016276,50,-9.712450903,-3.30E-11,0,0,0,-180 +124.41,50.40878318,-3.581016276,50,-9.677689103,-2.75E-11,0,0,0,-180 +124.42,50.40878231,-3.581016276,50,-9.642927286,-3.29E-11,0,0,0,-180 +124.43,50.40878145,-3.581016276,50,-9.625546367,-4.10E-11,0,0,0,-180 +124.44,50.40878058,-3.581016276,50,-9.622070181,-4.37E-11,0,0,0,-180 +124.45,50.40877972,-3.581016276,50,-9.618594,-4.10E-11,0,0,0,-180 +124.46,50.40877885,-3.581016276,50,-9.604689269,-3.01E-11,0,0,0,-180 +124.47,50.40877799,-3.581016276,50,-9.583832177,-1.37E-11,0,0,0,-180 +124.48,50.40877713,-3.581016276,50,-9.566451269,-5.45E-12,0,0,0,-180 +124.49,50.40877627,-3.581016276,50,-9.549070357,-1.36E-11,0,0,0,-180 +124.5,50.40877541,-3.581016276,50,-9.528213267,-2.99E-11,0,0,0,-180 +124.51,50.40877456,-3.581016276,50,-9.510832365,-3.81E-11,0,0,0,-180 +124.52,50.4087737,-3.581016276,50,-9.493451455,-3.01E-11,0,0,0,-180 +124.53,50.40877285,-3.581016276,50,-9.472594354,-1.38E-11,0,0,0,-180 +124.54,50.408772,-3.581016276,50,-9.455213443,-5.70E-12,0,0,0,-180 +124.55,50.40877115,-3.581016276,50,-9.437832544,-1.39E-11,0,0,0,-180 +124.56,50.4087703,-3.581016276,50,-9.416975461,-3.03E-11,0,0,0,-180 +124.57,50.40876946,-3.581016276,50,-9.403070735,-4.13E-11,0,0,0,-180 +124.58,50.40876861,-3.581016276,50,-9.399594552,-4.40E-11,0,0,0,-180 +124.59,50.40876777,-3.581016276,50,-9.396118368,-4.13E-11,0,0,0,-180 +124.6,50.40876692,-3.581016276,50,-9.378737458,-3.30E-11,0,0,0,-180 +124.61,50.40876608,-3.581016276,50,-9.343975641,-2.75E-11,0,0,0,-180 +124.62,50.40876524,-3.581016276,50,-9.31269001,-3.01E-11,0,0,0,-180 +124.63,50.40876441,-3.581016276,50,-9.305737648,-2.45E-11,0,0,0,-180 +124.64,50.40876357,-3.581016276,50,-9.305737637,-2.58E-12,0,0,0,-180 +124.65,50.40876273,-3.581016276,50,-9.284880543,1.38E-11,0,0,0,-180 +124.66,50.4087619,-3.581016276,50,-9.253594919,1.10E-11,0,0,0,-180 +124.67,50.40876107,-3.581016276,50,-9.236214018,2.73E-12,0,0,0,-180 +124.68,50.40876024,-3.581016276,50,-9.229261653,-2.73E-12,0,0,0,-180 +124.69,50.40875941,-3.581016276,50,-9.215356924,-1.37E-11,0,0,0,-180 +124.7,50.40875858,-3.581016276,50,-9.194499824,-3.01E-11,0,0,0,-180 +124.71,50.40875776,-3.581016276,50,-9.1771189,-3.83E-11,0,0,0,-180 +124.72,50.40875693,-3.581016276,50,-9.159737994,-3.01E-11,0,0,0,-180 +124.73,50.40875611,-3.581016276,50,-9.13888092,-1.36E-11,0,0,0,-180 +124.74,50.40875529,-3.581016276,50,-9.124976203,-2.58E-12,0,0,0,-180 +124.75,50.40875447,-3.581016276,50,-9.11802384,2.87E-12,0,0,0,-180 +124.76,50.40875365,-3.581016276,50,-9.104119112,1.37E-11,0,0,0,-180 +124.77,50.40875283,-3.581016276,50,-9.08326202,2.99E-11,0,0,0,-180 +124.78,50.40875202,-3.581016276,50,-9.06588111,3.81E-11,0,0,0,-180 +124.79,50.4087512,-3.581016276,50,-9.0485002,3.01E-11,0,0,0,-180 +124.8,50.40875039,-3.581016276,50,-9.027643108,1.38E-11,0,0,0,-180 +124.81,50.40874958,-3.581016276,50,-9.0102622,5.70E-12,0,0,0,-180 +124.82,50.40874877,-3.581016276,50,-8.992881296,1.39E-11,0,0,0,-180 +124.83,50.40874796,-3.581016276,50,-8.972024209,3.03E-11,0,0,0,-180 +124.84,50.40874716,-3.581016276,50,-8.954643296,3.84E-11,0,0,0,-180 +124.85,50.40874635,-3.581016276,50,-8.937262386,3.01E-11,0,0,0,-180 +124.86,50.40874555,-3.581016276,50,-8.916405297,1.35E-11,0,0,0,-180 +124.87,50.40874475,-3.581016276,50,-8.902500566,2.58E-12,0,0,0,-180 +124.88,50.40874395,-3.581016276,50,-8.895548201,-2.81E-12,0,0,0,-180 +124.89,50.40874315,-3.581016276,50,-8.881643475,-1.37E-11,0,0,0,-180 +124.9,50.40874235,-3.581016276,50,-8.860786381,-3.01E-11,0,0,0,-180 +124.91,50.40874156,-3.581016276,50,-8.843405473,-3.83E-11,0,0,0,-180 +124.92,50.40874076,-3.581016276,50,-8.826024572,-3.01E-11,0,0,0,-180 +124.93,50.40873997,-3.581016276,50,-8.80516748,-1.37E-11,0,0,0,-180 +124.94,50.40873918,-3.581016276,50,-8.791262743,-2.73E-12,0,0,0,-180 +124.95,50.40873839,-3.581016276,50,-8.784310379,2.73E-12,0,0,0,-180 +124.96,50.4087376,-3.581016276,50,-8.770405664,1.37E-11,0,0,0,-180 +124.97,50.40873681,-3.581016276,50,-8.74954859,3.01E-11,0,0,0,-180 +124.98,50.40873603,-3.581016276,50,-8.732167693,3.83E-11,0,0,0,-180 +124.99,50.40873524,-3.581016276,50,-8.714786783,3.02E-11,0,0,0,-180 +125,50.40873446,-3.581016276,50,-8.693929678,1.38E-11,0,0,0,-180 +125.01,50.40873368,-3.581016276,50,-8.676548752,5.61E-12,0,0,0,-180 +125.02,50.4087329,-3.581016276,50,-8.659167836,1.37E-11,0,0,0,-180 +125.03,50.40873212,-3.581016276,50,-8.638310746,2.99E-11,0,0,0,-180 +125.04,50.40873135,-3.581016276,50,-8.620929838,3.81E-11,0,0,0,-180 +125.05,50.40873057,-3.581016276,50,-8.603548937,2.99E-11,0,0,0,-180 +125.06,50.4087298,-3.581016276,50,-8.58269187,1.37E-11,0,0,0,-180 +125.07,50.40872903,-3.581016276,50,-8.568787159,2.89E-12,0,0,0,-180 +125.08,50.40872826,-3.581016276,50,-8.565310968,2.34E-13,0,0,0,-180 +125.09,50.40872749,-3.581016276,50,-8.561834767,2.97E-12,0,0,0,-180 +125.1,50.40872672,-3.581016276,50,-8.544453855,1.11E-11,0,0,0,-180 +125.11,50.40872595,-3.581016276,50,-8.509692045,1.65E-11,0,0,0,-180 +125.12,50.40872519,-3.581016276,50,-8.474930226,1.09E-11,0,0,0,-180 +125.13,50.40872443,-3.581016276,50,-8.457549305,2.66E-12,0,0,0,-180 +125.14,50.40872367,-3.581016276,50,-8.454073118,-1.56E-13,0,0,0,-180 +125.15,50.40872291,-3.581016276,50,-8.450596951,2.58E-12,0,0,0,-180 +125.16,50.40872215,-3.581016276,50,-8.436692245,1.36E-11,0,0,0,-180 +125.17,50.40872139,-3.581016276,50,-8.415835153,3.01E-11,0,0,0,-180 +125.18,50.40872064,-3.581016276,50,-8.398454223,3.83E-11,0,0,0,-180 +125.19,50.40871988,-3.581016276,50,-8.381073307,3.01E-11,0,0,0,-180 +125.2,50.40871913,-3.581016276,50,-8.360216231,1.36E-11,0,0,0,-180 +125.21,50.40871838,-3.581016276,50,-8.342835332,5.31E-12,0,0,0,-180 +125.22,50.40871763,-3.581016276,50,-8.325454415,1.35E-11,0,0,0,-180 +125.23,50.40871688,-3.581016276,50,-8.304597322,3.00E-11,0,0,0,-180 +125.24,50.40871614,-3.581016276,50,-8.287216423,3.82E-11,0,0,0,-180 +125.25,50.40871539,-3.581016276,50,-8.273311697,2.72E-11,0,0,0,-180 +125.26,50.40871465,-3.581016276,50,-8.262883146,-2.88E-12,0,0,0,-180 +125.27,50.40871391,-3.581016276,50,-8.252454607,-3.83E-11,0,0,0,-180 +125.28,50.40871316,-3.581016276,50,-8.231597522,-5.45E-11,0,0,0,-180 +125.29,50.40871243,-3.581016276,50,-8.210740428,-3.81E-11,0,0,0,-180 +125.3,50.40871169,-3.581016276,50,-8.196835695,-5.31E-12,0,0,0,-180 +125.31,50.40871095,-3.581016276,50,-8.175978599,1.09E-11,0,0,0,-180 +125.32,50.40871022,-3.581016276,50,-8.158597692,-2.89E-12,0,0,0,-180 +125.33,50.40870949,-3.581016276,50,-8.155121518,-2.21E-11,0,0,0,-180 +125.34,50.40870875,-3.581016276,50,-8.13774061,-1.39E-11,0,0,0,-180 +125.35,50.40870802,-3.581016276,50,-8.10297879,1.35E-11,0,0,0,-180 +125.36,50.4087073,-3.581016276,50,-8.085597884,2.18E-11,0,0,0,-180 +125.37,50.40870657,-3.581016276,50,-8.08212171,2.72E-12,0,0,0,-180 +125.38,50.40870584,-3.581016276,50,-8.061264626,-1.37E-11,0,0,0,-180 +125.39,50.40870512,-3.581016276,50,-8.029978987,-1.09E-11,0,0,0,-180 +125.4,50.4087044,-3.581016276,50,-8.01259807,-2.73E-12,0,0,0,-180 +125.41,50.40870368,-3.581016276,50,-8.009121892,1.56E-17,0,0,0,-180 +125.42,50.40870296,-3.581016276,50,-8.005645718,-2.73E-12,0,0,0,-180 +125.43,50.40870224,-3.581016276,50,-7.991740988,-1.37E-11,0,0,0,-180 +125.44,50.40870152,-3.581016276,50,-7.97088389,-3.01E-11,0,0,0,-180 +125.45,50.40870081,-3.581016276,50,-7.95350298,-3.83E-11,0,0,0,-180 +125.46,50.40870009,-3.581016276,50,-7.936122079,-3.01E-11,0,0,0,-180 +125.47,50.40869938,-3.581016276,50,-7.911788819,-1.09E-11,0,0,0,-180 +125.48,50.40869867,-3.581016276,50,-7.883979371,1.11E-11,0,0,0,-180 +125.49,50.40869796,-3.581016276,50,-7.859646091,3.03E-11,0,0,0,-180 +125.5,50.40869726,-3.581016276,50,-7.845741352,4.12E-11,0,0,0,-180 +125.51,50.40869655,-3.581016276,50,-7.84226517,4.39E-11,0,0,0,-180 +125.52,50.40869585,-3.581016276,50,-7.838788998,4.10E-11,0,0,0,-180 +125.53,50.40869514,-3.581016276,50,-7.824884274,2.99E-11,0,0,0,-180 +125.54,50.40869444,-3.581016276,50,-7.800550988,1.07E-11,0,0,0,-180 +125.55,50.40869374,-3.581016276,50,-7.77274152,-1.11E-11,0,0,0,-180 +125.56,50.40869304,-3.581016276,50,-7.748408258,-3.01E-11,0,0,0,-180 +125.57,50.40869235,-3.581016276,50,-7.734503552,-4.09E-11,0,0,0,-180 +125.58,50.40869165,-3.581016276,50,-7.731027376,-4.36E-11,0,0,0,-180 +125.59,50.40869096,-3.581016276,50,-7.727551189,-4.10E-11,0,0,0,-180 +125.6,50.40869026,-3.581016276,50,-7.710170277,-3.30E-11,0,0,0,-180 +125.61,50.40868957,-3.581016276,50,-7.675408459,-2.75E-11,0,0,0,-180 +125.62,50.40868888,-3.581016276,50,-7.640646643,-3.29E-11,0,0,0,-180 +125.63,50.4086882,-3.581016276,50,-7.62326574,-4.10E-11,0,0,0,-180 +125.64,50.40868751,-3.581016276,50,-7.619789562,-4.37E-11,0,0,0,-180 +125.65,50.40868683,-3.581016276,50,-7.616313375,-4.10E-11,0,0,0,-180 +125.66,50.40868614,-3.581016276,50,-7.60240864,-3.01E-11,0,0,0,-180 +125.67,50.40868546,-3.581016276,50,-7.581551549,-1.37E-11,0,0,0,-180 +125.68,50.40868478,-3.581016276,50,-7.564170648,-5.45E-12,0,0,0,-180 +125.69,50.4086841,-3.581016276,50,-7.546789752,-1.36E-11,0,0,0,-180 +125.7,50.40868342,-3.581016276,50,-7.525932669,-2.99E-11,0,0,0,-180 +125.71,50.40868275,-3.581016276,50,-7.50855176,-3.81E-11,0,0,0,-180 +125.72,50.40868207,-3.581016276,50,-7.491170842,-3.01E-11,0,0,0,-180 +125.73,50.4086814,-3.581016276,50,-7.470313739,-1.38E-11,0,0,0,-180 +125.74,50.40868073,-3.581016276,50,-7.456409011,-2.87E-12,0,0,0,-180 +125.75,50.40868006,-3.581016276,50,-7.449456658,2.73E-12,0,0,0,-180 +125.76,50.40867939,-3.581016276,50,-7.435551939,1.38E-11,0,0,0,-180 +125.77,50.40867872,-3.581016276,50,-7.414694848,3.03E-11,0,0,0,-180 +125.78,50.40867806,-3.581016276,50,-7.397313932,3.85E-11,0,0,0,-180 +125.79,50.40867739,-3.581016276,50,-7.37993302,3.03E-11,0,0,0,-180 +125.8,50.40867673,-3.581016276,50,-7.359075938,1.38E-11,0,0,0,-180 +125.81,50.40867607,-3.581016276,50,-7.341695033,5.47E-12,0,0,0,-180 +125.82,50.40867541,-3.581016276,50,-7.324314119,1.35E-11,0,0,0,-180 +125.83,50.40867475,-3.581016276,50,-7.303457034,2.99E-11,0,0,0,-180 +125.84,50.4086741,-3.581016276,50,-7.286076142,3.82E-11,0,0,0,-180 +125.85,50.40867344,-3.581016276,50,-7.26869524,3.01E-11,0,0,0,-180 +125.86,50.40867279,-3.581016276,50,-7.247838135,1.37E-11,0,0,0,-180 +125.87,50.40867214,-3.581016276,50,-7.233933392,2.73E-12,0,0,0,-180 +125.88,50.40867149,-3.581016276,50,-7.230457214,-1.56E-14,0,0,0,-180 +125.89,50.40867084,-3.581016276,50,-7.226981047,2.64E-12,0,0,0,-180 +125.9,50.40867019,-3.581016276,50,-7.20960014,1.07E-11,0,0,0,-180 +125.91,50.40866954,-3.581016276,50,-7.174838313,1.61E-11,0,0,0,-180 +125.92,50.4086689,-3.581016276,50,-7.140076495,1.07E-11,0,0,0,-180 +125.93,50.40866826,-3.581016276,50,-7.122695596,2.64E-12,0,0,0,-180 +125.94,50.40866762,-3.581016276,50,-7.11921942,8.67E-18,0,0,0,-180 +125.95,50.40866698,-3.581016276,50,-7.115743234,2.81E-12,0,0,0,-180 +125.96,50.40866634,-3.581016276,50,-7.101838501,1.38E-11,0,0,0,-180 +125.97,50.4086657,-3.581016276,50,-7.080981415,3.02E-11,0,0,0,-180 +125.98,50.40866507,-3.581016276,50,-7.063600514,3.83E-11,0,0,0,-180 +125.99,50.40866443,-3.581016276,50,-7.046219614,2.99E-11,0,0,0,-180 +126,50.4086638,-3.581016276,50,-7.025362527,1.34E-11,0,0,0,-180 +126.01,50.40866317,-3.581016276,50,-7.011457797,2.48E-12,0,0,0,-180 +126.02,50.40866254,-3.581016276,50,-7.004505431,-2.98E-12,0,0,0,-180 +126.03,50.40866191,-3.581016276,50,-6.987124515,-1.12E-11,0,0,0,-180 +126.04,50.40866128,-3.581016276,50,-6.955838865,-1.39E-11,0,0,0,-180 +126.05,50.40866066,-3.581016276,50,-6.934981776,2.58E-12,0,0,0,-180 +126.06,50.40866004,-3.581016276,50,-6.931505614,2.19E-11,0,0,0,-180 +126.07,50.40865941,-3.581016276,50,-6.914124713,1.38E-11,0,0,0,-180 +126.08,50.40865879,-3.581016276,50,-6.879362889,-1.35E-11,0,0,0,-180 +126.09,50.40865818,-3.581016276,50,-6.861981979,-2.18E-11,0,0,0,-180 +126.1,50.40865756,-3.581016276,50,-6.86198199,1.56E-14,0,0,0,-180 +126.11,50.40865694,-3.581016276,50,-6.855029634,2.73E-11,0,0,0,-180 +126.12,50.40865633,-3.581016276,50,-6.841124907,3.83E-11,0,0,0,-180 +126.13,50.40865571,-3.581016276,50,-6.823743989,3.01E-11,0,0,0,-180 +126.14,50.4086551,-3.581016276,50,-6.799410705,1.09E-11,0,0,0,-180 +126.15,50.40865449,-3.581016276,50,-6.771601251,-1.09E-11,0,0,0,-180 +126.16,50.40865388,-3.581016276,50,-6.747267989,-3.01E-11,0,0,0,-180 +126.17,50.40865328,-3.581016276,50,-6.729887088,-3.82E-11,0,0,0,-180 +126.18,50.40865267,-3.581016276,50,-6.712506181,-2.99E-11,0,0,0,-180 +126.19,50.40865207,-3.581016276,50,-6.69164909,-1.35E-11,0,0,0,-180 +126.2,50.40865147,-3.581016276,50,-6.677744363,-2.64E-12,0,0,0,-180 +126.21,50.40865087,-3.581016276,50,-6.67426818,9.38E-14,0,0,0,-180 +126.22,50.40865027,-3.581016276,50,-6.670792,-2.56E-12,0,0,0,-180 +126.23,50.40864967,-3.581016276,50,-6.656887282,-1.34E-11,0,0,0,-180 +126.24,50.40864907,-3.581016276,50,-6.636030202,-2.98E-11,0,0,0,-180 +126.25,50.40864848,-3.581016276,50,-6.618649292,-3.80E-11,0,0,0,-180 +126.26,50.40864788,-3.581016276,50,-6.601268372,-2.98E-11,0,0,0,-180 +126.27,50.40864729,-3.581016276,50,-6.580411272,-1.34E-11,0,0,0,-180 +126.28,50.4086467,-3.581016276,50,-6.563030361,-5.22E-12,0,0,0,-180 +126.29,50.40864611,-3.581016276,50,-6.545649452,-1.34E-11,0,0,0,-180 +126.3,50.40864552,-3.581016276,50,-6.524792363,-2.99E-11,0,0,0,-180 +126.31,50.40864494,-3.581016276,50,-6.507411463,-3.82E-11,0,0,0,-180 +126.32,50.40864435,-3.581016276,50,-6.490030567,-3.00E-11,0,0,0,-180 +126.33,50.40864377,-3.581016276,50,-6.469173485,-1.35E-11,0,0,0,-180 +126.34,50.40864319,-3.581016276,50,-6.455268759,-2.58E-12,0,0,0,-180 +126.35,50.40864261,-3.581016276,50,-6.448316395,2.81E-12,0,0,0,-180 +126.36,50.40864203,-3.581016276,50,-6.430935484,1.10E-11,0,0,0,-180 +126.37,50.40864145,-3.581016276,50,-6.399649841,1.37E-11,0,0,0,-180 +126.38,50.40864088,-3.581016276,50,-6.378792746,-2.73E-12,0,0,0,-180 +126.39,50.40864031,-3.581016276,50,-6.37879275,-2.46E-11,0,0,0,-180 +126.4,50.40863973,-3.581016276,50,-6.375316576,-2.74E-11,0,0,0,-180 +126.41,50.40863916,-3.581016276,50,-6.354459494,-1.11E-11,0,0,0,-180 +126.42,50.40863859,-3.581016276,50,-6.326650044,1.08E-11,0,0,0,-180 +126.43,50.40863802,-3.581016276,50,-6.302316767,3.00E-11,0,0,0,-180 +126.44,50.40863746,-3.581016276,50,-6.284935854,3.82E-11,0,0,0,-180 +126.45,50.40863689,-3.581016276,50,-6.267554951,2.99E-11,0,0,0,-180 +126.46,50.40863633,-3.581016276,50,-6.246697869,1.35E-11,0,0,0,-180 +126.47,50.40863577,-3.581016276,50,-6.232793135,2.73E-12,0,0,0,-180 +126.48,50.40863521,-3.581016276,50,-6.225840758,-2.58E-12,0,0,0,-180 +126.49,50.40863465,-3.581016276,50,-6.211936035,-1.34E-11,0,0,0,-180 +126.5,50.40863409,-3.581016276,50,-6.191078962,-2.98E-11,0,0,0,-180 +126.51,50.40863354,-3.581016276,50,-6.173698062,-3.80E-11,0,0,0,-180 +126.52,50.40863298,-3.581016276,50,-6.156317146,-2.99E-11,0,0,0,-180 +126.53,50.40863243,-3.581016276,50,-6.135460044,-1.36E-11,0,0,0,-180 +126.54,50.40863188,-3.581016276,50,-6.121555317,-2.64E-12,0,0,0,-180 +126.55,50.40863133,-3.581016276,50,-6.114602964,2.89E-12,0,0,0,-180 +126.56,50.40863078,-3.581016276,50,-6.100698245,1.38E-11,0,0,0,-180 +126.57,50.40863023,-3.581016276,50,-6.079841157,3.02E-11,0,0,0,-180 +126.58,50.40862969,-3.581016276,50,-6.062460248,3.83E-11,0,0,0,-180 +126.59,50.40862914,-3.581016276,50,-6.045079336,3.01E-11,0,0,0,-180 +126.6,50.4086286,-3.581016276,50,-6.024222239,1.37E-11,0,0,0,-180 +126.61,50.40862806,-3.581016276,50,-6.010317509,2.75E-12,0,0,0,-180 +126.62,50.40862752,-3.581016276,50,-6.003365159,-2.64E-12,0,0,0,-180 +126.63,50.40862698,-3.581016276,50,-5.985984269,-1.07E-11,0,0,0,-180 +126.64,50.40862644,-3.581016276,50,-5.95469864,-1.34E-11,0,0,0,-180 +126.65,50.40862591,-3.581016276,50,-5.933841534,2.97E-12,0,0,0,-180 +126.66,50.40862538,-3.581016276,50,-5.933841511,2.47E-11,0,0,0,-180 +126.67,50.40862484,-3.581016276,50,-5.926889148,3.01E-11,0,0,0,-180 +126.68,50.40862431,-3.581016276,50,-5.895603534,2.73E-11,0,0,0,-180 +126.69,50.40862378,-3.581016276,50,-5.860841734,3.26E-11,0,0,0,-180 +126.7,50.40862326,-3.581016276,50,-5.843460825,4.08E-11,0,0,0,-180 +126.71,50.40862273,-3.581016276,50,-5.839984627,4.35E-11,0,0,0,-180 +126.72,50.40862221,-3.581016276,50,-5.83650843,4.08E-11,0,0,0,-180 +126.73,50.40862168,-3.581016276,50,-5.822603707,2.98E-11,0,0,0,-180 +126.74,50.40862116,-3.581016276,50,-5.798270452,1.07E-11,0,0,0,-180 +126.75,50.40862064,-3.581016276,50,-5.770461007,-1.12E-11,0,0,0,-180 +126.76,50.40862012,-3.581016276,50,-5.74612773,-3.03E-11,0,0,0,-180 +126.77,50.40861961,-3.581016276,50,-5.728746817,-3.85E-11,0,0,0,-180 +126.78,50.40861909,-3.581016276,50,-5.714842094,-2.74E-11,0,0,0,-180 +126.79,50.40861858,-3.581016276,50,-5.707889736,-9.38E-14,0,0,0,-180 +126.8,50.40861807,-3.581016276,50,-5.70788974,2.17E-11,0,0,0,-180 +126.81,50.40861755,-3.581016276,50,-5.69050884,1.35E-11,0,0,0,-180 +126.82,50.40861704,-3.581016276,50,-5.652270852,-1.65E-11,0,0,0,-180 +126.83,50.40861654,-3.581016276,50,-5.624461398,-3.83E-11,0,0,0,-180 +126.84,50.40861603,-3.581016276,50,-5.617509023,-4.38E-11,0,0,0,-180 +126.85,50.40861553,-3.581016276,50,-5.614032832,-4.10E-11,0,0,0,-180 +126.86,50.40861502,-3.581016276,50,-5.600128103,-3.01E-11,0,0,0,-180 +126.87,50.40861452,-3.581016276,50,-5.579271014,-1.37E-11,0,0,0,-180 +126.88,50.40861402,-3.581016276,50,-5.561890114,-5.47E-12,0,0,0,-180 +126.89,50.40861352,-3.581016276,50,-5.544509216,-1.37E-11,0,0,0,-180 +126.9,50.40861302,-3.581016276,50,-5.523652126,-3.02E-11,0,0,0,-180 +126.91,50.40861253,-3.581016276,50,-5.50627121,-3.84E-11,0,0,0,-180 +126.92,50.40861203,-3.581016276,50,-5.488890308,-3.02E-11,0,0,0,-180 +126.93,50.40861154,-3.581016276,50,-5.468033231,-1.37E-11,0,0,0,-180 +126.94,50.40861105,-3.581016276,50,-5.454128501,-2.59E-12,0,0,0,-180 +126.95,50.40861056,-3.581016276,50,-5.447176128,2.87E-12,0,0,0,-180 +126.96,50.40861007,-3.581016276,50,-5.433271401,1.37E-11,0,0,0,-180 +126.97,50.40860958,-3.581016276,50,-5.412414311,2.99E-11,0,0,0,-180 +126.98,50.4086091,-3.581016276,50,-5.395033402,3.81E-11,0,0,0,-180 +126.99,50.40860861,-3.581016276,50,-5.377652502,2.99E-11,0,0,0,-180 +127,50.40860813,-3.581016276,50,-5.356795415,1.37E-11,0,0,0,-180 +127.01,50.40860765,-3.581016276,50,-5.3394145,5.61E-12,0,0,0,-180 +127.02,50.40860717,-3.581016276,50,-5.322033589,1.38E-11,0,0,0,-180 +127.03,50.40860669,-3.581016276,50,-5.301176505,3.01E-11,0,0,0,-180 +127.04,50.40860622,-3.581016276,50,-5.283795605,3.81E-11,0,0,0,-180 +127.05,50.40860574,-3.581016276,50,-5.266414701,2.99E-11,0,0,0,-180 +127.06,50.40860527,-3.581016276,50,-5.245557608,1.36E-11,0,0,0,-180 +127.07,50.4086048,-3.581016276,50,-5.231652881,2.72E-12,0,0,0,-180 +127.08,50.40860433,-3.581016276,50,-5.228176701,1.56E-17,0,0,0,-180 +127.09,50.40860386,-3.581016276,50,-5.224700519,2.73E-12,0,0,0,-180 +127.1,50.40860339,-3.581016276,50,-5.210795798,1.37E-11,0,0,0,-180 +127.11,50.40860292,-3.581016276,50,-5.189938714,3.01E-11,0,0,0,-180 +127.12,50.40860246,-3.581016276,50,-5.172557799,3.83E-11,0,0,0,-180 +127.13,50.40860199,-3.581016276,50,-5.151700704,3.29E-11,0,0,0,-180 +127.14,50.40860153,-3.581016276,50,-5.116938895,2.75E-11,0,0,0,-180 +127.15,50.40860107,-3.581016276,50,-5.085653266,3.02E-11,0,0,0,-180 +127.16,50.40860062,-3.581016276,50,-5.078700898,2.47E-11,0,0,0,-180 +127.17,50.40860016,-3.581016276,50,-5.078700896,2.83E-12,0,0,0,-180 +127.18,50.4085997,-3.581016276,50,-5.057843816,-1.35E-11,0,0,0,-180 +127.19,50.40859925,-3.581016276,50,-5.026558192,-1.07E-11,0,0,0,-180 +127.2,50.4085988,-3.581016276,50,-5.009177281,-2.48E-12,0,0,0,-180 +127.21,50.40859835,-3.581016276,50,-5.005701092,2.50E-13,0,0,0,-180 +127.22,50.4085979,-3.581016276,50,-5.005701089,0.000222146,0,0,0,-180 +127.23,50.40859745,-3.581016276,50,-5.005701089,0.001777172,0,0,0,179.9940665 +127.24,50.408597,-3.581016276,50,-5.005701089,0.007108685,0,0,0,179.9525317 +127.25,50.40859655,-3.581016275,50,-5.005701088,0.019326735,0,0,0,179.8397943 +127.26,50.4085961,-3.581016272,50,-5.005701088,0.04043064,0,0,0,179.6202532 +127.27,50.40859565,-3.581016265,50,-5.005701088,0.070198254,0,0,0,179.2701741 +127.28,50.4085952,-3.581016253,50,-5.005701087,0.107518846,0,0,0,178.8132912 +127.29,50.40859475,-3.581016236,50,-5.005701087,0.151281684,0,0,0,178.2852057 +127.3,50.4085943,-3.581016211,50,-5.005701086,0.199265303,0,0,0,177.721519 +127.31,50.40859385,-3.58101618,50,-5.002224904,0.248581802,0,0,0,177.1518987 +127.32,50.4085934,-3.581016141,50,-4.988320179,0.297676155,0,0,0,176.5822785 +127.33,50.40859295,-3.581016096,50,-4.970939277,0.346992656,0,0,0,176.0126582 +127.34,50.40859251,-3.581016044,50,-4.970939281,0.397197742,0,0,0,175.443038 +127.35,50.40859206,-3.581015984,50,-4.984844003,0.447624977,0,0,0,174.8734178 +127.36,50.40859161,-3.581015918,50,-4.984843996,0.497385774,0,0,0,174.3037975 +127.37,50.40859116,-3.581015844,50,-4.970939267,0.546257985,0,0,0,173.7341772 +127.38,50.40859072,-3.581015764,50,-4.967463085,0.594685904,0,0,0,173.164557 +127.39,50.40859027,-3.581015677,50,-4.967463084,0.643558117,0,0,0,172.5949367 +127.4,50.40858982,-3.581015583,50,-4.950082176,0.693096771,0,0,0,172.0253165 +127.41,50.40858938,-3.581015482,50,-4.932701269,0.742857572,0,0,0,171.4556962 +127.42,50.40858894,-3.581015374,50,-4.932701278,0.792396228,0,0,0,170.8860759 +127.43,50.40858849,-3.581015259,50,-4.929225109,0.841268444,0,0,0,170.3164557 +127.44,50.40858805,-3.581015137,50,-4.911844204,0.889696369,0,0,0,169.7468355 +127.45,50.40858761,-3.581015009,50,-4.897939462,0.938346442,0,0,0,169.1772152 +127.46,50.40858717,-3.581014873,50,-4.894463258,0.986996515,0,0,0,168.607595 +127.47,50.40858673,-3.581014731,50,-4.894463257,1.035424443,0,0,0,168.0379747 +127.48,50.40858629,-3.581014582,50,-4.890987097,1.084296664,0,0,0,167.4683544 +127.49,50.40858585,-3.581014426,50,-4.877082388,1.133613179,0,0,0,166.8987342 +127.5,50.40858541,-3.581014263,50,-4.8562253,1.182263255,0,0,0,166.3291139 +127.51,50.40858498,-3.581014093,50,-4.842320564,1.2298026,0,0,0,165.7594937 +127.52,50.40858454,-3.581013917,50,-4.838844371,1.277341946,0,0,0,165.1898734 +127.53,50.40858411,-3.581013734,50,-4.835368189,1.325992027,0,0,0,164.6202532 +127.54,50.40858367,-3.581013544,50,-4.821463473,1.3750864,0,0,0,164.0506329 +127.55,50.40858324,-3.581013347,50,-4.79713021,1.422847895,0,0,0,163.4810127 +127.56,50.40858281,-3.581013143,50,-4.769320758,1.469054366,0,0,0,162.9113924 +127.57,50.40858238,-3.581012934,50,-4.748463666,1.515482984,0,0,0,162.3417722 +127.58,50.40858196,-3.581012717,50,-4.744987475,1.563022335,0,0,0,161.7721519 +127.59,50.40858153,-3.581012494,50,-4.744987463,1.61100598,0,0,0,161.2025317 +127.6,50.4085811,-3.581012264,50,-4.724130373,1.658545333,0,0,0,160.6329114 +127.61,50.40858068,-3.581012027,50,-4.692844749,1.704973954,0,0,0,160.0632911 +127.62,50.40858026,-3.581011784,50,-4.675463849,1.75118043,0,0,0,159.4936709 +127.63,50.40857984,-3.581011535,50,-4.668511489,1.798497639,0,0,0,158.9240506 +127.64,50.40857942,-3.581011278,50,-4.654606771,1.845592702,0,0,0,158.3544304 +127.65,50.408579,-3.581011015,50,-4.633749692,1.890688449,0,0,0,157.7848102 +127.66,50.40857859,-3.581010746,50,-4.616368783,1.935117756,0,0,0,157.2151899 +127.67,50.40857817,-3.581010471,50,-4.598987864,1.981102089,0,0,0,156.6455696 +127.68,50.40857776,-3.581010189,50,-4.574654585,2.027975008,0,0,0,156.0759494 +127.69,50.40857735,-3.5810099,50,-4.546845138,2.073292903,0,0,0,155.5063291 +127.7,50.40857694,-3.581009605,50,-4.522511877,2.11727792,0,0,0,154.9367089 +127.71,50.40857654,-3.581009305,50,-4.50513097,2.16237367,0,0,0,154.3670886 +127.72,50.40857613,-3.581008997,50,-4.48775006,2.208358006,0,0,0,153.7974684 +127.73,50.40857573,-3.581008683,50,-4.463416792,2.253009465,0,0,0,153.2278481 +127.74,50.40857533,-3.581008363,50,-4.435607345,2.296328045,0,0,0,152.6582278 +127.75,50.40857493,-3.581008037,50,-4.411274073,2.339868773,0,0,0,152.0886076 +127.76,50.40857454,-3.581007705,50,-4.393893158,2.383853794,0,0,0,151.5189874 +127.77,50.40857414,-3.581007366,50,-4.376512245,2.427616669,0,0,0,150.9493671 +127.78,50.40857375,-3.581007022,50,-4.352178977,2.471157399,0,0,0,150.3797469 +127.79,50.40857336,-3.581006671,50,-4.320893349,2.514253836,0,0,0,149.8101266 +127.8,50.40857297,-3.581006314,50,-4.282655352,2.556461688,0,0,0,149.2405063 +127.81,50.40857259,-3.581005952,50,-4.24789354,2.598447393,0,0,0,148.6708861 +127.82,50.40857221,-3.581005583,50,-4.230512647,2.641099538,0,0,0,148.1012658 +127.83,50.40857183,-3.581005209,50,-4.223560298,2.684418124,0,0,0,147.5316456 +127.84,50.40857145,-3.581004828,50,-4.206179385,2.727292418,0,0,0,146.9620253 +127.85,50.40857107,-3.581004441,50,-4.171417551,2.768611687,0,0,0,146.392405 +127.86,50.4085707,-3.581004049,50,-4.133179543,2.80904237,0,0,0,145.8227848 +127.87,50.40857033,-3.581003651,50,-4.101893915,2.849473053,0,0,0,145.2531646 +127.88,50.40856996,-3.581003247,50,-4.077560656,2.889681589,0,0,0,144.6835443 +127.89,50.4085696,-3.581002838,50,-4.060179756,2.929890126,0,0,0,144.1139241 +127.9,50.40856923,-3.581002423,50,-4.039322668,2.970320812,0,0,0,143.5443038 +127.91,50.40856887,-3.581002002,50,-4.00108467,3.010529352,0,0,0,142.9746836 +127.92,50.40856851,-3.581001576,50,-3.952418128,3.050515744,0,0,0,142.4050633 +127.93,50.40856816,-3.581001144,50,-3.914180139,3.090057844,0,0,0,141.835443 +127.94,50.40856781,-3.581000706,50,-3.89332306,3.128711358,0,0,0,141.2658228 +127.95,50.40856746,-3.581000264,50,-3.872465969,3.166920581,0,0,0,140.6962025 +127.96,50.40856711,-3.580999815,50,-3.837704144,3.205129803,0,0,0,140.1265823 +127.97,50.40856677,-3.580999362,50,-3.799466145,3.243561173,0,0,0,139.5569621 +127.98,50.40856643,-3.580998903,50,-3.768180519,3.281770395,0,0,0,138.9873418 +127.99,50.40856609,-3.580998438,50,-3.74037107,3.318424592,0,0,0,138.4177215 +128,50.40856576,-3.580997969,50,-3.709085441,3.354190204,0,0,0,137.8481013 +128.01,50.40856542,-3.580997495,50,-3.670847458,3.391066549,0,0,0,137.278481 +128.02,50.4085651,-3.580997015,50,-3.632609466,3.428387188,0,0,0,136.7088608 +128.03,50.40856477,-3.58099653,50,-3.601323822,3.464374947,0,0,0,136.1392405 +128.04,50.40856445,-3.58099604,50,-3.573514362,3.499696267,0,0,0,135.5696202 +128.05,50.40856413,-3.580995546,50,-3.542228732,3.535461881,0,0,0,135 +128.06,50.40856381,-3.580995045,50,-3.50399074,3.570783201,0,0,0,134.4303797 +128.07,50.4085635,-3.580994541,50,-3.465752746,3.60499379,0,0,0,133.8607595 +128.08,50.40856319,-3.580994031,50,-3.430990936,3.638760085,0,0,0,133.2911393 +128.09,50.40856288,-3.580993517,50,-3.392752944,3.672526379,0,0,0,132.721519 +128.1,50.40856258,-3.580992998,50,-3.354514948,3.706070528,0,0,0,132.1518988 +128.11,50.40856228,-3.580992474,50,-3.319753131,3.739170386,0,0,0,131.5822785 +128.12,50.40856198,-3.580991946,50,-3.281515132,3.772270243,0,0,0,131.0126582 +128.13,50.40856169,-3.580991413,50,-3.243277138,3.805592245,0,0,0,130.443038 +128.14,50.4085614,-3.580990875,50,-3.208515337,3.838247809,0,0,0,129.8734177 +128.15,50.40856111,-3.580990333,50,-3.170277354,3.869570494,0,0,0,129.3037975 +128.16,50.40856083,-3.580989786,50,-3.132039351,3.900226739,0,0,0,128.7341772 +128.17,50.40856055,-3.580989236,50,-3.097277519,3.931105131,0,0,0,128.164557 +128.18,50.40856027,-3.58098868,50,-3.055563339,3.961761376,0,0,0,127.5949367 +128.19,50.40856,-3.580988121,50,-3.003420634,3.991306888,0,0,0,127.0253165 +128.2,50.40855973,-3.580987557,50,-2.951277929,4.02018596,0,0,0,126.4556962 +128.21,50.40855947,-3.58098699,50,-2.913039933,4.049509325,0,0,0,125.886076 +128.22,50.40855921,-3.580986418,50,-2.892182834,4.079276985,0,0,0,125.3164557 +128.23,50.40855895,-3.580985842,50,-2.86784956,4.108600352,0,0,0,124.7468354 +128.24,50.40855869,-3.580985262,50,-2.819183019,4.137035133,0,0,0,124.1772152 +128.25,50.40855844,-3.580984678,50,-2.763564112,4.164581327,0,0,0,123.6075949 +128.26,50.4085582,-3.58098409,50,-2.725326125,4.19146108,0,0,0,123.0379747 +128.27,50.40855795,-3.580983499,50,-2.687088149,4.21789654,0,0,0,122.4683544 +128.28,50.40855771,-3.580982903,50,-2.631469251,4.243887708,0,0,0,121.8987342 +128.29,50.40855748,-3.580982305,50,-2.582802701,4.269878876,0,0,0,121.329114 +128.3,50.40855725,-3.580981702,50,-2.558469427,4.29609219,0,0,0,120.7594937 +128.31,50.40855702,-3.580981096,50,-2.534136157,4.321861211,0,0,0,120.1898734 +128.32,50.40855679,-3.580980486,50,-2.485469612,4.346963792,0,0,0,119.6202532 +128.33,50.40855657,-3.580979873,50,-2.426374526,4.37162208,0,0,0,119.0506329 +128.34,50.40855636,-3.580979256,50,-2.377707994,4.395391781,0,0,0,118.4810127 +128.35,50.40855614,-3.580978636,50,-2.335993823,4.41805075,0,0,0,117.9113924 +128.36,50.40855594,-3.580978013,50,-2.294279647,4.440487572,0,0,0,117.3417721 +128.37,50.40855573,-3.580977387,50,-2.249089294,4.463146541,0,0,0,116.7721519 +128.38,50.40855553,-3.580976757,50,-2.203898944,4.485583362,0,0,0,116.2025317 +128.39,50.40855534,-3.580976125,50,-2.169137127,4.507798036,0,0,0,115.6329114 +128.4,50.40855514,-3.580975489,50,-2.130899122,4.529346272,0,0,0,115.0632912 +128.41,50.40855495,-3.58097485,50,-2.075280225,4.549561628,0,0,0,114.4936709 +128.42,50.40855477,-3.580974209,50,-2.023137522,4.569776982,0,0,0,113.9240506 +128.43,50.40855459,-3.580973565,50,-1.984899532,4.590880922,0,0,0,113.3544304 +128.44,50.40855441,-3.580972917,50,-1.943185344,4.61087413,0,0,0,112.7848101 +128.45,50.40855424,-3.580972267,50,-1.89104261,4.628645872,0,0,0,112.2151899 +128.46,50.40855407,-3.580971615,50,-1.838899887,4.645751174,0,0,0,111.6455696 +128.47,50.40855391,-3.58097096,50,-1.797185725,4.663522916,0,0,0,111.0759494 +128.48,50.40855375,-3.580970303,50,-1.758947749,4.682183244,0,0,0,110.5063292 +128.49,50.40855359,-3.580969643,50,-1.706805024,4.701065718,0,0,0,109.9367089 +128.5,50.40855344,-3.58096898,50,-1.647709918,4.718615312,0,0,0,109.3670886 +128.51,50.4085533,-3.580968315,50,-1.599043375,4.734165587,0,0,0,108.7974684 +128.52,50.40855315,-3.580967648,50,-1.557329215,4.748605128,0,0,0,108.2278481 +128.53,50.40855302,-3.580966979,50,-1.515615046,4.763044668,0,0,0,107.6582279 +128.54,50.40855288,-3.580966308,50,-1.470424685,4.778150649,0,0,0,107.0886076 +128.55,50.40855275,-3.580965635,50,-1.421758148,4.793478775,0,0,0,106.5189873 +128.56,50.40855263,-3.580964959,50,-1.3765678,4.80769617,0,0,0,105.9493671 +128.57,50.4085525,-3.580964282,50,-1.331377445,4.820580684,0,0,0,105.3797468 +128.58,50.40855239,-3.580963603,50,-1.279234718,4.833020904,0,0,0,104.8101266 +128.59,50.40855227,-3.580962922,50,-1.227091995,4.845461123,0,0,0,104.2405064 +128.6,50.40855217,-3.58096224,50,-1.181901645,4.857679195,0,0,0,103.6708861 +128.61,50.40855206,-3.580961555,50,-1.133235108,4.869452974,0,0,0,103.1012658 +128.62,50.40855196,-3.58096087,50,-1.074140014,4.881004607,0,0,0,102.5316456 +128.63,50.40855187,-3.580960182,50,-1.021997278,4.892111946,0,0,0,101.9620253 +128.64,50.40855178,-3.580959493,50,-0.983759282,4.902108551,0,0,0,101.3924051 +128.65,50.40855169,-3.580958803,50,-0.942045122,4.910994423,0,0,0,100.8227848 +128.66,50.40855161,-3.580958111,50,-0.889902419,4.919213855,0,0,0,100.2531646 +128.67,50.40855153,-3.580957419,50,-0.837759703,4.927433287,0,0,0,99.68354429 +128.68,50.40855146,-3.580956725,50,-0.796045517,4.935874864,0,0,0,99.11392404 +128.69,50.40855139,-3.58095603,50,-0.75780751,4.943872148,0,0,0,98.54430383 +128.7,50.40855132,-3.580955334,50,-0.70218861,4.951202992,0,0,0,97.97468358 +128.71,50.40855126,-3.580954637,50,-0.632664992,4.958089542,0,0,0,97.40506332 +128.72,50.40855121,-3.580953939,50,-0.577046092,4.964309652,0,0,0,96.83544306 +128.73,50.40855116,-3.58095324,50,-0.538808099,4.969863322,0,0,0,96.2658228 +128.74,50.40855111,-3.580952541,50,-0.500570112,4.974972699,0,0,0,95.69620254 +128.75,50.40855107,-3.58095184,50,-0.458855941,4.979637781,0,0,0,95.12658228 +128.76,50.40855103,-3.58095114,50,-0.4101894,4.984080717,0,0,0,94.55696202 +128.77,50.40855099,-3.580950438,50,-0.351094309,4.988079358,0,0,0,93.98734177 +128.78,50.40855097,-3.580949736,50,-0.295475396,4.990967267,0,0,0,93.41772151 +128.79,50.40855094,-3.580949034,50,-0.246808851,4.992966589,0,0,0,92.84810125 +128.8,50.40855092,-3.580948331,50,-0.198142321,4.99496591,0,0,0,92.27848105 +128.81,50.40855091,-3.580947629,50,-0.152951979,4.997409525,0,0,0,91.71479428 +128.82,50.40855089,-3.580946925,50,-0.111237811,4.999630992,0,0,0,91.18670882 +128.83,50.40855089,-3.580946222,50,-0.072999815,5.000519579,0,0,0,90.72982592 +128.84,50.40855088,-3.580945518,50,-0.04171418,4.99985314,0,0,0,90.37974681 +128.85,50.40855088,-3.580944815,50,-0.017380908,4.998742407,0,0,0,90.16020571 +128.86,50.40855088,-3.580944112,50,-0.003476182,4.998742407,0,0,0,90.04746836 +128.87,50.40855088,-3.580943409,50,0,4.999408847,0,0,0,90.00593356 +128.88,50.40855088,-3.580942705,50,0,4.997853821,0,0,0,90.00000001 +128.89,50.40855088,-3.580942002,50,0,4.99207801,0,0,0,90.00000001 +128.9,50.40855088,-3.5809413,50,0,4.983192147,0,0,0,90.00000001 +128.91,50.40855088,-3.5809406,50,0,4.973639844,0,0,0,90.00000001 +128.92,50.40855088,-3.580939901,50,0,4.964309687,0,0,0,90.00000001 +128.93,50.40855088,-3.580939203,50,0,4.954757384,0,0,0,90.00000001 +128.94,50.40855088,-3.580938507,50,0,4.94520508,0,0,0,90.00000001 +128.95,50.40855088,-3.580937812,50,0,4.935874924,0,0,0,90.00000001 +128.96,50.40855088,-3.580937118,50,0,4.926100475,0,0,0,90.00000001 +128.97,50.40855088,-3.580936426,50,0,4.915659585,0,0,0,90.00000001 +128.98,50.40855088,-3.580935735,50,0,4.904996549,0,0,0,90.00000001 +128.99,50.40855088,-3.580935046,50,0,4.894333514,0,0,0,90.00000001 +129,50.40855088,-3.580934358,50,0,4.883892624,0,0,0,90.00000001 +129.01,50.40855088,-3.580933672,50,0,4.874118174,0,0,0,90.00000001 +129.02,50.40855088,-3.580932987,50,0,4.864788018,0,0,0,90.00000001 +129.03,50.40855088,-3.580932303,50,0,4.855235715,0,0,0,90.00000001 +129.04,50.40855088,-3.580931621,50,0,4.845461265,0,0,0,90.00000001 +129.05,50.40855088,-3.58093094,50,0,4.835242522,0,0,0,90.00000001 +129.06,50.40855088,-3.58093026,50,0,4.824357339,0,0,0,90.00000001 +129.07,50.40855088,-3.580929583,50,0,4.813916451,0,0,0,90.00000001 +129.08,50.40855088,-3.580928906,50,0,4.804364148,0,0,0,90.00000001 +129.09,50.40855088,-3.580928231,50,0,4.794589698,0,0,0,90.00000001 +129.1,50.40855088,-3.580927557,50,0,4.784370955,0,0,0,90.00000001 +129.11,50.40855088,-3.580926885,50,0,4.774596505,0,0,0,90.00000001 +129.12,50.40855088,-3.580926214,50,0,4.765266348,0,0,0,90.00000001 +129.13,50.40855088,-3.580925544,50,0,4.755491899,0,0,0,90.00000001 +129.14,50.40855088,-3.580924876,50,0,4.74505101,0,0,0,90.00000001 +129.15,50.40855088,-3.580924209,50,0,4.734387974,0,0,0,90.00000001 +129.16,50.40855088,-3.580923544,50,0,4.723724938,0,0,0,90.00000001 +129.17,50.40855088,-3.58092288,50,0,4.713284049,0,0,0,90.00000001 +129.18,50.40855088,-3.580922218,50,0,4.703509599,0,0,0,90.00000001 +129.19,50.40855088,-3.580921557,50,0,4.694179442,0,0,0,90.00000001 +129.2,50.40855088,-3.580920897,50,0,4.684627139,0,0,0,90.00000001 +129.21,50.40855088,-3.580920239,50,0,4.67485269,0,0,0,90.00000001 +129.22,50.40855088,-3.580919582,50,0,4.664633947,0,0,0,90.00000001 +129.23,50.40855088,-3.580918926,50,0,4.653970911,0,0,0,90.00000001 +129.24,50.40855088,-3.580918273,50,0,4.644196461,0,0,0,90.00000001 +129.25,50.40855088,-3.58091762,50,0,4.635088451,0,0,0,90.00000001 +129.26,50.40855088,-3.580916968,50,0,4.625091855,0,0,0,90.00000001 +129.27,50.40855088,-3.580916319,50,0,4.614650965,0,0,0,90.00000001 +129.28,50.40855088,-3.58091567,50,0,4.604210076,0,0,0,90.00000001 +129.29,50.40855088,-3.580915023,50,0,4.593324893,0,0,0,90.00000001 +129.3,50.40855088,-3.580914378,50,0,4.582884004,0,0,0,90.00000001 +129.31,50.40855088,-3.580913734,50,0,4.573331701,0,0,0,90.00000001 +129.32,50.40855088,-3.580913091,50,0,4.563779398,0,0,0,90.00000001 +129.33,50.40855088,-3.58091245,50,0,4.554227096,0,0,0,90.00000001 +129.34,50.40855088,-3.58091181,50,0,4.544896939,0,0,0,90.00000001 +129.35,50.40855088,-3.580911171,50,0,4.535122489,0,0,0,90.00000001 +129.36,50.40855088,-3.580910534,50,0,4.524681599,0,0,0,90.00000001 +129.37,50.40855088,-3.580909898,50,0,4.51424071,0,0,0,90.00000001 +129.38,50.40855088,-3.580909264,50,0,4.504244114,0,0,0,90.00000001 +129.39,50.40855088,-3.580908631,50,0,4.494025372,0,0,0,90.00000001 +129.4,50.40855088,-3.580907999,50,0,4.483140189,0,0,0,90.00000001 +129.41,50.40855088,-3.58090737,50,0,4.472699299,0,0,0,90.00000001 +129.42,50.40855088,-3.580906741,50,0,4.463369143,0,0,0,90.00000001 +129.43,50.40855088,-3.580906114,50,0,4.454483279,0,0,0,90.00000001 +129.44,50.40855088,-3.580905488,50,0,4.445153122,0,0,0,90.00000001 +129.45,50.40855088,-3.580904863,50,0,4.434490087,0,0,0,90.00000001 +129.46,50.40855088,-3.58090424,50,0,4.422938465,0,0,0,90.00000001 +129.47,50.40855088,-3.580903619,50,0,4.412497576,0,0,0,90.00000001 +129.48,50.40855088,-3.580902999,50,0,4.403833859,0,0,0,90.00000001 +129.49,50.40855088,-3.58090238,50,0,4.395392289,0,0,0,90.00000001 +129.5,50.40855088,-3.580901762,50,0,4.385839985,0,0,0,90.00000001 +129.51,50.40855088,-3.580901146,50,0,4.375176949,0,0,0,90.00000001 +129.52,50.40855088,-3.580900531,50,0,4.363847473,0,0,0,90.00000001 +129.53,50.40855088,-3.580899918,50,0,4.352740143,0,0,0,90.00000001 +129.54,50.40855088,-3.580899307,50,0,4.342521401,0,0,0,90.00000001 +129.55,50.40855088,-3.580898696,50,0,4.332746952,0,0,0,90.00000001 +129.56,50.40855088,-3.580898088,50,0,4.323194649,0,0,0,90.00000001 +129.57,50.40855088,-3.58089748,50,0,4.313864493,0,0,0,90.00000001 +129.58,50.40855088,-3.580896874,50,0,4.304090043,0,0,0,90.00000001 +129.59,50.40855088,-3.580896269,50,0,4.293649154,0,0,0,90.00000001 +129.6,50.40855088,-3.580895666,50,0,4.282986118,0,0,0,90.00000001 +129.61,50.40855088,-3.580895064,50,0,4.272545228,0,0,0,90.00000001 +129.62,50.40855088,-3.580894464,50,0,4.262992925,0,0,0,90.00000001 +129.63,50.40855088,-3.580893865,50,0,4.254329208,0,0,0,90.00000001 +129.64,50.40855088,-3.580893267,50,0,4.244999051,0,0,0,90.00000001 +129.65,50.40855088,-3.58089267,50,0,4.234336016,0,0,0,90.00000001 +129.66,50.40855088,-3.580892076,50,0,4.22367298,0,0,0,90.00000001 +129.67,50.40855088,-3.580891482,50,0,4.213232091,0,0,0,90.00000001 +129.68,50.40855088,-3.58089089,50,0,4.202346908,0,0,0,90.00000001 +129.69,50.40855088,-3.5808903,50,0,4.191906019,0,0,0,90.00000001 +129.7,50.40855088,-3.580889711,50,0,4.182353716,0,0,0,90.00000001 +129.71,50.40855088,-3.580889123,50,0,4.172801413,0,0,0,90.00000001 +129.72,50.40855088,-3.580888537,50,0,4.163249109,0,0,0,90.00000001 +129.73,50.40855088,-3.580887952,50,0,4.153918952,0,0,0,90.00000001 +129.74,50.40855088,-3.580887368,50,0,4.144144503,0,0,0,90.00000001 +129.75,50.40855088,-3.580886786,50,0,4.133703614,0,0,0,90.00000001 +129.76,50.40855088,-3.580886205,50,0,4.123262725,0,0,0,90.00000001 +129.77,50.40855088,-3.580885626,50,0,4.113488275,0,0,0,90.00000001 +129.78,50.40855088,-3.580885048,50,0,4.103935972,0,0,0,90.00000001 +129.79,50.40855088,-3.580884471,50,0,4.093495082,0,0,0,90.00000001 +129.8,50.40855088,-3.580883896,50,0,4.0826099,0,0,0,90.00000001 +129.81,50.40855088,-3.580883323,50,0,4.072391157,0,0,0,90.00000001 +129.82,50.40855088,-3.58088275,50,0,4.062616707,0,0,0,90.00000001 +129.83,50.40855088,-3.58088218,50,0,4.053064404,0,0,0,90.00000001 +129.84,50.40855088,-3.58088161,50,0,4.043734247,0,0,0,90.00000001 +129.85,50.40855088,-3.580881042,50,0,4.033959798,0,0,0,90.00000001 +129.86,50.40855088,-3.580880475,50,0,4.023518908,0,0,0,90.00000001 +129.87,50.40855088,-3.58087991,50,0,4.012855873,0,0,0,90.00000001 +129.88,50.40855088,-3.580879346,50,0,4.002414984,0,0,0,90.00000001 +129.89,50.40855088,-3.580878784,50,0,3.992640534,0,0,0,90.00000001 +129.9,50.40855088,-3.580878223,50,0,3.983310377,0,0,0,90.00000001 +129.91,50.40855088,-3.580877663,50,0,3.973535927,0,0,0,90.00000001 +129.92,50.40855088,-3.580877105,50,0,3.963095038,0,0,0,90.00000001 +129.93,50.40855088,-3.580876548,50,0,3.952654148,0,0,0,90.00000001 +129.94,50.40855088,-3.580875993,50,0,3.942879699,0,0,0,90.00000001 +129.95,50.40855088,-3.580875439,50,0,3.933327396,0,0,0,90.00000001 +129.96,50.40855088,-3.580874886,50,0,3.922886507,0,0,0,90.00000001 +129.97,50.40855088,-3.580874335,50,0,3.912223471,0,0,0,90.00000001 +129.98,50.40855088,-3.580873786,50,0,3.902671168,0,0,0,90.00000001 +129.99,50.40855088,-3.580873237,50,0,3.893118865,0,0,0,90.00000001 +130,50.40855088,-3.58087269,50,0,3.882455828,0,0,0,90.00000001 +130.01,50.40855088,-3.580872145,50,0,3.872014939,0,0,0,90.00000001 +130.02,50.40855088,-3.580871601,50,0,3.862462636,0,0,0,90.00000001 +130.03,50.40855088,-3.580871058,50,0,3.852688186,0,0,0,90.00000001 +130.04,50.40855088,-3.580870517,50,0,3.842469444,0,0,0,90.00000001 +130.05,50.40855088,-3.580869977,50,0,3.832694994,0,0,0,90.00000001 +130.06,50.40855088,-3.580869439,50,0,3.823142691,0,0,0,90.00000001 +130.07,50.40855088,-3.580868901,50,0,3.812701802,0,0,0,90.00000001 +130.08,50.40855088,-3.580868366,50,0,3.801816619,0,0,0,90.00000001 +130.09,50.40855088,-3.580867832,50,0,3.791597876,0,0,0,90.00000001 +130.1,50.40855088,-3.580867299,50,0,3.781823426,0,0,0,90.00000001 +130.11,50.40855088,-3.580866768,50,0,3.772271123,0,0,0,90.00000001 +130.12,50.40855088,-3.580866238,50,0,3.762940967,0,0,0,90.00000001 +130.13,50.40855088,-3.580865709,50,0,3.753388664,0,0,0,90.00000001 +130.14,50.40855088,-3.580865182,50,0,3.743614214,0,0,0,90.00000001 +130.15,50.40855088,-3.580864656,50,0,3.733395471,0,0,0,90.00000001 +130.16,50.40855088,-3.580864131,50,0,3.722510289,0,0,0,90.00000001 +130.17,50.40855088,-3.580863609,50,0,3.712069399,0,0,0,90.00000001 +130.18,50.40855088,-3.580863087,50,0,3.702517096,0,0,0,90.00000001 +130.19,50.40855088,-3.580862567,50,0,3.692742647,0,0,0,90.00000001 +130.2,50.40855088,-3.580862048,50,0,3.682301757,0,0,0,90.00000001 +130.21,50.40855088,-3.580861531,50,0,3.671860868,0,0,0,90.00000001 +130.22,50.40855088,-3.580861015,50,0,3.662086418,0,0,0,90.00000001 +130.23,50.40855088,-3.580860501,50,0,3.652534115,0,0,0,90.00000001 +130.24,50.40855088,-3.580859987,50,0,3.642093226,0,0,0,90.00000001 +130.25,50.40855088,-3.580859476,50,0,3.63143019,0,0,0,90.00000001 +130.26,50.40855088,-3.580858966,50,0,3.622100034,0,0,0,90.00000001 +130.27,50.40855088,-3.580858457,50,0,3.61321417,0,0,0,90.00000001 +130.28,50.40855088,-3.580857949,50,0,3.602995427,0,0,0,90.00000001 +130.29,50.40855088,-3.580857443,50,0,3.592110245,0,0,0,90.00000001 +130.3,50.40855088,-3.580856939,50,0,3.581891502,0,0,0,90.00000001 +130.31,50.40855088,-3.580856435,50,0,3.572117052,0,0,0,90.00000001 +130.32,50.40855088,-3.580855934,50,0,3.562564749,0,0,0,90.00000001 +130.33,50.40855088,-3.580855433,50,0,3.553012446,0,0,0,90.00000001 +130.34,50.40855088,-3.580854934,50,0,3.54234941,0,0,0,90.00000001 +130.35,50.40855088,-3.580854436,50,0,3.531019935,0,0,0,90.00000001 +130.36,50.40855088,-3.580853941,50,0,3.521245485,0,0,0,90.00000001 +130.37,50.40855088,-3.580853446,50,0,3.512803915,0,0,0,90.00000001 +130.38,50.40855088,-3.580852952,50,0,3.503029465,0,0,0,90.00000001 +130.39,50.40855088,-3.58085246,50,0,3.491699989,0,0,0,90.00000001 +130.4,50.40855088,-3.58085197,50,0,3.481036954,0,0,0,90.00000001 +130.41,50.40855088,-3.580851481,50,0,3.47148465,0,0,0,90.00000001 +130.42,50.40855088,-3.580850993,50,0,3.4617102,0,0,0,90.00000001 +130.43,50.40855088,-3.580850507,50,0,3.451491457,0,0,0,90.00000001 +130.44,50.40855088,-3.580850022,50,0,3.441717008,0,0,0,90.00000001 +130.45,50.40855088,-3.580849539,50,0,3.432164705,0,0,0,90.00000001 +130.46,50.40855088,-3.580849056,50,0,3.421723815,0,0,0,90.00000001 +130.47,50.40855088,-3.580848576,50,0,3.411060779,0,0,0,90.00000001 +130.48,50.40855088,-3.580848097,50,0,3.401730623,0,0,0,90.00000001 +130.49,50.40855088,-3.580847619,50,0,3.39284476,0,0,0,90.00000001 +130.5,50.40855088,-3.580847142,50,0,3.382403871,0,0,0,90.00000001 +130.51,50.40855088,-3.580846667,50,0,3.370852249,0,0,0,90.00000001 +130.52,50.40855088,-3.580846194,50,0,3.360411359,0,0,0,90.00000001 +130.53,50.40855088,-3.580845722,50,0,3.351747642,0,0,0,90.00000001 +130.54,50.40855088,-3.580845251,50,0,3.343083925,0,0,0,90.00000001 +130.55,50.40855088,-3.580844781,50,0,3.332643035,0,0,0,90.00000001 +130.56,50.40855088,-3.580844313,50,0,3.321091413,0,0,0,90.00000001 +130.57,50.40855088,-3.580843847,50,0,3.310650524,0,0,0,90.00000001 +130.58,50.40855088,-3.580843382,50,0,3.301764661,0,0,0,90.00000001 +130.59,50.40855088,-3.580842918,50,0,3.292434505,0,0,0,90.00000001 +130.6,50.40855088,-3.580842455,50,0,3.281771469,0,0,0,90.00000001 +130.61,50.40855088,-3.580841995,50,0,3.271330579,0,0,0,90.00000001 +130.62,50.40855088,-3.580841535,50,0,3.261778276,0,0,0,90.00000001 +130.63,50.40855088,-3.580841077,50,0,3.252003826,0,0,0,90.00000001 +130.64,50.40855088,-3.58084062,50,0,3.241562937,0,0,0,90.00000001 +130.65,50.40855088,-3.580840165,50,0,3.230899901,0,0,0,90.00000001 +130.66,50.40855088,-3.580839711,50,0,3.220459011,0,0,0,90.00000001 +130.67,50.40855088,-3.580839259,50,0,3.210684562,0,0,0,90.00000001 +130.68,50.40855088,-3.580838808,50,0,3.201354406,0,0,0,90.00000001 +130.69,50.40855088,-3.580838358,50,0,3.191802103,0,0,0,90.00000001 +130.7,50.40855088,-3.58083791,50,0,3.1822498,0,0,0,90.00000001 +130.71,50.40855088,-3.580837463,50,0,3.172697496,0,0,0,90.00000001 +130.72,50.40855088,-3.580837017,50,0,3.162034461,0,0,0,90.00000001 +130.73,50.40855088,-3.580836573,50,0,3.150482838,0,0,0,90.00000001 +130.74,50.40855088,-3.580836131,50,0,3.140041949,0,0,0,90.00000001 +130.75,50.40855088,-3.58083569,50,0,3.131156086,0,0,0,90.00000001 +130.76,50.40855088,-3.58083525,50,0,3.121825929,0,0,0,90.00000001 +130.77,50.40855088,-3.580834811,50,0,3.111162892,0,0,0,90.00000001 +130.78,50.40855088,-3.580834375,50,0,3.100722003,0,0,0,90.00000001 +130.79,50.40855088,-3.580833939,50,0,3.0911697,0,0,0,90.00000001 +130.8,50.40855088,-3.580833505,50,0,3.081395251,0,0,0,90.00000001 +130.81,50.40855088,-3.580833072,50,0,3.071176508,0,0,0,90.00000001 +130.82,50.40855088,-3.580832641,50,0,3.061402058,0,0,0,90.00000001 +130.83,50.40855088,-3.580832211,50,0,3.051849755,0,0,0,90.00000001 +130.84,50.40855088,-3.580831782,50,0,3.041408866,0,0,0,90.00000001 +130.85,50.40855088,-3.580831355,50,0,3.03074583,0,0,0,90.00000001 +130.86,50.40855088,-3.58083093,50,0,3.021193527,0,0,0,90.00000001 +130.87,50.40855088,-3.580830505,50,0,3.011641223,0,0,0,90.00000001 +130.88,50.40855088,-3.580830082,50,0,3.000978188,0,0,0,90.00000001 +130.89,50.40855088,-3.580829661,50,0,2.990537298,0,0,0,90.00000001 +130.9,50.40855088,-3.580829241,50,0,2.980984995,0,0,0,90.00000001 +130.91,50.40855088,-3.580828822,50,0,2.971210545,0,0,0,90.00000001 +130.92,50.40855088,-3.580828405,50,0,2.960769656,0,0,0,90.00000001 +130.93,50.40855088,-3.580827989,50,0,2.950106621,0,0,0,90.00000001 +130.94,50.40855088,-3.580827575,50,0,2.939665731,0,0,0,90.00000001 +130.95,50.40855088,-3.580827162,50,0,2.930113428,0,0,0,90.00000001 +130.96,50.40855088,-3.580826751,50,0,2.921449711,0,0,0,90.00000001 +130.97,50.40855088,-3.58082634,50,0,2.912119554,0,0,0,90.00000001 +130.98,50.40855088,-3.580825931,50,0,2.901234372,0,0,0,90.00000001 +130.99,50.40855088,-3.580825524,50,0,2.890127043,0,0,0,90.00000001 +131,50.40855088,-3.580825118,50,0,2.880130447,0,0,0,90.00000001 +131.01,50.40855088,-3.580824714,50,0,2.87080029,0,0,0,90.00000001 +131.02,50.40855088,-3.58082431,50,0,2.861247987,0,0,0,90.00000001 +131.03,50.40855088,-3.580823909,50,0,2.851473538,0,0,0,90.00000001 +131.04,50.40855088,-3.580823508,50,0,2.841254796,0,0,0,90.00000001 +131.05,50.40855088,-3.580823109,50,0,2.830369613,0,0,0,90.00000001 +131.06,50.40855088,-3.580822712,50,0,2.819928722,0,0,0,90.00000001 +131.07,50.40855088,-3.580822316,50,0,2.810376419,0,0,0,90.00000001 +131.08,50.40855088,-3.580821921,50,0,2.80060197,0,0,0,90.00000001 +131.09,50.40855088,-3.580821528,50,0,2.790161081,0,0,0,90.00000001 +131.1,50.40855088,-3.580821136,50,0,2.779720191,0,0,0,90.00000001 +131.11,50.40855088,-3.580820746,50,0,2.769945741,0,0,0,90.00000001 +131.12,50.40855088,-3.580820357,50,0,2.760615585,0,0,0,90.00000001 +131.13,50.40855088,-3.580819969,50,0,2.751063282,0,0,0,90.00000001 +131.14,50.40855088,-3.580819583,50,0,2.741288832,0,0,0,90.00000001 +131.15,50.40855088,-3.580819198,50,0,2.731070089,0,0,0,90.00000001 +131.16,50.40855088,-3.580818814,50,0,2.720184907,0,0,0,90.00000001 +131.17,50.40855088,-3.580818433,50,0,2.709744018,0,0,0,90.00000001 +131.18,50.40855088,-3.580818052,50,0,2.700191715,0,0,0,90.00000001 +131.19,50.40855088,-3.580817673,50,0,2.690417265,0,0,0,90.00000001 +131.2,50.40855088,-3.580817295,50,0,2.680198522,0,0,0,90.00000001 +131.21,50.40855088,-3.580816919,50,0,2.670424072,0,0,0,90.00000001 +131.22,50.40855088,-3.580816544,50,0,2.660871769,0,0,0,90.00000001 +131.23,50.40855088,-3.58081617,50,0,2.65043088,0,0,0,90.00000001 +131.24,50.40855088,-3.580815798,50,0,2.639767844,0,0,0,90.00000001 +131.25,50.40855088,-3.580815428,50,0,2.630215541,0,0,0,90.00000001 +131.26,50.40855088,-3.580815058,50,0,2.620663238,0,0,0,90.00000001 +131.27,50.40855088,-3.58081469,50,0,2.610000203,0,0,0,90.00000001 +131.28,50.40855088,-3.580814324,50,0,2.599559313,0,0,0,90.00000001 +131.29,50.40855088,-3.580813959,50,0,2.590007009,0,0,0,90.00000001 +131.3,50.40855088,-3.580813595,50,0,2.580232559,0,0,0,90.00000001 +131.31,50.40855088,-3.580813233,50,0,2.570013817,0,0,0,90.00000001 +131.32,50.40855088,-3.580812872,50,0,2.560239367,0,0,0,90.00000001 +131.33,50.40855088,-3.580812513,50,0,2.550687064,0,0,0,90.00000001 +131.34,50.40855088,-3.580812154,50,0,2.540246175,0,0,0,90.00000001 +131.35,50.40855088,-3.580811798,50,0,2.52958314,0,0,0,90.00000001 +131.36,50.40855088,-3.580811443,50,0,2.520030836,0,0,0,90.00000001 +131.37,50.40855088,-3.580811089,50,0,2.510478533,0,0,0,90.00000001 +131.38,50.40855088,-3.580810736,50,0,2.499815497,0,0,0,90.00000001 +131.39,50.40855088,-3.580810386,50,0,2.489374607,0,0,0,90.00000001 +131.4,50.40855088,-3.580810036,50,0,2.479822304,0,0,0,90.00000001 +131.41,50.40855088,-3.580809688,50,0,2.470047855,0,0,0,90.00000001 +131.42,50.40855088,-3.580809341,50,0,2.459829112,0,0,0,90.00000001 +131.43,50.40855088,-3.580808996,50,0,2.450054662,0,0,0,90.00000001 +131.44,50.40855088,-3.580808652,50,0,2.440502359,0,0,0,90.00000001 +131.45,50.40855088,-3.580808309,50,0,2.43006147,0,0,0,90.00000001 +131.46,50.40855088,-3.580807968,50,0,2.419398434,0,0,0,90.00000001 +131.47,50.40855088,-3.580807629,50,0,2.40984613,0,0,0,90.00000001 +131.48,50.40855088,-3.58080729,50,0,2.400293827,0,0,0,90.00000001 +131.49,50.40855088,-3.580806953,50,0,2.389630792,0,0,0,90.00000001 +131.5,50.40855088,-3.580806618,50,0,2.379189903,0,0,0,90.00000001 +131.51,50.40855088,-3.580806284,50,0,2.3696376,0,0,0,90.00000001 +131.52,50.40855088,-3.580805951,50,0,2.35986315,0,0,0,90.00000001 +131.53,50.40855088,-3.58080562,50,0,2.349644406,0,0,0,90.00000001 +131.54,50.40855088,-3.58080529,50,0,2.339869957,0,0,0,90.00000001 +131.55,50.40855088,-3.580804962,50,0,2.330317654,0,0,0,90.00000001 +131.56,50.40855088,-3.580804634,50,0,2.319876765,0,0,0,90.00000001 +131.57,50.40855088,-3.580804309,50,0,2.308991582,0,0,0,90.00000001 +131.58,50.40855088,-3.580803985,50,0,2.298994986,0,0,0,90.00000001 +131.59,50.40855088,-3.580803662,50,0,2.289886976,0,0,0,90.00000001 +131.6,50.40855088,-3.580803341,50,0,2.28055682,0,0,0,90.00000001 +131.61,50.40855088,-3.58080302,50,0,2.27011593,0,0,0,90.00000001 +131.62,50.40855088,-3.580802702,50,0,2.259230747,0,0,0,90.00000001 +131.63,50.40855088,-3.580802385,50,0,2.249012005,0,0,0,90.00000001 +131.64,50.40855088,-3.580802069,50,0,2.239237556,0,0,0,90.00000001 +131.65,50.40855088,-3.580801755,50,0,2.229685253,0,0,0,90.00000001 +131.66,50.40855088,-3.580801442,50,0,2.220355096,0,0,0,90.00000001 +131.67,50.40855088,-3.58080113,50,0,2.210580646,0,0,0,90.00000001 +131.68,50.40855088,-3.58080082,50,0,2.200139757,0,0,0,90.00000001 +131.69,50.40855088,-3.580800511,50,0,2.189476721,0,0,0,90.00000001 +131.7,50.40855088,-3.580800204,50,0,2.178813684,0,0,0,90.00000001 +131.71,50.40855088,-3.580799898,50,0,2.168150648,0,0,0,90.00000001 +131.72,50.40855088,-3.580799594,50,0,2.157709759,0,0,0,90.00000001 +131.73,50.40855088,-3.580799291,50,0,2.148157457,0,0,0,90.00000001 +131.74,50.40855088,-3.58079899,50,0,2.13949374,0,0,0,90.00000001 +131.75,50.40855088,-3.580798689,50,0,2.130163583,0,0,0,90.00000001 +131.76,50.40855088,-3.58079839,50,0,2.119500548,0,0,0,90.00000001 +131.77,50.40855088,-3.580798093,50,0,2.109059658,0,0,0,90.00000001 +131.78,50.40855088,-3.580797797,50,0,2.099507354,0,0,0,90.00000001 +131.79,50.40855088,-3.580797502,50,0,2.089732904,0,0,0,90.00000001 +131.8,50.40855088,-3.580797209,50,0,2.079292016,0,0,0,90.00000001 +131.81,50.40855088,-3.580796917,50,0,2.068851127,0,0,0,90.00000001 +131.82,50.40855088,-3.580796627,50,0,2.059076676,0,0,0,90.00000001 +131.83,50.40855088,-3.580796338,50,0,2.049524373,0,0,0,90.00000001 +131.84,50.40855088,-3.58079605,50,0,2.039083484,0,0,0,90.00000001 +131.85,50.40855088,-3.580795764,50,0,2.028420448,0,0,0,90.00000001 +131.86,50.40855088,-3.58079548,50,0,2.018868145,0,0,0,90.00000001 +131.87,50.40855088,-3.580795196,50,0,2.009315842,0,0,0,90.00000001 +131.88,50.40855088,-3.580794914,50,0,1.998652805,0,0,0,90.00000001 +131.89,50.40855088,-3.580794634,50,0,1.988211916,0,0,0,90.00000001 +131.9,50.40855088,-3.580794355,50,0,1.978659614,0,0,0,90.00000001 +131.91,50.40855088,-3.580794077,50,0,1.968885164,0,0,0,90.00000001 +131.92,50.40855088,-3.580793801,50,0,1.958666422,0,0,0,90.00000001 +131.93,50.40855088,-3.580793526,50,0,1.948891972,0,0,0,90.00000001 +131.94,50.40855088,-3.580793253,50,0,1.939339668,0,0,0,90.00000001 +131.95,50.40855088,-3.58079298,50,0,1.928898779,0,0,0,90.00000001 +131.96,50.40855088,-3.58079271,50,0,1.918235743,0,0,0,90.00000001 +131.97,50.40855088,-3.580792441,50,0,1.908905587,0,0,0,90.00000001 +131.98,50.40855088,-3.580792173,50,0,1.900019724,0,0,0,90.00000001 +131.99,50.40855088,-3.580791906,50,0,1.889800981,0,0,0,90.00000001 +132,50.40855088,-3.580791641,50,0,1.878915798,0,0,0,90.00000001 +132.01,50.40855088,-3.580791378,50,0,1.868697054,0,0,0,90.00000001 +132.02,50.40855088,-3.580791115,50,0,1.858922605,0,0,0,90.00000001 +132.03,50.40855088,-3.580790855,50,0,1.849148156,0,0,0,90.00000001 +132.04,50.40855088,-3.580790595,50,0,1.838929413,0,0,0,90.00000001 +132.05,50.40855088,-3.580790337,50,0,1.82804423,0,0,0,90.00000001 +132.06,50.40855088,-3.580790081,50,0,1.81760334,0,0,0,90.00000001 +132.07,50.40855088,-3.580789826,50,0,1.808051037,0,0,0,90.00000001 +132.08,50.40855088,-3.580789572,50,0,1.798276588,0,0,0,90.00000001 +132.09,50.40855088,-3.58078932,50,0,1.788057845,0,0,0,90.00000001 +132.1,50.40855088,-3.580789069,50,0,1.778283396,0,0,0,90.00000001 +132.11,50.40855088,-3.58078882,50,0,1.76895324,0,0,0,90.00000001 +132.12,50.40855088,-3.580788571,50,0,1.75917879,0,0,0,90.00000001 +132.13,50.40855088,-3.580788325,50,0,1.7487379,0,0,0,90.00000001 +132.14,50.40855088,-3.580788079,50,0,1.738297011,0,0,0,90.00000001 +132.15,50.40855088,-3.580787836,50,0,1.728300415,0,0,0,90.00000001 +132.16,50.40855088,-3.580787593,50,0,1.718303818,0,0,0,90.00000001 +132.17,50.40855088,-3.580787352,50,0,1.708307221,0,0,0,90.00000001 +132.18,50.40855088,-3.580787113,50,0,1.698977065,0,0,0,90.00000001 +132.19,50.40855088,-3.580786874,50,0,1.689424762,0,0,0,90.00000001 +132.2,50.40855088,-3.580786637,50,0,1.678761727,0,0,0,90.00000001 +132.21,50.40855088,-3.580786402,50,0,1.668320838,0,0,0,90.00000001 +132.22,50.40855088,-3.580786168,50,0,1.658546388,0,0,0,90.00000001 +132.23,50.40855088,-3.580785935,50,0,1.648105498,0,0,0,90.00000001 +132.24,50.40855088,-3.580785704,50,0,1.637442462,0,0,0,90.00000001 +132.25,50.40855088,-3.580785475,50,0,1.62789016,0,0,0,90.00000001 +132.26,50.40855088,-3.580785246,50,0,1.618560003,0,0,0,90.00000001 +132.27,50.40855088,-3.580785019,50,0,1.608563407,0,0,0,90.00000001 +132.28,50.40855088,-3.580784794,50,0,1.598344664,0,0,0,90.00000001 +132.29,50.40855088,-3.580784569,50,0,1.587681627,0,0,0,90.00000001 +132.3,50.40855088,-3.580784347,50,0,1.577018591,0,0,0,90.00000001 +132.31,50.40855088,-3.580784126,50,0,1.567688435,0,0,0,90.00000001 +132.32,50.40855088,-3.580783906,50,0,1.559024719,0,0,0,90.00000001 +132.33,50.40855088,-3.580783687,50,0,1.549472415,0,0,0,90.00000001 +132.34,50.40855088,-3.58078347,50,0,1.538809379,0,0,0,90.00000001 +132.35,50.40855088,-3.580783254,50,0,1.527479904,0,0,0,90.00000001 +132.36,50.40855088,-3.58078304,50,0,1.516594721,0,0,0,90.00000001 +132.37,50.40855088,-3.580782828,50,0,1.507264565,0,0,0,90.00000001 +132.38,50.40855088,-3.580782616,50,0,1.498600848,0,0,0,90.00000001 +132.39,50.40855088,-3.580782406,50,0,1.489048545,0,0,0,90.00000001 +132.4,50.40855088,-3.580782197,50,0,1.478607655,0,0,0,90.00000001 +132.41,50.40855088,-3.58078199,50,0,1.467944619,0,0,0,90.00000001 +132.42,50.40855088,-3.580781784,50,0,1.45750373,0,0,0,90.00000001 +132.43,50.40855088,-3.58078158,50,0,1.44772928,0,0,0,90.00000001 +132.44,50.40855088,-3.580781377,50,0,1.438399124,0,0,0,90.00000001 +132.45,50.40855088,-3.580781175,50,0,1.428624674,0,0,0,90.00000001 +132.46,50.40855088,-3.580780975,50,0,1.418183785,0,0,0,90.00000001 +132.47,50.40855088,-3.580780776,50,0,1.407520749,0,0,0,90.00000001 +132.48,50.40855088,-3.580780579,50,0,1.39707986,0,0,0,90.00000001 +132.49,50.40855088,-3.580780383,50,0,1.38730541,0,0,0,90.00000001 +132.5,50.40855088,-3.580780189,50,0,1.377753107,0,0,0,90.00000001 +132.51,50.40855088,-3.580779995,50,0,1.367312218,0,0,0,90.00000001 +132.52,50.40855088,-3.580779804,50,0,1.356649182,0,0,0,90.00000001 +132.53,50.40855088,-3.580779614,50,0,1.347319025,0,0,0,90.00000001 +132.54,50.40855088,-3.580779425,50,0,1.338433162,0,0,0,90.00000001 +132.55,50.40855088,-3.580779237,50,0,1.328214419,0,0,0,90.00000001 +132.56,50.40855088,-3.580779051,50,0,1.317329236,0,0,0,90.00000001 +132.57,50.40855088,-3.580778867,50,0,1.307110493,0,0,0,90.00000001 +132.58,50.40855088,-3.580778683,50,0,1.297336044,0,0,0,90.00000001 +132.59,50.40855088,-3.580778502,50,0,1.287783741,0,0,0,90.00000001 +132.6,50.40855088,-3.580778321,50,0,1.278453584,0,0,0,90.00000001 +132.61,50.40855088,-3.580778142,50,0,1.268456988,0,0,0,90.00000001 +132.62,50.40855088,-3.580777964,50,0,1.257349659,0,0,0,90.00000001 +132.63,50.40855088,-3.580777788,50,0,1.246464477,0,0,0,90.00000001 +132.64,50.40855088,-3.580777614,50,0,1.23713432,0,0,0,90.00000001 +132.65,50.40855088,-3.58077744,50,0,1.228470603,0,0,0,90.00000001 +132.66,50.40855088,-3.580777268,50,0,1.218696153,0,0,0,90.00000001 +132.67,50.40855088,-3.580777097,50,0,1.207588824,0,0,0,90.00000001 +132.68,50.40855088,-3.580776928,50,0,1.196703642,0,0,0,90.00000001 +132.69,50.40855088,-3.580776761,50,0,1.187151339,0,0,0,90.00000001 +132.7,50.40855088,-3.580776594,50,0,1.177599036,0,0,0,90.00000001 +132.71,50.40855088,-3.580776429,50,0,1.166936,0,0,0,90.00000001 +132.72,50.40855088,-3.580776266,50,0,1.156495111,0,0,0,90.00000001 +132.73,50.40855088,-3.580776104,50,0,1.146942807,0,0,0,90.00000001 +132.74,50.40855088,-3.580775943,50,0,1.137168357,0,0,0,90.00000001 +132.75,50.40855088,-3.580775784,50,0,1.126949615,0,0,0,90.00000001 +132.76,50.40855088,-3.580775626,50,0,1.117175166,0,0,0,90.00000001 +132.77,50.40855088,-3.58077547,50,0,1.107845009,0,0,0,90.00000001 +132.78,50.40855088,-3.580775314,50,0,1.098070559,0,0,0,90.00000001 +132.79,50.40855088,-3.580775161,50,0,1.08762967,0,0,0,90.00000001 +132.8,50.40855088,-3.580775008,50,0,1.077188781,0,0,0,90.00000001 +132.81,50.40855088,-3.580774858,50,0,1.067192184,0,0,0,90.00000001 +132.82,50.40855088,-3.580774708,50,0,1.05697344,0,0,0,90.00000001 +132.83,50.40855088,-3.58077456,50,0,1.046088258,0,0,0,90.00000001 +132.84,50.40855088,-3.580774414,50,0,1.035869516,0,0,0,90.00000001 +132.85,50.40855088,-3.580774269,50,0,1.027205799,0,0,0,90.00000001 +132.86,50.40855088,-3.580774125,50,0,1.018542082,0,0,0,90.00000001 +132.87,50.40855088,-3.580773982,50,0,1.008101193,0,0,0,90.00000001 +132.88,50.40855088,-3.580773841,50,0,0.996549571,0,0,0,90.00000001 +132.89,50.40855088,-3.580773702,50,0,0.985886535,0,0,0,90.00000001 +132.9,50.40855088,-3.580773564,50,0,0.976334232,0,0,0,90.00000001 +132.91,50.40855088,-3.580773427,50,0,0.966781929,0,0,0,90.00000001 +132.92,50.40855088,-3.580773292,50,0,0.957229625,0,0,0,90.00000001 +132.93,50.40855088,-3.580773158,50,0,0.947677322,0,0,0,90.00000001 +132.94,50.40855088,-3.580773025,50,0,0.937236433,0,0,0,90.00000001 +132.95,50.40855088,-3.580772894,50,0,0.926351251,0,0,0,90.00000001 +132.96,50.40855088,-3.580772765,50,0,0.916132508,0,0,0,90.00000001 +132.97,50.40855088,-3.580772636,50,0,0.906358058,0,0,0,90.00000001 +132.98,50.40855088,-3.58077251,50,0,0.896805755,0,0,0,90.00000001 +132.99,50.40855088,-3.580772384,50,0,0.887475599,0,0,0,90.00000001 +133,50.40855088,-3.58077226,50,0,0.877701149,0,0,0,90.00000001 +133.01,50.40855088,-3.580772137,50,0,0.867260259,0,0,0,90.00000001 +133.02,50.40855088,-3.580772016,50,0,0.856597223,0,0,0,90.00000001 +133.03,50.40855088,-3.580771896,50,0,0.846156334,0,0,0,90.00000001 +133.04,50.40855088,-3.580771778,50,0,0.836381884,0,0,0,90.00000001 +133.05,50.40855088,-3.580771661,50,0,0.826829581,0,0,0,90.00000001 +133.06,50.40855088,-3.580771545,50,0,0.816388692,0,0,0,90.00000001 +133.07,50.40855088,-3.580771431,50,0,0.805725656,0,0,0,90.00000001 +133.08,50.40855088,-3.580771319,50,0,0.796173353,0,0,0,90.00000001 +133.09,50.40855088,-3.580771207,50,0,0.786843197,0,0,0,90.00000001 +133.1,50.40855088,-3.580771097,50,0,0.776846601,0,0,0,90.00000001 +133.11,50.40855088,-3.580770989,50,0,0.766627858,0,0,0,90.00000001 +133.12,50.40855088,-3.580770881,50,0,0.755964821,0,0,0,90.00000001 +133.13,50.40855088,-3.580770776,50,0,0.745301785,0,0,0,90.00000001 +133.14,50.40855088,-3.580770672,50,0,0.735971629,0,0,0,90.00000001 +133.15,50.40855088,-3.580770569,50,0,0.727307913,0,0,0,90.00000001 +133.16,50.40855088,-3.580770467,50,0,0.717755609,0,0,0,90.00000001 +133.17,50.40855088,-3.580770367,50,0,0.707314719,0,0,0,90.00000001 +133.18,50.40855088,-3.580770268,50,0,0.696651683,0,0,0,90.00000001 +133.19,50.40855088,-3.580770171,50,0,0.685988648,0,0,0,90.00000001 +133.2,50.40855088,-3.580770075,50,0,0.675547759,0,0,0,90.00000001 +133.21,50.40855088,-3.580769981,50,0,0.66577331,0,0,0,90.00000001 +133.22,50.40855088,-3.580769888,50,0,0.656443153,0,0,0,90.00000001 +133.23,50.40855088,-3.580769796,50,0,0.646668703,0,0,0,90.00000001 +133.24,50.40855088,-3.580769706,50,0,0.636227813,0,0,0,90.00000001 +133.25,50.40855088,-3.580769617,50,0,0.625786924,0,0,0,90.00000001 +133.26,50.40855088,-3.58076953,50,0,0.616012474,0,0,0,90.00000001 +133.27,50.40855088,-3.580769444,50,0,0.606682318,0,0,0,90.00000001 +133.28,50.40855088,-3.580769359,50,0,0.596907868,0,0,0,90.00000001 +133.29,50.40855088,-3.580769276,50,0,0.586466978,0,0,0,90.00000001 +133.3,50.40855088,-3.580769194,50,0,0.576026089,0,0,0,90.00000001 +133.31,50.40855088,-3.580769114,50,0,0.566251639,0,0,0,90.00000001 +133.32,50.40855088,-3.580769035,50,0,0.556699337,0,0,0,90.00000001 +133.33,50.40855088,-3.580768957,50,0,0.546258447,0,0,0,90.00000001 +133.34,50.40855088,-3.580768881,50,0,0.535595412,0,0,0,90.00000001 +133.35,50.40855088,-3.580768807,50,0,0.526043108,0,0,0,90.00000001 +133.36,50.40855088,-3.580768733,50,0,0.516490805,0,0,0,90.00000001 +133.37,50.40855088,-3.580768661,50,0,0.505827769,0,0,0,90.00000001 +133.38,50.40855088,-3.580768591,50,0,0.49538688,0,0,0,90.00000001 +133.39,50.40855088,-3.580768522,50,0,0.485834576,0,0,0,90.00000001 +133.4,50.40855088,-3.580768454,50,0,0.476060127,0,0,0,90.00000001 +133.41,50.40855088,-3.580768388,50,0,0.465619238,0,0,0,90.00000001 +133.42,50.40855088,-3.580768323,50,0,0.455178349,0,0,0,90.00000001 +133.43,50.40855088,-3.58076826,50,0,0.445403899,0,0,0,90.00000001 +133.44,50.40855088,-3.580768198,50,0,0.436073742,0,0,0,90.00000001 +133.45,50.40855088,-3.580768137,50,0,0.426299293,0,0,0,90.00000001 +133.46,50.40855088,-3.580768078,50,0,0.415858404,0,0,0,90.00000001 +133.47,50.40855088,-3.58076802,50,0,0.405417514,0,0,0,90.00000001 +133.48,50.40855088,-3.580767964,50,0,0.395643064,0,0,0,90.00000001 +133.49,50.40855088,-3.580767909,50,0,0.386312907,0,0,0,90.00000001 +133.5,50.40855088,-3.580767855,50,0,0.376538458,0,0,0,90.00000001 +133.51,50.40855088,-3.580767803,50,0,0.366097569,0,0,0,90.00000001 +133.52,50.40855088,-3.580767752,50,0,0.355434533,0,0,0,90.00000001 +133.53,50.40855088,-3.580767703,50,0,0.344993643,0,0,0,90.00000001 +133.54,50.40855088,-3.580767655,50,0,0.335219193,0,0,0,90.00000001 +133.55,50.40855088,-3.580767609,50,0,0.325889037,0,0,0,90.00000001 +133.56,50.40855088,-3.580767563,50,0,0.316114587,0,0,0,90.00000001 +133.57,50.40855088,-3.58076752,50,0,0.305673698,0,0,0,90.00000001 +133.58,50.40855088,-3.580767477,50,0,0.295232809,0,0,0,90.00000001 +133.59,50.40855088,-3.580767437,50,0,0.285458359,0,0,0,90.00000001 +133.6,50.40855088,-3.580767397,50,0,0.276128203,0,0,0,90.00000001 +133.61,50.40855088,-3.580767359,50,0,0.266353753,0,0,0,90.00000001 +133.62,50.40855088,-3.580767322,50,0,0.255912864,0,0,0,90.00000001 +133.63,50.40855088,-3.580767287,50,0,0.245249828,0,0,0,90.00000001 +133.64,50.40855088,-3.580767253,50,0,0.234808938,0,0,0,90.00000001 +133.65,50.40855088,-3.580767221,50,0,0.225034488,0,0,0,90.00000001 +133.66,50.40855088,-3.58076719,50,0,0.215482185,0,0,0,90.00000001 +133.67,50.40855088,-3.58076716,50,0,0.205041296,0,0,0,90.00000001 +133.68,50.40855088,-3.580767132,50,0,0.19437826,0,0,0,90.00000001 +133.69,50.40855088,-3.580767106,50,0,0.185048104,0,0,0,90.00000001 +133.7,50.40855088,-3.58076708,50,0,0.176384387,0,0,0,90.00000001 +133.71,50.40855088,-3.580767056,50,0,0.166609938,0,0,0,90.00000001 +133.72,50.40855088,-3.580767033,50,0,0.155502608,0,0,0,90.00000001 +133.73,50.40855088,-3.580767012,50,0,0.144617425,0,0,0,90.00000001 +133.74,50.40855088,-3.580766993,50,0,0.135065122,0,0,0,90.00000001 +133.75,50.40855088,-3.580766974,50,0,0.125512819,0,0,0,90.00000001 +133.76,50.40855088,-3.580766957,50,0,0.114849783,0,0,0,90.00000001 +133.77,50.40855088,-3.580766942,50,0,0.104408894,0,0,0,90.00000001 +133.78,50.40855088,-3.580766928,50,0,0.094856591,0,0,0,90.00000001 +133.79,50.40855088,-3.580766915,50,0,0.085082141,0,0,0,90.00000001 +133.8,50.40855088,-3.580766904,50,0,0.074863398,0,0,0,90.00000001 +133.81,50.40855088,-3.580766894,50,0,0.065088948,0,0,0,90.00000001 +133.82,50.40855088,-3.580766886,50,0,0.055758792,0,0,0,90.00000001 +133.83,50.40855088,-3.580766878,50,0,0.045984343,0,0,0,90.00000001 +133.84,50.40855088,-3.580766873,50,0,0.035543453,0,0,0,90.00000001 +133.85,50.40855088,-3.580766868,50,0,0.025102564,0,0,0,90.00000001 +133.86,50.40855088,-3.580766866,50,0,0.01555026,0,0,0,90.00000001 +133.87,50.40855088,-3.580766864,50,0,0.00777513,0,0,0,90.00000001 +133.88,50.40855088,-3.580766864,50,0,0.002665759,0,0,0,90.00000001 +133.89,50.40855088,-3.580766864,50,0,0.000444293,0,0,0,90.00000001 +133.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +133.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +133.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +133.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +133.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +133.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +133.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +133.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +133.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +133.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +134.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +135.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +136.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +137.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +138.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +139.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +140.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +141.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +142.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +143.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +144.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +145.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +146.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +147.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +148.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +149.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +150.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +151.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +152.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +153.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +154.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +155.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +156.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +157.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +158.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +159.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +160.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +161.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +162.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +163.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +164.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +165.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +166.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +167.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +168.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +169.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +170.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +171.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +172.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +173.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.01,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.02,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.03,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.04,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.05,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.06,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.07,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.08,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.09,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.1,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.11,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.12,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.13,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.14,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.15,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.16,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.17,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.18,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.19,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.2,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.21,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.22,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.23,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.24,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.25,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.26,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.27,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.28,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.29,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.3,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.31,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.32,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.33,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.34,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.35,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.36,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.37,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.38,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.39,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.4,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.41,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.42,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.43,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.44,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.45,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.46,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.47,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.48,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.49,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.5,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.51,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.52,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.53,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.54,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.55,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.56,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.57,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.58,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.59,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.6,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.61,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.62,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.63,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.64,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.65,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.66,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.67,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.68,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.69,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.7,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.71,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.72,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.73,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.74,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.75,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.76,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.77,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.78,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.79,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.8,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.81,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.82,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.83,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.84,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.85,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.86,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.87,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.88,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.89,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.9,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.91,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.92,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.93,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.94,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.95,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.96,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.97,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.98,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +174.99,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 +175,50.40855088,-3.580766864,50,0,0,0,0,0,90.00000001 diff --git a/Profile_3.csv b/Profile_3.csv new file mode 100644 index 0000000..f27381c --- /dev/null +++ b/Profile_3.csv @@ -0,0 +1,41801 @@ +0,50.425,-3.5958333,10000,0,200,0,0,0,90.00000001 +0.01,50.425,-3.595805199,10000,0,199.998794,0,0,0,90.00000001 +0.02,50.425,-3.595777099,10000,0,199.9984134,0,0,0,90.00000001 +0.03,50.425,-3.595748999,10000,0,199.9997163,0,0,0,90.00000001 +0.04,50.425,-3.595720898,10000,0,200.0014956,0,0,0,90.00000001 +0.05,50.425,-3.595692797,10000,0,200.0014956,0,0,0,90.00000001 +0.06,50.425,-3.595664696,10000,0,199.9997163,0,0,0,90.00000001 +0.07,50.425,-3.595636596,10000,0,199.9986042,0,0,0,90.00000001 +0.08,50.425,-3.595608496,10000,0,199.9994939,0,0,0,90.00000001 +0.09,50.425,-3.595580395,10000,0,200.000606,0,0,0,90.00000001 +0.1,50.425,-3.595552294,10000,0,200.0003835,0,0,0,90.00000001 +0.11,50.425,-3.595524194,10000,0,199.9997163,0,0,0,90.00000001 +0.12,50.425,-3.595496093,10000,0,199.9994939,0,0,0,90.00000001 +0.13,50.425,-3.595467993,10000,0,199.9994939,0,0,0,90.00000001 +0.14,50.425,-3.595439892,10000,0,199.9997163,0,0,0,90.00000001 +0.15,50.425,-3.595411792,10000,0,200.0003835,0,0,0,90.00000001 +0.16,50.425,-3.595383691,10000,0,200.0008284,0,0,0,90.00000001 +0.17,50.425,-3.59535559,10000,0,200.0003835,0,0,0,90.00000001 +0.18,50.425,-3.59532749,10000,0,199.9997163,0,0,0,90.00000001 +0.19,50.425,-3.595299389,10000,0,199.9997163,0,0,0,90.00000001 +0.2,50.425,-3.595271289,10000,0,200.0003835,0,0,0,90.00000001 +0.21,50.425,-3.595243188,10000,0,200.0008284,0,0,0,90.00000001 +0.22,50.425,-3.595215087,10000,0,200.0003835,0,0,0,90.00000001 +0.23,50.425,-3.595186987,10000,0,199.9997163,0,0,0,90.00000001 +0.24,50.425,-3.595158886,10000,0,199.9994939,0,0,0,90.00000001 +0.25,50.425,-3.595130786,10000,0,199.9994939,0,0,0,90.00000001 +0.26,50.425,-3.595102685,10000,0,199.9997163,0,0,0,90.00000001 +0.27,50.425,-3.595074585,10000,0,200.0003835,0,0,0,90.00000001 +0.28,50.425,-3.595046484,10000,0,200.000606,0,0,0,90.00000001 +0.29,50.425,-3.595018383,10000,0,199.9994939,0,0,0,90.00000001 +0.3,50.425,-3.594990283,10000,0,199.9986042,0,0,0,90.00000001 +0.31,50.425,-3.594962183,10000,0,199.9997163,0,0,0,90.00000001 +0.32,50.425,-3.594934082,10000,0,200.0014956,0,0,0,90.00000001 +0.33,50.425,-3.594905981,10000,0,200.0014956,0,0,0,90.00000001 +0.34,50.425,-3.59487788,10000,0,199.9997163,0,0,0,90.00000001 +0.35,50.425,-3.59484978,10000,0,199.9986042,0,0,0,90.00000001 +0.36,50.425,-3.59482168,10000,0,199.9994939,0,0,0,90.00000001 +0.37,50.425,-3.594793579,10000,0,200.000606,0,0,0,90.00000001 +0.38,50.425,-3.594765478,10000,0,200.0003835,0,0,0,90.00000001 +0.39,50.425,-3.594737378,10000,0,199.9997163,0,0,0,90.00000001 +0.4,50.425,-3.594709277,10000,0,199.9994939,0,0,0,90.00000001 +0.41,50.425,-3.594681177,10000,0,199.9994939,0,0,0,90.00000001 +0.42,50.425,-3.594653076,10000,0,199.9997163,0,0,0,90.00000001 +0.43,50.425,-3.594624976,10000,0,200.0003835,0,0,0,90.00000001 +0.44,50.425,-3.594596875,10000,0,200.0008284,0,0,0,90.00000001 +0.45,50.425,-3.594568774,10000,0,200.0003835,0,0,0,90.00000001 +0.46,50.425,-3.594540674,10000,0,199.9997163,0,0,0,90.00000001 +0.47,50.425,-3.594512573,10000,0,199.9997163,0,0,0,90.00000001 +0.48,50.425,-3.594484473,10000,0,200.0003835,0,0,0,90.00000001 +0.49,50.425,-3.594456372,10000,0,200.0008284,0,0,0,90.00000001 +0.5,50.425,-3.594428271,10000,0,200.0003835,0,0,0,90.00000001 +0.51,50.425,-3.594400171,10000,0,199.9997163,0,0,0,90.00000001 +0.52,50.425,-3.59437207,10000,0,199.9994939,0,0,0,90.00000001 +0.53,50.425,-3.59434397,10000,0,199.9994939,0,0,0,90.00000001 +0.54,50.425,-3.594315869,10000,0,199.9997163,0,0,0,90.00000001 +0.55,50.425,-3.594287769,10000,0,200.0003835,0,0,0,90.00000001 +0.56,50.425,-3.594259668,10000,0,200.000606,0,0,0,90.00000001 +0.57,50.425,-3.594231567,10000,0,199.9994939,0,0,0,90.00000001 +0.58,50.425,-3.594203467,10000,0,199.9986042,0,0,0,90.00000001 +0.59,50.425,-3.594175367,10000,0,199.9997163,0,0,0,90.00000001 +0.6,50.425,-3.594147266,10000,0,200.0014956,0,0,0,90.00000001 +0.61,50.425,-3.594119165,10000,0,200.0014956,0,0,0,90.00000001 +0.62,50.425,-3.594091064,10000,0,199.9997163,0,0,0,90.00000001 +0.63,50.425,-3.594062964,10000,0,199.9986042,0,0,0,90.00000001 +0.64,50.425,-3.594034864,10000,0,199.9994939,0,0,0,90.00000001 +0.65,50.425,-3.594006763,10000,0,200.000606,0,0,0,90.00000001 +0.66,50.425,-3.593978662,10000,0,200.0003835,0,0,0,90.00000001 +0.67,50.425,-3.593950562,10000,0,199.9997163,0,0,0,90.00000001 +0.68,50.425,-3.593922461,10000,0,199.9994939,0,0,0,90.00000001 +0.69,50.425,-3.593894361,10000,0,199.9994939,0,0,0,90.00000001 +0.7,50.425,-3.59386626,10000,0,199.9997163,0,0,0,90.00000001 +0.71,50.425,-3.59383816,10000,0,200.0003835,0,0,0,90.00000001 +0.72,50.425,-3.593810059,10000,0,200.0008284,0,0,0,90.00000001 +0.73,50.425,-3.593781958,10000,0,200.0003835,0,0,0,90.00000001 +0.74,50.425,-3.593753858,10000,0,199.9997163,0,0,0,90.00000001 +0.75,50.425,-3.593725757,10000,0,199.9997163,0,0,0,90.00000001 +0.76,50.425,-3.593697657,10000,0,200.0003835,0,0,0,90.00000001 +0.77,50.425,-3.593669556,10000,0,200.0008284,0,0,0,90.00000001 +0.78,50.425,-3.593641455,10000,0,200.0003835,0,0,0,90.00000001 +0.79,50.425,-3.593613355,10000,0,199.9997163,0,0,0,90.00000001 +0.8,50.425,-3.593585254,10000,0,199.9994939,0,0,0,90.00000001 +0.81,50.425,-3.593557154,10000,0,199.9994939,0,0,0,90.00000001 +0.82,50.425,-3.593529053,10000,0,199.9997163,0,0,0,90.00000001 +0.83,50.425,-3.593500953,10000,0,200.0003835,0,0,0,90.00000001 +0.84,50.425,-3.593472852,10000,0,200.000606,0,0,0,90.00000001 +0.85,50.425,-3.593444751,10000,0,199.9994939,0,0,0,90.00000001 +0.86,50.425,-3.593416651,10000,0,199.9986042,0,0,0,90.00000001 +0.87,50.425,-3.593388551,10000,0,199.9997163,0,0,0,90.00000001 +0.88,50.425,-3.59336045,10000,0,200.0014956,0,0,0,90.00000001 +0.89,50.425,-3.593332349,10000,0,200.0014956,0,0,0,90.00000001 +0.9,50.425,-3.593304248,10000,0,199.9997163,0,0,0,90.00000001 +0.91,50.425,-3.593276148,10000,0,199.9986042,0,0,0,90.00000001 +0.92,50.425,-3.593248048,10000,0,199.9994939,0,0,0,90.00000001 +0.93,50.425,-3.593219947,10000,0,200.000606,0,0,0,90.00000001 +0.94,50.425,-3.593191846,10000,0,200.0003835,0,0,0,90.00000001 +0.95,50.425,-3.593163746,10000,0,199.9997163,0,0,0,90.00000001 +0.96,50.425,-3.593135645,10000,0,199.9994939,0,0,0,90.00000001 +0.97,50.425,-3.593107545,10000,0,199.9994939,0,0,0,90.00000001 +0.98,50.425,-3.593079444,10000,0,199.9997163,0,0,0,90.00000001 +0.99,50.425,-3.593051344,10000,0,200.0003835,0,0,0,90.00000001 +1,50.425,-3.593023243,10000,0,200.0008284,0,0,0,90.00000001 +1.01,50.425,-3.592995142,10000,0,200.0003835,0,0,0,90.00000001 +1.02,50.425,-3.592967042,10000,0,199.9997163,0,0,0,90.00000001 +1.03,50.425,-3.592938941,10000,0,199.9997163,0,0,0,90.00000001 +1.04,50.425,-3.592910841,10000,0,200.0003835,0,0,0,90.00000001 +1.05,50.425,-3.59288274,10000,0,200.0008284,0,0,0,90.00000001 +1.06,50.425,-3.592854639,10000,0,200.0003835,0,0,0,90.00000001 +1.07,50.425,-3.592826539,10000,0,199.9997163,0,0,0,90.00000001 +1.08,50.425,-3.592798438,10000,0,199.9994939,0,0,0,90.00000001 +1.09,50.425,-3.592770338,10000,0,199.9994939,0,0,0,90.00000001 +1.1,50.425,-3.592742237,10000,0,199.9997163,0,0,0,90.00000001 +1.11,50.425,-3.592714137,10000,0,200.0003835,0,0,0,90.00000001 +1.12,50.425,-3.592686036,10000,0,200.000606,0,0,0,90.00000001 +1.13,50.425,-3.592657935,10000,0,199.9994939,0,0,0,90.00000001 +1.14,50.425,-3.592629835,10000,0,199.9986042,0,0,0,90.00000001 +1.15,50.425,-3.592601735,10000,0,199.9997163,0,0,0,90.00000001 +1.16,50.425,-3.592573634,10000,0,200.0014956,0,0,0,90.00000001 +1.17,50.425,-3.592545533,10000,0,200.0014956,0,0,0,90.00000001 +1.18,50.425,-3.592517432,10000,0,199.9997163,0,0,0,90.00000001 +1.19,50.425,-3.592489332,10000,0,199.9986042,0,0,0,90.00000001 +1.2,50.425,-3.592461232,10000,0,199.9994939,0,0,0,90.00000001 +1.21,50.425,-3.592433131,10000,0,200.000606,0,0,0,90.00000001 +1.22,50.425,-3.59240503,10000,0,200.0003835,0,0,0,90.00000001 +1.23,50.425,-3.59237693,10000,0,199.9997163,0,0,0,90.00000001 +1.24,50.425,-3.592348829,10000,0,199.9994939,0,0,0,90.00000001 +1.25,50.425,-3.592320729,10000,0,199.9994939,0,0,0,90.00000001 +1.26,50.425,-3.592292628,10000,0,199.9997163,0,0,0,90.00000001 +1.27,50.425,-3.592264528,10000,0,200.000606,0,0,0,90.00000001 +1.28,50.425,-3.592236427,10000,0,200.001718,0,0,0,90.00000001 +1.29,50.425,-3.592208326,10000,0,200.0014956,0,0,0,90.00000001 +1.3,50.425,-3.592180225,10000,0,199.9997163,0,0,0,90.00000001 +1.31,50.425,-3.592152125,10000,0,199.9986042,0,0,0,90.00000001 +1.32,50.425,-3.592124025,10000,0,199.9994939,0,0,0,90.00000001 +1.33,50.425,-3.592095924,10000,0,200.000606,0,0,0,90.00000001 +1.34,50.425,-3.592067823,10000,0,200.0003835,0,0,0,90.00000001 +1.35,50.425,-3.592039723,10000,0,199.9997163,0,0,0,90.00000001 +1.36,50.425,-3.592011622,10000,0,199.9994939,0,0,0,90.00000001 +1.37,50.425,-3.591983522,10000,0,199.9994939,0,0,0,90.00000001 +1.38,50.425,-3.591955421,10000,0,199.9997163,0,0,0,90.00000001 +1.39,50.425,-3.591927321,10000,0,200.0003835,0,0,0,90.00000001 +1.4,50.425,-3.59189922,10000,0,200.0008284,0,0,0,90.00000001 +1.41,50.425,-3.591871119,10000,0,200.0003835,0,0,0,90.00000001 +1.42,50.425,-3.591843019,10000,0,199.9997163,0,0,0,90.00000001 +1.43,50.425,-3.591814918,10000,0,199.9997163,0,0,0,90.00000001 +1.44,50.425,-3.591786818,10000,0,200.0003835,0,0,0,90.00000001 +1.45,50.425,-3.591758717,10000,0,200.0008284,0,0,0,90.00000001 +1.46,50.425,-3.591730616,10000,0,200.0003835,0,0,0,90.00000001 +1.47,50.425,-3.591702516,10000,0,199.9997163,0,0,0,90.00000001 +1.48,50.425,-3.591674415,10000,0,199.9994939,0,0,0,90.00000001 +1.49,50.425,-3.591646315,10000,0,199.9994939,0,0,0,90.00000001 +1.5,50.425,-3.591618214,10000,0,199.9997163,0,0,0,90.00000001 +1.51,50.425,-3.591590114,10000,0,200.0003835,0,0,0,90.00000001 +1.52,50.425,-3.591562013,10000,0,200.000606,0,0,0,90.00000001 +1.53,50.425,-3.591533912,10000,0,199.9994939,0,0,0,90.00000001 +1.54,50.425,-3.591505812,10000,0,199.9986042,0,0,0,90.00000001 +1.55,50.425,-3.591477712,10000,0,199.9997163,0,0,0,90.00000001 +1.56,50.425,-3.591449611,10000,0,200.0014956,0,0,0,90.00000001 +1.57,50.425,-3.59142151,10000,0,200.0014956,0,0,0,90.00000001 +1.58,50.425,-3.591393409,10000,0,199.9997163,0,0,0,90.00000001 +1.59,50.425,-3.591365309,10000,0,199.9986042,0,0,0,90.00000001 +1.6,50.425,-3.591337209,10000,0,199.9994939,0,0,0,90.00000001 +1.61,50.425,-3.591309108,10000,0,200.000606,0,0,0,90.00000001 +1.62,50.425,-3.591281007,10000,0,200.0003835,0,0,0,90.00000001 +1.63,50.425,-3.591252907,10000,0,199.9997163,0,0,0,90.00000001 +1.64,50.425,-3.591224806,10000,0,199.9994939,0,0,0,90.00000001 +1.65,50.425,-3.591196706,10000,0,199.9994939,0,0,0,90.00000001 +1.66,50.425,-3.591168605,10000,0,199.9997163,0,0,0,90.00000001 +1.67,50.425,-3.591140505,10000,0,200.0003835,0,0,0,90.00000001 +1.68,50.425,-3.591112404,10000,0,200.0008284,0,0,0,90.00000001 +1.69,50.425,-3.591084303,10000,0,200.0003835,0,0,0,90.00000001 +1.7,50.425,-3.591056203,10000,0,199.9997163,0,0,0,90.00000001 +1.71,50.425,-3.591028102,10000,0,199.9994939,0,0,0,90.00000001 +1.72,50.425,-3.591000002,10000,0,199.9994939,0,0,0,90.00000001 +1.73,50.425,-3.590971901,10000,0,199.9997163,0,0,0,90.00000001 +1.74,50.425,-3.590943801,10000,0,200.0003835,0,0,0,90.00000001 +1.75,50.425,-3.5909157,10000,0,200.000606,0,0,0,90.00000001 +1.76,50.425,-3.590887599,10000,0,199.9994939,0,0,0,90.00000001 +1.77,50.425,-3.590859499,10000,0,199.9986042,0,0,0,90.00000001 +1.78,50.425,-3.590831399,10000,0,199.9997163,0,0,0,90.00000001 +1.79,50.425,-3.590803298,10000,0,200.0014956,0,0,0,90.00000001 +1.8,50.425,-3.590775197,10000,0,200.0014956,0,0,0,90.00000001 +1.81,50.425,-3.590747096,10000,0,199.9997163,0,0,0,90.00000001 +1.82,50.425,-3.590718996,10000,0,199.9986042,0,0,0,90.00000001 +1.83,50.425,-3.590690896,10000,0,199.9994939,0,0,0,90.00000001 +1.84,50.425,-3.590662795,10000,0,200.000606,0,0,0,90.00000001 +1.85,50.425,-3.590634694,10000,0,200.0003835,0,0,0,90.00000001 +1.86,50.425,-3.590606594,10000,0,199.9997163,0,0,0,90.00000001 +1.87,50.425,-3.590578493,10000,0,199.9994939,0,0,0,90.00000001 +1.88,50.425,-3.590550393,10000,0,199.9994939,0,0,0,90.00000001 +1.89,50.425,-3.590522292,10000,0,199.9997163,0,0,0,90.00000001 +1.9,50.425,-3.590494192,10000,0,200.0003835,0,0,0,90.00000001 +1.91,50.425,-3.590466091,10000,0,200.0008284,0,0,0,90.00000001 +1.92,50.425,-3.59043799,10000,0,200.0003835,0,0,0,90.00000001 +1.93,50.425,-3.59040989,10000,0,199.9997163,0,0,0,90.00000001 +1.94,50.425,-3.590381789,10000,0,199.9997163,0,0,0,90.00000001 +1.95,50.425,-3.590353689,10000,0,200.0003835,0,0,0,90.00000001 +1.96,50.425,-3.590325588,10000,0,200.0008284,0,0,0,90.00000001 +1.97,50.425,-3.590297487,10000,0,200.0003835,0,0,0,90.00000001 +1.98,50.425,-3.590269387,10000,0,199.9997163,0,0,0,90.00000001 +1.99,50.425,-3.590241286,10000,0,199.9994939,0,0,0,90.00000001 +2,50.425,-3.590213186,10000,0,199.9994939,0,0,0,90.00000001 +2.01,50.425,-3.590185085,10000,0,199.9997163,0,0,0,90.00000001 +2.02,50.425,-3.590156985,10000,0,200.0003835,0,0,0,90.00000001 +2.03,50.425,-3.590128884,10000,0,200.000606,0,0,0,90.00000001 +2.04,50.425,-3.590100783,10000,0,199.9994939,0,0,0,90.00000001 +2.05,50.425,-3.590072683,10000,0,199.9986042,0,0,0,90.00000001 +2.06,50.425,-3.590044583,10000,0,199.9997163,0,0,0,90.00000001 +2.07,50.425,-3.590016482,10000,0,200.0014956,0,0,0,90.00000001 +2.08,50.425,-3.589988381,10000,0,200.0014956,0,0,0,90.00000001 +2.09,50.425,-3.58996028,10000,0,199.9997163,0,0,0,90.00000001 +2.1,50.425,-3.58993218,10000,0,199.9986042,0,0,0,90.00000001 +2.11,50.425,-3.58990408,10000,0,199.9994939,0,0,0,90.00000001 +2.12,50.425,-3.589875979,10000,0,200.000606,0,0,0,90.00000001 +2.13,50.425,-3.589847878,10000,0,200.0003835,0,0,0,90.00000001 +2.14,50.425,-3.589819778,10000,0,199.9997163,0,0,0,90.00000001 +2.15,50.425,-3.589791677,10000,0,199.9994939,0,0,0,90.00000001 +2.16,50.425,-3.589763577,10000,0,199.9994939,0,0,0,90.00000001 +2.17,50.425,-3.589735476,10000,0,199.9997163,0,0,0,90.00000001 +2.18,50.425,-3.589707376,10000,0,200.0003835,0,0,0,90.00000001 +2.19,50.425,-3.589679275,10000,0,200.0008284,0,0,0,90.00000001 +2.2,50.425,-3.589651174,10000,0,200.0003835,0,0,0,90.00000001 +2.21,50.425,-3.589623074,10000,0,199.9997163,0,0,0,90.00000001 +2.22,50.425,-3.589594973,10000,0,199.9997163,0,0,0,90.00000001 +2.23,50.425,-3.589566873,10000,0,200.0003835,0,0,0,90.00000001 +2.24,50.425,-3.589538772,10000,0,200.0008284,0,0,0,90.00000001 +2.25,50.425,-3.589510671,10000,0,200.0003835,0,0,0,90.00000001 +2.26,50.425,-3.589482571,10000,0,199.9997163,0,0,0,90.00000001 +2.27,50.425,-3.58945447,10000,0,199.9994939,0,0,0,90.00000001 +2.28,50.425,-3.58942637,10000,0,199.9994939,0,0,0,90.00000001 +2.29,50.425,-3.589398269,10000,0,199.9997163,0,0,0,90.00000001 +2.3,50.425,-3.589370169,10000,0,200.0003835,0,0,0,90.00000001 +2.31,50.425,-3.589342068,10000,0,200.000606,0,0,0,90.00000001 +2.32,50.425,-3.589313967,10000,0,199.9994939,0,0,0,90.00000001 +2.33,50.425,-3.589285867,10000,0,199.9986042,0,0,0,90.00000001 +2.34,50.425,-3.589257767,10000,0,199.9997163,0,0,0,90.00000001 +2.35,50.425,-3.589229666,10000,0,200.0014956,0,0,0,90.00000001 +2.36,50.425,-3.589201565,10000,0,200.0014956,0,0,0,90.00000001 +2.37,50.425,-3.589173464,10000,0,199.9997163,0,0,0,90.00000001 +2.38,50.425,-3.589145364,10000,0,199.9986042,0,0,0,90.00000001 +2.39,50.425,-3.589117264,10000,0,199.9994939,0,0,0,90.00000001 +2.4,50.425,-3.589089163,10000,0,200.000606,0,0,0,90.00000001 +2.41,50.425,-3.589061062,10000,0,200.0003835,0,0,0,90.00000001 +2.42,50.425,-3.589032962,10000,0,199.9997163,0,0,0,90.00000001 +2.43,50.425,-3.589004861,10000,0,199.9994939,0,0,0,90.00000001 +2.44,50.425,-3.588976761,10000,0,199.9994939,0,0,0,90.00000001 +2.45,50.425,-3.58894866,10000,0,199.9997163,0,0,0,90.00000001 +2.46,50.425,-3.58892056,10000,0,200.0003835,0,0,0,90.00000001 +2.47,50.425,-3.588892459,10000,0,200.0008284,0,0,0,90.00000001 +2.48,50.425,-3.588864358,10000,0,200.0003835,0,0,0,90.00000001 +2.49,50.425,-3.588836258,10000,0,199.9997163,0,0,0,90.00000001 +2.5,50.425,-3.588808157,10000,0,199.9997163,0,0,0,90.00000001 +2.51,50.425,-3.588780057,10000,0,200.0003835,0,0,0,90.00000001 +2.52,50.425,-3.588751956,10000,0,200.0008284,0,0,0,90.00000001 +2.53,50.425,-3.588723855,10000,0,200.0003835,0,0,0,90.00000001 +2.54,50.425,-3.588695755,10000,0,199.9997163,0,0,0,90.00000001 +2.55,50.425,-3.588667654,10000,0,199.9994939,0,0,0,90.00000001 +2.56,50.425,-3.588639554,10000,0,199.9994939,0,0,0,90.00000001 +2.57,50.425,-3.588611453,10000,0,199.9997163,0,0,0,90.00000001 +2.58,50.425,-3.588583353,10000,0,200.0003835,0,0,0,90.00000001 +2.59,50.425,-3.588555252,10000,0,200.000606,0,0,0,90.00000001 +2.6,50.425,-3.588527151,10000,0,199.9994939,0,0,0,90.00000001 +2.61,50.425,-3.588499051,10000,0,199.9986042,0,0,0,90.00000001 +2.62,50.425,-3.588470951,10000,0,199.9997163,0,0,0,90.00000001 +2.63,50.425,-3.58844285,10000,0,200.0014956,0,0,0,90.00000001 +2.64,50.425,-3.588414749,10000,0,200.0014956,0,0,0,90.00000001 +2.65,50.425,-3.588386648,10000,0,199.9997163,0,0,0,90.00000001 +2.66,50.425,-3.588358548,10000,0,199.9986042,0,0,0,90.00000001 +2.67,50.425,-3.588330448,10000,0,199.9994939,0,0,0,90.00000001 +2.68,50.425,-3.588302347,10000,0,200.000606,0,0,0,90.00000001 +2.69,50.425,-3.588274246,10000,0,200.0003835,0,0,0,90.00000001 +2.7,50.425,-3.588246146,10000,0,199.9997163,0,0,0,90.00000001 +2.71,50.425,-3.588218045,10000,0,199.9994939,0,0,0,90.00000001 +2.72,50.425,-3.588189945,10000,0,199.9994939,0,0,0,90.00000001 +2.73,50.425,-3.588161844,10000,0,199.9997163,0,0,0,90.00000001 +2.74,50.425,-3.588133744,10000,0,200.0003835,0,0,0,90.00000001 +2.75,50.425,-3.588105643,10000,0,200.0008284,0,0,0,90.00000001 +2.76,50.425,-3.588077542,10000,0,200.0003835,0,0,0,90.00000001 +2.77,50.425,-3.588049442,10000,0,199.9997163,0,0,0,90.00000001 +2.78,50.425,-3.588021341,10000,0,199.9997163,0,0,0,90.00000001 +2.79,50.425,-3.587993241,10000,0,200.0003835,0,0,0,90.00000001 +2.8,50.425,-3.58796514,10000,0,200.0008284,0,0,0,90.00000001 +2.81,50.425,-3.587937039,10000,0,200.0003835,0,0,0,90.00000001 +2.82,50.425,-3.587908939,10000,0,199.9997163,0,0,0,90.00000001 +2.83,50.425,-3.587880838,10000,0,199.9994939,0,0,0,90.00000001 +2.84,50.425,-3.587852738,10000,0,199.9994939,0,0,0,90.00000001 +2.85,50.425,-3.587824637,10000,0,199.9997163,0,0,0,90.00000001 +2.86,50.425,-3.587796537,10000,0,200.0003835,0,0,0,90.00000001 +2.87,50.425,-3.587768436,10000,0,200.000606,0,0,0,90.00000001 +2.88,50.425,-3.587740335,10000,0,199.9994939,0,0,0,90.00000001 +2.89,50.425,-3.587712235,10000,0,199.9986042,0,0,0,90.00000001 +2.9,50.425,-3.587684135,10000,0,199.9997163,0,0,0,90.00000001 +2.91,50.425,-3.587656034,10000,0,200.0014956,0,0,0,90.00000001 +2.92,50.425,-3.587627933,10000,0,200.0014956,0,0,0,90.00000001 +2.93,50.425,-3.587599832,10000,0,199.9997163,0,0,0,90.00000001 +2.94,50.425,-3.587571732,10000,0,199.9986042,0,0,0,90.00000001 +2.95,50.425,-3.587543632,10000,0,199.9994939,0,0,0,90.00000001 +2.96,50.425,-3.587515531,10000,0,200.000606,0,0,0,90.00000001 +2.97,50.425,-3.58748743,10000,0,200.0003835,0,0,0,90.00000001 +2.98,50.425,-3.58745933,10000,0,199.9997163,0,0,0,90.00000001 +2.99,50.425,-3.587431229,10000,0,199.9994939,0,0,0,90.00000001 +3,50.425,-3.587403129,10000,0,199.9994939,0,0,0,90.00000001 +3.01,50.425,-3.587375028,10000,0,199.9997163,0,0,0,90.00000001 +3.02,50.425,-3.587346928,10000,0,200.0003835,0,0,0,90.00000001 +3.03,50.425,-3.587318827,10000,0,200.0008284,0,0,0,90.00000001 +3.04,50.425,-3.587290726,10000,0,200.0003835,0,0,0,90.00000001 +3.05,50.425,-3.587262626,10000,0,199.9997163,0,0,0,90.00000001 +3.06,50.425,-3.587234525,10000,0,199.9997163,0,0,0,90.00000001 +3.07,50.425,-3.587206425,10000,0,200.0003835,0,0,0,90.00000001 +3.08,50.425,-3.587178324,10000,0,200.0008284,0,0,0,90.00000001 +3.09,50.425,-3.587150223,10000,0,200.0003835,0,0,0,90.00000001 +3.1,50.425,-3.587122123,10000,0,199.9997163,0,0,0,90.00000001 +3.11,50.425,-3.587094022,10000,0,199.9994939,0,0,0,90.00000001 +3.12,50.425,-3.587065922,10000,0,199.9994939,0,0,0,90.00000001 +3.13,50.425,-3.587037821,10000,0,199.9997163,0,0,0,90.00000001 +3.14,50.425,-3.587009721,10000,0,200.0003835,0,0,0,90.00000001 +3.15,50.425,-3.58698162,10000,0,200.000606,0,0,0,90.00000001 +3.16,50.425,-3.586953519,10000,0,199.9994939,0,0,0,90.00000001 +3.17,50.425,-3.586925419,10000,0,199.9986042,0,0,0,90.00000001 +3.18,50.425,-3.586897319,10000,0,199.9997163,0,0,0,90.00000001 +3.19,50.425,-3.586869218,10000,0,200.0014956,0,0,0,90.00000001 +3.2,50.425,-3.586841117,10000,0,200.0014956,0,0,0,90.00000001 +3.21,50.425,-3.586813016,10000,0,199.9997163,0,0,0,90.00000001 +3.22,50.425,-3.586784916,10000,0,199.9986042,0,0,0,90.00000001 +3.23,50.425,-3.586756816,10000,0,199.9994939,0,0,0,90.00000001 +3.24,50.425,-3.586728715,10000,0,200.000606,0,0,0,90.00000001 +3.25,50.425,-3.586700614,10000,0,200.0003835,0,0,0,90.00000001 +3.26,50.425,-3.586672514,10000,0,199.9997163,0,0,0,90.00000001 +3.27,50.425,-3.586644413,10000,0,199.9994939,0,0,0,90.00000001 +3.28,50.425,-3.586616313,10000,0,199.9994939,0,0,0,90.00000001 +3.29,50.425,-3.586588212,10000,0,199.9997163,0,0,0,90.00000001 +3.3,50.425,-3.586560112,10000,0,200.0003835,0,0,0,90.00000001 +3.31,50.425,-3.586532011,10000,0,200.0008284,0,0,0,90.00000001 +3.32,50.425,-3.58650391,10000,0,200.0003835,0,0,0,90.00000001 +3.33,50.425,-3.58647581,10000,0,199.9997163,0,0,0,90.00000001 +3.34,50.425,-3.586447709,10000,0,199.9997163,0,0,0,90.00000001 +3.35,50.425,-3.586419609,10000,0,200.0003835,0,0,0,90.00000001 +3.36,50.425,-3.586391508,10000,0,200.0008284,0,0,0,90.00000001 +3.37,50.425,-3.586363407,10000,0,200.0003835,0,0,0,90.00000001 +3.38,50.425,-3.586335307,10000,0,199.9997163,0,0,0,90.00000001 +3.39,50.425,-3.586307206,10000,0,199.9994939,0,0,0,90.00000001 +3.4,50.425,-3.586279106,10000,0,199.9994939,0,0,0,90.00000001 +3.41,50.425,-3.586251005,10000,0,199.9997163,0,0,0,90.00000001 +3.42,50.425,-3.586222905,10000,0,200.0003835,0,0,0,90.00000001 +3.43,50.425,-3.586194804,10000,0,200.000606,0,0,0,90.00000001 +3.44,50.425,-3.586166703,10000,0,199.9994939,0,0,0,90.00000001 +3.45,50.425,-3.586138603,10000,0,199.9986042,0,0,0,90.00000001 +3.46,50.425,-3.586110503,10000,0,199.9997163,0,0,0,90.00000001 +3.47,50.425,-3.586082402,10000,0,200.0014956,0,0,0,90.00000001 +3.48,50.425,-3.586054301,10000,0,200.0014956,0,0,0,90.00000001 +3.49,50.425,-3.5860262,10000,0,199.9997163,0,0,0,90.00000001 +3.5,50.425,-3.5859981,10000,0,199.9986042,0,0,0,90.00000001 +3.51,50.425,-3.58597,10000,0,199.9994939,0,0,0,90.00000001 +3.52,50.425,-3.585941899,10000,0,200.000606,0,0,0,90.00000001 +3.53,50.425,-3.585913798,10000,0,200.0003835,0,0,0,90.00000001 +3.54,50.425,-3.585885698,10000,0,199.9997163,0,0,0,90.00000001 +3.55,50.425,-3.585857597,10000,0,199.9994939,0,0,0,90.00000001 +3.56,50.425,-3.585829497,10000,0,199.9994939,0,0,0,90.00000001 +3.57,50.425,-3.585801396,10000,0,199.9997163,0,0,0,90.00000001 +3.58,50.425,-3.585773296,10000,0,200.0003835,0,0,0,90.00000001 +3.59,50.425,-3.585745195,10000,0,200.0008284,0,0,0,90.00000001 +3.6,50.425,-3.585717094,10000,0,200.0003835,0,0,0,90.00000001 +3.61,50.425,-3.585688994,10000,0,199.9997163,0,0,0,90.00000001 +3.62,50.425,-3.585660893,10000,0,199.9997163,0,0,0,90.00000001 +3.63,50.425,-3.585632793,10000,0,200.0003835,0,0,0,90.00000001 +3.64,50.425,-3.585604692,10000,0,200.0008284,0,0,0,90.00000001 +3.65,50.425,-3.585576591,10000,0,200.0003835,0,0,0,90.00000001 +3.66,50.425,-3.585548491,10000,0,199.9997163,0,0,0,90.00000001 +3.67,50.425,-3.58552039,10000,0,199.9994939,0,0,0,90.00000001 +3.68,50.425,-3.58549229,10000,0,199.9994939,0,0,0,90.00000001 +3.69,50.425,-3.585464189,10000,0,199.9997163,0,0,0,90.00000001 +3.7,50.425,-3.585436089,10000,0,200.0003835,0,0,0,90.00000001 +3.71,50.425,-3.585407988,10000,0,200.000606,0,0,0,90.00000001 +3.72,50.425,-3.585379887,10000,0,199.9994939,0,0,0,90.00000001 +3.73,50.425,-3.585351787,10000,0,199.9986042,0,0,0,90.00000001 +3.74,50.425,-3.585323687,10000,0,199.9994939,0,0,0,90.00000001 +3.75,50.425,-3.585295586,10000,0,200.000606,0,0,0,90.00000001 +3.76,50.425,-3.585267485,10000,0,200.0003835,0,0,0,90.00000001 +3.77,50.425,-3.585239385,10000,0,199.9997163,0,0,0,90.00000001 +3.78,50.425,-3.585211284,10000,0,199.9994939,0,0,0,90.00000001 +3.79,50.425,-3.585183184,10000,0,199.9994939,0,0,0,90.00000001 +3.8,50.425,-3.585155083,10000,0,199.9997163,0,0,0,90.00000001 +3.81,50.425,-3.585126983,10000,0,200.0003835,0,0,0,90.00000001 +3.82,50.425,-3.585098882,10000,0,200.0008284,0,0,0,90.00000001 +3.83,50.425,-3.585070781,10000,0,200.0003835,0,0,0,90.00000001 +3.84,50.425,-3.585042681,10000,0,199.9997163,0,0,0,90.00000001 +3.85,50.425,-3.58501458,10000,0,199.9997163,0,0,0,90.00000001 +3.86,50.425,-3.58498648,10000,0,200.0003835,0,0,0,90.00000001 +3.87,50.425,-3.584958379,10000,0,200.0008284,0,0,0,90.00000001 +3.88,50.425,-3.584930278,10000,0,200.0003835,0,0,0,90.00000001 +3.89,50.425,-3.584902178,10000,0,199.9997163,0,0,0,90.00000001 +3.9,50.425,-3.584874077,10000,0,199.9994939,0,0,0,90.00000001 +3.91,50.425,-3.584845977,10000,0,199.9994939,0,0,0,90.00000001 +3.92,50.425,-3.584817876,10000,0,199.9997163,0,0,0,90.00000001 +3.93,50.425,-3.584789776,10000,0,200.0003835,0,0,0,90.00000001 +3.94,50.425,-3.584761675,10000,0,200.000606,0,0,0,90.00000001 +3.95,50.425,-3.584733574,10000,0,199.9994939,0,0,0,90.00000001 +3.96,50.425,-3.584705474,10000,0,199.9986042,0,0,0,90.00000001 +3.97,50.425,-3.584677374,10000,0,199.9997163,0,0,0,90.00000001 +3.98,50.425,-3.584649273,10000,0,200.0014956,0,0,0,90.00000001 +3.99,50.425,-3.584621172,10000,0,200.0014956,0,0,0,90.00000001 +4,50.425,-3.584593071,10000,0,199.9997163,0,0,0,90.00000001 +4.01,50.425,-3.584564971,10000,0,199.9986042,0,0,0,90.00000001 +4.02,50.425,-3.584536871,10000,0,199.9994939,0,0,0,90.00000001 +4.03,50.425,-3.58450877,10000,0,200.000606,0,0,0,90.00000001 +4.04,50.425,-3.584480669,10000,0,200.0003835,0,0,0,90.00000001 +4.05,50.425,-3.584452569,10000,0,199.9997163,0,0,0,90.00000001 +4.06,50.425,-3.584424468,10000,0,199.9994939,0,0,0,90.00000001 +4.07,50.425,-3.584396368,10000,0,199.9994939,0,0,0,90.00000001 +4.08,50.425,-3.584368267,10000,0,199.9997163,0,0,0,90.00000001 +4.09,50.425,-3.584340167,10000,0,200.0003835,0,0,0,90.00000001 +4.1,50.425,-3.584312066,10000,0,200.0008284,0,0,0,90.00000001 +4.11,50.425,-3.584283965,10000,0,200.0003835,0,0,0,90.00000001 +4.12,50.425,-3.584255865,10000,0,199.9997163,0,0,0,90.00000001 +4.13,50.425,-3.584227764,10000,0,199.9997163,0,0,0,90.00000001 +4.14,50.425,-3.584199664,10000,0,200.0003835,0,0,0,90.00000001 +4.15,50.425,-3.584171563,10000,0,200.0008284,0,0,0,90.00000001 +4.16,50.425,-3.584143462,10000,0,200.0003835,0,0,0,90.00000001 +4.17,50.425,-3.584115362,10000,0,199.9997163,0,0,0,90.00000001 +4.18,50.425,-3.584087261,10000,0,199.9994939,0,0,0,90.00000001 +4.19,50.425,-3.584059161,10000,0,199.9994939,0,0,0,90.00000001 +4.2,50.425,-3.58403106,10000,0,199.9997163,0,0,0,90.00000001 +4.21,50.425,-3.58400296,10000,0,200.0003835,0,0,0,90.00000001 +4.22,50.425,-3.583974859,10000,0,200.000606,0,0,0,90.00000001 +4.23,50.425,-3.583946758,10000,0,199.9994939,0,0,0,90.00000001 +4.24,50.425,-3.583918658,10000,0,199.9986042,0,0,0,90.00000001 +4.25,50.425,-3.583890558,10000,0,199.9997163,0,0,0,90.00000001 +4.26,50.425,-3.583862457,10000,0,200.0014956,0,0,0,90.00000001 +4.27,50.425,-3.583834356,10000,0,200.0014956,0,0,0,90.00000001 +4.28,50.425,-3.583806255,10000,0,199.9997163,0,0,0,90.00000001 +4.29,50.425,-3.583778155,10000,0,199.9986042,0,0,0,90.00000001 +4.3,50.425,-3.583750055,10000,0,199.9994939,0,0,0,90.00000001 +4.31,50.425,-3.583721954,10000,0,200.000606,0,0,0,90.00000001 +4.32,50.425,-3.583693853,10000,0,200.0003835,0,0,0,90.00000001 +4.33,50.425,-3.583665753,10000,0,199.9997163,0,0,0,90.00000001 +4.34,50.425,-3.583637652,10000,0,199.9994939,0,0,0,90.00000001 +4.35,50.425,-3.583609552,10000,0,199.9994939,0,0,0,90.00000001 +4.36,50.425,-3.583581451,10000,0,199.9997163,0,0,0,90.00000001 +4.37,50.425,-3.583553351,10000,0,200.0003835,0,0,0,90.00000001 +4.38,50.425,-3.58352525,10000,0,200.0008284,0,0,0,90.00000001 +4.39,50.425,-3.583497149,10000,0,200.0003835,0,0,0,90.00000001 +4.4,50.425,-3.583469049,10000,0,199.9997163,0,0,0,90.00000001 +4.41,50.425,-3.583440948,10000,0,199.9997163,0,0,0,90.00000001 +4.42,50.425,-3.583412848,10000,0,200.0003835,0,0,0,90.00000001 +4.43,50.425,-3.583384747,10000,0,200.0008284,0,0,0,90.00000001 +4.44,50.425,-3.583356646,10000,0,200.0003835,0,0,0,90.00000001 +4.45,50.425,-3.583328546,10000,0,199.9997163,0,0,0,90.00000001 +4.46,50.425,-3.583300445,10000,0,199.9994939,0,0,0,90.00000001 +4.47,50.425,-3.583272345,10000,0,199.9994939,0,0,0,90.00000001 +4.48,50.425,-3.583244244,10000,0,199.9997163,0,0,0,90.00000001 +4.49,50.425,-3.583216144,10000,0,200.0003835,0,0,0,90.00000001 +4.5,50.425,-3.583188043,10000,0,200.000606,0,0,0,90.00000001 +4.51,50.425,-3.583159942,10000,0,199.9994939,0,0,0,90.00000001 +4.52,50.425,-3.583131842,10000,0,199.9986042,0,0,0,90.00000001 +4.53,50.425,-3.583103742,10000,0,199.9997163,0,0,0,90.00000001 +4.54,50.425,-3.583075641,10000,0,200.0014956,0,0,0,90.00000001 +4.55,50.425,-3.58304754,10000,0,200.0014956,0,0,0,90.00000001 +4.56,50.425,-3.583019439,10000,0,199.9997163,0,0,0,90.00000001 +4.57,50.425,-3.582991339,10000,0,199.9986042,0,0,0,90.00000001 +4.58,50.425,-3.582963239,10000,0,199.9994939,0,0,0,90.00000001 +4.59,50.425,-3.582935138,10000,0,200.000606,0,0,0,90.00000001 +4.6,50.425,-3.582907037,10000,0,200.0003835,0,0,0,90.00000001 +4.61,50.425,-3.582878937,10000,0,199.9997163,0,0,0,90.00000001 +4.62,50.425,-3.582850836,10000,0,199.9994939,0,0,0,90.00000001 +4.63,50.425,-3.582822736,10000,0,199.9994939,0,0,0,90.00000001 +4.64,50.425,-3.582794635,10000,0,199.9997163,0,0,0,90.00000001 +4.65,50.425,-3.582766535,10000,0,200.0003835,0,0,0,90.00000001 +4.66,50.425,-3.582738434,10000,0,200.0008284,0,0,0,90.00000001 +4.67,50.425,-3.582710333,10000,0,200.0003835,0,0,0,90.00000001 +4.68,50.425,-3.582682233,10000,0,199.9997163,0,0,0,90.00000001 +4.69,50.425,-3.582654132,10000,0,199.9997163,0,0,0,90.00000001 +4.7,50.425,-3.582626032,10000,0,200.0003835,0,0,0,90.00000001 +4.71,50.425,-3.582597931,10000,0,200.0008284,0,0,0,90.00000001 +4.72,50.425,-3.58256983,10000,0,200.0003835,0,0,0,90.00000001 +4.73,50.425,-3.58254173,10000,0,199.9997163,0,0,0,90.00000001 +4.74,50.425,-3.582513629,10000,0,199.9994939,0,0,0,90.00000001 +4.75,50.425,-3.582485529,10000,0,199.9994939,0,0,0,90.00000001 +4.76,50.425,-3.582457428,10000,0,199.9997163,0,0,0,90.00000001 +4.77,50.425,-3.582429328,10000,0,200.0003835,0,0,0,90.00000001 +4.78,50.425,-3.582401227,10000,0,200.000606,0,0,0,90.00000001 +4.79,50.425,-3.582373126,10000,0,199.9994939,0,0,0,90.00000001 +4.8,50.425,-3.582345026,10000,0,199.9986042,0,0,0,90.00000001 +4.81,50.425,-3.582316926,10000,0,199.9997163,0,0,0,90.00000001 +4.82,50.425,-3.582288825,10000,0,200.0014956,0,0,0,90.00000001 +4.83,50.425,-3.582260724,10000,0,200.0014956,0,0,0,90.00000001 +4.84,50.425,-3.582232623,10000,0,199.9997163,0,0,0,90.00000001 +4.85,50.425,-3.582204523,10000,0,199.9986042,0,0,0,90.00000001 +4.86,50.425,-3.582176423,10000,0,199.9994939,0,0,0,90.00000001 +4.87,50.425,-3.582148322,10000,0,200.000606,0,0,0,90.00000001 +4.88,50.425,-3.582120221,10000,0,200.0003835,0,0,0,90.00000001 +4.89,50.425,-3.582092121,10000,0,199.9997163,0,0,0,90.00000001 +4.9,50.425,-3.58206402,10000,0,199.9994939,0,0,0,90.00000001 +4.91,50.425,-3.58203592,10000,0,199.9994939,0,0,0,90.00000001 +4.92,50.425,-3.582007819,10000,0,199.9997163,0,0,0,90.00000001 +4.93,50.425,-3.581979719,10000,0,200.000606,0,0,0,90.00000001 +4.94,50.425,-3.581951618,10000,0,200.001718,0,0,0,90.00000001 +4.95,50.425,-3.581923517,10000,0,200.0014956,0,0,0,90.00000001 +4.96,50.425,-3.581895416,10000,0,199.9997163,0,0,0,90.00000001 +4.97,50.425,-3.581867316,10000,0,199.9986042,0,0,0,90.00000001 +4.98,50.425,-3.581839216,10000,0,199.9994939,0,0,0,90.00000001 +4.99,50.425,-3.581811115,10000,0,200.000606,0,0,0,90.00000001 +5,50.425,-3.581783014,10000,0,200.0003835,0,0,0,90.00000001 +5.01,50.425,-3.581754914,10000,0,199.9997163,0,0,0,90.00000001 +5.02,50.425,-3.581726813,10000,0,199.9994939,0,0,0,90.00000001 +5.03,50.425,-3.581698713,10000,0,199.9994939,0,0,0,90.00000001 +5.04,50.425,-3.581670612,10000,0,199.9997163,0,0,0,90.00000001 +5.05,50.425,-3.581642512,10000,0,200.0003835,0,0,0,90.00000001 +5.06,50.425,-3.581614411,10000,0,200.0008284,0,0,0,90.00000001 +5.07,50.425,-3.58158631,10000,0,200.0003835,0,0,0,90.00000001 +5.08,50.425,-3.58155821,10000,0,199.9997163,0,0,0,90.00000001 +5.09,50.425,-3.581530109,10000,0,199.9997163,0,0,0,90.00000001 +5.1,50.425,-3.581502009,10000,0,200.0003835,0,0,0,90.00000001 +5.11,50.425,-3.581473908,10000,0,200.0008284,0,0,0,90.00000001 +5.12,50.425,-3.581445807,10000,0,200.0003835,0,0,0,90.00000001 +5.13,50.425,-3.581417707,10000,0,199.9997163,0,0,0,90.00000001 +5.14,50.425,-3.581389606,10000,0,199.9994939,0,0,0,90.00000001 +5.15,50.425,-3.581361506,10000,0,199.9994939,0,0,0,90.00000001 +5.16,50.425,-3.581333405,10000,0,199.9997163,0,0,0,90.00000001 +5.17,50.425,-3.581305305,10000,0,200.0003835,0,0,0,90.00000001 +5.18,50.425,-3.581277204,10000,0,200.000606,0,0,0,90.00000001 +5.19,50.425,-3.581249103,10000,0,199.9994939,0,0,0,90.00000001 +5.2,50.425,-3.581221003,10000,0,199.9986042,0,0,0,90.00000001 +5.21,50.425,-3.581192903,10000,0,199.9997163,0,0,0,90.00000001 +5.22,50.425,-3.581164802,10000,0,200.0014956,0,0,0,90.00000001 +5.23,50.425,-3.581136701,10000,0,200.0014956,0,0,0,90.00000001 +5.24,50.425,-3.5811086,10000,0,199.9997163,0,0,0,90.00000001 +5.25,50.425,-3.5810805,10000,0,199.9986042,0,0,0,90.00000001 +5.26,50.425,-3.5810524,10000,0,199.9994939,0,0,0,90.00000001 +5.27,50.425,-3.581024299,10000,0,200.000606,0,0,0,90.00000001 +5.28,50.425,-3.580996198,10000,0,200.0003835,0,0,0,90.00000001 +5.29,50.425,-3.580968098,10000,0,199.9997163,0,0,0,90.00000001 +5.3,50.425,-3.580939997,10000,0,199.9994939,0,0,0,90.00000001 +5.31,50.425,-3.580911897,10000,0,199.9994939,0,0,0,90.00000001 +5.32,50.425,-3.580883796,10000,0,199.9997163,0,0,0,90.00000001 +5.33,50.425,-3.580855696,10000,0,200.0003835,0,0,0,90.00000001 +5.34,50.425,-3.580827595,10000,0,200.0008284,0,0,0,90.00000001 +5.35,50.425,-3.580799494,10000,0,200.0003835,0,0,0,90.00000001 +5.36,50.425,-3.580771394,10000,0,199.9997163,0,0,0,90.00000001 +5.37,50.425,-3.580743293,10000,0,199.9997163,0,0,0,90.00000001 +5.38,50.425,-3.580715193,10000,0,200.0003835,0,0,0,90.00000001 +5.39,50.425,-3.580687092,10000,0,200.0008284,0,0,0,90.00000001 +5.4,50.425,-3.580658991,10000,0,200.0003835,0,0,0,90.00000001 +5.41,50.425,-3.580630891,10000,0,199.9997163,0,0,0,90.00000001 +5.42,50.425,-3.58060279,10000,0,199.9994939,0,0,0,90.00000001 +5.43,50.425,-3.58057469,10000,0,199.9994939,0,0,0,90.00000001 +5.44,50.425,-3.580546589,10000,0,199.9997163,0,0,0,90.00000001 +5.45,50.425,-3.580518489,10000,0,200.0003835,0,0,0,90.00000001 +5.46,50.425,-3.580490388,10000,0,200.000606,0,0,0,90.00000001 +5.47,50.425,-3.580462287,10000,0,199.9994939,0,0,0,90.00000001 +5.48,50.425,-3.580434187,10000,0,199.9986042,0,0,0,90.00000001 +5.49,50.425,-3.580406087,10000,0,199.9997163,0,0,0,90.00000001 +5.5,50.425,-3.580377986,10000,0,200.0014956,0,0,0,90.00000001 +5.51,50.425,-3.580349885,10000,0,200.0014956,0,0,0,90.00000001 +5.52,50.425,-3.580321784,10000,0,199.9997163,0,0,0,90.00000001 +5.53,50.425,-3.580293684,10000,0,199.9986042,0,0,0,90.00000001 +5.54,50.425,-3.580265584,10000,0,199.9994939,0,0,0,90.00000001 +5.55,50.425,-3.580237483,10000,0,200.000606,0,0,0,90.00000001 +5.56,50.425,-3.580209382,10000,0,200.0003835,0,0,0,90.00000001 +5.57,50.425,-3.580181282,10000,0,199.9997163,0,0,0,90.00000001 +5.58,50.425,-3.580153181,10000,0,199.9994939,0,0,0,90.00000001 +5.59,50.425,-3.580125081,10000,0,199.9994939,0,0,0,90.00000001 +5.6,50.425,-3.58009698,10000,0,199.9997163,0,0,0,90.00000001 +5.61,50.425,-3.58006888,10000,0,200.0003835,0,0,0,90.00000001 +5.62,50.425,-3.580040779,10000,0,200.0008284,0,0,0,90.00000001 +5.63,50.425,-3.580012678,10000,0,200.0003835,0,0,0,90.00000001 +5.64,50.425,-3.579984578,10000,0,199.9997163,0,0,0,90.00000001 +5.65,50.425,-3.579956477,10000,0,199.9997163,0,0,0,90.00000001 +5.66,50.425,-3.579928377,10000,0,200.0003835,0,0,0,90.00000001 +5.67,50.425,-3.579900276,10000,0,200.0008284,0,0,0,90.00000001 +5.68,50.425,-3.579872175,10000,0,200.0003835,0,0,0,90.00000001 +5.69,50.425,-3.579844075,10000,0,199.9997163,0,0,0,90.00000001 +5.7,50.425,-3.579815974,10000,0,199.9994939,0,0,0,90.00000001 +5.71,50.425,-3.579787874,10000,0,199.9994939,0,0,0,90.00000001 +5.72,50.425,-3.579759773,10000,0,199.9997163,0,0,0,90.00000001 +5.73,50.425,-3.579731673,10000,0,200.0003835,0,0,0,90.00000001 +5.74,50.425,-3.579703572,10000,0,200.000606,0,0,0,90.00000001 +5.75,50.425,-3.579675471,10000,0,199.9994939,0,0,0,90.00000001 +5.76,50.425,-3.579647371,10000,0,199.9986042,0,0,0,90.00000001 +5.77,50.425,-3.579619271,10000,0,199.9994939,0,0,0,90.00000001 +5.78,50.425,-3.57959117,10000,0,200.000606,0,0,0,90.00000001 +5.79,50.425,-3.579563069,10000,0,200.0003835,0,0,0,90.00000001 +5.8,50.425,-3.579534969,10000,0,199.9997163,0,0,0,90.00000001 +5.81,50.425,-3.579506868,10000,0,199.9994939,0,0,0,90.00000001 +5.82,50.425,-3.579478768,10000,0,199.9994939,0,0,0,90.00000001 +5.83,50.425,-3.579450667,10000,0,199.9997163,0,0,0,90.00000001 +5.84,50.425,-3.579422567,10000,0,200.0003835,0,0,0,90.00000001 +5.85,50.425,-3.579394466,10000,0,200.0008284,0,0,0,90.00000001 +5.86,50.425,-3.579366365,10000,0,200.0003835,0,0,0,90.00000001 +5.87,50.425,-3.579338265,10000,0,199.9997163,0,0,0,90.00000001 +5.88,50.425,-3.579310164,10000,0,199.9997163,0,0,0,90.00000001 +5.89,50.425,-3.579282064,10000,0,200.0003835,0,0,0,90.00000001 +5.9,50.425,-3.579253963,10000,0,200.0008284,0,0,0,90.00000001 +5.91,50.425,-3.579225862,10000,0,200.0003835,0,0,0,90.00000001 +5.92,50.425,-3.579197762,10000,0,199.9997163,0,0,0,90.00000001 +5.93,50.425,-3.579169661,10000,0,199.9994939,0,0,0,90.00000001 +5.94,50.425,-3.579141561,10000,0,199.9994939,0,0,0,90.00000001 +5.95,50.425,-3.57911346,10000,0,199.9997163,0,0,0,90.00000001 +5.96,50.425,-3.57908536,10000,0,200.0003835,0,0,0,90.00000001 +5.97,50.425,-3.579057259,10000,0,200.000606,0,0,0,90.00000001 +5.98,50.425,-3.579029158,10000,0,199.9994939,0,0,0,90.00000001 +5.99,50.425,-3.579001058,10000,0,199.9986042,0,0,0,90.00000001 +6,50.425,-3.578972958,10000,0,199.9997163,0,0,0,90.00000001 +6.01,50.425,-3.578944857,10000,0,200.0014956,0,0,0,90.00000001 +6.02,50.425,-3.578916756,10000,0,200.0014956,0,0,0,90.00000001 +6.03,50.425,-3.578888655,10000,0,199.9997163,0,0,0,90.00000001 +6.04,50.425,-3.578860555,10000,0,199.9986042,0,0,0,90.00000001 +6.05,50.425,-3.578832455,10000,0,199.9994939,0,0,0,90.00000001 +6.06,50.425,-3.578804354,10000,0,200.000606,0,0,0,90.00000001 +6.07,50.425,-3.578776253,10000,0,200.0003835,0,0,0,90.00000001 +6.08,50.425,-3.578748153,10000,0,199.9997163,0,0,0,90.00000001 +6.09,50.425,-3.578720052,10000,0,199.9994939,0,0,0,90.00000001 +6.1,50.425,-3.578691952,10000,0,199.9994939,0,0,0,90.00000001 +6.11,50.425,-3.578663851,10000,0,199.9997163,0,0,0,90.00000001 +6.12,50.425,-3.578635751,10000,0,200.0003835,0,0,0,90.00000001 +6.13,50.425,-3.57860765,10000,0,200.0008284,0,0,0,90.00000001 +6.14,50.425,-3.578579549,10000,0,200.0003835,0,0,0,90.00000001 +6.15,50.425,-3.578551449,10000,0,199.9997163,0,0,0,90.00000001 +6.16,50.425,-3.578523348,10000,0,199.9997163,0,0,0,90.00000001 +6.17,50.425,-3.578495248,10000,0,200.0003835,0,0,0,90.00000001 +6.18,50.425,-3.578467147,10000,0,200.0008284,0,0,0,90.00000001 +6.19,50.425,-3.578439046,10000,0,200.0003835,0,0,0,90.00000001 +6.2,50.425,-3.578410946,10000,0,199.9997163,0,0,0,90.00000001 +6.21,50.425,-3.578382845,10000,0,199.9994939,0,0,0,90.00000001 +6.22,50.425,-3.578354745,10000,0,199.9994939,0,0,0,90.00000001 +6.23,50.425,-3.578326644,10000,0,199.9997163,0,0,0,90.00000001 +6.24,50.425,-3.578298544,10000,0,200.0003835,0,0,0,90.00000001 +6.25,50.425,-3.578270443,10000,0,200.000606,0,0,0,90.00000001 +6.26,50.425,-3.578242342,10000,0,199.9994939,0,0,0,90.00000001 +6.27,50.425,-3.578214242,10000,0,199.9986042,0,0,0,90.00000001 +6.28,50.425,-3.578186142,10000,0,199.9997163,0,0,0,90.00000001 +6.29,50.425,-3.578158041,10000,0,200.0014956,0,0,0,90.00000001 +6.3,50.425,-3.57812994,10000,0,200.0014956,0,0,0,90.00000001 +6.31,50.425,-3.578101839,10000,0,199.9997163,0,0,0,90.00000001 +6.32,50.425,-3.578073739,10000,0,199.9986042,0,0,0,90.00000001 +6.33,50.425,-3.578045639,10000,0,199.9994939,0,0,0,90.00000001 +6.34,50.425,-3.578017538,10000,0,200.000606,0,0,0,90.00000001 +6.35,50.425,-3.577989437,10000,0,200.0003835,0,0,0,90.00000001 +6.36,50.425,-3.577961337,10000,0,199.9997163,0,0,0,90.00000001 +6.37,50.425,-3.577933236,10000,0,199.9994939,0,0,0,90.00000001 +6.38,50.425,-3.577905136,10000,0,199.9994939,0,0,0,90.00000001 +6.39,50.425,-3.577877035,10000,0,199.9997163,0,0,0,90.00000001 +6.4,50.425,-3.577848935,10000,0,200.0003835,0,0,0,90.00000001 +6.41,50.425,-3.577820834,10000,0,200.0008284,0,0,0,90.00000001 +6.42,50.425,-3.577792733,10000,0,200.0003835,0,0,0,90.00000001 +6.43,50.425,-3.577764633,10000,0,199.9997163,0,0,0,90.00000001 +6.44,50.425,-3.577736532,10000,0,199.9997163,0,0,0,90.00000001 +6.45,50.425,-3.577708432,10000,0,200.0003835,0,0,0,90.00000001 +6.46,50.425,-3.577680331,10000,0,200.0008284,0,0,0,90.00000001 +6.47,50.425,-3.57765223,10000,0,200.0003835,0,0,0,90.00000001 +6.48,50.425,-3.57762413,10000,0,199.9997163,0,0,0,90.00000001 +6.49,50.425,-3.577596029,10000,0,199.9994939,0,0,0,90.00000001 +6.5,50.425,-3.577567929,10000,0,199.9994939,0,0,0,90.00000001 +6.51,50.425,-3.577539828,10000,0,199.9997163,0,0,0,90.00000001 +6.52,50.425,-3.577511728,10000,0,200.0003835,0,0,0,90.00000001 +6.53,50.425,-3.577483627,10000,0,200.000606,0,0,0,90.00000001 +6.54,50.425,-3.577455526,10000,0,199.9994939,0,0,0,90.00000001 +6.55,50.425,-3.577427426,10000,0,199.9986042,0,0,0,90.00000001 +6.56,50.425,-3.577399326,10000,0,199.9997163,0,0,0,90.00000001 +6.57,50.425,-3.577371225,10000,0,200.0014956,0,0,0,90.00000001 +6.58,50.425,-3.577343124,10000,0,200.0014956,0,0,0,90.00000001 +6.59,50.425,-3.577315023,10000,0,199.9997163,0,0,0,90.00000001 +6.6,50.425,-3.577286923,10000,0,199.9986042,0,0,0,90.00000001 +6.61,50.425,-3.577258823,10000,0,199.9994939,0,0,0,90.00000001 +6.62,50.425,-3.577230722,10000,0,200.000606,0,0,0,90.00000001 +6.63,50.425,-3.577202621,10000,0,200.0003835,0,0,0,90.00000001 +6.64,50.425,-3.577174521,10000,0,199.9997163,0,0,0,90.00000001 +6.65,50.425,-3.57714642,10000,0,199.9994939,0,0,0,90.00000001 +6.66,50.425,-3.57711832,10000,0,199.9994939,0,0,0,90.00000001 +6.67,50.425,-3.577090219,10000,0,199.9997163,0,0,0,90.00000001 +6.68,50.425,-3.577062119,10000,0,200.0003835,0,0,0,90.00000001 +6.69,50.425,-3.577034018,10000,0,200.0008284,0,0,0,90.00000001 +6.7,50.425,-3.577005917,10000,0,200.0003835,0,0,0,90.00000001 +6.71,50.425,-3.576977817,10000,0,199.9997163,0,0,0,90.00000001 +6.72,50.425,-3.576949716,10000,0,199.9997163,0,0,0,90.00000001 +6.73,50.425,-3.576921616,10000,0,200.0003835,0,0,0,90.00000001 +6.74,50.425,-3.576893515,10000,0,200.0008284,0,0,0,90.00000001 +6.75,50.425,-3.576865414,10000,0,200.0003835,0,0,0,90.00000001 +6.76,50.425,-3.576837314,10000,0,199.9997163,0,0,0,90.00000001 +6.77,50.425,-3.576809213,10000,0,199.9994939,0,0,0,90.00000001 +6.78,50.425,-3.576781113,10000,0,199.9994939,0,0,0,90.00000001 +6.79,50.425,-3.576753012,10000,0,199.9997163,0,0,0,90.00000001 +6.8,50.425,-3.576724912,10000,0,200.0003835,0,0,0,90.00000001 +6.81,50.425,-3.576696811,10000,0,200.000606,0,0,0,90.00000001 +6.82,50.425,-3.57666871,10000,0,199.9994939,0,0,0,90.00000001 +6.83,50.425,-3.57664061,10000,0,199.9986042,0,0,0,90.00000001 +6.84,50.425,-3.57661251,10000,0,199.9997163,0,0,0,90.00000001 +6.85,50.425,-3.576584409,10000,0,200.0014956,0,0,0,90.00000001 +6.86,50.425,-3.576556308,10000,0,200.0014956,0,0,0,90.00000001 +6.87,50.425,-3.576528207,10000,0,199.9997163,0,0,0,90.00000001 +6.88,50.425,-3.576500107,10000,0,199.9986042,0,0,0,90.00000001 +6.89,50.425,-3.576472007,10000,0,199.9994939,0,0,0,90.00000001 +6.9,50.425,-3.576443906,10000,0,200.000606,0,0,0,90.00000001 +6.91,50.425,-3.576415805,10000,0,200.0003835,0,0,0,90.00000001 +6.92,50.425,-3.576387705,10000,0,199.9997163,0,0,0,90.00000001 +6.93,50.425,-3.576359604,10000,0,199.9994939,0,0,0,90.00000001 +6.94,50.425,-3.576331504,10000,0,199.9994939,0,0,0,90.00000001 +6.95,50.425,-3.576303403,10000,0,199.9997163,0,0,0,90.00000001 +6.96,50.425,-3.576275303,10000,0,200.0003835,0,0,0,90.00000001 +6.97,50.425,-3.576247202,10000,0,200.0008284,0,0,0,90.00000001 +6.98,50.425,-3.576219101,10000,0,200.0003835,0,0,0,90.00000001 +6.99,50.425,-3.576191001,10000,0,199.9997163,0,0,0,90.00000001 +7,50.425,-3.5761629,10000,0,199.9997163,0,0,0,90.00000001 +7.01,50.425,-3.5761348,10000,0,200.0003835,0,0,0,90.00000001 +7.02,50.425,-3.576106699,10000,0,200.0008284,0,0,0,90.00000001 +7.03,50.425,-3.576078598,10000,0,200.0003835,0,0,0,90.00000001 +7.04,50.425,-3.576050498,10000,0,199.9997163,0,0,0,90.00000001 +7.05,50.425,-3.576022397,10000,0,199.9994939,0,0,0,90.00000001 +7.06,50.425,-3.575994297,10000,0,199.9994939,0,0,0,90.00000001 +7.07,50.425,-3.575966196,10000,0,199.9997163,0,0,0,90.00000001 +7.08,50.425,-3.575938096,10000,0,200.0003835,0,0,0,90.00000001 +7.09,50.425,-3.575909995,10000,0,200.000606,0,0,0,90.00000001 +7.1,50.425,-3.575881894,10000,0,199.9994939,0,0,0,90.00000001 +7.11,50.425,-3.575853794,10000,0,199.9986042,0,0,0,90.00000001 +7.12,50.425,-3.575825694,10000,0,199.9997163,0,0,0,90.00000001 +7.13,50.425,-3.575797593,10000,0,200.0014956,0,0,0,90.00000001 +7.14,50.425,-3.575769492,10000,0,200.0014956,0,0,0,90.00000001 +7.15,50.425,-3.575741391,10000,0,199.9997163,0,0,0,90.00000001 +7.16,50.425,-3.575713291,10000,0,199.9986042,0,0,0,90.00000001 +7.17,50.425,-3.575685191,10000,0,199.9994939,0,0,0,90.00000001 +7.18,50.425,-3.57565709,10000,0,200.000606,0,0,0,90.00000001 +7.19,50.425,-3.575628989,10000,0,200.0003835,0,0,0,90.00000001 +7.2,50.425,-3.575600889,10000,0,199.9997163,0,0,0,90.00000001 +7.21,50.425,-3.575572788,10000,0,199.9994939,0,0,0,90.00000001 +7.22,50.425,-3.575544688,10000,0,199.9994939,0,0,0,90.00000001 +7.23,50.425,-3.575516587,10000,0,199.9997163,0,0,0,90.00000001 +7.24,50.425,-3.575488487,10000,0,200.0003835,0,0,0,90.00000001 +7.25,50.425,-3.575460386,10000,0,200.0008284,0,0,0,90.00000001 +7.26,50.425,-3.575432285,10000,0,200.0003835,0,0,0,90.00000001 +7.27,50.425,-3.575404185,10000,0,199.9997163,0,0,0,90.00000001 +7.28,50.425,-3.575376084,10000,0,199.9997163,0,0,0,90.00000001 +7.29,50.425,-3.575347984,10000,0,200.0003835,0,0,0,90.00000001 +7.3,50.425,-3.575319883,10000,0,200.0008284,0,0,0,90.00000001 +7.31,50.425,-3.575291782,10000,0,200.0003835,0,0,0,90.00000001 +7.32,50.425,-3.575263682,10000,0,199.9997163,0,0,0,90.00000001 +7.33,50.425,-3.575235581,10000,0,199.9994939,0,0,0,90.00000001 +7.34,50.425,-3.575207481,10000,0,199.9994939,0,0,0,90.00000001 +7.35,50.425,-3.57517938,10000,0,199.9997163,0,0,0,90.00000001 +7.36,50.425,-3.57515128,10000,0,200.0003835,0,0,0,90.00000001 +7.37,50.425,-3.575123179,10000,0,200.000606,0,0,0,90.00000001 +7.38,50.425,-3.575095078,10000,0,199.9994939,0,0,0,90.00000001 +7.39,50.425,-3.575066978,10000,0,199.9986042,0,0,0,90.00000001 +7.4,50.425,-3.575038878,10000,0,199.9997163,0,0,0,90.00000001 +7.41,50.425,-3.575010777,10000,0,200.0014956,0,0,0,90.00000001 +7.42,50.425,-3.574982676,10000,0,200.0014956,0,0,0,90.00000001 +7.43,50.425,-3.574954575,10000,0,199.9997163,0,0,0,90.00000001 +7.44,50.425,-3.574926475,10000,0,199.9986042,0,0,0,90.00000001 +7.45,50.425,-3.574898375,10000,0,199.9994939,0,0,0,90.00000001 +7.46,50.425,-3.574870274,10000,0,200.000606,0,0,0,90.00000001 +7.47,50.425,-3.574842173,10000,0,200.0003835,0,0,0,90.00000001 +7.48,50.425,-3.574814073,10000,0,199.9997163,0,0,0,90.00000001 +7.49,50.425,-3.574785972,10000,0,199.9994939,0,0,0,90.00000001 +7.5,50.425,-3.574757872,10000,0,199.9994939,0,0,0,90.00000001 +7.51,50.425,-3.574729771,10000,0,199.9997163,0,0,0,90.00000001 +7.52,50.425,-3.574701671,10000,0,200.0003835,0,0,0,90.00000001 +7.53,50.425,-3.57467357,10000,0,200.0008284,0,0,0,90.00000001 +7.54,50.425,-3.574645469,10000,0,200.0003835,0,0,0,90.00000001 +7.55,50.425,-3.574617369,10000,0,199.9997163,0,0,0,90.00000001 +7.56,50.425,-3.574589268,10000,0,199.9997163,0,0,0,90.00000001 +7.57,50.425,-3.574561168,10000,0,200.0003835,0,0,0,90.00000001 +7.58,50.425,-3.574533067,10000,0,200.0008284,0,0,0,90.00000001 +7.59,50.425,-3.574504966,10000,0,200.0003835,0,0,0,90.00000001 +7.6,50.425,-3.574476866,10000,0,199.9997163,0,0,0,90.00000001 +7.61,50.425,-3.574448765,10000,0,199.9994939,0,0,0,90.00000001 +7.62,50.425,-3.574420665,10000,0,199.9994939,0,0,0,90.00000001 +7.63,50.425,-3.574392564,10000,0,199.9997163,0,0,0,90.00000001 +7.64,50.425,-3.574364464,10000,0,200.0003835,0,0,0,90.00000001 +7.65,50.425,-3.574336363,10000,0,200.000606,0,0,0,90.00000001 +7.66,50.425,-3.574308262,10000,0,199.9994939,0,0,0,90.00000001 +7.67,50.425,-3.574280162,10000,0,199.9986042,0,0,0,90.00000001 +7.68,50.425,-3.574252062,10000,0,199.9997163,0,0,0,90.00000001 +7.69,50.425,-3.574223961,10000,0,200.0014956,0,0,0,90.00000001 +7.7,50.425,-3.57419586,10000,0,200.0014956,0,0,0,90.00000001 +7.71,50.425,-3.574167759,10000,0,199.9997163,0,0,0,90.00000001 +7.72,50.425,-3.574139659,10000,0,199.9986042,0,0,0,90.00000001 +7.73,50.425,-3.574111559,10000,0,199.9994939,0,0,0,90.00000001 +7.74,50.425,-3.574083458,10000,0,200.000606,0,0,0,90.00000001 +7.75,50.425,-3.574055357,10000,0,200.0003835,0,0,0,90.00000001 +7.76,50.425,-3.574027257,10000,0,199.9997163,0,0,0,90.00000001 +7.77,50.425,-3.573999156,10000,0,199.9994939,0,0,0,90.00000001 +7.78,50.425,-3.573971056,10000,0,199.9994939,0,0,0,90.00000001 +7.79,50.425,-3.573942955,10000,0,199.9997163,0,0,0,90.00000001 +7.8,50.425,-3.573914855,10000,0,200.0003835,0,0,0,90.00000001 +7.81,50.425,-3.573886754,10000,0,200.0008284,0,0,0,90.00000001 +7.82,50.425,-3.573858653,10000,0,200.0003835,0,0,0,90.00000001 +7.83,50.425,-3.573830553,10000,0,199.9997163,0,0,0,90.00000001 +7.84,50.425,-3.573802452,10000,0,199.9994939,0,0,0,90.00000001 +7.85,50.425,-3.573774352,10000,0,199.9994939,0,0,0,90.00000001 +7.86,50.425,-3.573746251,10000,0,199.9997163,0,0,0,90.00000001 +7.87,50.425,-3.573718151,10000,0,200.0003835,0,0,0,90.00000001 +7.88,50.425,-3.57369005,10000,0,200.000606,0,0,0,90.00000001 +7.89,50.425,-3.573661949,10000,0,199.9994939,0,0,0,90.00000001 +7.9,50.425,-3.573633849,10000,0,199.9986042,0,0,0,90.00000001 +7.91,50.425,-3.573605749,10000,0,199.9997163,0,0,0,90.00000001 +7.92,50.425,-3.573577648,10000,0,200.0014956,0,0,0,90.00000001 +7.93,50.425,-3.573549547,10000,0,200.0014956,0,0,0,90.00000001 +7.94,50.425,-3.573521446,10000,0,199.9997163,0,0,0,90.00000001 +7.95,50.425,-3.573493346,10000,0,199.9986042,0,0,0,90.00000001 +7.96,50.425,-3.573465246,10000,0,199.9994939,0,0,0,90.00000001 +7.97,50.425,-3.573437145,10000,0,200.000606,0,0,0,90.00000001 +7.98,50.425,-3.573409044,10000,0,200.0003835,0,0,0,90.00000001 +7.99,50.425,-3.573380944,10000,0,199.9997163,0,0,0,90.00000001 +8,50.425,-3.573352843,10000,0,199.9994939,0,0,0,90.00000001 +8.01,50.425,-3.573324743,10000,0,199.9994939,0,0,0,90.00000001 +8.02,50.425,-3.573296642,10000,0,199.9997163,0,0,0,90.00000001 +8.03,50.425,-3.573268542,10000,0,200.0003835,0,0,0,90.00000001 +8.04,50.425,-3.573240441,10000,0,200.0008284,0,0,0,90.00000001 +8.05,50.425,-3.57321234,10000,0,200.0003835,0,0,0,90.00000001 +8.06,50.425,-3.57318424,10000,0,199.9997163,0,0,0,90.00000001 +8.07,50.425,-3.573156139,10000,0,199.9997163,0,0,0,90.00000001 +8.08,50.425,-3.573128039,10000,0,200.0003835,0,0,0,90.00000001 +8.09,50.425,-3.573099938,10000,0,200.0008284,0,0,0,90.00000001 +8.1,50.425,-3.573071837,10000,0,200.0003835,0,0,0,90.00000001 +8.11,50.425,-3.573043737,10000,0,199.9997163,0,0,0,90.00000001 +8.12,50.425,-3.573015636,10000,0,199.9994939,0,0,0,90.00000001 +8.13,50.425,-3.572987536,10000,0,199.9994939,0,0,0,90.00000001 +8.14,50.425,-3.572959435,10000,0,199.9997163,0,0,0,90.00000001 +8.15,50.425,-3.572931335,10000,0,200.0003835,0,0,0,90.00000001 +8.16,50.425,-3.572903234,10000,0,200.000606,0,0,0,90.00000001 +8.17,50.425,-3.572875133,10000,0,199.9994939,0,0,0,90.00000001 +8.18,50.425,-3.572847033,10000,0,199.9986042,0,0,0,90.00000001 +8.19,50.425,-3.572818933,10000,0,199.9997163,0,0,0,90.00000001 +8.2,50.425,-3.572790832,10000,0,200.0014956,0,0,0,90.00000001 +8.21,50.425,-3.572762731,10000,0,200.0014956,0,0,0,90.00000001 +8.22,50.425,-3.57273463,10000,0,199.9997163,0,0,0,90.00000001 +8.23,50.425,-3.57270653,10000,0,199.9986042,0,0,0,90.00000001 +8.24,50.425,-3.57267843,10000,0,199.9994939,0,0,0,90.00000001 +8.25,50.425,-3.572650329,10000,0,200.000606,0,0,0,90.00000001 +8.26,50.425,-3.572622228,10000,0,200.0003835,0,0,0,90.00000001 +8.27,50.425,-3.572594128,10000,0,199.9997163,0,0,0,90.00000001 +8.28,50.425,-3.572566027,10000,0,199.9994939,0,0,0,90.00000001 +8.29,50.425,-3.572537927,10000,0,199.9994939,0,0,0,90.00000001 +8.3,50.425,-3.572509826,10000,0,199.9997163,0,0,0,90.00000001 +8.31,50.425,-3.572481726,10000,0,200.0003835,0,0,0,90.00000001 +8.32,50.425,-3.572453625,10000,0,200.0008284,0,0,0,90.00000001 +8.33,50.425,-3.572425524,10000,0,200.0003835,0,0,0,90.00000001 +8.34,50.425,-3.572397424,10000,0,199.9997163,0,0,0,90.00000001 +8.35,50.425,-3.572369323,10000,0,199.9997163,0,0,0,90.00000001 +8.36,50.425,-3.572341223,10000,0,200.0003835,0,0,0,90.00000001 +8.37,50.425,-3.572313122,10000,0,200.0008284,0,0,0,90.00000001 +8.38,50.425,-3.572285021,10000,0,200.0003835,0,0,0,90.00000001 +8.39,50.425,-3.572256921,10000,0,199.9997163,0,0,0,90.00000001 +8.4,50.425,-3.57222882,10000,0,199.9994939,0,0,0,90.00000001 +8.41,50.425,-3.57220072,10000,0,199.9994939,0,0,0,90.00000001 +8.42,50.425,-3.572172619,10000,0,199.9997163,0,0,0,90.00000001 +8.43,50.425,-3.572144519,10000,0,200.0003835,0,0,0,90.00000001 +8.44,50.425,-3.572116418,10000,0,200.000606,0,0,0,90.00000001 +8.45,50.425,-3.572088317,10000,0,199.9994939,0,0,0,90.00000001 +8.46,50.425,-3.572060217,10000,0,199.9986042,0,0,0,90.00000001 +8.47,50.425,-3.572032117,10000,0,199.9997163,0,0,0,90.00000001 +8.48,50.425,-3.572004016,10000,0,200.0014956,0,0,0,90.00000001 +8.49,50.425,-3.571975915,10000,0,200.0014956,0,0,0,90.00000001 +8.5,50.425,-3.571947814,10000,0,199.9997163,0,0,0,90.00000001 +8.51,50.425,-3.571919714,10000,0,199.9986042,0,0,0,90.00000001 +8.52,50.425,-3.571891614,10000,0,199.9994939,0,0,0,90.00000001 +8.53,50.425,-3.571863513,10000,0,200.000606,0,0,0,90.00000001 +8.54,50.425,-3.571835412,10000,0,200.0003835,0,0,0,90.00000001 +8.55,50.425,-3.571807312,10000,0,199.9997163,0,0,0,90.00000001 +8.56,50.425,-3.571779211,10000,0,199.9994939,0,0,0,90.00000001 +8.57,50.425,-3.571751111,10000,0,199.9994939,0,0,0,90.00000001 +8.58,50.425,-3.57172301,10000,0,199.9997163,0,0,0,90.00000001 +8.59,50.425,-3.57169491,10000,0,200.000606,0,0,0,90.00000001 +8.6,50.425,-3.571666809,10000,0,200.001718,0,0,0,90.00000001 +8.61,50.425,-3.571638708,10000,0,200.0014956,0,0,0,90.00000001 +8.62,50.425,-3.571610607,10000,0,199.9997163,0,0,0,90.00000001 +8.63,50.425,-3.571582507,10000,0,199.9986042,0,0,0,90.00000001 +8.64,50.425,-3.571554407,10000,0,199.9994939,0,0,0,90.00000001 +8.65,50.425,-3.571526306,10000,0,200.000606,0,0,0,90.00000001 +8.66,50.425,-3.571498205,10000,0,200.0003835,0,0,0,90.00000001 +8.67,50.425,-3.571470105,10000,0,199.9997163,0,0,0,90.00000001 +8.68,50.425,-3.571442004,10000,0,199.9994939,0,0,0,90.00000001 +8.69,50.425,-3.571413904,10000,0,199.9994939,0,0,0,90.00000001 +8.7,50.425,-3.571385803,10000,0,199.9997163,0,0,0,90.00000001 +8.71,50.425,-3.571357703,10000,0,200.0003835,0,0,0,90.00000001 +8.72,50.425,-3.571329602,10000,0,200.0008284,0,0,0,90.00000001 +8.73,50.425,-3.571301501,10000,0,200.0003835,0,0,0,90.00000001 +8.74,50.425,-3.571273401,10000,0,199.9997163,0,0,0,90.00000001 +8.75,50.425,-3.5712453,10000,0,199.9997163,0,0,0,90.00000001 +8.76,50.425,-3.5712172,10000,0,200.0003835,0,0,0,90.00000001 +8.77,50.425,-3.571189099,10000,0,200.0008284,0,0,0,90.00000001 +8.78,50.425,-3.571160998,10000,0,200.0003835,0,0,0,90.00000001 +8.79,50.425,-3.571132898,10000,0,199.9997163,0,0,0,90.00000001 +8.8,50.425,-3.571104797,10000,0,199.9994939,0,0,0,90.00000001 +8.81,50.425,-3.571076697,10000,0,199.9994939,0,0,0,90.00000001 +8.82,50.425,-3.571048596,10000,0,199.9997163,0,0,0,90.00000001 +8.83,50.425,-3.571020496,10000,0,200.0003835,0,0,0,90.00000001 +8.84,50.425,-3.570992395,10000,0,200.000606,0,0,0,90.00000001 +8.85,50.425,-3.570964294,10000,0,199.9994939,0,0,0,90.00000001 +8.86,50.425,-3.570936194,10000,0,199.9986042,0,0,0,90.00000001 +8.87,50.425,-3.570908094,10000,0,199.9997163,0,0,0,90.00000001 +8.88,50.425,-3.570879993,10000,0,200.0014956,0,0,0,90.00000001 +8.89,50.425,-3.570851892,10000,0,200.0014956,0,0,0,90.00000001 +8.9,50.425,-3.570823791,10000,0,199.9997163,0,0,0,90.00000001 +8.91,50.425,-3.570795691,10000,0,199.9986042,0,0,0,90.00000001 +8.92,50.425,-3.570767591,10000,0,199.9994939,0,0,0,90.00000001 +8.93,50.425,-3.57073949,10000,0,200.000606,0,0,0,90.00000001 +8.94,50.425,-3.570711389,10000,0,200.0003835,0,0,0,90.00000001 +8.95,50.425,-3.570683289,10000,0,199.9997163,0,0,0,90.00000001 +8.96,50.425,-3.570655188,10000,0,199.9994939,0,0,0,90.00000001 +8.97,50.425,-3.570627088,10000,0,199.9994939,0,0,0,90.00000001 +8.98,50.425,-3.570598987,10000,0,199.9997163,0,0,0,90.00000001 +8.99,50.425,-3.570570887,10000,0,200.0003835,0,0,0,90.00000001 +9,50.425,-3.570542786,10000,0,200.0008284,0,0,0,90.00000001 +9.01,50.425,-3.570514685,10000,0,200.0003835,0,0,0,90.00000001 +9.02,50.425,-3.570486585,10000,0,199.9997163,0,0,0,90.00000001 +9.03,50.425,-3.570458484,10000,0,199.9997163,0,0,0,90.00000001 +9.04,50.425,-3.570430384,10000,0,200.0003835,0,0,0,90.00000001 +9.05,50.425,-3.570402283,10000,0,200.0008284,0,0,0,90.00000001 +9.06,50.425,-3.570374182,10000,0,200.0003835,0,0,0,90.00000001 +9.07,50.425,-3.570346082,10000,0,199.9997163,0,0,0,90.00000001 +9.08,50.425,-3.570317981,10000,0,199.9994939,0,0,0,90.00000001 +9.09,50.425,-3.570289881,10000,0,199.9994939,0,0,0,90.00000001 +9.1,50.425,-3.57026178,10000,0,199.9997163,0,0,0,90.00000001 +9.11,50.425,-3.57023368,10000,0,200.0003835,0,0,0,90.00000001 +9.12,50.425,-3.570205579,10000,0,200.000606,0,0,0,90.00000001 +9.13,50.425,-3.570177478,10000,0,199.9994939,0,0,0,90.00000001 +9.14,50.425,-3.570149378,10000,0,199.9986042,0,0,0,90.00000001 +9.15,50.425,-3.570121278,10000,0,199.9997163,0,0,0,90.00000001 +9.16,50.425,-3.570093177,10000,0,200.0014956,0,0,0,90.00000001 +9.17,50.425,-3.570065076,10000,0,200.0014956,0,0,0,90.00000001 +9.18,50.425,-3.570036975,10000,0,199.9997163,0,0,0,90.00000001 +9.19,50.425,-3.570008875,10000,0,199.9986042,0,0,0,90.00000001 +9.2,50.425,-3.569980775,10000,0,199.9994939,0,0,0,90.00000001 +9.21,50.425,-3.569952674,10000,0,200.000606,0,0,0,90.00000001 +9.22,50.425,-3.569924573,10000,0,200.0003835,0,0,0,90.00000001 +9.23,50.425,-3.569896473,10000,0,199.9997163,0,0,0,90.00000001 +9.24,50.425,-3.569868372,10000,0,199.9994939,0,0,0,90.00000001 +9.25,50.425,-3.569840272,10000,0,199.9994939,0,0,0,90.00000001 +9.26,50.425,-3.569812171,10000,0,199.9997163,0,0,0,90.00000001 +9.27,50.425,-3.569784071,10000,0,200.0003835,0,0,0,90.00000001 +9.28,50.425,-3.56975597,10000,0,200.0008284,0,0,0,90.00000001 +9.29,50.425,-3.569727869,10000,0,200.0003835,0,0,0,90.00000001 +9.3,50.425,-3.569699769,10000,0,199.9997163,0,0,0,90.00000001 +9.31,50.425,-3.569671668,10000,0,199.9997163,0,0,0,90.00000001 +9.32,50.425,-3.569643568,10000,0,200.0003835,0,0,0,90.00000001 +9.33,50.425,-3.569615467,10000,0,200.0008284,0,0,0,90.00000001 +9.34,50.425,-3.569587366,10000,0,200.0003835,0,0,0,90.00000001 +9.35,50.425,-3.569559266,10000,0,199.9997163,0,0,0,90.00000001 +9.36,50.425,-3.569531165,10000,0,199.9994939,0,0,0,90.00000001 +9.37,50.425,-3.569503065,10000,0,199.9994939,0,0,0,90.00000001 +9.38,50.425,-3.569474964,10000,0,199.9997163,0,0,0,90.00000001 +9.39,50.425,-3.569446864,10000,0,200.0003835,0,0,0,90.00000001 +9.4,50.425,-3.569418763,10000,0,200.000606,0,0,0,90.00000001 +9.41,50.425,-3.569390662,10000,0,199.9994939,0,0,0,90.00000001 +9.42,50.425,-3.569362562,10000,0,199.9986042,0,0,0,90.00000001 +9.43,50.425,-3.569334462,10000,0,199.9997163,0,0,0,90.00000001 +9.44,50.425,-3.569306361,10000,0,200.0014956,0,0,0,90.00000001 +9.45,50.425,-3.56927826,10000,0,200.0014956,0,0,0,90.00000001 +9.46,50.425,-3.569250159,10000,0,199.9997163,0,0,0,90.00000001 +9.47,50.425,-3.569222059,10000,0,199.9986042,0,0,0,90.00000001 +9.48,50.425,-3.569193959,10000,0,199.9994939,0,0,0,90.00000001 +9.49,50.425,-3.569165858,10000,0,200.000606,0,0,0,90.00000001 +9.5,50.425,-3.569137757,10000,0,200.0003835,0,0,0,90.00000001 +9.51,50.425,-3.569109657,10000,0,199.9997163,0,0,0,90.00000001 +9.52,50.425,-3.569081556,10000,0,199.9994939,0,0,0,90.00000001 +9.53,50.425,-3.569053456,10000,0,199.9994939,0,0,0,90.00000001 +9.54,50.425,-3.569025355,10000,0,199.9997163,0,0,0,90.00000001 +9.55,50.425,-3.568997255,10000,0,200.0003835,0,0,0,90.00000001 +9.56,50.425,-3.568969154,10000,0,200.0008284,0,0,0,90.00000001 +9.57,50.425,-3.568941053,10000,0,200.0003835,0,0,0,90.00000001 +9.58,50.425,-3.568912953,10000,0,199.9997163,0,0,0,90.00000001 +9.59,50.425,-3.568884852,10000,0,199.9997163,0,0,0,90.00000001 +9.6,50.425,-3.568856752,10000,0,200.0003835,0,0,0,90.00000001 +9.61,50.425,-3.568828651,10000,0,200.0008284,0,0,0,90.00000001 +9.62,50.425,-3.56880055,10000,0,200.0003835,0,0,0,90.00000001 +9.63,50.425,-3.56877245,10000,0,199.9997163,0,0,0,90.00000001 +9.64,50.425,-3.568744349,10000,0,199.9994939,0,0,0,90.00000001 +9.65,50.425,-3.568716249,10000,0,199.9994939,0,0,0,90.00000001 +9.66,50.425,-3.568688148,10000,0,199.9997163,0,0,0,90.00000001 +9.67,50.425,-3.568660048,10000,0,200.0003835,0,0,0,90.00000001 +9.68,50.425,-3.568631947,10000,0,200.000606,0,0,0,90.00000001 +9.69,50.425,-3.568603846,10000,0,199.9994939,0,0,0,90.00000001 +9.7,50.425,-3.568575746,10000,0,199.9986042,0,0,0,90.00000001 +9.71,50.425,-3.568547646,10000,0,199.9997163,0,0,0,90.00000001 +9.72,50.425,-3.568519545,10000,0,200.0014956,0,0,0,90.00000001 +9.73,50.425,-3.568491444,10000,0,200.0014956,0,0,0,90.00000001 +9.74,50.425,-3.568463343,10000,0,199.9997163,0,0,0,90.00000001 +9.75,50.425,-3.568435243,10000,0,199.9986042,0,0,0,90.00000001 +9.76,50.425,-3.568407143,10000,0,199.9994939,0,0,0,90.00000001 +9.77,50.425,-3.568379042,10000,0,200.000606,0,0,0,90.00000001 +9.78,50.425,-3.568350941,10000,0,200.0003835,0,0,0,90.00000001 +9.79,50.425,-3.568322841,10000,0,199.9997163,0,0,0,90.00000001 +9.8,50.425,-3.56829474,10000,0,199.9994939,0,0,0,90.00000001 +9.81,50.425,-3.56826664,10000,0,199.9994939,0,0,0,90.00000001 +9.82,50.425,-3.568238539,10000,0,199.9997163,0,0,0,90.00000001 +9.83,50.425,-3.568210439,10000,0,200.0003835,0,0,0,90.00000001 +9.84,50.425,-3.568182338,10000,0,200.0008284,0,0,0,90.00000001 +9.85,50.425,-3.568154237,10000,0,200.0003835,0,0,0,90.00000001 +9.86,50.425,-3.568126137,10000,0,199.9997163,0,0,0,90.00000001 +9.87,50.425,-3.568098036,10000,0,199.9994939,0,0,0,90.00000001 +9.88,50.425,-3.568069936,10000,0,199.9994939,0,0,0,90.00000001 +9.89,50.425,-3.568041835,10000,0,199.9997163,0,0,0,90.00000001 +9.9,50.425,-3.568013735,10000,0,200.0003835,0,0,0,90.00000001 +9.91,50.425,-3.567985634,10000,0,200.000606,0,0,0,90.00000001 +9.92,50.425,-3.567957533,10000,0,199.9994939,0,0,0,90.00000001 +9.93,50.425,-3.567929433,10000,0,199.9986042,0,0,0,90.00000001 +9.94,50.425,-3.567901333,10000,0,199.9997163,0,0,0,90.00000001 +9.95,50.425,-3.567873232,10000,0,200.0014956,0,0,0,90.00000001 +9.96,50.425,-3.567845131,10000,0,200.0014956,0,0,0,90.00000001 +9.97,50.425,-3.56781703,10000,0,199.9997163,0,0,0,90.00000001 +9.98,50.425,-3.56778893,10000,0,199.9986042,0,0,0,90.00000001 +9.99,50.425,-3.56776083,10000,0,199.9994939,0,0,0,90.00000001 +10,50.425,-3.567732729,10000,0,200.000606,0,0,0,90.00000001 +10.01,50.425,-3.567704628,10000,0,200.0003835,0,0,0,90.00000001 +10.02,50.425,-3.567676528,10000,0,199.9997163,0,0,0,90.00000001 +10.03,50.425,-3.567648427,10000,0,199.9994939,0,0,0,90.00000001 +10.04,50.425,-3.567620327,10000,0,199.9994939,0,0,0,90.00000001 +10.05,50.425,-3.567592226,10000,0,199.9997163,0,0,0,90.00000001 +10.06,50.425,-3.567564126,10000,0,200.0003835,0,0,0,90.00000001 +10.07,50.425,-3.567536025,10000,0,200.0008284,0,0,0,90.00000001 +10.08,50.425,-3.567507924,10000,0,200.0003835,0,0,0,90.00000001 +10.09,50.425,-3.567479824,10000,0,199.9997163,0,0,0,90.00000001 +10.1,50.425,-3.567451723,10000,0,199.9997163,0,0,0,90.00000001 +10.11,50.425,-3.567423623,10000,0,200.0003835,0,0,0,90.00000001 +10.12,50.425,-3.567395522,10000,0,200.0008284,0,0,0,90.00000001 +10.13,50.425,-3.567367421,10000,0,200.0003835,0,0,0,90.00000001 +10.14,50.425,-3.567339321,10000,0,199.9997163,0,0,0,90.00000001 +10.15,50.425,-3.56731122,10000,0,199.9994939,0,0,0,90.00000001 +10.16,50.425,-3.56728312,10000,0,199.9994939,0,0,0,90.00000001 +10.17,50.425,-3.567255019,10000,0,199.9997163,0,0,0,90.00000001 +10.18,50.425,-3.567226919,10000,0,200.0003835,0,0,0,90.00000001 +10.19,50.425,-3.567198818,10000,0,200.000606,0,0,0,90.00000001 +10.2,50.425,-3.567170717,10000,0,199.9994939,0,0,0,90.00000001 +10.21,50.425,-3.567142617,10000,0,199.9986042,0,0,0,90.00000001 +10.22,50.425,-3.567114517,10000,0,199.9997163,0,0,0,90.00000001 +10.23,50.425,-3.567086416,10000,0,200.0014956,0,0,0,90.00000001 +10.24,50.425,-3.567058315,10000,0,200.0014956,0,0,0,90.00000001 +10.25,50.425,-3.567030214,10000,0,199.9997163,0,0,0,90.00000001 +10.26,50.425,-3.567002114,10000,0,199.9986042,0,0,0,90.00000001 +10.27,50.425,-3.566974014,10000,0,199.9994939,0,0,0,90.00000001 +10.28,50.425,-3.566945913,10000,0,200.000606,0,0,0,90.00000001 +10.29,50.425,-3.566917812,10000,0,200.0003835,0,0,0,90.00000001 +10.3,50.425,-3.566889712,10000,0,199.9997163,0,0,0,90.00000001 +10.31,50.425,-3.566861611,10000,0,199.9994939,0,0,0,90.00000001 +10.32,50.425,-3.566833511,10000,0,199.9994939,0,0,0,90.00000001 +10.33,50.425,-3.56680541,10000,0,199.9997163,0,0,0,90.00000001 +10.34,50.425,-3.56677731,10000,0,200.0003835,0,0,0,90.00000001 +10.35,50.425,-3.566749209,10000,0,200.0008284,0,0,0,90.00000001 +10.36,50.425,-3.566721108,10000,0,200.0003835,0,0,0,90.00000001 +10.37,50.425,-3.566693008,10000,0,199.9997163,0,0,0,90.00000001 +10.38,50.425,-3.566664907,10000,0,199.9997163,0,0,0,90.00000001 +10.39,50.425,-3.566636807,10000,0,200.0003835,0,0,0,90.00000001 +10.4,50.425,-3.566608706,10000,0,200.0008284,0,0,0,90.00000001 +10.41,50.425,-3.566580605,10000,0,200.0003835,0,0,0,90.00000001 +10.42,50.425,-3.566552505,10000,0,199.9997163,0,0,0,90.00000001 +10.43,50.425,-3.566524404,10000,0,199.9994939,0,0,0,90.00000001 +10.44,50.425,-3.566496304,10000,0,199.9994939,0,0,0,90.00000001 +10.45,50.425,-3.566468203,10000,0,199.9997163,0,0,0,90.00000001 +10.46,50.425,-3.566440103,10000,0,200.0003835,0,0,0,90.00000001 +10.47,50.425,-3.566412002,10000,0,200.000606,0,0,0,90.00000001 +10.48,50.425,-3.566383901,10000,0,199.9994939,0,0,0,90.00000001 +10.49,50.425,-3.566355801,10000,0,199.9986042,0,0,0,90.00000001 +10.5,50.425,-3.566327701,10000,0,199.9997163,0,0,0,90.00000001 +10.51,50.425,-3.5662996,10000,0,200.0014956,0,0,0,90.00000001 +10.52,50.425,-3.566271499,10000,0,200.0014956,0,0,0,90.00000001 +10.53,50.425,-3.566243398,10000,0,199.9997163,0,0,0,90.00000001 +10.54,50.425,-3.566215298,10000,0,199.9986042,0,0,0,90.00000001 +10.55,50.425,-3.566187198,10000,0,199.9994939,0,0,0,90.00000001 +10.56,50.425,-3.566159097,10000,0,200.000606,0,0,0,90.00000001 +10.57,50.425,-3.566130996,10000,0,200.0003835,0,0,0,90.00000001 +10.58,50.425,-3.566102896,10000,0,199.9997163,0,0,0,90.00000001 +10.59,50.425,-3.566074795,10000,0,199.9994939,0,0,0,90.00000001 +10.6,50.425,-3.566046695,10000,0,199.9994939,0,0,0,90.00000001 +10.61,50.425,-3.566018594,10000,0,199.9997163,0,0,0,90.00000001 +10.62,50.425,-3.565990494,10000,0,200.0003835,0,0,0,90.00000001 +10.63,50.425,-3.565962393,10000,0,200.0008284,0,0,0,90.00000001 +10.64,50.425,-3.565934292,10000,0,200.0003835,0,0,0,90.00000001 +10.65,50.425,-3.565906192,10000,0,199.9997163,0,0,0,90.00000001 +10.66,50.425,-3.565878091,10000,0,199.9997163,0,0,0,90.00000001 +10.67,50.425,-3.565849991,10000,0,200.0003835,0,0,0,90.00000001 +10.68,50.425,-3.56582189,10000,0,200.0008284,0,0,0,90.00000001 +10.69,50.425,-3.565793789,10000,0,200.0003835,0,0,0,90.00000001 +10.7,50.425,-3.565765689,10000,0,199.9997163,0,0,0,90.00000001 +10.71,50.425,-3.565737588,10000,0,199.9994939,0,0,0,90.00000001 +10.72,50.425,-3.565709488,10000,0,199.9994939,0,0,0,90.00000001 +10.73,50.425,-3.565681387,10000,0,199.9997163,0,0,0,90.00000001 +10.74,50.425,-3.565653287,10000,0,200.0003835,0,0,0,90.00000001 +10.75,50.425,-3.565625186,10000,0,200.000606,0,0,0,90.00000001 +10.76,50.425,-3.565597085,10000,0,199.9994939,0,0,0,90.00000001 +10.77,50.425,-3.565568985,10000,0,199.9986042,0,0,0,90.00000001 +10.78,50.425,-3.565540885,10000,0,199.9997163,0,0,0,90.00000001 +10.79,50.425,-3.565512784,10000,0,200.0014956,0,0,0,90.00000001 +10.8,50.425,-3.565484683,10000,0,200.0014956,0,0,0,90.00000001 +10.81,50.425,-3.565456582,10000,0,199.9997163,0,0,0,90.00000001 +10.82,50.425,-3.565428482,10000,0,199.9986042,0,0,0,90.00000001 +10.83,50.425,-3.565400382,10000,0,199.9994939,0,0,0,90.00000001 +10.84,50.425,-3.565372281,10000,0,200.000606,0,0,0,90.00000001 +10.85,50.425,-3.56534418,10000,0,200.0003835,0,0,0,90.00000001 +10.86,50.425,-3.56531608,10000,0,199.9997163,0,0,0,90.00000001 +10.87,50.425,-3.565287979,10000,0,199.9994939,0,0,0,90.00000001 +10.88,50.425,-3.565259879,10000,0,199.9994939,0,0,0,90.00000001 +10.89,50.425,-3.565231778,10000,0,199.9997163,0,0,0,90.00000001 +10.9,50.425,-3.565203678,10000,0,200.0003835,0,0,0,90.00000001 +10.91,50.425,-3.565175577,10000,0,200.0008284,0,0,0,90.00000001 +10.92,50.425,-3.565147476,10000,0,200.0003835,0,0,0,90.00000001 +10.93,50.425,-3.565119376,10000,0,199.9997163,0,0,0,90.00000001 +10.94,50.425,-3.565091275,10000,0,199.9997163,0,0,0,90.00000001 +10.95,50.425,-3.565063175,10000,0,200.0003835,0,0,0,90.00000001 +10.96,50.425,-3.565035074,10000,0,200.0008284,0,0,0,90.00000001 +10.97,50.425,-3.565006973,10000,0,200.0003835,0,0,0,90.00000001 +10.98,50.425,-3.564978873,10000,0,199.9997163,0,0,0,90.00000001 +10.99,50.425,-3.564950772,10000,0,199.9994939,0,0,0,90.00000001 +11,50.425,-3.564922672,10000,0,199.9994939,0,0,0,90.00000001 +11.01,50.425,-3.564894571,10000,0,199.9997163,0,0,0,90.00000001 +11.02,50.425,-3.564866471,10000,0,200.0003835,0,0,0,90.00000001 +11.03,50.425,-3.56483837,10000,0,200.000606,0,0,0,90.00000001 +11.04,50.425,-3.564810269,10000,0,199.9994939,0,0,0,90.00000001 +11.05,50.425,-3.564782169,10000,0,199.9986042,0,0,0,90.00000001 +11.06,50.425,-3.564754069,10000,0,199.9997163,0,0,0,90.00000001 +11.07,50.425,-3.564725968,10000,0,200.0014956,0,0,0,90.00000001 +11.08,50.425,-3.564697867,10000,0,200.0014956,0,0,0,90.00000001 +11.09,50.425,-3.564669766,10000,0,199.9997163,0,0,0,90.00000001 +11.1,50.425,-3.564641666,10000,0,199.9986042,0,0,0,90.00000001 +11.11,50.425,-3.564613566,10000,0,199.9994939,0,0,0,90.00000001 +11.12,50.425,-3.564585465,10000,0,200.000606,0,0,0,90.00000001 +11.13,50.425,-3.564557364,10000,0,200.0003835,0,0,0,90.00000001 +11.14,50.425,-3.564529264,10000,0,199.9997163,0,0,0,90.00000001 +11.15,50.425,-3.564501163,10000,0,199.9994939,0,0,0,90.00000001 +11.16,50.425,-3.564473063,10000,0,199.9994939,0,0,0,90.00000001 +11.17,50.425,-3.564444962,10000,0,199.9997163,0,0,0,90.00000001 +11.18,50.425,-3.564416862,10000,0,200.0003835,0,0,0,90.00000001 +11.19,50.425,-3.564388761,10000,0,200.0008284,0,0,0,90.00000001 +11.2,50.425,-3.56436066,10000,0,200.0003835,0,0,0,90.00000001 +11.21,50.425,-3.56433256,10000,0,199.9997163,0,0,0,90.00000001 +11.22,50.425,-3.564304459,10000,0,199.9997163,0,0,0,90.00000001 +11.23,50.425,-3.564276359,10000,0,200.0003835,0,0,0,90.00000001 +11.24,50.425,-3.564248258,10000,0,200.0008284,0,0,0,90.00000001 +11.25,50.425,-3.564220157,10000,0,200.0003835,0,0,0,90.00000001 +11.26,50.425,-3.564192057,10000,0,199.9997163,0,0,0,90.00000001 +11.27,50.425,-3.564163956,10000,0,199.9994939,0,0,0,90.00000001 +11.28,50.425,-3.564135856,10000,0,199.9994939,0,0,0,90.00000001 +11.29,50.425,-3.564107755,10000,0,199.9997163,0,0,0,90.00000001 +11.3,50.425,-3.564079655,10000,0,200.0003835,0,0,0,90.00000001 +11.31,50.425,-3.564051554,10000,0,200.000606,0,0,0,90.00000001 +11.32,50.425,-3.564023453,10000,0,199.9994939,0,0,0,90.00000001 +11.33,50.425,-3.563995353,10000,0,199.9986042,0,0,0,90.00000001 +11.34,50.425,-3.563967253,10000,0,199.9997163,0,0,0,90.00000001 +11.35,50.425,-3.563939152,10000,0,200.0014956,0,0,0,90.00000001 +11.36,50.425,-3.563911051,10000,0,200.0014956,0,0,0,90.00000001 +11.37,50.425,-3.56388295,10000,0,199.9997163,0,0,0,90.00000001 +11.38,50.425,-3.56385485,10000,0,199.9986042,0,0,0,90.00000001 +11.39,50.425,-3.56382675,10000,0,199.9994939,0,0,0,90.00000001 +11.4,50.425,-3.563798649,10000,0,200.000606,0,0,0,90.00000001 +11.41,50.425,-3.563770548,10000,0,200.0003835,0,0,0,90.00000001 +11.42,50.425,-3.563742448,10000,0,199.9997163,0,0,0,90.00000001 +11.43,50.425,-3.563714347,10000,0,199.9994939,0,0,0,90.00000001 +11.44,50.425,-3.563686247,10000,0,199.9994939,0,0,0,90.00000001 +11.45,50.425,-3.563658146,10000,0,199.9997163,0,0,0,90.00000001 +11.46,50.425,-3.563630046,10000,0,200.0003835,0,0,0,90.00000001 +11.47,50.425,-3.563601945,10000,0,200.0008284,0,0,0,90.00000001 +11.48,50.425,-3.563573844,10000,0,200.0003835,0,0,0,90.00000001 +11.49,50.425,-3.563545744,10000,0,199.9997163,0,0,0,90.00000001 +11.5,50.425,-3.563517643,10000,0,199.9997163,0,0,0,90.00000001 +11.51,50.425,-3.563489543,10000,0,200.0003835,0,0,0,90.00000001 +11.52,50.425,-3.563461442,10000,0,200.0008284,0,0,0,90.00000001 +11.53,50.425,-3.563433341,10000,0,200.0003835,0,0,0,90.00000001 +11.54,50.425,-3.563405241,10000,0,199.9997163,0,0,0,90.00000001 +11.55,50.425,-3.56337714,10000,0,199.9994939,0,0,0,90.00000001 +11.56,50.425,-3.56334904,10000,0,199.9994939,0,0,0,90.00000001 +11.57,50.425,-3.563320939,10000,0,199.9997163,0,0,0,90.00000001 +11.58,50.425,-3.563292839,10000,0,200.0003835,0,0,0,90.00000001 +11.59,50.425,-3.563264738,10000,0,200.000606,0,0,0,90.00000001 +11.6,50.425,-3.563236637,10000,0,199.9994939,0,0,0,90.00000001 +11.61,50.425,-3.563208537,10000,0,199.9986042,0,0,0,90.00000001 +11.62,50.425,-3.563180437,10000,0,199.9997163,0,0,0,90.00000001 +11.63,50.425,-3.563152336,10000,0,200.0014956,0,0,0,90.00000001 +11.64,50.425,-3.563124235,10000,0,200.0014956,0,0,0,90.00000001 +11.65,50.425,-3.563096134,10000,0,199.9997163,0,0,0,90.00000001 +11.66,50.425,-3.563068034,10000,0,199.9986042,0,0,0,90.00000001 +11.67,50.425,-3.563039934,10000,0,199.9994939,0,0,0,90.00000001 +11.68,50.425,-3.563011833,10000,0,200.000606,0,0,0,90.00000001 +11.69,50.425,-3.562983732,10000,0,200.0003835,0,0,0,90.00000001 +11.7,50.425,-3.562955632,10000,0,199.9997163,0,0,0,90.00000001 +11.71,50.425,-3.562927531,10000,0,199.9994939,0,0,0,90.00000001 +11.72,50.425,-3.562899431,10000,0,199.9994939,0,0,0,90.00000001 +11.73,50.425,-3.56287133,10000,0,199.9997163,0,0,0,90.00000001 +11.74,50.425,-3.56284323,10000,0,200.0003835,0,0,0,90.00000001 +11.75,50.425,-3.562815129,10000,0,200.0008284,0,0,0,90.00000001 +11.76,50.425,-3.562787028,10000,0,200.0003835,0,0,0,90.00000001 +11.77,50.425,-3.562758928,10000,0,199.9997163,0,0,0,90.00000001 +11.78,50.425,-3.562730827,10000,0,199.9994939,0,0,0,90.00000001 +11.79,50.425,-3.562702727,10000,0,199.9994939,0,0,0,90.00000001 +11.8,50.425,-3.562674626,10000,0,199.9997163,0,0,0,90.00000001 +11.81,50.425,-3.562646526,10000,0,200.0003835,0,0,0,90.00000001 +11.82,50.425,-3.562618425,10000,0,200.000606,0,0,0,90.00000001 +11.83,50.425,-3.562590324,10000,0,199.9994939,0,0,0,90.00000001 +11.84,50.425,-3.562562224,10000,0,199.9986042,0,0,0,90.00000001 +11.85,50.425,-3.562534124,10000,0,199.9997163,0,0,0,90.00000001 +11.86,50.425,-3.562506023,10000,0,200.0014956,0,0,0,90.00000001 +11.87,50.425,-3.562477922,10000,0,200.0014956,0,0,0,90.00000001 +11.88,50.425,-3.562449821,10000,0,199.9997163,0,0,0,90.00000001 +11.89,50.425,-3.562421721,10000,0,199.9986042,0,0,0,90.00000001 +11.9,50.425,-3.562393621,10000,0,199.9994939,0,0,0,90.00000001 +11.91,50.425,-3.56236552,10000,0,200.000606,0,0,0,90.00000001 +11.92,50.425,-3.562337419,10000,0,200.0003835,0,0,0,90.00000001 +11.93,50.425,-3.562309319,10000,0,199.9997163,0,0,0,90.00000001 +11.94,50.425,-3.562281218,10000,0,199.9994939,0,0,0,90.00000001 +11.95,50.425,-3.562253118,10000,0,199.9994939,0,0,0,90.00000001 +11.96,50.425,-3.562225017,10000,0,199.9997163,0,0,0,90.00000001 +11.97,50.425,-3.562196917,10000,0,200.0003835,0,0,0,90.00000001 +11.98,50.425,-3.562168816,10000,0,200.0008284,0,0,0,90.00000001 +11.99,50.425,-3.562140715,10000,0,200.0003835,0,0,0,90.00000001 +12,50.425,-3.562112615,10000,0,199.9997163,0,0,0,90.00000001 +12.01,50.425,-3.562084514,10000,0,199.9997163,0,0,0,90.00000001 +12.02,50.425,-3.562056414,10000,0,200.0003835,0,0,0,90.00000001 +12.03,50.425,-3.562028313,10000,0,200.0008284,0,0,0,90.00000001 +12.04,50.425,-3.562000212,10000,0,200.0003835,0,0,0,90.00000001 +12.05,50.425,-3.561972112,10000,0,199.9997163,0,0,0,90.00000001 +12.06,50.425,-3.561944011,10000,0,199.9994939,0,0,0,90.00000001 +12.07,50.425,-3.561915911,10000,0,199.9994939,0,0,0,90.00000001 +12.08,50.425,-3.56188781,10000,0,199.9997163,0,0,0,90.00000001 +12.09,50.425,-3.56185971,10000,0,200.0003835,0,0,0,90.00000001 +12.1,50.425,-3.561831609,10000,0,200.000606,0,0,0,90.00000001 +12.11,50.425,-3.561803508,10000,0,199.9994939,0,0,0,90.00000001 +12.12,50.425,-3.561775408,10000,0,199.9986042,0,0,0,90.00000001 +12.13,50.425,-3.561747308,10000,0,199.9997163,0,0,0,90.00000001 +12.14,50.425,-3.561719207,10000,0,200.0014956,0,0,0,90.00000001 +12.15,50.425,-3.561691106,10000,0,200.0014956,0,0,0,90.00000001 +12.16,50.425,-3.561663005,10000,0,199.9997163,0,0,0,90.00000001 +12.17,50.425,-3.561634905,10000,0,199.9986042,0,0,0,90.00000001 +12.18,50.425,-3.561606805,10000,0,199.9994939,0,0,0,90.00000001 +12.19,50.425,-3.561578704,10000,0,200.000606,0,0,0,90.00000001 +12.2,50.425,-3.561550603,10000,0,200.0003835,0,0,0,90.00000001 +12.21,50.425,-3.561522503,10000,0,199.9997163,0,0,0,90.00000001 +12.22,50.425,-3.561494402,10000,0,199.9994939,0,0,0,90.00000001 +12.23,50.425,-3.561466302,10000,0,199.9994939,0,0,0,90.00000001 +12.24,50.425,-3.561438201,10000,0,199.9997163,0,0,0,90.00000001 +12.25,50.425,-3.561410101,10000,0,200.000606,0,0,0,90.00000001 +12.26,50.425,-3.561382,10000,0,200.001718,0,0,0,90.00000001 +12.27,50.425,-3.561353899,10000,0,200.0014956,0,0,0,90.00000001 +12.28,50.425,-3.561325798,10000,0,199.9997163,0,0,0,90.00000001 +12.29,50.425,-3.561297698,10000,0,199.9986042,0,0,0,90.00000001 +12.3,50.425,-3.561269598,10000,0,199.9994939,0,0,0,90.00000001 +12.31,50.425,-3.561241497,10000,0,200.000606,0,0,0,90.00000001 +12.32,50.425,-3.561213396,10000,0,200.0003835,0,0,0,90.00000001 +12.33,50.425,-3.561185296,10000,0,199.9997163,0,0,0,90.00000001 +12.34,50.425,-3.561157195,10000,0,199.9994939,0,0,0,90.00000001 +12.35,50.425,-3.561129095,10000,0,199.9994939,0,0,0,90.00000001 +12.36,50.425,-3.561100994,10000,0,199.9997163,0,0,0,90.00000001 +12.37,50.425,-3.561072894,10000,0,200.0003835,0,0,0,90.00000001 +12.38,50.425,-3.561044793,10000,0,200.0008284,0,0,0,90.00000001 +12.39,50.425,-3.561016692,10000,0,200.0003835,0,0,0,90.00000001 +12.4,50.425,-3.560988592,10000,0,199.9997163,0,0,0,90.00000001 +12.41,50.425,-3.560960491,10000,0,199.9997163,0,0,0,90.00000001 +12.42,50.425,-3.560932391,10000,0,200.0003835,0,0,0,90.00000001 +12.43,50.425,-3.56090429,10000,0,200.0008284,0,0,0,90.00000001 +12.44,50.425,-3.560876189,10000,0,200.0003835,0,0,0,90.00000001 +12.45,50.425,-3.560848089,10000,0,199.9997163,0,0,0,90.00000001 +12.46,50.425,-3.560819988,10000,0,199.9994939,0,0,0,90.00000001 +12.47,50.425,-3.560791888,10000,0,199.9994939,0,0,0,90.00000001 +12.48,50.425,-3.560763787,10000,0,199.9997163,0,0,0,90.00000001 +12.49,50.425,-3.560735687,10000,0,200.0003835,0,0,0,90.00000001 +12.5,50.425,-3.560707586,10000,0,200.000606,0,0,0,90.00000001 +12.51,50.425,-3.560679485,10000,0,199.9994939,0,0,0,90.00000001 +12.52,50.425,-3.560651385,10000,0,199.9986042,0,0,0,90.00000001 +12.53,50.425,-3.560623285,10000,0,199.9997163,0,0,0,90.00000001 +12.54,50.425,-3.560595184,10000,0,200.0014956,0,0,0,90.00000001 +12.55,50.425,-3.560567083,10000,0,200.0014956,0,0,0,90.00000001 +12.56,50.425,-3.560538982,10000,0,199.9997163,0,0,0,90.00000001 +12.57,50.425,-3.560510882,10000,0,199.9986042,0,0,0,90.00000001 +12.58,50.425,-3.560482782,10000,0,199.9994939,0,0,0,90.00000001 +12.59,50.425,-3.560454681,10000,0,200.000606,0,0,0,90.00000001 +12.6,50.425,-3.56042658,10000,0,200.0003835,0,0,0,90.00000001 +12.61,50.425,-3.56039848,10000,0,199.9997163,0,0,0,90.00000001 +12.62,50.425,-3.560370379,10000,0,199.9994939,0,0,0,90.00000001 +12.63,50.425,-3.560342279,10000,0,199.9994939,0,0,0,90.00000001 +12.64,50.425,-3.560314178,10000,0,199.9997163,0,0,0,90.00000001 +12.65,50.425,-3.560286078,10000,0,200.0003835,0,0,0,90.00000001 +12.66,50.425,-3.560257977,10000,0,200.0008284,0,0,0,90.00000001 +12.67,50.425,-3.560229876,10000,0,200.0003835,0,0,0,90.00000001 +12.68,50.425,-3.560201776,10000,0,199.9997163,0,0,0,90.00000001 +12.69,50.425,-3.560173675,10000,0,199.9997163,0,0,0,90.00000001 +12.7,50.425,-3.560145575,10000,0,200.0003835,0,0,0,90.00000001 +12.71,50.425,-3.560117474,10000,0,200.0008284,0,0,0,90.00000001 +12.72,50.425,-3.560089373,10000,0,200.0003835,0,0,0,90.00000001 +12.73,50.425,-3.560061273,10000,0,199.9997163,0,0,0,90.00000001 +12.74,50.425,-3.560033172,10000,0,199.9994939,0,0,0,90.00000001 +12.75,50.425,-3.560005072,10000,0,199.9994939,0,0,0,90.00000001 +12.76,50.425,-3.559976971,10000,0,199.9997163,0,0,0,90.00000001 +12.77,50.425,-3.559948871,10000,0,200.0003835,0,0,0,90.00000001 +12.78,50.425,-3.55992077,10000,0,200.000606,0,0,0,90.00000001 +12.79,50.425,-3.559892669,10000,0,199.9994939,0,0,0,90.00000001 +12.8,50.425,-3.559864569,10000,0,199.9986042,0,0,0,90.00000001 +12.81,50.425,-3.559836469,10000,0,199.9997163,0,0,0,90.00000001 +12.82,50.425,-3.559808368,10000,0,200.0014956,0,0,0,90.00000001 +12.83,50.425,-3.559780267,10000,0,200.0014956,0,0,0,90.00000001 +12.84,50.425,-3.559752166,10000,0,199.9997163,0,0,0,90.00000001 +12.85,50.425,-3.559724066,10000,0,199.9986042,0,0,0,90.00000001 +12.86,50.425,-3.559695966,10000,0,199.9994939,0,0,0,90.00000001 +12.87,50.425,-3.559667865,10000,0,200.000606,0,0,0,90.00000001 +12.88,50.425,-3.559639764,10000,0,200.0003835,0,0,0,90.00000001 +12.89,50.425,-3.559611664,10000,0,199.9997163,0,0,0,90.00000001 +12.9,50.425,-3.559583563,10000,0,199.9994939,0,0,0,90.00000001 +12.91,50.425,-3.559555463,10000,0,199.9994939,0,0,0,90.00000001 +12.92,50.425,-3.559527362,10000,0,199.9997163,0,0,0,90.00000001 +12.93,50.425,-3.559499262,10000,0,200.0003835,0,0,0,90.00000001 +12.94,50.425,-3.559471161,10000,0,200.0008284,0,0,0,90.00000001 +12.95,50.425,-3.55944306,10000,0,200.0003835,0,0,0,90.00000001 +12.96,50.425,-3.55941496,10000,0,199.9997163,0,0,0,90.00000001 +12.97,50.425,-3.559386859,10000,0,199.9997163,0,0,0,90.00000001 +12.98,50.425,-3.559358759,10000,0,200.0003835,0,0,0,90.00000001 +12.99,50.425,-3.559330658,10000,0,200.0008284,0,0,0,90.00000001 +13,50.425,-3.559302557,10000,0,200.0003835,0,0,0,90.00000001 +13.01,50.425,-3.559274457,10000,0,199.9997163,0,0,0,90.00000001 +13.02,50.425,-3.559246356,10000,0,199.9994939,0,0,0,90.00000001 +13.03,50.425,-3.559218256,10000,0,199.9994939,0,0,0,90.00000001 +13.04,50.425,-3.559190155,10000,0,199.9997163,0,0,0,90.00000001 +13.05,50.425,-3.559162055,10000,0,200.0003835,0,0,0,90.00000001 +13.06,50.425,-3.559133954,10000,0,200.000606,0,0,0,90.00000001 +13.07,50.425,-3.559105853,10000,0,199.9994939,0,0,0,90.00000001 +13.08,50.425,-3.559077753,10000,0,199.9986042,0,0,0,90.00000001 +13.09,50.425,-3.559049653,10000,0,199.9997163,0,0,0,90.00000001 +13.1,50.425,-3.559021552,10000,0,200.0014956,0,0,0,90.00000001 +13.11,50.425,-3.558993451,10000,0,200.0014956,0,0,0,90.00000001 +13.12,50.425,-3.55896535,10000,0,199.9997163,0,0,0,90.00000001 +13.13,50.425,-3.55893725,10000,0,199.9986042,0,0,0,90.00000001 +13.14,50.425,-3.55890915,10000,0,199.9994939,0,0,0,90.00000001 +13.15,50.425,-3.558881049,10000,0,200.000606,0,0,0,90.00000001 +13.16,50.425,-3.558852948,10000,0,200.0003835,0,0,0,90.00000001 +13.17,50.425,-3.558824848,10000,0,199.9997163,0,0,0,90.00000001 +13.18,50.425,-3.558796747,10000,0,199.9994939,0,0,0,90.00000001 +13.19,50.425,-3.558768647,10000,0,199.9994939,0,0,0,90.00000001 +13.2,50.425,-3.558740546,10000,0,199.9997163,0,0,0,90.00000001 +13.21,50.425,-3.558712446,10000,0,200.0003835,0,0,0,90.00000001 +13.22,50.425,-3.558684345,10000,0,200.0008284,0,0,0,90.00000001 +13.23,50.425,-3.558656244,10000,0,200.0003835,0,0,0,90.00000001 +13.24,50.425,-3.558628144,10000,0,199.9997163,0,0,0,90.00000001 +13.25,50.425,-3.558600043,10000,0,199.9997163,0,0,0,90.00000001 +13.26,50.425,-3.558571943,10000,0,200.0003835,0,0,0,90.00000001 +13.27,50.425,-3.558543842,10000,0,200.0008284,0,0,0,90.00000001 +13.28,50.425,-3.558515741,10000,0,200.0003835,0,0,0,90.00000001 +13.29,50.425,-3.558487641,10000,0,199.9997163,0,0,0,90.00000001 +13.3,50.425,-3.55845954,10000,0,199.9994939,0,0,0,90.00000001 +13.31,50.425,-3.55843144,10000,0,199.9994939,0,0,0,90.00000001 +13.32,50.425,-3.558403339,10000,0,199.9997163,0,0,0,90.00000001 +13.33,50.425,-3.558375239,10000,0,200.0003835,0,0,0,90.00000001 +13.34,50.425,-3.558347138,10000,0,200.000606,0,0,0,90.00000001 +13.35,50.425,-3.558319037,10000,0,199.9994939,0,0,0,90.00000001 +13.36,50.425,-3.558290937,10000,0,199.9986042,0,0,0,90.00000001 +13.37,50.425,-3.558262837,10000,0,199.9997163,0,0,0,90.00000001 +13.38,50.425,-3.558234736,10000,0,200.0014956,0,0,0,90.00000001 +13.39,50.425,-3.558206635,10000,0,200.0014956,0,0,0,90.00000001 +13.4,50.425,-3.558178534,10000,0,199.9997163,0,0,0,90.00000001 +13.41,50.425,-3.558150434,10000,0,199.9986042,0,0,0,90.00000001 +13.42,50.425,-3.558122334,10000,0,199.9994939,0,0,0,90.00000001 +13.43,50.425,-3.558094233,10000,0,200.000606,0,0,0,90.00000001 +13.44,50.425,-3.558066132,10000,0,200.0003835,0,0,0,90.00000001 +13.45,50.425,-3.558038032,10000,0,199.9997163,0,0,0,90.00000001 +13.46,50.425,-3.558009931,10000,0,199.9994939,0,0,0,90.00000001 +13.47,50.425,-3.557981831,10000,0,199.9994939,0,0,0,90.00000001 +13.48,50.425,-3.55795373,10000,0,199.9997163,0,0,0,90.00000001 +13.49,50.425,-3.55792563,10000,0,200.0003835,0,0,0,90.00000001 +13.5,50.425,-3.557897529,10000,0,200.0008284,0,0,0,90.00000001 +13.51,50.425,-3.557869428,10000,0,200.0003835,0,0,0,90.00000001 +13.52,50.425,-3.557841328,10000,0,199.9997163,0,0,0,90.00000001 +13.53,50.425,-3.557813227,10000,0,199.9997163,0,0,0,90.00000001 +13.54,50.425,-3.557785127,10000,0,200.0003835,0,0,0,90.00000001 +13.55,50.425,-3.557757026,10000,0,200.0008284,0,0,0,90.00000001 +13.56,50.425,-3.557728925,10000,0,200.0003835,0,0,0,90.00000001 +13.57,50.425,-3.557700825,10000,0,199.9997163,0,0,0,90.00000001 +13.58,50.425,-3.557672724,10000,0,199.9994939,0,0,0,90.00000001 +13.59,50.425,-3.557644624,10000,0,199.9994939,0,0,0,90.00000001 +13.6,50.425,-3.557616523,10000,0,199.9997163,0,0,0,90.00000001 +13.61,50.425,-3.557588423,10000,0,200.0003835,0,0,0,90.00000001 +13.62,50.425,-3.557560322,10000,0,200.000606,0,0,0,90.00000001 +13.63,50.425,-3.557532221,10000,0,199.9994939,0,0,0,90.00000001 +13.64,50.425,-3.557504121,10000,0,199.9986042,0,0,0,90.00000001 +13.65,50.425,-3.557476021,10000,0,199.9997163,0,0,0,90.00000001 +13.66,50.425,-3.55744792,10000,0,200.0014956,0,0,0,90.00000001 +13.67,50.425,-3.557419819,10000,0,200.0014956,0,0,0,90.00000001 +13.68,50.425,-3.557391718,10000,0,199.9997163,0,0,0,90.00000001 +13.69,50.425,-3.557363618,10000,0,199.9986042,0,0,0,90.00000001 +13.7,50.425,-3.557335518,10000,0,199.9994939,0,0,0,90.00000001 +13.71,50.425,-3.557307417,10000,0,200.000606,0,0,0,90.00000001 +13.72,50.425,-3.557279316,10000,0,200.0003835,0,0,0,90.00000001 +13.73,50.425,-3.557251216,10000,0,199.9997163,0,0,0,90.00000001 +13.74,50.425,-3.557223115,10000,0,199.9994939,0,0,0,90.00000001 +13.75,50.425,-3.557195015,10000,0,199.9994939,0,0,0,90.00000001 +13.76,50.425,-3.557166914,10000,0,199.9997163,0,0,0,90.00000001 +13.77,50.425,-3.557138814,10000,0,200.0003835,0,0,0,90.00000001 +13.78,50.425,-3.557110713,10000,0,200.0008284,0,0,0,90.00000001 +13.79,50.425,-3.557082612,10000,0,200.0003835,0,0,0,90.00000001 +13.8,50.425,-3.557054512,10000,0,199.9997163,0,0,0,90.00000001 +13.81,50.425,-3.557026411,10000,0,199.9994939,0,0,0,90.00000001 +13.82,50.425,-3.556998311,10000,0,199.9994939,0,0,0,90.00000001 +13.83,50.425,-3.55697021,10000,0,199.9997163,0,0,0,90.00000001 +13.84,50.425,-3.55694211,10000,0,200.0003835,0,0,0,90.00000001 +13.85,50.425,-3.556914009,10000,0,200.000606,0,0,0,90.00000001 +13.86,50.425,-3.556885908,10000,0,199.9994939,0,0,0,90.00000001 +13.87,50.425,-3.556857808,10000,0,199.9986042,0,0,0,90.00000001 +13.88,50.425,-3.556829708,10000,0,199.9997163,0,0,0,90.00000001 +13.89,50.425,-3.556801607,10000,0,200.0014956,0,0,0,90.00000001 +13.9,50.425,-3.556773506,10000,0,200.0014956,0,0,0,90.00000001 +13.91,50.425,-3.556745405,10000,0,199.9997163,0,0,0,90.00000001 +13.92,50.425,-3.556717305,10000,0,199.9986042,0,0,0,90.00000001 +13.93,50.425,-3.556689205,10000,0,199.9994939,0,0,0,90.00000001 +13.94,50.425,-3.556661104,10000,0,200.000606,0,0,0,90.00000001 +13.95,50.425,-3.556633003,10000,0,200.0003835,0,0,0,90.00000001 +13.96,50.425,-3.556604903,10000,0,199.9997163,0,0,0,90.00000001 +13.97,50.425,-3.556576802,10000,0,199.9994939,0,0,0,90.00000001 +13.98,50.425,-3.556548702,10000,0,199.9994939,0,0,0,90.00000001 +13.99,50.425,-3.556520601,10000,0,199.9997163,0,0,0,90.00000001 +14,50.425,-3.556492501,10000,0,200.0003835,0,0,0,90.00000001 +14.01,50.425,-3.5564644,10000,0,200.0008284,0,0,0,90.00000001 +14.02,50.425,-3.556436299,10000,0,200.0003835,0,0,0,90.00000001 +14.03,50.425,-3.556408199,10000,0,199.9997163,0,0,0,90.00000001 +14.04,50.425,-3.556380098,10000,0,199.9997163,0,0,0,90.00000001 +14.05,50.425,-3.556351998,10000,0,200.0003835,0,0,0,90.00000001 +14.06,50.425,-3.556323897,10000,0,200.0008284,0,0,0,90.00000001 +14.07,50.425,-3.556295796,10000,0,200.0003835,0,0,0,90.00000001 +14.08,50.425,-3.556267696,10000,0,199.9997163,0,0,0,90.00000001 +14.09,50.425,-3.556239595,10000,0,199.9994939,0,0,0,90.00000001 +14.1,50.425,-3.556211495,10000,0,199.9994939,0,0,0,90.00000001 +14.11,50.425,-3.556183394,10000,0,199.9997163,0,0,0,90.00000001 +14.12,50.425,-3.556155294,10000,0,200.0003835,0,0,0,90.00000001 +14.13,50.425,-3.556127193,10000,0,200.000606,0,0,0,90.00000001 +14.14,50.425,-3.556099092,10000,0,199.9994939,0,0,0,90.00000001 +14.15,50.425,-3.556070992,10000,0,199.9986042,0,0,0,90.00000001 +14.16,50.425,-3.556042892,10000,0,199.9997163,0,0,0,90.00000001 +14.17,50.425,-3.556014791,10000,0,200.0014956,0,0,0,90.00000001 +14.18,50.425,-3.55598669,10000,0,200.0014956,0,0,0,90.00000001 +14.19,50.425,-3.555958589,10000,0,199.9997163,0,0,0,90.00000001 +14.2,50.425,-3.555930489,10000,0,199.9986042,0,0,0,90.00000001 +14.21,50.425,-3.555902389,10000,0,199.9994939,0,0,0,90.00000001 +14.22,50.425,-3.555874288,10000,0,200.000606,0,0,0,90.00000001 +14.23,50.425,-3.555846187,10000,0,200.0003835,0,0,0,90.00000001 +14.24,50.425,-3.555818087,10000,0,199.9997163,0,0,0,90.00000001 +14.25,50.425,-3.555789986,10000,0,199.9994939,0,0,0,90.00000001 +14.26,50.425,-3.555761886,10000,0,199.9994939,0,0,0,90.00000001 +14.27,50.425,-3.555733785,10000,0,199.9997163,0,0,0,90.00000001 +14.28,50.425,-3.555705685,10000,0,200.0003835,0,0,0,90.00000001 +14.29,50.425,-3.555677584,10000,0,200.0008284,0,0,0,90.00000001 +14.3,50.425,-3.555649483,10000,0,200.0003835,0,0,0,90.00000001 +14.31,50.425,-3.555621383,10000,0,199.9997163,0,0,0,90.00000001 +14.32,50.425,-3.555593282,10000,0,199.9997163,0,0,0,90.00000001 +14.33,50.425,-3.555565182,10000,0,200.0003835,0,0,0,90.00000001 +14.34,50.425,-3.555537081,10000,0,200.0008284,0,0,0,90.00000001 +14.35,50.425,-3.55550898,10000,0,200.0003835,0,0,0,90.00000001 +14.36,50.425,-3.55548088,10000,0,199.9997163,0,0,0,90.00000001 +14.37,50.425,-3.555452779,10000,0,199.9994939,0,0,0,90.00000001 +14.38,50.425,-3.555424679,10000,0,199.9994939,0,0,0,90.00000001 +14.39,50.425,-3.555396578,10000,0,199.9997163,0,0,0,90.00000001 +14.4,50.425,-3.555368478,10000,0,200.0003835,0,0,0,90.00000001 +14.41,50.425,-3.555340377,10000,0,200.000606,0,0,0,90.00000001 +14.42,50.425,-3.555312276,10000,0,199.9994939,0,0,0,90.00000001 +14.43,50.425,-3.555284176,10000,0,199.9986042,0,0,0,90.00000001 +14.44,50.425,-3.555256076,10000,0,199.9997163,0,0,0,90.00000001 +14.45,50.425,-3.555227975,10000,0,200.0014956,0,0,0,90.00000001 +14.46,50.425,-3.555199874,10000,0,200.0014956,0,0,0,90.00000001 +14.47,50.425,-3.555171773,10000,0,199.9997163,0,0,0,90.00000001 +14.48,50.425,-3.555143673,10000,0,199.9986042,0,0,0,90.00000001 +14.49,50.425,-3.555115573,10000,0,199.9994939,0,0,0,90.00000001 +14.5,50.425,-3.555087472,10000,0,200.000606,0,0,0,90.00000001 +14.51,50.425,-3.555059371,10000,0,200.0003835,0,0,0,90.00000001 +14.52,50.425,-3.555031271,10000,0,199.9997163,0,0,0,90.00000001 +14.53,50.425,-3.55500317,10000,0,199.9994939,0,0,0,90.00000001 +14.54,50.425,-3.55497507,10000,0,199.9994939,0,0,0,90.00000001 +14.55,50.425,-3.554946969,10000,0,199.9997163,0,0,0,90.00000001 +14.56,50.425,-3.554918869,10000,0,200.0003835,0,0,0,90.00000001 +14.57,50.425,-3.554890768,10000,0,200.0008284,0,0,0,90.00000001 +14.58,50.425,-3.554862667,10000,0,200.0003835,0,0,0,90.00000001 +14.59,50.425,-3.554834567,10000,0,199.9997163,0,0,0,90.00000001 +14.6,50.425,-3.554806466,10000,0,199.9997163,0,0,0,90.00000001 +14.61,50.425,-3.554778366,10000,0,200.0003835,0,0,0,90.00000001 +14.62,50.425,-3.554750265,10000,0,200.0008284,0,0,0,90.00000001 +14.63,50.425,-3.554722164,10000,0,200.0003835,0,0,0,90.00000001 +14.64,50.425,-3.554694064,10000,0,199.9997163,0,0,0,90.00000001 +14.65,50.425,-3.554665963,10000,0,199.9994939,0,0,0,90.00000001 +14.66,50.425,-3.554637863,10000,0,199.9994939,0,0,0,90.00000001 +14.67,50.425,-3.554609762,10000,0,199.9997163,0,0,0,90.00000001 +14.68,50.425,-3.554581662,10000,0,200.0003835,0,0,0,90.00000001 +14.69,50.425,-3.554553561,10000,0,200.000606,0,0,0,90.00000001 +14.7,50.425,-3.55452546,10000,0,199.9994939,0,0,0,90.00000001 +14.71,50.425,-3.55449736,10000,0,199.9986042,0,0,0,90.00000001 +14.72,50.425,-3.55446926,10000,0,199.9997163,0,0,0,90.00000001 +14.73,50.425,-3.554441159,10000,0,200.0014956,0,0,0,90.00000001 +14.74,50.425,-3.554413058,10000,0,200.0014956,0,0,0,90.00000001 +14.75,50.425,-3.554384957,10000,0,199.9997163,0,0,0,90.00000001 +14.76,50.425,-3.554356857,10000,0,199.9986042,0,0,0,90.00000001 +14.77,50.425,-3.554328757,10000,0,199.9994939,0,0,0,90.00000001 +14.78,50.425,-3.554300656,10000,0,200.000606,0,0,0,90.00000001 +14.79,50.425,-3.554272555,10000,0,200.0003835,0,0,0,90.00000001 +14.8,50.425,-3.554244455,10000,0,199.9997163,0,0,0,90.00000001 +14.81,50.425,-3.554216354,10000,0,199.9994939,0,0,0,90.00000001 +14.82,50.425,-3.554188254,10000,0,199.9994939,0,0,0,90.00000001 +14.83,50.425,-3.554160153,10000,0,199.9997163,0,0,0,90.00000001 +14.84,50.425,-3.554132053,10000,0,200.0003835,0,0,0,90.00000001 +14.85,50.425,-3.554103952,10000,0,200.0008284,0,0,0,90.00000001 +14.86,50.425,-3.554075851,10000,0,200.0003835,0,0,0,90.00000001 +14.87,50.425,-3.554047751,10000,0,199.9997163,0,0,0,90.00000001 +14.88,50.425,-3.55401965,10000,0,199.9997163,0,0,0,90.00000001 +14.89,50.425,-3.55399155,10000,0,200.0003835,0,0,0,90.00000001 +14.9,50.425,-3.553963449,10000,0,200.0008284,0,0,0,90.00000001 +14.91,50.425,-3.553935348,10000,0,200.0003835,0,0,0,90.00000001 +14.92,50.425,-3.553907248,10000,0,199.9997163,0,0,0,90.00000001 +14.93,50.425,-3.553879147,10000,0,199.9994939,0,0,0,90.00000001 +14.94,50.425,-3.553851047,10000,0,199.9994939,0,0,0,90.00000001 +14.95,50.425,-3.553822946,10000,0,199.9997163,0,0,0,90.00000001 +14.96,50.425,-3.553794846,10000,0,200.0003835,0,0,0,90.00000001 +14.97,50.425,-3.553766745,10000,0,200.000606,0,0,0,90.00000001 +14.98,50.425,-3.553738644,10000,0,199.9994939,0,0,0,90.00000001 +14.99,50.425,-3.553710544,10000,0,199.9986042,0,0,0,90.00000001 +15,50.425,-3.553682444,10000,0,199.9997163,0,0,0,90.00000001 +15.01,50.425,-3.553654343,10000,0,200.0014956,0,0,0,90.00000001 +15.02,50.425,-3.553626242,10000,0,200.0014956,0,0,0,90.00000001 +15.03,50.425,-3.553598141,10000,0,199.9997163,0,0,0,90.00000001 +15.04,50.425,-3.553570041,10000,0,199.9986042,0,0,0,90.00000001 +15.05,50.425,-3.553541941,10000,0,199.9994939,0,0,0,90.00000001 +15.06,50.425,-3.55351384,10000,0,200.000606,0,0,0,90.00000001 +15.07,50.425,-3.553485739,10000,0,200.0003835,0,0,0,90.00000001 +15.08,50.425,-3.553457639,10000,0,199.9997163,0,0,0,90.00000001 +15.09,50.425,-3.553429538,10000,0,199.9994939,0,0,0,90.00000001 +15.1,50.425,-3.553401438,10000,0,199.9994939,0,0,0,90.00000001 +15.11,50.425,-3.553373337,10000,0,199.9997163,0,0,0,90.00000001 +15.12,50.425,-3.553345237,10000,0,200.0003835,0,0,0,90.00000001 +15.13,50.425,-3.553317136,10000,0,200.0008284,0,0,0,90.00000001 +15.14,50.425,-3.553289035,10000,0,200.0003835,0,0,0,90.00000001 +15.15,50.425,-3.553260935,10000,0,199.9997163,0,0,0,90.00000001 +15.16,50.425,-3.553232834,10000,0,199.9997163,0,0,0,90.00000001 +15.17,50.425,-3.553204734,10000,0,200.0003835,0,0,0,90.00000001 +15.18,50.425,-3.553176633,10000,0,200.0008284,0,0,0,90.00000001 +15.19,50.425,-3.553148532,10000,0,200.0003835,0,0,0,90.00000001 +15.2,50.425,-3.553120432,10000,0,199.9997163,0,0,0,90.00000001 +15.21,50.425,-3.553092331,10000,0,199.9994939,0,0,0,90.00000001 +15.22,50.425,-3.553064231,10000,0,199.9994939,0,0,0,90.00000001 +15.23,50.425,-3.55303613,10000,0,199.9997163,0,0,0,90.00000001 +15.24,50.425,-3.55300803,10000,0,200.0003835,0,0,0,90.00000001 +15.25,50.425,-3.552979929,10000,0,200.000606,0,0,0,90.00000001 +15.26,50.425,-3.552951828,10000,0,199.9994939,0,0,0,90.00000001 +15.27,50.425,-3.552923728,10000,0,199.9986042,0,0,0,90.00000001 +15.28,50.425,-3.552895628,10000,0,199.9997163,0,0,0,90.00000001 +15.29,50.425,-3.552867527,10000,0,200.0014956,0,0,0,90.00000001 +15.3,50.425,-3.552839426,10000,0,200.0014956,0,0,0,90.00000001 +15.31,50.425,-3.552811325,10000,0,199.9997163,0,0,0,90.00000001 +15.32,50.425,-3.552783225,10000,0,199.9986042,0,0,0,90.00000001 +15.33,50.425,-3.552755125,10000,0,199.9994939,0,0,0,90.00000001 +15.34,50.425,-3.552727024,10000,0,200.000606,0,0,0,90.00000001 +15.35,50.425,-3.552698923,10000,0,200.0003835,0,0,0,90.00000001 +15.36,50.425,-3.552670823,10000,0,199.9997163,0,0,0,90.00000001 +15.37,50.425,-3.552642722,10000,0,199.9994939,0,0,0,90.00000001 +15.38,50.425,-3.552614622,10000,0,199.9994939,0,0,0,90.00000001 +15.39,50.425,-3.552586521,10000,0,199.9997163,0,0,0,90.00000001 +15.4,50.425,-3.552558421,10000,0,200.0003835,0,0,0,90.00000001 +15.41,50.425,-3.55253032,10000,0,200.0008284,0,0,0,90.00000001 +15.42,50.425,-3.552502219,10000,0,200.0003835,0,0,0,90.00000001 +15.43,50.425,-3.552474119,10000,0,199.9997163,0,0,0,90.00000001 +15.44,50.425,-3.552446018,10000,0,199.9997163,0,0,0,90.00000001 +15.45,50.425,-3.552417918,10000,0,200.0003835,0,0,0,90.00000001 +15.46,50.425,-3.552389817,10000,0,200.0008284,0,0,0,90.00000001 +15.47,50.425,-3.552361716,10000,0,200.0003835,0,0,0,90.00000001 +15.48,50.425,-3.552333616,10000,0,199.9997163,0,0,0,90.00000001 +15.49,50.425,-3.552305515,10000,0,199.9994939,0,0,0,90.00000001 +15.5,50.425,-3.552277415,10000,0,199.9994939,0,0,0,90.00000001 +15.51,50.425,-3.552249314,10000,0,199.9997163,0,0,0,90.00000001 +15.52,50.425,-3.552221214,10000,0,200.0003835,0,0,0,90.00000001 +15.53,50.425,-3.552193113,10000,0,200.000606,0,0,0,90.00000001 +15.54,50.425,-3.552165012,10000,0,199.9994939,0,0,0,90.00000001 +15.55,50.425,-3.552136912,10000,0,199.9986042,0,0,0,90.00000001 +15.56,50.425,-3.552108812,10000,0,199.9997163,0,0,0,90.00000001 +15.57,50.425,-3.552080711,10000,0,200.0014956,0,0,0,90.00000001 +15.58,50.425,-3.55205261,10000,0,200.0014956,0,0,0,90.00000001 +15.59,50.425,-3.552024509,10000,0,199.9997163,0,0,0,90.00000001 +15.6,50.425,-3.551996409,10000,0,199.9986042,0,0,0,90.00000001 +15.61,50.425,-3.551968309,10000,0,199.9994939,0,0,0,90.00000001 +15.62,50.425,-3.551940208,10000,0,200.000606,0,0,0,90.00000001 +15.63,50.425,-3.551912107,10000,0,200.0003835,0,0,0,90.00000001 +15.64,50.425,-3.551884007,10000,0,199.9997163,0,0,0,90.00000001 +15.65,50.425,-3.551855906,10000,0,199.9994939,0,0,0,90.00000001 +15.66,50.425,-3.551827806,10000,0,199.9994939,0,0,0,90.00000001 +15.67,50.425,-3.551799705,10000,0,199.9997163,0,0,0,90.00000001 +15.68,50.425,-3.551771605,10000,0,200.0003835,0,0,0,90.00000001 +15.69,50.425,-3.551743504,10000,0,200.0008284,0,0,0,90.00000001 +15.7,50.425,-3.551715403,10000,0,200.0003835,0,0,0,90.00000001 +15.71,50.425,-3.551687303,10000,0,199.9997163,0,0,0,90.00000001 +15.72,50.425,-3.551659202,10000,0,199.9997163,0,0,0,90.00000001 +15.73,50.425,-3.551631102,10000,0,200.0003835,0,0,0,90.00000001 +15.74,50.425,-3.551603001,10000,0,200.0008284,0,0,0,90.00000001 +15.75,50.425,-3.5515749,10000,0,200.0003835,0,0,0,90.00000001 +15.76,50.425,-3.5515468,10000,0,199.9997163,0,0,0,90.00000001 +15.77,50.425,-3.551518699,10000,0,199.9994939,0,0,0,90.00000001 +15.78,50.425,-3.551490599,10000,0,199.9994939,0,0,0,90.00000001 +15.79,50.425,-3.551462498,10000,0,199.9997163,0,0,0,90.00000001 +15.8,50.425,-3.551434398,10000,0,200.0003835,0,0,0,90.00000001 +15.81,50.425,-3.551406297,10000,0,200.000606,0,0,0,90.00000001 +15.82,50.425,-3.551378196,10000,0,199.9994939,0,0,0,90.00000001 +15.83,50.425,-3.551350096,10000,0,199.9986042,0,0,0,90.00000001 +15.84,50.425,-3.551321996,10000,0,199.9994939,0,0,0,90.00000001 +15.85,50.425,-3.551293895,10000,0,200.000606,0,0,0,90.00000001 +15.86,50.425,-3.551265794,10000,0,200.000606,0,0,0,90.00000001 +15.87,50.425,-3.551237694,10000,0,200.000606,0,0,0,90.00000001 +15.88,50.425,-3.551209593,10000,0,200.000606,0,0,0,90.00000001 +15.89,50.425,-3.551181492,10000,0,199.9994939,0,0,0,90.00000001 +15.9,50.425,-3.551153392,10000,0,199.9986042,0,0,0,90.00000001 +15.91,50.425,-3.551125292,10000,0,199.9997163,0,0,0,90.00000001 +15.92,50.425,-3.551097191,10000,0,200.0014956,0,0,0,90.00000001 +15.93,50.425,-3.55106909,10000,0,200.0014956,0,0,0,90.00000001 +15.94,50.425,-3.551040989,10000,0,199.9997163,0,0,0,90.00000001 +15.95,50.425,-3.551012889,10000,0,199.9986042,0,0,0,90.00000001 +15.96,50.425,-3.550984789,10000,0,199.9994939,0,0,0,90.00000001 +15.97,50.425,-3.550956688,10000,0,200.000606,0,0,0,90.00000001 +15.98,50.425,-3.550928587,10000,0,200.0003835,0,0,0,90.00000001 +15.99,50.425,-3.550900487,10000,0,199.9997163,0,0,0,90.00000001 +16,50.425,-3.550872386,10000,0,199.9994939,0,0,0,90.00000001 +16.01,50.425,-3.550844286,10000,0,199.9994939,0,0,0,90.00000001 +16.02,50.425,-3.550816185,10000,0,199.9997163,0,0,0,90.00000001 +16.03,50.425,-3.550788085,10000,0,200.0003835,0,0,0,90.00000001 +16.04,50.425,-3.550759984,10000,0,200.0008284,0,0,0,90.00000001 +16.05,50.425,-3.550731883,10000,0,200.0003835,0,0,0,90.00000001 +16.06,50.425,-3.550703783,10000,0,199.9997163,0,0,0,90.00000001 +16.07,50.425,-3.550675682,10000,0,199.9997163,0,0,0,90.00000001 +16.08,50.425,-3.550647582,10000,0,200.0003835,0,0,0,90.00000001 +16.09,50.425,-3.550619481,10000,0,200.0008284,0,0,0,90.00000001 +16.1,50.425,-3.55059138,10000,0,200.0003835,0,0,0,90.00000001 +16.11,50.425,-3.55056328,10000,0,199.9997163,0,0,0,90.00000001 +16.12,50.425,-3.550535179,10000,0,199.9994939,0,0,0,90.00000001 +16.13,50.425,-3.550507079,10000,0,199.9994939,0,0,0,90.00000001 +16.14,50.425,-3.550478978,10000,0,199.9997163,0,0,0,90.00000001 +16.15,50.425,-3.550450878,10000,0,200.0003835,0,0,0,90.00000001 +16.16,50.425,-3.550422777,10000,0,200.000606,0,0,0,90.00000001 +16.17,50.425,-3.550394676,10000,0,199.9994939,0,0,0,90.00000001 +16.18,50.425,-3.550366576,10000,0,199.9986042,0,0,0,90.00000001 +16.19,50.425,-3.550338476,10000,0,199.9997163,0,0,0,90.00000001 +16.2,50.425,-3.550310375,10000,0,200.0014956,0,0,0,90.00000001 +16.21,50.425,-3.550282274,10000,0,200.0014956,0,0,0,90.00000001 +16.22,50.425,-3.550254173,10000,0,199.9997163,0,0,0,90.00000001 +16.23,50.425,-3.550226073,10000,0,199.9986042,0,0,0,90.00000001 +16.24,50.425,-3.550197973,10000,0,199.9994939,0,0,0,90.00000001 +16.25,50.425,-3.550169872,10000,0,200.000606,0,0,0,90.00000001 +16.26,50.425,-3.550141771,10000,0,200.0003835,0,0,0,90.00000001 +16.27,50.425,-3.550113671,10000,0,199.9997163,0,0,0,90.00000001 +16.28,50.425,-3.55008557,10000,0,199.9994939,0,0,0,90.00000001 +16.29,50.425,-3.55005747,10000,0,199.9994939,0,0,0,90.00000001 +16.3,50.425,-3.550029369,10000,0,199.9997163,0,0,0,90.00000001 +16.31,50.425,-3.550001269,10000,0,200.0003835,0,0,0,90.00000001 +16.32,50.425,-3.549973168,10000,0,200.0008284,0,0,0,90.00000001 +16.33,50.425,-3.549945067,10000,0,200.0003835,0,0,0,90.00000001 +16.34,50.425,-3.549916967,10000,0,199.9997163,0,0,0,90.00000001 +16.35,50.425,-3.549888866,10000,0,199.9997163,0,0,0,90.00000001 +16.36,50.425,-3.549860766,10000,0,200.0003835,0,0,0,90.00000001 +16.37,50.425,-3.549832665,10000,0,200.0008284,0,0,0,90.00000001 +16.38,50.425,-3.549804564,10000,0,200.0003835,0,0,0,90.00000001 +16.39,50.425,-3.549776464,10000,0,199.9997163,0,0,0,90.00000001 +16.4,50.425,-3.549748363,10000,0,199.9994939,0,0,0,90.00000001 +16.41,50.425,-3.549720263,10000,0,199.9994939,0,0,0,90.00000001 +16.42,50.425,-3.549692162,10000,0,199.9997163,0,0,0,90.00000001 +16.43,50.425,-3.549664062,10000,0,200.0003835,0,0,0,90.00000001 +16.44,50.425,-3.549635961,10000,0,200.000606,0,0,0,90.00000001 +16.45,50.425,-3.54960786,10000,0,199.9994939,0,0,0,90.00000001 +16.46,50.425,-3.54957976,10000,0,199.9986042,0,0,0,90.00000001 +16.47,50.425,-3.54955166,10000,0,199.9997163,0,0,0,90.00000001 +16.48,50.425,-3.549523559,10000,0,200.0014956,0,0,0,90.00000001 +16.49,50.425,-3.549495458,10000,0,200.0014956,0,0,0,90.00000001 +16.5,50.425,-3.549467357,10000,0,199.9997163,0,0,0,90.00000001 +16.51,50.425,-3.549439257,10000,0,199.9986042,0,0,0,90.00000001 +16.52,50.425,-3.549411157,10000,0,199.9994939,0,0,0,90.00000001 +16.53,50.425,-3.549383056,10000,0,200.000606,0,0,0,90.00000001 +16.54,50.425,-3.549354955,10000,0,200.0003835,0,0,0,90.00000001 +16.55,50.425,-3.549326855,10000,0,199.9997163,0,0,0,90.00000001 +16.56,50.425,-3.549298754,10000,0,199.9994939,0,0,0,90.00000001 +16.57,50.425,-3.549270654,10000,0,199.9994939,0,0,0,90.00000001 +16.58,50.425,-3.549242553,10000,0,199.9997163,0,0,0,90.00000001 +16.59,50.425,-3.549214453,10000,0,200.0003835,0,0,0,90.00000001 +16.6,50.425,-3.549186352,10000,0,200.0008284,0,0,0,90.00000001 +16.61,50.425,-3.549158251,10000,0,200.0003835,0,0,0,90.00000001 +16.62,50.425,-3.549130151,10000,0,199.9997163,0,0,0,90.00000001 +16.63,50.425,-3.54910205,10000,0,199.9997163,0,0,0,90.00000001 +16.64,50.425,-3.54907395,10000,0,200.0003835,0,0,0,90.00000001 +16.65,50.425,-3.549045849,10000,0,200.0008284,0,0,0,90.00000001 +16.66,50.425,-3.549017748,10000,0,200.0003835,0,0,0,90.00000001 +16.67,50.425,-3.548989648,10000,0,199.9997163,0,0,0,90.00000001 +16.68,50.425,-3.548961547,10000,0,199.9994939,0,0,0,90.00000001 +16.69,50.425,-3.548933447,10000,0,199.9994939,0,0,0,90.00000001 +16.7,50.425,-3.548905346,10000,0,199.9997163,0,0,0,90.00000001 +16.71,50.425,-3.548877246,10000,0,200.0003835,0,0,0,90.00000001 +16.72,50.425,-3.548849145,10000,0,200.000606,0,0,0,90.00000001 +16.73,50.425,-3.548821044,10000,0,199.9994939,0,0,0,90.00000001 +16.74,50.425,-3.548792944,10000,0,199.9986042,0,0,0,90.00000001 +16.75,50.425,-3.548764844,10000,0,199.9997163,0,0,0,90.00000001 +16.76,50.425,-3.548736743,10000,0,200.0014956,0,0,0,90.00000001 +16.77,50.425,-3.548708642,10000,0,200.0014956,0,0,0,90.00000001 +16.78,50.425,-3.548680541,10000,0,199.9997163,0,0,0,90.00000001 +16.79,50.425,-3.548652441,10000,0,199.9986042,0,0,0,90.00000001 +16.8,50.425,-3.548624341,10000,0,199.9994939,0,0,0,90.00000001 +16.81,50.425,-3.54859624,10000,0,200.000606,0,0,0,90.00000001 +16.82,50.425,-3.548568139,10000,0,200.0003835,0,0,0,90.00000001 +16.83,50.425,-3.548540039,10000,0,199.9997163,0,0,0,90.00000001 +16.84,50.425,-3.548511938,10000,0,199.9994939,0,0,0,90.00000001 +16.85,50.425,-3.548483838,10000,0,199.9994939,0,0,0,90.00000001 +16.86,50.425,-3.548455737,10000,0,199.9997163,0,0,0,90.00000001 +16.87,50.425,-3.548427637,10000,0,200.0003835,0,0,0,90.00000001 +16.88,50.425,-3.548399536,10000,0,200.0008284,0,0,0,90.00000001 +16.89,50.425,-3.548371435,10000,0,200.0003835,0,0,0,90.00000001 +16.9,50.425,-3.548343335,10000,0,199.9997163,0,0,0,90.00000001 +16.91,50.425,-3.548315234,10000,0,199.9997163,0,0,0,90.00000001 +16.92,50.425,-3.548287134,10000,0,200.0003835,0,0,0,90.00000001 +16.93,50.425,-3.548259033,10000,0,200.0008284,0,0,0,90.00000001 +16.94,50.425,-3.548230932,10000,0,200.0003835,0,0,0,90.00000001 +16.95,50.425,-3.548202832,10000,0,199.9997163,0,0,0,90.00000001 +16.96,50.425,-3.548174731,10000,0,199.9994939,0,0,0,90.00000001 +16.97,50.425,-3.548146631,10000,0,199.9994939,0,0,0,90.00000001 +16.98,50.425,-3.54811853,10000,0,199.9997163,0,0,0,90.00000001 +16.99,50.425,-3.54809043,10000,0,200.0003835,0,0,0,90.00000001 +17,50.425,-3.548062329,10000,0,200.000606,0,0,0,90.00000001 +17.01,50.425,-3.548034228,10000,0,199.9994939,0,0,0,90.00000001 +17.02,50.425,-3.548006128,10000,0,199.9986042,0,0,0,90.00000001 +17.03,50.425,-3.547978028,10000,0,199.9997163,0,0,0,90.00000001 +17.04,50.425,-3.547949927,10000,0,200.0014956,0,0,0,90.00000001 +17.05,50.425,-3.547921826,10000,0,200.0014956,0,0,0,90.00000001 +17.06,50.425,-3.547893725,10000,0,199.9997163,0,0,0,90.00000001 +17.07,50.425,-3.547865625,10000,0,199.9986042,0,0,0,90.00000001 +17.08,50.425,-3.547837525,10000,0,199.9994939,0,0,0,90.00000001 +17.09,50.425,-3.547809424,10000,0,200.000606,0,0,0,90.00000001 +17.1,50.425,-3.547781323,10000,0,200.0003835,0,0,0,90.00000001 +17.11,50.425,-3.547753223,10000,0,199.9997163,0,0,0,90.00000001 +17.12,50.425,-3.547725122,10000,0,199.9994939,0,0,0,90.00000001 +17.13,50.425,-3.547697022,10000,0,199.9994939,0,0,0,90.00000001 +17.14,50.425,-3.547668921,10000,0,199.9997163,0,0,0,90.00000001 +17.15,50.425,-3.547640821,10000,0,200.0003835,0,0,0,90.00000001 +17.16,50.425,-3.54761272,10000,0,200.0008284,0,0,0,90.00000001 +17.17,50.425,-3.547584619,10000,0,200.0003835,0,0,0,90.00000001 +17.18,50.425,-3.547556519,10000,0,199.9997163,0,0,0,90.00000001 +17.19,50.425,-3.547528418,10000,0,199.9997163,0,0,0,90.00000001 +17.2,50.425,-3.547500318,10000,0,200.0003835,0,0,0,90.00000001 +17.21,50.425,-3.547472217,10000,0,200.0008284,0,0,0,90.00000001 +17.22,50.425,-3.547444116,10000,0,200.0003835,0,0,0,90.00000001 +17.23,50.425,-3.547416016,10000,0,199.9997163,0,0,0,90.00000001 +17.24,50.425,-3.547387915,10000,0,199.9994939,0,0,0,90.00000001 +17.25,50.425,-3.547359815,10000,0,199.9994939,0,0,0,90.00000001 +17.26,50.425,-3.547331714,10000,0,199.9997163,0,0,0,90.00000001 +17.27,50.425,-3.547303614,10000,0,200.0003835,0,0,0,90.00000001 +17.28,50.425,-3.547275513,10000,0,200.000606,0,0,0,90.00000001 +17.29,50.425,-3.547247412,10000,0,199.9994939,0,0,0,90.00000001 +17.3,50.425,-3.547219312,10000,0,199.9986042,0,0,0,90.00000001 +17.31,50.425,-3.547191212,10000,0,199.9997163,0,0,0,90.00000001 +17.32,50.425,-3.547163111,10000,0,200.0014956,0,0,0,90.00000001 +17.33,50.425,-3.54713501,10000,0,200.0014956,0,0,0,90.00000001 +17.34,50.425,-3.547106909,10000,0,199.9997163,0,0,0,90.00000001 +17.35,50.425,-3.547078809,10000,0,199.9986042,0,0,0,90.00000001 +17.36,50.425,-3.547050709,10000,0,199.9994939,0,0,0,90.00000001 +17.37,50.425,-3.547022608,10000,0,200.000606,0,0,0,90.00000001 +17.38,50.425,-3.546994507,10000,0,200.0003835,0,0,0,90.00000001 +17.39,50.425,-3.546966407,10000,0,199.9997163,0,0,0,90.00000001 +17.4,50.425,-3.546938306,10000,0,199.9994939,0,0,0,90.00000001 +17.41,50.425,-3.546910206,10000,0,199.9994939,0,0,0,90.00000001 +17.42,50.425,-3.546882105,10000,0,199.9997163,0,0,0,90.00000001 +17.43,50.425,-3.546854005,10000,0,200.0003835,0,0,0,90.00000001 +17.44,50.425,-3.546825904,10000,0,200.0008284,0,0,0,90.00000001 +17.45,50.425,-3.546797803,10000,0,200.0003835,0,0,0,90.00000001 +17.46,50.425,-3.546769703,10000,0,199.9997163,0,0,0,90.00000001 +17.47,50.425,-3.546741602,10000,0,199.9997163,0,0,0,90.00000001 +17.48,50.425,-3.546713502,10000,0,200.0003835,0,0,0,90.00000001 +17.49,50.425,-3.546685401,10000,0,200.0008284,0,0,0,90.00000001 +17.5,50.425,-3.5466573,10000,0,200.0003835,0,0,0,90.00000001 +17.51,50.425,-3.5466292,10000,0,199.9997163,0,0,0,90.00000001 +17.52,50.425,-3.546601099,10000,0,199.9994939,0,0,0,90.00000001 +17.53,50.425,-3.546572999,10000,0,199.9994939,0,0,0,90.00000001 +17.54,50.425,-3.546544898,10000,0,199.9997163,0,0,0,90.00000001 +17.55,50.425,-3.546516798,10000,0,200.0003835,0,0,0,90.00000001 +17.56,50.425,-3.546488697,10000,0,200.000606,0,0,0,90.00000001 +17.57,50.425,-3.546460596,10000,0,199.9994939,0,0,0,90.00000001 +17.58,50.425,-3.546432496,10000,0,199.9986042,0,0,0,90.00000001 +17.59,50.425,-3.546404396,10000,0,199.9997163,0,0,0,90.00000001 +17.6,50.425,-3.546376295,10000,0,200.0014956,0,0,0,90.00000001 +17.61,50.425,-3.546348194,10000,0,200.0014956,0,0,0,90.00000001 +17.62,50.425,-3.546320093,10000,0,199.9997163,0,0,0,90.00000001 +17.63,50.425,-3.546291993,10000,0,199.9986042,0,0,0,90.00000001 +17.64,50.425,-3.546263893,10000,0,199.9994939,0,0,0,90.00000001 +17.65,50.425,-3.546235792,10000,0,200.000606,0,0,0,90.00000001 +17.66,50.425,-3.546207691,10000,0,200.0003835,0,0,0,90.00000001 +17.67,50.425,-3.546179591,10000,0,199.9997163,0,0,0,90.00000001 +17.68,50.425,-3.54615149,10000,0,199.9994939,0,0,0,90.00000001 +17.69,50.425,-3.54612339,10000,0,199.9994939,0,0,0,90.00000001 +17.7,50.425,-3.546095289,10000,0,199.9997163,0,0,0,90.00000001 +17.71,50.425,-3.546067189,10000,0,200.0003835,0,0,0,90.00000001 +17.72,50.425,-3.546039088,10000,0,200.0008284,0,0,0,90.00000001 +17.73,50.425,-3.546010987,10000,0,200.0003835,0,0,0,90.00000001 +17.74,50.425,-3.545982887,10000,0,199.9997163,0,0,0,90.00000001 +17.75,50.425,-3.545954786,10000,0,199.9997163,0,0,0,90.00000001 +17.76,50.425,-3.545926686,10000,0,200.0003835,0,0,0,90.00000001 +17.77,50.425,-3.545898585,10000,0,200.0008284,0,0,0,90.00000001 +17.78,50.425,-3.545870484,10000,0,200.0003835,0,0,0,90.00000001 +17.79,50.425,-3.545842384,10000,0,199.9997163,0,0,0,90.00000001 +17.8,50.425,-3.545814283,10000,0,199.9994939,0,0,0,90.00000001 +17.81,50.425,-3.545786183,10000,0,199.9994939,0,0,0,90.00000001 +17.82,50.425,-3.545758082,10000,0,199.9997163,0,0,0,90.00000001 +17.83,50.425,-3.545729982,10000,0,200.0003835,0,0,0,90.00000001 +17.84,50.425,-3.545701881,10000,0,200.000606,0,0,0,90.00000001 +17.85,50.425,-3.54567378,10000,0,199.9994939,0,0,0,90.00000001 +17.86,50.425,-3.54564568,10000,0,199.9986042,0,0,0,90.00000001 +17.87,50.425,-3.54561758,10000,0,199.9994939,0,0,0,90.00000001 +17.88,50.425,-3.545589479,10000,0,200.000606,0,0,0,90.00000001 +17.89,50.425,-3.545561378,10000,0,200.0003835,0,0,0,90.00000001 +17.9,50.425,-3.545533278,10000,0,199.9997163,0,0,0,90.00000001 +17.91,50.425,-3.545505177,10000,0,199.9994939,0,0,0,90.00000001 +17.92,50.425,-3.545477077,10000,0,199.9994939,0,0,0,90.00000001 +17.93,50.425,-3.545448976,10000,0,199.9997163,0,0,0,90.00000001 +17.94,50.425,-3.545420876,10000,0,200.0003835,0,0,0,90.00000001 +17.95,50.425,-3.545392775,10000,0,200.0008284,0,0,0,90.00000001 +17.96,50.425,-3.545364674,10000,0,200.0003835,0,0,0,90.00000001 +17.97,50.425,-3.545336574,10000,0,199.9997163,0,0,0,90.00000001 +17.98,50.425,-3.545308473,10000,0,199.9997163,0,0,0,90.00000001 +17.99,50.425,-3.545280373,10000,0,200.0003835,0,0,0,90.00000001 +18,50.425,-3.545252272,10000,0,200.0008284,0,0,0,90.00000001 +18.01,50.425,-3.545224171,10000,0,200.0003835,0,0,0,90.00000001 +18.02,50.425,-3.545196071,10000,0,199.9997163,0,0,0,90.00000001 +18.03,50.425,-3.54516797,10000,0,199.9994939,0,0,0,90.00000001 +18.04,50.425,-3.54513987,10000,0,199.9994939,0,0,0,90.00000001 +18.05,50.425,-3.545111769,10000,0,199.9997163,0,0,0,90.00000001 +18.06,50.425,-3.545083669,10000,0,200.0003835,0,0,0,90.00000001 +18.07,50.425,-3.545055568,10000,0,200.000606,0,0,0,90.00000001 +18.08,50.425,-3.545027467,10000,0,199.9994939,0,0,0,90.00000001 +18.09,50.425,-3.544999367,10000,0,199.9986042,0,0,0,90.00000001 +18.1,50.425,-3.544971267,10000,0,199.9997163,0,0,0,90.00000001 +18.11,50.425,-3.544943166,10000,0,200.0014956,0,0,0,90.00000001 +18.12,50.425,-3.544915065,10000,0,200.0014956,0,0,0,90.00000001 +18.13,50.425,-3.544886964,10000,0,199.9997163,0,0,0,90.00000001 +18.14,50.425,-3.544858864,10000,0,199.9986042,0,0,0,90.00000001 +18.15,50.425,-3.544830764,10000,0,199.9994939,0,0,0,90.00000001 +18.16,50.425,-3.544802663,10000,0,200.000606,0,0,0,90.00000001 +18.17,50.425,-3.544774562,10000,0,200.0003835,0,0,0,90.00000001 +18.18,50.425,-3.544746462,10000,0,199.9997163,0,0,0,90.00000001 +18.19,50.425,-3.544718361,10000,0,199.9994939,0,0,0,90.00000001 +18.2,50.425,-3.544690261,10000,0,199.9994939,0,0,0,90.00000001 +18.21,50.425,-3.54466216,10000,0,199.9997163,0,0,0,90.00000001 +18.22,50.425,-3.54463406,10000,0,200.0003835,0,0,0,90.00000001 +18.23,50.425,-3.544605959,10000,0,200.0008284,0,0,0,90.00000001 +18.24,50.425,-3.544577858,10000,0,200.0003835,0,0,0,90.00000001 +18.25,50.425,-3.544549758,10000,0,199.9997163,0,0,0,90.00000001 +18.26,50.425,-3.544521657,10000,0,199.9997163,0,0,0,90.00000001 +18.27,50.425,-3.544493557,10000,0,200.0003835,0,0,0,90.00000001 +18.28,50.425,-3.544465456,10000,0,200.0008284,0,0,0,90.00000001 +18.29,50.425,-3.544437355,10000,0,200.0003835,0,0,0,90.00000001 +18.3,50.425,-3.544409255,10000,0,199.9997163,0,0,0,90.00000001 +18.31,50.425,-3.544381154,10000,0,199.9994939,0,0,0,90.00000001 +18.32,50.425,-3.544353054,10000,0,199.9994939,0,0,0,90.00000001 +18.33,50.425,-3.544324953,10000,0,199.9997163,0,0,0,90.00000001 +18.34,50.425,-3.544296853,10000,0,200.0003835,0,0,0,90.00000001 +18.35,50.425,-3.544268752,10000,0,200.000606,0,0,0,90.00000001 +18.36,50.425,-3.544240651,10000,0,199.9994939,0,0,0,90.00000001 +18.37,50.425,-3.544212551,10000,0,199.9986042,0,0,0,90.00000001 +18.38,50.425,-3.544184451,10000,0,199.9997163,0,0,0,90.00000001 +18.39,50.425,-3.54415635,10000,0,200.0014956,0,0,0,90.00000001 +18.4,50.425,-3.544128249,10000,0,200.0014956,0,0,0,90.00000001 +18.41,50.425,-3.544100148,10000,0,199.9997163,0,0,0,90.00000001 +18.42,50.425,-3.544072048,10000,0,199.9986042,0,0,0,90.00000001 +18.43,50.425,-3.544043948,10000,0,199.9994939,0,0,0,90.00000001 +18.44,50.425,-3.544015847,10000,0,200.000606,0,0,0,90.00000001 +18.45,50.425,-3.543987746,10000,0,200.0003835,0,0,0,90.00000001 +18.46,50.425,-3.543959646,10000,0,199.9997163,0,0,0,90.00000001 +18.47,50.425,-3.543931545,10000,0,199.9994939,0,0,0,90.00000001 +18.48,50.425,-3.543903445,10000,0,199.9994939,0,0,0,90.00000001 +18.49,50.425,-3.543875344,10000,0,199.9997163,0,0,0,90.00000001 +18.5,50.425,-3.543847244,10000,0,200.0003835,0,0,0,90.00000001 +18.51,50.425,-3.543819143,10000,0,200.0008284,0,0,0,90.00000001 +18.52,50.425,-3.543791042,10000,0,200.0003835,0,0,0,90.00000001 +18.53,50.425,-3.543762942,10000,0,199.9997163,0,0,0,90.00000001 +18.54,50.425,-3.543734841,10000,0,199.9997163,0,0,0,90.00000001 +18.55,50.425,-3.543706741,10000,0,200.0003835,0,0,0,90.00000001 +18.56,50.425,-3.54367864,10000,0,200.0008284,0,0,0,90.00000001 +18.57,50.425,-3.543650539,10000,0,200.0003835,0,0,0,90.00000001 +18.58,50.425,-3.543622439,10000,0,199.9997163,0,0,0,90.00000001 +18.59,50.425,-3.543594338,10000,0,199.9994939,0,0,0,90.00000001 +18.6,50.425,-3.543566238,10000,0,199.9994939,0,0,0,90.00000001 +18.61,50.425,-3.543538137,10000,0,199.9997163,0,0,0,90.00000001 +18.62,50.425,-3.543510037,10000,0,200.0003835,0,0,0,90.00000001 +18.63,50.425,-3.543481936,10000,0,200.000606,0,0,0,90.00000001 +18.64,50.425,-3.543453835,10000,0,199.9994939,0,0,0,90.00000001 +18.65,50.425,-3.543425735,10000,0,199.9986042,0,0,0,90.00000001 +18.66,50.425,-3.543397635,10000,0,199.9997163,0,0,0,90.00000001 +18.67,50.425,-3.543369534,10000,0,200.0014956,0,0,0,90.00000001 +18.68,50.425,-3.543341433,10000,0,200.0014956,0,0,0,90.00000001 +18.69,50.425,-3.543313332,10000,0,199.9997163,0,0,0,90.00000001 +18.7,50.425,-3.543285232,10000,0,199.9986042,0,0,0,90.00000001 +18.71,50.425,-3.543257132,10000,0,199.9994939,0,0,0,90.00000001 +18.72,50.425,-3.543229031,10000,0,200.000606,0,0,0,90.00000001 +18.73,50.425,-3.54320093,10000,0,200.0003835,0,0,0,90.00000001 +18.74,50.425,-3.54317283,10000,0,199.9997163,0,0,0,90.00000001 +18.75,50.425,-3.543144729,10000,0,199.9994939,0,0,0,90.00000001 +18.76,50.425,-3.543116629,10000,0,199.9994939,0,0,0,90.00000001 +18.77,50.425,-3.543088528,10000,0,199.9997163,0,0,0,90.00000001 +18.78,50.425,-3.543060428,10000,0,200.0003835,0,0,0,90.00000001 +18.79,50.425,-3.543032327,10000,0,200.0008284,0,0,0,90.00000001 +18.8,50.425,-3.543004226,10000,0,200.0003835,0,0,0,90.00000001 +18.81,50.425,-3.542976126,10000,0,199.9997163,0,0,0,90.00000001 +18.82,50.425,-3.542948025,10000,0,199.9997163,0,0,0,90.00000001 +18.83,50.425,-3.542919925,10000,0,200.0003835,0,0,0,90.00000001 +18.84,50.425,-3.542891824,10000,0,200.0008284,0,0,0,90.00000001 +18.85,50.425,-3.542863723,10000,0,200.0003835,0,0,0,90.00000001 +18.86,50.425,-3.542835623,10000,0,199.9997163,0,0,0,90.00000001 +18.87,50.425,-3.542807522,10000,0,199.9994939,0,0,0,90.00000001 +18.88,50.425,-3.542779422,10000,0,199.9994939,0,0,0,90.00000001 +18.89,50.425,-3.542751321,10000,0,199.9997163,0,0,0,90.00000001 +18.9,50.425,-3.542723221,10000,0,200.0003835,0,0,0,90.00000001 +18.91,50.425,-3.54269512,10000,0,200.000606,0,0,0,90.00000001 +18.92,50.425,-3.542667019,10000,0,199.9994939,0,0,0,90.00000001 +18.93,50.425,-3.542638919,10000,0,199.9986042,0,0,0,90.00000001 +18.94,50.425,-3.542610819,10000,0,199.9997163,0,0,0,90.00000001 +18.95,50.425,-3.542582718,10000,0,200.0014956,0,0,0,90.00000001 +18.96,50.425,-3.542554617,10000,0,200.0014956,0,0,0,90.00000001 +18.97,50.425,-3.542526516,10000,0,199.9997163,0,0,0,90.00000001 +18.98,50.425,-3.542498416,10000,0,199.9986042,0,0,0,90.00000001 +18.99,50.425,-3.542470316,10000,0,199.9994939,0,0,0,90.00000001 +19,50.425,-3.542442215,10000,0,200.000606,0,0,0,90.00000001 +19.01,50.425,-3.542414114,10000,0,200.0003835,0,0,0,90.00000001 +19.02,50.425,-3.542386014,10000,0,199.9997163,0,0,0,90.00000001 +19.03,50.425,-3.542357913,10000,0,199.9994939,0,0,0,90.00000001 +19.04,50.425,-3.542329813,10000,0,199.9994939,0,0,0,90.00000001 +19.05,50.425,-3.542301712,10000,0,199.9997163,0,0,0,90.00000001 +19.06,50.425,-3.542273612,10000,0,200.0003835,0,0,0,90.00000001 +19.07,50.425,-3.542245511,10000,0,200.0008284,0,0,0,90.00000001 +19.08,50.425,-3.54221741,10000,0,200.0003835,0,0,0,90.00000001 +19.09,50.425,-3.54218931,10000,0,199.9997163,0,0,0,90.00000001 +19.1,50.425,-3.542161209,10000,0,199.9997163,0,0,0,90.00000001 +19.11,50.425,-3.542133109,10000,0,200.0003835,0,0,0,90.00000001 +19.12,50.425,-3.542105008,10000,0,200.0008284,0,0,0,90.00000001 +19.13,50.425,-3.542076907,10000,0,200.0003835,0,0,0,90.00000001 +19.14,50.425,-3.542048807,10000,0,199.9997163,0,0,0,90.00000001 +19.15,50.425,-3.542020706,10000,0,199.9994939,0,0,0,90.00000001 +19.16,50.425,-3.541992606,10000,0,199.9994939,0,0,0,90.00000001 +19.17,50.425,-3.541964505,10000,0,199.9997163,0,0,0,90.00000001 +19.18,50.425,-3.541936405,10000,0,200.0003835,0,0,0,90.00000001 +19.19,50.425,-3.541908304,10000,0,200.000606,0,0,0,90.00000001 +19.2,50.425,-3.541880203,10000,0,199.9994939,0,0,0,90.00000001 +19.21,50.425,-3.541852103,10000,0,199.9986042,0,0,0,90.00000001 +19.22,50.425,-3.541824003,10000,0,199.9997163,0,0,0,90.00000001 +19.23,50.425,-3.541795902,10000,0,200.0014956,0,0,0,90.00000001 +19.24,50.425,-3.541767801,10000,0,200.0014956,0,0,0,90.00000001 +19.25,50.425,-3.5417397,10000,0,199.9997163,0,0,0,90.00000001 +19.26,50.425,-3.5417116,10000,0,199.9986042,0,0,0,90.00000001 +19.27,50.425,-3.5416835,10000,0,199.9994939,0,0,0,90.00000001 +19.28,50.425,-3.541655399,10000,0,200.000606,0,0,0,90.00000001 +19.29,50.425,-3.541627298,10000,0,200.0003835,0,0,0,90.00000001 +19.3,50.425,-3.541599198,10000,0,199.9997163,0,0,0,90.00000001 +19.31,50.425,-3.541571097,10000,0,199.9994939,0,0,0,90.00000001 +19.32,50.425,-3.541542997,10000,0,199.9994939,0,0,0,90.00000001 +19.33,50.425,-3.541514896,10000,0,199.9997163,0,0,0,90.00000001 +19.34,50.425,-3.541486796,10000,0,200.0003835,0,0,0,90.00000001 +19.35,50.425,-3.541458695,10000,0,200.0008284,0,0,0,90.00000001 +19.36,50.425,-3.541430594,10000,0,200.0003835,0,0,0,90.00000001 +19.37,50.425,-3.541402494,10000,0,199.9997163,0,0,0,90.00000001 +19.38,50.425,-3.541374393,10000,0,199.9997163,0,0,0,90.00000001 +19.39,50.425,-3.541346293,10000,0,200.0003835,0,0,0,90.00000001 +19.4,50.425,-3.541318192,10000,0,200.0008284,0,0,0,90.00000001 +19.41,50.425,-3.541290091,10000,0,200.0003835,0,0,0,90.00000001 +19.42,50.425,-3.541261991,10000,0,199.9997163,0,0,0,90.00000001 +19.43,50.425,-3.54123389,10000,0,199.9994939,0,0,0,90.00000001 +19.44,50.425,-3.54120579,10000,0,199.9994939,0,0,0,90.00000001 +19.45,50.425,-3.541177689,10000,0,199.9997163,0,0,0,90.00000001 +19.46,50.425,-3.541149589,10000,0,200.0003835,0,0,0,90.00000001 +19.47,50.425,-3.541121488,10000,0,200.000606,0,0,0,90.00000001 +19.48,50.425,-3.541093387,10000,0,199.9994939,0,0,0,90.00000001 +19.49,50.425,-3.541065287,10000,0,199.9986042,0,0,0,90.00000001 +19.5,50.425,-3.541037187,10000,0,199.9997163,0,0,0,90.00000001 +19.51,50.425,-3.541009086,10000,0,200.0014956,0,0,0,90.00000001 +19.52,50.425,-3.540980985,10000,0,200.001718,0,0,0,90.00000001 +19.53,50.425,-3.540952884,10000,0,200.000606,0,0,0,90.00000001 +19.54,50.425,-3.540924784,10000,0,199.9997163,0,0,0,90.00000001 +19.55,50.425,-3.540896683,10000,0,199.9994939,0,0,0,90.00000001 +19.56,50.425,-3.540868583,10000,0,199.9994939,0,0,0,90.00000001 +19.57,50.425,-3.540840482,10000,0,199.9997163,0,0,0,90.00000001 +19.58,50.425,-3.540812382,10000,0,200.0003835,0,0,0,90.00000001 +19.59,50.425,-3.540784281,10000,0,200.000606,0,0,0,90.00000001 +19.6,50.425,-3.54075618,10000,0,199.9994939,0,0,0,90.00000001 +19.61,50.425,-3.54072808,10000,0,199.9986042,0,0,0,90.00000001 +19.62,50.425,-3.54069998,10000,0,199.9997163,0,0,0,90.00000001 +19.63,50.425,-3.540671879,10000,0,200.0014956,0,0,0,90.00000001 +19.64,50.425,-3.540643778,10000,0,200.0014956,0,0,0,90.00000001 +19.65,50.425,-3.540615677,10000,0,199.9997163,0,0,0,90.00000001 +19.66,50.425,-3.540587577,10000,0,199.9986042,0,0,0,90.00000001 +19.67,50.425,-3.540559477,10000,0,199.9994939,0,0,0,90.00000001 +19.68,50.425,-3.540531376,10000,0,200.000606,0,0,0,90.00000001 +19.69,50.425,-3.540503275,10000,0,200.0003835,0,0,0,90.00000001 +19.7,50.425,-3.540475175,10000,0,199.9997163,0,0,0,90.00000001 +19.71,50.425,-3.540447074,10000,0,199.9994939,0,0,0,90.00000001 +19.72,50.425,-3.540418974,10000,0,199.9994939,0,0,0,90.00000001 +19.73,50.425,-3.540390873,10000,0,199.9997163,0,0,0,90.00000001 +19.74,50.425,-3.540362773,10000,0,200.0003835,0,0,0,90.00000001 +19.75,50.425,-3.540334672,10000,0,200.0008284,0,0,0,90.00000001 +19.76,50.425,-3.540306571,10000,0,200.0003835,0,0,0,90.00000001 +19.77,50.425,-3.540278471,10000,0,199.9997163,0,0,0,90.00000001 +19.78,50.425,-3.54025037,10000,0,199.9997163,0,0,0,90.00000001 +19.79,50.425,-3.54022227,10000,0,200.0003835,0,0,0,90.00000001 +19.8,50.425,-3.540194169,10000,0,200.0008284,0,0,0,90.00000001 +19.81,50.425,-3.540166068,10000,0,200.0003835,0,0,0,90.00000001 +19.82,50.425,-3.540137968,10000,0,199.9997163,0,0,0,90.00000001 +19.83,50.425,-3.540109867,10000,0,199.9994939,0,0,0,90.00000001 +19.84,50.425,-3.540081767,10000,0,199.9994939,0,0,0,90.00000001 +19.85,50.425,-3.540053666,10000,0,199.9997163,0,0,0,90.00000001 +19.86,50.425,-3.540025566,10000,0,200.0003835,0,0,0,90.00000001 +19.87,50.425,-3.539997465,10000,0,200.000606,0,0,0,90.00000001 +19.88,50.425,-3.539969364,10000,0,199.9994939,0,0,0,90.00000001 +19.89,50.425,-3.539941264,10000,0,199.9986042,0,0,0,90.00000001 +19.9,50.425,-3.539913164,10000,0,199.9994939,0,0,0,90.00000001 +19.91,50.425,-3.539885063,10000,0,200.000606,0,0,0,90.00000001 +19.92,50.425,-3.539856962,10000,0,200.0003835,0,0,0,90.00000001 +19.93,50.425,-3.539828862,10000,0,199.9997163,0,0,0,90.00000001 +19.94,50.425,-3.539800761,10000,0,199.9994939,0,0,0,90.00000001 +19.95,50.425,-3.539772661,10000,0,199.9994939,0,0,0,90.00000001 +19.96,50.425,-3.53974456,10000,0,199.9997163,0,0,0,90.00000001 +19.97,50.425,-3.53971646,10000,0,200.0003835,0,0,0,90.00000001 +19.98,50.425,-3.539688359,10000,0,200.0008284,0,0,0,90.00000001 +19.99,50.425,-3.539660258,10000,0,200.0003835,0,0,0,90.00000001 +20,50.425,-3.539632158,10000,0,199.9997163,0,0,0,90.00000001 +20.01,50.425,-3.539604057,10000,0,199.9997163,0,0.005415253,0,90.00000064 +20.02,50.425,-3.539575957,10000,0,200.0003835,0,0.043321912,0,90.00001061 +20.03,50.425,-3.539547856,10000,0,200.0008284,0,0.146211438,0,90.00005381 +20.04,50.425,-3.539519755,10000,0,200.0003835,0,0.346575237,0,90.00017001 +20.05,50.425,-3.539491655,10000,0,199.9997163,0,0.676904772,0,90.00041506 +20.06,50.425,-3.539463554,10000,0,199.9994939,0,1.169691448,0,90.00086065 +20.07,50.425,-3.539435454,10000,0,199.9994939,0,1.846596163,0,90.00159324 +20.08,50.425,-3.539407353,10000,-0.003481616,199.9997163,0,2.685958076,0,90.0026995 +20.09,50.425,-3.539379253,10000,-0.017408081,200.0003835,0,3.655285668,0,90.00425165 +20.1,50.425,-3.539351152,10000,-0.034816162,200.000606,0,4.722087589,0,90.00630656 +20.11,50.42499999,-3.539323051,10000,-0.038297778,199.9994939,0,5.853872379,0,90.00890578 +20.12,50.42499999,-3.539294951,10000,-0.03829778,199.9986043,0,7.018148516,0,90.01207544 +20.13,50.42499999,-3.539266851,10000,-0.059187489,199.9997164,0,8.182424711,0,90.01582619 +20.14,50.42499998,-3.53923875,10000,-0.090522057,200.0014957,0,9.3142095,0,90.02015311 +20.15,50.42499997,-3.539210649,10000,-0.10793016,200.0014957,0,10.38101136,0,90.02503506 +20.16,50.42499996,-3.539182548,10000,-0.111411787,199.9997165,0,11.35033901,0,90.03043444 +20.17,50.42499995,-3.539154448,10000,-0.114893408,199.9986044,0,12.18970087,0,90.0362966 +20.18,50.42499994,-3.539126348,10000,-0.132301498,199.9994941,0,12.86660564,0,90.04254923 +20.19,50.42499993,-3.539098247,10000,-0.167117673,200.0006063,0,13.35939232,0,90.04910364 +20.2,50.42499991,-3.539070146,10000,-0.201933846,200.0003839,0,13.68972185,0,90.05586976 +20.21,50.42499989,-3.539042046,10000,-0.222823557,199.9997168,0,13.89008565,0,90.06277235 +20.22,50.42499987,-3.539013945,10000,-0.240231658,199.9994944,0,13.99297518,0,90.06975241 +20.23,50.42499985,-3.538985845,10000,-0.261121366,199.9994945,0,14.03088184,0,90.07676776 +20.24,50.42499982,-3.538957744,10000,-0.282011056,199.999717,0,14.03629709,0,90.08379297 +20.25,50.4249998,-3.538929644,10000,-0.313345602,200.0003844,0,14.03629709,0,90.09081892 +20.26,50.42499977,-3.538901543,10000,-0.355125023,200.0008294,0,14.03629709,0,90.09784482 +20.27,50.42499973,-3.538873442,10000,-0.382977988,200.0003847,0,14.03629709,0,90.10487077 +20.28,50.4249997,-3.538845342,10000,-0.389941238,199.9994952,0,14.03629709,0,90.11189666 +20.29,50.42499966,-3.538817241,10000,-0.396904471,199.9986056,0,14.03629709,0,90.11892262 +20.3,50.42499963,-3.538789141,10000,-0.424757403,199.998161,0,14.03629709,0,90.12594851 +20.31,50.42499959,-3.538761041,10000,-0.46653681,199.998606,0,14.03629709,0,90.13297446 +20.32,50.42499954,-3.53873294,10000,-0.497871376,199.9992734,0,14.03629709,0,90.14000036 +20.33,50.4249995,-3.53870484,10000,-0.518761096,199.999496,0,14.03629709,0,90.14702631 +20.34,50.42499945,-3.538676739,10000,-0.539650804,199.9997186,0,14.03629709,0,90.15405221 +20.35,50.4249994,-3.538648639,10000,-0.55705888,200.0003861,0,14.03629709,0,90.16107816 +20.36,50.42499935,-3.538620538,10000,-0.577948586,200.0006087,0,14.03629709,0,90.16810405 +20.37,50.4249993,-3.538592437,10000,-0.612764782,199.9994968,0,14.03629709,0,90.17513 +20.38,50.42499924,-3.538564337,10000,-0.647580966,199.998385,0,14.03629709,0,90.1821559 +20.39,50.42499918,-3.538536237,10000,-0.668470665,199.9983853,0,14.03629709,0,90.18918185 +20.4,50.42499912,-3.538508136,10000,-0.685878757,199.9983855,0,14.03629709,0,90.19620775 +20.41,50.42499906,-3.538480036,10000,-0.706768468,199.9981634,0,14.03629709,0,90.2032337 +20.42,50.42499899,-3.538451936,10000,-0.724176549,199.998386,0,14.03629709,0,90.21025959 +20.43,50.42499893,-3.538423835,10000,-0.745066259,199.9983863,0,14.03629709,0,90.21728555 +20.44,50.42499886,-3.538395735,10000,-0.779882455,199.9981642,0,14.03629709,0,90.22431144 +20.45,50.42499879,-3.538367635,10000,-0.814698634,199.9983869,0,14.03629709,0,90.23133739 +20.46,50.42499871,-3.538339534,10000,-0.835588327,199.9983872,0,14.03629709,0,90.23836329 +20.47,50.42499864,-3.538311434,10000,-0.85299641,199.9981651,0,14.03629709,0,90.24538924 +20.48,50.42499856,-3.538283334,10000,-0.877367744,199.9983879,0,14.03629709,0,90.25241514 +20.49,50.42499848,-3.538255233,10000,-0.905220695,199.9983882,0,14.03629709,0,90.25944109 +20.5,50.4249984,-3.538227133,10000,-0.92959202,199.9981661,0,14.03629709,0,90.26646698 +20.51,50.42499831,-3.538199033,10000,-0.947000105,199.9983889,0,14.03629709,0,90.27349294 +20.52,50.42499823,-3.538170932,10000,-0.967889814,199.9981669,0,14.03629709,0,90.28051883 +20.53,50.42499814,-3.538142832,10000,-1.002705998,199.9970552,0,14.03629709,0,90.28754478 +20.54,50.42499805,-3.538114732,10000,-1.037522184,199.9961659,0,14.03629709,0,90.29457068 +20.55,50.42499795,-3.538086632,10000,-1.058411899,199.9959439,0,14.03629709,0,90.30159663 +20.56,50.42499786,-3.538058532,10000,-1.075819984,199.9961667,0,14.03629709,0,90.30862252 +20.57,50.42499776,-3.538030432,10000,-1.100191291,199.9970567,0,14.03629709,0,90.31564848 +20.58,50.42499766,-3.538002332,10000,-1.128044227,199.9981692,0,14.03629709,0,90.32267437 +20.59,50.42499756,-3.537974231,10000,-1.152415567,199.9981697,0,14.03629709,0,90.32970032 +20.6,50.42499745,-3.537946131,10000,-1.169823666,199.997058,0,14.03629709,0,90.33672622 +20.61,50.42499735,-3.537918031,10000,-1.19071337,199.9961688,0,14.03629709,0,90.34375211 +20.62,50.42499724,-3.537889931,10000,-1.225529554,199.9959469,0,14.03629709,0,90.35077807 +20.63,50.42499713,-3.537861831,10000,-1.260345747,199.9959473,0,14.03629709,0,90.35780396 +20.64,50.42499701,-3.537833731,10000,-1.281235458,199.9959478,0,14.03629709,0,90.36482991 +20.65,50.4249969,-3.537805631,10000,-1.298643536,199.9959483,0,14.03629709,0,90.37185581 +20.66,50.42499678,-3.537777531,10000,-1.32301485,199.9959488,0,14.03629709,0,90.37888176 +20.67,50.42499666,-3.537749431,10000,-1.35086779,199.9957269,0,14.03629709,0,90.38590766 +20.68,50.42499654,-3.537721331,10000,-1.375239124,199.9950602,0,14.03629709,0,90.39293361 +20.69,50.42499641,-3.537693231,10000,-1.392647222,199.9946159,0,14.03629709,0,90.3999595 +20.7,50.42499629,-3.537665132,10000,-1.413536933,199.9948388,0,14.03629709,0,90.40698546 +20.71,50.42499616,-3.537637031,10000,-1.448353108,199.9948393,0,14.03629709,0,90.41401135 +20.72,50.42499603,-3.537608932,10000,-1.483169281,199.9943951,0,14.03629709,0,90.4210373 +20.73,50.42499589,-3.537580832,10000,-1.504058992,199.9939508,0,14.03629709,0,90.4280632 +20.74,50.42499576,-3.537552732,10000,-1.52146709,199.9935065,0,14.03629709,0,90.43508915 +20.75,50.42499562,-3.537524633,10000,-1.542356796,199.9937295,0,14.03629709,0,90.44211504 +20.76,50.42499548,-3.537496533,10000,-1.559764882,199.9946198,0,14.03629709,0,90.449141 +20.77,50.42499534,-3.537468433,10000,-1.580654597,199.9946204,0,14.03629709,0,90.45616689 +20.78,50.4249952,-3.537440333,10000,-1.615470776,199.9935089,0,14.03629709,0,90.46319284 +20.79,50.42499505,-3.537412234,10000,-1.650286943,199.9926199,0,14.03629709,0,90.47021874 +20.8,50.4249949,-3.537384134,10000,-1.671176653,199.9923981,0,14.03629709,0,90.47724469 +20.81,50.42499475,-3.537356035,10000,-1.688584763,199.9923987,0,14.03629709,0,90.48427059 +20.82,50.4249946,-3.537327935,10000,-1.709474473,199.9926218,0,14.03629709,0,90.49129654 +20.83,50.42499444,-3.537299836,10000,-1.726882545,199.9932897,0,14.03629709,0,90.49832243 +20.84,50.42499429,-3.537271736,10000,-1.747772247,199.9935127,0,14.03629709,0,90.50534839 +20.85,50.42499413,-3.537243636,10000,-1.78258844,199.9924013,0,14.03629709,0,90.51237428 +20.86,50.42499397,-3.537215537,10000,-1.817404633,199.9912899,0,14.03629709,0,90.51940023 +20.87,50.4249938,-3.537187438,10000,-1.838294343,199.9912906,0,14.03629709,0,90.52642613 +20.88,50.42499364,-3.537159338,10000,-1.859184043,199.9910689,0,14.03629709,0,90.53345208 +20.89,50.42499347,-3.537131239,10000,-1.894000209,199.9901799,0,14.03629709,0,90.54047798 +20.9,50.4249933,-3.53710314,10000,-1.928816389,199.9901807,0,14.03629709,0,90.54750393 +20.91,50.42499312,-3.537075041,10000,-1.94970611,199.9910711,0,14.03629709,0,90.55452982 +20.92,50.42499295,-3.537046941,10000,-1.967114202,199.9910718,0,14.03629709,0,90.56155577 +20.93,50.42499277,-3.537018842,10000,-1.988003899,199.9899605,0,14.03629709,0,90.56858167 +20.94,50.42499259,-3.536990743,10000,-2.005411987,199.9890716,0,14.03629709,0,90.57560762 +20.95,50.42499241,-3.536962644,10000,-2.026301702,199.9888499,0,14.03629709,0,90.58263352 +20.96,50.42499223,-3.536934545,10000,-2.061117886,199.9888507,0,14.03629709,0,90.58965947 +20.97,50.42499204,-3.536906446,10000,-2.095934061,199.9888515,0,14.03629709,0,90.59668536 +20.98,50.42499185,-3.536878347,10000,-2.113342142,199.9888523,0,14.03629709,0,90.60371132 +20.99,50.42499166,-3.536850248,10000,-2.120305379,199.9888531,0,14.03629709,0,90.61073721 +21,50.42499147,-3.536822149,10000,-2.13771348,199.9888539,0,14.03629709,0,90.61776311 +21.01,50.42499128,-3.53679405,10000,-2.172529664,199.9888547,0,14.03629709,0,90.62478906 +21.02,50.42499108,-3.536765951,10000,-2.207345839,199.9886331,0,14.03629709,0,90.63181495 +21.03,50.42499088,-3.536737852,10000,-2.228235547,199.9877443,0,14.03629709,0,90.63884091 +21.04,50.42499068,-3.536709753,10000,-2.24912526,199.986633,0,14.03629709,0,90.6458668 +21.05,50.42499048,-3.536681655,10000,-2.283941439,199.9866339,0,14.03629709,0,90.65289275 +21.06,50.42499027,-3.536653556,10000,-2.318757617,199.9875244,0,14.03629709,0,90.65991865 +21.07,50.42499006,-3.536625457,10000,-2.336165709,199.9875253,0,14.03629709,0,90.6669446 +21.08,50.42498985,-3.536597358,10000,-2.343128952,199.9864141,0,14.03629709,0,90.6739705 +21.09,50.42498964,-3.53656926,10000,-2.360537046,199.9855253,0,14.03629709,0,90.68099645 +21.1,50.42498943,-3.536541161,10000,-2.395353219,199.9853038,0,14.03629709,0,90.68802234 +21.11,50.42498921,-3.536513063,10000,-2.430169392,199.9853047,0,14.03629709,0,90.69504829 +21.12,50.42498899,-3.536484964,10000,-2.451059105,199.9853057,0,14.03629709,0,90.70207419 +21.13,50.42498877,-3.536456866,10000,-2.47194882,199.9850842,0,14.03629709,0,90.70910014 +21.14,50.42498855,-3.536428767,10000,-2.506764995,199.9841955,0,14.03629709,0,90.71612604 +21.15,50.42498832,-3.536400669,10000,-2.541581161,199.9830843,0,14.03629709,0,90.72315199 +21.16,50.42498809,-3.536372571,10000,-2.558989248,199.9830853,0,14.03629709,0,90.73017788 +21.17,50.42498786,-3.536344473,10000,-2.565952498,199.9839759,0,14.03629709,0,90.73720384 +21.18,50.42498763,-3.536316374,10000,-2.583360595,199.9839769,0,14.03629709,0,90.74422973 +21.19,50.4249874,-3.536288276,10000,-2.618176761,199.9828658,0,14.03629709,0,90.75125568 +21.2,50.42498716,-3.536260178,10000,-2.652992927,199.9819771,0,14.03629709,0,90.75828158 +21.21,50.42498692,-3.53623208,10000,-2.673882644,199.9817557,0,14.03629709,0,90.76530753 +21.22,50.42498668,-3.536203982,10000,-2.694772377,199.9817567,0,14.03629709,0,90.77233343 +21.23,50.42498644,-3.536175884,10000,-2.729588568,199.9817578,0,14.03629709,0,90.77935938 +21.24,50.42498619,-3.536147786,10000,-2.764404734,199.9817588,0,14.03629709,0,90.78638527 +21.25,50.42498594,-3.536119688,10000,-2.781812806,199.9815374,0,14.03629709,0,90.79341123 +21.26,50.42498569,-3.53609159,10000,-2.78877604,199.9806488,0,14.03629709,0,90.80043712 +21.27,50.42498544,-3.536063492,10000,-2.806184141,199.9795378,0,14.03629709,0,90.80746307 +21.28,50.42498519,-3.536035395,10000,-2.841000325,199.9793165,0,14.03629709,0,90.81448897 +21.29,50.42498493,-3.536007297,10000,-2.8758165,199.97954,0,14.03629709,0,90.82151492 +21.3,50.42498467,-3.535979199,10000,-2.89322459,199.9790962,0,14.03629709,0,90.82854081 +21.31,50.42498441,-3.535951102,10000,-2.900187829,199.9784301,0,14.03629709,0,90.83556677 +21.32,50.42498415,-3.535923004,10000,-2.917595918,199.9782088,0,14.03629709,0,90.84259266 +21.33,50.42498389,-3.535894907,10000,-2.952412102,199.9779874,0,14.03629709,0,90.84961861 +21.34,50.42498362,-3.535866809,10000,-2.990709905,199.9773213,0,14.03629709,0,90.85664451 +21.35,50.42498335,-3.535838712,10000,-3.022044459,199.9768776,0,14.03629709,0,90.86367046 +21.36,50.42498308,-3.535810615,10000,-3.046415777,199.9771012,0,14.03629709,0,90.87069636 +21.37,50.4249828,-3.535782517,10000,-3.063823871,199.9768799,0,14.03629709,0,90.87772231 +21.38,50.42498253,-3.53575442,10000,-3.081231967,199.975769,0,14.03629709,0,90.8847482 +21.39,50.42498225,-3.535726323,10000,-3.105603289,199.9751029,0,14.03629709,0,90.89177416 +21.4,50.42498197,-3.535698226,10000,-3.136937846,199.9755489,0,14.03629709,0,90.89880005 +21.41,50.42498169,-3.535670129,10000,-3.175235653,199.9757726,0,14.03629709,0,90.90582595 +21.42,50.4249814,-3.535642031,10000,-3.210051843,199.9746617,0,14.03629709,0,90.9128519 +21.43,50.42498111,-3.535613935,10000,-3.227459929,199.9735508,0,14.03629709,0,90.91987779 +21.44,50.42498082,-3.535585838,10000,-3.234423159,199.9737745,0,14.03629709,0,90.92690375 +21.45,50.42498053,-3.535557741,10000,-3.248349632,199.9742205,0,14.03629709,0,90.93392964 +21.46,50.42498024,-3.535529644,10000,-3.272720956,199.9735545,0,14.03629709,0,90.94095559 +21.47,50.42497994,-3.535501547,10000,-3.304055515,199.9724437,0,14.03629709,0,90.94798149 +21.48,50.42497965,-3.535473451,10000,-3.338871697,199.9722225,0,14.03629709,0,90.95500744 +21.49,50.42497934,-3.535445354,10000,-3.363243023,199.9724462,0,14.03629709,0,90.96203333 +21.5,50.42497904,-3.535417257,10000,-3.37716949,199.9720026,0,14.03629709,0,90.96905929 +21.51,50.42497874,-3.535389161,10000,-3.401540814,199.9711143,0,14.03629709,0,90.97608518 +21.52,50.42497843,-3.535361064,10000,-3.432875384,199.9702259,0,14.03629709,0,90.98311113 +21.53,50.42497812,-3.535332968,10000,-3.453765101,199.9697824,0,14.03629709,0,90.99013703 +21.54,50.42497781,-3.535304872,10000,-3.474654809,199.9700061,0,14.03629709,0,90.99716298 +21.55,50.4249775,-3.535276775,10000,-3.509470977,199.969785,0,14.03629709,0,91.00418888 +21.56,50.42497718,-3.535248679,10000,-3.544287146,199.9686742,0,14.03629709,0,91.01121483 +21.57,50.42497686,-3.535220583,10000,-3.561695242,199.9677859,0,14.03629709,0,91.01824072 +21.58,50.42497654,-3.535192487,10000,-3.568658494,199.9675649,0,14.03629709,0,91.02526668 +21.59,50.42497622,-3.535164391,10000,-3.586066586,199.9675662,0,14.03629709,0,91.03229257 +21.6,50.4249759,-3.535136295,10000,-3.620882752,199.9675676,0,14.03629709,0,91.03931852 +21.61,50.42497557,-3.535108199,10000,-3.655698925,199.9673465,0,14.03629709,0,91.04634442 +21.62,50.42497524,-3.535080103,10000,-3.676588644,199.9664582,0,14.03629709,0,91.05337037 +21.63,50.42497491,-3.535052007,10000,-3.697478365,199.9651251,0,14.03629709,0,91.06039627 +21.64,50.42497458,-3.535023912,10000,-3.732294547,199.9642369,0,14.03629709,0,91.06742222 +21.65,50.42497424,-3.534995816,10000,-3.767110722,199.9640159,0,14.03629709,0,91.07444811 +21.66,50.4249739,-3.534967721,10000,-3.784518805,199.9640173,0,14.03629709,0,91.08147406 +21.67,50.42497356,-3.534939625,10000,-3.791482037,199.9640188,0,14.03629709,0,91.08849996 +21.68,50.42497322,-3.53491153,10000,-3.808890131,199.9637978,0,14.03629709,0,91.09552591 +21.69,50.42497288,-3.534883434,10000,-3.843706312,199.9629096,0,14.03629709,0,91.10255181 +21.7,50.42497253,-3.534855339,10000,-3.878522485,199.9615765,0,14.03629709,0,91.10957776 +21.71,50.42497218,-3.534827244,10000,-3.899412186,199.9609107,0,14.03629709,0,91.11660365 +21.72,50.42497183,-3.534799149,10000,-3.920301894,199.9615795,0,14.03629709,0,91.12362961 +21.73,50.42497148,-3.534771054,10000,-3.955118078,199.9624706,0,14.03629709,0,91.1306555 +21.74,50.42497112,-3.534742958,10000,-3.989934264,199.9615825,0,14.03629709,0,91.13768145 +21.75,50.42497076,-3.534714863,10000,-4.007342365,199.9593598,0,14.03629709,0,91.14470735 +21.76,50.4249704,-3.534686769,10000,-4.01430561,199.9584717,0,14.03629709,0,91.1517333 +21.77,50.42497004,-3.534658674,10000,-4.031713693,199.9593629,0,14.03629709,0,91.1587592 +21.78,50.42496968,-3.534630579,10000,-4.066529855,199.9600316,0,14.03629709,0,91.16578515 +21.79,50.42496931,-3.534602484,10000,-4.101346027,199.9593659,0,14.03629709,0,91.17281104 +21.8,50.42496894,-3.534574389,10000,-4.118754121,199.958033,0,14.03629709,0,91.179837 +21.81,50.42496857,-3.534546295,10000,-4.125717364,199.9569225,0,14.03629709,0,91.18686289 +21.82,50.4249682,-3.5345182,10000,-4.143125467,199.9560344,0,14.03629709,0,91.19388879 +21.83,50.42496783,-3.534490106,10000,-4.177941653,199.9555911,0,14.03629709,0,91.20091474 +21.84,50.42496745,-3.534462012,10000,-4.21623944,199.9558151,0,14.03629709,0,91.20794063 +21.85,50.42496707,-3.534433917,10000,-4.24757399,199.9555943,0,14.03629709,0,91.21496658 +21.86,50.42496669,-3.534405823,10000,-4.271945314,199.9544838,0,14.03629709,0,91.22199248 +21.87,50.4249663,-3.534377729,10000,-4.289353405,199.9535958,0,14.03629709,0,91.22901843 +21.88,50.42496592,-3.534349635,10000,-4.310243116,199.9531526,0,14.03629709,0,91.23604433 +21.89,50.42496553,-3.534321541,10000,-4.345059297,199.9522645,0,14.03629709,0,91.24307028 +21.9,50.42496514,-3.534293447,10000,-4.379875474,199.9511541,0,14.03629709,0,91.25009617 +21.91,50.42496474,-3.534265354,10000,-4.40076518,199.9511558,0,14.03629709,0,91.25712213 +21.92,50.42496435,-3.53423726,10000,-4.418173274,199.9520471,0,14.03629709,0,91.26414802 +21.93,50.42496395,-3.534209166,10000,-4.439062984,199.9518264,0,14.03629709,0,91.27117397 +21.94,50.42496355,-3.534181072,10000,-4.456471073,199.9500487,0,14.03629709,0,91.27819987 +21.95,50.42496315,-3.534152979,10000,-4.477360785,199.9489383,0,14.03629709,0,91.28522582 +21.96,50.42496275,-3.534124886,10000,-4.512176969,199.9496073,0,14.03629709,0,91.29225172 +21.97,50.42496234,-3.534096792,10000,-4.54699315,199.949609,0,14.03629709,0,91.29927767 +21.98,50.42496193,-3.534068698,10000,-4.564401244,199.947609,0,14.03629709,0,91.30630356 +21.99,50.42496152,-3.534040606,10000,-4.571364479,199.9462762,0,14.03629709,0,91.31332952 +22,50.42496111,-3.534012513,10000,-4.588772559,199.9467228,0,14.03629709,0,91.32035541 +22.01,50.4249607,-3.533984419,10000,-4.623588734,199.9469469,0,14.03629709,0,91.32738136 +22.02,50.42496028,-3.533956327,10000,-4.658404915,199.9462814,0,14.03629709,0,91.33440726 +22.03,50.42495986,-3.533928233,10000,-4.679294623,199.9453935,0,14.03629709,0,91.34143321 +22.04,50.42495944,-3.533900141,10000,-4.700184324,199.9447281,0,14.03629709,0,91.3484591 +22.05,50.42495902,-3.533872048,10000,-4.735000497,199.944285,0,14.03629709,0,91.35548506 +22.06,50.42495859,-3.533843955,10000,-4.76981668,199.9436196,0,14.03629709,0,91.36251095 +22.07,50.42495816,-3.533815863,10000,-4.790706401,199.9427317,0,14.03629709,0,91.3695369 +22.08,50.42495773,-3.53378777,10000,-4.808114502,199.9418439,0,14.03629709,0,91.3765628 +22.09,50.4249573,-3.533759678,10000,-4.829004214,199.9414008,0,14.03629709,0,91.38358875 +22.1,50.42495686,-3.533731586,10000,-4.846412304,199.9416251,0,14.03629709,0,91.39061465 +22.11,50.42495643,-3.533703493,10000,-4.867302005,199.9414045,0,14.03629709,0,91.3976406 +22.12,50.42495599,-3.533675401,10000,-4.902118177,199.9400719,0,14.03629709,0,91.40466649 +22.13,50.42495555,-3.533647309,10000,-4.936934358,199.9385168,0,14.03629709,0,91.41169245 +22.14,50.4249551,-3.533619217,10000,-4.957824068,199.9378514,0,14.03629709,0,91.41871834 +22.15,50.42495466,-3.533591126,10000,-4.975232149,199.9380757,0,14.03629709,0,91.42574429 +22.16,50.42495421,-3.533563033,10000,-4.999603468,199.9378552,0,14.03629709,0,91.43277019 +22.17,50.42495376,-3.533534942,10000,-5.027456424,199.936745,0,14.03629709,0,91.43979614 +22.18,50.42495331,-3.53350685,10000,-5.051827761,199.9358573,0,14.03629709,0,91.44682204 +22.19,50.42495285,-3.533478759,10000,-5.069235844,199.9354143,0,14.03629709,0,91.45384799 +22.2,50.4249524,-3.533450667,10000,-5.086643924,199.934749,0,14.03629709,0,91.46087388 +22.21,50.42495194,-3.533422576,10000,-5.111015255,199.9343061,0,14.03629709,0,91.46789978 +22.22,50.42495148,-3.533394485,10000,-5.142349824,199.9345305,0,14.03629709,0,91.47492573 +22.23,50.42495102,-3.533366393,10000,-5.18064762,199.93431,0,14.03629709,0,91.48195162 +22.24,50.42495055,-3.533338302,10000,-5.21546379,199.9331999,0,14.03629709,0,91.48897758 +22.25,50.42495008,-3.533310211,10000,-5.232871873,199.9320898,0,14.03629709,0,91.49600347 +22.26,50.42494961,-3.53328212,10000,-5.239835109,199.9309797,0,14.03629709,0,91.50302942 +22.27,50.42494914,-3.533254029,10000,-5.257243207,199.9298696,0,14.03629709,0,91.51005532 +22.28,50.42494867,-3.533225939,10000,-5.292059395,199.9296492,0,14.03629709,0,91.51708127 +22.29,50.42494819,-3.533197848,10000,-5.326875576,199.9296512,0,14.03629709,0,91.52410717 +22.3,50.42494771,-3.533169757,10000,-5.347765286,199.9285411,0,14.03629709,0,91.53113312 +22.31,50.42494723,-3.533141667,10000,-5.368654996,199.927431,0,14.03629709,0,91.53815901 +22.32,50.42494675,-3.533113577,10000,-5.39998955,199.9274331,0,14.03629709,0,91.54518497 +22.33,50.42494626,-3.533085486,10000,-5.424360867,199.9272127,0,14.03629709,0,91.55221086 +22.34,50.42494577,-3.533057396,10000,-5.43828734,199.9261027,0,14.03629709,0,91.55923681 +22.35,50.42494529,-3.533029306,10000,-5.462658666,199.9249927,0,14.03629709,0,91.56626271 +22.36,50.42494479,-3.533001216,10000,-5.49399322,199.9238827,0,14.03629709,0,91.57328866 +22.37,50.4249443,-3.532973126,10000,-5.514882923,199.9227727,0,14.03629709,0,91.58031456 +22.38,50.4249438,-3.532945037,10000,-5.535772642,199.9225523,0,14.03629709,0,91.58734051 +22.39,50.42494331,-3.532916947,10000,-5.567107225,199.9227768,0,14.03629709,0,91.5943664 +22.4,50.4249428,-3.532888857,10000,-5.591478555,199.9223341,0,14.03629709,0,91.60139235 +22.41,50.4249423,-3.532860768,10000,-5.605405006,199.9214466,0,14.03629709,0,91.60841825 +22.42,50.4249418,-3.532832678,10000,-5.629776314,199.9203366,0,14.03629709,0,91.6154442 +22.43,50.42494129,-3.532804589,10000,-5.664592498,199.9192267,0,14.03629709,0,91.6224701 +22.44,50.42494078,-3.5327765,10000,-5.695927069,199.9190064,0,14.03629709,0,91.62949605 +22.45,50.42494027,-3.532748411,10000,-5.7202984,199.9190086,0,14.03629709,0,91.63652194 +22.46,50.42493975,-3.532720321,10000,-5.737706491,199.9178987,0,14.03629709,0,91.6435479 +22.47,50.42493924,-3.532692233,10000,-5.75511458,199.9165663,0,14.03629709,0,91.65057379 +22.48,50.42493872,-3.532664144,10000,-5.779485902,199.9159013,0,14.03629709,0,91.65759974 +22.49,50.4249382,-3.532636055,10000,-5.807338844,199.9154586,0,14.03629709,0,91.66462564 +22.5,50.42493768,-3.532607967,10000,-5.831710176,199.9154608,0,14.03629709,0,91.67165159 +22.51,50.42493715,-3.532579878,10000,-5.849118272,199.915463,0,14.03629709,0,91.67867749 +22.52,50.42493663,-3.532551789,10000,-5.870007973,199.9141307,0,14.03629709,0,91.68570344 +22.53,50.4249361,-3.532523701,10000,-5.904824139,199.9121312,0,14.03629709,0,91.69272933 +22.54,50.42493557,-3.532495613,10000,-5.939640317,199.9110214,0,14.03629709,0,91.69975529 +22.55,50.42493503,-3.532467525,10000,-5.960530038,199.9108012,0,14.03629709,0,91.70678118 +22.56,50.4249345,-3.532439437,10000,-5.97793813,199.9105811,0,14.03629709,0,91.71380713 +22.57,50.42493396,-3.532411349,10000,-6.002309447,199.9096937,0,14.03629709,0,91.72083303 +22.58,50.42493342,-3.532383261,10000,-6.033644011,199.9083614,0,14.03629709,0,91.72785898 +22.59,50.42493288,-3.532355174,10000,-6.068460195,199.9074741,0,14.03629709,0,91.73488487 +22.6,50.42493233,-3.532327086,10000,-6.092831509,199.9074764,0,14.03629709,0,91.74191083 +22.61,50.42493178,-3.532298999,10000,-6.106757976,199.9079235,0,14.03629709,0,91.74893672 +22.62,50.42493124,-3.532270911,10000,-6.13112931,199.9072586,0,14.03629709,0,91.75596262 +22.63,50.42493068,-3.532242823,10000,-6.162463875,199.9048143,0,14.03629709,0,91.76298857 +22.64,50.42493013,-3.532214737,10000,-6.17987196,199.9028149,0,14.03629709,0,91.77001446 +22.65,50.42492957,-3.53218665,10000,-6.186835203,199.9028172,0,14.03629709,0,91.77704042 +22.66,50.42492902,-3.532158563,10000,-6.204243305,199.9034868,0,14.03629709,0,91.78406631 +22.67,50.42492846,-3.532130476,10000,-6.242541095,199.9034892,0,14.03629709,0,91.79109226 +22.68,50.4249279,-3.532102389,10000,-6.287802112,199.9023795,0,14.03629709,0,91.79811816 +22.69,50.42492733,-3.532074302,10000,-6.315655049,199.9003801,0,14.03629709,0,91.80514411 +22.7,50.42492676,-3.532046216,10000,-6.329581522,199.899048,0,14.03629709,0,91.81217001 +22.71,50.4249262,-3.53201813,10000,-6.350471238,199.8990504,0,14.03629709,0,91.81919596 +22.72,50.42492562,-3.531990043,10000,-6.371360961,199.8988304,0,14.03629709,0,91.82622185 +22.73,50.42492505,-3.531961957,10000,-6.385287434,199.8977207,0,14.03629709,0,91.83324781 +22.74,50.42492448,-3.531933871,10000,-6.409658749,199.8968335,0,14.03629709,0,91.8402737 +22.75,50.4249239,-3.531905785,10000,-6.444474925,199.8963911,0,14.03629709,0,91.84729965 +22.76,50.42492332,-3.531877699,10000,-6.475809485,199.8955038,0,14.03629709,0,91.85432555 +22.77,50.42492274,-3.531849613,10000,-6.500180802,199.8941718,0,14.03629709,0,91.8613515 +22.78,50.42492215,-3.531821528,10000,-6.517588887,199.8932846,0,14.03629709,0,91.86837739 +22.79,50.42492157,-3.531793442,10000,-6.538478605,199.8930646,0,14.03629709,0,91.87540335 +22.8,50.42492098,-3.531765357,10000,-6.573294808,199.8928447,0,14.03629709,0,91.88242924 +22.81,50.42492039,-3.531737271,10000,-6.608111002,199.8919575,0,14.03629709,0,91.88945519 +22.82,50.42491979,-3.531709186,10000,-6.629000701,199.8906255,0,14.03629709,0,91.89648109 +22.83,50.4249192,-3.531681101,10000,-6.646408772,199.8897384,0,14.03629709,0,91.90350704 +22.84,50.4249186,-3.531653016,10000,-6.667298471,199.8892961,0,14.03629709,0,91.91053294 +22.85,50.424918,-3.531624931,10000,-6.684706559,199.8884089,0,14.03629709,0,91.91755889 +22.86,50.4249174,-3.531596846,10000,-6.705596269,199.887077,0,14.03629709,0,91.92458478 +22.87,50.4249168,-3.531568762,10000,-6.740412448,199.8859674,0,14.03629709,0,91.93161074 +22.88,50.42491619,-3.531540677,10000,-6.775228613,199.8848579,0,14.03629709,0,91.93863663 +22.89,50.42491558,-3.531512593,10000,-6.7961183,199.883526,0,14.03629709,0,91.94566258 +22.9,50.42491497,-3.531484509,10000,-6.813526391,199.8828613,0,14.03629709,0,91.95268848 +22.91,50.42491436,-3.531456425,10000,-6.834416123,199.8833087,0,14.03629709,0,91.95971443 +22.92,50.42491374,-3.531428341,10000,-6.855305848,199.8835337,0,14.03629709,0,91.96674033 +22.93,50.42491313,-3.531400256,10000,-6.886640408,199.8824242,0,14.03629709,0,91.97376628 +22.94,50.42491251,-3.531372173,10000,-6.924938198,199.8810923,0,14.03629709,0,91.98079217 +22.95,50.42491188,-3.531344089,10000,-6.942346289,199.8802053,0,14.03629709,0,91.98781812 +22.96,50.42491126,-3.531316005,10000,-6.945827916,199.878651,0,14.03629709,0,91.99484402 +22.97,50.42491064,-3.531287922,10000,-6.970199241,199.8768743,0,14.03629709,0,92.00186997 +22.98,50.42491001,-3.531259839,10000,-7.015460262,199.8766545,0,14.03629709,0,92.00889587 +22.99,50.42490938,-3.531231756,10000,-7.05375805,199.8773244,0,14.03629709,0,92.01592182 +23,50.42490874,-3.531203672,10000,-7.074647761,199.8764374,0,14.03629709,0,92.02294771 +23.01,50.42490811,-3.531175589,10000,-7.092055859,199.8739935,0,14.03629709,0,92.02997361 +23.02,50.42490747,-3.531147507,10000,-7.11294557,199.8722169,0,14.03629709,0,92.03699956 +23.03,50.42490683,-3.531119424,10000,-7.130353659,199.8717748,0,14.03629709,0,92.04402546 +23.04,50.42490619,-3.531091342,10000,-7.15124336,199.8717775,0,14.03629709,0,92.05105141 +23.05,50.42490555,-3.531063259,10000,-7.186059532,199.8715577,0,14.03629709,0,92.0580773 +23.06,50.4249049,-3.531035177,10000,-7.220875712,199.8706708,0,14.03629709,0,92.06510326 +23.07,50.42490425,-3.531007094,10000,-7.238283805,199.8695615,0,14.03629709,0,92.07212915 +23.08,50.4249036,-3.530979013,10000,-7.245247037,199.8691194,0,14.03629709,0,92.0791551 +23.09,50.42490295,-3.53095093,10000,-7.262655123,199.8684549,0,14.03629709,0,92.086181 +23.1,50.4249023,-3.530922848,10000,-7.297471313,199.8666783,0,14.03629709,0,92.09320695 +23.11,50.42490164,-3.530894767,10000,-7.332287504,199.8651241,0,14.03629709,0,92.10023285 +23.12,50.42490098,-3.530866685,10000,-7.353177205,199.8646821,0,14.03629709,0,92.1072588 +23.13,50.42490032,-3.530838604,10000,-7.374066894,199.86424,0,14.03629709,0,92.11428469 +23.14,50.42489966,-3.530810522,10000,-7.408883075,199.8626859,0,14.03629709,0,92.12131064 +23.15,50.42489899,-3.530782441,10000,-7.443699269,199.8609094,0,14.03629709,0,92.12833654 +23.16,50.42489832,-3.530754361,10000,-7.461107357,199.860245,0,14.03629709,0,92.13536249 +23.17,50.42489765,-3.530726279,10000,-7.468070582,199.8600254,0,14.03629709,0,92.14238839 +23.18,50.42489698,-3.530698199,10000,-7.485478666,199.8595833,0,14.03629709,0,92.14941434 +23.19,50.42489631,-3.530670118,10000,-7.520294842,199.8589189,0,14.03629709,0,92.15644023 +23.2,50.42489563,-3.530642037,10000,-7.555111018,199.8575873,0,14.03629709,0,92.16346619 +23.21,50.42489495,-3.530613957,10000,-7.576000728,199.8564781,0,14.03629709,0,92.17049208 +23.22,50.42489427,-3.530585877,10000,-7.596890444,199.8562585,0,14.03629709,0,92.17751803 +23.23,50.42489359,-3.530557796,10000,-7.631706631,199.8551493,0,14.03629709,0,92.18454393 +23.24,50.4248929,-3.530529716,10000,-7.666522809,199.852928,0,14.03629709,0,92.19156988 +23.25,50.42489221,-3.530501637,10000,-7.683930893,199.8518189,0,14.03629709,0,92.19859578 +23.26,50.42489152,-3.530473557,10000,-7.690894127,199.8518218,0,14.03629709,0,92.20562173 +23.27,50.42489083,-3.530445477,10000,-7.708302218,199.8513798,0,14.03629709,0,92.21264762 +23.28,50.42489014,-3.530417398,10000,-7.7431184,199.8504931,0,14.03629709,0,92.21967358 +23.29,50.42488944,-3.530389318,10000,-7.777934583,199.8493839,0,14.03629709,0,92.22669947 +23.3,50.42488874,-3.530361239,10000,-7.79882429,199.8480524,0,14.03629709,0,92.23372542 +23.31,50.42488804,-3.53033316,10000,-7.816232372,199.8471657,0,14.03629709,0,92.24075132 +23.32,50.42488734,-3.530305081,10000,-7.83712207,199.8467238,0,14.03629709,0,92.24777727 +23.33,50.42488663,-3.530277002,10000,-7.85453016,199.8456147,0,14.03629709,0,92.25480316 +23.34,50.42488593,-3.530248923,10000,-7.875419878,199.8436159,0,14.03629709,0,92.26182912 +23.35,50.42488522,-3.530220845,10000,-7.910236061,199.842062,0,14.03629709,0,92.26885501 +23.36,50.42488451,-3.530192767,10000,-7.945052235,199.8413977,0,14.03629709,0,92.27588096 +23.37,50.42488379,-3.530164688,10000,-7.965941942,199.8409559,0,14.03629709,0,92.28290686 +23.38,50.42488308,-3.530136611,10000,-7.986831653,199.8407365,0,14.03629709,0,92.28993281 +23.39,50.42488236,-3.530108532,10000,-8.021647829,199.8400723,0,14.03629709,0,92.29695871 +23.4,50.42488164,-3.530080454,10000,-8.056463998,199.838296,0,14.03629709,0,92.30398466 +23.41,50.42488091,-3.530052377,10000,-8.0773537,199.8367421,0,14.03629709,0,92.31101055 +23.42,50.42488019,-3.530024299,10000,-8.094761793,199.8363003,0,14.03629709,0,92.31803645 +23.43,50.42487946,-3.529996222,10000,-8.115651502,199.8358586,0,14.03629709,0,92.3250624 +23.44,50.42487873,-3.529968144,10000,-8.133059591,199.8343047,0,14.03629709,0,92.3320883 +23.45,50.424878,-3.529940067,10000,-8.153949302,199.8325285,0,14.03629709,0,92.33911425 +23.46,50.42487727,-3.529911991,10000,-8.188765485,199.8318643,0,14.03629709,0,92.34614014 +23.47,50.42487653,-3.529883913,10000,-8.223581665,199.8314226,0,14.03629709,0,92.3531661 +23.48,50.42487579,-3.529855837,10000,-8.240989755,199.8303136,0,14.03629709,0,92.36019199 +23.49,50.42487505,-3.52982776,10000,-8.247952984,199.8294271,0,14.03629709,0,92.36721794 +23.5,50.42487431,-3.529799684,10000,-8.265361068,199.8289854,0,14.03629709,0,92.37424384 +23.51,50.42487357,-3.529771607,10000,-8.300177255,199.8278764,0,14.03629709,0,92.38126979 +23.52,50.42487282,-3.529743531,10000,-8.338475051,199.8256554,0,14.03629709,0,92.38829568 +23.53,50.42487207,-3.529715455,10000,-8.369809598,199.8236568,0,14.03629709,0,92.39532164 +23.54,50.42487132,-3.52968738,10000,-8.394180925,199.8232151,0,14.03629709,0,92.40234753 +23.55,50.42487056,-3.529659304,10000,-8.411589033,199.8232183,0,14.03629709,0,92.40937348 +23.56,50.42486981,-3.529631228,10000,-8.428997124,199.8221094,0,14.03629709,0,92.41639938 +23.57,50.42486905,-3.529603153,10000,-8.453368431,199.8210005,0,14.03629709,0,92.42342533 +23.58,50.42486829,-3.529575078,10000,-8.481221368,199.8210037,0,14.03629709,0,92.43045123 +23.59,50.42486753,-3.529547002,10000,-8.505592702,199.8205621,0,14.03629709,0,92.43747718 +23.6,50.42486676,-3.529518927,10000,-8.523000793,199.8185636,0,14.03629709,0,92.44450307 +23.61,50.424866,-3.529490852,10000,-8.54389049,199.8163426,0,14.03629709,0,92.45152903 +23.62,50.42486523,-3.529462778,10000,-8.578706664,199.8152338,0,14.03629709,0,92.45855492 +23.63,50.42486446,-3.529434703,10000,-8.613522844,199.8150146,0,14.03629709,0,92.46558087 +23.64,50.42486368,-3.529406629,10000,-8.634412555,199.814573,0,14.03629709,0,92.47260677 +23.65,50.42486291,-3.529378554,10000,-8.651820654,199.8130194,0,14.03629709,0,92.47963272 +23.66,50.42486213,-3.52935048,10000,-8.676191992,199.8112433,0,14.03629709,0,92.48665862 +23.67,50.42486135,-3.529322407,10000,-8.704044938,199.8105794,0,14.03629709,0,92.49368457 +23.68,50.42486057,-3.529294332,10000,-8.728416254,199.8101378,0,14.03629709,0,92.50071046 +23.69,50.42485978,-3.529266259,10000,-8.745824333,199.8088066,0,14.03629709,0,92.50773641 +23.7,50.424859,-3.529238185,10000,-8.766714031,199.8070306,0,14.03629709,0,92.51476231 +23.71,50.42485821,-3.529210112,10000,-8.801530202,199.805477,0,14.03629709,0,92.52178826 +23.72,50.42485742,-3.529182039,10000,-8.836346382,199.8045907,0,14.03629709,0,92.52881416 +23.73,50.42485662,-3.529153966,10000,-8.857236093,199.8041492,0,14.03629709,0,92.53584011 +23.74,50.42485583,-3.529125893,10000,-8.874644181,199.8032629,0,14.03629709,0,92.542866 +23.75,50.42485503,-3.52909782,10000,-8.895533892,199.8019317,0,14.03629709,0,92.54989196 +23.76,50.42485423,-3.529069748,10000,-8.912941992,199.800823,0,14.03629709,0,92.55691785 +23.77,50.42485343,-3.529041675,10000,-8.9338317,199.7997143,0,14.03629709,0,92.5639438 +23.78,50.42485263,-3.529013603,10000,-8.968647871,199.7983832,0,14.03629709,0,92.5709697 +23.79,50.42485182,-3.528985531,10000,-9.003464045,199.7974969,0,14.03629709,0,92.57799565 +23.8,50.42485101,-3.528957459,10000,-9.024353751,199.7970555,0,14.03629709,0,92.58502155 +23.81,50.4248502,-3.528929387,10000,-9.04524346,199.7961692,0,14.03629709,0,92.5920475 +23.82,50.42484939,-3.528901315,10000,-9.076578024,199.7948382,0,14.03629709,0,92.59907339 +23.83,50.42484857,-3.528873244,10000,-9.100949351,199.7937295,0,14.03629709,0,92.60609929 +23.84,50.42484775,-3.528845172,10000,-9.114875823,199.7923984,0,14.03629709,0,92.61312524 +23.85,50.42484694,-3.528817101,10000,-9.139247147,199.7901777,0,14.03629709,0,92.62015113 +23.86,50.42484611,-3.52878903,10000,-9.17406332,199.7881794,0,14.03629709,0,92.62717709 +23.87,50.42484529,-3.52876096,10000,-9.205397871,199.7877381,0,14.03629709,0,92.63420298 +23.88,50.42484446,-3.528732889,10000,-9.229769189,199.7877416,0,14.03629709,0,92.64122893 +23.89,50.42484363,-3.528704818,10000,-9.243695661,199.786633,0,14.03629709,0,92.64825483 +23.9,50.4248428,-3.528676748,10000,-9.250658905,199.7855244,0,14.03629709,0,92.65528078 +23.91,50.42484197,-3.528648678,10000,-9.268067006,199.7853055,0,14.03629709,0,92.66230668 +23.92,50.42484114,-3.528620607,10000,-9.302883186,199.7841969,0,14.03629709,0,92.66933263 +23.93,50.4248403,-3.528592537,10000,-9.341180966,199.7817538,0,14.03629709,0,92.67635852 +23.94,50.42483946,-3.528564468,10000,-9.372515512,199.7797556,0,14.03629709,0,92.68338448 +23.95,50.42483862,-3.528536398,10000,-9.396886846,199.7786471,0,14.03629709,0,92.69041037 +23.96,50.42483777,-3.528508329,10000,-9.414294958,199.7779834,0,14.03629709,0,92.69743632 +23.97,50.42483693,-3.52848026,10000,-9.431703055,199.7773197,0,14.03629709,0,92.70446222 +23.98,50.42483608,-3.52845219,10000,-9.456074364,199.7759888,0,14.03629709,0,92.71148817 +23.99,50.42483523,-3.528424122,10000,-9.483927289,199.7746578,0,14.03629709,0,92.71851407 +24,50.42483438,-3.528396053,10000,-9.508298614,199.7737718,0,14.03629709,0,92.72554002 +24.01,50.42483352,-3.528367984,10000,-9.525706713,199.7724409,0,14.03629709,0,92.73256591 +24.02,50.42483267,-3.528339916,10000,-9.546596422,199.77111,0,14.03629709,0,92.73959187 +24.03,50.42483181,-3.528311848,10000,-9.581412594,199.7702239,0,14.03629709,0,92.74661776 +24.04,50.42483095,-3.528283779,10000,-9.616228774,199.768893,0,14.03629709,0,92.75364371 +24.05,50.42483008,-3.528255712,10000,-9.637118485,199.7675622,0,14.03629709,0,92.76066961 +24.06,50.42482922,-3.528227644,10000,-9.654526573,199.7668986,0,14.03629709,0,92.76769556 +24.07,50.42482835,-3.528199576,10000,-9.678897897,199.766235,0,14.03629709,0,92.77472145 +24.08,50.42482748,-3.528171509,10000,-9.710232454,199.765349,0,14.03629709,0,92.78174741 +24.09,50.42482661,-3.528143441,10000,-9.745048622,199.7642406,0,14.03629709,0,92.7887733 +24.1,50.42482573,-3.528115374,10000,-9.769419949,199.7626873,0,14.03629709,0,92.79579925 +24.11,50.42482485,-3.528087307,10000,-9.783346432,199.7606893,0,14.03629709,0,92.80282515 +24.12,50.42482398,-3.52805924,10000,-9.804236136,199.7584688,0,14.03629709,0,92.8098511 +24.13,50.42482309,-3.528031174,10000,-9.825125829,199.757138,0,14.03629709,0,92.816877 +24.14,50.42482221,-3.528003108,10000,-9.839052298,199.7571417,0,14.03629709,0,92.82390295 +24.15,50.42482133,-3.527975041,10000,-9.863423634,199.756923,0,14.03629709,0,92.83092884 +24.16,50.42482044,-3.527946975,10000,-9.898239815,199.7555923,0,14.03629709,0,92.8379548 +24.17,50.42481955,-3.527918909,10000,-9.929574368,199.7535943,0,14.03629709,0,92.84498069 +24.18,50.42481866,-3.527890843,10000,-9.953945687,199.7513739,0,14.03629709,0,92.85200664 +24.19,50.42481776,-3.527862778,10000,-9.971353782,199.7500431,0,14.03629709,0,92.85903254 +24.2,50.42481687,-3.527834713,10000,-9.992243495,199.7498245,0,14.03629709,0,92.86605849 +24.21,50.42481597,-3.527806647,10000,-10.02705967,199.7487162,0,14.03629709,0,92.87308438 +24.22,50.42481507,-3.527778582,10000,-10.06187584,199.7464958,0,14.03629709,0,92.88011028 +24.23,50.42481416,-3.527750518,10000,-10.08276554,199.7453875,0,14.03629709,0,92.88713623 +24.24,50.42481326,-3.527722453,10000,-10.10017363,199.7451689,0,14.03629709,0,92.89416213 +24.25,50.42481235,-3.527694388,10000,-10.12454496,199.7438382,0,14.03629709,0,92.90118808 +24.26,50.42481144,-3.527666324,10000,-10.15239791,199.7418403,0,14.03629709,0,92.90821397 +24.27,50.42481053,-3.52763826,10000,-10.17676924,199.7407321,0,14.03629709,0,92.91523993 +24.28,50.42480961,-3.527610196,10000,-10.19417732,199.7402911,0,14.03629709,0,92.92226582 +24.29,50.4248087,-3.527582132,10000,-10.21158541,199.7394053,0,14.03629709,0,92.92929177 +24.3,50.42480778,-3.527554068,10000,-10.23595673,199.7380746,0,14.03629709,0,92.93631767 +24.31,50.42480686,-3.527526005,10000,-10.26729129,199.7369664,0,14.03629709,0,92.94334362 +24.32,50.42480594,-3.527497941,10000,-10.30558907,199.7358582,0,14.03629709,0,92.95036952 +24.33,50.42480501,-3.527469878,10000,-10.34040525,199.7343052,0,14.03629709,0,92.95739547 +24.34,50.42480408,-3.527441815,10000,-10.35781335,199.7323074,0,14.03629709,0,92.96442136 +24.35,50.42480315,-3.527413752,10000,-10.36477659,199.7300871,0,14.03629709,0,92.97144732 +24.36,50.42480222,-3.52738569,10000,-10.38218468,199.7287565,0,14.03629709,0,92.97847321 +24.37,50.42480129,-3.527357628,10000,-10.41700085,199.7287605,0,14.03629709,0,92.98549916 +24.38,50.42480035,-3.527329565,10000,-10.45181702,199.7283196,0,14.03629709,0,92.99252506 +24.39,50.42479941,-3.527301503,10000,-10.46922511,199.7263218,0,14.03629709,0,92.99955101 +24.4,50.42479847,-3.527273441,10000,-10.47618835,199.7241016,0,14.03629709,0,93.0065769 +24.41,50.42479753,-3.52724538,10000,-10.49359643,199.7229934,0,14.03629709,0,93.01360286 +24.42,50.42479659,-3.527217318,10000,-10.52841262,199.7225526,0,14.03629709,0,93.02062875 +24.43,50.42479564,-3.527189257,10000,-10.5632288,199.7214445,0,14.03629709,0,93.0276547 +24.44,50.42479469,-3.527161195,10000,-10.5841185,199.7192243,0,14.03629709,0,93.0346806 +24.45,50.42479374,-3.527133135,10000,-10.6050082,199.7170041,0,14.03629709,0,93.04170655 +24.46,50.42479279,-3.527105074,10000,-10.63982438,199.7158961,0,14.03629709,0,93.04873245 +24.47,50.42479183,-3.527077014,10000,-10.67464055,199.7154552,0,14.03629709,0,93.0557584 +24.48,50.42479087,-3.527048953,10000,-10.69553025,199.7145696,0,14.03629709,0,93.06278429 +24.49,50.42478991,-3.527020893,10000,-10.71293835,199.7132392,0,14.03629709,0,93.06981025 +24.5,50.42478895,-3.526992833,10000,-10.73382808,199.7121311,0,14.03629709,0,93.07683614 +24.51,50.42478798,-3.526964773,10000,-10.75123616,199.7108007,0,14.03629709,0,93.08386209 +24.52,50.42478702,-3.526936713,10000,-10.77212585,199.7085806,0,14.03629709,0,93.09088799 +24.53,50.42478605,-3.526908654,10000,-10.80694202,199.7063605,0,14.03629709,0,93.09791394 +24.54,50.42478508,-3.526880595,10000,-10.8417582,199.7052525,0,14.03629709,0,93.10493984 +24.55,50.4247841,-3.526852536,10000,-10.86264791,199.7050342,0,14.03629709,0,93.11196579 +24.56,50.42478313,-3.526824477,10000,-10.880056,199.7048159,0,14.03629709,0,93.11899168 +24.57,50.42478215,-3.526796418,10000,-10.90442733,199.7037079,0,14.03629709,0,93.12601763 +24.58,50.42478117,-3.526768359,10000,-10.93228026,199.7014878,0,14.03629709,0,93.13304353 +24.59,50.42478019,-3.526740301,10000,-10.95665158,199.6992678,0,14.03629709,0,93.14006948 +24.6,50.4247792,-3.526712243,10000,-10.97405968,199.6981599,0,14.03629709,0,93.14709538 +24.61,50.42477822,-3.526684185,10000,-10.99494939,199.6977192,0,14.03629709,0,93.15412133 +24.62,50.42477723,-3.526656127,10000,-11.02976556,199.6966113,0,14.03629709,0,93.16114722 +24.63,50.42477624,-3.526628069,10000,-11.06458173,199.6943913,0,14.03629709,0,93.16817312 +24.64,50.42477524,-3.526600012,10000,-11.08547144,199.6921713,0,14.03629709,0,93.17519907 +24.65,50.42477425,-3.526571955,10000,-11.10287953,199.6910634,0,14.03629709,0,93.18222497 +24.66,50.42477325,-3.526543898,10000,-11.12725086,199.6906227,0,14.03629709,0,93.18925092 +24.67,50.42477225,-3.526515841,10000,-11.15510379,199.6895149,0,14.03629709,0,93.19627681 +24.68,50.42477125,-3.526487784,10000,-11.17947511,199.6872949,0,14.03629709,0,93.20330277 +24.69,50.42477024,-3.526459728,10000,-11.1968832,199.685075,0,14.03629709,0,93.21032866 +24.7,50.42476924,-3.526431672,10000,-11.2142913,199.6839671,0,14.03629709,0,93.21735461 +24.71,50.42476823,-3.526403616,10000,-11.23866262,199.6835265,0,14.03629709,0,93.22438051 +24.72,50.42476722,-3.52637556,10000,-11.26999717,199.6826411,0,14.03629709,0,93.23140646 +24.73,50.42476621,-3.526347504,10000,-11.30829497,199.6810885,0,14.03629709,0,93.23843236 +24.74,50.42476519,-3.526319449,10000,-11.34311115,199.679091,0,14.03629709,0,93.24545831 +24.75,50.42476417,-3.526291393,10000,-11.36051925,199.6768711,0,14.03629709,0,93.2524842 +24.76,50.42476315,-3.526263339,10000,-11.36748249,199.6755409,0,14.03629709,0,93.25951015 +24.77,50.42476213,-3.526235284,10000,-11.38489057,199.6755452,0,14.03629709,0,93.26653605 +24.78,50.42476111,-3.526207229,10000,-11.41970674,199.6751047,0,14.03629709,0,93.273562 +24.79,50.42476008,-3.526179174,10000,-11.45452291,199.6731072,0,14.03629709,0,93.2805879 +24.8,50.42475905,-3.52615112,10000,-11.47193098,199.6708874,0,14.03629709,0,93.28761385 +24.81,50.42475802,-3.526123066,10000,-11.47889422,199.6695572,0,14.03629709,0,93.29463974 +24.82,50.42475699,-3.526095012,10000,-11.49630232,199.6682271,0,14.03629709,0,93.3016657 +24.83,50.42475596,-3.526066958,10000,-11.53111851,199.6662296,0,14.03629709,0,93.30869159 +24.84,50.42475492,-3.526038905,10000,-11.56941631,199.6646771,0,14.03629709,0,93.31571754 +24.85,50.42475388,-3.526010852,10000,-11.60075085,199.6637918,0,14.03629709,0,93.32274344 +24.86,50.42475284,-3.525982798,10000,-11.62512215,199.6622393,0,14.03629709,0,93.32976939 +24.87,50.42475179,-3.525954746,10000,-11.64253024,199.6602419,0,14.03629709,0,93.33679529 +24.88,50.42475075,-3.525926693,10000,-11.65993835,199.6591342,0,14.03629709,0,93.34382124 +24.89,50.4247497,-3.525898641,10000,-11.68430968,199.6586938,0,14.03629709,0,93.35084713 +24.9,50.42474865,-3.525870588,10000,-11.71564423,199.6575861,0,14.03629709,0,93.35787309 +24.91,50.4247476,-3.525842536,10000,-11.75394202,199.6553664,0,14.03629709,0,93.36489898 +24.92,50.42474654,-3.525814484,10000,-11.7887582,199.6531467,0,14.03629709,0,93.37192493 +24.93,50.42474548,-3.525786433,10000,-11.80616629,199.6518166,0,14.03629709,0,93.37895083 +24.94,50.42474442,-3.525758381,10000,-11.81312952,199.650709,0,14.03629709,0,93.38597678 +24.95,50.42474336,-3.52573033,10000,-11.82705599,199.6493789,0,14.03629709,0,93.39300267 +24.96,50.4247423,-3.525702279,10000,-11.84794571,199.6482713,0,14.03629709,0,93.40002863 +24.97,50.42474123,-3.525674228,10000,-11.86883542,199.6471637,0,14.03629709,0,93.40705452 +24.98,50.42474017,-3.525646177,10000,-11.90016997,199.6456113,0,14.03629709,0,93.41408047 +24.99,50.4247391,-3.525618127,10000,-11.94194937,199.643614,0,14.03629709,0,93.42110637 +25,50.42473802,-3.525590076,10000,-11.97328393,199.6413944,0,14.03629709,0,93.42813232 +25.01,50.42473695,-3.525562027,10000,-11.99417363,199.639842,0,14.03629709,0,93.43515822 +25.02,50.42473587,-3.525533977,10000,-12.01506334,199.6391793,0,14.03629709,0,93.44218411 +25.03,50.42473479,-3.525505927,10000,-12.03247143,199.6385166,0,14.03629709,0,93.44921006 +25.04,50.42473371,-3.525477878,10000,-12.04987952,199.637409,0,14.03629709,0,93.45623596 +25.05,50.42473263,-3.525449828,10000,-12.07076922,199.6354118,0,14.03629709,0,93.46326191 +25.06,50.42473154,-3.525421779,10000,-12.09165893,199.6327474,0,14.03629709,0,93.47028781 +25.07,50.42473046,-3.525393731,10000,-12.12299348,199.6307502,0,14.03629709,0,93.47731376 +25.08,50.42472937,-3.525365682,10000,-12.1647729,199.6294203,0,14.03629709,0,93.48433965 +25.09,50.42472827,-3.525337634,10000,-12.19610746,199.6280904,0,14.03629709,0,93.49136561 +25.1,50.42472718,-3.525309586,10000,-12.21699717,199.6269829,0,14.03629709,0,93.4983915 +25.11,50.42472608,-3.525281538,10000,-12.23788686,199.6258754,0,14.03629709,0,93.50541745 +25.12,50.42472498,-3.52525349,10000,-12.25181333,199.6245455,0,14.03629709,0,93.51244335 +25.13,50.42472388,-3.525225443,10000,-12.25877658,199.6234381,0,14.03629709,0,93.5194693 +25.14,50.42472278,-3.525197395,10000,-12.27618468,199.6221082,0,14.03629709,0,93.52649519 +25.15,50.42472168,-3.525169348,10000,-12.31100086,199.6198887,0,14.03629709,0,93.53352115 +25.16,50.42472057,-3.525141301,10000,-12.34929863,199.6176692,0,14.03629709,0,93.54054704 +25.17,50.42471946,-3.525113255,10000,-12.38063318,199.6163393,0,14.03629709,0,93.54757299 +25.18,50.42471835,-3.525085208,10000,-12.4050045,199.6152319,0,14.03629709,0,93.55459889 +25.19,50.42471723,-3.525057162,10000,-12.42241259,199.6139021,0,14.03629709,0,93.56162484 +25.2,50.42471612,-3.525029116,10000,-12.4433023,199.6127947,0,14.03629709,0,93.56865074 +25.21,50.424715,-3.52500107,10000,-12.47811849,199.6114649,0,14.03629709,0,93.57567669 +25.22,50.42471388,-3.524973024,10000,-12.51293466,199.6092455,0,14.03629709,0,93.58270258 +25.23,50.42471275,-3.524944979,10000,-12.53382436,199.607026,0,14.03629709,0,93.58972854 +25.24,50.42471163,-3.524916934,10000,-12.55123243,199.6056963,0,14.03629709,0,93.59675443 +25.25,50.4247105,-3.524888889,10000,-12.57212213,199.6045889,0,14.03629709,0,93.60378038 +25.26,50.42470937,-3.524860844,10000,-12.58953024,199.6032592,0,14.03629709,0,93.61080628 +25.27,50.42470824,-3.5248328,10000,-12.61041995,199.6021518,0,14.03629709,0,93.61783223 +25.28,50.42470711,-3.524804755,10000,-12.64523612,199.6008221,0,14.03629709,0,93.62485813 +25.29,50.42470597,-3.524776711,10000,-12.68005229,199.5986027,0,14.03629709,0,93.63188408 +25.3,50.42470483,-3.524748667,10000,-12.700942,199.5963833,0,14.03629709,0,93.63890997 +25.31,50.42470369,-3.524720624,10000,-12.71835009,199.5950536,0,14.03629709,0,93.64593592 +25.32,50.42470255,-3.52469258,10000,-12.7392398,199.5939463,0,14.03629709,0,93.65296182 +25.33,50.4247014,-3.524664537,10000,-12.75664788,199.5923942,0,14.03629709,0,93.65998777 +25.34,50.42470026,-3.524636494,10000,-12.77753757,199.5903973,0,14.03629709,0,93.66701367 +25.35,50.42469911,-3.524608451,10000,-12.81235375,199.5879555,0,14.03629709,0,93.67403962 +25.36,50.42469796,-3.524580409,10000,-12.84716994,199.5857362,0,14.03629709,0,93.68106551 +25.37,50.4246968,-3.524552367,10000,-12.86805966,199.584629,0,14.03629709,0,93.68809147 +25.38,50.42469565,-3.524524325,10000,-12.88546774,199.584189,0,14.03629709,0,93.69511736 +25.39,50.42469449,-3.524496283,10000,-12.90983906,199.5833042,0,14.03629709,0,93.70214331 +25.4,50.42469333,-3.524468241,10000,-12.93769199,199.5817522,0,14.03629709,0,93.70916921 +25.41,50.42469217,-3.5244402,10000,-12.9620633,199.5797553,0,14.03629709,0,93.71619516 +25.42,50.424691,-3.524412158,10000,-12.97947138,199.577536,0,14.03629709,0,93.72322106 +25.43,50.42468984,-3.524384118,10000,-13.00036111,199.575984,0,14.03629709,0,93.73024695 +25.44,50.42468867,-3.524356077,10000,-13.0351773,199.5750992,0,14.03629709,0,93.7372729 +25.45,50.4246875,-3.524328036,10000,-13.06999347,199.5735472,0,14.03629709,0,93.7442988 +25.46,50.42468632,-3.524299996,10000,-13.09088316,199.571328,0,14.03629709,0,93.75132475 +25.47,50.42468515,-3.524271956,10000,-13.10829124,199.5693312,0,14.03629709,0,93.75835065 +25.48,50.42468397,-3.524243916,10000,-13.13266256,199.5677792,0,14.03629709,0,93.7653766 +25.49,50.42468279,-3.524215877,10000,-13.16399711,199.5666721,0,14.03629709,0,93.77240249 +25.5,50.42468161,-3.524187837,10000,-13.19881329,199.565565,0,14.03629709,0,93.77942844 +25.51,50.42468042,-3.524159798,10000,-13.21970301,199.5640131,0,14.03629709,0,93.78645434 +25.52,50.42467923,-3.524131759,10000,-13.22318465,199.5620163,0,14.03629709,0,93.79348029 +25.53,50.42467805,-3.52410372,10000,-13.24059274,199.5597971,0,14.03629709,0,93.80050619 +25.54,50.42467686,-3.524075682,10000,-13.27889051,199.5582452,0,14.03629709,0,93.80753214 +25.55,50.42467566,-3.524047644,10000,-13.31022506,199.5573605,0,14.03629709,0,93.81455803 +25.56,50.42467447,-3.524019605,10000,-13.33111476,199.5558086,0,14.03629709,0,93.82158399 +25.57,50.42467327,-3.523991568,10000,-13.35548608,199.5535895,0,14.03629709,0,93.82860988 +25.58,50.42467207,-3.52396353,10000,-13.38333903,199.5515928,0,14.03629709,0,93.83563583 +25.59,50.42467087,-3.523935493,10000,-13.40771035,199.5500409,0,14.03629709,0,93.84266173 +25.6,50.42466966,-3.523907456,10000,-13.42511844,199.5489339,0,14.03629709,0,93.84968768 +25.61,50.42466846,-3.523879419,10000,-13.44600814,199.5476045,0,14.03629709,0,93.85671358 +25.62,50.42466725,-3.523851382,10000,-13.48082432,199.5453854,0,14.03629709,0,93.86373953 +25.63,50.42466604,-3.523823346,10000,-13.51564049,199.5431663,0,14.03629709,0,93.87076542 +25.64,50.42466482,-3.52379531,10000,-13.53653018,199.5418369,0,14.03629709,0,93.87779138 +25.65,50.42466361,-3.523767274,10000,-13.55393825,199.5405075,0,14.03629709,0,93.88481727 +25.66,50.42466239,-3.523739238,10000,-13.57482797,199.5382885,0,14.03629709,0,93.89184322 +25.67,50.42466117,-3.523711203,10000,-13.59223608,199.5360694,0,14.03629709,0,93.89886912 +25.68,50.42465995,-3.523683168,10000,-13.61312579,199.53474,0,14.03629709,0,93.90589507 +25.69,50.42465873,-3.523655133,10000,-13.64794196,199.5336331,0,14.03629709,0,93.91292096 +25.7,50.4246575,-3.523627098,10000,-13.68275813,199.5323037,0,14.03629709,0,93.91994692 +25.71,50.42465627,-3.523599064,10000,-13.70364784,199.5311968,0,14.03629709,0,93.92697281 +25.72,50.42465504,-3.523571029,10000,-13.72105593,199.5298675,0,14.03629709,0,93.93399876 +25.73,50.42465381,-3.523542995,10000,-13.74194563,199.5274261,0,14.03629709,0,93.94102466 +25.74,50.42465257,-3.523514961,10000,-13.75935371,199.5243174,0,14.03629709,0,93.94805061 +25.75,50.42465134,-3.523486928,10000,-13.7802434,199.5220985,0,14.03629709,0,93.95507651 +25.76,50.4246501,-3.523458895,10000,-13.81505958,199.5216588,0,14.03629709,0,93.96210246 +25.77,50.42464886,-3.523430862,10000,-13.84987576,199.521664,0,14.03629709,0,93.96912835 +25.78,50.42464761,-3.523402828,10000,-13.87076548,199.5203348,0,14.03629709,0,93.97615431 +25.79,50.42464637,-3.523374796,10000,-13.88817356,199.5181158,0,14.03629709,0,93.9831802 +25.8,50.42464512,-3.523346763,10000,-13.91254487,199.5158969,0,14.03629709,0,93.99020615 +25.81,50.42464387,-3.523318731,10000,-13.94039781,199.5132332,0,14.03629709,0,93.99723205 +25.82,50.42464262,-3.523290699,10000,-13.96476914,199.510347,0,14.03629709,0,94.004258 +25.83,50.42464136,-3.523262668,10000,-13.98565884,199.5087953,0,14.03629709,0,94.0112839 +25.84,50.42464011,-3.523234637,10000,-14.0169934,199.5085782,0,14.03629709,0,94.01830979 +25.85,50.42463885,-3.523206605,10000,-14.05529119,199.5074714,0,14.03629709,0,94.02533574 +25.86,50.42463758,-3.523178574,10000,-14.07269929,199.5050301,0,14.03629709,0,94.03236164 +25.87,50.42463632,-3.523150544,10000,-14.0761809,199.5030337,0,14.03629709,0,94.03938759 +25.88,50.42463506,-3.523122513,10000,-14.09707059,199.5017045,0,14.03629709,0,94.04641348 +25.89,50.42463379,-3.523094483,10000,-14.13188677,199.5001529,0,14.03629709,0,94.05343944 +25.9,50.42463252,-3.523066453,10000,-14.16670296,199.4983789,0,14.03629709,0,94.06046533 +25.91,50.42463125,-3.523038423,10000,-14.20151913,199.4966049,0,14.03629709,0,94.06749128 +25.92,50.42462997,-3.523010394,10000,-14.22589044,199.4946085,0,14.03629709,0,94.07451718 +25.93,50.42462869,-3.522982364,10000,-14.2398169,199.4923897,0,14.03629709,0,94.08154313 +25.94,50.42462742,-3.522954336,10000,-14.26070661,199.4908382,0,14.03629709,0,94.08856903 +25.95,50.42462613,-3.522926307,10000,-14.28159632,199.4899539,0,14.03629709,0,94.09559498 +25.96,50.42462485,-3.522898278,10000,-14.29552279,199.4884023,0,14.03629709,0,94.10262087 +25.97,50.42462357,-3.52287025,10000,-14.3198941,199.4861836,0,14.03629709,0,94.10964683 +25.98,50.42462228,-3.522842222,10000,-14.35471028,199.4839648,0,14.03629709,0,94.11667272 +25.99,50.42462099,-3.522814194,10000,-14.38604485,199.4815236,0,14.03629709,0,94.12369867 +26,50.4246197,-3.522786167,10000,-14.41041618,199.4793049,0,14.03629709,0,94.13072457 +26.01,50.4246184,-3.52275814,10000,-14.42782426,199.4779758,0,14.03629709,0,94.13775052 +26.02,50.42461711,-3.522730113,10000,-14.44871396,199.4766468,0,14.03629709,0,94.14477642 +26.03,50.42461581,-3.522702086,10000,-14.48353013,199.4746505,0,14.03629709,0,94.15180237 +26.04,50.42461451,-3.52267406,10000,-14.51834629,199.473099,0,14.03629709,0,94.15882826 +26.05,50.4246132,-3.522646034,10000,-14.539236,199.4719924,0,14.03629709,0,94.16585421 +26.06,50.4246119,-3.522618007,10000,-14.5566441,199.4697737,0,14.03629709,0,94.17288011 +26.07,50.42461059,-3.522589982,10000,-14.57753381,199.4671102,0,14.03629709,0,94.17990606 +26.08,50.42460928,-3.522561957,10000,-14.59494189,199.4655588,0,14.03629709,0,94.18693196 +26.09,50.42460797,-3.522533931,10000,-14.61583159,199.4646746,0,14.03629709,0,94.19395791 +26.1,50.42460666,-3.522505907,10000,-14.65064776,199.463568,0,14.03629709,0,94.2009838 +26.11,50.42460534,-3.522477881,10000,-14.68546393,199.4615718,0,14.03629709,0,94.20800976 +26.12,50.42460402,-3.522449857,10000,-14.70635363,199.4589083,0,14.03629709,0,94.21503565 +26.13,50.4246027,-3.522421833,10000,-14.72376172,199.4569121,0,14.03629709,0,94.2220616 +26.14,50.42460138,-3.522393809,10000,-14.74465143,199.4555832,0,14.03629709,0,94.2290875 +26.15,50.42460005,-3.522365785,10000,-14.76205951,199.4540318,0,14.03629709,0,94.23611345 +26.16,50.42459873,-3.522337762,10000,-14.78294921,199.4520356,0,14.03629709,0,94.24313935 +26.17,50.4245974,-3.522309738,10000,-14.81776539,199.4495946,0,14.03629709,0,94.2501653 +26.18,50.42459607,-3.522281716,10000,-14.85258157,199.4473761,0,14.03629709,0,94.25719119 +26.19,50.42459473,-3.522253693,10000,-14.87347128,199.4460471,0,14.03629709,0,94.26421715 +26.2,50.4245934,-3.522225671,10000,-14.89087937,199.4447183,0,14.03629709,0,94.27124304 +26.21,50.42459206,-3.522197648,10000,-14.91525068,199.4427221,0,14.03629709,0,94.27826899 +26.22,50.42459072,-3.522169627,10000,-14.94658522,199.4411708,0,14.03629709,0,94.28529489 +26.23,50.42458938,-3.522141605,10000,-14.98488302,199.4402868,0,14.03629709,0,94.29232078 +26.24,50.42458803,-3.522113583,10000,-15.01969921,199.4385131,0,14.03629709,0,94.29934673 +26.25,50.42458668,-3.522085562,10000,-15.03710729,199.4354049,0,14.03629709,0,94.30637263 +26.26,50.42458533,-3.522057541,10000,-15.04407051,199.4322968,0,14.03629709,0,94.31339858 +26.27,50.42458398,-3.522029521,10000,-15.05799699,199.4307455,0,14.03629709,0,94.32042448 +26.28,50.42458263,-3.522001501,10000,-15.0788867,199.4305288,0,14.03629709,0,94.32745043 +26.29,50.42458127,-3.52197348,10000,-15.09977639,199.4292,0,14.03629709,0,94.33447632 +26.3,50.42457992,-3.52194546,10000,-15.13111094,199.4258694,0,14.03629709,0,94.34150228 +26.31,50.42457856,-3.521917441,10000,-15.17289036,199.4227613,0,14.03629709,0,94.34852817 +26.32,50.42457719,-3.521889422,10000,-15.20422492,199.4214325,0,14.03629709,0,94.35555412 +26.33,50.42457583,-3.521861403,10000,-15.22511461,199.4209934,0,14.03629709,0,94.36258002 +26.34,50.42457446,-3.521833384,10000,-15.24600431,199.4196646,0,14.03629709,0,94.36960597 +26.35,50.42457309,-3.521805365,10000,-15.26341239,199.416779,0,14.03629709,0,94.37663187 +26.36,50.42457172,-3.521777347,10000,-15.28082049,199.4141157,0,14.03629709,0,94.38365782 +26.37,50.42457035,-3.52174933,10000,-15.30171021,199.4130094,0,14.03629709,0,94.39068371 +26.38,50.42456897,-3.521721311,10000,-15.31911829,199.4116806,0,14.03629709,0,94.39770967 +26.39,50.4245676,-3.521693294,10000,-15.34000799,199.4090174,0,14.03629709,0,94.40473556 +26.4,50.42456622,-3.521665277,10000,-15.37830578,199.4063542,0,14.03629709,0,94.41176151 +26.41,50.42456484,-3.52163726,10000,-15.42356681,199.4045807,0,14.03629709,0,94.41878741 +26.42,50.42456345,-3.521609244,10000,-15.44793813,199.4034744,0,14.03629709,0,94.42581336 +26.43,50.42456206,-3.521581227,10000,-15.45141974,199.4023681,0,14.03629709,0,94.43283925 +26.44,50.42456068,-3.521553211,10000,-15.46882782,199.400817,0,14.03629709,0,94.43986521 +26.45,50.42455929,-3.521525195,10000,-15.50712562,199.3988211,0,14.03629709,0,94.4468911 +26.46,50.42455789,-3.521497179,10000,-15.53846019,199.3961579,0,14.03629709,0,94.45391705 +26.47,50.4245565,-3.521469164,10000,-15.5593499,199.39305,0,14.03629709,0,94.46094295 +26.48,50.4245551,-3.521441149,10000,-15.58372121,199.3906092,0,14.03629709,0,94.4679689 +26.49,50.4245537,-3.521413135,10000,-15.61157414,199.389503,0,14.03629709,0,94.4749948 +26.5,50.4245523,-3.52138512,10000,-15.63594545,199.3890641,0,14.03629709,0,94.48202075 +26.51,50.42455089,-3.521357106,10000,-15.65335354,199.3877355,0,14.03629709,0,94.48904664 +26.52,50.42454949,-3.521329091,10000,-15.67076163,199.3848499,0,14.03629709,0,94.4960726 +26.53,50.42454808,-3.521301078,10000,-15.69513294,199.3819644,0,14.03629709,0,94.50309849 +26.54,50.42454667,-3.521273065,10000,-15.72298588,199.380191,0,14.03629709,0,94.51012444 +26.55,50.42454526,-3.521245051,10000,-15.74735721,199.3784176,0,14.03629709,0,94.51715034 +26.56,50.42454384,-3.521217039,10000,-15.76824691,199.3761994,0,14.03629709,0,94.52417629 +26.57,50.42454243,-3.521189026,10000,-15.79958146,199.3742036,0,14.03629709,0,94.53120219 +26.58,50.42454101,-3.521161014,10000,-15.84136086,199.3726526,0,14.03629709,0,94.53822814 +26.59,50.42453958,-3.521133002,10000,-15.8692138,199.3715465,0,14.03629709,0,94.54525403 +26.6,50.42453816,-3.52110499,10000,-15.87617704,199.370218,0,14.03629709,0,94.55227998 +26.61,50.42453673,-3.521076978,10000,-15.88314027,199.3679998,0,14.03629709,0,94.55930588 +26.62,50.42453531,-3.521048967,10000,-15.91099322,199.3655592,0,14.03629709,0,94.56633183 +26.63,50.42453388,-3.521020956,10000,-15.95277263,199.363341,0,14.03629709,0,94.57335773 +26.64,50.42453244,-3.520992945,10000,-15.98410719,199.3609004,0,14.03629709,0,94.58038362 +26.65,50.42453101,-3.520964935,10000,-16.00499689,199.3586823,0,14.03629709,0,94.58740957 +26.66,50.42452957,-3.520936925,10000,-16.02588658,199.3573538,0,14.03629709,0,94.59443547 +26.67,50.42452813,-3.520908915,10000,-16.04329465,199.3560253,0,14.03629709,0,94.60146142 +26.68,50.42452669,-3.520880905,10000,-16.06418436,199.3538072,0,14.03629709,0,94.60848732 +26.69,50.42452525,-3.520852896,10000,-16.09551894,199.3513667,0,14.03629709,0,94.61551327 +26.7,50.4245238,-3.520824887,10000,-16.11989026,199.349371,0,14.03629709,0,94.62253916 +26.71,50.42452235,-3.520796878,10000,-16.13381672,199.3478201,0,14.03629709,0,94.62956512 +26.72,50.42452091,-3.52076887,10000,-16.15818803,199.3464917,0,14.03629709,0,94.63659101 +26.73,50.42451945,-3.520740861,10000,-16.19300421,199.3442736,0,14.03629709,0,94.64361696 +26.74,50.424518,-3.520712853,10000,-16.22433877,199.3409435,0,14.03629709,0,94.65064286 +26.75,50.42451654,-3.520684846,10000,-16.24871008,199.338503,0,14.03629709,0,94.65766881 +26.76,50.42451508,-3.520656839,10000,-16.26611817,199.337397,0,14.03629709,0,94.66469471 +26.77,50.42451362,-3.520628831,10000,-16.28352626,199.3358462,0,14.03629709,0,94.67172066 +26.78,50.42451216,-3.520600825,10000,-16.30441597,199.3336282,0,14.03629709,0,94.67874655 +26.79,50.42451069,-3.520572818,10000,-16.32530566,199.3314102,0,14.03629709,0,94.6857725 +26.8,50.42450923,-3.520544812,10000,-16.35664021,199.3289697,0,14.03629709,0,94.6927984 +26.81,50.42450776,-3.520516806,10000,-16.39841961,199.3267517,0,14.03629709,0,94.69982435 +26.82,50.42450628,-3.520488801,10000,-16.42627255,199.3254234,0,14.03629709,0,94.70685025 +26.83,50.42450481,-3.520460795,10000,-16.43671741,199.3243175,0,14.03629709,0,94.7138762 +26.84,50.42450333,-3.52043279,10000,-16.45412551,199.3225444,0,14.03629709,0,94.72090209 +26.85,50.42450186,-3.520404785,10000,-16.48546006,199.3196591,0,14.03629709,0,94.72792805 +26.86,50.42450037,-3.52037678,10000,-16.50983137,199.3161067,0,14.03629709,0,94.73495394 +26.87,50.42449889,-3.520348777,10000,-16.52375784,199.3136663,0,14.03629709,0,94.74197989 +26.88,50.42449741,-3.520320773,10000,-16.54812916,199.3127828,0,14.03629709,0,94.74900579 +26.89,50.42449592,-3.520292769,10000,-16.58294533,199.3121218,0,14.03629709,0,94.75603174 +26.9,50.42449443,-3.520264766,10000,-16.61427988,199.311016,0,14.03629709,0,94.76305764 +26.91,50.42449294,-3.520236762,10000,-16.63865121,199.3087981,0,14.03629709,0,94.77008359 +26.92,50.42449144,-3.520208759,10000,-16.65605929,199.3052457,0,14.03629709,0,94.77710948 +26.93,50.42448995,-3.520180757,10000,-16.67346737,199.3021381,0,14.03629709,0,94.78413544 +26.94,50.42448845,-3.520152755,10000,-16.69783869,199.3005875,0,14.03629709,0,94.79116133 +26.95,50.42448695,-3.520124753,10000,-16.72917325,199.2992592,0,14.03629709,0,94.79818728 +26.96,50.42448545,-3.520096751,10000,-16.76398942,199.2970414,0,14.03629709,0,94.80521318 +26.97,50.42448394,-3.52006875,10000,-16.78836075,199.2948235,0,14.03629709,0,94.81223913 +26.98,50.42448243,-3.520040749,10000,-16.80228721,199.2934953,0,14.03629709,0,94.81926502 +26.99,50.42448093,-3.520012748,10000,-16.82665853,199.2919448,0,14.03629709,0,94.82629098 +27,50.42447941,-3.519984747,10000,-16.85799309,199.2888372,0,14.03629709,0,94.83331687 +27.01,50.4244779,-3.519956747,10000,-16.87540117,199.2855073,0,14.03629709,0,94.84034282 +27.02,50.42447638,-3.519928748,10000,-16.88584602,199.2839568,0,14.03629709,0,94.84736872 +27.03,50.42447487,-3.519900748,10000,-16.91369896,199.282851,0,14.03629709,0,94.85439461 +27.04,50.42447335,-3.519872748,10000,-16.95547836,199.2804108,0,14.03629709,0,94.86142057 +27.05,50.42447182,-3.51984475,10000,-16.98681292,199.278193,0,14.03629709,0,94.86844646 +27.06,50.4244703,-3.519816751,10000,-17.00770263,199.2770873,0,14.03629709,0,94.87547241 +27.07,50.42446877,-3.519788752,10000,-17.02859233,199.2753144,0,14.03629709,0,94.88249831 +27.08,50.42446724,-3.519760754,10000,-17.0460004,199.2724294,0,14.03629709,0,94.88952426 +27.09,50.42446571,-3.519732756,10000,-17.06340848,199.2697668,0,14.03629709,0,94.89655016 +27.1,50.42446418,-3.519704759,10000,-17.08429818,199.2675491,0,14.03629709,0,94.90357611 +27.11,50.42446264,-3.519676761,10000,-17.10518789,199.2653313,0,14.03629709,0,94.910602 +27.12,50.42446111,-3.519648765,10000,-17.13652244,199.2635584,0,14.03629709,0,94.91762796 +27.13,50.42445957,-3.519620768,10000,-17.17830185,199.2617855,0,14.03629709,0,94.92465385 +27.14,50.42445802,-3.519592771,10000,-17.20963641,199.259123,0,14.03629709,0,94.9316798 +27.15,50.42445648,-3.519564776,10000,-17.23052612,199.2569053,0,14.03629709,0,94.9387057 +27.16,50.42445493,-3.51953678,10000,-17.25141582,199.2557997,0,14.03629709,0,94.94573165 +27.17,50.42445338,-3.519508784,10000,-17.26882391,199.2540269,0,14.03629709,0,94.95275754 +27.18,50.42445183,-3.519480789,10000,-17.28623199,199.2511419,0,14.03629709,0,94.9597835 +27.19,50.42445028,-3.519452794,10000,-17.30712169,199.2487019,0,14.03629709,0,94.96680939 +27.2,50.42444872,-3.5194248,10000,-17.32452977,199.2471515,0,14.03629709,0,94.97383534 +27.21,50.42444717,-3.519396805,10000,-17.34541948,199.2451562,0,14.03629709,0,94.98086124 +27.22,50.42444561,-3.519368811,10000,-17.38023565,199.2424937,0,14.03629709,0,94.98788719 +27.23,50.42444405,-3.519340818,10000,-17.41505181,199.2404985,0,14.03629709,0,94.99491309 +27.24,50.42444248,-3.519312824,10000,-17.43594151,199.2389482,0,14.03629709,0,95.00193904 +27.25,50.42444092,-3.519284831,10000,-17.45683123,199.2365081,0,14.03629709,0,95.00896493 +27.26,50.42443935,-3.519256838,10000,-17.49164741,199.2334009,0,14.03629709,0,95.01599089 +27.27,50.42443778,-3.519228846,10000,-17.52646356,199.2309609,0,14.03629709,0,95.02301678 +27.28,50.4244362,-3.519200854,10000,-17.54735326,199.229633,0,14.03629709,0,95.03004273 +27.29,50.42443463,-3.519172862,10000,-17.56476134,199.2283051,0,14.03629709,0,95.03706863 +27.3,50.42443305,-3.51914487,10000,-17.58565105,199.2258651,0,14.03629709,0,95.04409458 +27.31,50.42443147,-3.519116879,10000,-17.60305914,199.2227579,0,14.03629709,0,95.05112048 +27.32,50.42442989,-3.519088888,10000,-17.62394884,199.2203179,0,14.03629709,0,95.05814643 +27.33,50.42442831,-3.519060898,10000,-17.65876501,199.21899,0,14.03629709,0,95.06517232 +27.34,50.42442672,-3.519032907,10000,-17.69358118,199.2176622,0,14.03629709,0,95.07219827 +27.35,50.42442513,-3.519004917,10000,-17.71447088,199.2152222,0,14.03629709,0,95.07922417 +27.36,50.42442354,-3.518976927,10000,-17.73187896,199.2121151,0,14.03629709,0,95.08625012 +27.37,50.42442195,-3.518948938,10000,-17.75276867,199.2094527,0,14.03629709,0,95.09327602 +27.38,50.42442035,-3.518920949,10000,-17.77017675,199.2074576,0,14.03629709,0,95.10030197 +27.39,50.42441876,-3.51889296,10000,-17.79106645,199.2059074,0,14.03629709,0,95.10732786 +27.4,50.42441716,-3.518864972,10000,-17.82588262,199.2045796,0,14.03629709,0,95.11435382 +27.41,50.42441556,-3.518836983,10000,-17.86069879,199.2025846,0,14.03629709,0,95.12137971 +27.42,50.42441395,-3.518808995,10000,-17.8815885,199.1996999,0,14.03629709,0,95.12840566 +27.43,50.42441235,-3.518781008,10000,-17.89899658,199.1968152,0,14.03629709,0,95.13543156 +27.44,50.42441074,-3.51875302,10000,-17.9233679,199.1941529,0,14.03629709,0,95.14245745 +27.45,50.42440913,-3.518725034,10000,-17.95122083,199.191713,0,14.03629709,0,95.14948341 +27.46,50.42440752,-3.518697047,10000,-17.97559217,199.189718,0,14.03629709,0,95.1565093 +27.47,50.4244059,-3.518669061,10000,-17.99300025,199.1879455,0,14.03629709,0,95.16353525 +27.48,50.42440429,-3.518641075,10000,-18.01388994,199.1861729,0,14.03629709,0,95.17056115 +27.49,50.42440267,-3.518613089,10000,-18.04870611,199.1844003,0,14.03629709,0,95.1775871 +27.5,50.42440105,-3.518585104,10000,-18.08352228,199.1824054,0,14.03629709,0,95.184613 +27.51,50.42439942,-3.518557118,10000,-18.10441199,199.1799656,0,14.03629709,0,95.19163895 +27.52,50.4243978,-3.518529134,10000,-18.12182007,199.1775258,0,14.03629709,0,95.19866484 +27.53,50.42439617,-3.518501149,10000,-18.14619138,199.1753084,0,14.03629709,0,95.20569079 +27.54,50.42439454,-3.518473165,10000,-18.17404431,199.1726463,0,14.03629709,0,95.21271669 +27.55,50.42439291,-3.518445181,10000,-18.19841563,199.1697617,0,14.03629709,0,95.21974264 +27.56,50.42439127,-3.518417198,10000,-18.21582373,199.1679892,0,14.03629709,0,95.22676854 +27.57,50.42438964,-3.518389215,10000,-18.23671344,199.1671064,0,14.03629709,0,95.23379449 +27.58,50.424388,-3.518361231,10000,-18.27152962,199.1653339,0,14.03629709,0,95.24082038 +27.59,50.42438636,-3.518333249,10000,-18.30634579,199.1622269,0,14.03629709,0,95.24784634 +27.6,50.42438471,-3.518305266,10000,-18.32723547,199.1588975,0,14.03629709,0,95.25487223 +27.61,50.42438307,-3.518277285,10000,-18.34464354,199.1562354,0,14.03629709,0,95.26189818 +27.62,50.42438142,-3.518249303,10000,-18.36553324,199.1542406,0,14.03629709,0,95.26892408 +27.63,50.42437977,-3.518221322,10000,-18.38294134,199.1524681,0,14.03629709,0,95.27595003 +27.64,50.42437812,-3.518193341,10000,-18.40383104,199.1504733,0,14.03629709,0,95.28297593 +27.65,50.42437647,-3.51816536,10000,-18.4386472,199.1480336,0,14.03629709,0,95.29000188 +27.66,50.42437481,-3.51813738,10000,-18.47346338,199.145594,0,14.03629709,0,95.29702777 +27.67,50.42437315,-3.5181094,10000,-18.49435309,199.1435992,0,14.03629709,0,95.30405373 +27.68,50.42437149,-3.51808142,10000,-18.51176117,199.1418268,0,14.03629709,0,95.31107962 +27.69,50.42436983,-3.518053441,10000,-18.53265087,199.139832,0,14.03629709,0,95.31810557 +27.7,50.42436816,-3.518025461,10000,-18.55005895,199.1373924,0,14.03629709,0,95.32513147 +27.71,50.4243665,-3.517997483,10000,-18.57094865,199.1349528,0,14.03629709,0,95.33215742 +27.72,50.42436483,-3.517969504,10000,-18.60576482,199.1327356,0,14.03629709,0,95.33918331 +27.73,50.42436316,-3.517941526,10000,-18.64058099,199.1300736,0,14.03629709,0,95.34620927 +27.74,50.42436148,-3.517913548,10000,-18.6614707,199.1269667,0,14.03629709,0,95.35323516 +27.75,50.42435981,-3.517885571,10000,-18.67887878,199.1243047,0,14.03629709,0,95.36026111 +27.76,50.42435813,-3.517857594,10000,-18.7032501,199.12231,0,14.03629709,0,95.36728701 +27.77,50.42435645,-3.517829617,10000,-18.73458465,199.1207601,0,14.03629709,0,95.37431296 +27.78,50.42435477,-3.517801641,10000,-18.76940082,199.1194327,0,14.03629709,0,95.38133886 +27.79,50.42435308,-3.517773664,10000,-18.79377213,199.1172155,0,14.03629709,0,95.38836481 +27.8,50.42435139,-3.517745688,10000,-18.8076986,199.1136639,0,14.03629709,0,95.3953907 +27.81,50.42434971,-3.517717713,10000,-18.83206992,199.1105572,0,14.03629709,0,95.40241666 +27.82,50.42434801,-3.517689738,10000,-18.86340449,199.1090073,0,14.03629709,0,95.40944255 +27.83,50.42434632,-3.517661763,10000,-18.88081256,199.1076799,0,14.03629709,0,95.41646845 +27.84,50.42434462,-3.517633788,10000,-18.8912574,199.1054628,0,14.03629709,0,95.4234944 +27.85,50.42434293,-3.517605814,10000,-18.91911033,199.1030233,0,14.03629709,0,95.43052029 +27.86,50.42434123,-3.51757784,10000,-18.96088975,199.1008063,0,14.03629709,0,95.43754625 +27.87,50.42433952,-3.517549866,10000,-18.99222431,199.0981444,0,14.03629709,0,95.44457214 +27.88,50.42433782,-3.517521893,10000,-19.013114,199.0948153,0,14.03629709,0,95.45159809 +27.89,50.42433611,-3.51749392,10000,-19.0340037,199.0914862,0,14.03629709,0,95.45862399 +27.9,50.4243344,-3.517465948,10000,-19.04793016,199.0890467,0,14.03629709,0,95.46564994 +27.91,50.42433269,-3.517437976,10000,-19.05489339,199.0877194,0,14.03629709,0,95.47267583 +27.92,50.42433098,-3.517410004,10000,-19.07230147,199.086392,0,14.03629709,0,95.47970179 +27.93,50.42432927,-3.517382032,10000,-19.10711765,199.084175,0,14.03629709,0,95.48672768 +27.94,50.42432755,-3.517354061,10000,-19.14541544,199.0817356,0,14.03629709,0,95.49375363 +27.95,50.42432583,-3.51732609,10000,-19.17675,199.0795187,0,14.03629709,0,95.50077953 +27.96,50.42432411,-3.517298119,10000,-19.20112132,199.0770793,0,14.03629709,0,95.50780548 +27.97,50.42432238,-3.517270149,10000,-19.21852939,199.0746399,0,14.03629709,0,95.51483138 +27.98,50.42432066,-3.517242179,10000,-19.23941909,199.0724229,0,14.03629709,0,95.52185733 +27.99,50.42431893,-3.517214209,10000,-19.27423526,199.0699836,0,14.03629709,0,95.52888322 +28,50.4243172,-3.51718624,10000,-19.30905142,199.0675442,0,14.03629709,0,95.53590918 +28.01,50.42431546,-3.517158271,10000,-19.32994112,199.0653273,0,14.03629709,0,95.54293507 +28.02,50.42431373,-3.517130302,10000,-19.34734922,199.0626656,0,14.03629709,0,95.54996102 +28.03,50.42431199,-3.517102334,10000,-19.36823892,199.059559,0,14.03629709,0,95.55698692 +28.04,50.42431025,-3.517074366,10000,-19.38564699,199.0568973,0,14.03629709,0,95.56401287 +28.05,50.42430851,-3.517046399,10000,-19.40653669,199.0546804,0,14.03629709,0,95.57103876 +28.06,50.42430677,-3.517018431,10000,-19.44135287,199.0522411,0,14.03629709,0,95.57806472 +28.07,50.42430502,-3.516990465,10000,-19.47616904,199.0498018,0,14.03629709,0,95.58509061 +28.08,50.42430327,-3.516962498,10000,-19.49705874,199.0478074,0,14.03629709,0,95.59211656 +28.09,50.42430152,-3.516934532,10000,-19.51446683,199.0460353,0,14.03629709,0,95.59914246 +28.1,50.42429977,-3.516906566,10000,-19.53535653,199.0440409,0,14.03629709,0,95.60616841 +28.11,50.42429801,-3.5168786,10000,-19.55276461,199.0413793,0,14.03629709,0,95.61319431 +28.12,50.42429626,-3.516850635,10000,-19.5736543,199.0382727,0,14.03629709,0,95.62022026 +28.13,50.4242945,-3.51682267,10000,-19.60847047,199.0356111,0,14.03629709,0,95.62724615 +28.14,50.42429274,-3.516794706,10000,-19.64328663,199.0333943,0,14.03629709,0,95.63427211 +28.15,50.42429097,-3.516766741,10000,-19.66417634,199.0309551,0,14.03629709,0,95.641298 +28.16,50.42428921,-3.516738778,10000,-19.68158443,199.0285159,0,14.03629709,0,95.64832395 +28.17,50.42428744,-3.516710814,10000,-19.70595574,199.0265215,0,14.03629709,0,95.65534985 +28.18,50.42428567,-3.516682851,10000,-19.73380868,199.0247496,0,14.03629709,0,95.6623758 +28.19,50.4242839,-3.516654888,10000,-19.75818,199.0227552,0,14.03629709,0,95.6694017 +28.2,50.42428212,-3.516626925,10000,-19.77558809,199.0200937,0,14.03629709,0,95.67642765 +28.21,50.42428035,-3.516598963,10000,-19.79647779,199.0167648,0,14.03629709,0,95.68345354 +28.22,50.42427857,-3.516571001,10000,-19.83129395,199.013436,0,14.03629709,0,95.6904795 +28.23,50.42427679,-3.51654304,10000,-19.86611011,199.0109968,0,14.03629709,0,95.69750539 +28.24,50.424275,-3.516515079,10000,-19.88699981,199.0096698,0,14.03629709,0,95.70453128 +28.25,50.42427322,-3.516487118,10000,-19.9044079,199.0083428,0,14.03629709,0,95.71155724 +28.26,50.42427143,-3.516459157,10000,-19.92877922,199.0059037,0,14.03629709,0,95.71858313 +28.27,50.42426964,-3.516431197,10000,-19.95663214,199.0025749,0,14.03629709,0,95.72560908 +28.28,50.42426785,-3.516403237,10000,-19.98100346,198.9992461,0,14.03629709,0,95.73263498 +28.29,50.42426605,-3.516375278,10000,-19.99841154,198.9965846,0,14.03629709,0,95.73966093 +28.3,50.42426426,-3.516347319,10000,-20.01581962,198.9943679,0,14.03629709,0,95.74668683 +28.31,50.42426246,-3.51631936,10000,-20.04019094,198.9919289,0,14.03629709,0,95.75371278 +28.32,50.42426066,-3.516291402,10000,-20.0715255,198.9894898,0,14.03629709,0,95.76073867 +28.33,50.42425886,-3.516263444,10000,-20.10982329,198.9872732,0,14.03629709,0,95.76776463 +28.34,50.42425705,-3.516235486,10000,-20.14463946,198.9848341,0,14.03629709,0,95.77479052 +28.35,50.42425524,-3.516207529,10000,-20.16204754,198.9823951,0,14.03629709,0,95.78181647 +28.36,50.42425343,-3.516179572,10000,-20.16901077,198.9801785,0,14.03629709,0,95.78884237 +28.37,50.42425162,-3.516151615,10000,-20.18641886,198.9777395,0,14.03629709,0,95.79586832 +28.38,50.42424981,-3.516123659,10000,-20.22123502,198.9753005,0,14.03629709,0,95.80289422 +28.39,50.42424799,-3.516095703,10000,-20.25605118,198.9730839,0,14.03629709,0,95.80992017 +28.4,50.42424617,-3.516067747,10000,-20.27345927,198.9704225,0,14.03629709,0,95.81694606 +28.41,50.42424435,-3.516039792,10000,-20.28042251,198.9673162,0,14.03629709,0,95.82397201 +28.42,50.42424253,-3.516011837,10000,-20.2978306,198.9646548,0,14.03629709,0,95.83099791 +28.43,50.42424071,-3.515983883,10000,-20.33264676,198.9624383,0,14.03629709,0,95.83802386 +28.44,50.42423888,-3.515955928,10000,-20.37094454,198.9599993,0,14.03629709,0,95.84504976 +28.45,50.42423705,-3.515927975,10000,-20.40227909,198.9575604,0,14.03629709,0,95.85207571 +28.46,50.42423522,-3.515900021,10000,-20.42665041,198.9555663,0,14.03629709,0,95.8591016 +28.47,50.42423338,-3.515872068,10000,-20.44405847,198.9537946,0,14.03629709,0,95.86612756 +28.48,50.42423155,-3.515844115,10000,-20.46146655,198.9518006,0,14.03629709,0,95.87315345 +28.49,50.42422971,-3.515816162,10000,-20.48583788,198.9491392,0,14.03629709,0,95.8801794 +28.5,50.42422787,-3.51578821,10000,-20.51369082,198.9458107,0,14.03629709,0,95.8872053 +28.51,50.42422603,-3.515760258,10000,-20.53806214,198.9424821,0,14.03629709,0,95.89423125 +28.52,50.42422418,-3.515732307,10000,-20.55547022,198.9398208,0,14.03629709,0,95.90125715 +28.53,50.42422234,-3.515704356,10000,-20.57635991,198.9376043,0,14.03629709,0,95.9082831 +28.54,50.42422049,-3.515676405,10000,-20.61117608,198.934943,0,14.03629709,0,95.91530899 +28.55,50.42421864,-3.515648455,10000,-20.64599227,198.9318369,0,14.03629709,0,95.92233495 +28.56,50.42421678,-3.515620505,10000,-20.66688197,198.9291757,0,14.03629709,0,95.92936084 +28.57,50.42421493,-3.515592556,10000,-20.68429004,198.9269593,0,14.03629709,0,95.93638679 +28.58,50.42421307,-3.515564606,10000,-20.70866134,198.9245204,0,14.03629709,0,95.94341269 +28.59,50.42421121,-3.515536658,10000,-20.73651428,198.9220816,0,14.03629709,0,95.95043864 +28.6,50.42420935,-3.515508709,10000,-20.7608856,198.9198652,0,14.03629709,0,95.95746453 +28.61,50.42420748,-3.515480761,10000,-20.77829368,198.9174264,0,14.03629709,0,95.96449049 +28.62,50.42420562,-3.515452813,10000,-20.79918339,198.9149876,0,14.03629709,0,95.97151638 +28.63,50.42420375,-3.515424866,10000,-20.83399957,198.9125488,0,14.03629709,0,95.97854233 +28.64,50.42420188,-3.515396918,10000,-20.86881573,198.9092204,0,14.03629709,0,95.98556823 +28.65,50.4242,-3.515368972,10000,-20.88970541,198.9056695,0,14.03629709,0,95.99259412 +28.66,50.42419813,-3.515341026,10000,-20.90711348,198.9034532,0,14.03629709,0,95.99962008 +28.67,50.42419625,-3.51531308,10000,-20.92800318,198.9019041,0,14.03629709,0,96.00664597 +28.68,50.42419437,-3.515285134,10000,-20.94541128,198.8996878,0,14.03629709,0,96.01367192 +28.69,50.42419249,-3.515257189,10000,-20.966301,198.8972491,0,14.03629709,0,96.02069782 +28.7,50.42419061,-3.515229244,10000,-21.00111716,198.8950328,0,14.03629709,0,96.02772377 +28.71,50.42418872,-3.515201299,10000,-21.03593331,198.8923716,0,14.03629709,0,96.03474967 +28.72,50.42418683,-3.515173355,10000,-21.05682299,198.8890433,0,14.03629709,0,96.04177562 +28.73,50.42418494,-3.515145411,10000,-21.07423108,198.8857149,0,14.03629709,0,96.04880151 +28.74,50.42418305,-3.515117468,10000,-21.09512079,198.8830538,0,14.03629709,0,96.05582747 +28.75,50.42418115,-3.515089525,10000,-21.11252888,198.8808375,0,14.03629709,0,96.06285336 +28.76,50.42417926,-3.515061582,10000,-21.13341858,198.8783989,0,14.03629709,0,96.06987931 +28.77,50.42417736,-3.51503364,10000,-21.16823475,198.8759602,0,14.03629709,0,96.07690521 +28.78,50.42417546,-3.515005698,10000,-21.20305092,198.873744,0,14.03629709,0,96.08393116 +28.79,50.42417355,-3.514977756,10000,-21.22394061,198.8713053,0,14.03629709,0,96.09095705 +28.8,50.42417165,-3.514949815,10000,-21.24134868,198.8688667,0,14.03629709,0,96.09798301 +28.81,50.42416974,-3.514921874,10000,-21.26572,198.8666505,0,14.03629709,0,96.1050089 +28.82,50.42416783,-3.514893933,10000,-21.29705456,198.8639895,0,14.03629709,0,96.11203485 +28.83,50.42416592,-3.514865993,10000,-21.33187073,198.8606612,0,14.03629709,0,96.11906075 +28.84,50.424164,-3.514838053,10000,-21.35624204,198.8573329,0,14.03629709,0,96.1260867 +28.85,50.42416208,-3.514810114,10000,-21.37016851,198.8546719,0,14.03629709,0,96.1331126 +28.86,50.42416017,-3.514782175,10000,-21.39105821,198.8524558,0,14.03629709,0,96.14013855 +28.87,50.42415824,-3.514754236,10000,-21.4119479,198.8500172,0,14.03629709,0,96.14716444 +28.88,50.42415632,-3.514726298,10000,-21.42587436,198.8475786,0,14.03629709,0,96.1541904 +28.89,50.4241544,-3.51469836,10000,-21.45024567,198.8453625,0,14.03629709,0,96.16121629 +28.9,50.42415247,-3.514670422,10000,-21.48506184,198.8427015,0,14.03629709,0,96.16824224 +28.91,50.42415054,-3.514642485,10000,-21.51987801,198.8395957,0,14.03629709,0,96.17526814 +28.92,50.42414861,-3.514614548,10000,-21.55469418,198.8369348,0,14.03629709,0,96.18229409 +28.93,50.42414667,-3.514586612,10000,-21.57558388,198.8344963,0,14.03629709,0,96.18931999 +28.94,50.42414473,-3.514558675,10000,-21.57906549,198.8313905,0,14.03629709,0,96.19634594 +28.95,50.4241428,-3.51453074,10000,-21.59647357,198.8285072,0,14.03629709,0,96.20337183 +28.96,50.42414086,-3.514502805,10000,-21.63477135,198.8265135,0,14.03629709,0,96.21039778 +28.97,50.42413891,-3.514474869,10000,-21.66610591,198.8238526,0,14.03629709,0,96.21742368 +28.98,50.42413697,-3.514446935,10000,-21.68699561,198.8205245,0,14.03629709,0,96.22444963 +28.99,50.42413502,-3.514419001,10000,-21.71136692,198.818086,0,14.03629709,0,96.23147553 +29,50.42413307,-3.514391067,10000,-21.73921986,198.8156476,0,14.03629709,0,96.23850148 +29.01,50.42413112,-3.514363133,10000,-21.76359118,198.812097,0,14.03629709,0,96.24552737 +29.02,50.42412916,-3.514335201,10000,-21.78099924,198.8089914,0,14.03629709,0,96.25255333 +29.03,50.42412721,-3.514307268,10000,-21.79840732,198.8074426,0,14.03629709,0,96.25957922 +29.04,50.42412525,-3.514279336,10000,-21.82277866,198.8061163,0,14.03629709,0,96.26660512 +29.05,50.42412329,-3.514251403,10000,-21.85411321,198.8036779,0,14.03629709,0,96.27363107 +29.06,50.42412133,-3.514223472,10000,-21.89241098,198.8003498,0,14.03629709,0,96.28065696 +29.07,50.42411936,-3.51419554,10000,-21.92722714,198.7970217,0,14.03629709,0,96.28768292 +29.08,50.42411739,-3.51416761,10000,-21.94463523,198.7943609,0,14.03629709,0,96.29470881 +29.09,50.42411542,-3.514139679,10000,-21.95159846,198.792145,0,14.03629709,0,96.30173476 +29.1,50.42411345,-3.514111749,10000,-21.96900653,198.7894842,0,14.03629709,0,96.30876066 +29.11,50.42411148,-3.514083819,10000,-22.0038227,198.7861562,0,14.03629709,0,96.31578661 +29.12,50.4241095,-3.51405589,10000,-22.03863887,198.7826057,0,14.03629709,0,96.32281251 +29.13,50.42410752,-3.514027961,10000,-22.05604696,198.7792777,0,14.03629709,0,96.32983846 +29.14,50.42410554,-3.514000033,10000,-22.0630102,198.7768394,0,14.03629709,0,96.33686435 +29.15,50.42410356,-3.513972105,10000,-22.08041828,198.7755132,0,14.03629709,0,96.3438903 +29.16,50.42410158,-3.513944177,10000,-22.11523443,198.7739645,0,14.03629709,0,96.3509162 +29.17,50.42409959,-3.513916249,10000,-22.15005058,198.7706366,0,14.03629709,0,96.35794215 +29.18,50.4240976,-3.513888322,10000,-22.17094028,198.7661965,0,14.03629709,0,96.36496805 +29.19,50.42409561,-3.513860396,10000,-22.19182999,198.7628685,0,14.03629709,0,96.371994 +29.2,50.42409362,-3.51383247,10000,-22.22664616,198.7613199,0,14.03629709,0,96.37901989 +29.21,50.42409162,-3.513804544,10000,-22.26146233,198.7599938,0,14.03629709,0,96.38604585 +29.22,50.42408962,-3.513776618,10000,-22.2788704,198.7575555,0,14.03629709,0,96.39307174 +29.23,50.42408762,-3.513748693,10000,-22.28583363,198.7542276,0,14.03629709,0,96.40009769 +29.24,50.42408562,-3.513720768,10000,-22.30324171,198.7506773,0,14.03629709,0,96.40712359 +29.25,50.42408362,-3.513692844,10000,-22.33805788,198.7473494,0,14.03629709,0,96.41414954 +29.26,50.42408161,-3.51366492,10000,-22.37287404,198.7449111,0,14.03629709,0,96.42117544 +29.27,50.4240796,-3.513636997,10000,-22.39376374,198.7433626,0,14.03629709,0,96.42820139 +29.28,50.42407759,-3.513609073,10000,-22.41117183,198.7411468,0,14.03629709,0,96.43522728 +29.29,50.42407558,-3.51358115,10000,-22.43206153,198.7373741,0,14.03629709,0,96.44225324 +29.3,50.42407356,-3.513553228,10000,-22.45295123,198.733379,0,14.03629709,0,96.44927913 +29.31,50.42407155,-3.513525306,10000,-22.48428577,198.7307184,0,14.03629709,0,96.45630508 +29.32,50.42406953,-3.513497385,10000,-22.52606517,198.7291699,0,14.03629709,0,96.46333098 +29.33,50.4240675,-3.513469463,10000,-22.5539181,198.7269542,0,14.03629709,0,96.47035693 +29.34,50.42406548,-3.513441542,10000,-22.56436295,198.7234039,0,14.03629709,0,96.47738282 +29.35,50.42406345,-3.513413622,10000,-22.58177104,198.7200761,0,14.03629709,0,96.48440878 +29.36,50.42406143,-3.513385702,10000,-22.61310559,198.717638,0,14.03629709,0,96.49143467 +29.37,50.42405939,-3.513357782,10000,-22.6374769,198.7149774,0,14.03629709,0,96.49846062 +29.38,50.42405736,-3.513329863,10000,-22.65140334,198.7116497,0,14.03629709,0,96.50548652 +29.39,50.42405533,-3.513301944,10000,-22.67577465,198.7083219,0,14.03629709,0,96.51251247 +29.4,50.42405329,-3.513274026,10000,-22.71059082,198.7056614,0,14.03629709,0,96.51953837 +29.41,50.42405125,-3.513246108,10000,-22.74192539,198.7036681,0,14.03629709,0,96.52656432 +29.42,50.42404921,-3.51321819,10000,-22.7662967,198.7018973,0,14.03629709,0,96.53359021 +29.43,50.42404716,-3.513190273,10000,-22.78370477,198.6996816,0,14.03629709,0,96.54061617 +29.44,50.42404512,-3.513162355,10000,-22.80111285,198.6963539,0,14.03629709,0,96.54764206 +29.45,50.42404307,-3.513134439,10000,-22.82548417,198.6925813,0,14.03629709,0,96.55466796 +29.46,50.42404102,-3.513106523,10000,-22.85333712,198.689476,0,14.03629709,0,96.56169391 +29.47,50.42403897,-3.513078607,10000,-22.87770843,198.6865932,0,14.03629709,0,96.5687198 +29.48,50.42403691,-3.513050692,10000,-22.8951165,198.6834879,0,14.03629709,0,96.57574576 +29.49,50.42403486,-3.513022777,10000,-22.91600618,198.6808274,0,14.03629709,0,96.58277165 +29.5,50.4240328,-3.512994863,10000,-22.95082235,198.6786119,0,14.03629709,0,96.5897976 +29.51,50.42403074,-3.512966948,10000,-22.98563853,198.6761739,0,14.03629709,0,96.5968235 +29.52,50.42402867,-3.512939035,10000,-23.00652823,198.6735135,0,14.03629709,0,96.60384945 +29.53,50.42402661,-3.512911121,10000,-23.0239363,198.6704082,0,14.03629709,0,96.61087534 +29.54,50.42402454,-3.512883208,10000,-23.04830761,198.6666357,0,14.03629709,0,96.6179013 +29.55,50.42402247,-3.512855296,10000,-23.07616053,198.6635305,0,14.03629709,0,96.62492719 +29.56,50.4240204,-3.512827384,10000,-23.10053185,198.6619822,0,14.03629709,0,96.63195314 +29.57,50.42401832,-3.512799472,10000,-23.11793994,198.660434,0,14.03629709,0,96.63897904 +29.58,50.42401625,-3.51277156,10000,-23.13882965,198.6571064,0,14.03629709,0,96.64600499 +29.59,50.42401417,-3.512743649,10000,-23.17364581,198.6526667,0,14.03629709,0,96.65303089 +29.6,50.42401209,-3.512715739,10000,-23.20846197,198.6491166,0,14.03629709,0,96.66005684 +29.61,50.42401,-3.512687829,10000,-23.22935166,198.6466787,0,14.03629709,0,96.66708273 +29.62,50.42400792,-3.512659919,10000,-23.24675974,198.6442408,0,14.03629709,0,96.67410869 +29.63,50.42400583,-3.51263201,10000,-23.26764943,198.641803,0,14.03629709,0,96.68113458 +29.64,50.42400374,-3.512604101,10000,-23.28505751,198.6395875,0,14.03629709,0,96.68816053 +29.65,50.42400165,-3.512576192,10000,-23.30594722,198.6369272,0,14.03629709,0,96.69518643 +29.66,50.42399956,-3.512548284,10000,-23.34076339,198.6335997,0,14.03629709,0,96.70221238 +29.67,50.42399746,-3.512520376,10000,-23.37557955,198.6300497,0,14.03629709,0,96.70923828 +29.68,50.42399536,-3.512492469,10000,-23.39646924,198.6267222,0,14.03629709,0,96.71626423 +29.69,50.42399326,-3.512464562,10000,-23.41387732,198.6242843,0,14.03629709,0,96.72329012 +29.7,50.42399116,-3.512436656,10000,-23.43476702,198.6225138,0,14.03629709,0,96.73031607 +29.71,50.42398905,-3.512408749,10000,-23.4521751,198.6196311,0,14.03629709,0,96.73734197 +29.72,50.42398695,-3.512380843,10000,-23.47306479,198.6156364,0,14.03629709,0,96.74436792 +29.73,50.42398484,-3.512352939,10000,-23.50788096,198.6125313,0,14.03629709,0,96.75139382 +29.74,50.42398273,-3.512325033,10000,-23.54269713,198.6100935,0,14.03629709,0,96.75841977 +29.75,50.42398061,-3.512297129,10000,-23.56358683,198.6072109,0,14.03629709,0,96.76544566 +29.76,50.4239785,-3.512269225,10000,-23.5809949,198.6043283,0,14.03629709,0,96.77247162 +29.77,50.42397638,-3.512241321,10000,-23.60536621,198.6014457,0,14.03629709,0,96.77949751 +29.78,50.42397426,-3.512213418,10000,-23.63670077,198.5983407,0,14.03629709,0,96.78652346 +29.79,50.42397214,-3.512185515,10000,-23.67151693,198.5956805,0,14.03629709,0,96.79354936 +29.8,50.42397001,-3.512157613,10000,-23.69588823,198.5932428,0,14.03629709,0,96.80057531 +29.81,50.42396788,-3.51212971,10000,-23.70981469,198.5899154,0,14.03629709,0,96.80760121 +29.82,50.42396576,-3.512101809,10000,-23.73418601,198.5863655,0,14.03629709,0,96.81462716 +29.83,50.42396362,-3.512073908,10000,-23.76552057,198.5841502,0,14.03629709,0,96.82165305 +29.84,50.42396149,-3.512046007,10000,-23.78292865,198.5823798,0,14.03629709,0,96.82867895 +29.85,50.42395935,-3.512018106,10000,-23.78989188,198.5790524,0,14.03629709,0,96.8357049 +29.86,50.42395722,-3.511990206,10000,-23.80729995,198.574613,0,14.03629709,0,96.8427308 +29.87,50.42395508,-3.511962307,10000,-23.84559772,198.5712856,0,14.03629709,0,96.84975675 +29.88,50.42395294,-3.511934408,10000,-23.89085874,198.5697376,0,14.03629709,0,96.85678264 +29.89,50.42395079,-3.511906509,10000,-23.91871168,198.5681896,0,14.03629709,0,96.86380859 +29.9,50.42394864,-3.51187861,10000,-23.93263814,198.5648623,0,14.03629709,0,96.87083449 +29.91,50.4239465,-3.511850712,10000,-23.95352784,198.5604229,0,14.03629709,0,96.87786044 +29.92,50.42394434,-3.511822815,10000,-23.97441754,198.5568732,0,14.03629709,0,96.88488634 +29.93,50.42394219,-3.511794918,10000,-23.98834399,198.5544355,0,14.03629709,0,96.89191229 +29.94,50.42394004,-3.511767021,10000,-24.01271529,198.5517755,0,14.03629709,0,96.89893818 +29.95,50.42393788,-3.511739125,10000,-24.04753145,198.5484482,0,14.03629709,0,96.90596414 +29.96,50.42393572,-3.511711229,10000,-24.07886601,198.5451209,0,14.03629709,0,96.91299003 +29.97,50.42393356,-3.511683334,10000,-24.10323734,198.5424609,0,14.03629709,0,96.92001598 +29.98,50.42393139,-3.511655439,10000,-24.12064541,198.5402458,0,14.03629709,0,96.92704188 +29.99,50.42392923,-3.511627544,10000,-24.13805348,198.5375858,0,14.03629709,0,96.93406783 +30,50.42392706,-3.51159965,10000,-24.16242479,198.5342585,0,14.03629709,0,96.94109373 +30.01,50.42392489,-3.511571756,10000,-24.19375935,198.5309313,0,14.03629709,0,96.94811968 +30.02,50.42392272,-3.511543863,10000,-24.22857552,198.5282713,0,14.03629709,0,96.95514557 +30.03,50.42392054,-3.51151597,10000,-24.25294682,198.5260562,0,14.03629709,0,96.96217153 +30.04,50.42391836,-3.511488077,10000,-24.26687327,198.5233963,0,14.03629709,0,96.96919742 +30.05,50.42391619,-3.511460185,10000,-24.29124458,198.5200691,0,14.03629709,0,96.97622337 +30.06,50.423914,-3.511432293,10000,-24.32257915,198.5165195,0,14.03629709,0,96.98324927 +30.07,50.42391182,-3.511404402,10000,-24.33998724,198.5129699,0,14.03629709,0,96.99027522 +30.08,50.42390963,-3.511376511,10000,-24.35043208,198.5096427,0,14.03629709,0,96.99730111 +30.09,50.42390745,-3.511348621,10000,-24.378285,198.5069828,0,14.03629709,0,97.00432707 +30.1,50.42390526,-3.511320731,10000,-24.42006439,198.5047678,0,14.03629709,0,97.01135296 +30.11,50.42390306,-3.511292841,10000,-24.45139894,198.5021079,0,14.03629709,0,97.01837891 +30.12,50.42390087,-3.511264952,10000,-24.47228863,198.4987808,0,14.03629709,0,97.02540481 +30.13,50.42389867,-3.511237063,10000,-24.49317832,198.4952312,0,14.03629709,0,97.03243076 +30.14,50.42389647,-3.511209175,10000,-24.5105864,198.4916817,0,14.03629709,0,97.03945666 +30.15,50.42389427,-3.511181287,10000,-24.52799448,198.4883546,0,14.03629709,0,97.04648261 +30.16,50.42389207,-3.5111534,10000,-24.54888418,198.4856947,0,14.03629709,0,97.0535085 +30.17,50.42388986,-3.511125513,10000,-24.56977388,198.4834797,0,14.03629709,0,97.06053446 +30.18,50.42388766,-3.511097626,10000,-24.60110842,198.4808199,0,14.03629709,0,97.06756035 +30.19,50.42388545,-3.51106974,10000,-24.64288782,198.4774928,0,14.03629709,0,97.0745863 +30.2,50.42388323,-3.511041854,10000,-24.67074075,198.4741658,0,14.03629709,0,97.0816122 +30.21,50.42388102,-3.511013969,10000,-24.6811856,198.471506,0,14.03629709,0,97.08863815 +30.22,50.4238788,-3.510986084,10000,-24.69859368,198.4690686,0,14.03629709,0,97.09566405 +30.23,50.42387659,-3.510958199,10000,-24.72992822,198.4657416,0,14.03629709,0,97.10269 +30.24,50.42387436,-3.510930315,10000,-24.75429953,198.4619697,0,14.03629709,0,97.10971589 +30.25,50.42387214,-3.510902432,10000,-24.76822599,198.4588651,0,14.03629709,0,97.11674179 +30.26,50.42386992,-3.510874548,10000,-24.7925973,198.4562054,0,14.03629709,0,97.12376774 +30.27,50.42386769,-3.510846666,10000,-24.82741347,198.4535456,0,14.03629709,0,97.13079363 +30.28,50.42386546,-3.510818783,10000,-24.85874801,198.450441,0,14.03629709,0,97.13781959 +30.29,50.42386323,-3.510790901,10000,-24.88311931,198.4466692,0,14.03629709,0,97.14484548 +30.3,50.42386099,-3.51076302,10000,-24.90052739,198.4433422,0,14.03629709,0,97.15187143 +30.31,50.42385876,-3.510735139,10000,-24.91793548,198.440905,0,14.03629709,0,97.15889733 +30.32,50.42385652,-3.510707258,10000,-24.94230681,198.4382453,0,14.03629709,0,97.16592328 +30.33,50.42385428,-3.510679378,10000,-24.97015974,198.4349183,0,14.03629709,0,97.17294918 +30.34,50.42385204,-3.510651498,10000,-24.99453105,198.4313689,0,14.03629709,0,97.17997513 +30.35,50.42384979,-3.510623619,10000,-25.01542073,198.4278196,0,14.03629709,0,97.18700102 +30.36,50.42384755,-3.51059574,10000,-25.04675526,198.4244927,0,14.03629709,0,97.19402698 +30.37,50.4238453,-3.510567862,10000,-25.08505304,198.421833,0,14.03629709,0,97.20105287 +30.38,50.42384304,-3.510539984,10000,-25.10246114,198.4196182,0,14.03629709,0,97.20807882 +30.39,50.42384079,-3.510512106,10000,-25.10594275,198.4169586,0,14.03629709,0,97.21510472 +30.4,50.42383854,-3.510484229,10000,-25.12683243,198.4136317,0,14.03629709,0,97.22213067 +30.41,50.42383628,-3.510456352,10000,-25.16164859,198.4103048,0,14.03629709,0,97.22915657 +30.42,50.42383402,-3.510428476,10000,-25.19646477,198.4076452,0,14.03629709,0,97.23618252 +30.43,50.42383176,-3.5104006,10000,-25.23128093,198.405208,0,14.03629709,0,97.24320841 +30.44,50.42382949,-3.510372724,10000,-25.25565224,198.4016588,0,14.03629709,0,97.25023436 +30.45,50.42382722,-3.510344849,10000,-25.2695787,198.3972198,0,14.03629709,0,97.25726026 +30.46,50.42382496,-3.510316975,10000,-25.2904684,198.3936706,0,14.03629709,0,97.26428621 +30.47,50.42382268,-3.510289101,10000,-25.31135809,198.3912334,0,14.03629709,0,97.27131211 +30.48,50.42382041,-3.510261227,10000,-25.32528454,198.3885739,0,14.03629709,0,97.27833806 +30.49,50.42381814,-3.510233354,10000,-25.34965585,198.385247,0,14.03629709,0,97.28536395 +30.5,50.42381586,-3.510205481,10000,-25.38447201,198.3816978,0,14.03629709,0,97.29238991 +30.51,50.42381358,-3.510177609,10000,-25.41580657,198.378371,0,14.03629709,0,97.2994158 +30.52,50.4238113,-3.510149737,10000,-25.44017788,198.3757115,0,14.03629709,0,97.30644175 +30.53,50.42380901,-3.510121866,10000,-25.45758595,198.3732744,0,14.03629709,0,97.31346765 +30.54,50.42380673,-3.510093994,10000,-25.47847565,198.3699477,0,14.03629709,0,97.3204936 +30.55,50.42380444,-3.510066124,10000,-25.51329182,198.3661761,0,14.03629709,0,97.3275195 +30.56,50.42380215,-3.510038254,10000,-25.54810798,198.3630717,0,14.03629709,0,97.33454545 +30.57,50.42379985,-3.510010384,10000,-25.56899767,198.3604123,0,14.03629709,0,97.34157134 +30.58,50.42379756,-3.509982515,10000,-25.58640574,198.3579752,0,14.03629709,0,97.3485973 +30.59,50.42379526,-3.509954646,10000,-25.60729543,198.3555382,0,14.03629709,0,97.35562319 +30.6,50.42379296,-3.509926777,10000,-25.6247035,198.3519891,0,14.03629709,0,97.36264914 +30.61,50.42379066,-3.509898909,10000,-25.64559321,198.3475502,0,14.03629709,0,97.36967504 +30.62,50.42378836,-3.509871042,10000,-25.68040939,198.3440011,0,14.03629709,0,97.37670099 +30.63,50.42378605,-3.509843175,10000,-25.71522556,198.3415641,0,14.03629709,0,97.38372688 +30.64,50.42378374,-3.509815308,10000,-25.73263362,198.3389047,0,14.03629709,0,97.39075284 +30.65,50.42378143,-3.509787442,10000,-25.73959683,198.3355781,0,14.03629709,0,97.39777873 +30.66,50.42377912,-3.509759576,10000,-25.7570049,198.332029,0,14.03629709,0,97.40480463 +30.67,50.42377681,-3.509731711,10000,-25.79182106,198.3284799,0,14.03629709,0,97.41183058 +30.68,50.42377449,-3.509703846,10000,-25.82663723,198.3251532,0,14.03629709,0,97.41885647 +30.69,50.42377217,-3.509675982,10000,-25.84752693,198.3224939,0,14.03629709,0,97.42588243 +30.7,50.42376985,-3.509648118,10000,-25.86841663,198.3200569,0,14.03629709,0,97.43290832 +30.71,50.42376753,-3.509620254,10000,-25.90323279,198.3165079,0,14.03629709,0,97.43993427 +30.72,50.4237652,-3.509592391,10000,-25.93804894,198.3120692,0,14.03629709,0,97.44696017 +30.73,50.42376287,-3.509564529,10000,-25.95545701,198.3087426,0,14.03629709,0,97.45398612 +30.74,50.42376054,-3.509536667,10000,-25.96242024,198.306973,0,14.03629709,0,97.46101202 +30.75,50.42375821,-3.509508805,10000,-25.97982833,198.3047585,0,14.03629709,0,97.46803797 +30.76,50.42375588,-3.509480943,10000,-26.0146445,198.3009871,0,14.03629709,0,97.47506386 +30.77,50.42375354,-3.509453083,10000,-26.04946066,198.2967708,0,14.03629709,0,97.48208982 +30.78,50.4237512,-3.509425222,10000,-26.07035034,198.2932218,0,14.03629709,0,97.48911571 +30.79,50.42374886,-3.509397363,10000,-26.09124003,198.2905626,0,14.03629709,0,97.49614166 +30.8,50.42374652,-3.509369503,10000,-26.12257459,198.2881257,0,14.03629709,0,97.50316756 +30.81,50.42374417,-3.509341644,10000,-26.1469459,198.2845768,0,14.03629709,0,97.51019351 +30.82,50.42374182,-3.509313785,10000,-26.16087235,198.2801381,0,14.03629709,0,97.5172194 +30.83,50.42373948,-3.509285928,10000,-26.18524366,198.2765892,0,14.03629709,0,97.52424536 +30.84,50.42373712,-3.50925807,10000,-26.2165782,198.2743748,0,14.03629709,0,97.53127125 +30.85,50.42373477,-3.509230213,10000,-26.23746791,198.2723829,0,14.03629709,0,97.5382972 +30.86,50.42373241,-3.509202356,10000,-26.2583576,198.2695012,0,14.03629709,0,97.5453231 +30.87,50.42373006,-3.509174499,10000,-26.28969213,198.2657299,0,14.03629709,0,97.55234905 +30.88,50.42372769,-3.509146644,10000,-26.31406343,198.262181,0,14.03629709,0,97.55937495 +30.89,50.42372533,-3.509118788,10000,-26.32798991,198.2588546,0,14.03629709,0,97.5664009 +30.9,50.42372297,-3.509090933,10000,-26.35236122,198.2548608,0,14.03629709,0,97.57342679 +30.91,50.4237206,-3.509063079,10000,-26.38369576,198.2508671,0,14.03629709,0,97.58045275 +30.92,50.42371823,-3.509035225,10000,-26.40458545,198.2479856,0,14.03629709,0,97.58747864 +30.93,50.42371586,-3.509007372,10000,-26.42547515,198.2455488,0,14.03629709,0,97.59450459 +30.94,50.42371349,-3.508979518,10000,-26.46029132,198.2422224,0,14.03629709,0,97.60153049 +30.95,50.42371111,-3.508951666,10000,-26.49510747,198.2384512,0,14.03629709,0,97.60855644 +30.96,50.42370873,-3.508923814,10000,-26.51599716,198.2353472,0,14.03629709,0,97.61558234 +30.97,50.42370635,-3.508895962,10000,-26.53340524,198.2326881,0,14.03629709,0,97.62260829 +30.98,50.42370397,-3.508868111,10000,-26.55429493,198.2302514,0,14.03629709,0,97.62963418 +30.99,50.42370158,-3.50884026,10000,-26.571703,198.2278147,0,14.03629709,0,97.63666013 +31,50.4236992,-3.508812409,10000,-26.58911108,198.2242659,0,14.03629709,0,97.64368603 +31.01,50.42369681,-3.508784559,10000,-26.61348242,198.219605,0,14.03629709,0,97.65071198 +31.02,50.42369442,-3.50875671,10000,-26.64481697,198.2151666,0,14.03629709,0,97.65773788 +31.03,50.42369203,-3.508728861,10000,-26.68311473,198.2116178,0,14.03629709,0,97.66476383 +31.04,50.42368963,-3.508701013,10000,-26.71793087,198.2089588,0,14.03629709,0,97.67178972 +31.05,50.42368723,-3.508673165,10000,-26.73533895,198.2067446,0,14.03629709,0,97.67881562 +31.06,50.42368483,-3.508645317,10000,-26.74230217,198.2040855,0,14.03629709,0,97.68584157 +31.07,50.42368243,-3.50861747,10000,-26.75971025,198.2007592,0,14.03629709,0,97.69286747 +31.08,50.42368003,-3.508589623,10000,-26.79452641,198.1972105,0,14.03629709,0,97.69989342 +31.09,50.42367762,-3.508561777,10000,-26.82934258,198.1936618,0,14.03629709,0,97.70691931 +31.1,50.42367521,-3.508533931,10000,-26.85023227,198.1901131,0,14.03629709,0,97.71394527 +31.11,50.4236728,-3.508506086,10000,-26.86764035,198.1865644,0,14.03629709,0,97.72097116 +31.12,50.42367039,-3.508478241,10000,-26.88853003,198.1832382,0,14.03629709,0,97.72799711 +31.13,50.42366797,-3.508450397,10000,-26.9059381,198.1803568,0,14.03629709,0,97.73502301 +31.14,50.42366556,-3.508422553,10000,-26.92682779,198.1772529,0,14.03629709,0,97.74204896 +31.15,50.42366314,-3.508394709,10000,-26.96164397,198.1734819,0,14.03629709,0,97.74907486 +31.16,50.42366072,-3.508366867,10000,-26.99646014,198.1701556,0,14.03629709,0,97.75610081 +31.17,50.42365829,-3.508339024,10000,-27.01734983,198.1674967,0,14.03629709,0,97.7631267 +31.18,50.42365587,-3.508311182,10000,-27.0382395,198.1639481,0,14.03629709,0,97.77015265 +31.19,50.42365344,-3.50828334,10000,-27.07305565,198.1597322,0,14.03629709,0,97.77717855 +31.2,50.42365101,-3.5082555,10000,-27.10787182,198.1568509,0,14.03629709,0,97.7842045 +31.21,50.42364857,-3.508227659,10000,-27.12876152,198.1546368,0,14.03629709,0,97.7912304 +31.22,50.42364614,-3.508199818,10000,-27.14616961,198.1508658,0,14.03629709,0,97.79825635 +31.23,50.4236437,-3.508171979,10000,-27.16705931,198.1464275,0,14.03629709,0,97.80528224 +31.24,50.42364126,-3.50814414,10000,-27.18446738,198.1431014,0,14.03629709,0,97.8123082 +31.25,50.42363882,-3.508116301,10000,-27.20187544,198.1402201,0,14.03629709,0,97.81933409 +31.26,50.42363638,-3.508088463,10000,-27.22276512,198.1368939,0,14.03629709,0,97.82636004 +31.27,50.42363393,-3.508060625,10000,-27.24365481,198.1335678,0,14.03629709,0,97.83338594 +31.28,50.42363149,-3.508032788,10000,-27.27498937,198.130909,0,14.03629709,0,97.84041189 +31.29,50.42362904,-3.508004951,10000,-27.31676877,198.1284725,0,14.03629709,0,97.84743779 +31.3,50.42362658,-3.507977114,10000,-27.34810331,198.124924,0,14.03629709,0,97.85446374 +31.31,50.42362413,-3.507949278,10000,-27.36899299,198.1202634,0,14.03629709,0,97.86148963 +31.32,50.42362167,-3.507921443,10000,-27.38988268,198.1160476,0,14.03629709,0,97.86851559 +31.33,50.42361921,-3.507893608,10000,-27.40380915,198.1131664,0,14.03629709,0,97.87554148 +31.34,50.42361675,-3.507865774,10000,-27.41077238,198.11073,0,14.03629709,0,97.88256743 +31.35,50.42361429,-3.507837939,10000,-27.42818045,198.1071816,0,14.03629709,0,97.88959333 +31.36,50.42361183,-3.507810106,10000,-27.4629966,198.102521,0,14.03629709,0,97.89661928 +31.37,50.42360936,-3.507782273,10000,-27.50129438,198.0983053,0,14.03629709,0,97.90364517 +31.38,50.42360689,-3.507754441,10000,-27.53262893,198.0954241,0,14.03629709,0,97.91067113 +31.39,50.42360442,-3.507726609,10000,-27.55700024,198.0932102,0,14.03629709,0,97.91769702 +31.4,50.42360194,-3.507698777,10000,-27.57440831,198.0905514,0,14.03629709,0,97.92472297 +31.41,50.42359947,-3.507670946,10000,-27.59181637,198.0872254,0,14.03629709,0,97.93174887 +31.42,50.42359699,-3.507643115,10000,-27.61618768,198.083677,0,14.03629709,0,97.93877482 +31.43,50.42359451,-3.507615285,10000,-27.64752223,198.0801286,0,14.03629709,0,97.94580072 +31.44,50.42359203,-3.507587455,10000,-27.68582001,198.0765802,0,14.03629709,0,97.95282667 +31.45,50.42358954,-3.507559626,10000,-27.72063617,198.0730318,0,14.03629709,0,97.95985256 +31.46,50.42358705,-3.507531797,10000,-27.73804424,198.0694834,0,14.03629709,0,97.96687846 +31.47,50.42358456,-3.507503969,10000,-27.74500746,198.0659351,0,14.03629709,0,97.97390441 +31.48,50.42358207,-3.507476141,10000,-27.75893393,198.0626091,0,14.03629709,0,97.98093031 +31.49,50.42357958,-3.507448314,10000,-27.77982363,198.0599505,0,14.03629709,0,97.98795626 +31.5,50.42357708,-3.507420487,10000,-27.80071332,198.0575142,0,14.03629709,0,97.99498215 +31.51,50.42357459,-3.50739266,10000,-27.83204785,198.0539659,0,14.03629709,0,98.00200811 +31.52,50.42357209,-3.507364834,10000,-27.87382725,198.0493055,0,14.03629709,0,98.009034 +31.53,50.42356958,-3.507337009,10000,-27.90516179,198.0448675,0,14.03629709,0,98.01605995 +31.54,50.42356708,-3.507309184,10000,-27.92605147,198.0413191,0,14.03629709,0,98.02308585 +31.55,50.42356457,-3.50728136,10000,-27.94694116,198.0386605,0,14.03629709,0,98.0301118 +31.56,50.42356206,-3.507253536,10000,-27.96434925,198.0362244,0,14.03629709,0,98.03713769 +31.57,50.42355955,-3.507225712,10000,-27.98175732,198.0326761,0,14.03629709,0,98.04416365 +31.58,50.42355704,-3.507197889,10000,-28.00264701,198.0282381,0,14.03629709,0,98.05118954 +31.59,50.42355452,-3.507170067,10000,-28.02005508,198.0246898,0,14.03629709,0,98.05821549 +31.6,50.42355201,-3.507142245,10000,-28.04094478,198.0220313,0,14.03629709,0,98.06524139 +31.61,50.42354949,-3.507114423,10000,-28.07576095,198.018483,0,14.03629709,0,98.07226734 +31.62,50.42354697,-3.507086602,10000,-28.1105771,198.0140451,0,14.03629709,0,98.07929324 +31.63,50.42354444,-3.507058782,10000,-28.13146678,198.0104968,0,14.03629709,0,98.08631919 +31.64,50.42354192,-3.507030962,10000,-28.15235647,198.0080607,0,14.03629709,0,98.09334508 +31.65,50.42353939,-3.507003142,10000,-28.18717262,198.0054022,0,14.03629709,0,98.10037104 +31.66,50.42353686,-3.506975323,10000,-28.22198879,198.001854,0,14.03629709,0,98.10739693 +31.67,50.42353432,-3.506947504,10000,-28.24287849,197.9974161,0,14.03629709,0,98.11442288 +31.68,50.42353179,-3.506919686,10000,-28.26028657,197.9929783,0,14.03629709,0,98.12144878 +31.69,50.42352925,-3.506891869,10000,-28.28117625,197.9900973,0,14.03629709,0,98.12847473 +31.7,50.42352671,-3.506864052,10000,-28.29858431,197.9878837,0,14.03629709,0,98.13550063 +31.71,50.42352417,-3.506836234,10000,-28.31947401,197.9841131,0,14.03629709,0,98.14252658 +31.72,50.42352163,-3.506808419,10000,-28.35429017,197.9796753,0,14.03629709,0,98.14955247 +31.73,50.42351908,-3.506780603,10000,-28.38910633,197.9763496,0,14.03629709,0,98.15657842 +31.74,50.42351653,-3.506752788,10000,-28.40651441,197.9734687,0,14.03629709,0,98.16360432 +31.75,50.42351398,-3.506724973,10000,-28.41347763,197.970143,0,14.03629709,0,98.17063027 +31.76,50.42351143,-3.506697159,10000,-28.43088569,197.9665949,0,14.03629709,0,98.17765617 +31.77,50.42350888,-3.506669345,10000,-28.46570185,197.9630468,0,14.03629709,0,98.18468212 +31.78,50.42350632,-3.506641532,10000,-28.50051802,197.9594987,0,14.03629709,0,98.19170801 +31.79,50.42350376,-3.506613719,10000,-28.52140772,197.9559506,0,14.03629709,0,98.19873397 +31.8,50.4235012,-3.506585907,10000,-28.5422974,197.9524025,0,14.03629709,0,98.20575986 +31.81,50.42349864,-3.506558095,10000,-28.57711355,197.9488544,0,14.03629709,0,98.21278581 +31.82,50.42349607,-3.506530284,10000,-28.61192972,197.9453063,0,14.03629709,0,98.21981171 +31.83,50.4234935,-3.506502473,10000,-28.62933779,197.9417583,0,14.03629709,0,98.22683766 +31.84,50.42349093,-3.506474663,10000,-28.636301,197.9382102,0,14.03629709,0,98.23386356 +31.85,50.42348836,-3.506446853,10000,-28.65370907,197.9346622,0,14.03629709,0,98.24088945 +31.86,50.42348579,-3.506419044,10000,-28.68852524,197.9311142,0,14.03629709,0,98.2479154 +31.87,50.42348321,-3.506391235,10000,-28.72334141,197.9275661,0,14.03629709,0,98.2549413 +31.88,50.42348063,-3.506363427,10000,-28.7442311,197.9240181,0,14.03629709,0,98.26196725 +31.89,50.42347805,-3.506335619,10000,-28.76163917,197.9204701,0,14.03629709,0,98.26899315 +31.9,50.42347547,-3.506307812,10000,-28.78252885,197.9169221,0,14.03629709,0,98.2760191 +31.91,50.42347288,-3.506280005,10000,-28.79993692,197.9135966,0,14.03629709,0,98.28304499 +31.92,50.4234703,-3.506252199,10000,-28.8208266,197.9107158,0,14.03629709,0,98.29007094 +31.93,50.42346771,-3.506224393,10000,-28.85564276,197.9076127,0,14.03629709,0,98.29709684 +31.94,50.42346512,-3.506196587,10000,-28.89045893,197.9038423,0,14.03629709,0,98.30412279 +31.95,50.42346252,-3.506168783,10000,-28.91134864,197.9002944,0,14.03629709,0,98.31114869 +31.96,50.42345993,-3.506140978,10000,-28.93223833,197.8969689,0,14.03629709,0,98.31817464 +31.97,50.42345733,-3.506113174,10000,-28.96705447,197.8929761,0,14.03629709,0,98.32520053 +31.98,50.42345473,-3.506085371,10000,-29.00187063,197.8887609,0,14.03629709,0,98.33222649 +31.99,50.42345212,-3.506057568,10000,-29.02276032,197.8849906,0,14.03629709,0,98.33925238 +32,50.42344952,-3.506029766,10000,-29.04016839,197.8814427,0,14.03629709,0,98.34627833 +32.01,50.42344691,-3.506001964,10000,-29.06105808,197.8778948,0,14.03629709,0,98.35330423 +32.02,50.4234443,-3.505974163,10000,-29.07846616,197.8743469,0,14.03629709,0,98.36033018 +32.03,50.42344169,-3.505946362,10000,-29.09587423,197.870799,0,14.03629709,0,98.36735608 +32.04,50.42343908,-3.505918562,10000,-29.11676391,197.8672511,0,14.03629709,0,98.37438203 +32.05,50.42343646,-3.505890762,10000,-29.1376536,197.8637032,0,14.03629709,0,98.38140792 +32.06,50.42343385,-3.505862963,10000,-29.16898815,197.8601554,0,14.03629709,0,98.38843388 +32.07,50.42343123,-3.505835164,10000,-29.21076754,197.8566075,0,14.03629709,0,98.39545977 +32.08,50.4234286,-3.505807366,10000,-29.23862047,197.8530597,0,14.03629709,0,98.40248572 +32.09,50.42342598,-3.505779568,10000,-29.24906531,197.8495119,0,14.03629709,0,98.40951162 +32.1,50.42342335,-3.505751771,10000,-29.26647337,197.845964,0,14.03629709,0,98.41653757 +32.11,50.42342073,-3.505723974,10000,-29.2978079,197.8424162,0,14.03629709,0,98.42356346 +32.12,50.42341809,-3.505696178,10000,-29.3221792,197.8388684,0,14.03629709,0,98.43058942 +32.13,50.42341546,-3.505668382,10000,-29.33610567,197.8353206,0,14.03629709,0,98.43761531 +32.14,50.42341283,-3.505640587,10000,-29.36047699,197.8317728,0,14.03629709,0,98.44464126 +32.15,50.42341019,-3.505612792,10000,-29.39529314,197.828225,0,14.03629709,0,98.45166716 +32.16,50.42340755,-3.505584998,10000,-29.42662768,197.8246773,0,14.03629709,0,98.45869311 +32.17,50.42340491,-3.505557204,10000,-29.45099899,197.8211295,0,14.03629709,0,98.46571901 +32.18,50.42340226,-3.505529411,10000,-29.46840706,197.8175818,0,14.03629709,0,98.47274496 +32.19,50.42339962,-3.505501618,10000,-29.48581513,197.814034,0,14.03629709,0,98.47977085 +32.2,50.42339697,-3.505473826,10000,-29.51018643,197.8102639,0,14.03629709,0,98.48679681 +32.21,50.42339432,-3.505446034,10000,-29.53803935,197.8058264,0,14.03629709,0,98.4938227 +32.22,50.42339167,-3.505418243,10000,-29.56241066,197.8011666,0,14.03629709,0,98.50084865 +32.23,50.42338901,-3.505390453,10000,-29.58330034,197.7978413,0,14.03629709,0,98.50787455 +32.24,50.42338636,-3.505362663,10000,-29.61463488,197.796073,0,14.03629709,0,98.5149005 +32.25,50.4233837,-3.505334873,10000,-29.65293267,197.7936374,0,14.03629709,0,98.52192639 +32.26,50.42338103,-3.505307083,10000,-29.67034074,197.7892001,0,14.03629709,0,98.52895229 +32.27,50.42337837,-3.505279295,10000,-29.67382234,197.7843178,0,14.03629709,0,98.53597824 +32.28,50.42337571,-3.505251507,10000,-29.69471203,197.7801029,0,14.03629709,0,98.54300414 +32.29,50.42337304,-3.505223719,10000,-29.7295282,197.7761104,0,14.03629709,0,98.55003009 +32.3,50.42337037,-3.505195933,10000,-29.76434436,197.7727852,0,14.03629709,0,98.55705598 +32.31,50.4233677,-3.505168146,10000,-29.79916051,197.7703496,0,14.03629709,0,98.56408194 +32.32,50.42336502,-3.50514036,10000,-29.82005019,197.7674693,0,14.03629709,0,98.57110783 +32.33,50.42336234,-3.505112574,10000,-29.82353179,197.7632544,0,14.03629709,0,98.57813378 +32.34,50.42335967,-3.505084789,10000,-29.84093986,197.7585947,0,14.03629709,0,98.58515968 +32.35,50.42335699,-3.505057005,10000,-29.87923764,197.7550471,0,14.03629709,0,98.59218563 +32.36,50.4233543,-3.505029221,10000,-29.91057219,197.7523891,0,14.03629709,0,98.59921153 +32.37,50.42335162,-3.505001437,10000,-29.93146187,197.7488416,0,14.03629709,0,98.60623748 +32.38,50.42334893,-3.504973654,10000,-29.95583317,197.7441819,0,14.03629709,0,98.61326337 +32.39,50.42334624,-3.504945872,10000,-29.98368609,197.7397446,0,14.03629709,0,98.62028933 +32.4,50.42334355,-3.50491809,10000,-30.00805741,197.736197,0,14.03629709,0,98.62731522 +32.41,50.42334085,-3.504890309,10000,-30.02546548,197.7333168,0,14.03629709,0,98.63434117 +32.42,50.42333816,-3.504862528,10000,-30.04287355,197.7302141,0,14.03629709,0,98.64136707 +32.43,50.42333546,-3.504834747,10000,-30.06724485,197.7262217,0,14.03629709,0,98.64839302 +32.44,50.42333276,-3.504806968,10000,-30.09509777,197.7220069,0,14.03629709,0,98.65541891 +32.45,50.42333006,-3.504779188,10000,-30.11946907,197.7182369,0,14.03629709,0,98.66244487 +32.46,50.42332735,-3.50475141,10000,-30.14035876,197.7146894,0,14.03629709,0,98.66947076 +32.47,50.42332465,-3.504723631,10000,-30.1716933,197.7111419,0,14.03629709,0,98.67649671 +32.48,50.42332194,-3.504695854,10000,-30.20999107,197.7075944,0,14.03629709,0,98.68352261 +32.49,50.42331922,-3.504668076,10000,-30.22739915,197.7040469,0,14.03629709,0,98.69054856 +32.5,50.42331651,-3.5046403,10000,-30.23088076,197.700277,0,14.03629709,0,98.69757446 +32.51,50.4233138,-3.504612523,10000,-30.25177045,197.6960623,0,14.03629709,0,98.70460041 +32.52,50.42331108,-3.504584748,10000,-30.2865866,197.69207,0,14.03629709,0,98.7116263 +32.53,50.42330836,-3.504556973,10000,-30.32140276,197.6889674,0,14.03629709,0,98.71865226 +32.54,50.42330564,-3.504529198,10000,-30.35621892,197.6860872,0,14.03629709,0,98.72567815 +32.55,50.42330291,-3.504501424,10000,-30.38059022,197.6825398,0,14.03629709,0,98.7327041 +32.56,50.42330018,-3.50447365,10000,-30.39451666,197.6781027,0,14.03629709,0,98.73973 +32.57,50.42329746,-3.504445877,10000,-30.41540634,197.6734432,0,14.03629709,0,98.74675595 +32.58,50.42329472,-3.504418105,10000,-30.43629604,197.6696733,0,14.03629709,0,98.75378185 +32.59,50.42329199,-3.504390333,10000,-30.45022251,197.6663483,0,14.03629709,0,98.7608078 +32.6,50.42328926,-3.504362561,10000,-30.47459382,197.6625785,0,14.03629709,0,98.76783369 +32.61,50.42328652,-3.504334791,10000,-30.50940996,197.6590311,0,14.03629709,0,98.77485964 +32.62,50.42328378,-3.50430702,10000,-30.54074449,197.6557062,0,14.03629709,0,98.78188554 +32.63,50.42328104,-3.50427925,10000,-30.5651158,197.651714,0,14.03629709,0,98.78891149 +32.64,50.42327829,-3.504251481,10000,-30.58252387,197.6474994,0,14.03629709,0,98.79593739 +32.65,50.42327555,-3.504223712,10000,-30.59993194,197.6437296,0,14.03629709,0,98.80296334 +32.66,50.4232728,-3.504195944,10000,-30.62430325,197.6401823,0,14.03629709,0,98.80998923 +32.67,50.42327005,-3.504168176,10000,-30.65563779,197.6366349,0,14.03629709,0,98.81701513 +32.68,50.4232673,-3.504140409,10000,-30.69393556,197.6330876,0,14.03629709,0,98.82404108 +32.69,50.42326454,-3.504112642,10000,-30.72875172,197.6295403,0,14.03629709,0,98.83106698 +32.7,50.42326178,-3.504084876,10000,-30.74615977,197.6257706,0,14.03629709,0,98.83809293 +32.71,50.42325902,-3.50405711,10000,-30.75312299,197.621556,0,14.03629709,0,98.84511882 +32.72,50.42325626,-3.504029345,10000,-30.76704945,197.6175639,0,14.03629709,0,98.85214478 +32.73,50.4232535,-3.504001581,10000,-30.78793916,197.614239,0,14.03629709,0,98.85917067 +32.74,50.42325073,-3.503973816,10000,-30.80882885,197.6104693,0,14.03629709,0,98.86619662 +32.75,50.42324797,-3.503946053,10000,-30.84016337,197.6058099,0,14.03629709,0,98.87322252 +32.76,50.4232452,-3.50391829,10000,-30.88194275,197.6015954,0,14.03629709,0,98.88024847 +32.77,50.42324242,-3.503890528,10000,-30.91327729,197.598493,0,14.03629709,0,98.88727437 +32.78,50.42323965,-3.503862766,10000,-30.93416699,197.5953906,0,14.03629709,0,98.89430032 +32.79,50.42323687,-3.503835004,10000,-30.95505668,197.5913986,0,14.03629709,0,98.90132621 +32.8,50.42323409,-3.503807244,10000,-30.97246473,197.5871841,0,14.03629709,0,98.90835216 +32.81,50.42323131,-3.503779483,10000,-30.9898728,197.5834145,0,14.03629709,0,98.91537806 +32.82,50.42322853,-3.503751724,10000,-31.01076249,197.5796448,0,14.03629709,0,98.92240401 +32.83,50.42322574,-3.503723964,10000,-31.02817057,197.5754304,0,14.03629709,0,98.92942991 +32.84,50.42322296,-3.503696206,10000,-31.04906026,197.5714383,0,14.03629709,0,98.93645586 +32.85,50.42322017,-3.503668448,10000,-31.08387642,197.568336,0,14.03629709,0,98.94348175 +32.86,50.42321738,-3.50364069,10000,-31.11869257,197.5654561,0,14.03629709,0,98.95050771 +32.87,50.42321458,-3.503612933,10000,-31.13958225,197.5619089,0,14.03629709,0,98.9575336 +32.88,50.42321179,-3.503585176,10000,-31.16047193,197.5576945,0,14.03629709,0,98.96455955 +32.89,50.42320899,-3.50355742,10000,-31.19528809,197.5537025,0,14.03629709,0,98.97158545 +32.9,50.42320619,-3.503529665,10000,-31.23010425,197.5503778,0,14.03629709,0,98.9786114 +32.91,50.42320338,-3.503501909,10000,-31.25099393,197.5466083,0,14.03629709,0,98.9856373 +32.92,50.42320058,-3.503474155,10000,-31.268402,197.5419491,0,14.03629709,0,98.99266325 +32.93,50.42319777,-3.503446401,10000,-31.28929169,197.5375123,0,14.03629709,0,98.99968914 +32.94,50.42319496,-3.503418648,10000,-31.30669976,197.5337427,0,14.03629709,0,99.0067151 +32.95,50.42319215,-3.503390895,10000,-31.32758944,197.5299732,0,14.03629709,0,99.01374099 +32.96,50.42318934,-3.503363143,10000,-31.36240559,197.5255365,0,14.03629709,0,99.02076694 +32.97,50.42318652,-3.503335391,10000,-31.39722176,197.5208773,0,14.03629709,0,99.02779284 +32.98,50.4231837,-3.503307641,10000,-31.41462984,197.5173302,0,14.03629709,0,99.03481879 +32.99,50.42318088,-3.50327989,10000,-31.42159306,197.5148953,0,14.03629709,0,99.04184468 +33,50.42317806,-3.50325214,10000,-31.43900112,197.5120155,0,14.03629709,0,99.04887064 +33.01,50.42317524,-3.50322439,10000,-31.47381727,197.5078012,0,14.03629709,0,99.05589653 +33.02,50.42317241,-3.503196641,10000,-31.50863342,197.5029196,0,14.03629709,0,99.06292248 +33.03,50.42316958,-3.503168893,10000,-31.52952311,197.4984829,0,14.03629709,0,99.06994838 +33.04,50.42316675,-3.503141145,10000,-31.54693117,197.4949359,0,14.03629709,0,99.07697433 +33.05,50.42316392,-3.503113398,10000,-31.56782085,197.4920562,0,14.03629709,0,99.08400023 +33.06,50.42316108,-3.503085651,10000,-31.58871054,197.4887316,0,14.03629709,0,99.09102612 +33.07,50.42315825,-3.503057904,10000,-31.62004509,197.4840725,0,14.03629709,0,99.09805207 +33.08,50.42315541,-3.503030159,10000,-31.66182449,197.4794134,0,14.03629709,0,99.10507797 +33.09,50.42315256,-3.503002414,10000,-31.68967741,197.4758664,0,14.03629709,0,99.11210392 +33.1,50.42314972,-3.502974669,10000,-31.70012223,197.4723195,0,14.03629709,0,99.11912982 +33.11,50.42314687,-3.502946925,10000,-31.71753028,197.4685501,0,14.03629709,0,99.12615577 +33.12,50.42314403,-3.502919182,10000,-31.74886482,197.4652256,0,14.03629709,0,99.13318166 +33.13,50.42314117,-3.502891438,10000,-31.77323614,197.4614562,0,14.03629709,0,99.14020762 +33.14,50.42313832,-3.502863696,10000,-31.7871626,197.4565747,0,14.03629709,0,99.14723351 +33.15,50.42313547,-3.502835954,10000,-31.81153389,197.4514709,0,14.03629709,0,99.15425946 +33.16,50.42313261,-3.502808213,10000,-31.84286842,197.4474791,0,14.03629709,0,99.16128536 +33.17,50.42312975,-3.502780473,10000,-31.86375812,197.4450443,0,14.03629709,0,99.16831131 +33.18,50.42312689,-3.502752732,10000,-31.88464782,197.4423871,0,14.03629709,0,99.1753372 +33.19,50.42312403,-3.502724992,10000,-31.91946396,197.4377281,0,14.03629709,0,99.18236316 +33.2,50.42312116,-3.502697253,10000,-31.9542801,197.4324019,0,14.03629709,0,99.18938905 +33.21,50.42311829,-3.502669515,10000,-31.97168817,197.4286326,0,14.03629709,0,99.196415 +33.22,50.42311542,-3.502641777,10000,-31.9786514,197.4259754,0,14.03629709,0,99.2034409 +33.23,50.42311255,-3.502614039,10000,-31.99605947,197.4224286,0,14.03629709,0,99.21046685 +33.24,50.42310968,-3.502586302,10000,-32.03087562,197.4177696,0,14.03629709,0,99.21749275 +33.25,50.4231068,-3.502558566,10000,-32.06569177,197.4133331,0,14.03629709,0,99.2245187 +33.26,50.42310392,-3.50253083,10000,-32.08658146,197.4095638,0,14.03629709,0,99.23154459 +33.27,50.42310104,-3.502503095,10000,-32.10747115,197.4057946,0,14.03629709,0,99.23857055 +33.28,50.42309816,-3.50247536,10000,-32.1422873,197.4013581,0,14.03629709,0,99.24559644 +33.29,50.42309527,-3.502447626,10000,-32.17710345,197.3966992,0,14.03629709,0,99.25262239 +33.3,50.42309238,-3.502419893,10000,-32.19451152,197.39293,0,14.03629709,0,99.25964829 +33.31,50.42308949,-3.50239216,10000,-32.20147473,197.3896056,0,14.03629709,0,99.26667424 +33.32,50.4230866,-3.502364427,10000,-32.2188828,197.3858364,0,14.03629709,0,99.27370014 +33.33,50.42308371,-3.502336696,10000,-32.25369894,197.3822897,0,14.03629709,0,99.28072609 +33.34,50.42308081,-3.502308964,10000,-32.2885151,197.3789653,0,14.03629709,0,99.28775198 +33.35,50.42307791,-3.502281233,10000,-32.30592319,197.3749737,0,14.03629709,0,99.29477793 +33.36,50.42307501,-3.502253503,10000,-32.31288641,197.3705373,0,14.03629709,0,99.30180383 +33.37,50.42307211,-3.502225773,10000,-32.33029447,197.3658784,0,14.03629709,0,99.30882978 +33.38,50.42306921,-3.502198044,10000,-32.36511061,197.3609972,0,14.03629709,0,99.31585568 +33.39,50.4230663,-3.502170316,10000,-32.40340839,197.3567832,0,14.03629709,0,99.32288163 +33.4,50.42306339,-3.502142588,10000,-32.43474294,197.3539038,0,14.03629709,0,99.32990752 +33.41,50.42306048,-3.502114861,10000,-32.45911424,197.3514692,0,14.03629709,0,99.33693348 +33.42,50.42305756,-3.502087133,10000,-32.4765223,197.3479225,0,14.03629709,0,99.34395937 +33.43,50.42305465,-3.502059407,10000,-32.49393036,197.3430413,0,14.03629709,0,99.35098532 +33.44,50.42305173,-3.502031681,10000,-32.51830166,197.3379377,0,14.03629709,0,99.35801122 +33.45,50.42304881,-3.502003956,10000,-32.54615458,197.3337237,0,14.03629709,0,99.36503717 +33.46,50.42304589,-3.501976232,10000,-32.57052588,197.3303995,0,14.03629709,0,99.37206307 +33.47,50.42304296,-3.501948507,10000,-32.58793394,197.3266304,0,14.03629709,0,99.37908896 +33.48,50.42304004,-3.501920784,10000,-32.60534199,197.3219717,0,14.03629709,0,99.38611491 +33.49,50.42303711,-3.501893061,10000,-32.6297133,197.3175353,0,14.03629709,0,99.39314081 +33.5,50.42303418,-3.501865339,10000,-32.66104786,197.3137663,0,14.03629709,0,99.40016676 +33.51,50.42303125,-3.501837617,10000,-32.69934564,197.3102197,0,14.03629709,0,99.40719266 +33.52,50.42302831,-3.501809896,10000,-32.73416178,197.3064507,0,14.03629709,0,99.41421861 +33.53,50.42302537,-3.501782175,10000,-32.75156983,197.3022368,0,14.03629709,0,99.4212445 +33.54,50.42302243,-3.501754455,10000,-32.75853306,197.2982454,0,14.03629709,0,99.42827045 +33.55,50.42301949,-3.501726736,10000,-32.77594114,197.2949212,0,14.03629709,0,99.43529635 +33.56,50.42301655,-3.501699016,10000,-32.8107573,197.2911522,0,14.03629709,0,99.4423223 +33.57,50.4230136,-3.501671298,10000,-32.84557344,197.2864936,0,14.03629709,0,99.4493482 +33.58,50.42301065,-3.50164358,10000,-32.86298149,197.2820573,0,14.03629709,0,99.45637415 +33.59,50.4230077,-3.501615863,10000,-32.86994471,197.2780659,0,14.03629709,0,99.46340004 +33.6,50.42300475,-3.501588146,10000,-32.88735278,197.2736297,0,14.03629709,0,99.470426 +33.61,50.4230018,-3.50156043,10000,-32.92216894,197.268971,0,14.03629709,0,99.47745189 +33.62,50.42299884,-3.501532715,10000,-32.9604667,197.2654245,0,14.03629709,0,99.48447784 +33.63,50.42299588,-3.501505,10000,-32.99180124,197.2627677,0,14.03629709,0,99.49150374 +33.64,50.42299292,-3.501477285,10000,-33.01617255,197.2589988,0,14.03629709,0,99.49852969 +33.65,50.42298995,-3.501449571,10000,-33.03358061,197.2536729,0,14.03629709,0,99.50555559 +33.66,50.42298699,-3.501421858,10000,-33.05098868,197.2487919,0,14.03629709,0,99.51258154 +33.67,50.42298402,-3.501394146,10000,-33.07535999,197.2452454,0,14.03629709,0,99.51960743 +33.68,50.42298105,-3.501366433,10000,-33.1032129,197.241699,0,14.03629709,0,99.52663339 +33.69,50.42297808,-3.501338722,10000,-33.12758419,197.2377077,0,14.03629709,0,99.53365928 +33.7,50.4229751,-3.501311011,10000,-33.14499225,197.2337164,0,14.03629709,0,99.54068523 +33.71,50.42297213,-3.5012833,10000,-33.16240032,197.2297251,0,14.03629709,0,99.54771113 +33.72,50.42296915,-3.501255591,10000,-33.18677163,197.2261786,0,14.03629709,0,99.55473708 +33.73,50.42296617,-3.501227881,10000,-33.21810618,197.2226322,0,14.03629709,0,99.56176297 +33.74,50.42296319,-3.501200172,10000,-33.25640395,197.2177513,0,14.03629709,0,99.56878893 +33.75,50.4229602,-3.501172464,10000,-33.29122008,197.2124255,0,14.03629709,0,99.57581482 +33.76,50.42295721,-3.501144757,10000,-33.30862814,197.2084342,0,14.03629709,0,99.58284077 +33.77,50.42295422,-3.50111705,10000,-33.31559136,197.2051103,0,14.03629709,0,99.58986667 +33.78,50.42295123,-3.501089343,10000,-33.33299944,197.201119,0,14.03629709,0,99.59689262 +33.79,50.42294824,-3.501061638,10000,-33.36781559,197.196683,0,14.03629709,0,99.60391852 +33.8,50.42294524,-3.501033932,10000,-33.40263174,197.1922469,0,14.03629709,0,99.61094447 +33.81,50.42294224,-3.501006228,10000,-33.42003981,197.1882557,0,14.03629709,0,99.61797036 +33.82,50.42293924,-3.500978524,10000,-33.42700303,197.1849318,0,14.03629709,0,99.62499632 +33.83,50.42293624,-3.50095082,10000,-33.4444111,197.181163,0,14.03629709,0,99.63202221 +33.84,50.42293324,-3.500923117,10000,-33.47922724,197.1765046,0,14.03629709,0,99.63904816 +33.85,50.42293023,-3.500895415,10000,-33.51404339,197.1720686,0,14.03629709,0,99.64607406 +33.86,50.42292722,-3.500867713,10000,-33.53493307,197.1682998,0,14.03629709,0,99.65309995 +33.87,50.42292421,-3.500840012,10000,-33.55582275,197.1645311,0,14.03629709,0,99.66012591 +33.88,50.4229212,-3.500812311,10000,-33.59063889,197.1600951,0,14.03629709,0,99.6671518 +33.89,50.42291818,-3.500784611,10000,-33.62545504,197.1552143,0,14.03629709,0,99.67417775 +33.9,50.42291516,-3.500756912,10000,-33.64286312,197.1507783,0,14.03629709,0,99.68120365 +33.91,50.42291214,-3.500729213,10000,-33.64982635,197.1470096,0,14.03629709,0,99.6882296 +33.92,50.42290912,-3.500701515,10000,-33.66723441,197.1434634,0,14.03629709,0,99.69525549 +33.93,50.4229061,-3.500673817,10000,-33.70205054,197.1399171,0,14.03629709,0,99.70228145 +33.94,50.42290307,-3.50064612,10000,-33.73686668,197.1361484,0,14.03629709,0,99.70930734 +33.95,50.42290004,-3.500618423,10000,-33.75775638,197.1317125,0,14.03629709,0,99.71633329 +33.96,50.42289701,-3.500590727,10000,-33.77864607,197.1268317,0,14.03629709,0,99.72335919 +33.97,50.42289398,-3.500563032,10000,-33.80998061,197.1223958,0,14.03629709,0,99.73038514 +33.98,50.42289094,-3.500535337,10000,-33.83435191,197.1186272,0,14.03629709,0,99.73741104 +33.99,50.4228879,-3.500507643,10000,-33.84827837,197.115081,0,14.03629709,0,99.74443699 +34,50.42288487,-3.500479949,10000,-33.87264966,197.1113124,0,14.03629709,0,99.75146288 +34.01,50.42288182,-3.500452256,10000,-33.90398418,197.1068765,0,14.03629709,0,99.75848884 +34.02,50.42287878,-3.500424563,10000,-33.92139224,197.1019958,0,14.03629709,0,99.76551473 +34.03,50.42287573,-3.500396872,10000,-33.93183707,197.0973375,0,14.03629709,0,99.77254068 +34.04,50.42287269,-3.50036918,10000,-33.95969,197.0929016,0,14.03629709,0,99.77956658 +34.05,50.42286964,-3.50034149,10000,-34.00146939,197.0889106,0,14.03629709,0,99.78659253 +34.06,50.42286658,-3.5003138,10000,-34.03280392,197.0855869,0,14.03629709,0,99.79361843 +34.07,50.42286353,-3.50028611,10000,-34.05369359,197.0818184,0,14.03629709,0,99.80064438 +34.08,50.42286047,-3.500258421,10000,-34.07458328,197.0771601,0,14.03629709,0,99.80767027 +34.09,50.42285741,-3.500230733,10000,-34.09199136,197.0727243,0,14.03629709,0,99.81469622 +34.1,50.42285435,-3.500203045,10000,-34.10939943,197.0689558,0,14.03629709,0,99.82172212 +34.11,50.42285129,-3.500175358,10000,-34.13028909,197.0651872,0,14.03629709,0,99.82874807 +34.12,50.42284822,-3.500147671,10000,-34.15117877,197.0607514,0,14.03629709,0,99.83577397 +34.13,50.42284516,-3.500119985,10000,-34.18251331,197.0558708,0,14.03629709,0,99.84279992 +34.14,50.42284209,-3.5000923,10000,-34.22429271,197.0512126,0,14.03629709,0,99.84982581 +34.15,50.42283901,-3.500064615,10000,-34.25562724,197.0465544,0,14.03629709,0,99.85685177 +34.16,50.42283594,-3.500036931,10000,-34.27651691,197.0418963,0,14.03629709,0,99.86387766 +34.17,50.42283286,-3.500009248,10000,-34.29740659,197.0383502,0,14.03629709,0,99.87090361 +34.18,50.42282978,-3.499981565,10000,-34.31133303,197.0356939,0,14.03629709,0,99.87792951 +34.19,50.4228267,-3.499953882,10000,-34.31829626,197.0321478,0,14.03629709,0,99.88495546 +34.2,50.42282362,-3.4999262,10000,-34.33570434,197.0274897,0,14.03629709,0,99.89198136 +34.21,50.42282054,-3.499898519,10000,-34.37052049,197.0228315,0,14.03629709,0,99.89900731 +34.22,50.42281745,-3.499870838,10000,-34.40881825,197.0181734,0,14.03629709,0,99.9060332 +34.23,50.42281436,-3.499843158,10000,-34.44015277,197.0135153,0,14.03629709,0,99.91305916 +34.24,50.42281127,-3.499815479,10000,-34.46452405,197.0097469,0,14.03629709,0,99.92008505 +34.25,50.42280817,-3.4997878,10000,-34.48193211,197.0062009,0,14.03629709,0,99.927111 +34.26,50.42280508,-3.499760121,10000,-34.49934019,197.0015428,0,14.03629709,0,99.9341369 +34.27,50.42280198,-3.499732444,10000,-34.5237115,196.9966623,0,14.03629709,0,99.94116279 +34.28,50.42279888,-3.499704767,10000,-34.55156442,196.9924491,0,14.03629709,0,99.94818874 +34.29,50.42279578,-3.49967709,10000,-34.57593573,196.9882359,0,14.03629709,0,99.95521464 +34.3,50.42279267,-3.499649415,10000,-34.5933438,196.9840226,0,14.03629709,0,99.96224059 +34.31,50.42278957,-3.499621739,10000,-34.61423347,196.9802543,0,14.03629709,0,99.96926649 +34.32,50.42278646,-3.499594065,10000,-34.6490496,196.9764859,0,14.03629709,0,99.97629244 +34.33,50.42278335,-3.49956639,10000,-34.68386575,196.9720503,0,14.03629709,0,99.98331833 +34.34,50.42278023,-3.499538717,10000,-34.70475544,196.9671699,0,14.03629709,0,99.99034429 +34.35,50.42277712,-3.499511044,10000,-34.72216351,196.9627343,0,14.03629709,0,99.99737018 +34.36,50.422774,-3.499483372,10000,-34.74305319,196.958966,0,14.03629709,0,100.0043961 +34.37,50.42277088,-3.4994557,10000,-34.76046125,196.9551977,0,14.03629709,0,100.011422 +34.38,50.42276776,-3.499428029,10000,-34.78135093,196.9507621,0,14.03629709,0,100.018448 +34.39,50.42276464,-3.499400358,10000,-34.81616707,196.9458817,0,14.03629709,0,100.0254739 +34.4,50.42276151,-3.499372689,10000,-34.85098322,196.9414461,0,14.03629709,0,100.0324998 +34.41,50.42275838,-3.499345019,10000,-34.8718729,196.9376779,0,14.03629709,0,100.0395257 +34.42,50.42275525,-3.499317351,10000,-34.88928097,196.9339096,0,14.03629709,0,100.0465517 +34.43,50.42275212,-3.499289682,10000,-34.91017066,196.9294741,0,14.03629709,0,100.0535776 +34.44,50.42274898,-3.499262015,10000,-34.92757872,196.9245937,0,14.03629709,0,100.0606035 +34.45,50.42274585,-3.499234348,10000,-34.9484684,196.9201582,0,14.03629709,0,100.0676294 +34.46,50.42274271,-3.499206682,10000,-34.98328455,196.9161675,0,14.03629709,0,100.0746554 +34.47,50.42273957,-3.499179016,10000,-35.01810069,196.911732,0,14.03629709,0,100.0816813 +34.48,50.42273642,-3.499151351,10000,-35.03899037,196.9068517,0,14.03629709,0,100.0887072 +34.49,50.42273328,-3.499123687,10000,-35.05639844,196.9024162,0,14.03629709,0,100.0957331 +34.5,50.42273013,-3.499096023,10000,-35.08076974,196.898648,0,14.03629709,0,100.1027591 +34.51,50.42272698,-3.49906836,10000,-35.10862265,196.8948799,0,14.03629709,0,100.109785 +34.52,50.42272383,-3.499040697,10000,-35.13299396,196.8904444,0,14.03629709,0,100.1168109 +34.53,50.42272067,-3.499013035,10000,-35.15040202,196.8857865,0,14.03629709,0,100.1238368 +34.54,50.42271752,-3.498985374,10000,-35.17129169,196.8820184,0,14.03629709,0,100.1308628 +34.55,50.42271436,-3.498957713,10000,-35.20610784,196.8784726,0,14.03629709,0,100.1378887 +34.56,50.4227112,-3.498930052,10000,-35.240924,196.8738148,0,14.03629709,0,100.1449146 +34.57,50.42270803,-3.498902393,10000,-35.26181368,196.8689345,0,14.03629709,0,100.1519405 +34.58,50.42270487,-3.498874734,10000,-35.27922175,196.8644991,0,14.03629709,0,100.1589665 +34.59,50.4227017,-3.498847075,10000,-35.30011143,196.8596189,0,14.03629709,0,100.1659923 +34.6,50.42269853,-3.498819418,10000,-35.31751948,196.8549611,0,14.03629709,0,100.1730183 +34.61,50.42269536,-3.498791761,10000,-35.33840915,196.8514154,0,14.03629709,0,100.1800442 +34.62,50.42269219,-3.498764104,10000,-35.3732253,196.8476473,0,14.03629709,0,100.1870701 +34.63,50.42268901,-3.498736448,10000,-35.40804146,196.8429895,0,14.03629709,0,100.194096 +34.64,50.42268583,-3.498708793,10000,-35.42893115,196.8383318,0,14.03629709,0,100.201122 +34.65,50.42268265,-3.498681138,10000,-35.44633922,196.833674,0,14.03629709,0,100.2081479 +34.66,50.42267947,-3.498653484,10000,-35.46722889,196.8290162,0,14.03629709,0,100.2151738 +34.67,50.42267628,-3.498625831,10000,-35.48463693,196.8252482,0,14.03629709,0,100.2221997 +34.68,50.4226731,-3.498598178,10000,-35.5055266,196.8217026,0,14.03629709,0,100.2292256 +34.69,50.42266991,-3.498570525,10000,-35.54034275,196.8170448,0,14.03629709,0,100.2362516 +34.7,50.42266672,-3.498542874,10000,-35.57515892,196.8121647,0,14.03629709,0,100.2432775 +34.71,50.42266352,-3.498515223,10000,-35.59604861,196.8079518,0,14.03629709,0,100.2503034 +34.72,50.42266033,-3.498487572,10000,-35.61345668,196.803739,0,14.03629709,0,100.2573293 +34.73,50.42265713,-3.498459923,10000,-35.63782797,196.7993037,0,14.03629709,0,100.2643553 +34.74,50.42265393,-3.498432273,10000,-35.66568088,196.794646,0,14.03629709,0,100.2713812 +34.75,50.42265073,-3.498404625,10000,-35.69005217,196.7897659,0,14.03629709,0,100.2784071 +34.76,50.42264752,-3.498376977,10000,-35.70746023,196.7853306,0,14.03629709,0,100.285433 +34.77,50.42264432,-3.49834933,10000,-35.72486829,196.7815627,0,14.03629709,0,100.292459 +34.78,50.42264111,-3.498321683,10000,-35.7492396,196.7777947,0,14.03629709,0,100.2994849 +34.79,50.4226379,-3.498294037,10000,-35.78057413,196.7733595,0,14.03629709,0,100.3065108 +34.8,50.42263469,-3.498266391,10000,-35.81887189,196.7684794,0,14.03629709,0,100.3135367 +34.81,50.42263147,-3.498238747,10000,-35.85368803,196.7638218,0,14.03629709,0,100.3205627 +34.82,50.42262825,-3.498211102,10000,-35.8710961,196.7593866,0,14.03629709,0,100.3275886 +34.83,50.42262503,-3.498183459,10000,-35.87805931,196.7553962,0,14.03629709,0,100.3346145 +34.84,50.42262181,-3.498155816,10000,-35.89546738,196.7520732,0,14.03629709,0,100.3416404 +34.85,50.42261859,-3.498128173,10000,-35.93028353,196.7480829,0,14.03629709,0,100.3486664 +34.86,50.42261536,-3.498100531,10000,-35.96509967,196.7425356,0,14.03629709,0,100.3556923 +34.87,50.42261213,-3.49807289,10000,-35.98250772,196.7367659,0,14.03629709,0,100.3627182 +34.88,50.4226089,-3.49804525,10000,-35.98947092,196.7321083,0,14.03629709,0,100.3697441 +34.89,50.42260567,-3.49801761,10000,-36.00687899,196.7283404,0,14.03629709,0,100.3767701 +34.9,50.42260244,-3.497989971,10000,-36.04169515,196.7245726,0,14.03629709,0,100.383796 +34.91,50.4225992,-3.497962332,10000,-36.07651131,196.7201374,0,14.03629709,0,100.3908219 +34.92,50.42259596,-3.497934694,10000,-36.09740099,196.7152575,0,14.03629709,0,100.3978478 +34.93,50.42259272,-3.497907057,10000,-36.11480905,196.7108223,0,14.03629709,0,100.4048738 +34.94,50.42258948,-3.49787942,10000,-36.13569872,196.7070545,0,14.03629709,0,100.4118996 +34.95,50.42258623,-3.497851784,10000,-36.15658839,196.7032867,0,14.03629709,0,100.4189256 +34.96,50.42258299,-3.497824148,10000,-36.18792292,196.6988516,0,14.03629709,0,100.4259515 +34.97,50.42257974,-3.497796513,10000,-36.22970231,196.6937493,0,14.03629709,0,100.4329774 +34.98,50.42257648,-3.497768879,10000,-36.25755524,196.6884245,0,14.03629709,0,100.4400033 +34.99,50.42257323,-3.497741245,10000,-36.26451845,196.6835446,0,14.03629709,0,100.4470293 +35,50.42256997,-3.497713613,10000,-36.27148164,196.6797768,0,14.03629709,0,100.4540552 +35.01,50.42256672,-3.49768598,10000,-36.29933455,196.6762315,0,14.03629709,0,100.4610811 +35.02,50.42256346,-3.497658348,10000,-36.34111393,196.6713516,0,14.03629709,0,100.468107 +35.03,50.42256019,-3.497630717,10000,-36.37244847,196.6660269,0,14.03629709,0,100.475133 +35.04,50.42255693,-3.497603087,10000,-36.39333815,196.6620367,0,14.03629709,0,100.4821589 +35.05,50.42255366,-3.497575457,10000,-36.41422782,196.6584914,0,14.03629709,0,100.4891848 +35.06,50.42255039,-3.497547827,10000,-36.43163588,196.6536115,0,14.03629709,0,100.4962107 +35.07,50.42254712,-3.497520199,10000,-36.45252556,196.6480644,0,14.03629709,0,100.5032366 +35.08,50.42254385,-3.497492571,10000,-36.48734169,196.6436294,0,14.03629709,0,100.5102626 +35.09,50.42254057,-3.497464944,10000,-36.52215784,196.640529,0,14.03629709,0,100.5172885 +35.1,50.42253729,-3.497437317,10000,-36.53956593,196.6372062,0,14.03629709,0,100.5243144 +35.11,50.42253401,-3.49740969,10000,-36.54652915,196.6323264,0,14.03629709,0,100.5313403 +35.12,50.42253073,-3.497382065,10000,-36.56393719,196.6265569,0,14.03629709,0,100.5383663 +35.13,50.42252745,-3.49735444,10000,-36.59875332,196.6212322,0,14.03629709,0,100.5453922 +35.14,50.42252416,-3.497326816,10000,-36.63356947,196.6170197,0,14.03629709,0,100.5524181 +35.15,50.42252087,-3.497299193,10000,-36.65445916,196.6134745,0,14.03629709,0,100.559444 +35.16,50.42251758,-3.497271569,10000,-36.67186723,196.6088172,0,14.03629709,0,100.56647 +35.17,50.42251429,-3.497243947,10000,-36.6927569,196.6030477,0,14.03629709,0,100.5734959 +35.18,50.42251099,-3.497216326,10000,-36.71364658,196.5986128,0,14.03629709,0,100.5805218 +35.19,50.4225077,-3.497188705,10000,-36.7449811,196.5957349,0,14.03629709,0,100.5875477 +35.2,50.4225044,-3.497161084,10000,-36.78676049,196.5919673,0,14.03629709,0,100.5945737 +35.21,50.42250109,-3.497133464,10000,-36.8146134,196.5864203,0,14.03629709,0,100.6015996 +35.22,50.42249779,-3.497105845,10000,-36.82157661,196.5806508,0,14.03629709,0,100.6086255 +35.23,50.42249448,-3.497078227,10000,-36.82853982,196.5759936,0,14.03629709,0,100.6156514 +35.24,50.42249118,-3.497050609,10000,-36.85639273,196.572226,0,14.03629709,0,100.6226774 +35.25,50.42248787,-3.497022992,10000,-36.8981721,196.5684584,0,14.03629709,0,100.6297032 +35.26,50.42248455,-3.496995375,10000,-36.92950663,196.5640236,0,14.03629709,0,100.6367292 +35.27,50.42248124,-3.496967759,10000,-36.95039631,196.5591439,0,14.03629709,0,100.6437551 +35.28,50.42247792,-3.496940144,10000,-36.97128599,196.5544867,0,14.03629709,0,100.650781 +35.29,50.4224746,-3.496912529,10000,-36.98869405,196.5498294,0,14.03629709,0,100.6578069 +35.3,50.42247128,-3.496884915,10000,-37.00610212,196.5449498,0,14.03629709,0,100.6648329 +35.31,50.42246796,-3.496857302,10000,-37.0269918,196.540515,0,14.03629709,0,100.6718588 +35.32,50.42246463,-3.496829689,10000,-37.04439986,196.5365251,0,14.03629709,0,100.6788847 +35.33,50.42246131,-3.496802077,10000,-37.06528954,196.5320903,0,14.03629709,0,100.6859106 +35.34,50.42245798,-3.496774465,10000,-37.10010568,196.5272106,0,14.03629709,0,100.6929366 +35.35,50.42245465,-3.496746855,10000,-37.13492181,196.5225535,0,14.03629709,0,100.6999625 +35.36,50.42245131,-3.496719244,10000,-37.15581148,196.5181187,0,14.03629709,0,100.7069884 +35.37,50.42244798,-3.496691635,10000,-37.17670116,196.5139064,0,14.03629709,0,100.7140143 +35.38,50.42244464,-3.496664026,10000,-37.21151731,196.5096941,0,14.03629709,0,100.7210403 +35.39,50.4224413,-3.496636417,10000,-37.24633346,196.5045921,0,14.03629709,0,100.7280662 +35.4,50.42243795,-3.49660881,10000,-37.26722314,196.4990452,0,14.03629709,0,100.7350921 +35.41,50.42243461,-3.496581203,10000,-37.2846312,196.4943881,0,14.03629709,0,100.742118 +35.42,50.42243126,-3.496553597,10000,-37.30552088,196.4903983,0,14.03629709,0,100.749144 +35.43,50.42242791,-3.496525991,10000,-37.32292894,196.4859636,0,14.03629709,0,100.7561699 +35.44,50.42242456,-3.496498386,10000,-37.34381862,196.481084,0,14.03629709,0,100.7631958 +35.45,50.42242121,-3.496470782,10000,-37.37863477,196.4764269,0,14.03629709,0,100.7702217 +35.46,50.42241785,-3.496443178,10000,-37.41345092,196.4719923,0,14.03629709,0,100.7772477 +35.47,50.42241449,-3.496415575,10000,-37.43085898,196.4680025,0,14.03629709,0,100.7842736 +35.48,50.42241113,-3.496387973,10000,-37.43782219,196.4644575,0,14.03629709,0,100.7912995 +35.49,50.42240777,-3.49636037,10000,-37.45523025,196.4598004,0,14.03629709,0,100.7983254 +35.5,50.42240441,-3.496332769,10000,-37.49004638,196.4538088,0,14.03629709,0,100.8053513 +35.51,50.42240104,-3.496305169,10000,-37.52486251,196.4484845,0,14.03629709,0,100.8123773 +35.52,50.42239767,-3.496277569,10000,-37.5457522,196.4442723,0,14.03629709,0,100.8194032 +35.53,50.4223943,-3.49624997,10000,-37.56316026,196.4398377,0,14.03629709,0,100.8264291 +35.54,50.42239093,-3.496222371,10000,-37.58404993,196.4351807,0,14.03629709,0,100.833455 +35.55,50.42238755,-3.496194774,10000,-37.6049396,196.4314133,0,14.03629709,0,100.840481 +35.56,50.42238418,-3.496167176,10000,-37.63627413,196.4278685,0,14.03629709,0,100.8475069 +35.57,50.4223808,-3.496139579,10000,-37.6745719,196.4227666,0,14.03629709,0,100.8545328 +35.58,50.42237741,-3.496111983,10000,-37.69197998,196.4163302,0,14.03629709,0,100.8615587 +35.59,50.42237403,-3.496084388,10000,-37.69546157,196.4105611,0,14.03629709,0,100.8685847 +35.6,50.42237065,-3.496056794,10000,-37.71983285,196.4065714,0,14.03629709,0,100.8756105 +35.61,50.42236726,-3.4960292,10000,-37.76509384,196.4030265,0,14.03629709,0,100.8826365 +35.62,50.42236387,-3.496001606,10000,-37.80339159,196.3983696,0,14.03629709,0,100.8896624 +35.63,50.42236047,-3.495974014,10000,-37.82428127,196.3937126,0,14.03629709,0,100.8966883 +35.64,50.42235708,-3.495946422,10000,-37.84168933,196.3901678,0,14.03629709,0,100.9037142 +35.65,50.42235368,-3.49591883,10000,-37.86257901,196.3861782,0,14.03629709,0,100.9107402 +35.66,50.42235028,-3.495891239,10000,-37.87998709,196.3806315,0,14.03629709,0,100.9177661 +35.67,50.42234688,-3.495863649,10000,-37.89739516,196.3748625,0,14.03629709,0,100.924792 +35.68,50.42234348,-3.49583606,10000,-37.91828482,196.3702056,0,14.03629709,0,100.9318179 +35.69,50.42234007,-3.495808471,10000,-37.93917449,196.3662159,0,14.03629709,0,100.9388439 +35.7,50.42233667,-3.495780883,10000,-37.970509,196.3617815,0,14.03629709,0,100.9458698 +35.71,50.42233326,-3.495753295,10000,-38.01228838,196.3569021,0,14.03629709,0,100.9528957 +35.72,50.42232984,-3.495725709,10000,-38.0401413,196.3522453,0,14.03629709,0,100.9599216 +35.73,50.42232643,-3.495698122,10000,-38.04710451,196.3475884,0,14.03629709,0,100.9669476 +35.74,50.42232301,-3.495670537,10000,-38.05406771,196.3427091,0,14.03629709,0,100.9739735 +35.75,50.4223196,-3.495642952,10000,-38.08192062,196.3380522,0,14.03629709,0,100.9809994 +35.76,50.42231618,-3.495615368,10000,-38.1237,196.3333954,0,14.03629709,0,100.9880253 +35.77,50.42231275,-3.495587784,10000,-38.15503454,196.3285161,0,14.03629709,0,100.9950513 +35.78,50.42230933,-3.495560202,10000,-38.17592422,196.3238593,0,14.03629709,0,101.0020772 +35.79,50.4223059,-3.495532619,10000,-38.19681389,196.3192025,0,14.03629709,0,101.0091031 +35.8,50.42230247,-3.495505038,10000,-38.21422193,196.3141008,0,14.03629709,0,101.016129 +35.81,50.42229904,-3.495477457,10000,-38.2351116,196.3089992,0,14.03629709,0,101.023155 +35.82,50.42229561,-3.495449877,10000,-38.26992774,196.3047872,0,14.03629709,0,101.0301809 +35.83,50.42229217,-3.495422298,10000,-38.3047439,196.301465,0,14.03629709,0,101.0372068 +35.84,50.42228873,-3.495394718,10000,-38.32215197,196.2976979,0,14.03629709,0,101.0442327 +35.85,50.42228529,-3.49536714,10000,-38.32911518,196.2925963,0,14.03629709,0,101.0512587 +35.86,50.42228185,-3.495339562,10000,-38.34652323,196.2863825,0,14.03629709,0,101.0582846 +35.87,50.42227841,-3.495311985,10000,-38.38133936,196.2801688,0,14.03629709,0,101.0653105 +35.88,50.42227496,-3.49528441,10000,-38.4161555,196.275512,0,14.03629709,0,101.0723364 +35.89,50.42227151,-3.495256834,10000,-38.43704518,196.2719674,0,14.03629709,0,101.0793623 +35.9,50.42226806,-3.495229259,10000,-38.45445324,196.267978,0,14.03629709,0,101.0863883 +35.91,50.42226461,-3.495201685,10000,-38.47534293,196.2635437,0,14.03629709,0,101.0934142 +35.92,50.42226115,-3.495174111,10000,-38.49275098,196.258887,0,14.03629709,0,101.1004401 +35.93,50.4222577,-3.495146538,10000,-38.51364065,196.2537854,0,14.03629709,0,101.107466 +35.94,50.42225424,-3.495118966,10000,-38.54845679,196.2484614,0,14.03629709,0,101.1144919 +35.95,50.42225078,-3.495091394,10000,-38.58327293,196.2435823,0,14.03629709,0,101.1215178 +35.96,50.42224731,-3.495063824,10000,-38.60416262,196.2395929,0,14.03629709,0,101.1285438 +35.97,50.42224385,-3.495036253,10000,-38.62157068,196.2353811,0,14.03629709,0,101.1355697 +35.98,50.42224038,-3.495008683,10000,-38.64594196,196.2300571,0,14.03629709,0,101.1425956 +35.99,50.42223691,-3.494981115,10000,-38.67727648,196.2247332,0,14.03629709,0,101.1496215 +36,50.42223344,-3.494953546,10000,-38.71557424,196.2198541,0,14.03629709,0,101.1566475 +36.01,50.42222996,-3.494925979,10000,-38.75039038,196.2149751,0,14.03629709,0,101.1636734 +36.02,50.42222648,-3.494898412,10000,-38.76779844,196.2105409,0,14.03629709,0,101.1706993 +36.03,50.422223,-3.494870846,10000,-38.77128004,196.2065515,0,14.03629709,0,101.1777252 +36.04,50.42221952,-3.49484328,10000,-38.77476163,196.2021174,0,14.03629709,0,101.1847512 +36.05,50.42221604,-3.494815715,10000,-38.79216969,196.1970159,0,14.03629709,0,101.1917771 +36.06,50.42221256,-3.494788151,10000,-38.82698583,196.1914696,0,14.03629709,0,101.198803 +36.07,50.42220907,-3.494760587,10000,-38.86528358,196.1857008,0,14.03629709,0,101.2058289 +36.08,50.42220558,-3.494733025,10000,-38.89661811,196.1808218,0,14.03629709,0,101.2128549 +36.09,50.42220209,-3.494705463,10000,-38.92098941,196.1772774,0,14.03629709,0,101.2198808 +36.1,50.42219859,-3.494677901,10000,-38.93839746,196.1735105,0,14.03629709,0,101.2269067 +36.11,50.4221951,-3.49465034,10000,-38.95928713,196.168854,0,14.03629709,0,101.2339326 +36.12,50.4221916,-3.49462278,10000,-38.99410328,196.1641974,0,14.03629709,0,101.2409586 +36.13,50.4221881,-3.49459522,10000,-39.02891941,196.1595409,0,14.03629709,0,101.2479845 +36.14,50.42218459,-3.494567661,10000,-39.04980909,196.1544395,0,14.03629709,0,101.2550104 +36.15,50.42218109,-3.494540103,10000,-39.06721715,196.1488933,0,14.03629709,0,101.2620363 +36.16,50.42217758,-3.494512545,10000,-39.08810683,196.1431246,0,14.03629709,0,101.2690623 +36.17,50.42217407,-3.494484989,10000,-39.10551489,196.1380232,0,14.03629709,0,101.2760882 +36.18,50.42217056,-3.494457433,10000,-39.12292294,196.1335892,0,14.03629709,0,101.2831141 +36.19,50.42216705,-3.494429877,10000,-39.14381261,196.1287102,0,14.03629709,0,101.29014 +36.2,50.42216353,-3.494402323,10000,-39.16470228,196.1240538,0,14.03629709,0,101.297166 +36.21,50.42216002,-3.494374769,10000,-39.19603681,196.1205094,0,14.03629709,0,101.3041919 +36.22,50.4221565,-3.494347215,10000,-39.23781618,196.1167427,0,14.03629709,0,101.3112178 +36.23,50.42215297,-3.494319662,10000,-39.26566909,196.1118638,0,14.03629709,0,101.3182437 +36.24,50.42214945,-3.49429211,10000,-39.27611392,196.1063176,0,14.03629709,0,101.3252697 +36.25,50.42214592,-3.494264558,10000,-39.29352197,196.1003266,0,14.03629709,0,101.3322956 +36.26,50.4221424,-3.494237008,10000,-39.32485648,196.094558,0,14.03629709,0,101.3393215 +36.27,50.42213886,-3.494209458,10000,-39.34922777,196.0899016,0,14.03629709,0,101.3463474 +36.28,50.42213533,-3.494181909,10000,-39.36315422,196.0859125,0,14.03629709,0,101.3533733 +36.29,50.4221318,-3.49415436,10000,-39.38752552,196.0814785,0,14.03629709,0,101.3603992 +36.3,50.42212826,-3.494126812,10000,-39.41886005,196.0765997,0,14.03629709,0,101.3674251 +36.31,50.42212472,-3.494099265,10000,-39.43974971,196.0721657,0,14.03629709,0,101.3744511 +36.32,50.42212118,-3.494071718,10000,-39.46063938,196.0681766,0,14.03629709,0,101.381477 +36.33,50.42211764,-3.494044172,10000,-39.49545553,196.0635202,0,14.03629709,0,101.3885029 +36.34,50.42211409,-3.494016626,10000,-39.53027167,196.0577517,0,14.03629709,0,101.3955288 +36.35,50.42211054,-3.493989082,10000,-39.55116134,196.0519832,0,14.03629709,0,101.4025548 +36.36,50.42210699,-3.493961538,10000,-39.56856939,196.0473268,0,14.03629709,0,101.4095807 +36.37,50.42210344,-3.493933995,10000,-39.58945907,196.0433378,0,14.03629709,0,101.4166066 +36.38,50.42209988,-3.493906452,10000,-39.60686713,196.0386815,0,14.03629709,0,101.4236325 +36.39,50.42209633,-3.49387891,10000,-39.62427518,196.032913,0,14.03629709,0,101.4306585 +36.4,50.42209277,-3.493851369,10000,-39.64864647,196.0271445,0,14.03629709,0,101.4376844 +36.41,50.42208921,-3.493823829,10000,-39.679981,196.0224882,0,14.03629709,0,101.4447103 +36.42,50.42208565,-3.493796289,10000,-39.71827876,196.0184992,0,14.03629709,0,101.4517362 +36.43,50.42208208,-3.49376875,10000,-39.75309489,196.0140653,0,14.03629709,0,101.4587622 +36.44,50.42207851,-3.493741211,10000,-39.77050295,196.0091866,0,14.03629709,0,101.4657881 +36.45,50.42207494,-3.493713674,10000,-39.77746616,196.0043079,0,14.03629709,0,101.472814 +36.46,50.42207137,-3.493686136,10000,-39.79487422,195.9987619,0,14.03629709,0,101.4798399 +36.47,50.4220678,-3.4936586,10000,-39.82969034,195.9927711,0,14.03629709,0,101.4868659 +36.48,50.42206422,-3.493631065,10000,-39.86450648,195.9883372,0,14.03629709,0,101.4938918 +36.49,50.42206064,-3.49360353,10000,-39.88191454,195.985238,0,14.03629709,0,101.5009177 +36.5,50.42205706,-3.493575995,10000,-39.88887775,195.9808042,0,14.03629709,0,101.5079436 +36.51,50.42205348,-3.493548461,10000,-39.90628582,195.9748134,0,14.03629709,0,101.5149696 +36.52,50.4220499,-3.493520929,10000,-39.94110196,195.9692674,0,14.03629709,0,101.5219955 +36.53,50.42204631,-3.493493396,10000,-39.97591808,195.9643888,0,14.03629709,0,101.5290214 +36.54,50.42204272,-3.493465865,10000,-39.99680774,195.9595102,0,14.03629709,0,101.5360473 +36.55,50.42203913,-3.493438334,10000,-40.01769742,195.9550764,0,14.03629709,0,101.5430733 +36.56,50.42203554,-3.493410804,10000,-40.05251358,195.9508651,0,14.03629709,0,101.5500992 +36.57,50.42203194,-3.493383274,10000,-40.08732973,195.9455416,0,14.03629709,0,101.5571251 +36.58,50.42202834,-3.493355745,10000,-40.10473779,195.9395509,0,14.03629709,0,101.564151 +36.59,50.42202474,-3.493328218,10000,-40.11170099,195.9348947,0,14.03629709,0,101.571177 +36.6,50.42202114,-3.49330069,10000,-40.12910903,195.9311283,0,14.03629709,0,101.5782029 +36.61,50.42201754,-3.493273163,10000,-40.16392516,195.9262497,0,14.03629709,0,101.5852288 +36.62,50.42201393,-3.493245637,10000,-40.1987413,195.9204814,0,14.03629709,0,101.5922547 +36.63,50.42201032,-3.493218112,10000,-40.21614936,195.9149355,0,14.03629709,0,101.5992806 +36.64,50.42200671,-3.493190587,10000,-40.22311257,195.9098346,0,14.03629709,0,101.6063065 +36.65,50.4220031,-3.493163064,10000,-40.24052062,195.9051784,0,14.03629709,0,101.6133325 +36.66,50.42199949,-3.49313554,10000,-40.27533675,195.9005223,0,14.03629709,0,101.6203584 +36.67,50.42199587,-3.493108018,10000,-40.3136345,195.8954214,0,14.03629709,0,101.6273843 +36.68,50.42199225,-3.493080496,10000,-40.34496904,195.890098,0,14.03629709,0,101.6344102 +36.69,50.42198863,-3.493052975,10000,-40.36934034,195.884997,0,14.03629709,0,101.6414361 +36.7,50.421985,-3.493025455,10000,-40.38674839,195.8805634,0,14.03629709,0,101.6484621 +36.71,50.42198138,-3.492997935,10000,-40.40415643,195.8765746,0,14.03629709,0,101.655488 +36.72,50.42197775,-3.492970416,10000,-40.42852772,195.8719186,0,14.03629709,0,101.6625139 +36.73,50.42197412,-3.492942897,10000,-40.45638063,195.8661504,0,14.03629709,0,101.6695398 +36.74,50.42197049,-3.49291538,10000,-40.48075191,195.8603822,0,14.03629709,0,101.6765658 +36.75,50.42196685,-3.492887863,10000,-40.49815996,195.8557261,0,14.03629709,0,101.6835917 +36.76,50.42196322,-3.492860347,10000,-40.51556803,195.8517374,0,14.03629709,0,101.6906176 +36.77,50.42195958,-3.492832831,10000,-40.53993933,195.8473038,0,14.03629709,0,101.6976435 +36.78,50.42195594,-3.492805316,10000,-40.57127385,195.8422029,0,14.03629709,0,101.7046695 +36.79,50.4219523,-3.492777802,10000,-40.60608998,195.8366572,0,14.03629709,0,101.7116954 +36.8,50.42194865,-3.492750288,10000,-40.63046127,195.8306667,0,14.03629709,0,101.7187213 +36.81,50.421945,-3.492722776,10000,-40.6443877,195.8248985,0,14.03629709,0,101.7257472 +36.82,50.42194136,-3.492695264,10000,-40.66875898,195.8202426,0,14.03629709,0,101.7327732 +36.83,50.4219377,-3.492667753,10000,-40.7000935,195.8162539,0,14.03629709,0,101.7397991 +36.84,50.42193405,-3.492640242,10000,-40.71750156,195.8118203,0,14.03629709,0,101.746825 +36.85,50.42193039,-3.492612732,10000,-40.72794639,195.8067195,0,14.03629709,0,101.7538509 +36.86,50.42192674,-3.492585223,10000,-40.75579929,195.8013963,0,14.03629709,0,101.7608769 +36.87,50.42192308,-3.492557714,10000,-40.79757866,195.7962955,0,14.03629709,0,101.7679028 +36.88,50.42191941,-3.492530207,10000,-40.82891319,195.7916396,0,14.03629709,0,101.7749287 +36.89,50.42191575,-3.492502699,10000,-40.84980286,195.7869837,0,14.03629709,0,101.7819546 +36.9,50.42191208,-3.492475193,10000,-40.87069252,195.7818829,0,14.03629709,0,101.7889806 +36.91,50.42190841,-3.492447687,10000,-40.88461895,195.7765597,0,14.03629709,0,101.7960065 +36.92,50.42190474,-3.492420182,10000,-40.89158217,195.7712365,0,14.03629709,0,101.8030324 +36.93,50.42190107,-3.492392678,10000,-40.90899023,195.7659133,0,14.03629709,0,101.8100583 +36.94,50.4218974,-3.492365174,10000,-40.94380635,195.7608126,0,14.03629709,0,101.8170843 +36.95,50.42189372,-3.492337672,10000,-40.9821041,195.7561567,0,14.03629709,0,101.8241101 +36.96,50.42189004,-3.492310169,10000,-41.01343862,195.7515008,0,14.03629709,0,101.8311361 +36.97,50.42188636,-3.492282668,10000,-41.03780991,195.7466226,0,14.03629709,0,101.838162 +36.98,50.42188267,-3.492255167,10000,-41.05521797,195.7419667,0,14.03629709,0,101.8451879 +36.99,50.42187899,-3.492227667,10000,-41.07262605,195.7370884,0,14.03629709,0,101.8522138 +37,50.4218753,-3.492200167,10000,-41.09699734,195.7313205,0,14.03629709,0,101.8592398 +37.01,50.42187161,-3.492172669,10000,-41.12485023,195.7255525,0,14.03629709,0,101.8662657 +37.02,50.42186792,-3.492145171,10000,-41.1492215,195.7206742,0,14.03629709,0,101.8732916 +37.03,50.42186422,-3.492117674,10000,-41.16662955,195.715796,0,14.03629709,0,101.8803175 +37.04,50.42186053,-3.492090177,10000,-41.18751922,195.7100281,0,14.03629709,0,101.8873435 +37.05,50.42185683,-3.492062682,10000,-41.22233536,195.7042601,0,14.03629709,0,101.8943694 +37.06,50.42185313,-3.492035187,10000,-41.25715151,195.6996043,0,14.03629709,0,101.9013953 +37.07,50.42184942,-3.492007693,10000,-41.27804119,195.6956159,0,14.03629709,0,101.9084212 +37.08,50.42184572,-3.491980199,10000,-41.29544924,195.6911825,0,14.03629709,0,101.9154471 +37.09,50.42184201,-3.491952706,10000,-41.31982051,195.6863043,0,14.03629709,0,101.9224731 +37.1,50.4218383,-3.491925214,10000,-41.34767341,195.6816486,0,14.03629709,0,101.929499 +37.11,50.42183459,-3.491897722,10000,-41.3720447,195.6767704,0,14.03629709,0,101.9365249 +37.12,50.42183087,-3.491870231,10000,-41.38945276,195.6710025,0,14.03629709,0,101.9435508 +37.13,50.42182716,-3.491842741,10000,-41.40686082,195.6650122,0,14.03629709,0,101.9505768 +37.14,50.42182344,-3.491815252,10000,-41.4312321,195.6594668,0,14.03629709,0,101.9576027 +37.15,50.42181972,-3.491787763,10000,-41.459085,195.6545886,0,14.03629709,0,101.9646286 +37.16,50.421816,-3.491760276,10000,-41.48345629,195.6506002,0,14.03629709,0,101.9716545 +37.17,50.42181227,-3.491732788,10000,-41.50086434,195.646167,0,14.03629709,0,101.9786805 +37.18,50.42180855,-3.491705301,10000,-41.521754,195.6399543,0,14.03629709,0,101.9857064 +37.19,50.42180482,-3.491677816,10000,-41.55657013,195.6335191,0,14.03629709,0,101.9927323 +37.2,50.42180109,-3.491650331,10000,-41.59138627,195.628641,0,14.03629709,0,101.9997582 +37.21,50.42179735,-3.491622847,10000,-41.61227595,195.6246527,0,14.03629709,0,102.0067842 +37.22,50.42179362,-3.491595363,10000,-41.62968401,195.619997,0,14.03629709,0,102.0138101 +37.23,50.42178988,-3.49156788,10000,-41.6540553,195.6142292,0,14.03629709,0,102.020836 +37.24,50.42178614,-3.491540398,10000,-41.6819082,195.6084614,0,14.03629709,0,102.0278619 +37.25,50.4217824,-3.491512917,10000,-41.70627948,195.6035834,0,14.03629709,0,102.0348879 +37.26,50.42177865,-3.491485436,10000,-41.72368752,195.5989278,0,14.03629709,0,102.0419138 +37.27,50.42177491,-3.491457956,10000,-41.74109558,195.5940497,0,14.03629709,0,102.0489397 +37.28,50.42177116,-3.491430477,10000,-41.76546687,195.5893941,0,14.03629709,0,102.0559656 +37.29,50.42176741,-3.491402998,10000,-41.79680139,195.5845161,0,14.03629709,0,102.0629916 +37.3,50.42176366,-3.49137552,10000,-41.83509915,195.5787484,0,14.03629709,0,102.0700174 +37.31,50.4217599,-3.491348043,10000,-41.86991528,195.5729806,0,14.03629709,0,102.0770434 +37.32,50.42175614,-3.491320567,10000,-41.88732332,195.5681026,0,14.03629709,0,102.0840693 +37.33,50.42175238,-3.491293091,10000,-41.89428652,195.5634471,0,14.03629709,0,102.0910952 +37.34,50.42174862,-3.491265616,10000,-41.90821298,195.5585691,0,14.03629709,0,102.0981211 +37.35,50.42174486,-3.491238142,10000,-41.92910265,195.5536911,0,14.03629709,0,102.1051471 +37.36,50.42174109,-3.491210668,10000,-41.9499923,195.5481458,0,14.03629709,0,102.112173 +37.37,50.42173733,-3.491183195,10000,-41.98132681,195.5419333,0,14.03629709,0,102.1191989 +37.38,50.42173356,-3.491155724,10000,-42.02310619,195.536388,0,14.03629709,0,102.1262248 +37.39,50.42172978,-3.491128252,10000,-42.05444071,195.5315101,0,14.03629709,0,102.1332508 +37.4,50.42172601,-3.491100782,10000,-42.07533037,195.5266322,0,14.03629709,0,102.1402767 +37.41,50.42172223,-3.491073312,10000,-42.09622004,195.5219767,0,14.03629709,0,102.1473026 +37.42,50.42171845,-3.491045843,10000,-42.11014648,195.5170988,0,14.03629709,0,102.1543285 +37.43,50.42171467,-3.491018374,10000,-42.1171097,195.5115536,0,14.03629709,0,102.1613545 +37.44,50.42171089,-3.490990907,10000,-42.13451775,195.5064532,0,14.03629709,0,102.1683804 +37.45,50.42170711,-3.49096344,10000,-42.16933388,195.5020202,0,14.03629709,0,102.1754063 +37.46,50.42170332,-3.490935973,10000,-42.20415,195.4969198,0,14.03629709,0,102.1824322 +37.47,50.42169953,-3.490908508,10000,-42.22503966,195.4913747,0,14.03629709,0,102.1894582 +37.48,50.42169574,-3.490881043,10000,-42.24592933,195.4864968,0,14.03629709,0,102.1964841 +37.49,50.42169195,-3.490853579,10000,-42.28074547,195.4816189,0,14.03629709,0,102.20351 +37.5,50.42168815,-3.490826115,10000,-42.31556163,195.4758514,0,14.03629709,0,102.2105359 +37.51,50.42168435,-3.490798653,10000,-42.3364513,195.4698614,0,14.03629709,0,102.2175618 +37.52,50.42168055,-3.490771191,10000,-42.35385933,195.4643162,0,14.03629709,0,102.2245878 +37.53,50.42167675,-3.49074373,10000,-42.37474899,195.459216,0,14.03629709,0,102.2316137 +37.54,50.42167294,-3.49071627,10000,-42.39215705,195.4545606,0,14.03629709,0,102.2386396 +37.55,50.42166914,-3.49068881,10000,-42.4095651,195.4499052,0,14.03629709,0,102.2456655 +37.56,50.42166533,-3.490661351,10000,-42.43393639,195.4448049,0,14.03629709,0,102.2526915 +37.57,50.42166152,-3.490633893,10000,-42.46527091,195.4392598,0,14.03629709,0,102.2597174 +37.58,50.42165771,-3.490606435,10000,-42.50356866,195.4332699,0,14.03629709,0,102.2667433 +37.59,50.42165389,-3.490578979,10000,-42.53838479,195.4275024,0,14.03629709,0,102.2737692 +37.6,50.42165007,-3.490551523,10000,-42.55579284,195.4228471,0,14.03629709,0,102.2807952 +37.61,50.42164625,-3.490524068,10000,-42.56275604,195.4186366,0,14.03629709,0,102.287821 +37.62,50.42164243,-3.490496613,10000,-42.57668248,195.413314,0,14.03629709,0,102.294847 +37.63,50.42163861,-3.490469159,10000,-42.59757215,195.407324,0,14.03629709,0,102.3018729 +37.64,50.42163478,-3.490441707,10000,-42.61846182,195.4024463,0,14.03629709,0,102.3088988 +37.65,50.42163096,-3.490414254,10000,-42.64979634,195.397791,0,14.03629709,0,102.3159247 +37.66,50.42162713,-3.490386802,10000,-42.6915757,195.3918011,0,14.03629709,0,102.3229507 +37.67,50.42162329,-3.490359352,10000,-42.72291021,195.3860337,0,14.03629709,0,102.3299766 +37.68,50.42161946,-3.490331902,10000,-42.74379988,195.3813784,0,14.03629709,0,102.3370025 +37.69,50.42161562,-3.490304452,10000,-42.76468953,195.3762783,0,14.03629709,0,102.3440284 +37.7,50.42161178,-3.490277004,10000,-42.78209758,195.3707333,0,14.03629709,0,102.3510544 +37.71,50.42160794,-3.490249556,10000,-42.79950564,195.3658556,0,14.03629709,0,102.3580803 +37.72,50.4216041,-3.490222109,10000,-42.82039533,195.3609779,0,14.03629709,0,102.3651062 +37.73,50.42160025,-3.490194662,10000,-42.83780339,195.3552105,0,14.03629709,0,102.3721321 +37.74,50.42159641,-3.490167217,10000,-42.85869304,195.3494431,0,14.03629709,0,102.3791581 +37.75,50.42159256,-3.490139772,10000,-42.89350916,195.3445654,0,14.03629709,0,102.386184 +37.76,50.42158871,-3.490112328,10000,-42.92832528,195.3396878,0,14.03629709,0,102.3932099 +37.77,50.42158485,-3.490084884,10000,-42.94921496,195.3339204,0,14.03629709,0,102.4002358 +37.78,50.421581,-3.490057442,10000,-42.97010465,195.3281531,0,14.03629709,0,102.4072618 +37.79,50.42157714,-3.49003,10000,-43.0049208,195.3234979,0,14.03629709,0,102.4142877 +37.8,50.42157328,-3.490002559,10000,-43.03973691,195.31951,0,14.03629709,0,102.4213136 +37.81,50.42156941,-3.489975118,10000,-43.06062655,195.3148548,0,14.03629709,0,102.4283395 +37.82,50.42156555,-3.489947678,10000,-43.07803459,195.3088651,0,14.03629709,0,102.4353655 +37.83,50.42156168,-3.489920239,10000,-43.09892427,195.302208,0,14.03629709,0,102.4423914 +37.84,50.42155781,-3.489892801,10000,-43.11285072,195.2962183,0,14.03629709,0,102.4494173 +37.85,50.42155394,-3.489865364,10000,-43.11981392,195.2913407,0,14.03629709,0,102.4564432 +37.86,50.42155007,-3.489837927,10000,-43.13722197,195.2866856,0,14.03629709,0,102.4634692 +37.87,50.4215462,-3.489810491,10000,-43.17203811,195.281808,0,14.03629709,0,102.4704951 +37.88,50.42154232,-3.489783056,10000,-43.21033586,195.2771529,0,14.03629709,0,102.477521 +37.89,50.42153844,-3.489755621,10000,-43.24167037,195.2722753,0,14.03629709,0,102.4845469 +37.9,50.42153456,-3.489728187,10000,-43.26604164,195.2662856,0,14.03629709,0,102.4915728 +37.91,50.42153067,-3.489700754,10000,-43.28344969,195.2596287,0,14.03629709,0,102.4985988 +37.92,50.42152679,-3.489673322,10000,-43.30085776,195.253639,0,14.03629709,0,102.5056247 +37.93,50.4215229,-3.489645891,10000,-43.32522904,195.2487615,0,14.03629709,0,102.5126506 +37.94,50.42151901,-3.48961846,10000,-43.35656355,195.2441064,0,14.03629709,0,102.5196765 +37.95,50.42151512,-3.48959103,10000,-43.39486129,195.2390065,0,14.03629709,0,102.5267025 +37.96,50.42151122,-3.489563601,10000,-43.42967743,195.2334617,0,14.03629709,0,102.5337283 +37.97,50.42150732,-3.489536172,10000,-43.44708548,195.2276945,0,14.03629709,0,102.5407543 +37.98,50.42150342,-3.489508745,10000,-43.45056706,195.2225946,0,14.03629709,0,102.5477802 +37.99,50.42149952,-3.489481318,10000,-43.45404865,195.218162,0,14.03629709,0,102.5548061 +38,50.42149562,-3.489453891,10000,-43.47145669,195.2130621,0,14.03629709,0,102.561832 +38.01,50.42149172,-3.489426466,10000,-43.50627282,195.2072949,0,14.03629709,0,102.568858 +38.02,50.42148781,-3.489399041,10000,-43.54457058,195.2017502,0,14.03629709,0,102.5758839 +38.03,50.4214839,-3.489371617,10000,-43.5759051,195.1966503,0,14.03629709,0,102.5829098 +38.04,50.42147999,-3.489344194,10000,-43.60027638,195.1917729,0,14.03629709,0,102.5899357 +38.05,50.42147607,-3.489316771,10000,-43.61768442,195.1862282,0,14.03629709,0,102.5969617 +38.06,50.42147216,-3.489289349,10000,-43.63509247,195.1800162,0,14.03629709,0,102.6039876 +38.07,50.42146824,-3.489261929,10000,-43.65946375,195.1744715,0,14.03629709,0,102.6110135 +38.08,50.42146432,-3.489234508,10000,-43.69079827,195.1695941,0,14.03629709,0,102.6180394 +38.09,50.4214604,-3.489207089,10000,-43.72909601,195.1644943,0,14.03629709,0,102.6250654 +38.1,50.42145647,-3.48917967,10000,-43.76391214,195.1589496,0,14.03629709,0,102.6320913 +38.11,50.42145254,-3.489152252,10000,-43.78132019,195.1529601,0,14.03629709,0,102.6391172 +38.12,50.42144861,-3.489124835,10000,-43.78828338,195.147193,0,14.03629709,0,102.6461431 +38.13,50.42144468,-3.489097419,10000,-43.80220982,195.1423157,0,14.03629709,0,102.6531691 +38.14,50.42144075,-3.489070003,10000,-43.8230995,195.1376607,0,14.03629709,0,102.660195 +38.15,50.42143681,-3.489042588,10000,-43.84398918,195.132561,0,14.03629709,0,102.6672209 +38.16,50.42143288,-3.489015174,10000,-43.87532369,195.1270163,0,14.03629709,0,102.6742468 +38.17,50.42142894,-3.48898776,10000,-43.91710304,195.1210269,0,14.03629709,0,102.6812728 +38.18,50.42142499,-3.488960348,10000,-43.94495593,195.1150374,0,14.03629709,0,102.6882987 +38.19,50.42142105,-3.488932936,10000,-43.95191913,195.1094928,0,14.03629709,0,102.6953246 +38.2,50.4214171,-3.488905525,10000,-43.95888233,195.1043931,0,14.03629709,0,102.7023505 +38.21,50.42141316,-3.488878115,10000,-43.98673523,195.0997382,0,14.03629709,0,102.7093765 +38.22,50.42140921,-3.488850705,10000,-44.0285146,195.0950833,0,14.03629709,0,102.7164024 +38.23,50.42140525,-3.488823296,10000,-44.05984911,195.0899836,0,14.03629709,0,102.7234283 +38.24,50.4214013,-3.488795888,10000,-44.08073878,195.0844391,0,14.03629709,0,102.7304542 +38.25,50.42139734,-3.48876848,10000,-44.10162845,195.0784497,0,14.03629709,0,102.7374802 +38.26,50.42139338,-3.488741074,10000,-44.11903649,195.0724603,0,14.03629709,0,102.7445061 +38.27,50.42138942,-3.488713668,10000,-44.13992613,195.0669157,0,14.03629709,0,102.751532 +38.28,50.42138546,-3.488686263,10000,-44.17474226,195.0618161,0,14.03629709,0,102.7585579 +38.29,50.42138149,-3.488658859,10000,-44.20955842,195.0569388,0,14.03629709,0,102.7655838 +38.3,50.42137752,-3.488631455,10000,-44.22696647,195.0513943,0,14.03629709,0,102.7726097 +38.31,50.42137355,-3.488604052,10000,-44.23392966,195.0451825,0,14.03629709,0,102.7796356 +38.32,50.42136958,-3.488576651,10000,-44.2513377,195.039638,0,14.03629709,0,102.7866616 +38.33,50.42136561,-3.488549249,10000,-44.28615384,195.0347608,0,14.03629709,0,102.7936875 +38.34,50.42136163,-3.488521849,10000,-44.32096997,195.0296612,0,14.03629709,0,102.8007134 +38.35,50.42135765,-3.488494449,10000,-44.33837801,195.0241167,0,14.03629709,0,102.8077393 +38.36,50.42135367,-3.48846705,10000,-44.34534121,195.0181274,0,14.03629709,0,102.8147653 +38.37,50.42134969,-3.488439652,10000,-44.36274927,195.0123605,0,14.03629709,0,102.8217912 +38.38,50.42134571,-3.488412255,10000,-44.3975654,195.0074834,0,14.03629709,0,102.8288171 +38.39,50.42134172,-3.488384858,10000,-44.43238153,195.0028286,0,14.03629709,0,102.835843 +38.4,50.42133773,-3.488357462,10000,-44.45327118,194.9977291,0,14.03629709,0,102.842869 +38.41,50.42133374,-3.488330067,10000,-44.47416084,194.9921846,0,14.03629709,0,102.8498949 +38.42,50.42132975,-3.488302672,10000,-44.50897697,194.9861954,0,14.03629709,0,102.8569208 +38.43,50.42132575,-3.488275279,10000,-44.5437931,194.9802061,0,14.03629709,0,102.8639467 +38.44,50.42132175,-3.488247886,10000,-44.56120114,194.9744393,0,14.03629709,0,102.8709727 +38.45,50.42131775,-3.488220494,10000,-44.56816434,194.96845,0,14.03629709,0,102.8779986 +38.46,50.42131375,-3.488193103,10000,-44.58557239,194.9626832,0,14.03629709,0,102.8850245 +38.47,50.42130975,-3.488165713,10000,-44.62038853,194.9578061,0,14.03629709,0,102.8920504 +38.48,50.42130574,-3.488138323,10000,-44.65520466,194.9531514,0,14.03629709,0,102.8990764 +38.49,50.42130173,-3.488110934,10000,-44.67609434,194.9480519,0,14.03629709,0,102.9061023 +38.5,50.42129772,-3.488083546,10000,-44.69350239,194.9425076,0,14.03629709,0,102.9131282 +38.51,50.42129371,-3.488056158,10000,-44.71439205,194.9365184,0,14.03629709,0,102.9201541 +38.52,50.42128969,-3.488028772,10000,-44.73180009,194.9307516,0,14.03629709,0,102.9271801 +38.53,50.42128568,-3.488001386,10000,-44.75268975,194.9258746,0,14.03629709,0,102.934206 +38.54,50.42128166,-3.487974001,10000,-44.78750587,194.9209975,0,14.03629709,0,102.9412319 +38.55,50.42127764,-3.487946616,10000,-44.82232199,194.9150084,0,14.03629709,0,102.9482578 +38.56,50.42127361,-3.487919233,10000,-44.84321165,194.9083519,0,14.03629709,0,102.9552838 +38.57,50.42126959,-3.48789185,10000,-44.86061968,194.9023627,0,14.03629709,0,102.9623097 +38.58,50.42126556,-3.487864469,10000,-44.88499097,194.8974857,0,14.03629709,0,102.9693356 +38.59,50.42126153,-3.487837087,10000,-44.91284388,194.8928312,0,14.03629709,0,102.9763615 +38.6,50.4212575,-3.487809707,10000,-44.93721517,194.8877318,0,14.03629709,0,102.9833875 +38.61,50.42125346,-3.487782327,10000,-44.95462322,194.8821875,0,14.03629709,0,102.9904134 +38.62,50.42124943,-3.487754948,10000,-44.97551288,194.8761984,0,14.03629709,0,102.9974393 +38.63,50.42124539,-3.48772757,10000,-45.01032901,194.8702092,0,14.03629709,0,103.0044652 +38.64,50.42124135,-3.487700193,10000,-45.04514515,194.8644426,0,14.03629709,0,103.0114912 +38.65,50.4212373,-3.487672816,10000,-45.06603481,194.8584535,0,14.03629709,0,103.018517 +38.66,50.42123326,-3.487645441,10000,-45.08344285,194.8526868,0,14.03629709,0,103.025543 +38.67,50.42122921,-3.487618066,10000,-45.1043325,194.8480323,0,14.03629709,0,103.0325689 +38.68,50.42122516,-3.487590692,10000,-45.12174055,194.8438227,0,14.03629709,0,103.0395948 +38.69,50.42122111,-3.487563318,10000,-45.14263022,194.8385009,0,14.03629709,0,103.0466207 +38.7,50.42121706,-3.487535945,10000,-45.17744635,194.8322894,0,14.03629709,0,103.0536466 +38.71,50.421213,-3.487508574,10000,-45.21226247,194.8267452,0,14.03629709,0,103.0606726 +38.72,50.42120894,-3.487481202,10000,-45.22967052,194.8216459,0,14.03629709,0,103.0676985 +38.73,50.42120488,-3.487453832,10000,-45.2366337,194.8156569,0,14.03629709,0,103.0747244 +38.74,50.42120082,-3.487426462,10000,-45.25404175,194.8090005,0,14.03629709,0,103.0817503 +38.75,50.42119676,-3.487399094,10000,-45.28885789,194.8027891,0,14.03629709,0,103.0887763 +38.76,50.42119269,-3.487371726,10000,-45.32367402,194.7972449,0,14.03629709,0,103.0958022 +38.77,50.42118862,-3.487344359,10000,-45.34108206,194.7921457,0,14.03629709,0,103.1028281 +38.78,50.42118455,-3.487316993,10000,-45.34804526,194.7874913,0,14.03629709,0,103.109854 +38.79,50.42118048,-3.487289627,10000,-45.36545332,194.7826144,0,14.03629709,0,103.11688 +38.8,50.42117641,-3.487262262,10000,-45.40026944,194.7768479,0,14.03629709,0,103.1239059 +38.81,50.42117233,-3.487234898,10000,-45.43856717,194.7708589,0,14.03629709,0,103.1309318 +38.82,50.42116825,-3.487207535,10000,-45.46990168,194.7650923,0,14.03629709,0,103.1379577 +38.83,50.42116417,-3.487180172,10000,-45.49427296,194.7593258,0,14.03629709,0,103.1449837 +38.84,50.42116008,-3.487152811,10000,-45.511681,194.7542266,0,14.03629709,0,103.1520096 +38.85,50.421156,-3.48712545,10000,-45.52908905,194.7495722,0,14.03629709,0,103.1590355 +38.86,50.42115191,-3.487098089,10000,-45.55346034,194.7435833,0,14.03629709,0,103.1660614 +38.87,50.42114782,-3.48707073,10000,-45.58131323,194.7367046,0,14.03629709,0,103.1730874 +38.88,50.42114373,-3.487043372,10000,-45.6056845,194.7309382,0,14.03629709,0,103.1801133 +38.89,50.42113963,-3.487016014,10000,-45.62309254,194.725839,0,14.03629709,0,103.1871392 +38.9,50.42113554,-3.486988657,10000,-45.64050059,194.7200725,0,14.03629709,0,103.1941651 +38.91,50.42113144,-3.486961301,10000,-45.66487189,194.714306,0,14.03629709,0,103.2011911 +38.92,50.42112734,-3.486933946,10000,-45.69620639,194.7094293,0,14.03629709,0,103.208217 +38.93,50.42112324,-3.486906591,10000,-45.73102251,194.7045526,0,14.03629709,0,103.2152429 +38.94,50.42111913,-3.486879237,10000,-45.75539379,194.6985637,0,14.03629709,0,103.2222688 +38.95,50.42111502,-3.486851884,10000,-45.76932023,194.6919075,0,14.03629709,0,103.2292948 +38.96,50.42111092,-3.486824532,10000,-45.79369152,194.6859187,0,14.03629709,0,103.2363207 +38.97,50.4211068,-3.486797181,10000,-45.82502602,194.681042,0,14.03629709,0,103.2433466 +38.98,50.42110269,-3.48676983,10000,-45.84243405,194.6761653,0,14.03629709,0,103.2503725 +38.99,50.42109857,-3.48674248,10000,-45.85287886,194.6701765,0,14.03629709,0,103.2573985 +39,50.42109446,-3.486715131,10000,-45.88073175,194.6635203,0,14.03629709,0,103.2644243 +39.01,50.42109034,-3.486687783,10000,-45.92251112,194.6575315,0,14.03629709,0,103.2714503 +39.02,50.42108621,-3.486660436,10000,-45.95036401,194.6526549,0,14.03629709,0,103.2784762 +39.03,50.42108209,-3.486633089,10000,-45.96080882,194.6480007,0,14.03629709,0,103.2855021 +39.04,50.42107796,-3.486605743,10000,-45.97821686,194.6429016,0,14.03629709,0,103.292528 +39.05,50.42107384,-3.486578398,10000,-46.00955137,194.6373577,0,14.03629709,0,103.299554 +39.06,50.4210697,-3.486551053,10000,-46.03392264,194.6313689,0,14.03629709,0,103.3065799 +39.07,50.42106557,-3.48652371,10000,-46.04784907,194.6253801,0,14.03629709,0,103.3136058 +39.08,50.42106144,-3.486496367,10000,-46.07222037,194.6196138,0,14.03629709,0,103.3206317 +39.09,50.4210573,-3.486469025,10000,-46.10355488,194.6134026,0,14.03629709,0,103.3276576 +39.1,50.42105316,-3.486441684,10000,-46.12444454,194.6067465,0,14.03629709,0,103.3346836 +39.11,50.42104902,-3.486414344,10000,-46.14533419,194.6007578,0,14.03629709,0,103.3417095 +39.12,50.42104488,-3.486387005,10000,-46.18015031,194.5958812,0,14.03629709,0,103.3487354 +39.13,50.42104073,-3.486359666,10000,-46.21496643,194.5910046,0,14.03629709,0,103.3557613 +39.14,50.42103658,-3.486332328,10000,-46.23237448,194.5852384,0,14.03629709,0,103.3627873 +39.15,50.42103243,-3.486304991,10000,-46.23933768,194.5792496,0,14.03629709,0,103.3698132 +39.16,50.42102828,-3.486277655,10000,-46.25674572,194.5734834,0,14.03629709,0,103.3768391 +39.17,50.42102413,-3.486250319,10000,-46.29156184,194.5674947,0,14.03629709,0,103.383865 +39.18,50.42101997,-3.486222985,10000,-46.32637798,194.5617284,0,14.03629709,0,103.390891 +39.19,50.42101581,-3.486195651,10000,-46.34726765,194.5568519,0,14.03629709,0,103.3979169 +39.2,50.42101165,-3.486168318,10000,-46.36467569,194.5519754,0,14.03629709,0,103.4049428 +39.21,50.42100749,-3.486140985,10000,-46.38556535,194.5462091,0,14.03629709,0,103.4119687 +39.22,50.42100332,-3.486113654,10000,-46.40297339,194.5402205,0,14.03629709,0,103.4189947 +39.23,50.42099916,-3.486086323,10000,-46.42386304,194.5344543,0,14.03629709,0,103.4260206 +39.24,50.42099499,-3.486058993,10000,-46.45867915,194.5284656,0,14.03629709,0,103.4330465 +39.25,50.42099082,-3.486031664,10000,-46.49349528,194.5226994,0,14.03629709,0,103.4400724 +39.26,50.42098664,-3.486004336,10000,-46.51438496,194.5176005,0,14.03629709,0,103.4470984 +39.27,50.42098247,-3.485977008,10000,-46.531793,194.5120568,0,14.03629709,0,103.4541243 +39.28,50.42097829,-3.485949681,10000,-46.55616427,194.5058457,0,14.03629709,0,103.4611502 +39.29,50.42097411,-3.485922356,10000,-46.58401716,194.5000795,0,14.03629709,0,103.4681761 +39.3,50.42096993,-3.48589503,10000,-46.60838844,194.4943134,0,14.03629709,0,103.4752021 +39.31,50.42096574,-3.485867706,10000,-46.62579649,194.4881024,0,14.03629709,0,103.4822279 +39.32,50.42096156,-3.485840383,10000,-46.64668615,194.4825586,0,14.03629709,0,103.4892539 +39.33,50.42095737,-3.48581306,10000,-46.68150227,194.4774598,0,14.03629709,0,103.4962798 +39.34,50.42095318,-3.485785738,10000,-46.71631839,194.4714712,0,14.03629709,0,103.5033057 +39.35,50.42094898,-3.485758417,10000,-46.73720804,194.4648154,0,14.03629709,0,103.5103316 +39.36,50.42094479,-3.485731097,10000,-46.75461608,194.4588268,0,14.03629709,0,103.5173576 +39.37,50.42094059,-3.485703778,10000,-46.77550574,194.4539505,0,14.03629709,0,103.5243835 +39.38,50.42093639,-3.485676459,10000,-46.79291379,194.4490741,0,14.03629709,0,103.5314094 +39.39,50.42093219,-3.485649141,10000,-46.81380347,194.4430856,0,14.03629709,0,103.5384353 +39.4,50.42092799,-3.485621824,10000,-46.84861959,194.4364297,0,14.03629709,0,103.5454613 +39.41,50.42092378,-3.485594508,10000,-46.88343571,194.4304412,0,14.03629709,0,103.5524872 +39.42,50.42091957,-3.485567193,10000,-46.90084375,194.4253425,0,14.03629709,0,103.5595131 +39.43,50.42091536,-3.485539878,10000,-46.90780694,194.4197988,0,14.03629709,0,103.566539 +39.44,50.42091115,-3.485512564,10000,-46.92521499,194.4135879,0,14.03629709,0,103.573565 +39.45,50.42090694,-3.485485252,10000,-46.96003111,194.4080443,0,14.03629709,0,103.5805909 +39.46,50.42090272,-3.485457939,10000,-46.99484724,194.403168,0,14.03629709,0,103.5876168 +39.47,50.4208985,-3.485430628,10000,-47.01225528,194.3978468,0,14.03629709,0,103.5946427 +39.48,50.42089428,-3.485403317,10000,-47.01921848,194.3914135,0,14.03629709,0,103.6016687 +39.49,50.42089006,-3.485376007,10000,-47.03662652,194.3840904,0,14.03629709,0,103.6086946 +39.5,50.42088584,-3.485348699,10000,-47.07144263,194.3774347,0,14.03629709,0,103.6157205 +39.51,50.42088161,-3.485321391,10000,-47.10974037,194.372336,0,14.03629709,0,103.6227464 +39.52,50.42087738,-3.485294084,10000,-47.14107488,194.3674597,0,14.03629709,0,103.6297723 +39.53,50.42087315,-3.485266777,10000,-47.16544615,194.3619162,0,14.03629709,0,103.6367983 +39.54,50.42086891,-3.485239472,10000,-47.18285419,194.3568175,0,14.03629709,0,103.6438242 +39.55,50.42086468,-3.485212167,10000,-47.20026223,194.3521637,0,14.03629709,0,103.6508501 +39.56,50.42086044,-3.485184862,10000,-47.22115188,194.3461753,0,14.03629709,0,103.657876 +39.57,50.4208562,-3.485157559,10000,-47.23855994,194.3390747,0,14.03629709,0,103.664902 +39.58,50.42085196,-3.485130257,10000,-47.25944961,194.3324191,0,14.03629709,0,103.6719279 +39.59,50.42084772,-3.485102955,10000,-47.29426573,194.3262082,0,14.03629709,0,103.6789538 +39.6,50.42084347,-3.485075655,10000,-47.32908185,194.3202199,0,14.03629709,0,103.6859797 +39.61,50.42083922,-3.485048355,10000,-47.34997151,194.3146764,0,14.03629709,0,103.6930057 +39.62,50.42083497,-3.485021056,10000,-47.36737954,194.3095778,0,14.03629709,0,103.7000316 +39.63,50.42083072,-3.484993758,10000,-47.38826919,194.3047016,0,14.03629709,0,103.7070575 +39.64,50.42082646,-3.48496646,10000,-47.40567724,194.2991581,0,14.03629709,0,103.7140834 +39.65,50.42082221,-3.484939163,10000,-47.4265669,194.2929474,0,14.03629709,0,103.7211094 +39.66,50.42081795,-3.484911868,10000,-47.46138303,194.2871815,0,14.03629709,0,103.7281352 +39.67,50.42081369,-3.484884572,10000,-47.49619915,194.2811932,0,14.03629709,0,103.7351612 +39.68,50.42080942,-3.484857278,10000,-47.5170888,194.2740927,0,14.03629709,0,103.7421871 +39.69,50.42080516,-3.484829985,10000,-47.53449684,194.2674371,0,14.03629709,0,103.749213 +39.7,50.42080089,-3.484802693,10000,-47.55886813,194.2623385,0,14.03629709,0,103.7562389 +39.71,50.42079662,-3.484775401,10000,-47.58672102,194.2576849,0,14.03629709,0,103.7632649 +39.72,50.42079235,-3.48474811,10000,-47.61109227,194.2525863,0,14.03629709,0,103.7702908 +39.73,50.42078807,-3.48472082,10000,-47.62850031,194.2468205,0,14.03629709,0,103.7773167 +39.74,50.4207838,-3.48469353,10000,-47.64590837,194.2399425,0,14.03629709,0,103.7843426 +39.75,50.42077952,-3.484666242,10000,-47.67027966,194.2328421,0,14.03629709,0,103.7913686 +39.76,50.42077524,-3.484638955,10000,-47.70161415,194.2270763,0,14.03629709,0,103.7983945 +39.77,50.42077096,-3.484611668,10000,-47.73643026,194.2222002,0,14.03629709,0,103.8054204 +39.78,50.42076667,-3.484584382,10000,-47.76080153,194.2171017,0,14.03629709,0,103.8124463 +39.79,50.42076238,-3.484557097,10000,-47.77472796,194.2115584,0,14.03629709,0,103.8194723 +39.8,50.4207581,-3.484529812,10000,-47.79561762,194.2055702,0,14.03629709,0,103.8264982 +39.81,50.4207538,-3.484502529,10000,-47.81650728,194.1995819,0,14.03629709,0,103.8335241 +39.82,50.42074951,-3.484475246,10000,-47.83043371,194.1938162,0,14.03629709,0,103.84055 +39.83,50.42074522,-3.484447964,10000,-47.85480499,194.1876055,0,14.03629709,0,103.847576 +39.84,50.42074092,-3.484420683,10000,-47.8896211,194.1807276,0,14.03629709,0,103.8546019 +39.85,50.42073662,-3.484393403,10000,-47.92095561,194.1738497,0,14.03629709,0,103.8616278 +39.86,50.42073232,-3.484366124,10000,-47.94532688,194.1678615,0,14.03629709,0,103.8686537 +39.87,50.42072801,-3.484338846,10000,-47.96273492,194.1629856,0,14.03629709,0,103.8756797 +39.88,50.42072371,-3.484311568,10000,-47.98014296,194.158332,0,14.03629709,0,103.8827056 +39.89,50.4207194,-3.484284291,10000,-48.00451423,194.1530112,0,14.03629709,0,103.8897315 +39.9,50.42071509,-3.484257015,10000,-48.03584874,194.1465782,0,14.03629709,0,103.8967574 +39.91,50.42071078,-3.484229739,10000,-48.07066486,194.1394779,0,14.03629709,0,103.9037833 +39.92,50.42070646,-3.484202466,10000,-48.09503612,194.1334897,0,14.03629709,0,103.9108093 +39.93,50.42070214,-3.484175192,10000,-48.10896255,194.1288362,0,14.03629709,0,103.9178352 +39.94,50.42069783,-3.484147919,10000,-48.12985222,194.1235154,0,14.03629709,0,103.9248611 +39.95,50.4206935,-3.484120647,10000,-48.15074188,194.11686,0,14.03629709,0,103.931887 +39.96,50.42068918,-3.484093376,10000,-48.16466829,194.1099822,0,14.03629709,0,103.938913 +39.97,50.42068486,-3.484066106,10000,-48.18903956,194.1039941,0,14.03629709,0,103.9459388 +39.98,50.42068053,-3.484038837,10000,-48.22385568,194.0991182,0,14.03629709,0,103.9529648 +39.99,50.4206762,-3.484011568,10000,-48.25519018,194.0942423,0,14.03629709,0,103.9599907 +40,50.42067187,-3.4839843,10000,-48.27956145,194.0882543,0,14.03629709,0,103.9670166 +40.01,50.42066753,-3.483957033,10000,-48.2969695,194.0813765,0,14.03629709,0,103.9740425 +40.02,50.4206632,-3.483929767,10000,-48.31437755,194.0744987,0,14.03629709,0,103.9810685 +40.03,50.42065886,-3.483902502,10000,-48.33874882,194.0682882,0,14.03629709,0,103.9880944 +40.04,50.42065452,-3.483875238,10000,-48.37008333,194.0625226,0,14.03629709,0,103.9951203 +40.05,50.42065018,-3.483847974,10000,-48.40489945,194.0565346,0,14.03629709,0,104.0021462 +40.06,50.42064583,-3.483820712,10000,-48.42927072,194.050769,0,14.03629709,0,104.0091722 +40.07,50.42064148,-3.48379345,10000,-48.44319714,194.0458932,0,14.03629709,0,104.0161981 +40.08,50.42063714,-3.483766189,10000,-48.46408679,194.0407949,0,14.03629709,0,104.023224 +40.09,50.42063278,-3.483738928,10000,-48.48497643,194.0341396,0,14.03629709,0,104.0302499 +40.1,50.42062843,-3.483711669,10000,-48.49890286,194.0270395,0,14.03629709,0,104.0372759 +40.11,50.42062408,-3.483684411,10000,-48.52327414,194.0212739,0,14.03629709,0,104.0443018 +40.12,50.42061972,-3.483657153,10000,-48.55809026,194.0161757,0,14.03629709,0,104.0513277 +40.13,50.42061536,-3.483629896,10000,-48.58942475,194.0101877,0,14.03629709,0,104.0583536 +40.14,50.420611,-3.48360264,10000,-48.61379602,194.0035325,0,14.03629709,0,104.0653796 +40.15,50.42060663,-3.483575385,10000,-48.63120407,193.9973221,0,14.03629709,0,104.0724055 +40.16,50.42060227,-3.483548131,10000,-48.64861213,193.9915566,0,14.03629709,0,104.0794314 +40.17,50.4205979,-3.483520877,10000,-48.67298339,193.9855687,0,14.03629709,0,104.0864573 +40.18,50.42059353,-3.483493625,10000,-48.70083627,193.9795807,0,14.03629709,0,104.0934833 +40.19,50.42058916,-3.483466373,10000,-48.72520754,193.9738153,0,14.03629709,0,104.1005092 +40.2,50.42058478,-3.483439122,10000,-48.74261558,193.9678273,0,14.03629709,0,104.1075351 +40.21,50.42058041,-3.483411872,10000,-48.76350523,193.9620619,0,14.03629709,0,104.114561 +40.22,50.42057603,-3.483384623,10000,-48.79832135,193.9569637,0,14.03629709,0,104.121587 +40.23,50.42057165,-3.483357374,10000,-48.83313748,193.9511983,0,14.03629709,0,104.1286129 +40.24,50.42056726,-3.483330126,10000,-48.85402714,193.9440982,0,14.03629709,0,104.1356388 +40.25,50.42056288,-3.48330288,10000,-48.87143517,193.9372206,0,14.03629709,0,104.1426647 +40.26,50.42055849,-3.483275634,10000,-48.89232481,193.9312328,0,14.03629709,0,104.1496907 +40.27,50.4205541,-3.483248389,10000,-48.90973284,193.9252449,0,14.03629709,0,104.1567166 +40.28,50.42054971,-3.483221145,10000,-48.9306225,193.9194795,0,14.03629709,0,104.1637425 +40.29,50.42054532,-3.483193902,10000,-48.96543864,193.9143814,0,14.03629709,0,104.1707684 +40.3,50.42054092,-3.483166659,10000,-49.00025478,193.908616,0,14.03629709,0,104.1777943 +40.31,50.42053652,-3.483139417,10000,-49.01766281,193.901516,0,14.03629709,0,104.1848203 +40.32,50.42053212,-3.483112177,10000,-49.02462598,193.8948609,0,14.03629709,0,104.1918461 +40.33,50.42052772,-3.483084937,10000,-49.04203401,193.8897628,0,14.03629709,0,104.1988721 +40.34,50.42052332,-3.483057698,10000,-49.07685013,193.8848872,0,14.03629709,0,104.205898 +40.35,50.42051891,-3.483030459,10000,-49.11166625,193.8788994,0,14.03629709,0,104.2129239 +40.36,50.4205145,-3.483003222,10000,-49.13255591,193.8720219,0,14.03629709,0,104.2199498 +40.37,50.42051009,-3.482975985,10000,-49.14996395,193.8653668,0,14.03629709,0,104.2269758 +40.38,50.42050568,-3.48294875,10000,-49.1708536,193.8598239,0,14.03629709,0,104.2340017 +40.39,50.42050126,-3.482921515,10000,-49.18826164,193.8545034,0,14.03629709,0,104.2410276 +40.4,50.42049685,-3.48289428,10000,-49.20915129,193.8482932,0,14.03629709,0,104.2480535 +40.41,50.42049243,-3.482867048,10000,-49.24396741,193.8423055,0,14.03629709,0,104.2550795 +40.42,50.42048801,-3.482839815,10000,-49.27878353,193.8367626,0,14.03629709,0,104.2621054 +40.43,50.42048358,-3.482812583,10000,-49.29967319,193.8301076,0,14.03629709,0,104.2691313 +40.44,50.42047916,-3.482785353,10000,-49.31708123,193.8227852,0,14.03629709,0,104.2761572 +40.45,50.42047473,-3.482758123,10000,-49.3414525,193.8165751,0,14.03629709,0,104.2831832 +40.46,50.4204703,-3.482730895,10000,-49.36930538,193.8116995,0,14.03629709,0,104.2902091 +40.47,50.42046587,-3.482703666,10000,-49.39367665,193.806824,0,14.03629709,0,104.297235 +40.48,50.42046143,-3.482676439,10000,-49.41108469,193.8006139,0,14.03629709,0,104.3042609 +40.49,50.420457,-3.482649212,10000,-49.43197435,193.7930691,0,14.03629709,0,104.3112869 +40.5,50.42045256,-3.482621987,10000,-49.46679046,193.7857468,0,14.03629709,0,104.3183128 +40.51,50.42044812,-3.482594763,10000,-49.50160658,193.7799816,0,14.03629709,0,104.3253387 +40.52,50.42044367,-3.482567539,10000,-49.52249622,193.7748837,0,14.03629709,0,104.3323646 +40.53,50.42043923,-3.482540316,10000,-49.53990425,193.7691185,0,14.03629709,0,104.3393906 +40.54,50.42043478,-3.482513094,10000,-49.56079391,193.7631308,0,14.03629709,0,104.3464165 +40.55,50.42043033,-3.482485873,10000,-49.57820196,193.7573656,0,14.03629709,0,104.3534424 +40.56,50.42042588,-3.482458652,10000,-49.59909163,193.751378,0,14.03629709,0,104.3604683 +40.57,50.42042143,-3.482431433,10000,-49.63390774,193.7453903,0,14.03629709,0,104.3674943 +40.58,50.42041697,-3.482404214,10000,-49.66872384,193.7396252,0,14.03629709,0,104.3745202 +40.59,50.42041251,-3.482376996,10000,-49.68613187,193.7334151,0,14.03629709,0,104.3815461 +40.6,50.42040805,-3.482349779,10000,-49.69309507,193.7265378,0,14.03629709,0,104.388572 +40.61,50.42040359,-3.482322563,10000,-49.71050312,193.7196604,0,14.03629709,0,104.395598 +40.62,50.42039913,-3.482295348,10000,-49.74531923,193.7136728,0,14.03629709,0,104.4026239 +40.63,50.42039466,-3.482268134,10000,-49.78013534,193.708575,0,14.03629709,0,104.4096498 +40.64,50.42039019,-3.48224092,10000,-49.79754338,193.7028099,0,14.03629709,0,104.4166757 +40.65,50.42038572,-3.482213707,10000,-49.80450658,193.6957101,0,14.03629709,0,104.4237017 +40.66,50.42038125,-3.482186496,10000,-49.82191461,193.6890552,0,14.03629709,0,104.4307275 +40.67,50.42037678,-3.482159285,10000,-49.85673071,193.6839574,0,14.03629709,0,104.4377535 +40.68,50.4203723,-3.482132075,10000,-49.89154682,193.6788596,0,14.03629709,0,104.4447794 +40.69,50.42036782,-3.482104865,10000,-49.91243648,193.6722048,0,14.03629709,0,104.4518053 +40.7,50.42036334,-3.482077657,10000,-49.93332614,193.6648826,0,14.03629709,0,104.4588312 +40.71,50.42035886,-3.48205045,10000,-49.96814226,193.6582278,0,14.03629709,0,104.4658571 +40.72,50.42035437,-3.482023243,10000,-50.00295837,193.6520178,0,14.03629709,0,104.4728831 +40.73,50.42034988,-3.481996038,10000,-50.0203664,193.6460303,0,14.03629709,0,104.479909 +40.74,50.42034539,-3.481968833,10000,-50.02732961,193.6404877,0,14.03629709,0,104.4869349 +40.75,50.4203409,-3.481941629,10000,-50.04473765,193.6351675,0,14.03629709,0,104.4939608 +40.76,50.42033641,-3.481914426,10000,-50.07955375,193.6296249,0,14.03629709,0,104.5009868 +40.77,50.42033191,-3.481887223,10000,-50.11436985,193.623415,0,14.03629709,0,104.5080127 +40.78,50.42032741,-3.481860022,10000,-50.13177789,193.6165378,0,14.03629709,0,104.5150386 +40.79,50.42032291,-3.481832821,10000,-50.1387411,193.6096606,0,14.03629709,0,104.5220645 +40.8,50.42031841,-3.481805622,10000,-50.15614914,193.6034507,0,14.03629709,0,104.5290905 +40.81,50.42031391,-3.481778423,10000,-50.19096525,193.5976857,0,14.03629709,0,104.5361164 +40.82,50.4203094,-3.481751225,10000,-50.22578136,193.5916982,0,14.03629709,0,104.5431423 +40.83,50.42030489,-3.481724028,10000,-50.24667101,193.5857108,0,14.03629709,0,104.5501682 +40.84,50.42030038,-3.481696832,10000,-50.26756066,193.5799458,0,14.03629709,0,104.5571942 +40.85,50.42029587,-3.481669636,10000,-50.30237677,193.5739584,0,14.03629709,0,104.5642201 +40.86,50.42029135,-3.481642442,10000,-50.33719289,193.5677486,0,14.03629709,0,104.571246 +40.87,50.42028683,-3.481615248,10000,-50.35460093,193.5613163,0,14.03629709,0,104.5782719 +40.88,50.42028231,-3.481588055,10000,-50.36156411,193.5546616,0,14.03629709,0,104.5852979 +40.89,50.42027779,-3.481560864,10000,-50.37549052,193.5482293,0,14.03629709,0,104.5923238 +40.9,50.42027327,-3.481533672,10000,-50.39638018,193.5420195,0,14.03629709,0,104.5993497 +40.91,50.42026874,-3.481506483,10000,-50.41726984,193.5360321,0,14.03629709,0,104.6063756 +40.92,50.42026422,-3.481479293,10000,-50.44860433,193.5302672,0,14.03629709,0,104.6134016 +40.93,50.42025969,-3.481452105,10000,-50.49038368,193.5240574,0,14.03629709,0,104.6204275 +40.94,50.42025515,-3.481424917,10000,-50.52171819,193.5174027,0,14.03629709,0,104.6274534 +40.95,50.42025062,-3.481397731,10000,-50.54260785,193.511193,0,14.03629709,0,104.6344793 +40.96,50.42024608,-3.481370545,10000,-50.56349749,193.5054281,0,14.03629709,0,104.6415053 +40.97,50.42024154,-3.48134336,10000,-50.58090551,193.4992183,0,14.03629709,0,104.6485312 +40.98,50.420237,-3.481316176,10000,-50.59831354,193.4925637,0,14.03629709,0,104.6555571 +40.99,50.42023246,-3.481288993,10000,-50.6192032,193.4863539,0,14.03629709,0,104.662583 +41,50.42022791,-3.481261811,10000,-50.63661123,193.4805891,0,14.03629709,0,104.669609 +41.01,50.42022337,-3.481234629,10000,-50.65750089,193.4746018,0,14.03629709,0,104.6766348 +41.02,50.42021882,-3.481207449,10000,-50.69231701,193.468392,0,14.03629709,0,104.6836608 +41.03,50.42021427,-3.481180269,10000,-50.72713313,193.4619599,0,14.03629709,0,104.6906867 +41.04,50.42020971,-3.48115309,10000,-50.74802278,193.4555277,0,14.03629709,0,104.6977126 +41.05,50.42020516,-3.481125913,10000,-50.76543081,193.4497629,0,14.03629709,0,104.7047385 +41.06,50.4202006,-3.481098735,10000,-50.78980207,193.4437756,0,14.03629709,0,104.7117645 +41.07,50.42019604,-3.481071559,10000,-50.81765495,193.4366762,0,14.03629709,0,104.7187904 +41.08,50.42019148,-3.481044384,10000,-50.84202623,193.4297992,0,14.03629709,0,104.7258163 +41.09,50.42018691,-3.48101721,10000,-50.85943426,193.423812,0,14.03629709,0,104.7328422 +41.1,50.42018235,-3.480990036,10000,-50.8803239,193.4178247,0,14.03629709,0,104.7398681 +41.11,50.42017778,-3.480962864,10000,-50.91514002,193.4118375,0,14.03629709,0,104.7468941 +41.12,50.42017321,-3.480935692,10000,-50.94995614,193.4060728,0,14.03629709,0,104.75392 +41.13,50.42016863,-3.480908521,10000,-50.97084578,193.3998631,0,14.03629709,0,104.7609459 +41.14,50.42016406,-3.480881351,10000,-50.9882538,193.3932086,0,14.03629709,0,104.7679718 +41.15,50.42015948,-3.480854182,10000,-51.00914346,193.386999,0,14.03629709,0,104.7749978 +41.16,50.4201549,-3.480827014,10000,-51.02655151,193.3812342,0,14.03629709,0,104.7820237 +41.17,50.42015032,-3.480799846,10000,-51.04395954,193.3750246,0,14.03629709,0,104.7890496 +41.18,50.42014574,-3.48077268,10000,-51.06484919,193.3681477,0,14.03629709,0,104.7960755 +41.19,50.42014115,-3.480745514,10000,-51.08573883,193.3612708,0,14.03629709,0,104.8031015 +41.2,50.42013657,-3.48071835,10000,-51.11707333,193.3550612,0,14.03629709,0,104.8101274 +41.21,50.42013198,-3.480691186,10000,-51.15885268,193.3492965,0,14.03629709,0,104.8171533 +41.22,50.42012738,-3.480664023,10000,-51.18670557,193.3433093,0,14.03629709,0,104.8241792 +41.23,50.42012279,-3.480636861,10000,-51.19366875,193.3373222,0,14.03629709,0,104.8312052 +41.24,50.42011819,-3.4806097,10000,-51.20063193,193.3313351,0,14.03629709,0,104.8382311 +41.25,50.4201136,-3.480582539,10000,-51.22848481,193.3244582,0,14.03629709,0,104.845257 +41.26,50.420109,-3.48055538,10000,-51.27026414,193.3173589,0,14.03629709,0,104.8522829 +41.27,50.42010439,-3.480528222,10000,-51.30159864,193.3113718,0,14.03629709,0,104.8593089 +41.28,50.42009979,-3.480501064,10000,-51.32248829,193.3053847,0,14.03629709,0,104.8663348 +41.29,50.42009518,-3.480473907,10000,-51.34337794,193.2985079,0,14.03629709,0,104.8733607 +41.3,50.42009057,-3.480446752,10000,-51.36078598,193.2925208,0,14.03629709,0,104.8803866 +41.31,50.42008596,-3.480419597,10000,-51.37819402,193.2876459,0,14.03629709,0,104.8874126 +41.32,50.42008135,-3.480392442,10000,-51.39908367,193.2816589,0,14.03629709,0,104.8944385 +41.33,50.42007673,-3.480365289,10000,-51.41997331,193.2745596,0,14.03629709,0,104.9014644 +41.34,50.42007212,-3.480338137,10000,-51.4513078,193.2676828,0,14.03629709,0,104.9084903 +41.35,50.4200675,-3.480310985,10000,-51.48960554,193.2605836,0,14.03629709,0,104.9155163 +41.36,50.42006287,-3.480283835,10000,-51.50701359,193.2534843,0,14.03629709,0,104.9225421 +41.37,50.42005825,-3.480256686,10000,-51.51049516,193.2477197,0,14.03629709,0,104.9295681 +41.38,50.42005363,-3.480229537,10000,-51.5348664,193.2426225,0,14.03629709,0,104.936594 +41.39,50.420049,-3.480202389,10000,-51.58012735,193.2366355,0,14.03629709,0,104.9436199 +41.4,50.42004437,-3.480175242,10000,-51.61842509,193.2297587,0,14.03629709,0,104.9506458 +41.41,50.42003973,-3.480148096,10000,-51.63583313,193.222882,0,14.03629709,0,104.9576718 +41.42,50.4200351,-3.480120951,10000,-51.64279632,193.2166725,0,14.03629709,0,104.9646977 +41.43,50.42003046,-3.480093807,10000,-51.66020435,193.210908,0,14.03629709,0,104.9717236 +41.44,50.42002583,-3.480066663,10000,-51.69153885,193.204921,0,14.03629709,0,104.9787495 +41.45,50.42002118,-3.480039521,10000,-51.71591012,193.1987116,0,14.03629709,0,104.9857755 +41.46,50.42001654,-3.480012379,10000,-51.72983654,193.1920573,0,14.03629709,0,104.9928014 +41.47,50.4200119,-3.479985238,10000,-51.7542078,193.1847357,0,14.03629709,0,104.9998273 +41.48,50.42000725,-3.479958099,10000,-51.78902389,193.177859,0,14.03629709,0,105.0068532 +41.49,50.4200026,-3.47993096,10000,-51.82035837,193.1718721,0,14.03629709,0,105.0138791 +41.5,50.41999795,-3.479903822,10000,-51.84472963,193.1658852,0,14.03629709,0,105.0209051 +41.51,50.41999329,-3.479876685,10000,-51.86213769,193.1598983,0,14.03629709,0,105.027931 +41.52,50.41998864,-3.479849549,10000,-51.87954573,193.1541338,0,14.03629709,0,105.0349569 +41.53,50.41998398,-3.479822413,10000,-51.90043537,193.1479244,0,14.03629709,0,105.0419828 +41.54,50.41997932,-3.479795279,10000,-51.91784339,193.1410478,0,14.03629709,0,105.0490088 +41.55,50.41997466,-3.479768145,10000,-51.93873305,193.1341711,0,14.03629709,0,105.0560347 +41.56,50.41997,-3.479741013,10000,-51.97354917,193.1279618,0,14.03629709,0,105.0630606 +41.57,50.41996533,-3.479713881,10000,-52.00836528,193.1221974,0,14.03629709,0,105.0700865 +41.58,50.41996066,-3.47968675,10000,-52.02925492,193.115988,0,14.03629709,0,105.0771125 +41.59,50.41995599,-3.47965962,10000,-52.04666294,193.1091114,0,14.03629709,0,105.0841384 +41.6,50.41995132,-3.479632491,10000,-52.06755259,193.1022348,0,14.03629709,0,105.0911643 +41.61,50.41994664,-3.479605363,10000,-52.08496064,193.0960255,0,14.03629709,0,105.0981902 +41.62,50.41994197,-3.479578236,10000,-52.10585029,193.0902611,0,14.03629709,0,105.1052162 +41.63,50.41993729,-3.479551109,10000,-52.1406664,193.0840518,0,14.03629709,0,105.1122421 +41.64,50.41993261,-3.479523984,10000,-52.1754825,193.0769528,0,14.03629709,0,105.119268 +41.65,50.41992792,-3.479496859,10000,-52.19637214,193.0694089,0,14.03629709,0,105.1262939 +41.66,50.41992324,-3.479469736,10000,-52.21378017,193.0629772,0,14.03629709,0,105.1333199 +41.67,50.41991855,-3.479442614,10000,-52.23815144,193.0581026,0,14.03629709,0,105.1403457 +41.68,50.41991386,-3.479415491,10000,-52.26600433,193.0523383,0,14.03629709,0,105.1473717 +41.69,50.41990917,-3.47938837,10000,-52.29037558,193.0450169,0,14.03629709,0,105.1543976 +41.7,50.41990447,-3.479361251,10000,-52.30778359,193.0383628,0,14.03629709,0,105.1614235 +41.71,50.41989978,-3.479334131,10000,-52.32519163,193.032376,0,14.03629709,0,105.1684494 +41.72,50.41989508,-3.479307013,10000,-52.34956291,193.0259443,0,14.03629709,0,105.1754754 +41.73,50.41989038,-3.479279896,10000,-52.38089741,193.0192903,0,14.03629709,0,105.1825013 +41.74,50.41988568,-3.479252779,10000,-52.41571351,193.0121913,0,14.03629709,0,105.1895272 +41.75,50.41988097,-3.479225664,10000,-52.43660315,193.0050924,0,14.03629709,0,105.1965531 +41.76,50.41987626,-3.47919855,10000,-52.44008473,192.9993281,0,14.03629709,0,105.2035791 +41.77,50.41987156,-3.479171436,10000,-52.45749277,192.9942311,0,14.03629709,0,105.210605 +41.78,50.41986685,-3.479144323,10000,-52.49579049,192.9882444,0,14.03629709,0,105.2176309 +41.79,50.41986213,-3.479117211,10000,-52.52712497,192.9813679,0,14.03629709,0,105.2246568 +41.8,50.41985742,-3.4790901,10000,-52.54801461,192.974269,0,14.03629709,0,105.2316828 +41.81,50.4198527,-3.47906299,10000,-52.56890426,192.9671701,0,14.03629709,0,105.2387087 +41.82,50.41984798,-3.479035881,10000,-52.5863123,192.9602937,0,14.03629709,0,105.2457346 +41.83,50.41984326,-3.479008773,10000,-52.60720194,192.954307,0,14.03629709,0,105.2527605 +41.84,50.41983854,-3.478981666,10000,-52.64201805,192.94921,0,14.03629709,0,105.2597865 +41.85,50.41983381,-3.478954559,10000,-52.67683416,192.9434458,0,14.03629709,0,105.2668124 +41.86,50.41982908,-3.478927453,10000,-52.69424219,192.9361245,0,14.03629709,0,105.2738383 +41.87,50.41982435,-3.478900349,10000,-52.70120538,192.9283583,0,14.03629709,0,105.2808642 +41.88,50.41981962,-3.478873245,10000,-52.71861341,192.9212595,0,14.03629709,0,105.2878902 +41.89,50.41981489,-3.478846143,10000,-52.75342951,192.9150504,0,14.03629709,0,105.2949161 +41.9,50.41981015,-3.478819041,10000,-52.78824562,192.9092862,0,14.03629709,0,105.301942 +41.91,50.41980541,-3.47879194,10000,-52.80913528,192.9032996,0,14.03629709,0,105.3089679 +41.92,50.41980067,-3.47876484,10000,-52.83002492,192.897313,0,14.03629709,0,105.3159938 +41.93,50.41979593,-3.478737741,10000,-52.86135941,192.8913264,0,14.03629709,0,105.3230198 +41.94,50.41979118,-3.478710642,10000,-52.88573066,192.88445,0,14.03629709,0,105.3300457 +41.95,50.41978643,-3.478683545,10000,-52.89965709,192.8771288,0,14.03629709,0,105.3370716 +41.96,50.41978169,-3.478656449,10000,-52.92054674,192.8704749,0,14.03629709,0,105.3440975 +41.97,50.41977693,-3.478629353,10000,-52.94143638,192.8642658,0,14.03629709,0,105.3511235 +41.98,50.41977218,-3.478602259,10000,-52.95536279,192.8580568,0,14.03629709,0,105.3581494 +41.99,50.41976743,-3.478575165,10000,-52.97973406,192.8516254,0,14.03629709,0,105.3651753 +42,50.41976267,-3.478548072,10000,-53.01455016,192.8449715,0,14.03629709,0,105.3722012 +42.01,50.41975791,-3.478520981,10000,-53.04588464,192.8385401,0,14.03629709,0,105.3792272 +42.02,50.41975315,-3.478493889,10000,-53.0702559,192.8321086,0,14.03629709,0,105.386253 +42.03,50.41974838,-3.4784668,10000,-53.08766394,192.8252323,0,14.03629709,0,105.393279 +42.04,50.41974362,-3.47843971,10000,-53.10855359,192.818356,0,14.03629709,0,105.4003049 +42.05,50.41973885,-3.478412623,10000,-53.14336969,192.8119246,0,14.03629709,0,105.4073308 +42.06,50.41973408,-3.478385535,10000,-53.17818579,192.8054932,0,14.03629709,0,105.4143567 +42.07,50.4197293,-3.478358449,10000,-53.19907544,192.7988394,0,14.03629709,0,105.4213827 +42.08,50.41972453,-3.478331364,10000,-53.21648348,192.792408,0,14.03629709,0,105.4284086 +42.09,50.41971975,-3.478304279,10000,-53.23737311,192.7861991,0,14.03629709,0,105.4354345 +42.1,50.41971497,-3.478277196,10000,-53.25478114,192.7799902,0,14.03629709,0,105.4424604 +42.11,50.41971019,-3.478250113,10000,-53.27218919,192.7735588,0,14.03629709,0,105.4494864 +42.12,50.41970541,-3.478223031,10000,-53.29307884,192.766905,0,14.03629709,0,105.4565123 +42.13,50.41970062,-3.478195951,10000,-53.31048685,192.7602512,0,14.03629709,0,105.4635382 +42.14,50.41969584,-3.47816887,10000,-53.3313765,192.7531526,0,14.03629709,0,105.4705641 +42.15,50.41969105,-3.478141792,10000,-53.3661926,192.7460539,0,14.03629709,0,105.4775901 +42.16,50.41968626,-3.478114714,10000,-53.40100871,192.7402899,0,14.03629709,0,105.484616 +42.17,50.41968146,-3.478087637,10000,-53.42189836,192.7349708,0,14.03629709,0,105.4916419 +42.18,50.41967667,-3.47806056,10000,-53.43930639,192.7280946,0,14.03629709,0,105.4986678 +42.19,50.41967187,-3.478033485,10000,-53.46367764,192.7201062,0,14.03629709,0,105.5056938 +42.2,50.41966707,-3.478006411,10000,-53.49153051,192.7132301,0,14.03629709,0,105.5127197 +42.21,50.41966227,-3.477979338,10000,-53.51590178,192.707911,0,14.03629709,0,105.5197456 +42.22,50.41965746,-3.477952265,10000,-53.53330982,192.702147,0,14.03629709,0,105.5267715 +42.23,50.41965266,-3.477925193,10000,-53.55419946,192.6950484,0,14.03629709,0,105.5337975 +42.24,50.41964785,-3.477898123,10000,-53.58901555,192.6881723,0,14.03629709,0,105.5408234 +42.25,50.41964304,-3.477871053,10000,-53.62383164,192.6819635,0,14.03629709,0,105.5478493 +42.26,50.41963822,-3.477843984,10000,-53.64472128,192.6748649,0,14.03629709,0,105.5548752 +42.27,50.41963341,-3.477816916,10000,-53.66212933,192.667099,0,14.03629709,0,105.5619012 +42.28,50.41962859,-3.47778985,10000,-53.68301898,192.6608902,0,14.03629709,0,105.5689271 +42.29,50.41962377,-3.477762784,10000,-53.70042702,192.6560161,0,14.03629709,0,105.575953 +42.3,50.41961895,-3.477735718,10000,-53.72131666,192.6498073,0,14.03629709,0,105.5829789 +42.31,50.41961413,-3.477708654,10000,-53.75613276,192.641819,0,14.03629709,0,105.5900048 +42.32,50.4196093,-3.477681591,10000,-53.79094885,192.6340531,0,14.03629709,0,105.5970308 +42.33,50.41960447,-3.477654529,10000,-53.80835689,192.627622,0,14.03629709,0,105.6040566 +42.34,50.41959964,-3.477627468,10000,-53.81532008,192.6218581,0,14.03629709,0,105.6110826 +42.35,50.41959481,-3.477600407,10000,-53.83272811,192.6158718,0,14.03629709,0,105.6181085 +42.36,50.41958998,-3.477573348,10000,-53.86754421,192.609663,0,14.03629709,0,105.6251344 +42.37,50.41958514,-3.477546289,10000,-53.90236031,192.6030094,0,14.03629709,0,105.6321603 +42.38,50.4195803,-3.477519231,10000,-53.91976835,192.5954661,0,14.03629709,0,105.6391863 +42.39,50.41957546,-3.477492175,10000,-53.92673153,192.5877003,0,14.03629709,0,105.6462122 +42.4,50.41957062,-3.477465119,10000,-53.94413955,192.5808242,0,14.03629709,0,105.6532381 +42.41,50.41956578,-3.477438065,10000,-53.97895564,192.5752828,0,14.03629709,0,105.660264 +42.42,50.41956093,-3.477411011,10000,-54.01377174,192.5697415,0,14.03629709,0,105.66729 +42.43,50.41955608,-3.477383957,10000,-54.03466139,192.562643,0,14.03629709,0,105.6743159 +42.44,50.41955123,-3.477356906,10000,-54.05555104,192.5555446,0,14.03629709,0,105.6813418 +42.45,50.41954638,-3.477329855,10000,-54.09036716,192.5497808,0,14.03629709,0,105.6883677 +42.46,50.41954152,-3.477302804,10000,-54.12518326,192.5433497,0,14.03629709,0,105.6953937 +42.47,50.41953666,-3.477275755,10000,-54.14259128,192.535584,0,14.03629709,0,105.7024196 +42.48,50.4195318,-3.477248707,10000,-54.14955446,192.528708,0,14.03629709,0,105.7094455 +42.49,50.41952694,-3.47722166,10000,-54.16348086,192.5233891,0,14.03629709,0,105.7164714 +42.5,50.41952208,-3.477194613,10000,-54.18437052,192.5176253,0,14.03629709,0,105.7234974 +42.51,50.41951721,-3.477167567,10000,-54.20526017,192.5105269,0,14.03629709,0,105.7305233 +42.52,50.41951235,-3.477140523,10000,-54.23659465,192.5034286,0,14.03629709,0,105.7375492 +42.53,50.41950748,-3.477113479,10000,-54.27837397,192.4965526,0,14.03629709,0,105.7445751 +42.54,50.4195026,-3.477086436,10000,-54.30970846,192.4892318,0,14.03629709,0,105.7516011 +42.55,50.41949773,-3.477059395,10000,-54.33059812,192.4823559,0,14.03629709,0,105.758627 +42.56,50.41949285,-3.477032354,10000,-54.35148777,192.4763698,0,14.03629709,0,105.7656529 +42.57,50.41948797,-3.477005314,10000,-54.36541416,192.4701612,0,14.03629709,0,105.7726788 +42.58,50.41948309,-3.476978275,10000,-54.37237733,192.4632853,0,14.03629709,0,105.7797048 +42.59,50.41947821,-3.476951237,10000,-54.38978536,192.4561869,0,14.03629709,0,105.7867307 +42.6,50.41947333,-3.4769242,10000,-54.42460147,192.4490886,0,14.03629709,0,105.7937566 +42.61,50.41946844,-3.476897164,10000,-54.45941758,192.4419903,0,14.03629709,0,105.8007825 +42.62,50.41946355,-3.476870129,10000,-54.48030724,192.4351144,0,14.03629709,0,105.8078085 +42.63,50.41945866,-3.476843095,10000,-54.50119688,192.4289059,0,14.03629709,0,105.8148344 +42.64,50.41945377,-3.476816062,10000,-54.53601296,192.4231422,0,14.03629709,0,105.8218603 +42.65,50.41944887,-3.476789029,10000,-54.57082904,192.4169337,0,14.03629709,0,105.8288862 +42.66,50.41944397,-3.476761998,10000,-54.58823708,192.4100578,0,14.03629709,0,105.8359122 +42.67,50.41943907,-3.476734967,10000,-54.59520028,192.4029596,0,14.03629709,0,105.8429381 +42.68,50.41943417,-3.476707938,10000,-54.61260831,192.3958613,0,14.03629709,0,105.849964 +42.69,50.41942927,-3.476680909,10000,-54.64742442,192.388763,0,14.03629709,0,105.8569899 +42.7,50.41942436,-3.476653882,10000,-54.68224053,192.3816648,0,14.03629709,0,105.8640158 +42.71,50.41941945,-3.476626855,10000,-54.69964855,192.374789,0,14.03629709,0,105.8710417 +42.72,50.41941454,-3.47659983,10000,-54.70661172,192.3685805,0,14.03629709,0,105.8780676 +42.73,50.41940963,-3.476572805,10000,-54.72401973,192.3628169,0,14.03629709,0,105.8850936 +42.74,50.41940472,-3.476545781,10000,-54.75883584,192.3566084,0,14.03629709,0,105.8921195 +42.75,50.4193998,-3.476518758,10000,-54.79365195,192.3497327,0,14.03629709,0,105.8991454 +42.76,50.41939488,-3.476491736,10000,-54.81454159,192.3426344,0,14.03629709,0,105.9061713 +42.77,50.41938996,-3.476464715,10000,-54.83543123,192.3355362,0,14.03629709,0,105.9131973 +42.78,50.41938504,-3.476437695,10000,-54.87024732,192.3286605,0,14.03629709,0,105.9202232 +42.79,50.41938011,-3.476410676,10000,-54.90506342,192.3224521,0,14.03629709,0,105.9272491 +42.8,50.41937518,-3.476383658,10000,-54.92247146,192.3164661,0,14.03629709,0,105.934275 +42.81,50.41937025,-3.47635664,10000,-54.92943465,192.3095904,0,14.03629709,0,105.941301 +42.82,50.41936532,-3.476329624,10000,-54.94336105,192.3022698,0,14.03629709,0,105.9483269 +42.83,50.41936039,-3.476302609,10000,-54.96425068,192.295394,0,14.03629709,0,105.9553528 +42.84,50.41935545,-3.476275594,10000,-54.98514032,192.2882959,0,14.03629709,0,105.9623787 +42.85,50.41935052,-3.476248581,10000,-55.01647481,192.2809753,0,14.03629709,0,105.9694047 +42.86,50.41934558,-3.476221569,10000,-55.05825415,192.274322,0,14.03629709,0,105.9764306 +42.87,50.41934063,-3.476194557,10000,-55.08610702,192.2678912,0,14.03629709,0,105.9834565 +42.88,50.41933569,-3.476167547,10000,-55.09655181,192.2610155,0,14.03629709,0,105.9904824 +42.89,50.41933074,-3.476140537,10000,-55.11395983,192.2541398,0,14.03629709,0,105.9975084 +42.9,50.4193258,-3.476113529,10000,-55.14529432,192.2477091,0,14.03629709,0,106.0045343 +42.91,50.41932084,-3.476086521,10000,-55.16966558,192.2412783,0,14.03629709,0,106.0115602 +42.92,50.41931589,-3.476059514,10000,-55.18359199,192.2346251,0,14.03629709,0,106.0185861 +42.93,50.41931094,-3.476032509,10000,-55.20796325,192.2279719,0,14.03629709,0,106.0256121 +42.94,50.41930598,-3.476005503,10000,-55.23929774,192.2208738,0,14.03629709,0,106.032638 +42.95,50.41930102,-3.4759785,10000,-55.26018736,192.2135532,0,14.03629709,0,106.0396639 +42.96,50.41929606,-3.475951497,10000,-55.281077,192.2069001,0,14.03629709,0,106.0466898 +42.97,50.4192911,-3.475924495,10000,-55.31589311,192.2006918,0,14.03629709,0,106.0537158 +42.98,50.41928613,-3.475897494,10000,-55.35070922,192.1944835,0,14.03629709,0,106.0607417 +42.99,50.41928116,-3.475870494,10000,-55.36811725,192.1878303,0,14.03629709,0,106.0677676 +43,50.41927619,-3.475843494,10000,-55.37508042,192.1805098,0,14.03629709,0,106.0747935 +43.01,50.41927122,-3.475816497,10000,-55.38900682,192.1734118,0,14.03629709,0,106.0818195 +43.02,50.41926625,-3.475789499,10000,-55.40989646,192.1667587,0,14.03629709,0,106.0888454 +43.03,50.41926127,-3.475762503,10000,-55.43078611,192.1601055,0,14.03629709,0,106.0958713 +43.04,50.4192563,-3.475735508,10000,-55.4621206,192.1534524,0,14.03629709,0,106.1028972 +43.05,50.41925132,-3.475708513,10000,-55.50389992,192.1463544,0,14.03629709,0,106.1099231 +43.06,50.41924633,-3.47568152,10000,-55.5352344,192.1390339,0,14.03629709,0,106.116949 +43.07,50.41924135,-3.475654528,10000,-55.55612405,192.1323808,0,14.03629709,0,106.123975 +43.08,50.41923636,-3.475627536,10000,-55.5770137,192.1259502,0,14.03629709,0,106.1310009 +43.09,50.41923137,-3.475600546,10000,-55.59094011,192.1190746,0,14.03629709,0,106.1380268 +43.1,50.41922638,-3.475573556,10000,-55.59790327,192.1119767,0,14.03629709,0,106.1450527 +43.11,50.41922139,-3.475546568,10000,-55.61531128,192.1048787,0,14.03629709,0,106.1520786 +43.12,50.4192164,-3.47551958,10000,-55.65012738,192.0980032,0,14.03629709,0,106.1591046 +43.13,50.4192114,-3.475492594,10000,-55.6884251,192.091795,0,14.03629709,0,106.1661305 +43.14,50.4192064,-3.475465608,10000,-55.71975959,192.0858093,0,14.03629709,0,106.1731564 +43.15,50.4192014,-3.475438623,10000,-55.74413085,192.0787113,0,14.03629709,0,106.1801823 +43.16,50.41919639,-3.475411639,10000,-55.76153888,192.0707236,0,14.03629709,0,106.1872083 +43.17,50.41919139,-3.475384657,10000,-55.77894692,192.0636257,0,14.03629709,0,106.1942342 +43.18,50.41918638,-3.475357675,10000,-55.79983655,192.05764,0,14.03629709,0,106.2012601 +43.19,50.41918137,-3.475330694,10000,-55.81724456,192.0514319,0,14.03629709,0,106.208286 +43.2,50.41917636,-3.475303714,10000,-55.83813419,192.0445564,0,14.03629709,0,106.215312 +43.21,50.41917135,-3.475276735,10000,-55.87295029,192.0374585,0,14.03629709,0,106.2223379 +43.22,50.41916633,-3.475249757,10000,-55.9077664,192.0303606,0,14.03629709,0,106.2293638 +43.23,50.41916131,-3.47522278,10000,-55.92865604,192.0232628,0,14.03629709,0,106.2363897 +43.24,50.41915629,-3.475195804,10000,-55.94606405,192.0161649,0,14.03629709,0,106.2434157 +43.25,50.41915127,-3.475168829,10000,-55.96695368,192.009067,0,14.03629709,0,106.2504416 +43.26,50.41914624,-3.475141855,10000,-55.98436171,192.0019692,0,14.03629709,0,106.2574675 +43.27,50.41914122,-3.475114882,10000,-56.00176974,191.9948713,0,14.03629709,0,106.2644934 +43.28,50.41913619,-3.47508791,10000,-56.026141,191.9879959,0,14.03629709,0,106.2715194 +43.29,50.41913116,-3.475060939,10000,-56.05747549,191.9817878,0,14.03629709,0,106.2785453 +43.3,50.41912613,-3.475033969,10000,-56.0957732,191.9760247,0,14.03629709,0,106.2855712 +43.31,50.41912109,-3.475006999,10000,-56.13058929,191.9698166,0,14.03629709,0,106.2925971 +43.32,50.41911605,-3.474980031,10000,-56.14799731,191.9627188,0,14.03629709,0,106.2996231 +43.33,50.41911101,-3.474953063,10000,-56.15496049,191.9547312,0,14.03629709,0,106.306649 +43.34,50.41910597,-3.474926097,10000,-56.16888688,191.9465212,0,14.03629709,0,106.3136749 +43.35,50.41910093,-3.474899132,10000,-56.18977652,191.9394234,0,14.03629709,0,106.3207008 +43.36,50.41909588,-3.474872168,10000,-56.21066617,191.9334378,0,14.03629709,0,106.3277268 +43.37,50.41909084,-3.474845204,10000,-56.24200067,191.9272298,0,14.03629709,0,106.3347526 +43.38,50.41908579,-3.474818242,10000,-56.28378,191.9203545,0,14.03629709,0,106.3417786 +43.39,50.41908073,-3.47479128,10000,-56.31511447,191.9132567,0,14.03629709,0,106.3488045 +43.4,50.41907568,-3.47476432,10000,-56.3360041,191.906159,0,14.03629709,0,106.3558304 +43.41,50.41907062,-3.47473736,10000,-56.35689372,191.8992837,0,14.03629709,0,106.3628563 +43.42,50.41906556,-3.474710402,10000,-56.37082013,191.8928533,0,14.03629709,0,106.3698823 +43.43,50.4190605,-3.474683444,10000,-56.37778332,191.8862004,0,14.03629709,0,106.3769082 +43.44,50.41905544,-3.474656487,10000,-56.39519136,191.8786578,0,14.03629709,0,106.3839341 +43.45,50.41905038,-3.474629532,10000,-56.43000745,191.8708927,0,14.03629709,0,106.39096 +43.46,50.41904531,-3.474602577,10000,-56.46482354,191.863795,0,14.03629709,0,106.397986 +43.47,50.41904024,-3.474575624,10000,-56.48571318,191.8575871,0,14.03629709,0,106.4050119 +43.48,50.41903517,-3.474548671,10000,-56.50660282,191.8516016,0,14.03629709,0,106.4120378 +43.49,50.4190301,-3.474521719,10000,-56.53793731,191.8445039,0,14.03629709,0,106.4190637 +43.5,50.41902502,-3.474494768,10000,-56.56230855,191.8365164,0,14.03629709,0,106.4260896 +43.51,50.41901994,-3.474467819,10000,-56.57623495,191.8294188,0,14.03629709,0,106.4331156 +43.52,50.41901487,-3.47444087,10000,-56.6006062,191.8234333,0,14.03629709,0,106.4401415 +43.53,50.41900978,-3.474413922,10000,-56.63194069,191.8172254,0,14.03629709,0,106.4471674 +43.54,50.4190047,-3.474386975,10000,-56.64934871,191.8103502,0,14.03629709,0,106.4541933 +43.55,50.41899961,-3.474360029,10000,-56.65979351,191.8030301,0,14.03629709,0,106.4612193 +43.56,50.41899453,-3.474333084,10000,-56.68764638,191.7950427,0,14.03629709,0,106.4682452 +43.57,50.41898944,-3.47430614,10000,-56.72942569,191.7868328,0,14.03629709,0,106.4752711 +43.58,50.41898434,-3.474279198,10000,-56.76076017,191.7797352,0,14.03629709,0,106.482297 +43.59,50.41897925,-3.474252256,10000,-56.78164982,191.7737498,0,14.03629709,0,106.489323 +43.6,50.41897415,-3.474225315,10000,-56.80253945,191.7677644,0,14.03629709,0,106.4963489 +43.61,50.41896905,-3.474198375,10000,-56.81646584,191.761779,0,14.03629709,0,106.5033748 +43.62,50.41896395,-3.474171436,10000,-56.82342902,191.7557936,0,14.03629709,0,106.5104007 +43.63,50.41895885,-3.474144497,10000,-56.84083705,191.7484735,0,14.03629709,0,106.5174267 +43.64,50.41895375,-3.47411756,10000,-56.87565315,191.739374,0,14.03629709,0,106.5244526 +43.65,50.41894864,-3.474090624,10000,-56.91046925,191.7302744,0,14.03629709,0,106.5314785 +43.66,50.41894353,-3.47406369,10000,-56.93135888,191.7231768,0,14.03629709,0,106.5385044 +43.67,50.41893842,-3.474036756,10000,-56.95224852,191.7180812,0,14.03629709,0,106.5455304 +43.68,50.41893331,-3.474009823,10000,-56.98706461,191.7129857,0,14.03629709,0,106.5525563 +43.69,50.41892819,-3.47398289,10000,-57.02188071,191.7061105,0,14.03629709,0,106.5595822 +43.7,50.41892307,-3.473955959,10000,-57.03928873,191.6979008,0,14.03629709,0,106.5666081 +43.71,50.41891795,-3.473929029,10000,-57.04625191,191.6901359,0,14.03629709,0,106.5736341 +43.72,50.41891283,-3.4739021,10000,-57.06017831,191.6837057,0,14.03629709,0,106.5806599 +43.73,50.41890771,-3.473875172,10000,-57.08106795,191.6777204,0,14.03629709,0,106.5876859 +43.74,50.41890258,-3.473848244,10000,-57.10195759,191.6706229,0,14.03629709,0,106.5947118 +43.75,50.41889746,-3.473821318,10000,-57.13329207,191.6624131,0,14.03629709,0,106.6017377 +43.76,50.41889233,-3.473794393,10000,-57.17507138,191.6546483,0,14.03629709,0,106.6087636 +43.77,50.41888719,-3.473767469,10000,-57.20640586,191.6482181,0,14.03629709,0,106.6157896 +43.78,50.41888206,-3.473740546,10000,-57.22729549,191.6422329,0,14.03629709,0,106.6228155 +43.79,50.41887692,-3.473713623,10000,-57.24818514,191.6351354,0,14.03629709,0,106.6298414 +43.8,50.41887178,-3.473686702,10000,-57.26211156,191.6271481,0,14.03629709,0,106.6368673 +43.81,50.41886664,-3.473659782,10000,-57.26907473,191.6200506,0,14.03629709,0,106.6438933 +43.82,50.4188615,-3.473632863,10000,-57.28648274,191.613843,0,14.03629709,0,106.6509192 +43.83,50.41885636,-3.473605944,10000,-57.32129883,191.6069679,0,14.03629709,0,106.6579451 +43.84,50.41885121,-3.473579027,10000,-57.35611492,191.599648,0,14.03629709,0,106.664971 +43.85,50.41884606,-3.473552111,10000,-57.37700456,191.592773,0,14.03629709,0,106.671997 +43.86,50.41884091,-3.473525195,10000,-57.39789419,191.5856756,0,14.03629709,0,106.6790229 +43.87,50.41883576,-3.473498281,10000,-57.43271029,191.5783557,0,14.03629709,0,106.6860488 +43.88,50.4188306,-3.473471368,10000,-57.46752638,191.5717032,0,14.03629709,0,106.6930747 +43.89,50.41882544,-3.473444455,10000,-57.48493441,191.5652731,0,14.03629709,0,106.7001007 +43.9,50.41882028,-3.473417544,10000,-57.49189759,191.5581757,0,14.03629709,0,106.7071266 +43.91,50.41881512,-3.473390633,10000,-57.5093056,191.550411,0,14.03629709,0,106.7141525 +43.92,50.41880996,-3.473363724,10000,-57.54412168,191.5428687,0,14.03629709,0,106.7211784 +43.93,50.41880479,-3.473336816,10000,-57.57893778,191.5359937,0,14.03629709,0,106.7282043 +43.94,50.41879962,-3.473309908,10000,-57.59634581,191.5288964,0,14.03629709,0,106.7352303 +43.95,50.41879445,-3.473283002,10000,-57.603309,191.5215765,0,14.03629709,0,106.7422562 +43.96,50.41878928,-3.473256097,10000,-57.62071701,191.5149241,0,14.03629709,0,106.7492821 +43.97,50.41878411,-3.473229192,10000,-57.65553309,191.508494,0,14.03629709,0,106.756308 +43.98,50.41877893,-3.473202289,10000,-57.69034918,191.5016191,0,14.03629709,0,106.763334 +43.99,50.41877375,-3.473175386,10000,-57.71123883,191.4945218,0,14.03629709,0,106.7703599 +44,50.41876857,-3.473148485,10000,-57.72864685,191.487202,0,14.03629709,0,106.7773858 +44.01,50.41876339,-3.473121584,10000,-57.74953647,191.4792149,0,14.03629709,0,106.7844117 +44.02,50.4187582,-3.473094685,10000,-57.76694449,191.4710053,0,14.03629709,0,106.7914377 +44.03,50.41875302,-3.473067787,10000,-57.78783412,191.4641304,0,14.03629709,0,106.7984635 +44.04,50.41874783,-3.47304089,10000,-57.82265022,191.4588127,0,14.03629709,0,106.8054895 +44.05,50.41874264,-3.473013993,10000,-57.85746632,191.4528276,0,14.03629709,0,106.8125154 +44.06,50.41873744,-3.472987097,10000,-57.87835596,191.4446181,0,14.03629709,0,106.8195413 +44.07,50.41873225,-3.472960203,10000,-57.89576397,191.4357412,0,14.03629709,0,106.8265672 +44.08,50.41872705,-3.47293331,10000,-57.92013521,191.4284215,0,14.03629709,0,106.8335932 +44.09,50.41872185,-3.472906418,10000,-57.94798806,191.4224365,0,14.03629709,0,106.8406191 +44.1,50.41871665,-3.472879526,10000,-57.97235931,191.416229,0,14.03629709,0,106.847645 +44.11,50.41871144,-3.472852636,10000,-57.98976733,191.4091317,0,14.03629709,0,106.8546709 +44.12,50.41870624,-3.472825746,10000,-58.00717535,191.4013671,0,14.03629709,0,106.8616969 +44.13,50.41870103,-3.472798858,10000,-58.03154661,191.393825,0,14.03629709,0,106.8687228 +44.14,50.41869582,-3.472771971,10000,-58.05939949,191.3871726,0,14.03629709,0,106.8757487 +44.15,50.41869061,-3.472745084,10000,-58.08377074,191.3807427,0,14.03629709,0,106.8827746 +44.16,50.41868539,-3.472718199,10000,-58.10117875,191.3736455,0,14.03629709,0,106.8898006 +44.17,50.41868018,-3.472691314,10000,-58.12206838,191.3658809,0,14.03629709,0,106.8968265 +44.18,50.41867496,-3.472664431,10000,-58.15688447,191.3583388,0,14.03629709,0,106.9038524 +44.19,50.41866974,-3.472637549,10000,-58.19170055,191.3514641,0,14.03629709,0,106.9108783 +44.2,50.41866451,-3.472610667,10000,-58.21259017,191.3443669,0,14.03629709,0,106.9179043 +44.21,50.41865929,-3.472583787,10000,-58.22999819,191.3370472,0,14.03629709,0,106.9249302 +44.22,50.41865406,-3.472556908,10000,-58.25088783,191.3303949,0,14.03629709,0,106.9319561 +44.23,50.41864883,-3.472530029,10000,-58.26829586,191.3239651,0,14.03629709,0,106.938982 +44.24,50.4186436,-3.472503152,10000,-58.28570387,191.3170904,0,14.03629709,0,106.946008 +44.25,50.41863837,-3.472476275,10000,-58.30659349,191.3097707,0,14.03629709,0,106.9530339 +44.26,50.41863313,-3.4724494,10000,-58.32748313,191.3017838,0,14.03629709,0,106.9600598 +44.27,50.4186279,-3.472422525,10000,-58.35881761,191.2935744,0,14.03629709,0,106.9670857 +44.28,50.41862266,-3.472395653,10000,-58.40059692,191.2862548,0,14.03629709,0,106.9741117 +44.29,50.41861741,-3.47236878,10000,-58.42844978,191.2796026,0,14.03629709,0,106.9811376 +44.3,50.41861217,-3.472341909,10000,-58.43541297,191.2729503,0,14.03629709,0,106.9881635 +44.31,50.41860692,-3.472315039,10000,-58.44237615,191.2662981,0,14.03629709,0,106.9951894 +44.32,50.41860168,-3.472288169,10000,-58.47022902,191.2589785,0,14.03629709,0,107.0022153 +44.33,50.41859643,-3.472261301,10000,-58.51200834,191.2509916,0,14.03629709,0,107.0092413 +44.34,50.41859117,-3.472234434,10000,-58.5433428,191.2438945,0,14.03629709,0,107.0162672 +44.35,50.41858592,-3.472207568,10000,-58.56423241,191.2376872,0,14.03629709,0,107.0232931 +44.36,50.41858066,-3.472180702,10000,-58.58512204,191.2308126,0,14.03629709,0,107.030319 +44.37,50.4185754,-3.472153838,10000,-58.60253008,191.2232706,0,14.03629709,0,107.037345 +44.38,50.41857014,-3.472126975,10000,-58.61993811,191.2157287,0,14.03629709,0,107.0443708 +44.39,50.41856488,-3.472100112,10000,-58.64082773,191.2081867,0,14.03629709,0,107.0513968 +44.4,50.41855961,-3.472073252,10000,-58.65823573,191.2010896,0,14.03629709,0,107.0584227 +44.41,50.41855435,-3.472046391,10000,-58.67912537,191.194215,0,14.03629709,0,107.0654486 +44.42,50.41854908,-3.472019532,10000,-58.71394147,191.1866731,0,14.03629709,0,107.0724745 +44.43,50.41854381,-3.471992674,10000,-58.74875757,191.1791311,0,14.03629709,0,107.0795005 +44.44,50.41853853,-3.471965817,10000,-58.7696472,191.1727014,0,14.03629709,0,107.0865264 +44.45,50.41853326,-3.471938961,10000,-58.7870552,191.1664942,0,14.03629709,0,107.0935523 +44.46,50.41852798,-3.471912105,10000,-58.80794483,191.1587298,0,14.03629709,0,107.1005782 +44.47,50.4185227,-3.471885251,10000,-58.82535285,191.1502981,0,14.03629709,0,107.1076042 +44.48,50.41851742,-3.471858399,10000,-58.84624248,191.1434236,0,14.03629709,0,107.1146301 +44.49,50.41851214,-3.471831546,10000,-58.88105856,191.1369939,0,14.03629709,0,107.121656 +44.5,50.41850685,-3.471804695,10000,-58.91587465,191.1290071,0,14.03629709,0,107.1286819 +44.51,50.41850156,-3.471777845,10000,-58.93676428,191.1210204,0,14.03629709,0,107.1357079 +44.52,50.41849627,-3.471750997,10000,-58.9541723,191.1148132,0,14.03629709,0,107.1427338 +44.53,50.41849098,-3.471724148,10000,-58.97506194,191.108606,0,14.03629709,0,107.1497597 +44.54,50.41848568,-3.471697301,10000,-58.99246995,191.1003968,0,14.03629709,0,107.1567856 +44.55,50.41848039,-3.471670455,10000,-59.00987797,191.0915202,0,14.03629709,0,107.1638116 +44.56,50.41847509,-3.471643611,10000,-59.03424922,191.0842008,0,14.03629709,0,107.1708375 +44.57,50.41846979,-3.471616767,10000,-59.0655837,191.0782161,0,14.03629709,0,107.1778634 +44.58,50.41846449,-3.471589924,10000,-59.10039978,191.072009,0,14.03629709,0,107.1848893 +44.59,50.41845918,-3.471563082,10000,-59.12477101,191.0651345,0,14.03629709,0,107.1919153 +44.6,50.41845387,-3.471536241,10000,-59.13869742,191.0578151,0,14.03629709,0,107.1989412 +44.61,50.41844857,-3.471509401,10000,-59.16306868,191.0498284,0,14.03629709,0,107.2059671 +44.62,50.41844325,-3.471482562,10000,-59.19440316,191.0416193,0,14.03629709,0,107.212993 +44.63,50.41843794,-3.471455725,10000,-59.21181117,191.0342999,0,14.03629709,0,107.220019 +44.64,50.41843262,-3.471428888,10000,-59.21877433,191.0274255,0,14.03629709,0,107.2270449 +44.65,50.41842731,-3.471402052,10000,-59.23618234,191.0198837,0,14.03629709,0,107.2340708 +44.66,50.41842199,-3.471375218,10000,-59.27099843,191.0121195,0,14.03629709,0,107.2410967 +44.67,50.41841667,-3.471348384,10000,-59.30581452,191.0050226,0,14.03629709,0,107.2481227 +44.68,50.41841134,-3.471321552,10000,-59.32670415,190.998593,0,14.03629709,0,107.2551486 +44.69,50.41840602,-3.47129472,10000,-59.34411217,190.9919411,0,14.03629709,0,107.2621745 +44.7,50.41840069,-3.471267889,10000,-59.36848341,190.9843993,0,14.03629709,0,107.2692004 +44.71,50.41839536,-3.47124106,10000,-59.39633627,190.9766351,0,14.03629709,0,107.2762263 +44.72,50.41839003,-3.471214231,10000,-59.4207075,190.9695383,0,14.03629709,0,107.2832522 +44.73,50.41838469,-3.471187404,10000,-59.43811552,190.9631088,0,14.03629709,0,107.2902781 +44.74,50.41837936,-3.471160577,10000,-59.45900515,190.9562344,0,14.03629709,0,107.2973041 +44.75,50.41837402,-3.471133751,10000,-59.49382125,190.9480253,0,14.03629709,0,107.30433 +44.76,50.41836868,-3.471106927,10000,-59.52863734,190.9398163,0,14.03629709,0,107.3113559 +44.77,50.41836333,-3.471080104,10000,-59.54952697,190.9327195,0,14.03629709,0,107.3183818 +44.78,50.41835799,-3.471053281,10000,-59.56693498,190.9256227,0,14.03629709,0,107.3254078 +44.79,50.41835264,-3.47102646,10000,-59.5878246,190.9183035,0,14.03629709,0,107.3324337 +44.8,50.41834729,-3.47099964,10000,-59.60523261,190.9114291,0,14.03629709,0,107.3394596 +44.81,50.41834194,-3.47097282,10000,-59.62612225,190.9041099,0,14.03629709,0,107.3464855 +44.82,50.41833659,-3.470946002,10000,-59.65745672,190.8961233,0,14.03629709,0,107.3535115 +44.83,50.41833123,-3.470919185,10000,-59.68182797,190.8890266,0,14.03629709,0,107.3605374 +44.84,50.41832587,-3.470892369,10000,-59.69575437,190.8828196,0,14.03629709,0,107.3675633 +44.85,50.41832052,-3.470865553,10000,-59.72012561,190.8757228,0,14.03629709,0,107.3745892 +44.86,50.41831515,-3.470838739,10000,-59.75146008,190.8675138,0,14.03629709,0,107.3816152 +44.87,50.41830979,-3.470811926,10000,-59.76886809,190.8595273,0,14.03629709,0,107.3886411 +44.88,50.41830442,-3.470785114,10000,-59.77931288,190.8522081,0,14.03629709,0,107.395667 +44.89,50.41829906,-3.470758303,10000,-59.80716573,190.8451114,0,14.03629709,0,107.4026929 +44.9,50.41829369,-3.470731493,10000,-59.84894505,190.8380147,0,14.03629709,0,107.4097189 +44.91,50.41828831,-3.470704684,10000,-59.88027953,190.8306955,0,14.03629709,0,107.4167448 +44.92,50.41828294,-3.470677876,10000,-59.90116916,190.822709,0,14.03629709,0,107.4237707 +44.93,50.41827756,-3.470651069,10000,-59.92205878,190.8145001,0,14.03629709,0,107.4307966 +44.94,50.41827218,-3.470624264,10000,-59.93598519,190.8074034,0,14.03629709,0,107.4378226 +44.95,50.4182668,-3.470597459,10000,-59.94294836,190.8011965,0,14.03629709,0,107.4448485 +44.96,50.41826142,-3.470570655,10000,-59.96035636,190.7940998,0,14.03629709,0,107.4518744 +44.97,50.41825604,-3.470543852,10000,-59.99517244,190.7861133,0,14.03629709,0,107.4589003 +44.98,50.41825065,-3.470517051,10000,-60.02998853,190.7790167,0,14.03629709,0,107.4659263 +44.99,50.41824526,-3.47049025,10000,-60.05087815,190.7728098,0,14.03629709,0,107.4729522 +45,50.41823987,-3.47046345,10000,-60.07176779,190.7654907,0,14.03629709,0,107.4799781 +45.01,50.41823448,-3.470436651,10000,-60.10658388,190.7566145,0,14.03629709,0,107.487004 +45.02,50.41822908,-3.470409854,10000,-60.14139997,190.7481832,0,14.03629709,0,107.49403 +45.03,50.41822368,-3.470383058,10000,-60.15880798,190.741309,0,14.03629709,0,107.5010559 +45.04,50.41821828,-3.470356262,10000,-60.16577114,190.7348797,0,14.03629709,0,107.5080818 +45.05,50.41821288,-3.470329468,10000,-60.17969753,190.7280055,0,14.03629709,0,107.5151077 +45.06,50.41820748,-3.470302674,10000,-60.20058716,190.7209089,0,14.03629709,0,107.5221337 +45.07,50.41820207,-3.470275882,10000,-60.2214768,190.7135899,0,14.03629709,0,107.5291595 +45.08,50.41819667,-3.47024909,10000,-60.25281128,190.7056035,0,14.03629709,0,107.5361855 +45.09,50.41819126,-3.4702223,10000,-60.2945906,190.6973946,0,14.03629709,0,107.5432114 +45.1,50.41818584,-3.470195511,10000,-60.32592506,190.690298,0,14.03629709,0,107.5502373 +45.11,50.41818043,-3.470168723,10000,-60.34681468,190.6840913,0,14.03629709,0,107.5572632 +45.12,50.41817501,-3.470141935,10000,-60.36770431,190.6769947,0,14.03629709,0,107.5642891 +45.13,50.41816959,-3.470115149,10000,-60.3816307,190.6687859,0,14.03629709,0,107.5713151 +45.14,50.41816417,-3.470088364,10000,-60.38859386,190.6607996,0,14.03629709,0,107.578341 +45.15,50.41815875,-3.47006158,10000,-60.40600187,190.6534805,0,14.03629709,0,107.5853669 +45.16,50.41815333,-3.470034797,10000,-60.44081797,190.646384,0,14.03629709,0,107.5923928 +45.17,50.4181479,-3.470008015,10000,-60.47563406,190.639065,0,14.03629709,0,107.5994188 +45.18,50.41814247,-3.469981234,10000,-60.49652369,190.6310787,0,14.03629709,0,107.6064447 +45.19,50.41813704,-3.469954454,10000,-60.51393169,190.6228699,0,14.03629709,0,107.6134706 +45.2,50.41813161,-3.469927676,10000,-60.53482132,190.6157734,0,14.03629709,0,107.6204965 +45.21,50.41812617,-3.469900898,10000,-60.55571096,190.6095667,0,14.03629709,0,107.6275225 +45.22,50.41812074,-3.469874121,10000,-60.58704542,190.6024702,0,14.03629709,0,107.6345484 +45.23,50.4181153,-3.469847345,10000,-60.6253431,190.5942614,0,14.03629709,0,107.6415743 +45.24,50.41810985,-3.469820571,10000,-60.6427511,190.5862752,0,14.03629709,0,107.6486002 +45.25,50.41810441,-3.469793797,10000,-60.64623267,190.5789562,0,14.03629709,0,107.6556262 +45.26,50.41809897,-3.469767025,10000,-60.66712231,190.5718597,0,14.03629709,0,107.6626521 +45.27,50.41809352,-3.469740253,10000,-60.70193839,190.5647633,0,14.03629709,0,107.669678 +45.28,50.41808807,-3.469713483,10000,-60.73327286,190.5574444,0,14.03629709,0,107.6767039 +45.29,50.41808262,-3.469686713,10000,-60.75764411,190.5494581,0,14.03629709,0,107.6837299 +45.3,50.41807716,-3.469659945,10000,-60.77505211,190.5412494,0,14.03629709,0,107.6907558 +45.31,50.41807171,-3.469633178,10000,-60.79594173,190.534153,0,14.03629709,0,107.6977817 +45.32,50.41806625,-3.469606412,10000,-60.83075781,190.5279463,0,14.03629709,0,107.7048076 +45.33,50.41806079,-3.469579646,10000,-60.8655739,190.5208499,0,14.03629709,0,107.7118336 +45.34,50.41805532,-3.469552882,10000,-60.88298192,190.5126413,0,14.03629709,0,107.7188595 +45.35,50.41804986,-3.469526119,10000,-60.88994508,190.504655,0,14.03629709,0,107.7258854 +45.36,50.41804439,-3.469499357,10000,-60.90735309,190.4973362,0,14.03629709,0,107.7329113 +45.37,50.41803893,-3.469472596,10000,-60.93868755,190.4900173,0,14.03629709,0,107.7399373 +45.38,50.41803345,-3.469445836,10000,-60.96305881,190.4820311,0,14.03629709,0,107.7469632 +45.39,50.41802798,-3.469419077,10000,-60.9769852,190.4738225,0,14.03629709,0,107.7539891 +45.4,50.41802251,-3.46939232,10000,-61.00135643,190.4665037,0,14.03629709,0,107.761015 +45.41,50.41801703,-3.469365563,10000,-61.0326909,190.4596297,0,14.03629709,0,107.7680409 +45.42,50.41801155,-3.469338807,10000,-61.05358054,190.4520885,0,14.03629709,0,107.7750668 +45.43,50.41800607,-3.469312053,10000,-61.07447017,190.4443248,0,14.03629709,0,107.7820928 +45.44,50.41800059,-3.469285299,10000,-61.10928624,190.4372284,0,14.03629709,0,107.7891187 +45.45,50.4179951,-3.469258547,10000,-61.14410231,190.4307994,0,14.03629709,0,107.7961446 +45.46,50.41798961,-3.469231795,10000,-61.16151032,190.4239255,0,14.03629709,0,107.8031705 +45.47,50.41798412,-3.469205044,10000,-61.16847349,190.4157169,0,14.03629709,0,107.8101965 +45.48,50.41797863,-3.469178295,10000,-61.1858815,190.4072859,0,14.03629709,0,107.8172224 +45.49,50.41797314,-3.469151547,10000,-61.22069759,190.3995223,0,14.03629709,0,107.8242483 +45.5,50.41796764,-3.469124799,10000,-61.25551367,190.391981,0,14.03629709,0,107.8312742 +45.51,50.41796214,-3.469098054,10000,-61.27292169,190.3848847,0,14.03629709,0,107.8383001 +45.52,50.41795664,-3.469071308,10000,-61.27988486,190.3780109,0,14.03629709,0,107.8453261 +45.53,50.41795114,-3.469044564,10000,-61.29729287,190.3704697,0,14.03629709,0,107.852352 +45.54,50.41794564,-3.469017821,10000,-61.33210894,190.362706,0,14.03629709,0,107.8593779 +45.55,50.41794013,-3.468991079,10000,-61.36692502,190.3551649,0,14.03629709,0,107.8664038 +45.56,50.41793462,-3.468964338,10000,-61.38781464,190.3471788,0,14.03629709,0,107.8734298 +45.57,50.41792911,-3.468937598,10000,-61.40522265,190.3389703,0,14.03629709,0,107.8804557 +45.58,50.4179236,-3.46891086,10000,-61.42611229,190.3316516,0,14.03629709,0,107.8874816 +45.59,50.41791808,-3.468884122,10000,-61.4435203,190.3247778,0,14.03629709,0,107.8945075 +45.6,50.41791257,-3.468857385,10000,-61.46440992,190.3172366,0,14.03629709,0,107.9015335 +45.61,50.41790705,-3.46883065,10000,-61.49922599,190.309473,0,14.03629709,0,107.9085594 +45.62,50.41790153,-3.468803915,10000,-61.53404207,190.3021543,0,14.03629709,0,107.9155853 +45.63,50.417896,-3.468777182,10000,-61.5549317,190.2948357,0,14.03629709,0,107.9226112 +45.64,50.41789048,-3.468750449,10000,-61.57233971,190.2868497,0,14.03629709,0,107.9296372 +45.65,50.41788495,-3.468723718,10000,-61.59322933,190.2786412,0,14.03629709,0,107.9366631 +45.66,50.41787942,-3.468696988,10000,-61.61063734,190.271545,0,14.03629709,0,107.943689 +45.67,50.41787389,-3.468670259,10000,-61.63152696,190.2653386,0,14.03629709,0,107.9507149 +45.68,50.41786836,-3.46864353,10000,-61.66634304,190.2582424,0,14.03629709,0,107.9577409 +45.69,50.41786282,-3.468616803,10000,-61.70115912,190.250034,0,14.03629709,0,107.9647668 +45.7,50.41785728,-3.468590077,10000,-61.71856713,190.2418255,0,14.03629709,0,107.9717927 +45.71,50.41785174,-3.468563352,10000,-61.72553029,190.2336171,0,14.03629709,0,107.9788186 +45.72,50.4178462,-3.468536628,10000,-61.74293831,190.2254087,0,14.03629709,0,107.9858446 +45.73,50.41784066,-3.468509906,10000,-61.7777544,190.2180901,0,14.03629709,0,107.9928704 +45.74,50.41783511,-3.468483184,10000,-61.81257048,190.2112164,0,14.03629709,0,107.9998964 +45.75,50.41782956,-3.468456463,10000,-61.8334601,190.2038978,0,14.03629709,0,108.0069223 +45.76,50.41782401,-3.468429744,10000,-61.8508681,190.1968016,0,14.03629709,0,108.0139482 +45.77,50.41781846,-3.468403025,10000,-61.87175772,190.1897055,0,14.03629709,0,108.0209741 +45.78,50.4178129,-3.468376307,10000,-61.88916574,190.1814971,0,14.03629709,0,108.0280001 +45.79,50.41780735,-3.468349591,10000,-61.91005536,190.1732888,0,14.03629709,0,108.035026 +45.8,50.41780179,-3.468322876,10000,-61.94487143,190.1661926,0,14.03629709,0,108.0420519 +45.81,50.41779623,-3.468296161,10000,-61.9796875,190.1588741,0,14.03629709,0,108.0490778 +45.82,50.41779066,-3.468269448,10000,-62.00057713,190.1506657,0,14.03629709,0,108.0561038 +45.83,50.4177851,-3.468242736,10000,-62.01798516,190.1426798,0,14.03629709,0,108.0631297 +45.84,50.41777953,-3.468216025,10000,-62.03887478,190.1353613,0,14.03629709,0,108.0701556 +45.85,50.41777396,-3.468189315,10000,-62.05628277,190.1282652,0,14.03629709,0,108.0771815 +45.86,50.41776839,-3.468162606,10000,-62.07369077,190.1209467,0,14.03629709,0,108.0842075 +45.87,50.41776282,-3.468135898,10000,-62.0945804,190.1127384,0,14.03629709,0,108.0912334 +45.88,50.41775724,-3.468109191,10000,-62.11547003,190.1036403,0,14.03629709,0,108.0982593 +45.89,50.41775167,-3.468082486,10000,-62.14680449,190.0952095,0,14.03629709,0,108.1052852 +45.9,50.41774609,-3.468055782,10000,-62.1885838,190.0883359,0,14.03629709,0,108.1123112 +45.91,50.4177405,-3.468029078,10000,-62.21643666,190.0819072,0,14.03629709,0,108.1193371 +45.92,50.41773492,-3.468002376,10000,-62.22339983,190.0750336,0,14.03629709,0,108.126363 +45.93,50.41772933,-3.467975674,10000,-62.23036298,190.0679376,0,14.03629709,0,108.1333889 +45.94,50.41772375,-3.467948974,10000,-62.25821583,190.0606191,0,14.03629709,0,108.1404148 +45.95,50.41771816,-3.467922274,10000,-62.29999514,190.0526333,0,14.03629709,0,108.1474408 +45.96,50.41771256,-3.467895576,10000,-62.33132961,190.0442026,0,14.03629709,0,108.1544667 +45.97,50.41770697,-3.467868879,10000,-62.35221922,190.0362168,0,14.03629709,0,108.1614926 +45.98,50.41770137,-3.467842183,10000,-62.37310884,190.0286759,0,14.03629709,0,108.1685185 +45.99,50.41769577,-3.467815488,10000,-62.38703523,190.0206901,0,14.03629709,0,108.1755445 +46,50.41769017,-3.467788794,10000,-62.39399841,190.0124819,0,14.03629709,0,108.1825704 +46.01,50.41768457,-3.467762102,10000,-62.41140641,190.0051635,0,14.03629709,0,108.1895963 +46.02,50.41767897,-3.46773541,10000,-62.44622248,189.9982899,0,14.03629709,0,108.1966222 +46.03,50.41767336,-3.467708719,10000,-62.48103856,189.9907491,0,14.03629709,0,108.2036482 +46.04,50.41766775,-3.46768203,10000,-62.50192818,189.9829858,0,14.03629709,0,108.2106741 +46.05,50.41766214,-3.467655341,10000,-62.52281781,189.9756674,0,14.03629709,0,108.2177 +46.06,50.41765653,-3.467628654,10000,-62.5576339,189.968349,0,14.03629709,0,108.2247259 +46.07,50.41765091,-3.467601967,10000,-62.59244997,189.9603633,0,14.03629709,0,108.2317519 +46.08,50.41764529,-3.467575282,10000,-62.60985798,189.9519326,0,14.03629709,0,108.2387777 +46.09,50.41763967,-3.467548598,10000,-62.61682114,189.9439469,0,14.03629709,0,108.2458037 +46.1,50.41763405,-3.467521915,10000,-62.63422915,189.9364061,0,14.03629709,0,108.2528296 +46.11,50.41762843,-3.467495233,10000,-62.66904522,189.9286428,0,14.03629709,0,108.2598555 +46.12,50.4176228,-3.467468552,10000,-62.70386129,189.921102,0,14.03629709,0,108.2668814 +46.13,50.41761717,-3.467441873,10000,-62.72126929,189.9140061,0,14.03629709,0,108.2739074 +46.14,50.41761154,-3.467415193,10000,-62.72823246,189.9060204,0,14.03629709,0,108.2809333 +46.15,50.41760591,-3.467388516,10000,-62.74564047,189.8973674,0,14.03629709,0,108.2879592 +46.16,50.41760028,-3.46736184,10000,-62.78045654,189.8898266,0,14.03629709,0,108.2949851 +46.17,50.41759464,-3.467335164,10000,-62.81527261,189.8831757,0,14.03629709,0,108.3020111 +46.18,50.417589,-3.46730849,10000,-62.83268061,189.8760798,0,14.03629709,0,108.309037 +46.19,50.41758336,-3.467281816,10000,-62.83964379,189.8680941,0,14.03629709,0,108.3160629 +46.2,50.41757772,-3.467255144,10000,-62.85705181,189.8596636,0,14.03629709,0,108.3230888 +46.21,50.41757208,-3.467228473,10000,-62.89186788,189.8516779,0,14.03629709,0,108.3301148 +46.22,50.41756643,-3.467201803,10000,-62.92668396,189.8441372,0,14.03629709,0,108.3371407 +46.23,50.41756078,-3.467175134,10000,-62.94757359,189.8361516,0,14.03629709,0,108.3441666 +46.24,50.41755513,-3.467148466,10000,-62.9649816,189.8279435,0,14.03629709,0,108.3511925 +46.25,50.41754948,-3.4671218,10000,-62.9858712,189.8208477,0,14.03629709,0,108.3582185 +46.26,50.41754382,-3.467095134,10000,-63.00327919,189.8146417,0,14.03629709,0,108.3652444 +46.27,50.41753817,-3.467068469,10000,-63.0241688,189.8073234,0,14.03629709,0,108.3722703 +46.28,50.41753251,-3.467041805,10000,-63.05898488,189.7982255,0,14.03629709,0,108.3792962 +46.29,50.41752685,-3.467015143,10000,-63.09380097,189.7889052,0,14.03629709,0,108.3863222 +46.3,50.41752118,-3.466988482,10000,-63.1146906,189.7806972,0,14.03629709,0,108.3933481 +46.31,50.41751552,-3.466961822,10000,-63.1320986,189.7736014,0,14.03629709,0,108.400374 +46.32,50.41750985,-3.466935163,10000,-63.15646982,189.7673955,0,14.03629709,0,108.4073999 +46.33,50.41750418,-3.466908505,10000,-63.18432267,189.7611895,0,14.03629709,0,108.4144258 +46.34,50.41749851,-3.466881847,10000,-63.20869392,189.7532039,0,14.03629709,0,108.4214518 +46.35,50.41749283,-3.466855191,10000,-63.22610193,189.7436612,0,14.03629709,0,108.4284777 +46.36,50.41748716,-3.466828537,10000,-63.24350993,189.7347859,0,14.03629709,0,108.4355036 +46.37,50.41748148,-3.466801883,10000,-63.26788116,189.7274677,0,14.03629709,0,108.4425295 +46.38,50.4174758,-3.466775231,10000,-63.29573401,189.7210393,0,14.03629709,0,108.4495555 +46.39,50.41747012,-3.466748579,10000,-63.32010523,189.714166,0,14.03629709,0,108.4565813 +46.4,50.41746443,-3.466721928,10000,-63.33751323,189.7057356,0,14.03629709,0,108.4636073 +46.41,50.41745875,-3.466695279,10000,-63.35492124,189.6966378,0,14.03629709,0,108.4706332 +46.42,50.41745306,-3.466668631,10000,-63.37929248,189.6884299,0,14.03629709,0,108.4776591 +46.43,50.41744737,-3.466641984,10000,-63.40714532,189.6811117,0,14.03629709,0,108.484685 +46.44,50.41744168,-3.466615338,10000,-63.43151655,189.674016,0,14.03629709,0,108.491711 +46.45,50.41743598,-3.466588693,10000,-63.45240618,189.6666979,0,14.03629709,0,108.4987369 +46.46,50.41743029,-3.466562049,10000,-63.48374064,189.6587124,0,14.03629709,0,108.5057628 +46.47,50.41742459,-3.466535406,10000,-63.52203833,189.650282,0,14.03629709,0,108.5127887 +46.48,50.41741888,-3.466508765,10000,-63.53944634,189.6422966,0,14.03629709,0,108.5198147 +46.49,50.41741318,-3.466482124,10000,-63.54292788,189.6349785,0,14.03629709,0,108.5268406 +46.5,50.41740748,-3.466455485,10000,-63.56381749,189.6276604,0,14.03629709,0,108.5338665 +46.51,50.41740177,-3.466428846,10000,-63.59515194,189.6196749,0,14.03629709,0,108.5408924 +46.52,50.41739606,-3.466402209,10000,-63.61604156,189.6112446,0,14.03629709,0,108.5479184 +46.53,50.41739035,-3.466375573,10000,-63.63693119,189.6032591,0,14.03629709,0,108.5549443 +46.54,50.41738464,-3.466348938,10000,-63.67174727,189.595941,0,14.03629709,0,108.5619702 +46.55,50.41737892,-3.466322304,10000,-63.70656334,189.5888454,0,14.03629709,0,108.5689961 +46.56,50.4173732,-3.466295671,10000,-63.72397134,189.5815274,0,14.03629709,0,108.5760221 +46.57,50.41736748,-3.466269039,10000,-63.7309345,189.5735419,0,14.03629709,0,108.583048 +46.58,50.41736176,-3.466242408,10000,-63.7483425,189.5651116,0,14.03629709,0,108.5900739 +46.59,50.41735604,-3.466215779,10000,-63.78315858,189.5569038,0,14.03629709,0,108.5970998 +46.6,50.41735031,-3.46618915,10000,-63.81797465,189.5486959,0,14.03629709,0,108.6041258 +46.61,50.41734458,-3.466162523,10000,-63.83538266,189.5402657,0,14.03629709,0,108.6111517 +46.62,50.41733885,-3.466135897,10000,-63.84234582,189.5322803,0,14.03629709,0,108.6181776 +46.63,50.41733312,-3.466109272,10000,-63.85975383,189.5249622,0,14.03629709,0,108.6252035 +46.64,50.41732739,-3.466082648,10000,-63.89456989,189.5178667,0,14.03629709,0,108.6322295 +46.65,50.41732165,-3.466056025,10000,-63.92938595,189.5107711,0,14.03629709,0,108.6392554 +46.66,50.41731591,-3.466029403,10000,-63.95027557,189.5034531,0,14.03629709,0,108.6462813 +46.67,50.41731017,-3.466002782,10000,-63.96768358,189.4952453,0,14.03629709,0,108.6533072 +46.68,50.41730443,-3.465976162,10000,-63.9885732,189.4861477,0,14.03629709,0,108.6603332 +46.69,50.41729868,-3.465949544,10000,-64.0059812,189.4777175,0,14.03629709,0,108.6673591 +46.7,50.41729294,-3.465922927,10000,-64.02687082,189.470622,0,14.03629709,0,108.674385 +46.71,50.41728719,-3.46589631,10000,-64.0616869,189.463304,0,14.03629709,0,108.6814109 +46.72,50.41728144,-3.465869695,10000,-64.09650297,189.4550962,0,14.03629709,0,108.6884368 +46.73,50.41727568,-3.465843081,10000,-64.11739258,189.4468885,0,14.03629709,0,108.6954628 +46.74,50.41726993,-3.465816468,10000,-64.13480058,189.4386807,0,14.03629709,0,108.7024886 +46.75,50.41726417,-3.465789856,10000,-64.1556902,189.4302505,0,14.03629709,0,108.7095146 +46.76,50.41725841,-3.465763246,10000,-64.17309821,189.4222652,0,14.03629709,0,108.7165405 +46.77,50.41725265,-3.465736636,10000,-64.19398783,189.4149473,0,14.03629709,0,108.7235664 +46.78,50.41724689,-3.465710028,10000,-64.2288039,189.4078518,0,14.03629709,0,108.7305923 +46.79,50.41724112,-3.46568342,10000,-64.26361997,189.4007563,0,14.03629709,0,108.7376183 +46.8,50.41723535,-3.465656814,10000,-64.28102797,189.3934384,0,14.03629709,0,108.7446442 +46.81,50.41722958,-3.465630208,10000,-64.28799111,189.3854532,0,14.03629709,0,108.7516701 +46.82,50.41722381,-3.465603604,10000,-64.30539912,189.377023,0,14.03629709,0,108.758696 +46.83,50.41721804,-3.465577001,10000,-64.34021521,189.3688153,0,14.03629709,0,108.765722 +46.84,50.41721226,-3.465550399,10000,-64.37503128,189.3603852,0,14.03629709,0,108.7727479 +46.85,50.41720648,-3.465523798,10000,-64.39243927,189.3512877,0,14.03629709,0,108.7797738 +46.86,50.4172007,-3.465497199,10000,-64.39940243,189.3428576,0,14.03629709,0,108.7867997 +46.87,50.41719492,-3.465470601,10000,-64.41681044,189.3357621,0,14.03629709,0,108.7938257 +46.88,50.41718914,-3.465444003,10000,-64.45162651,189.3286667,0,14.03629709,0,108.8008516 +46.89,50.41718335,-3.465417407,10000,-64.48644257,189.3213489,0,14.03629709,0,108.8078775 +46.9,50.41717756,-3.465390812,10000,-64.50733217,189.3144759,0,14.03629709,0,108.8149034 +46.91,50.41717177,-3.465364217,10000,-64.52474018,189.3069356,0,14.03629709,0,108.8219294 +46.92,50.41716598,-3.465337624,10000,-64.54562981,189.2978382,0,14.03629709,0,108.8289553 +46.93,50.41716018,-3.465311032,10000,-64.56303783,189.2887408,0,14.03629709,0,108.8359812 +46.94,50.41715439,-3.465284442,10000,-64.58392745,189.2812005,0,14.03629709,0,108.8430071 +46.95,50.41714859,-3.465257852,10000,-64.6187435,189.2741051,0,14.03629709,0,108.8500331 +46.96,50.41714279,-3.465231263,10000,-64.65355955,189.265675,0,14.03629709,0,108.857059 +46.97,50.41713698,-3.465204676,10000,-64.67444917,189.2565776,0,14.03629709,0,108.8640849 +46.98,50.41713118,-3.46517809,10000,-64.69185717,189.24837,0,14.03629709,0,108.8711108 +46.99,50.41712537,-3.465151505,10000,-64.71274679,189.2410522,0,14.03629709,0,108.8781368 +47,50.41711956,-3.465124921,10000,-64.73015479,189.2339569,0,14.03629709,0,108.8851627 +47.01,50.41711375,-3.465098338,10000,-64.75104441,189.2266391,0,14.03629709,0,108.8921886 +47.02,50.41710794,-3.465071756,10000,-64.78237888,189.218654,0,14.03629709,0,108.8992145 +47.03,50.41710212,-3.465045175,10000,-64.80675012,189.210224,0,14.03629709,0,108.9062405 +47.04,50.4170963,-3.465018596,10000,-64.82067651,189.2020164,0,14.03629709,0,108.9132664 +47.05,50.41709049,-3.464992017,10000,-64.84504772,189.1938089,0,14.03629709,0,108.9202923 +47.06,50.41708466,-3.46496544,10000,-64.87638216,189.1853789,0,14.03629709,0,108.9273182 +47.07,50.41707884,-3.464938864,10000,-64.89727178,189.1773938,0,14.03629709,0,108.9343442 +47.08,50.41707301,-3.464912289,10000,-64.91816141,189.170076,0,14.03629709,0,108.94137 +47.09,50.41706719,-3.464885715,10000,-64.94949586,189.1627583,0,14.03629709,0,108.948396 +47.1,50.41706135,-3.464859142,10000,-64.97386708,189.1547732,0,14.03629709,0,108.9554219 +47.11,50.41705552,-3.46483257,10000,-64.98779346,189.1463433,0,14.03629709,0,108.9624478 +47.12,50.41704969,-3.464806,10000,-65.01216469,189.1381357,0,14.03629709,0,108.9694737 +47.13,50.41704385,-3.46477943,10000,-65.04349914,189.1301507,0,14.03629709,0,108.9764996 +47.14,50.41703801,-3.464752862,10000,-65.06090713,189.1223881,0,14.03629709,0,108.9835256 +47.15,50.41703217,-3.464726295,10000,-65.06787029,189.1146255,0,14.03629709,0,108.9905515 +47.16,50.41702633,-3.464699728,10000,-65.08527831,189.1061955,0,14.03629709,0,108.9975774 +47.17,50.41702049,-3.464673164,10000,-65.12009438,189.0979881,0,14.03629709,0,109.0046033 +47.18,50.41701464,-3.4646466,10000,-65.15491045,189.0908928,0,14.03629709,0,109.0116293 +47.19,50.41700879,-3.464620037,10000,-65.17580005,189.0835752,0,14.03629709,0,109.0186552 +47.2,50.41700294,-3.464593475,10000,-65.19668967,189.0753677,0,14.03629709,0,109.0256811 +47.21,50.41699709,-3.464566915,10000,-65.23150575,189.0671603,0,14.03629709,0,109.032707 +47.22,50.41699123,-3.464540355,10000,-65.26632181,189.0589528,0,14.03629709,0,109.039733 +47.23,50.41698537,-3.464513797,10000,-65.2837298,189.0503005,0,14.03629709,0,109.0467589 +47.24,50.41697951,-3.46448724,10000,-65.29069295,189.0414257,0,14.03629709,0,109.0537848 +47.25,50.41697365,-3.464460684,10000,-65.30461935,189.0329958,0,14.03629709,0,109.0608107 +47.26,50.41696779,-3.46443413,10000,-65.32550898,189.0256782,0,14.03629709,0,109.0678367 +47.27,50.41696192,-3.464407576,10000,-65.34639859,189.018583,0,14.03629709,0,109.0748626 +47.28,50.41695606,-3.464381023,10000,-65.37773302,189.0103756,0,14.03629709,0,109.0818885 +47.29,50.41695019,-3.464354472,10000,-65.41951231,189.0021682,0,14.03629709,0,109.0889144 +47.3,50.41694431,-3.464327922,10000,-65.44736516,188.9950731,0,14.03629709,0,109.0959404 +47.31,50.41693844,-3.464301372,10000,-65.45432834,188.9877555,0,14.03629709,0,109.1029663 +47.32,50.41693256,-3.464274824,10000,-65.46129149,188.9793256,0,14.03629709,0,109.1099922 +47.33,50.41692669,-3.464248277,10000,-65.48914431,188.9704509,0,14.03629709,0,109.1170181 +47.34,50.41692081,-3.464221731,10000,-65.5309236,188.9617986,0,14.03629709,0,109.1240441 +47.35,50.41691492,-3.464195187,10000,-65.55877644,188.9538137,0,14.03629709,0,109.13107 +47.36,50.41690904,-3.464168643,10000,-65.56922122,188.9464961,0,14.03629709,0,109.1380959 +47.37,50.41690315,-3.464142101,10000,-65.58662923,188.9389561,0,14.03629709,0,109.1451218 +47.38,50.41689727,-3.464115559,10000,-65.61796368,188.9303039,0,14.03629709,0,109.1521478 +47.39,50.41689137,-3.464089019,10000,-65.64233491,188.9214292,0,14.03629709,0,109.1591737 +47.4,50.41688548,-3.464062481,10000,-65.65626129,188.9136667,0,14.03629709,0,109.1661996 +47.41,50.41687959,-3.464035942,10000,-65.68063251,188.9061268,0,14.03629709,0,109.1732255 +47.42,50.41687369,-3.464009406,10000,-65.71196697,188.8979194,0,14.03629709,0,109.1802515 +47.43,50.41686779,-3.46398287,10000,-65.73285658,188.8899346,0,14.03629709,0,109.1872773 +47.44,50.41686189,-3.463956336,10000,-65.75026457,188.8823946,0,14.03629709,0,109.1943033 +47.45,50.41685599,-3.463929802,10000,-65.77115419,188.8744098,0,14.03629709,0,109.2013292 +47.46,50.41685008,-3.46390327,10000,-65.7885622,188.86598,0,14.03629709,0,109.2083551 +47.47,50.41684418,-3.463876739,10000,-65.80945181,188.8577727,0,14.03629709,0,109.215381 +47.48,50.41683827,-3.463850209,10000,-65.84426787,188.8495654,0,14.03629709,0,109.222407 +47.49,50.41683236,-3.46382368,10000,-65.87908392,188.8411357,0,14.03629709,0,109.2294329 +47.5,50.41682644,-3.463797153,10000,-65.89997353,188.8329284,0,14.03629709,0,109.2364588 +47.51,50.41682053,-3.463770626,10000,-65.91738153,188.8247211,0,14.03629709,0,109.2434847 +47.52,50.41681461,-3.463744101,10000,-65.94175276,188.8162914,0,14.03629709,0,109.2505106 +47.53,50.41680869,-3.463717577,10000,-65.96960561,188.8083066,0,14.03629709,0,109.2575366 +47.54,50.41680277,-3.463691054,10000,-65.99397683,188.8009892,0,14.03629709,0,109.2645625 +47.55,50.41679684,-3.463664532,10000,-66.01138483,188.7936717,0,14.03629709,0,109.2715884 +47.56,50.41679092,-3.463638011,10000,-66.02879282,188.7856869,0,14.03629709,0,109.2786143 +47.57,50.41678499,-3.463611491,10000,-66.05316404,188.7772573,0,14.03629709,0,109.2856403 +47.58,50.41677906,-3.463584973,10000,-66.08101687,188.76905,0,14.03629709,0,109.2926662 +47.59,50.41677313,-3.463558455,10000,-66.1053881,188.7608428,0,14.03629709,0,109.2996921 +47.6,50.41676719,-3.463531939,10000,-66.12279611,188.7524131,0,14.03629709,0,109.306718 +47.61,50.41676126,-3.463505424,10000,-66.14020412,188.7442059,0,14.03629709,0,109.313744 +47.62,50.41675532,-3.46347891,10000,-66.16457534,188.7359987,0,14.03629709,0,109.3207699 +47.63,50.41674938,-3.463452397,10000,-66.19242817,188.7275691,0,14.03629709,0,109.3277958 +47.64,50.41674344,-3.463425886,10000,-66.21679938,188.7193619,0,14.03629709,0,109.3348217 +47.65,50.41673749,-3.463399375,10000,-66.23420737,188.7113772,0,14.03629709,0,109.3418477 +47.66,50.41673155,-3.463372866,10000,-66.255097,188.7036149,0,14.03629709,0,109.3488736 +47.67,50.4167256,-3.463346358,10000,-66.28991307,188.6958526,0,14.03629709,0,109.3558995 +47.68,50.41671965,-3.46331985,10000,-66.32472913,188.687423,0,14.03629709,0,109.3629254 +47.69,50.41671369,-3.463293345,10000,-66.34561873,188.6789934,0,14.03629709,0,109.3699514 +47.7,50.41670774,-3.46326684,10000,-66.36302673,188.6712311,0,14.03629709,0,109.3769773 +47.71,50.41670178,-3.463240336,10000,-66.38391634,188.6634689,0,14.03629709,0,109.3840032 +47.72,50.41669582,-3.463213834,10000,-66.40132433,188.6554842,0,14.03629709,0,109.3910291 +47.73,50.41668986,-3.463187332,10000,-66.42221394,188.6472771,0,14.03629709,0,109.3980551 +47.74,50.4166839,-3.463160832,10000,-66.45354839,188.6388475,0,14.03629709,0,109.405081 +47.75,50.41667793,-3.463134333,10000,-66.47791962,188.6306404,0,14.03629709,0,109.4121069 +47.76,50.41667196,-3.463107835,10000,-66.49184599,188.6224333,0,14.03629709,0,109.4191328 +47.77,50.416666,-3.463081338,10000,-66.51621722,188.6140037,0,14.03629709,0,109.4261588 +47.78,50.41666002,-3.463054843,10000,-66.54755168,188.6057966,0,14.03629709,0,109.4331846 +47.79,50.41665405,-3.463028348,10000,-66.56495968,188.5975895,0,14.03629709,0,109.4402106 +47.8,50.41664807,-3.463001855,10000,-66.57540445,188.58916,0,14.03629709,0,109.4472365 +47.81,50.4166421,-3.462975363,10000,-66.60325728,188.5811753,0,14.03629709,0,109.4542624 +47.82,50.41663612,-3.462948872,10000,-66.64503657,188.5736356,0,14.03629709,0,109.4612883 +47.83,50.41663013,-3.462922382,10000,-66.6728894,188.565651,0,14.03629709,0,109.4683143 +47.84,50.41662415,-3.462895893,10000,-66.67985255,188.5572215,0,14.03629709,0,109.4753402 +47.85,50.41661816,-3.462869406,10000,-66.6868157,188.5490144,0,14.03629709,0,109.4823661 +47.86,50.41661218,-3.462842919,10000,-66.71466855,188.5408074,0,14.03629709,0,109.489392 +47.87,50.41660619,-3.462816434,10000,-66.75644785,188.5323779,0,14.03629709,0,109.496418 +47.88,50.41660019,-3.46278995,10000,-66.78430068,188.5241708,0,14.03629709,0,109.5034439 +47.89,50.4165942,-3.462763467,10000,-66.79474543,188.5159638,0,14.03629709,0,109.5104698 +47.9,50.4165882,-3.462736985,10000,-66.81215342,188.5075343,0,14.03629709,0,109.5174957 +47.91,50.41658221,-3.462710505,10000,-66.84348787,188.4993273,0,14.03629709,0,109.5245217 +47.92,50.4165762,-3.462684025,10000,-66.8678591,188.4911203,0,14.03629709,0,109.5315476 +47.93,50.4165702,-3.462657547,10000,-66.8817855,188.4826908,0,14.03629709,0,109.5385735 +47.94,50.4165642,-3.46263107,10000,-66.90615673,188.4747062,0,14.03629709,0,109.5455994 +47.95,50.41655819,-3.462604594,10000,-66.93749118,188.4671666,0,14.03629709,0,109.5526253 +47.96,50.41655218,-3.462578119,10000,-66.95838078,188.4591821,0,14.03629709,0,109.5596513 +47.97,50.41654617,-3.462551645,10000,-66.97927037,188.4507526,0,14.03629709,0,109.5666772 +47.98,50.41654016,-3.462525173,10000,-67.0106048,188.4425456,0,14.03629709,0,109.5737031 +47.99,50.41653414,-3.462498701,10000,-67.03497602,188.4343387,0,14.03629709,0,109.580729 +48,50.41652812,-3.462472231,10000,-67.04890242,188.4259092,0,14.03629709,0,109.587755 +48.01,50.41652211,-3.462445762,10000,-67.06979204,188.4177023,0,14.03629709,0,109.5947809 +48.02,50.41651608,-3.462419294,10000,-67.09068165,188.4094953,0,14.03629709,0,109.6018068 +48.03,50.41651006,-3.462392827,10000,-67.10460803,188.4010659,0,14.03629709,0,109.6088327 +48.04,50.41650404,-3.462366362,10000,-67.12897924,188.392859,0,14.03629709,0,109.6158587 +48.05,50.41649801,-3.462339897,10000,-67.1637953,188.384652,0,14.03629709,0,109.6228846 +48.06,50.41649198,-3.462313434,10000,-67.19512975,188.3762226,0,14.03629709,0,109.6299105 +48.07,50.41648595,-3.462286972,10000,-67.21950098,188.3680157,0,14.03629709,0,109.6369364 +48.08,50.41647991,-3.462260511,10000,-67.23690898,188.3598088,0,14.03629709,0,109.6439624 +48.09,50.41647388,-3.462234051,10000,-67.25431696,188.3513794,0,14.03629709,0,109.6509882 +48.1,50.41646784,-3.462207593,10000,-67.27868818,188.3431725,0,14.03629709,0,109.6580142 +48.11,50.4164618,-3.462181135,10000,-67.30654102,188.3349656,0,14.03629709,0,109.6650401 +48.12,50.41645576,-3.462154679,10000,-67.33091224,188.3265363,0,14.03629709,0,109.672066 +48.13,50.41644971,-3.462128224,10000,-67.34832023,188.3185518,0,14.03629709,0,109.6790919 +48.14,50.41644367,-3.46210177,10000,-67.36572823,188.3110123,0,14.03629709,0,109.6861179 +48.15,50.41643762,-3.462075317,10000,-67.39009945,188.3028054,0,14.03629709,0,109.6931438 +48.16,50.41643157,-3.462048865,10000,-67.4214339,188.2937088,0,14.03629709,0,109.7001697 +48.17,50.41642552,-3.462022415,10000,-67.45624994,188.2852794,0,14.03629709,0,109.7071956 +48.18,50.41641946,-3.461995966,10000,-67.47713953,188.2779624,0,14.03629709,0,109.7142216 +48.19,50.4164134,-3.461969517,10000,-67.48062109,188.2697556,0,14.03629709,0,109.7212475 +48.2,50.41640735,-3.46194307,10000,-67.4980291,188.260214,0,14.03629709,0,109.7282734 +48.21,50.41640129,-3.461916625,10000,-67.53632678,188.2513398,0,14.03629709,0,109.7352993 +48.22,50.41639522,-3.46189018,10000,-67.56766122,188.2438003,0,14.03629709,0,109.7423253 +48.23,50.41638916,-3.461863737,10000,-67.58855081,188.2364833,0,14.03629709,0,109.7493512 +48.24,50.41638309,-3.461837294,10000,-67.60944041,188.2284989,0,14.03629709,0,109.7563771 +48.25,50.41637702,-3.461810853,10000,-67.62684841,188.2200697,0,14.03629709,0,109.763403 +48.26,50.41637095,-3.461784413,10000,-67.64773802,188.2118629,0,14.03629709,0,109.770429 +48.27,50.41636488,-3.461757974,10000,-67.68255409,188.2034336,0,14.03629709,0,109.7774549 +48.28,50.4163588,-3.461731536,10000,-67.71737014,188.194337,0,14.03629709,0,109.7844808 +48.29,50.41635272,-3.4617051,10000,-67.73477812,188.1856853,0,14.03629709,0,109.7915067 +48.3,50.41634664,-3.461678665,10000,-67.74174127,188.177701,0,14.03629709,0,109.7985327 +48.31,50.41634056,-3.46165223,10000,-67.75566766,188.1692717,0,14.03629709,0,109.8055586 +48.32,50.41633448,-3.461625798,10000,-67.77655728,188.1608425,0,14.03629709,0,109.8125845 +48.33,50.41632839,-3.461599366,10000,-67.79396528,188.1528582,0,14.03629709,0,109.8196104 +48.34,50.41632231,-3.461572935,10000,-67.81485488,188.1442065,0,14.03629709,0,109.8266363 +48.35,50.41631622,-3.461546506,10000,-67.84967092,188.1351099,0,14.03629709,0,109.8336623 +48.36,50.41631013,-3.461520078,10000,-67.88448698,188.1269032,0,14.03629709,0,109.8406882 +48.37,50.41630403,-3.461493651,10000,-67.90537659,188.1195862,0,14.03629709,0,109.8477141 +48.38,50.41629794,-3.461467225,10000,-67.92278458,188.1122693,0,14.03629709,0,109.85474 +48.39,50.41629184,-3.4614408,10000,-67.9471558,188.1040626,0,14.03629709,0,109.861766 +48.4,50.41628574,-3.461414376,10000,-67.97849025,188.0947436,0,14.03629709,0,109.8687919 +48.41,50.41627964,-3.461387954,10000,-68.01330631,188.0854246,0,14.03629709,0,109.8758178 +48.42,50.41627353,-3.461361533,10000,-68.03419591,188.0772179,0,14.03629709,0,109.8828437 +48.43,50.41626742,-3.461335113,10000,-68.03767744,188.069901,0,14.03629709,0,109.8898697 +48.44,50.41626132,-3.461308694,10000,-68.05508543,188.0625841,0,14.03629709,0,109.8968955 +48.45,50.41625521,-3.461282276,10000,-68.09338311,188.0543774,0,14.03629709,0,109.9039215 +48.46,50.41624909,-3.461255859,10000,-68.12471756,188.0450585,0,14.03629709,0,109.9109474 +48.47,50.41624298,-3.461229444,10000,-68.14560716,188.0357395,0,14.03629709,0,109.9179733 +48.48,50.41623686,-3.46120303,10000,-68.16649675,188.0275328,0,14.03629709,0,109.9249992 +48.49,50.41623074,-3.461176617,10000,-68.18042313,188.0199935,0,14.03629709,0,109.9320252 +48.5,50.41622462,-3.461150205,10000,-68.1873863,188.0117869,0,14.03629709,0,109.9390511 +48.51,50.4162185,-3.461123794,10000,-68.20479429,188.0024679,0,14.03629709,0,109.946077 +48.52,50.41621238,-3.461097385,10000,-68.23961034,187.993149,0,14.03629709,0,109.9531029 +48.53,50.41620625,-3.461070977,10000,-68.27790801,187.9849423,0,14.03629709,0,109.9601289 +48.54,50.41620012,-3.46104457,10000,-68.30924246,187.9776255,0,14.03629709,0,109.9671548 +48.55,50.41619399,-3.461018164,10000,-68.33361367,187.9703087,0,14.03629709,0,109.9741807 +48.56,50.41618785,-3.460991759,10000,-68.35102166,187.9621021,0,14.03629709,0,109.9812066 +48.57,50.41618172,-3.460965355,10000,-68.36842965,187.9527832,0,14.03629709,0,109.9882326 +48.58,50.41617558,-3.460938953,10000,-68.38931926,187.9434643,0,14.03629709,0,109.9952585 +48.59,50.41616944,-3.460912552,10000,-68.40672725,187.9352577,0,14.03629709,0,110.0022844 +48.6,50.4161633,-3.460886152,10000,-68.42761685,187.9277185,0,14.03629709,0,110.0093103 +48.61,50.41615716,-3.460859753,10000,-68.45895128,187.9197343,0,14.03629709,0,110.0163363 +48.62,50.41615101,-3.460833355,10000,-68.4833225,187.9110828,0,14.03629709,0,110.0233622 +48.63,50.41614486,-3.460806959,10000,-68.49724889,187.9019864,0,14.03629709,0,110.0303881 +48.64,50.41613872,-3.460780563,10000,-68.52162012,187.8926675,0,14.03629709,0,110.037414 +48.65,50.41613256,-3.46075417,10000,-68.55295456,187.8842385,0,14.03629709,0,110.04444 +48.66,50.41612641,-3.460727777,10000,-68.57036254,187.8771442,0,14.03629709,0,110.0514659 +48.67,50.41612025,-3.460701385,10000,-68.58080729,187.869605,0,14.03629709,0,110.0584918 +48.68,50.4161141,-3.460674994,10000,-68.60866012,187.8605086,0,14.03629709,0,110.0655177 +48.69,50.41610794,-3.460648605,10000,-68.65043942,187.8511898,0,14.03629709,0,110.0725437 +48.7,50.41610177,-3.460622217,10000,-68.68177386,187.8429833,0,14.03629709,0,110.0795696 +48.71,50.41609561,-3.46059583,10000,-68.70266346,187.8354441,0,14.03629709,0,110.0865955 +48.72,50.41608944,-3.460569444,10000,-68.72355305,187.8272376,0,14.03629709,0,110.0936214 +48.73,50.41608327,-3.460543059,10000,-68.73747944,187.8179188,0,14.03629709,0,110.1006473 +48.74,50.4160771,-3.460516676,10000,-68.7444426,187.8086,0,14.03629709,0,110.1076733 +48.75,50.41607093,-3.460490294,10000,-68.76185059,187.8003935,0,14.03629709,0,110.1146991 +48.76,50.41606476,-3.460463913,10000,-68.79666663,187.7928543,0,14.03629709,0,110.1217251 +48.77,50.41605858,-3.460437533,10000,-68.83148269,187.7848703,0,14.03629709,0,110.128751 +48.78,50.4160524,-3.460411154,10000,-68.85237229,187.7764413,0,14.03629709,0,110.1357769 +48.79,50.41604622,-3.460384777,10000,-68.86978027,187.7682348,0,14.03629709,0,110.1428028 +48.8,50.41604004,-3.4603584,10000,-68.89066988,187.7598059,0,14.03629709,0,110.1498288 +48.81,50.41603385,-3.460332025,10000,-68.90807788,187.7504871,0,14.03629709,0,110.1568547 +48.82,50.41602767,-3.460305651,10000,-68.92896748,187.7411684,0,14.03629709,0,110.1638806 +48.83,50.41602148,-3.460279279,10000,-68.96378352,187.7329619,0,14.03629709,0,110.1709065 +48.84,50.41601529,-3.460252907,10000,-68.99859956,187.7256453,0,14.03629709,0,110.1779325 +48.85,50.41600909,-3.460226537,10000,-69.01948917,187.7181062,0,14.03629709,0,110.1849584 +48.86,50.4160029,-3.460200167,10000,-69.03689718,187.7092324,0,14.03629709,0,110.1919843 +48.87,50.4159967,-3.460173799,10000,-69.0577868,187.6994687,0,14.03629709,0,110.1990102 +48.88,50.4159905,-3.460147433,10000,-69.07519478,187.6903725,0,14.03629709,0,110.2060362 +48.89,50.4159843,-3.460121067,10000,-69.09608436,187.6819436,0,14.03629709,0,110.2130621 +48.9,50.4159781,-3.460094703,10000,-69.1309004,187.6735147,0,14.03629709,0,110.220088 +48.91,50.41597189,-3.46006834,10000,-69.16571646,187.6655307,0,14.03629709,0,110.2271139 +48.92,50.41596568,-3.460041978,10000,-69.18312445,187.6579917,0,14.03629709,0,110.2341399 +48.93,50.41595947,-3.460015617,10000,-69.1900876,187.6497853,0,14.03629709,0,110.2411658 +48.94,50.41595326,-3.459989257,10000,-69.2074956,187.6406891,0,14.03629709,0,110.2481917 +48.95,50.41594705,-3.459962899,10000,-69.24231167,187.6320378,0,14.03629709,0,110.2552176 +48.96,50.41594083,-3.459936542,10000,-69.27712772,187.6240538,0,14.03629709,0,110.2622436 +48.97,50.41593461,-3.459910185,10000,-69.2945357,187.6154025,0,14.03629709,0,110.2692695 +48.98,50.41592839,-3.459883831,10000,-69.30149884,187.6060839,0,14.03629709,0,110.2762954 +48.99,50.41592217,-3.459857477,10000,-69.31890682,187.5969877,0,14.03629709,0,110.2833213 +49,50.41591595,-3.459831125,10000,-69.35372288,187.5883364,0,14.03629709,0,110.2903473 +49.01,50.41590972,-3.459804774,10000,-69.38853894,187.5803525,0,14.03629709,0,110.2973732 +49.02,50.41590349,-3.459778424,10000,-69.40594693,187.5728135,0,14.03629709,0,110.3043991 +49.03,50.41589726,-3.459752075,10000,-69.41291007,187.5648296,0,14.03629709,0,110.311425 +49.04,50.41589103,-3.459725727,10000,-69.43031806,187.5564008,0,14.03629709,0,110.318451 +49.05,50.4158848,-3.459699381,10000,-69.46513411,187.5481945,0,14.03629709,0,110.3254769 +49.06,50.41587856,-3.459673035,10000,-69.49995015,187.5397657,0,14.03629709,0,110.3325028 +49.07,50.41587232,-3.459646691,10000,-69.52083975,187.5302246,0,14.03629709,0,110.3395287 +49.08,50.41586608,-3.459620348,10000,-69.53824773,187.5202386,0,14.03629709,0,110.3465547 +49.09,50.41585984,-3.459594007,10000,-69.55913735,187.511365,0,14.03629709,0,110.3535806 +49.1,50.41585359,-3.459567667,10000,-69.57654535,187.5036036,0,14.03629709,0,110.3606065 +49.11,50.41584735,-3.459541327,10000,-69.59743494,187.4958422,0,14.03629709,0,110.3676324 +49.12,50.4158411,-3.45951499,10000,-69.632251,187.4876359,0,14.03629709,0,110.3746584 +49.13,50.41583485,-3.459488652,10000,-69.66706706,187.4785398,0,14.03629709,0,110.3816842 +49.14,50.41582859,-3.459462317,10000,-69.68795666,187.4687763,0,14.03629709,0,110.3887101 +49.15,50.41582234,-3.459435983,10000,-69.70536464,187.4599026,0,14.03629709,0,110.3957361 +49.16,50.41581608,-3.45940965,10000,-69.72625422,187.4523638,0,14.03629709,0,110.402762 +49.17,50.41580982,-3.459383318,10000,-69.7436622,187.4452698,0,14.03629709,0,110.4097879 +49.18,50.41580356,-3.459356987,10000,-69.7645518,187.4377309,0,14.03629709,0,110.4168138 +49.19,50.4157973,-3.459330657,10000,-69.79936786,187.4288573,0,14.03629709,0,110.4238398 +49.2,50.41579103,-3.459304328,10000,-69.83418392,187.4190938,0,14.03629709,0,110.4308657 +49.21,50.41578476,-3.459278002,10000,-69.85159191,187.4099978,0,14.03629709,0,110.4378916 +49.22,50.41577849,-3.459251675,10000,-69.85855505,187.4015691,0,14.03629709,0,110.4449175 +49.23,50.41577222,-3.459225351,10000,-69.87248142,187.3929179,0,14.03629709,0,110.4519435 +49.24,50.41576595,-3.459199027,10000,-69.89337103,187.3840443,0,14.03629709,0,110.4589694 +49.25,50.41575967,-3.459172705,10000,-69.91426064,187.3753932,0,14.03629709,0,110.4659953 +49.26,50.4157534,-3.459146384,10000,-69.94559507,187.367187,0,14.03629709,0,110.4730212 +49.27,50.41574712,-3.459120064,10000,-69.98737433,187.3589808,0,14.03629709,0,110.4800472 +49.28,50.41574083,-3.459093745,10000,-70.01522715,187.3505521,0,14.03629709,0,110.4870731 +49.29,50.41573455,-3.459067428,10000,-70.0221903,187.3421235,0,14.03629709,0,110.494099 +49.3,50.41572826,-3.459041111,10000,-70.02915345,187.3330274,0,14.03629709,0,110.5011249 +49.31,50.41572198,-3.459014796,10000,-70.05700628,187.3234865,0,14.03629709,0,110.5081509 +49.32,50.41571569,-3.458988483,10000,-70.09878555,187.3152803,0,14.03629709,0,110.5151768 +49.33,50.41570939,-3.45896217,10000,-70.13011999,187.307964,0,14.03629709,0,110.5222027 +49.34,50.4157031,-3.458935858,10000,-70.1510096,187.2995354,0,14.03629709,0,110.5292286 +49.35,50.4156968,-3.458909548,10000,-70.1718992,187.2902169,0,14.03629709,0,110.5362546 +49.36,50.4156905,-3.458883239,10000,-70.18582556,187.281121,0,14.03629709,0,110.5432805 +49.37,50.4156842,-3.458856931,10000,-70.1927887,187.2724699,0,14.03629709,0,110.5503064 +49.38,50.4156779,-3.458830625,10000,-70.21019669,187.2642638,0,14.03629709,0,110.5573323 +49.39,50.4156716,-3.458804319,10000,-70.24501274,187.2560576,0,14.03629709,0,110.5643583 +49.4,50.41566529,-3.458778015,10000,-70.27982879,187.2474066,0,14.03629709,0,110.5713842 +49.41,50.41565898,-3.458751712,10000,-70.30071839,187.2385331,0,14.03629709,0,110.5784101 +49.42,50.41565267,-3.45872541,10000,-70.31812639,187.229882,0,14.03629709,0,110.585436 +49.43,50.41564636,-3.45869911,10000,-70.33901598,187.2214535,0,14.03629709,0,110.592462 +49.44,50.41564004,-3.45867281,10000,-70.35642396,187.2123575,0,14.03629709,0,110.5994878 +49.45,50.41563373,-3.458646512,10000,-70.37731355,187.2028167,0,14.03629709,0,110.6065138 +49.46,50.41562741,-3.458620216,10000,-70.41212961,187.1946106,0,14.03629709,0,110.6135397 +49.47,50.41562109,-3.45859392,10000,-70.44694566,187.1872943,0,14.03629709,0,110.6205656 +49.48,50.41561476,-3.458567625,10000,-70.46783525,187.1788658,0,14.03629709,0,110.6275915 +49.49,50.41560844,-3.458541332,10000,-70.48524323,187.1695474,0,14.03629709,0,110.6346175 +49.5,50.41560211,-3.45851504,10000,-70.50613284,187.1604515,0,14.03629709,0,110.6416434 +49.51,50.41559578,-3.458488749,10000,-70.52354082,187.1518005,0,14.03629709,0,110.6486693 +49.52,50.41558945,-3.45846246,10000,-70.54443041,187.1435945,0,14.03629709,0,110.6556952 +49.53,50.41558312,-3.458436171,10000,-70.57924645,187.1353884,0,14.03629709,0,110.6627211 +49.54,50.41557678,-3.458409884,10000,-70.61406251,187.1267375,0,14.03629709,0,110.6697471 +49.55,50.41557044,-3.458383598,10000,-70.63147051,187.1176416,0,14.03629709,0,110.676773 +49.56,50.4155641,-3.458357313,10000,-70.63843366,187.1083233,0,14.03629709,0,110.6837989 +49.57,50.41555776,-3.45833103,10000,-70.65236002,187.0996723,0,14.03629709,0,110.6908248 +49.58,50.41555142,-3.458304748,10000,-70.6732496,187.0916888,0,14.03629709,0,110.6978508 +49.59,50.41554507,-3.458278466,10000,-70.69413919,187.0830378,0,14.03629709,0,110.7048767 +49.6,50.41553873,-3.458252187,10000,-70.72547363,187.0737195,0,14.03629709,0,110.7119026 +49.61,50.41553238,-3.458225908,10000,-70.76725292,187.0646237,0,14.03629709,0,110.7189285 +49.62,50.41552602,-3.458199631,10000,-70.79858735,187.0559727,0,14.03629709,0,110.7259545 +49.63,50.41551967,-3.458173355,10000,-70.81947694,187.0477668,0,14.03629709,0,110.7329804 +49.64,50.41551331,-3.45814708,10000,-70.84036654,187.0393383,0,14.03629709,0,110.7400063 +49.65,50.41550695,-3.458120806,10000,-70.85429291,187.0302425,0,14.03629709,0,110.7470322 +49.66,50.41550059,-3.458094534,10000,-70.86125606,187.0218141,0,14.03629709,0,110.7540582 +49.67,50.41549423,-3.458068263,10000,-70.87866405,187.0144979,0,14.03629709,0,110.7610841 +49.68,50.41548787,-3.458041992,10000,-70.91348009,187.0060695,0,14.03629709,0,110.76811 +49.69,50.4154815,-3.458015723,10000,-70.94829614,186.995639,0,14.03629709,0,110.7751359 +49.7,50.41547513,-3.457989456,10000,-70.96570411,186.9854309,0,14.03629709,0,110.7821619 +49.71,50.41546876,-3.45796319,10000,-70.97266726,186.9770025,0,14.03629709,0,110.7891878 +49.72,50.41546239,-3.457936925,10000,-70.99007525,186.9694639,0,14.03629709,0,110.7962137 +49.73,50.41545602,-3.457910661,10000,-71.02489129,186.9614804,0,14.03629709,0,110.8032396 +49.74,50.41544964,-3.457884398,10000,-71.05970733,186.953052,0,14.03629709,0,110.8102656 +49.75,50.41544326,-3.457858137,10000,-71.08059694,186.9448461,0,14.03629709,0,110.8172915 +49.76,50.41543688,-3.457831876,10000,-71.10148654,186.9364177,0,14.03629709,0,110.8243174 +49.77,50.4154305,-3.457805617,10000,-71.13282097,186.9270995,0,14.03629709,0,110.8313433 +49.78,50.41542411,-3.457779359,10000,-71.15719217,186.9177813,0,14.03629709,0,110.8383693 +49.79,50.41541772,-3.457753103,10000,-71.17111854,186.9091305,0,14.03629709,0,110.8453951 +49.8,50.41541134,-3.457726847,10000,-71.19200814,186.9000348,0,14.03629709,0,110.8524211 +49.81,50.41540494,-3.457700593,10000,-71.21289772,186.8904941,0,14.03629709,0,110.859447 +49.82,50.41539855,-3.457674341,10000,-71.22682409,186.8820658,0,14.03629709,0,110.8664729 +49.83,50.41539216,-3.457648089,10000,-71.2511953,186.8738599,0,14.03629709,0,110.8734988 +49.84,50.41538576,-3.457621838,10000,-71.28601135,186.8643193,0,14.03629709,0,110.8805248 +49.85,50.41537936,-3.45759559,10000,-71.3173458,186.8550011,0,14.03629709,0,110.8875507 +49.86,50.41537296,-3.457569342,10000,-71.34171701,186.8470177,0,14.03629709,0,110.8945766 +49.87,50.41536655,-3.457543095,10000,-71.35912498,186.8392568,0,14.03629709,0,110.9016025 +49.88,50.41536015,-3.45751685,10000,-71.37653295,186.8310509,0,14.03629709,0,110.9086285 +49.89,50.41535374,-3.457490605,10000,-71.39742254,186.8219552,0,14.03629709,0,110.9156544 +49.9,50.41534733,-3.457464362,10000,-71.41483052,186.8121922,0,14.03629709,0,110.9226803 +49.91,50.41534092,-3.457438121,10000,-71.43572012,186.8030965,0,14.03629709,0,110.9297062 +49.92,50.41533451,-3.45741188,10000,-71.47053617,186.7946682,0,14.03629709,0,110.9367322 +49.93,50.41532809,-3.457385641,10000,-71.50535222,186.78624,0,14.03629709,0,110.9437581 +49.94,50.41532167,-3.457359403,10000,-71.5227602,186.7780341,0,14.03629709,0,110.950784 +49.95,50.41531525,-3.457333166,10000,-71.52972333,186.7696059,0,14.03629709,0,110.9578099 +49.96,50.41530883,-3.45730693,10000,-71.54713131,186.7602878,0,14.03629709,0,110.9648358 +49.97,50.41530241,-3.457280696,10000,-71.58194737,186.7509697,0,14.03629709,0,110.9718618 +49.98,50.41529598,-3.457254463,10000,-71.61676343,186.7425414,0,14.03629709,0,110.9788877 +49.99,50.41528955,-3.457228231,10000,-71.6341714,186.7343356,0,14.03629709,0,110.9859136 +50,50.41528312,-3.457202,10000,-71.64113453,186.7256849,0,14.03629709,0,110.9929395 +50.01,50.41527669,-3.457175771,10000,-71.6585425,186.7165893,0,14.03629709,0,110.9999655 +50.02,50.41527026,-3.457149542,10000,-71.69335855,186.7070488,0,14.03629709,0,111.0069914 +50.03,50.41526382,-3.457123316,10000,-71.7281746,186.6977307,0,14.03629709,0,111.0140173 +50.04,50.41525738,-3.45709709,10000,-71.74558259,186.6893025,0,14.03629709,0,111.0210432 +50.05,50.41525094,-3.457070866,10000,-71.75254573,186.6808743,0,14.03629709,0,111.0280692 +50.06,50.4152445,-3.457044642,10000,-71.76995371,186.6717787,0,14.03629709,0,111.0350951 +50.07,50.41523806,-3.457018421,10000,-71.80476976,186.663128,0,14.03629709,0,111.042121 +50.08,50.41523161,-3.4569922,10000,-71.83958581,186.6551448,0,14.03629709,0,111.0491469 +50.09,50.41522516,-3.45696598,10000,-71.8604754,186.6464941,0,14.03629709,0,111.0561729 +50.1,50.41521871,-3.456939762,10000,-71.87788337,186.6371761,0,14.03629709,0,111.0631988 +50.11,50.41521226,-3.456913545,10000,-71.89877295,186.6278581,0,14.03629709,0,111.0702247 +50.12,50.4152058,-3.456887329,10000,-71.91966254,186.6185401,0,14.03629709,0,111.0772506 +50.13,50.41519935,-3.456861115,10000,-71.95099697,186.6098894,0,14.03629709,0,111.0842766 +50.14,50.41519289,-3.456834902,10000,-71.98929463,186.6019062,0,14.03629709,0,111.0913024 +50.15,50.41518642,-3.456808689,10000,-72.00670261,186.5932556,0,14.03629709,0,111.0983284 +50.16,50.41517996,-3.456782479,10000,-72.01018415,186.5839376,0,14.03629709,0,111.1053543 +50.17,50.4151735,-3.456756269,10000,-72.03107376,186.5748421,0,14.03629709,0,111.1123802 +50.18,50.41516703,-3.456730061,10000,-72.06240818,186.5661915,0,14.03629709,0,111.1194061 +50.19,50.41516056,-3.456703854,10000,-72.08329775,186.5579858,0,14.03629709,0,111.1264321 +50.2,50.41515409,-3.456677648,10000,-72.10418734,186.5495577,0,14.03629709,0,111.133458 +50.21,50.41514762,-3.456651443,10000,-72.13900339,186.5402397,0,14.03629709,0,111.1404839 +50.22,50.41514114,-3.45662524,10000,-72.17381944,186.5309218,0,14.03629709,0,111.1475098 +50.23,50.41513466,-3.456599038,10000,-72.19122741,186.5224937,0,14.03629709,0,111.1545358 +50.24,50.41512818,-3.456572837,10000,-72.19819056,186.5140656,0,14.03629709,0,111.1615617 +50.25,50.4151217,-3.456546637,10000,-72.21211694,186.5047476,0,14.03629709,0,111.1685876 +50.26,50.41511522,-3.456520439,10000,-72.23300653,186.4952072,0,14.03629709,0,111.1756135 +50.27,50.41510873,-3.456494242,10000,-72.25389611,186.4858893,0,14.03629709,0,111.1826395 +50.28,50.41510225,-3.456468046,10000,-72.28523053,186.4765714,0,14.03629709,0,111.1896654 +50.29,50.41509576,-3.456441852,10000,-72.3270098,186.4681433,0,14.03629709,0,111.1966913 +50.3,50.41508926,-3.456415659,10000,-72.35486262,186.4608275,0,14.03629709,0,111.2037172 +50.31,50.41508277,-3.456389466,10000,-72.36182576,186.4523995,0,14.03629709,0,111.2107432 +50.32,50.41507627,-3.456363275,10000,-72.3687889,186.4419693,0,14.03629709,0,111.2177691 +50.33,50.41506978,-3.456337086,10000,-72.39664172,186.4317615,0,14.03629709,0,111.224795 +50.34,50.41506328,-3.456310898,10000,-72.43842099,186.4233335,0,14.03629709,0,111.2318209 +50.35,50.41505677,-3.456284711,10000,-72.4662738,186.4157953,0,14.03629709,0,111.2388468 +50.36,50.41505027,-3.456258525,10000,-72.47323694,186.4075897,0,14.03629709,0,111.2458728 +50.37,50.41504376,-3.45623234,10000,-72.48020009,186.3982719,0,14.03629709,0,111.2528987 +50.38,50.41503726,-3.456206157,10000,-72.50805291,186.388954,0,14.03629709,0,111.2599246 +50.39,50.41503075,-3.456179975,10000,-72.54983217,186.380526,0,14.03629709,0,111.2669505 +50.4,50.41502423,-3.456153794,10000,-72.58116658,186.372098,0,14.03629709,0,111.2739765 +50.41,50.41501772,-3.456127614,10000,-72.60205617,186.3627801,0,14.03629709,0,111.2810024 +50.42,50.4150112,-3.456101436,10000,-72.62294576,186.3532398,0,14.03629709,0,111.2880283 +50.43,50.41500468,-3.456075259,10000,-72.63687214,186.3441444,0,14.03629709,0,111.2950542 +50.44,50.41499816,-3.456049083,10000,-72.6438353,186.335494,0,14.03629709,0,111.3020802 +50.45,50.41499164,-3.456022909,10000,-72.66124329,186.327066,0,14.03629709,0,111.309106 +50.46,50.41498512,-3.455996735,10000,-72.69605931,186.3179706,0,14.03629709,0,111.316132 +50.47,50.41497859,-3.455970563,10000,-72.73087533,186.3082079,0,14.03629709,0,111.3231579 +50.48,50.41497206,-3.455944393,10000,-72.7517649,186.2991125,0,14.03629709,0,111.3301838 +50.49,50.41496553,-3.455918223,10000,-72.76917287,186.2906846,0,14.03629709,0,111.3372097 +50.5,50.414959,-3.455892055,10000,-72.79006248,186.2822566,0,14.03629709,0,111.3442357 +50.51,50.41495246,-3.455865888,10000,-72.80747048,186.2740511,0,14.03629709,0,111.3512616 +50.52,50.41494593,-3.455839722,10000,-72.82836007,186.2654007,0,14.03629709,0,111.3582875 +50.53,50.41493939,-3.455813557,10000,-72.86317612,186.2551931,0,14.03629709,0,111.3653134 +50.54,50.41493285,-3.455787394,10000,-72.89799216,186.244763,0,14.03629709,0,111.3723394 +50.55,50.4149263,-3.455761233,10000,-72.91888174,186.2363351,0,14.03629709,0,111.3793653 +50.56,50.41491976,-3.455735072,10000,-72.9362897,186.2290195,0,14.03629709,0,111.3863912 +50.57,50.41491321,-3.455708912,10000,-72.95717929,186.2205915,0,14.03629709,0,111.3934171 +50.58,50.41490666,-3.455682754,10000,-72.97458726,186.2112738,0,14.03629709,0,111.4004431 +50.59,50.41490011,-3.455656597,10000,-72.99199525,186.201956,0,14.03629709,0,111.407469 +50.6,50.41489356,-3.455630441,10000,-73.01288484,186.1924158,0,14.03629709,0,111.4144949 +50.61,50.414887,-3.455604287,10000,-73.03377444,186.1830981,0,14.03629709,0,111.4215208 +50.62,50.41488045,-3.455578134,10000,-73.06510886,186.1746702,0,14.03629709,0,111.4285468 +50.63,50.41487389,-3.455551982,10000,-73.1034065,186.1662423,0,14.03629709,0,111.4355727 +50.64,50.41486732,-3.455525831,10000,-73.12081448,186.1569246,0,14.03629709,0,111.4425986 +50.65,50.41486076,-3.455499682,10000,-73.12429601,186.1473844,0,14.03629709,0,111.4496245 +50.66,50.4148542,-3.455473534,10000,-73.14518561,186.1382891,0,14.03629709,0,111.4566505 +50.67,50.41484763,-3.455447387,10000,-73.18000165,186.1296388,0,14.03629709,0,111.4636764 +50.68,50.41484106,-3.455421242,10000,-73.21133606,186.1214334,0,14.03629709,0,111.4707023 +50.69,50.41483449,-3.455395097,10000,-73.23570725,186.1130056,0,14.03629709,0,111.4777282 +50.7,50.41482791,-3.455368954,10000,-73.25311522,186.1034654,0,14.03629709,0,111.4847542 +50.71,50.41482134,-3.455342812,10000,-73.27052321,186.0934804,0,14.03629709,0,111.4917801 +50.72,50.41481476,-3.455316672,10000,-73.29489442,186.0846076,0,14.03629709,0,111.498806 +50.73,50.41480818,-3.455290533,10000,-73.32274723,186.0766247,0,14.03629709,0,111.5058319 +50.74,50.4148016,-3.455264394,10000,-73.34711842,186.067752,0,14.03629709,0,111.5128578 +50.75,50.41479501,-3.455238258,10000,-73.3645264,186.0577669,0,14.03629709,0,111.5198838 +50.76,50.41478843,-3.455212122,10000,-73.38193438,186.0482268,0,14.03629709,0,111.5269097 +50.77,50.41478184,-3.455185989,10000,-73.40630558,186.0395765,0,14.03629709,0,111.5339356 +50.78,50.41477525,-3.455159855,10000,-73.43415839,186.0307038,0,14.03629709,0,111.5409615 +50.79,50.41476866,-3.455133724,10000,-73.45852959,186.0218311,0,14.03629709,0,111.5479875 +50.8,50.41476206,-3.455107594,10000,-73.47593758,186.0138482,0,14.03629709,0,111.5550133 +50.81,50.41475547,-3.455081464,10000,-73.49334556,186.0054204,0,14.03629709,0,111.5620393 +50.82,50.41474887,-3.455055336,10000,-73.51771675,185.9958803,0,14.03629709,0,111.5690652 +50.83,50.41474227,-3.45502921,10000,-73.54905116,185.9865627,0,14.03629709,0,111.5760911 +50.84,50.41473567,-3.455003084,10000,-73.58386719,185.9772451,0,14.03629709,0,111.583117 +50.85,50.41472906,-3.45497696,10000,-73.60823839,185.9674826,0,14.03629709,0,111.590143 +50.86,50.41472245,-3.454950838,10000,-73.62216476,185.958165,0,14.03629709,0,111.5971689 +50.87,50.41471585,-3.454924716,10000,-73.64305436,185.9488474,0,14.03629709,0,111.6041948 +50.88,50.41470923,-3.454898596,10000,-73.66394395,185.9393073,0,14.03629709,0,111.6112207 +50.89,50.41470262,-3.454872478,10000,-73.67787031,185.931102,0,14.03629709,0,111.6182467 +50.9,50.41469601,-3.45484636,10000,-73.7022415,185.9237866,0,14.03629709,0,111.6252726 +50.91,50.41468939,-3.454820243,10000,-73.73357592,185.9151364,0,14.03629709,0,111.6322985 +50.92,50.41468277,-3.454794128,10000,-73.75446551,185.9051515,0,14.03629709,0,111.6393244 +50.93,50.41467615,-3.454768014,10000,-73.77187348,185.895389,0,14.03629709,0,111.6463504 +50.94,50.41466953,-3.454741902,10000,-73.79276306,185.8860714,0,14.03629709,0,111.6533763 +50.95,50.4146629,-3.45471579,10000,-73.81017103,185.8767539,0,14.03629709,0,111.6604022 +50.96,50.41465628,-3.454689681,10000,-73.83106063,185.8681037,0,14.03629709,0,111.6674281 +50.97,50.41464965,-3.454663572,10000,-73.86587668,185.8601209,0,14.03629709,0,111.6744541 +50.98,50.41464302,-3.454637464,10000,-73.90069271,185.8514708,0,14.03629709,0,111.68148 +50.99,50.41463638,-3.454611358,10000,-73.92158229,185.8421533,0,14.03629709,0,111.6885059 +51,50.41462975,-3.454585253,10000,-73.93899026,185.8328357,0,14.03629709,0,111.6955318 +51.01,50.41462311,-3.454559149,10000,-73.95987985,185.8230733,0,14.03629709,0,111.7025578 +51.02,50.41461647,-3.454533047,10000,-73.97728782,185.8128659,0,14.03629709,0,111.7095837 +51.03,50.41460983,-3.454506946,10000,-73.99817741,185.8033259,0,14.03629709,0,111.7166096 +51.04,50.41460319,-3.454480847,10000,-74.03299345,185.7948983,0,14.03629709,0,111.7236355 +51.05,50.41459654,-3.454454748,10000,-74.06780948,185.7866931,0,14.03629709,0,111.7306615 +51.06,50.41458989,-3.454428651,10000,-74.08521744,185.7782655,0,14.03629709,0,111.7376874 +51.07,50.41458324,-3.454402555,10000,-74.09218057,185.7700603,0,14.03629709,0,111.7447133 +51.08,50.41457659,-3.45437646,10000,-74.10610693,185.7614102,0,14.03629709,0,111.7517392 +51.09,50.41456994,-3.454350366,10000,-74.12699653,185.7512029,0,14.03629709,0,111.7587652 +51.1,50.41456328,-3.454324274,10000,-74.14788613,185.7405506,0,14.03629709,0,111.7657911 +51.11,50.41455663,-3.454298184,10000,-74.17922055,185.7312331,0,14.03629709,0,111.772817 +51.12,50.41454997,-3.454272094,10000,-74.2175182,185.7228055,0,14.03629709,0,111.7798429 +51.13,50.4145433,-3.454246006,10000,-74.23492618,185.7141554,0,14.03629709,0,111.7868689 +51.14,50.41453664,-3.454219919,10000,-74.23840769,185.7052829,0,14.03629709,0,111.7938947 +51.15,50.41452998,-3.454193833,10000,-74.25929726,185.6964104,0,14.03629709,0,111.8009206 +51.16,50.41452331,-3.454167749,10000,-74.29411329,185.6873154,0,14.03629709,0,111.8079466 +51.17,50.41451664,-3.454141665,10000,-74.32544773,185.6777755,0,14.03629709,0,111.8149725 +51.18,50.41450997,-3.454115584,10000,-74.34981892,185.6682356,0,14.03629709,0,111.8219984 +51.19,50.41450329,-3.454089503,10000,-74.36722688,185.6591406,0,14.03629709,0,111.8290243 +51.2,50.41449662,-3.454063424,10000,-74.38811647,185.6502682,0,14.03629709,0,111.8360503 +51.21,50.41448994,-3.454037346,10000,-74.42293252,185.6411732,0,14.03629709,0,111.8430762 +51.22,50.41448326,-3.454011269,10000,-74.45774857,185.6316333,0,14.03629709,0,111.8501021 +51.23,50.41447657,-3.453985194,10000,-74.47515652,185.6223159,0,14.03629709,0,111.857128 +51.24,50.41446989,-3.45395912,10000,-74.47863803,185.6138884,0,14.03629709,0,111.864154 +51.25,50.4144632,-3.453933047,10000,-74.48560116,185.6054609,0,14.03629709,0,111.8711799 +51.26,50.41445652,-3.453906975,10000,-74.51345398,185.5961435,0,14.03629709,0,111.8782058 +51.27,50.41444983,-3.453880905,10000,-74.55523323,185.5866036,0,14.03629709,0,111.8852317 +51.28,50.41444313,-3.453854836,10000,-74.58656765,185.5772862,0,14.03629709,0,111.8922577 +51.29,50.41443644,-3.453828768,10000,-74.60745724,185.5677464,0,14.03629709,0,111.8992836 +51.3,50.41442974,-3.453802702,10000,-74.62834683,185.558429,0,14.03629709,0,111.9063095 +51.31,50.41442304,-3.453776637,10000,-74.64227319,185.5500015,0,14.03629709,0,111.9133354 +51.32,50.41441634,-3.453750573,10000,-74.64923633,185.541574,0,14.03629709,0,111.9203614 +51.33,50.41440964,-3.45372451,10000,-74.6666443,185.5322567,0,14.03629709,0,111.9273873 +51.34,50.41440294,-3.453698449,10000,-74.70146034,185.5227169,0,14.03629709,0,111.9344132 +51.35,50.41439623,-3.453672389,10000,-74.73627637,185.5133995,0,14.03629709,0,111.9414391 +51.36,50.41438952,-3.45364633,10000,-74.75716595,185.5038597,0,14.03629709,0,111.9484651 +51.37,50.41438281,-3.453620273,10000,-74.77457392,185.4943199,0,14.03629709,0,111.955491 +51.38,50.4143761,-3.453594217,10000,-74.79546349,185.4852251,0,14.03629709,0,111.9625169 +51.39,50.41436938,-3.453568162,10000,-74.81287145,185.4765752,0,14.03629709,0,111.9695428 +51.4,50.41436267,-3.453542109,10000,-74.83376104,185.4681477,0,14.03629709,0,111.9765688 +51.41,50.41435595,-3.453516056,10000,-74.86857709,185.4588304,0,14.03629709,0,111.9835947 +51.42,50.41434923,-3.453490005,10000,-74.90339313,185.4484008,0,14.03629709,0,111.9906206 +51.43,50.4143425,-3.453463956,10000,-74.9242827,185.438861,0,14.03629709,0,111.9976465 +51.44,50.41433578,-3.453437908,10000,-74.94169067,185.430656,0,14.03629709,0,112.0046725 +51.45,50.41432905,-3.45341186,10000,-74.96258025,185.4220061,0,14.03629709,0,112.0116984 +51.46,50.41432232,-3.453385815,10000,-74.97998822,185.4126889,0,14.03629709,0,112.0187243 +51.47,50.41431559,-3.45335977,10000,-75.0008778,185.4033716,0,14.03629709,0,112.0257502 +51.48,50.41430886,-3.453333727,10000,-75.03569383,185.3936094,0,14.03629709,0,112.0327762 +51.49,50.41430212,-3.453307685,10000,-75.07050985,185.3836247,0,14.03629709,0,112.039802 +51.5,50.41429538,-3.453281645,10000,-75.08791782,185.3747524,0,14.03629709,0,112.046828 +51.51,50.41428864,-3.453255606,10000,-75.09488096,185.3667699,0,14.03629709,0,112.0538539 +51.52,50.4142819,-3.453229567,10000,-75.10880733,185.3581201,0,14.03629709,0,112.0608798 +51.53,50.41427516,-3.453203531,10000,-75.12969691,185.3488028,0,14.03629709,0,112.0679057 +51.54,50.41426841,-3.453177495,10000,-75.14710489,185.3394856,0,14.03629709,0,112.0749316 +51.55,50.41426167,-3.453151461,10000,-75.16799447,185.3297234,0,14.03629709,0,112.0819576 +51.56,50.41425492,-3.453125428,10000,-75.20281049,185.3195163,0,14.03629709,0,112.0889835 +51.57,50.41424817,-3.453099397,10000,-75.23762651,185.3097542,0,14.03629709,0,112.0960094 +51.58,50.41424141,-3.453073367,10000,-75.2585161,185.3006594,0,14.03629709,0,112.1030353 +51.59,50.41423466,-3.453047338,10000,-75.27592408,185.2920096,0,14.03629709,0,112.1100613 +51.6,50.4142279,-3.453021311,10000,-75.30029527,185.2838047,0,14.03629709,0,112.1170872 +51.61,50.41422114,-3.452995284,10000,-75.32814808,185.2753774,0,14.03629709,0,112.1241131 +51.62,50.41421438,-3.452969259,10000,-75.35251926,185.2658377,0,14.03629709,0,112.131139 +51.63,50.41420761,-3.452943235,10000,-75.36992723,185.2556307,0,14.03629709,0,112.138165 +51.64,50.41420085,-3.452917213,10000,-75.38733519,185.2458686,0,14.03629709,0,112.1451909 +51.65,50.41419408,-3.452891192,10000,-75.41170639,185.2365514,0,14.03629709,0,112.1522168 +51.66,50.41418731,-3.452865172,10000,-75.43955921,185.2270117,0,14.03629709,0,112.1592427 +51.67,50.41418054,-3.452839154,10000,-75.46393041,185.2176946,0,14.03629709,0,112.1662687 +51.68,50.41417376,-3.452813137,10000,-75.48133836,185.2092673,0,14.03629709,0,112.1732946 +51.69,50.41416699,-3.452787121,10000,-75.49874632,185.20084,0,14.03629709,0,112.1803205 +51.7,50.41416021,-3.452761106,10000,-75.52311752,185.1913003,0,14.03629709,0,112.1873464 +51.71,50.41415343,-3.452735093,10000,-75.55097033,185.1810933,0,14.03629709,0,112.1943724 +51.72,50.41414665,-3.452709081,10000,-75.57534151,185.1715537,0,14.03629709,0,112.2013983 +51.73,50.41413986,-3.452683071,10000,-75.59274949,185.1631264,0,14.03629709,0,112.2084242 +51.74,50.41413308,-3.452657061,10000,-75.61015747,185.1546992,0,14.03629709,0,112.2154501 +51.75,50.41412629,-3.452631053,10000,-75.63452866,185.1451596,0,14.03629709,0,112.2224761 +51.76,50.4141195,-3.452605046,10000,-75.66586306,185.1349526,0,14.03629709,0,112.229502 +51.77,50.41411271,-3.452579041,10000,-75.70067907,185.1251905,0,14.03629709,0,112.2365279 +51.78,50.41410591,-3.452553037,10000,-75.72156866,185.1160959,0,14.03629709,0,112.2435538 +51.79,50.41409911,-3.452527034,10000,-75.7250502,185.1074462,0,14.03629709,0,112.2505798 +51.8,50.41409232,-3.452501033,10000,-75.74245818,185.099019,0,14.03629709,0,112.2576057 +51.81,50.41408552,-3.452475032,10000,-75.78075581,185.0897019,0,14.03629709,0,112.2646316 +51.82,50.41407871,-3.452449033,10000,-75.81209021,185.07905,0,14.03629709,0,112.2716575 +51.83,50.41407191,-3.452423036,10000,-75.83297978,185.068843,0,14.03629709,0,112.2786834 +51.84,50.4140651,-3.45239704,10000,-75.85386936,185.0601933,0,14.03629709,0,112.2857093 +51.85,50.41405829,-3.452371045,10000,-75.87127733,185.0517661,0,14.03629709,0,112.2927353 +51.86,50.41405148,-3.452345051,10000,-75.8886853,185.0424491,0,14.03629709,0,112.2997612 +51.87,50.41404467,-3.452319059,10000,-75.90957489,185.0329095,0,14.03629709,0,112.3067871 +51.88,50.41403785,-3.452293068,10000,-75.92698288,185.0235925,0,14.03629709,0,112.313813 +51.89,50.41403104,-3.452267078,10000,-75.94439084,185.0140529,0,14.03629709,0,112.320839 +51.9,50.41402422,-3.45224109,10000,-75.96876202,185.0045134,0,14.03629709,0,112.3278649 +51.91,50.4140174,-3.452215103,10000,-76.00009643,184.9951964,0,14.03629709,0,112.3348908 +51.92,50.41401058,-3.452189117,10000,-76.03839406,184.9856569,0,14.03629709,0,112.3419167 +51.93,50.41400375,-3.452163133,10000,-76.07321009,184.9763398,0,14.03629709,0,112.3489427 +51.94,50.41399692,-3.45213715,10000,-76.09061806,184.9679127,0,14.03629709,0,112.3559686 +51.95,50.41399009,-3.452111168,10000,-76.0975812,184.9594855,0,14.03629709,0,112.3629945 +51.96,50.41398326,-3.452085187,10000,-76.11150755,184.9501685,0,14.03629709,0,112.3700204 +51.97,50.41397643,-3.452059208,10000,-76.13239713,184.940629,0,14.03629709,0,112.3770463 +51.98,50.41396959,-3.45203323,10000,-76.1498051,184.931312,0,14.03629709,0,112.3840723 +51.99,50.41396276,-3.452007253,10000,-76.17069467,184.9217726,0,14.03629709,0,112.3910982 +52,50.41395592,-3.451981278,10000,-76.20551069,184.9122331,0,14.03629709,0,112.3981241 +52.01,50.41394908,-3.451955304,10000,-76.24032672,184.9026936,0,14.03629709,0,112.40515 +52.02,50.41394223,-3.451929331,10000,-76.26121631,184.8922643,0,14.03629709,0,112.412176 +52.03,50.41393539,-3.45190336,10000,-76.27862427,184.881835,0,14.03629709,0,112.4192019 +52.04,50.41392854,-3.451877391,10000,-76.29951383,184.8734079,0,14.03629709,0,112.4262278 +52.05,50.41392169,-3.451851422,10000,-76.31692181,184.8658707,0,14.03629709,0,112.4332537 +52.06,50.41391484,-3.451825454,10000,-76.33781139,184.8565537,0,14.03629709,0,112.4402797 +52.07,50.41390799,-3.451799488,10000,-76.37262742,184.8461244,0,14.03629709,0,112.4473056 +52.08,50.41390113,-3.451773524,10000,-76.40744344,184.8368074,0,14.03629709,0,112.4543315 +52.09,50.41389427,-3.45174756,10000,-76.42485141,184.8281579,0,14.03629709,0,112.4613574 +52.1,50.41388741,-3.451721598,10000,-76.43181454,184.8186185,0,14.03629709,0,112.4683834 +52.11,50.41388055,-3.451695637,10000,-76.44574088,184.8084117,0,14.03629709,0,112.4754093 +52.12,50.41387369,-3.451669678,10000,-76.46663045,184.7986498,0,14.03629709,0,112.4824352 +52.13,50.41386682,-3.45164372,10000,-76.48752003,184.7895553,0,14.03629709,0,112.4894611 +52.14,50.41385996,-3.451617763,10000,-76.51885446,184.7806833,0,14.03629709,0,112.4964871 +52.15,50.41385309,-3.451591808,10000,-76.56063372,184.7715889,0,14.03629709,0,112.5035129 +52.16,50.41384621,-3.451565853,10000,-76.58848651,184.7620495,0,14.03629709,0,112.5105389 +52.17,50.41383934,-3.451539901,10000,-76.59544963,184.7522877,0,14.03629709,0,112.5175648 +52.18,50.41383246,-3.451513949,10000,-76.59893115,184.7423034,0,14.03629709,0,112.5245907 +52.19,50.41382559,-3.451487999,10000,-76.61633913,184.7323191,0,14.03629709,0,112.5316166 +52.2,50.41381871,-3.451462051,10000,-76.65115516,184.7232246,0,14.03629709,0,112.5386426 +52.21,50.41381183,-3.451436103,10000,-76.68597117,184.7147976,0,14.03629709,0,112.5456685 +52.22,50.41380494,-3.451410157,10000,-76.70686074,184.7061481,0,14.03629709,0,112.5526944 +52.23,50.41379806,-3.451384212,10000,-76.72426871,184.6970537,0,14.03629709,0,112.5597203 +52.24,50.41379117,-3.451358268,10000,-76.7486399,184.6875144,0,14.03629709,0,112.5667463 +52.25,50.41378428,-3.451332326,10000,-76.77997431,184.6779751,0,14.03629709,0,112.5737722 +52.26,50.41377739,-3.451306385,10000,-76.81479034,184.6686582,0,14.03629709,0,112.5807981 +52.27,50.41377049,-3.451280445,10000,-76.83567991,184.6588964,0,14.03629709,0,112.587824 +52.28,50.41376359,-3.451254507,10000,-76.83916142,184.6486897,0,14.03629709,0,112.59485 +52.29,50.4137567,-3.45122857,10000,-76.85656939,184.6389279,0,14.03629709,0,112.6018759 +52.3,50.4137498,-3.451202635,10000,-76.89486703,184.6296111,0,14.03629709,0,112.6089018 +52.31,50.41374289,-3.4511767,10000,-76.92271982,184.6200718,0,14.03629709,0,112.6159277 +52.32,50.41373599,-3.451150768,10000,-76.93316456,184.6105325,0,14.03629709,0,112.6229537 +52.33,50.41372908,-3.451124836,10000,-76.95057254,184.6014381,0,14.03629709,0,112.6299796 +52.34,50.41372218,-3.451098906,10000,-76.98190695,184.5925662,0,14.03629709,0,112.6370055 +52.35,50.41371526,-3.451072977,10000,-77.00627813,184.5834719,0,14.03629709,0,112.6440314 +52.36,50.41370835,-3.451047049,10000,-77.02020447,184.5739326,0,14.03629709,0,112.6510573 +52.37,50.41370144,-3.451021123,10000,-77.04457565,184.5643933,0,14.03629709,0,112.6580833 +52.38,50.41369452,-3.450995198,10000,-77.07591007,184.5550765,0,14.03629709,0,112.6651092 +52.39,50.4136876,-3.450969274,10000,-77.09331804,184.5453148,0,14.03629709,0,112.6721351 +52.4,50.41368068,-3.450943352,10000,-77.10028118,184.5351081,0,14.03629709,0,112.679161 +52.41,50.41367376,-3.450917431,10000,-77.11768915,184.5255689,0,14.03629709,0,112.686187 +52.42,50.41366684,-3.450891512,10000,-77.15250516,184.5169195,0,14.03629709,0,112.6932129 +52.43,50.41365991,-3.450865593,10000,-77.18732117,184.5076027,0,14.03629709,0,112.7002388 +52.44,50.41365298,-3.450839676,10000,-77.20821075,184.4971736,0,14.03629709,0,112.7072647 +52.45,50.41364605,-3.450813761,10000,-77.22910033,184.4876344,0,14.03629709,0,112.7142907 +52.46,50.41363912,-3.450787847,10000,-77.26043473,184.4792075,0,14.03629709,0,112.7213166 +52.47,50.41363218,-3.450761933,10000,-77.28132431,184.4698907,0,14.03629709,0,112.7283425 +52.48,50.41362524,-3.450736022,10000,-77.28480584,184.4601291,0,14.03629709,0,112.7353684 +52.49,50.41361831,-3.450710112,10000,-77.3022138,184.4510348,0,14.03629709,0,112.7423944 +52.5,50.41361137,-3.450684202,10000,-77.34051142,184.4412731,0,14.03629709,0,112.7494202 +52.51,50.41360442,-3.450658295,10000,-77.37184582,184.430844,0,14.03629709,0,112.7564462 +52.52,50.41359748,-3.450632389,10000,-77.39273539,184.4215273,0,14.03629709,0,112.7634721 +52.53,50.41359053,-3.450606484,10000,-77.41362497,184.412878,0,14.03629709,0,112.770498 +52.54,50.41358358,-3.45058058,10000,-77.43103294,184.4035613,0,14.03629709,0,112.7775239 +52.55,50.41357663,-3.450554678,10000,-77.44844091,184.3940221,0,14.03629709,0,112.7845499 +52.56,50.41356968,-3.450528777,10000,-77.46933048,184.3844829,0,14.03629709,0,112.7915758 +52.57,50.41356272,-3.450502877,10000,-77.48673844,184.3740539,0,14.03629709,0,112.7986017 +52.58,50.41355577,-3.450476979,10000,-77.50762802,184.3634023,0,14.03629709,0,112.8056276 +52.59,50.41354881,-3.450451083,10000,-77.54244404,184.3540856,0,14.03629709,0,112.8126536 +52.6,50.41354185,-3.450425187,10000,-77.57726006,184.3456588,0,14.03629709,0,112.8196795 +52.61,50.41353488,-3.450399293,10000,-77.59814964,184.3370096,0,14.03629709,0,112.8267054 +52.62,50.41352792,-3.4503734,10000,-77.61555761,184.3279154,0,14.03629709,0,112.8337313 +52.63,50.41352095,-3.450347508,10000,-77.63644718,184.3181538,0,14.03629709,0,112.8407573 +52.64,50.41351398,-3.450321618,10000,-77.65385513,184.3079472,0,14.03629709,0,112.8477832 +52.65,50.41350701,-3.450295729,10000,-77.67474468,184.2981856,0,14.03629709,0,112.8548091 +52.66,50.41350004,-3.450269842,10000,-77.7095607,184.288869,0,14.03629709,0,112.861835 +52.67,50.41349306,-3.450243955,10000,-77.74437674,184.2793298,0,14.03629709,0,112.868861 +52.68,50.41348608,-3.450218071,10000,-77.7617847,184.2697907,0,14.03629709,0,112.8758869 +52.69,50.4134791,-3.450192187,10000,-77.76874782,184.2604741,0,14.03629709,0,112.8829128 +52.7,50.41347212,-3.450166305,10000,-77.78267418,184.2507125,0,14.03629709,0,112.8899387 +52.71,50.41346514,-3.450140424,10000,-77.80356377,184.240506,0,14.03629709,0,112.8969647 +52.72,50.41345815,-3.450114545,10000,-77.82445333,184.2309669,0,14.03629709,0,112.9039906 +52.73,50.41345117,-3.450088667,10000,-77.85578772,184.2223177,0,14.03629709,0,112.9110165 +52.74,50.41344418,-3.45006279,10000,-77.89408535,184.2130011,0,14.03629709,0,112.9180424 +52.75,50.41343718,-3.450036914,10000,-77.91149333,184.2025721,0,14.03629709,0,112.9250683 +52.76,50.41343019,-3.450011041,10000,-77.91497485,184.193033,0,14.03629709,0,112.9320943 +52.77,50.4134232,-3.449985168,10000,-77.93586441,184.1846063,0,14.03629709,0,112.9391202 +52.78,50.4134162,-3.449959296,10000,-77.97068042,184.1750672,0,14.03629709,0,112.9461461 +52.79,50.4134092,-3.449933426,10000,-78.00201482,184.1646383,0,14.03629709,0,112.953172 +52.8,50.4134022,-3.449907558,10000,-78.02638601,184.1550993,0,14.03629709,0,112.960198 +52.81,50.41339519,-3.44988169,10000,-78.04379399,184.1457827,0,14.03629709,0,112.9672238 +52.82,50.41338819,-3.449855824,10000,-78.06120195,184.1360212,0,14.03629709,0,112.9742498 +52.83,50.41338118,-3.44982996,10000,-78.08557313,184.1267046,0,14.03629709,0,112.9812757 +52.84,50.41337417,-3.449804096,10000,-78.11342591,184.117388,0,14.03629709,0,112.9883016 +52.85,50.41336716,-3.449778234,10000,-78.13779709,184.1074041,0,14.03629709,0,112.9953275 +52.86,50.41336014,-3.449752374,10000,-78.15520505,184.0974201,0,14.03629709,0,113.0023535 +52.87,50.41335313,-3.449726514,10000,-78.17261302,184.0876586,0,14.03629709,0,113.0093794 +52.88,50.41334611,-3.449700657,10000,-78.19698419,184.0781196,0,14.03629709,0,113.0164053 +52.89,50.41333909,-3.4496748,10000,-78.22483699,184.0688031,0,14.03629709,0,113.0234312 +52.9,50.41333207,-3.449648945,10000,-78.24920818,184.059264,0,14.03629709,0,113.0304572 +52.91,50.41332504,-3.449623091,10000,-78.26661614,184.049725,0,14.03629709,0,113.0374831 +52.92,50.41331802,-3.449597239,10000,-78.2840241,184.0404085,0,14.03629709,0,113.044509 +52.93,50.41331099,-3.449571387,10000,-78.30839527,184.0308695,0,14.03629709,0,113.0515349 +52.94,50.41330396,-3.449545538,10000,-78.33624807,184.0213305,0,14.03629709,0,113.0585609 +52.95,50.41329693,-3.449519689,10000,-78.36061925,184.012014,0,14.03629709,0,113.0655868 +52.96,50.41328989,-3.449493842,10000,-78.37802721,184.0022526,0,14.03629709,0,113.0726127 +52.97,50.41328286,-3.449467996,10000,-78.39543517,183.9920462,0,14.03629709,0,113.0796386 +52.98,50.41327582,-3.449442152,10000,-78.41980636,183.9822848,0,14.03629709,0,113.0866646 +52.99,50.41326878,-3.449416309,10000,-78.44765915,183.9729683,0,14.03629709,0,113.0936905 +53,50.41326174,-3.449390467,10000,-78.47203034,183.9632069,0,14.03629709,0,113.1007164 +53.01,50.41325469,-3.449364627,10000,-78.4894383,183.9530005,0,14.03629709,0,113.1077423 +53.02,50.41324765,-3.449338788,10000,-78.50684626,183.9432391,0,14.03629709,0,113.1147683 +53.03,50.4132406,-3.449312951,10000,-78.53121744,183.9339226,0,14.03629709,0,113.1217942 +53.04,50.41323355,-3.449287114,10000,-78.56255185,183.9243837,0,14.03629709,0,113.1288201 +53.05,50.4132265,-3.44926128,10000,-78.59736787,183.9148447,0,14.03629709,0,113.135846 +53.06,50.41321944,-3.449235446,10000,-78.61825744,183.9055283,0,14.03629709,0,113.142872 +53.07,50.41321238,-3.449209614,10000,-78.62173894,183.8959894,0,14.03629709,0,113.1498979 +53.08,50.41320533,-3.449183783,10000,-78.63914687,183.8866729,0,14.03629709,0,113.1569238 +53.09,50.41319827,-3.449157954,10000,-78.6774445,183.8780239,0,14.03629709,0,113.1639497 +53.1,50.4131912,-3.449132125,10000,-78.70877892,183.8687075,0,14.03629709,0,113.1709757 +53.11,50.41318414,-3.449106298,10000,-78.7296685,183.8578338,0,14.03629709,0,113.1780016 +53.12,50.41317707,-3.449080473,10000,-78.75055807,183.8467376,0,14.03629709,0,113.1850275 +53.13,50.41317,-3.449054649,10000,-78.76448441,183.8369762,0,14.03629709,0,113.1920534 +53.14,50.41316293,-3.449028827,10000,-78.77144753,183.8283272,0,14.03629709,0,113.1990794 +53.15,50.41315586,-3.449003005,10000,-78.78885549,183.8190108,0,14.03629709,0,113.2061053 +53.16,50.41314879,-3.448977185,10000,-78.82367151,183.808582,0,14.03629709,0,113.2131311 +53.17,50.41314171,-3.448951367,10000,-78.85848753,183.7990432,0,14.03629709,0,113.2201571 +53.18,50.41313463,-3.44892555,10000,-78.87937708,183.7906166,0,14.03629709,0,113.227183 +53.19,50.41312755,-3.448899733,10000,-78.89678504,183.7810778,0,14.03629709,0,113.2342089 +53.2,50.41312047,-3.448873919,10000,-78.91767462,183.7704266,0,14.03629709,0,113.2412348 +53.21,50.41311338,-3.448848106,10000,-78.93508258,183.7602203,0,14.03629709,0,113.2482608 +53.22,50.4131063,-3.448822294,10000,-78.95597214,183.7502365,0,14.03629709,0,113.2552867 +53.23,50.41309921,-3.448796484,10000,-78.99078816,183.7400303,0,14.03629709,0,113.2623126 +53.24,50.41309212,-3.448770675,10000,-79.02560418,183.7304914,0,14.03629709,0,113.2693385 +53.25,50.41308502,-3.448744868,10000,-79.04649375,183.722065,0,14.03629709,0,113.2763645 +53.26,50.41307793,-3.448719061,10000,-79.06390169,183.7136385,0,14.03629709,0,113.2833904 +53.27,50.41307083,-3.448693256,10000,-79.08479126,183.7040997,0,14.03629709,0,113.2904163 +53.28,50.41306373,-3.448667452,10000,-79.10219922,183.693671,0,14.03629709,0,113.2974422 +53.29,50.41305663,-3.44864165,10000,-79.11960718,183.6830198,0,14.03629709,0,113.3044682 +53.3,50.41304953,-3.448615849,10000,-79.14049675,183.6725911,0,14.03629709,0,113.3114941 +53.31,50.41304242,-3.44859005,10000,-79.15790471,183.6628298,0,14.03629709,0,113.31852 +53.32,50.41303532,-3.448564252,10000,-79.17879427,183.6535135,0,14.03629709,0,113.3255459 +53.33,50.41302821,-3.448538455,10000,-79.21361027,183.6439747,0,14.03629709,0,113.3325719 +53.34,50.4130211,-3.44851266,10000,-79.24842629,183.6344359,0,14.03629709,0,113.3395978 +53.35,50.41301398,-3.448486866,10000,-79.26931588,183.6251196,0,14.03629709,0,113.3466237 +53.36,50.41300687,-3.448461073,10000,-79.28672384,183.6153584,0,14.03629709,0,113.3536496 +53.37,50.41299975,-3.448435282,10000,-79.3076134,183.6051522,0,14.03629709,0,113.3606756 +53.38,50.41299263,-3.448409492,10000,-79.32502134,183.595391,0,14.03629709,0,113.3677015 +53.39,50.41298551,-3.448383704,10000,-79.34242929,183.5860747,0,14.03629709,0,113.3747274 +53.4,50.41297839,-3.448357916,10000,-79.36331886,183.5765359,0,14.03629709,0,113.3817533 +53.41,50.41297126,-3.448332131,10000,-79.38072682,183.5667747,0,14.03629709,0,113.3887793 +53.42,50.41296414,-3.448306346,10000,-79.40161639,183.5565685,0,14.03629709,0,113.3958052 +53.43,50.41295701,-3.448280563,10000,-79.4364324,183.5459174,0,14.03629709,0,113.4028311 +53.44,50.41294988,-3.448254782,10000,-79.47124842,183.5363787,0,14.03629709,0,113.409857 +53.45,50.41294274,-3.448229002,10000,-79.49213799,183.5279523,0,14.03629709,0,113.416883 +53.46,50.41293561,-3.448203222,10000,-79.50954593,183.5184136,0,14.03629709,0,113.4239089 +53.47,50.41292847,-3.448177445,10000,-79.53043549,183.507985,0,14.03629709,0,113.4309348 +53.48,50.41292133,-3.448151669,10000,-79.54784345,183.4986687,0,14.03629709,0,113.4379607 +53.49,50.41291419,-3.448125894,10000,-79.56873303,183.4897974,0,14.03629709,0,113.4449867 +53.5,50.41290705,-3.44810012,10000,-79.60354905,183.4795913,0,14.03629709,0,113.4520125 +53.51,50.4128999,-3.448074348,10000,-79.63836505,183.4687178,0,14.03629709,0,113.4590385 +53.52,50.41289275,-3.448048578,10000,-79.65577299,183.4585117,0,14.03629709,0,113.4660644 +53.53,50.4128856,-3.448022808,10000,-79.66273612,183.4487505,0,14.03629709,0,113.4730903 +53.54,50.41287845,-3.447997041,10000,-79.67666247,183.4392118,0,14.03629709,0,113.4801162 +53.55,50.4128713,-3.447971274,10000,-79.69755204,183.4298956,0,14.03629709,0,113.4871421 +53.56,50.41286414,-3.447945509,10000,-79.71495999,183.4203569,0,14.03629709,0,113.4941681 +53.57,50.41285699,-3.447919745,10000,-79.73584955,183.4108182,0,14.03629709,0,113.501194 +53.58,50.41284983,-3.447893983,10000,-79.77066557,183.4012796,0,14.03629709,0,113.5082199 +53.59,50.41284267,-3.447868221,10000,-79.80548159,183.390851,0,14.03629709,0,113.5152458 +53.6,50.4128355,-3.447842462,10000,-79.82637116,183.3799775,0,14.03629709,0,113.5222718 +53.61,50.41282834,-3.447816704,10000,-79.8437791,183.3699939,0,14.03629709,0,113.5292977 +53.62,50.41282117,-3.447790947,10000,-79.86815026,183.3611227,0,14.03629709,0,113.5363236 +53.63,50.412814,-3.447765192,10000,-79.89600305,183.3526964,0,14.03629709,0,113.5433495 +53.64,50.41280683,-3.447739437,10000,-79.92037424,183.3433802,0,14.03629709,0,113.5503755 +53.65,50.41279965,-3.447713684,10000,-79.93778219,183.3325068,0,14.03629709,0,113.5574014 +53.66,50.41279248,-3.447687933,10000,-79.95519014,183.3214108,0,14.03629709,0,113.5644273 +53.67,50.4127853,-3.447662183,10000,-79.97607971,183.3116497,0,14.03629709,0,113.5714532 +53.68,50.41277812,-3.447636435,10000,-79.99348767,183.303001,0,14.03629709,0,113.5784792 +53.69,50.41277094,-3.447610687,10000,-80.01437723,183.2936849,0,14.03629709,0,113.5855051 +53.7,50.41276376,-3.447584941,10000,-80.04919324,183.2830339,0,14.03629709,0,113.592531 +53.71,50.41275657,-3.447559197,10000,-80.08400924,183.2726054,0,14.03629709,0,113.5995569 +53.72,50.41274938,-3.447533454,10000,-80.1014172,183.2630668,0,14.03629709,0,113.6065829 +53.73,50.41274219,-3.447507712,10000,-80.10838032,183.2535282,0,14.03629709,0,113.6136088 +53.74,50.412735,-3.447481972,10000,-80.12578827,183.2439896,0,14.03629709,0,113.6206347 +53.75,50.41272781,-3.447456233,10000,-80.16060427,183.2346735,0,14.03629709,0,113.6276606 +53.76,50.41272061,-3.447430495,10000,-80.19542028,183.2249124,0,14.03629709,0,113.6346866 +53.77,50.41271341,-3.447404759,10000,-80.21282825,183.214484,0,14.03629709,0,113.6417125 +53.78,50.41270621,-3.447379024,10000,-80.21979139,183.203833,0,14.03629709,0,113.6487384 +53.79,50.41269901,-3.447353291,10000,-80.23719933,183.1934046,0,14.03629709,0,113.6557643 +53.8,50.41269181,-3.447327559,10000,-80.27201532,183.183866,0,14.03629709,0,113.6627903 +53.81,50.4126846,-3.447301829,10000,-80.30683132,183.1752174,0,14.03629709,0,113.6698162 +53.82,50.41267739,-3.447276099,10000,-80.32423929,183.1659013,0,14.03629709,0,113.6768421 +53.83,50.41267018,-3.447250371,10000,-80.33120242,183.1552504,0,14.03629709,0,113.683868 +53.84,50.41266297,-3.447224645,10000,-80.34861037,183.1448219,0,14.03629709,0,113.690894 +53.85,50.41265576,-3.44719892,10000,-80.38342637,183.1352834,0,14.03629709,0,113.6979198 +53.86,50.41264854,-3.447173196,10000,-80.41824237,183.1255224,0,14.03629709,0,113.7049458 +53.87,50.41264132,-3.447147474,10000,-80.43565033,183.115094,0,14.03629709,0,113.7119717 +53.88,50.4126341,-3.447121753,10000,-80.44261345,183.1046655,0,14.03629709,0,113.7189976 +53.89,50.41262688,-3.447096034,10000,-80.46002139,183.0949046,0,14.03629709,0,113.7260235 +53.9,50.41261966,-3.447070316,10000,-80.49483739,183.085811,0,14.03629709,0,113.7330495 +53.91,50.41261243,-3.447044599,10000,-80.5296534,183.0769399,0,14.03629709,0,113.7400754 +53.92,50.4126052,-3.447018884,10000,-80.54706137,183.0676239,0,14.03629709,0,113.7471013 +53.93,50.41259797,-3.446993169,10000,-80.55402449,183.0571955,0,14.03629709,0,113.7541272 +53.94,50.41259074,-3.446967457,10000,-80.57143244,183.0465446,0,14.03629709,0,113.7611532 +53.95,50.41258351,-3.446941746,10000,-80.60624844,183.0370061,0,14.03629709,0,113.7681791 +53.96,50.41257627,-3.446916036,10000,-80.64106445,183.0274676,0,14.03629709,0,113.775205 +53.97,50.41256903,-3.446890327,10000,-80.6584724,183.0168168,0,14.03629709,0,113.7822309 +53.98,50.41256179,-3.446864621,10000,-80.66543552,183.0063884,0,14.03629709,0,113.7892568 +53.99,50.41255455,-3.446838915,10000,-80.68284348,182.9968499,0,14.03629709,0,113.7962828 +54,50.41254731,-3.446813211,10000,-80.71765949,182.987089,0,14.03629709,0,113.8033087 +54.01,50.41254006,-3.446787508,10000,-80.75247549,182.9768831,0,14.03629709,0,113.8103346 +54.02,50.41253281,-3.446761807,10000,-80.76988344,182.9671222,0,14.03629709,0,113.8173605 +54.03,50.41252556,-3.446736107,10000,-80.77684655,182.9578062,0,14.03629709,0,113.8243865 +54.04,50.41251831,-3.446710408,10000,-80.7942545,182.9480453,0,14.03629709,0,113.8314124 +54.05,50.41251106,-3.446684711,10000,-80.8290705,182.9376169,0,14.03629709,0,113.8384383 +54.06,50.4125038,-3.446659015,10000,-80.8638865,182.9271886,0,14.03629709,0,113.8454642 +54.07,50.41249654,-3.446633321,10000,-80.88129447,182.9174277,0,14.03629709,0,113.8524902 +54.08,50.41248928,-3.446607628,10000,-80.8882576,182.9081118,0,14.03629709,0,113.8595161 +54.09,50.41248202,-3.446581936,10000,-80.90566555,182.8983509,0,14.03629709,0,113.866542 +54.1,50.41247476,-3.446556246,10000,-80.94048156,182.888145,0,14.03629709,0,113.8735679 +54.11,50.41246749,-3.446530557,10000,-80.97529755,182.8783841,0,14.03629709,0,113.8805939 +54.12,50.41246022,-3.44650487,10000,-80.9961871,182.8688457,0,14.03629709,0,113.8876198 +54.13,50.41245295,-3.446479183,10000,-81.01359505,182.8584174,0,14.03629709,0,113.8946457 +54.14,50.41244568,-3.446453499,10000,-81.03448462,182.8477666,0,14.03629709,0,113.9016716 +54.15,50.4124384,-3.446427816,10000,-81.05189257,182.8384507,0,14.03629709,0,113.9086976 +54.16,50.41243113,-3.446402134,10000,-81.06930052,182.8295798,0,14.03629709,0,113.9157235 +54.17,50.41242385,-3.446376453,10000,-81.09367169,182.8191515,0,14.03629709,0,113.9227494 +54.18,50.41241657,-3.446350774,10000,-81.12500609,182.8076108,0,14.03629709,0,113.9297753 +54.19,50.41240929,-3.446325097,10000,-81.15982209,182.7971825,0,14.03629709,0,113.9368012 +54.2,50.412402,-3.446299421,10000,-81.18071165,182.7885341,0,14.03629709,0,113.9438271 +54.21,50.41239471,-3.446273746,10000,-81.18419314,182.7801081,0,14.03629709,0,113.9508531 +54.22,50.41238743,-3.446248072,10000,-81.2016011,182.7705697,0,14.03629709,0,113.957879 +54.23,50.41238014,-3.4462224,10000,-81.23989872,182.7601415,0,14.03629709,0,113.9649049 +54.24,50.41237284,-3.446196729,10000,-81.27123313,182.7494907,0,14.03629709,0,113.9719308 +54.25,50.41236555,-3.44617106,10000,-81.29212269,182.73884,0,14.03629709,0,113.9789568 +54.26,50.41235825,-3.446145392,10000,-81.31301225,182.7281893,0,14.03629709,0,113.9859827 +54.27,50.41235095,-3.446119726,10000,-81.32693859,182.7175386,0,14.03629709,0,113.9930086 +54.28,50.41234365,-3.446094061,10000,-81.33390169,182.7071104,0,14.03629709,0,114.0000345 +54.29,50.41233635,-3.446068398,10000,-81.35130962,182.697572,0,14.03629709,0,114.0070605 +54.3,50.41232905,-3.446042736,10000,-81.38612562,182.6891461,0,14.03629709,0,114.0140864 +54.31,50.41232174,-3.446017075,10000,-81.42094163,182.6807201,0,14.03629709,0,114.0211123 +54.32,50.41231443,-3.445991415,10000,-81.44183121,182.6709594,0,14.03629709,0,114.0281382 +54.33,50.41230712,-3.445965757,10000,-81.45923917,182.6596412,0,14.03629709,0,114.0351642 +54.34,50.41229981,-3.4459401,10000,-81.48012873,182.6478782,0,14.03629709,0,114.0421901 +54.35,50.41229249,-3.445914446,10000,-81.49753667,182.63745,0,14.03629709,0,114.049216 +54.36,50.41228518,-3.445888792,10000,-81.51494461,182.6288016,0,14.03629709,0,114.0562419 +54.37,50.41227786,-3.44586314,10000,-81.53931577,182.6201532,0,14.03629709,0,114.0632678 +54.38,50.41227054,-3.445837488,10000,-81.57065017,182.6099475,0,14.03629709,0,114.0702938 +54.39,50.41226322,-3.445811839,10000,-81.60894779,182.5990744,0,14.03629709,0,114.0773197 +54.4,50.41225589,-3.445786191,10000,-81.64376379,182.5888687,0,14.03629709,0,114.0843456 +54.41,50.41224856,-3.445760544,10000,-81.66117173,182.5791079,0,14.03629709,0,114.0913715 +54.42,50.41224123,-3.445734899,10000,-81.66465324,182.5695697,0,14.03629709,0,114.0983975 +54.43,50.4122339,-3.445709255,10000,-81.66813475,182.5600314,0,14.03629709,0,114.1054234 +54.44,50.41222657,-3.445683612,10000,-81.68554269,182.5496032,0,14.03629709,0,114.1124493 +54.45,50.41221924,-3.445657971,10000,-81.72035869,182.5389526,0,14.03629709,0,114.1194752 +54.46,50.4122119,-3.445632332,10000,-81.7551747,182.5294144,0,14.03629709,0,114.1265012 +54.47,50.41220456,-3.445606693,10000,-81.77606426,182.5198761,0,14.03629709,0,114.1335271 +54.48,50.41219722,-3.445581056,10000,-81.79347221,182.509003,0,14.03629709,0,114.140553 +54.49,50.41218988,-3.445555421,10000,-81.81436177,182.4979075,0,14.03629709,0,114.1475789 +54.5,50.41218253,-3.445529787,10000,-81.83176972,182.4879243,0,14.03629709,0,114.1546049 +54.51,50.41217519,-3.445504155,10000,-81.85265928,182.4786085,0,14.03629709,0,114.1616307 +54.52,50.41216784,-3.445478523,10000,-81.88747527,182.4690703,0,14.03629709,0,114.1686567 +54.53,50.41216049,-3.445452894,10000,-81.92229126,182.4593096,0,14.03629709,0,114.1756826 +54.54,50.41215313,-3.445427265,10000,-81.94318082,182.449104,0,14.03629709,0,114.1827085 +54.55,50.41214578,-3.445401638,10000,-81.96058878,182.4382309,0,14.03629709,0,114.1897344 +54.56,50.41213842,-3.445376013,10000,-81.98147834,182.4278028,0,14.03629709,0,114.1967604 +54.57,50.41213106,-3.445350389,10000,-81.99540467,182.4182646,0,14.03629709,0,114.2037863 +54.58,50.4121237,-3.445324766,10000,-82.00236779,182.408504,0,14.03629709,0,114.2108122 +54.59,50.41211634,-3.445299145,10000,-82.01977574,182.3980759,0,14.03629709,0,114.2178381 +54.6,50.41210898,-3.445273525,10000,-82.05459173,182.3876478,0,14.03629709,0,114.2248641 +54.61,50.41210161,-3.445247907,10000,-82.08940772,182.3778871,0,14.03629709,0,114.23189 +54.62,50.41209424,-3.44522229,10000,-82.11029729,182.3685714,0,14.03629709,0,114.2389159 +54.63,50.41208687,-3.445196674,10000,-82.13118686,182.3588108,0,14.03629709,0,114.2459418 +54.64,50.4120795,-3.44517106,10000,-82.16252125,182.3483827,0,14.03629709,0,114.2529678 +54.65,50.41207212,-3.445145447,10000,-82.1834108,182.3379546,0,14.03629709,0,114.2599937 +54.66,50.41206474,-3.445119836,10000,-82.18689229,182.328194,0,14.03629709,0,114.2670196 +54.67,50.41205737,-3.445094226,10000,-82.20430023,182.3186559,0,14.03629709,0,114.2740455 +54.68,50.41204999,-3.445068617,10000,-82.24259784,182.3082278,0,14.03629709,0,114.2810715 +54.69,50.4120426,-3.44504301,10000,-82.27393224,182.2973548,0,14.03629709,0,114.2880974 +54.7,50.41203522,-3.445017405,10000,-82.2948218,182.2871492,0,14.03629709,0,114.2951233 +54.71,50.41202783,-3.4449918,10000,-82.31571135,182.2773886,0,14.03629709,0,114.3021492 +54.72,50.41202044,-3.444966198,10000,-82.3331193,182.2678505,0,14.03629709,0,114.3091752 +54.73,50.41201305,-3.444940596,10000,-82.35052726,182.2585349,0,14.03629709,0,114.3162011 +54.74,50.41200566,-3.444914996,10000,-82.37141681,182.2485518,0,14.03629709,0,114.323227 +54.75,50.41199826,-3.444889397,10000,-82.38882474,182.2372339,0,14.03629709,0,114.3302529 +54.76,50.41199087,-3.4448638,10000,-82.40971428,182.225471,0,14.03629709,0,114.3372788 +54.77,50.41198347,-3.444838205,10000,-82.44453028,182.215043,0,14.03629709,0,114.3443048 +54.78,50.41197607,-3.444812611,10000,-82.4793463,182.2063948,0,14.03629709,0,114.3513307 +54.79,50.41196866,-3.444787018,10000,-82.50023587,182.1977466,0,14.03629709,0,114.3583566 +54.8,50.41196126,-3.444761426,10000,-82.51764381,182.1873186,0,14.03629709,0,114.3653825 +54.81,50.41195385,-3.444735836,10000,-82.53853335,182.1757782,0,14.03629709,0,114.3724085 +54.82,50.41194644,-3.444710248,10000,-82.5559413,182.1653503,0,14.03629709,0,114.3794344 +54.83,50.41193903,-3.444684661,10000,-82.57334925,182.1564796,0,14.03629709,0,114.3864603 +54.84,50.41193162,-3.444659075,10000,-82.5942388,182.147164,0,14.03629709,0,114.3934862 +54.85,50.4119242,-3.44463349,10000,-82.61164674,182.1365136,0,14.03629709,0,114.4005122 +54.86,50.41191679,-3.444607908,10000,-82.6325363,182.1260856,0,14.03629709,0,114.407538 +54.87,50.41190937,-3.444582326,10000,-82.6673523,182.1163251,0,14.03629709,0,114.414564 +54.88,50.41190195,-3.444556746,10000,-82.70216829,182.1058971,0,14.03629709,0,114.4215899 +54.89,50.41189452,-3.444531167,10000,-82.72305786,182.0952467,0,14.03629709,0,114.4286158 +54.9,50.4118871,-3.444505591,10000,-82.74046581,182.0854861,0,14.03629709,0,114.4356417 +54.91,50.41187967,-3.444480014,10000,-82.76135537,182.0752807,0,14.03629709,0,114.4426677 +54.92,50.41187224,-3.44445444,10000,-82.7787633,182.0641853,0,14.03629709,0,114.4496936 +54.93,50.41186481,-3.444428868,10000,-82.79617124,182.0539798,0,14.03629709,0,114.4567195 +54.94,50.41185738,-3.444403296,10000,-82.81706079,182.0444418,0,14.03629709,0,114.4637454 +54.95,50.41184994,-3.444377726,10000,-82.83446874,182.0344588,0,14.03629709,0,114.4707714 +54.96,50.41184251,-3.444352158,10000,-82.8553583,182.0244759,0,14.03629709,0,114.4777973 +54.97,50.41183507,-3.44432659,10000,-82.89017429,182.0147154,0,14.03629709,0,114.4848232 +54.98,50.41182763,-3.444301025,10000,-82.92499027,182.0049549,0,14.03629709,0,114.4918491 +54.99,50.41182018,-3.44427546,10000,-82.94587982,181.9947495,0,14.03629709,0,114.4988751 +55,50.41181274,-3.444249897,10000,-82.96328778,181.9838766,0,14.03629709,0,114.505901 +55.01,50.41180529,-3.444224336,10000,-82.98417734,181.9734487,0,14.03629709,0,114.5129269 +55.02,50.41179784,-3.444198776,10000,-83.00158528,181.9636882,0,14.03629709,0,114.5199528 +55.03,50.41179039,-3.444173217,10000,-83.01899322,181.9532603,0,14.03629709,0,114.5269788 +55.04,50.41178294,-3.44414766,10000,-83.03988278,181.9423875,0,14.03629709,0,114.5340047 +55.05,50.41177548,-3.444122105,10000,-83.05729074,181.9319596,0,14.03629709,0,114.5410306 +55.06,50.41176803,-3.44409655,10000,-83.07818029,181.9213092,0,14.03629709,0,114.5480565 +55.07,50.41176057,-3.444070998,10000,-83.11299628,181.9106589,0,14.03629709,0,114.5550825 +55.08,50.41175311,-3.444045447,10000,-83.14781226,181.9013434,0,14.03629709,0,114.5621084 +55.09,50.41174564,-3.444019897,10000,-83.1687018,181.8926954,0,14.03629709,0,114.5691343 +55.1,50.41173818,-3.443994348,10000,-83.18610975,181.8831574,0,14.03629709,0,114.5761602 +55.11,50.41173071,-3.443968801,10000,-83.20699931,181.8727296,0,14.03629709,0,114.5831862 +55.12,50.41172324,-3.443943255,10000,-83.22440726,181.8620792,0,14.03629709,0,114.5902121 +55.13,50.41171577,-3.443917711,10000,-83.2418152,181.8514289,0,14.03629709,0,114.597238 +55.14,50.4117083,-3.443892168,10000,-83.26270475,181.8410011,0,14.03629709,0,114.6042639 +55.15,50.41170082,-3.443866627,10000,-83.28011269,181.8310182,0,14.03629709,0,114.6112898 +55.16,50.41169335,-3.443841087,10000,-83.30100226,181.8208128,0,14.03629709,0,114.6183158 +55.17,50.41168587,-3.443815548,10000,-83.33581826,181.80994,0,14.03629709,0,114.6253416 +55.18,50.41167839,-3.443790012,10000,-83.37063425,181.7995122,0,14.03629709,0,114.6323676 +55.19,50.4116709,-3.443764476,10000,-83.39152378,181.7899743,0,14.03629709,0,114.6393935 +55.2,50.41166342,-3.443738942,10000,-83.40893172,181.7802139,0,14.03629709,0,114.6464194 +55.21,50.41165593,-3.443713409,10000,-83.42982128,181.7697861,0,14.03629709,0,114.6534453 +55.22,50.41164844,-3.443687878,10000,-83.44722923,181.7591358,0,14.03629709,0,114.6604713 +55.23,50.41164095,-3.443662348,10000,-83.46811878,181.7484855,0,14.03629709,0,114.6674972 +55.24,50.41163346,-3.44363682,10000,-83.49945315,181.7378352,0,14.03629709,0,114.6745231 +55.25,50.41162596,-3.443611293,10000,-83.52382432,181.7274074,0,14.03629709,0,114.681549 +55.26,50.41161846,-3.443585768,10000,-83.53775065,181.7176471,0,14.03629709,0,114.688575 +55.27,50.41161097,-3.443560244,10000,-83.5586402,181.7083317,0,14.03629709,0,114.6956009 +55.28,50.41160346,-3.443534721,10000,-83.57952976,181.6985713,0,14.03629709,0,114.7026268 +55.29,50.41159596,-3.4435092,10000,-83.59345609,181.6881436,0,14.03629709,0,114.7096527 +55.3,50.41158846,-3.44348368,10000,-83.61782725,181.6774933,0,14.03629709,0,114.7166787 +55.31,50.41158095,-3.443458162,10000,-83.64916163,181.666843,0,14.03629709,0,114.7237046 +55.32,50.41157344,-3.443432645,10000,-83.67005118,181.6564153,0,14.03629709,0,114.7307305 +55.33,50.41156593,-3.44340713,10000,-83.69094073,181.646655,0,14.03629709,0,114.7377564 +55.34,50.41155842,-3.443381616,10000,-83.72575672,181.6373396,0,14.03629709,0,114.7447824 +55.35,50.4115509,-3.443356103,10000,-83.76057272,181.6275793,0,14.03629709,0,114.7518083 +55.36,50.41154338,-3.443330592,10000,-83.77798067,181.6169291,0,14.03629709,0,114.7588342 +55.37,50.41153586,-3.443305082,10000,-83.78146217,181.6053889,0,14.03629709,0,114.7658601 +55.38,50.41152834,-3.443279574,10000,-83.78494366,181.5936263,0,14.03629709,0,114.7728861 +55.39,50.41152082,-3.443254068,10000,-83.80235159,181.5831986,0,14.03629709,0,114.779912 +55.4,50.4115133,-3.443228563,10000,-83.83716759,181.5743282,0,14.03629709,0,114.7869379 +55.41,50.41150577,-3.443203059,10000,-83.87198358,181.5650128,0,14.03629709,0,114.7939638 +55.42,50.41149824,-3.443177556,10000,-83.89287313,181.5543626,0,14.03629709,0,114.8009898 +55.43,50.41149071,-3.443152056,10000,-83.91376269,181.5439349,0,14.03629709,0,114.8080157 +55.44,50.41148318,-3.443126556,10000,-83.94857868,181.5343971,0,14.03629709,0,114.8150416 +55.45,50.41147564,-3.443101058,10000,-83.98339466,181.5244144,0,14.03629709,0,114.8220675 +55.46,50.4114681,-3.443075561,10000,-84.0008026,181.5130968,0,14.03629709,0,114.8290935 +55.47,50.41146056,-3.443050066,10000,-84.00776572,181.5013342,0,14.03629709,0,114.8361194 +55.48,50.41145302,-3.443024573,10000,-84.02169206,181.490684,0,14.03629709,0,114.8431453 +55.49,50.41144548,-3.442999081,10000,-84.04258161,181.4811462,0,14.03629709,0,114.8501712 +55.5,50.41143793,-3.44297359,10000,-84.05998954,181.4716085,0,14.03629709,0,114.8571972 +55.51,50.41143039,-3.442948101,10000,-84.08087909,181.4618482,0,14.03629709,0,114.8642231 +55.52,50.41142284,-3.442922613,10000,-84.11569507,181.451643,0,14.03629709,0,114.871249 +55.53,50.41141529,-3.442897126,10000,-84.15051106,181.4407704,0,14.03629709,0,114.8782749 +55.54,50.41140773,-3.442871642,10000,-84.17140061,181.4303427,0,14.03629709,0,114.8853009 +55.55,50.41140018,-3.442846158,10000,-84.18880855,181.420805,0,14.03629709,0,114.8923267 +55.56,50.41139262,-3.442820676,10000,-84.2096981,181.4108223,0,14.03629709,0,114.8993526 +55.57,50.41138506,-3.442795195,10000,-84.22710604,181.3995047,0,14.03629709,0,114.9063786 +55.58,50.4113775,-3.442769716,10000,-84.24451399,181.3877422,0,14.03629709,0,114.9134045 +55.59,50.41136994,-3.442744239,10000,-84.26540355,181.377092,0,14.03629709,0,114.9204304 +55.6,50.41136237,-3.442718763,10000,-84.28281149,181.3675543,0,14.03629709,0,114.9274563 +55.61,50.41135481,-3.442693288,10000,-84.30370103,181.3577941,0,14.03629709,0,114.9344823 +55.62,50.41134724,-3.442667815,10000,-84.338517,181.3475889,0,14.03629709,0,114.9415082 +55.63,50.41133967,-3.442642343,10000,-84.37333298,181.3378287,0,14.03629709,0,114.9485341 +55.64,50.41133209,-3.442616873,10000,-84.39422254,181.328291,0,14.03629709,0,114.95556 +55.65,50.41132452,-3.442591403,10000,-84.41163049,181.3178634,0,14.03629709,0,114.962586 +55.66,50.41131694,-3.442565936,10000,-84.43252004,181.3069908,0,14.03629709,0,114.9696119 +55.67,50.41130936,-3.44254047,10000,-84.44992797,181.2965632,0,14.03629709,0,114.9766378 +55.68,50.41130178,-3.442515005,10000,-84.46733591,181.2856907,0,14.03629709,0,114.9836637 +55.69,50.4112942,-3.442489542,10000,-84.48822546,181.2741506,0,14.03629709,0,114.9906897 +55.7,50.41128661,-3.442464081,10000,-84.50563339,181.2635006,0,14.03629709,0,114.9977156 +55.71,50.41127903,-3.442438621,10000,-84.52652295,181.2539629,0,14.03629709,0,115.0047415 +55.72,50.41127144,-3.442413162,10000,-84.56133895,181.2442027,0,14.03629709,0,115.0117674 +55.73,50.41126385,-3.442387705,10000,-84.59615492,181.2337751,0,14.03629709,0,115.0187934 +55.74,50.41125625,-3.442362249,10000,-84.61704446,181.2233476,0,14.03629709,0,115.0258193 +55.75,50.41124866,-3.442336795,10000,-84.6344524,181.2133649,0,14.03629709,0,115.0328452 +55.76,50.41124106,-3.442311342,10000,-84.65534196,181.2031598,0,14.03629709,0,115.0398711 +55.77,50.41123346,-3.44228589,10000,-84.66926829,181.1922873,0,14.03629709,0,115.0468971 +55.78,50.41122586,-3.442260441,10000,-84.67623139,181.1818597,0,14.03629709,0,115.053923 +55.79,50.41121826,-3.442234992,10000,-84.69363932,181.1723221,0,14.03629709,0,115.0609489 +55.8,50.41121066,-3.442209545,10000,-84.72845531,181.162562,0,14.03629709,0,115.0679748 +55.81,50.41120305,-3.442184099,10000,-84.7632713,181.1521344,0,14.03629709,0,115.0750008 +55.82,50.41119544,-3.442158655,10000,-84.78416086,181.1412619,0,14.03629709,0,115.0820267 +55.83,50.41118783,-3.442133212,10000,-84.80505041,181.129722,0,14.03629709,0,115.0890526 +55.84,50.41118022,-3.442107771,10000,-84.83986639,181.1179595,0,14.03629709,0,115.0960785 +55.85,50.4111726,-3.442082332,10000,-84.87468237,181.1073095,0,14.03629709,0,115.1031045 +55.86,50.41116498,-3.442056894,10000,-84.89209031,181.0977719,0,14.03629709,0,115.1101303 +55.87,50.41115736,-3.442031457,10000,-84.8955718,181.0880118,0,14.03629709,0,115.1171563 +55.88,50.41114974,-3.442006022,10000,-84.89905329,181.0775843,0,14.03629709,0,115.1241822 +55.89,50.41114212,-3.441980588,10000,-84.91646123,181.0671568,0,14.03629709,0,115.1312081 +55.9,50.4111345,-3.441955156,10000,-84.95127723,181.0573967,0,14.03629709,0,115.138234 +55.91,50.41112687,-3.441929725,10000,-84.98609322,181.0478591,0,14.03629709,0,115.14526 +55.92,50.41111924,-3.441904295,10000,-85.00698276,181.0372091,0,14.03629709,0,115.1522859 +55.93,50.41111161,-3.441878867,10000,-85.02439069,181.0256692,0,14.03629709,0,115.1593118 +55.94,50.41110398,-3.441853441,10000,-85.04528023,181.0150192,0,14.03629709,0,115.1663377 +55.95,50.41109634,-3.441828016,10000,-85.06268817,181.0052592,0,14.03629709,0,115.1733637 +55.96,50.41108871,-3.441802592,10000,-85.08357772,180.9946092,0,14.03629709,0,115.1803896 +55.97,50.41108107,-3.44177717,10000,-85.11839371,180.9830693,0,14.03629709,0,115.1874155 +55.98,50.41107343,-3.44175175,10000,-85.1532097,180.9724193,0,14.03629709,0,115.1944414 +55.99,50.41106578,-3.441726331,10000,-85.17409924,180.9628818,0,14.03629709,0,115.2014673 +56,50.41105814,-3.441700913,10000,-85.19150718,180.9533442,0,14.03629709,0,115.2084933 +56.01,50.41105049,-3.441675497,10000,-85.21239673,180.9435842,0,14.03629709,0,115.2155192 +56.02,50.41104284,-3.441650082,10000,-85.22980467,180.9333792,0,14.03629709,0,115.2225451 +56.03,50.41103519,-3.441624668,10000,-85.2472126,180.9225068,0,14.03629709,0,115.229571 +56.04,50.41102754,-3.441599257,10000,-85.26810215,180.9118569,0,14.03629709,0,115.236597 +56.05,50.41101988,-3.441573846,10000,-85.28551008,180.9012069,0,14.03629709,0,115.2436229 +56.06,50.41101223,-3.441548437,10000,-85.302918,180.8894446,0,14.03629709,0,115.2506488 +56.07,50.41100457,-3.44152303,10000,-85.32728915,180.8779047,0,14.03629709,0,115.2576747 +56.08,50.41099691,-3.441497625,10000,-85.35862353,180.8681447,0,14.03629709,0,115.2647007 +56.09,50.41098925,-3.44147222,10000,-85.39343951,180.8586072,0,14.03629709,0,115.2717266 +56.1,50.41098158,-3.441446817,10000,-85.41781067,180.8479573,0,14.03629709,0,115.2787525 +56.11,50.41097391,-3.441421416,10000,-85.43173701,180.8375299,0,14.03629709,0,115.2857784 +56.12,50.41096625,-3.441396016,10000,-85.45262656,180.8279924,0,14.03629709,0,115.2928044 +56.13,50.41095857,-3.441370617,10000,-85.47351609,180.8182324,0,14.03629709,0,115.2998303 +56.14,50.4109509,-3.44134522,10000,-85.48744241,180.8075825,0,14.03629709,0,115.3068562 +56.15,50.41094323,-3.441319824,10000,-85.51181357,180.7960427,0,14.03629709,0,115.3138821 +56.16,50.41093555,-3.44129443,10000,-85.54314795,180.7842804,0,14.03629709,0,115.3209081 +56.17,50.41092787,-3.441269038,10000,-85.56403749,180.7736305,0,14.03629709,0,115.327934 +56.18,50.41092019,-3.441243647,10000,-85.58144541,180.7640931,0,14.03629709,0,115.3349599 +56.19,50.41091251,-3.441218257,10000,-85.60233496,180.7543331,0,14.03629709,0,115.3419858 +56.2,50.41090482,-3.441192869,10000,-85.6197429,180.7436832,0,14.03629709,0,115.3490118 +56.21,50.41089714,-3.441167482,10000,-85.63715084,180.7323659,0,14.03629709,0,115.3560376 +56.22,50.41088945,-3.441142097,10000,-85.66152199,180.7214936,0,14.03629709,0,115.3630636 +56.23,50.41088176,-3.441116714,10000,-85.68937475,180.7119561,0,14.03629709,0,115.3700895 +56.24,50.41087407,-3.441091331,10000,-85.71374592,180.7021962,0,14.03629709,0,115.3771154 +56.25,50.41086637,-3.44106595,10000,-85.73115385,180.6906564,0,14.03629709,0,115.3841413 +56.26,50.41085868,-3.441040571,10000,-85.75204338,180.6791166,0,14.03629709,0,115.3911673 +56.27,50.41085098,-3.441015194,10000,-85.78685935,180.6693567,0,14.03629709,0,115.3981932 +56.28,50.41084328,-3.440989817,10000,-85.82167534,180.6598193,0,14.03629709,0,115.4052191 +56.29,50.41083557,-3.440964442,10000,-85.84256489,180.6491695,0,14.03629709,0,115.412245 +56.3,50.41082787,-3.440939069,10000,-85.85997283,180.6385196,0,14.03629709,0,115.419271 +56.31,50.41082016,-3.440913697,10000,-85.88086236,180.6280923,0,14.03629709,0,115.4262969 +56.32,50.41081245,-3.440888326,10000,-85.89478868,180.61722,0,14.03629709,0,115.4333228 +56.33,50.41080474,-3.440862958,10000,-85.90175179,180.6065702,0,14.03629709,0,115.4403487 +56.34,50.41079703,-3.44083759,10000,-85.91915973,180.5961428,0,14.03629709,0,115.4473747 +56.35,50.41078932,-3.440812224,10000,-85.95397571,180.5850481,0,14.03629709,0,115.4544006 +56.36,50.4107816,-3.44078686,10000,-85.98879169,180.5739533,0,14.03629709,0,115.4614265 +56.37,50.41077388,-3.440761497,10000,-86.00619962,180.5639709,0,14.03629709,0,115.4684524 +56.38,50.41076616,-3.440736136,10000,-86.01316271,180.5544335,0,14.03629709,0,115.4754783 +56.39,50.41075844,-3.440710775,10000,-86.03057065,180.5440062,0,14.03629709,0,115.4825043 +56.4,50.41075072,-3.440685417,10000,-86.06538663,180.533134,0,14.03629709,0,115.4895302 +56.41,50.41074299,-3.44066006,10000,-86.10020261,180.5227066,0,14.03629709,0,115.4965561 +56.42,50.41073526,-3.440634704,10000,-86.12109216,180.5118344,0,14.03629709,0,115.503582 +56.43,50.41072753,-3.44060935,10000,-86.1385001,180.5002947,0,14.03629709,0,115.510608 +56.44,50.4107198,-3.440583998,10000,-86.15938965,180.4896449,0,14.03629709,0,115.5176339 +56.45,50.41071206,-3.440558647,10000,-86.17679758,180.4801076,0,14.03629709,0,115.5246598 +56.46,50.41070433,-3.440533297,10000,-86.19420551,180.4701252,0,14.03629709,0,115.5316857 +56.47,50.41069659,-3.440507949,10000,-86.21857666,180.458808,0,14.03629709,0,115.5387117 +56.48,50.41068885,-3.440482602,10000,-86.24642941,180.4470459,0,14.03629709,0,115.5457376 +56.49,50.41068111,-3.440457258,10000,-86.27080055,180.4363961,0,14.03629709,0,115.5527635 +56.5,50.41067336,-3.440431914,10000,-86.28820848,180.4268588,0,14.03629709,0,115.5597894 +56.51,50.41066562,-3.440406572,10000,-86.30561642,180.4170989,0,14.03629709,0,115.5668154 +56.52,50.41065787,-3.440381231,10000,-86.32998758,180.4066717,0,14.03629709,0,115.5738413 +56.53,50.41065012,-3.440355892,10000,-86.35784035,180.3960219,0,14.03629709,0,115.5808672 +56.54,50.41064237,-3.440330554,10000,-86.38221149,180.3853722,0,14.03629709,0,115.5878931 +56.55,50.41063461,-3.440305218,10000,-86.39961941,180.3745,0,14.03629709,0,115.5949191 +56.56,50.41062686,-3.440279883,10000,-86.41702734,180.3631828,0,14.03629709,0,115.6019449 +56.57,50.4106191,-3.44025455,10000,-86.4413985,180.3520881,0,14.03629709,0,115.6089709 +56.58,50.41061134,-3.440229219,10000,-86.46925127,180.3418834,0,14.03629709,0,115.6159968 +56.59,50.41060358,-3.440203888,10000,-86.49362242,180.3319011,0,14.03629709,0,115.6230227 +56.6,50.41059581,-3.44017856,10000,-86.51103035,180.3214739,0,14.03629709,0,115.6300486 +56.61,50.41058805,-3.440153232,10000,-86.52843827,180.3110467,0,14.03629709,0,115.6370746 +56.62,50.41058028,-3.440127907,10000,-86.55280942,180.3008419,0,14.03629709,0,115.6441005 +56.63,50.41057251,-3.440102582,10000,-86.58066218,180.2897473,0,14.03629709,0,115.6511264 +56.64,50.41056474,-3.440077259,10000,-86.60503333,180.2775402,0,14.03629709,0,115.6581523 +56.65,50.41055696,-3.440051939,10000,-86.62244126,180.2662231,0,14.03629709,0,115.6651783 +56.66,50.41054919,-3.440026619,10000,-86.63984919,180.2566858,0,14.03629709,0,115.6722042 +56.67,50.41054141,-3.440001301,10000,-86.66422033,180.2475935,0,14.03629709,0,115.6792301 +56.68,50.41053363,-3.439975984,10000,-86.69207309,180.2376113,0,14.03629709,0,115.686256 +56.69,50.41052585,-3.439950668,10000,-86.71644426,180.2265166,0,14.03629709,0,115.693282 +56.7,50.41051806,-3.439925355,10000,-86.73385219,180.214977,0,14.03629709,0,115.7003079 +56.71,50.41051028,-3.439900042,10000,-86.75126011,180.2034374,0,14.03629709,0,115.7073338 +56.72,50.41050249,-3.439874732,10000,-86.77563125,180.1925653,0,14.03629709,0,115.7143597 +56.73,50.4104947,-3.439849423,10000,-86.80348402,180.1830281,0,14.03629709,0,115.7213857 +56.74,50.41048691,-3.439824115,10000,-86.82785518,180.1732683,0,14.03629709,0,115.7284116 +56.75,50.41047911,-3.439798808,10000,-86.8452631,180.1617288,0,14.03629709,0,115.7354375 +56.76,50.41047132,-3.439773504,10000,-86.86267101,180.1499667,0,14.03629709,0,115.7424634 +56.77,50.41046352,-3.439748201,10000,-86.88704215,180.1395395,0,14.03629709,0,115.7494893 +56.78,50.41045572,-3.439722899,10000,-86.91489492,180.1295574,0,14.03629709,0,115.7565153 +56.79,50.41044792,-3.439697599,10000,-86.93926609,180.1191302,0,14.03629709,0,115.7635412 +56.8,50.41044011,-3.4396723,10000,-86.95667403,180.1084806,0,14.03629709,0,115.7705671 +56.81,50.41043231,-3.439647003,10000,-86.97408195,180.097831,0,14.03629709,0,115.777593 +56.82,50.4104245,-3.439621707,10000,-86.99845308,180.0874038,0,14.03629709,0,115.784619 +56.83,50.41041669,-3.439596413,10000,-87.02630583,180.0774217,0,14.03629709,0,115.7916449 +56.84,50.41040888,-3.43957112,10000,-87.05067698,180.0669945,0,14.03629709,0,115.7986708 +56.85,50.41040106,-3.439545828,10000,-87.06808492,180.0552325,0,14.03629709,0,115.8056967 +56.86,50.41039325,-3.439520539,10000,-87.08549286,180.043693,0,14.03629709,0,115.8127227 +56.87,50.41038543,-3.439495251,10000,-87.1063824,180.0339333,0,14.03629709,0,115.8197485 +56.88,50.41037761,-3.439469964,10000,-87.12379032,180.0241737,0,14.03629709,0,115.8267745 +56.89,50.41036979,-3.439444678,10000,-87.14467984,180.0126341,0,14.03629709,0,115.8338004 +56.9,50.41036197,-3.439419395,10000,-87.17949581,180.0008721,0,14.03629709,0,115.8408263 +56.91,50.41035414,-3.439394113,10000,-87.21431179,179.990445,0,14.03629709,0,115.8478522 +56.92,50.41034631,-3.439368832,10000,-87.23171973,179.9804629,0,14.03629709,0,115.8548782 +56.93,50.41033848,-3.439343553,10000,-87.23868284,179.9700358,0,14.03629709,0,115.8619041 +56.94,50.41033065,-3.439318275,10000,-87.25260915,179.9593862,0,14.03629709,0,115.86893 +56.95,50.41032282,-3.439292999,10000,-87.27349868,179.9487367,0,14.03629709,0,115.8759559 +56.96,50.41031498,-3.439267724,10000,-87.29090661,179.9378646,0,14.03629709,0,115.8829819 +56.97,50.41030715,-3.439242451,10000,-87.31179616,179.9263251,0,14.03629709,0,115.8900078 +56.98,50.41029931,-3.439217179,10000,-87.34661214,179.9145631,0,14.03629709,0,115.8970337 +56.99,50.41029147,-3.43919191,10000,-87.3814281,179.9039136,0,14.03629709,0,115.9040596 +57,50.41028362,-3.439166641,10000,-87.40231763,179.8943764,0,14.03629709,0,115.9110856 +57.01,50.41027578,-3.439141374,10000,-87.41972556,179.8843944,0,14.03629709,0,115.9181115 +57.02,50.41026793,-3.439116108,10000,-87.44061511,179.8732998,0,14.03629709,0,115.9251374 +57.03,50.41026008,-3.439090844,10000,-87.45802304,179.8624278,0,14.03629709,0,115.9321633 +57.04,50.41025223,-3.439065582,10000,-87.47891257,179.8526682,0,14.03629709,0,115.9391893 +57.05,50.41024438,-3.43904032,10000,-87.51372854,179.8422412,0,14.03629709,0,115.9462152 +57.06,50.41023652,-3.43901506,10000,-87.5485445,179.8302568,0,14.03629709,0,115.9532411 +57.07,50.41022866,-3.438989803,10000,-87.56595243,179.8187173,0,14.03629709,0,115.960267 +57.08,50.4102208,-3.438964546,10000,-87.57291554,179.8080678,0,14.03629709,0,115.967293 +57.09,50.41021294,-3.438939291,10000,-87.58684187,179.7971958,0,14.03629709,0,115.9743189 +57.1,50.41020508,-3.438914038,10000,-87.6077314,179.7867688,0,14.03629709,0,115.9813448 +57.11,50.41019721,-3.438888786,10000,-87.62513932,179.7772317,0,14.03629709,0,115.9883707 +57.12,50.41018935,-3.438863535,10000,-87.64602885,179.7672496,0,14.03629709,0,115.9953967 +57.13,50.41018148,-3.438838286,10000,-87.68084482,179.7559327,0,14.03629709,0,116.0024226 +57.14,50.41017361,-3.438813038,10000,-87.71566079,179.7441708,0,14.03629709,0,116.0094485 +57.15,50.41016573,-3.438787793,10000,-87.73655034,179.7332988,0,14.03629709,0,116.0164744 +57.16,50.41015786,-3.438762548,10000,-87.75395828,179.7228718,0,14.03629709,0,116.0235003 +57.17,50.41014998,-3.438737305,10000,-87.7748478,179.7117773,0,14.03629709,0,116.0305263 +57.18,50.4101421,-3.438712064,10000,-87.79225572,179.7006829,0,14.03629709,0,116.0375522 +57.19,50.41013422,-3.438686824,10000,-87.80966365,179.6907009,0,14.03629709,0,116.0445781 +57.2,50.41012634,-3.438661586,10000,-87.8305532,179.6809414,0,14.03629709,0,116.051604 +57.21,50.41011845,-3.438636348,10000,-87.84796112,179.6696244,0,14.03629709,0,116.05863 +57.22,50.41011057,-3.438611113,10000,-87.86885064,179.6576401,0,14.03629709,0,116.0656558 +57.23,50.41010268,-3.43858588,10000,-87.90366661,179.6472131,0,14.03629709,0,116.0726818 +57.24,50.41009479,-3.438560647,10000,-87.93848259,179.6374536,0,14.03629709,0,116.0797077 +57.25,50.41008689,-3.438535416,10000,-87.95937213,179.6265816,0,14.03629709,0,116.0867336 +57.26,50.410079,-3.438510187,10000,-87.97678005,179.6150423,0,14.03629709,0,116.0937595 +57.27,50.4100711,-3.438484959,10000,-87.99766958,179.6035029,0,14.03629709,0,116.1007855 +57.28,50.4100632,-3.438459733,10000,-88.0115959,179.5924085,0,14.03629709,0,116.1078114 +57.29,50.4100553,-3.438434509,10000,-88.018559,179.582204,0,14.03629709,0,116.1148373 +57.3,50.4100474,-3.438409285,10000,-88.03596693,179.572222,0,14.03629709,0,116.1218632 +57.31,50.4100395,-3.438384064,10000,-88.0707829,179.5615726,0,14.03629709,0,116.1288892 +57.32,50.41003159,-3.438358843,10000,-88.10559888,179.5502557,0,14.03629709,0,116.1359151 +57.33,50.41002368,-3.438333625,10000,-88.12648841,179.5391613,0,14.03629709,0,116.142941 +57.34,50.41001577,-3.438308408,10000,-88.14389634,179.5287344,0,14.03629709,0,116.1499669 +57.35,50.41000786,-3.438283192,10000,-88.16478587,179.518085,0,14.03629709,0,116.1569929 +57.36,50.40999994,-3.438257978,10000,-88.18219378,179.5072131,0,14.03629709,0,116.1640188 +57.37,50.40999203,-3.438232766,10000,-88.20308331,179.4967862,0,14.03629709,0,116.1710447 +57.38,50.40998411,-3.438207554,10000,-88.23789929,179.4859143,0,14.03629709,0,116.1780706 +57.39,50.40997619,-3.438182345,10000,-88.27271527,179.4741525,0,14.03629709,0,116.1850966 +57.4,50.40996826,-3.438157137,10000,-88.29012319,179.4626131,0,14.03629709,0,116.1921225 +57.41,50.40996034,-3.438131931,10000,-88.29360467,179.4519637,0,14.03629709,0,116.1991484 +57.42,50.40995241,-3.438106726,10000,-88.30056776,179.4422043,0,14.03629709,0,116.2061743 +57.43,50.40994449,-3.438081523,10000,-88.32842052,179.4326673,0,14.03629709,0,116.2132003 +57.44,50.40993656,-3.43805632,10000,-88.37019971,179.422018,0,14.03629709,0,116.2202262 +57.45,50.40992862,-3.43803112,10000,-88.40153407,179.4100337,0,14.03629709,0,116.2272521 +57.46,50.40992069,-3.438005921,10000,-88.42242361,179.3978269,0,14.03629709,0,116.234278 +57.47,50.40991275,-3.437980724,10000,-88.44331314,179.3867326,0,14.03629709,0,116.241304 +57.48,50.40990481,-3.437955529,10000,-88.45723945,179.3771956,0,14.03629709,0,116.2483299 +57.49,50.40989687,-3.437930334,10000,-88.46420254,179.3674362,0,14.03629709,0,116.2553558 +57.5,50.40988893,-3.437905141,10000,-88.48161047,179.3558969,0,14.03629709,0,116.2623817 +57.51,50.40988099,-3.43787995,10000,-88.51642644,179.3441352,0,14.03629709,0,116.2694077 +57.52,50.40987304,-3.437854761,10000,-88.55124241,179.3334858,0,14.03629709,0,116.2764336 +57.53,50.40986509,-3.437829572,10000,-88.56865033,179.322614,0,14.03629709,0,116.2834595 +57.54,50.40985714,-3.437804386,10000,-88.57561341,179.3110747,0,14.03629709,0,116.2904854 +57.55,50.40984919,-3.437779201,10000,-88.59302134,179.3004254,0,14.03629709,0,116.2975114 +57.56,50.40984124,-3.437754018,10000,-88.62783731,179.290666,0,14.03629709,0,116.3045372 +57.57,50.40983328,-3.437728835,10000,-88.66265329,179.2802391,0,14.03629709,0,116.3115631 +57.58,50.40982532,-3.437703655,10000,-88.68006122,179.2691448,0,14.03629709,0,116.3185891 +57.59,50.40981736,-3.437678476,10000,-88.68702431,179.2580506,0,14.03629709,0,116.325615 +57.6,50.4098094,-3.437653298,10000,-88.70443222,179.2467338,0,14.03629709,0,116.3326409 +57.61,50.40980144,-3.437628123,10000,-88.7392482,179.2351945,0,14.03629709,0,116.3396668 +57.62,50.40979347,-3.437602948,10000,-88.77406417,179.2236553,0,14.03629709,0,116.3466928 +57.63,50.4097855,-3.437577776,10000,-88.79147208,179.2127835,0,14.03629709,0,116.3537187 +57.64,50.40977753,-3.437552605,10000,-88.79843517,179.2032466,0,14.03629709,0,116.3607446 +57.65,50.40976956,-3.437527435,10000,-88.81584309,179.1934873,0,14.03629709,0,116.3677705 +57.66,50.40976159,-3.437502266,10000,-88.85065906,179.181948,0,14.03629709,0,116.3747965 +57.67,50.40975361,-3.4374771,10000,-88.88547504,179.1701863,0,14.03629709,0,116.3818224 +57.68,50.40974563,-3.437451935,10000,-88.90288298,179.1597595,0,14.03629709,0,116.3888483 +57.69,50.40973765,-3.437426771,10000,-88.90984607,179.1495552,0,14.03629709,0,116.3958742 +57.7,50.40972967,-3.437401609,10000,-88.92377238,179.1382385,0,14.03629709,0,116.4029002 +57.71,50.40972169,-3.437376448,10000,-88.9446619,179.1264767,0,14.03629709,0,116.4099261 +57.72,50.4097137,-3.43735129,10000,-88.96555142,179.115605,0,14.03629709,0,116.416952 +57.73,50.40970572,-3.437326132,10000,-88.99688578,179.1051782,0,14.03629709,0,116.4239779 +57.74,50.40969773,-3.437300976,10000,-89.03518336,179.0943065,0,14.03629709,0,116.4310039 +57.75,50.40968973,-3.437275822,10000,-89.05259127,179.0836572,0,14.03629709,0,116.4380298 +57.76,50.40968174,-3.437250669,10000,-89.05607275,179.0730079,0,14.03629709,0,116.4450557 +57.77,50.40967375,-3.437225517,10000,-89.07696228,179.0612463,0,14.03629709,0,116.4520816 +57.78,50.40966575,-3.437200368,10000,-89.11177827,179.0494846,0,14.03629709,0,116.4591076 +57.79,50.40965775,-3.43717522,10000,-89.14311264,179.0390578,0,14.03629709,0,116.4661335 +57.8,50.40964975,-3.437150073,10000,-89.16748378,179.029076,0,14.03629709,0,116.4731594 +57.81,50.40964174,-3.437124928,10000,-89.18489168,179.0184268,0,14.03629709,0,116.4801853 +57.82,50.40963374,-3.437099784,10000,-89.20229958,179.0068876,0,14.03629709,0,116.4872113 +57.83,50.40962573,-3.437074642,10000,-89.22318911,178.995126,0,14.03629709,0,116.4942372 +57.84,50.40961772,-3.437049502,10000,-89.24059704,178.9844767,0,14.03629709,0,116.5012631 +57.85,50.40960971,-3.437024363,10000,-89.25800496,178.9747175,0,14.03629709,0,116.508289 +57.86,50.4096017,-3.436999225,10000,-89.2788945,178.9640683,0,14.03629709,0,116.515315 +57.87,50.40959368,-3.436974089,10000,-89.29630244,178.9523066,0,14.03629709,0,116.5223409 +57.88,50.40958567,-3.436948955,10000,-89.31719196,178.9407674,0,14.03629709,0,116.5293668 +57.89,50.40957765,-3.436923822,10000,-89.35200791,178.9298957,0,14.03629709,0,116.5363927 +57.9,50.40956963,-3.436898691,10000,-89.38682387,178.9192465,0,14.03629709,0,116.5434187 +57.91,50.4095616,-3.436873561,10000,-89.40771341,178.9085974,0,14.03629709,0,116.5504445 +57.92,50.40955358,-3.436848433,10000,-89.42512133,178.8977257,0,14.03629709,0,116.5574705 +57.93,50.40954555,-3.436823306,10000,-89.44601086,178.8861865,0,14.03629709,0,116.5644964 +57.94,50.40953752,-3.436798181,10000,-89.46341877,178.8744249,0,14.03629709,0,116.5715223 +57.95,50.40952949,-3.436773058,10000,-89.48082669,178.8635532,0,14.03629709,0,116.5785482 +57.96,50.40952146,-3.436747936,10000,-89.50171621,178.8531265,0,14.03629709,0,116.5855742 +57.97,50.40951342,-3.436722815,10000,-89.51912414,178.8422549,0,14.03629709,0,116.5926001 +57.98,50.40950539,-3.436697697,10000,-89.54001368,178.8316057,0,14.03629709,0,116.599626 +57.99,50.40949735,-3.436672579,10000,-89.57482964,178.821179,0,14.03629709,0,116.6066519 +58,50.40948931,-3.436647463,10000,-89.6096456,178.8100849,0,14.03629709,0,116.6136778 +58.01,50.40948126,-3.436622349,10000,-89.63053513,178.7987683,0,14.03629709,0,116.6207038 +58.02,50.40947322,-3.436597236,10000,-89.64794305,178.7878966,0,14.03629709,0,116.6277297 +58.03,50.40946517,-3.436572125,10000,-89.66883258,178.777025,0,14.03629709,0,116.6347556 +58.04,50.40945712,-3.436547015,10000,-89.68275888,178.7654859,0,14.03629709,0,116.6417815 +58.05,50.40944907,-3.436521907,10000,-89.68972198,178.7535018,0,14.03629709,0,116.6488075 +58.06,50.40944102,-3.436496801,10000,-89.70712991,178.7419627,0,14.03629709,0,116.6558334 +58.07,50.40943297,-3.436471696,10000,-89.74194587,178.7313136,0,14.03629709,0,116.6628593 +58.08,50.40942491,-3.436446593,10000,-89.77676181,178.7213319,0,14.03629709,0,116.6698852 +58.09,50.40941685,-3.436421491,10000,-89.79765132,178.7111278,0,14.03629709,0,116.6769112 +58.1,50.40940879,-3.43639639,10000,-89.81505924,178.7000336,0,14.03629709,0,116.6839371 +58.11,50.40940073,-3.436371292,10000,-89.83594878,178.6887171,0,14.03629709,0,116.690963 +58.12,50.40939266,-3.436346194,10000,-89.85335671,178.6778455,0,14.03629709,0,116.6979889 +58.13,50.4093846,-3.436321099,10000,-89.87076463,178.6669738,0,14.03629709,0,116.7050149 +58.14,50.40937653,-3.436296004,10000,-89.89513576,178.6554348,0,14.03629709,0,116.7120408 +58.15,50.40936846,-3.436270912,10000,-89.9229885,178.6436732,0,14.03629709,0,116.7190667 +58.16,50.40936039,-3.436245821,10000,-89.94735964,178.6330241,0,14.03629709,0,116.7260926 +58.17,50.40935231,-3.436220732,10000,-89.96476757,178.623265,0,14.03629709,0,116.7331186 +58.18,50.40934424,-3.436195643,10000,-89.9821755,178.6126159,0,14.03629709,0,116.7401445 +58.19,50.40933616,-3.436170557,10000,-90.00654663,178.6006318,0,14.03629709,0,116.7471704 +58.2,50.40932808,-3.436145472,10000,-90.03439937,178.5882028,0,14.03629709,0,116.7541963 +58.21,50.40932,-3.436120389,10000,-90.0587705,178.5762188,0,14.03629709,0,116.7612223 +58.22,50.40931191,-3.436095308,10000,-90.07617841,178.5655698,0,14.03629709,0,116.7682481 +58.23,50.40930383,-3.436070228,10000,-90.09358633,178.5560331,0,14.03629709,0,116.7752741 +58.24,50.40929574,-3.436045149,10000,-90.11795746,178.5460515,0,14.03629709,0,116.7823 +58.25,50.40928765,-3.436020072,10000,-90.1458102,178.534735,0,14.03629709,0,116.7893259 +58.26,50.40927956,-3.435994996,10000,-90.17018134,178.5229735,0,14.03629709,0,116.7963518 +58.27,50.40927146,-3.435969923,10000,-90.18758926,178.5121019,0,14.03629709,0,116.8033778 +58.28,50.40926337,-3.43594485,10000,-90.20499717,178.5016753,0,14.03629709,0,116.8104037 +58.29,50.40925527,-3.435919779,10000,-90.2293683,178.4905813,0,14.03629709,0,116.8174296 +58.3,50.40924717,-3.43589471,10000,-90.25722105,178.4790423,0,14.03629709,0,116.8244555 +58.31,50.40923907,-3.435869642,10000,-90.28159219,178.4672808,0,14.03629709,0,116.8314815 +58.32,50.40923096,-3.435844576,10000,-90.2990001,178.4555193,0,14.03629709,0,116.8385074 +58.33,50.40922286,-3.435819512,10000,-90.31640803,178.4448703,0,14.03629709,0,116.8455333 +58.34,50.40921475,-3.435794449,10000,-90.34077916,178.4351112,0,14.03629709,0,116.8525592 +58.35,50.40920664,-3.435769387,10000,-90.3686319,178.4242397,0,14.03629709,0,116.8595852 +58.36,50.40919853,-3.435744327,10000,-90.39300303,178.4118107,0,14.03629709,0,116.8666111 +58.37,50.40919041,-3.435719269,10000,-90.41041095,178.4000492,0,14.03629709,0,116.873637 +58.38,50.4091823,-3.435694213,10000,-90.42781886,178.3902902,0,14.03629709,0,116.8806629 +58.39,50.40917418,-3.435669157,10000,-90.44870839,178.3805311,0,14.03629709,0,116.8876888 +58.4,50.40916606,-3.435644103,10000,-90.4661163,178.3687697,0,14.03629709,0,116.8947148 +58.41,50.40915794,-3.435619051,10000,-90.48352421,178.3563407,0,14.03629709,0,116.9017407 +58.42,50.40914982,-3.435594001,10000,-90.50441373,178.3452467,0,14.03629709,0,116.9087666 +58.43,50.40914169,-3.435568952,10000,-90.52530327,178.3345977,0,14.03629709,0,116.9157925 +58.44,50.40913357,-3.435543904,10000,-90.55663762,178.3228363,0,14.03629709,0,116.9228185 +58.45,50.40912544,-3.435518859,10000,-90.59493518,178.3110748,0,14.03629709,0,116.9298444 +58.46,50.4091173,-3.435493815,10000,-90.61234309,178.3006483,0,14.03629709,0,116.9368703 +58.47,50.40910917,-3.435468772,10000,-90.61582457,178.2906668,0,14.03629709,0,116.9438962 +58.48,50.40910104,-3.435443731,10000,-90.6367141,178.2800178,0,14.03629709,0,116.9509222 +58.49,50.4090929,-3.435418691,10000,-90.66804846,178.2684789,0,14.03629709,0,116.9579481 +58.5,50.40908476,-3.435393653,10000,-90.68893797,178.256495,0,14.03629709,0,116.964974 +58.51,50.40907662,-3.435368617,10000,-90.70982749,178.244956,0,14.03629709,0,116.9719999 +58.52,50.40906848,-3.435343582,10000,-90.74116184,178.2340846,0,14.03629709,0,116.9790259 +58.53,50.40906033,-3.435318549,10000,-90.76205138,178.2232131,0,14.03629709,0,116.9860518 +58.54,50.40905218,-3.435293517,10000,-90.76553287,178.2118967,0,14.03629709,0,116.9930777 +58.55,50.40904404,-3.435268487,10000,-90.78294078,178.2008027,0,14.03629709,0,117.0001036 +58.56,50.40903589,-3.435243459,10000,-90.82123834,178.1903762,0,14.03629709,0,117.0071296 +58.57,50.40902773,-3.435218431,10000,-90.85257268,178.1795048,0,14.03629709,0,117.0141554 +58.58,50.40901958,-3.435193406,10000,-90.8734622,178.1677434,0,14.03629709,0,117.0211814 +58.59,50.40901142,-3.435168382,10000,-90.89435172,178.1562045,0,14.03629709,0,117.0282073 +58.6,50.40900326,-3.43514336,10000,-90.91175964,178.1451106,0,14.03629709,0,117.0352332 +58.61,50.4089951,-3.435118339,10000,-90.92916755,178.1337942,0,14.03629709,0,117.0422591 +58.62,50.40898694,-3.43509332,10000,-90.95005707,178.1227002,0,14.03629709,0,117.0492851 +58.63,50.40897877,-3.435068303,10000,-90.96746498,178.1122738,0,14.03629709,0,117.056311 +58.64,50.40897061,-3.435043286,10000,-90.98487289,178.1016249,0,14.03629709,0,117.0633369 +58.65,50.40896244,-3.435018272,10000,-91.00924402,178.090531,0,14.03629709,0,117.0703628 +58.66,50.40895427,-3.434993259,10000,-91.03709678,178.0792146,0,14.03629709,0,117.0773888 +58.67,50.4089461,-3.434968247,10000,-91.06146793,178.0672307,0,14.03629709,0,117.0844147 +58.68,50.40893792,-3.434943238,10000,-91.07887584,178.0554693,0,14.03629709,0,117.0914406 +58.69,50.40892975,-3.43491823,10000,-91.09628374,178.0448204,0,14.03629709,0,117.0984665 +58.7,50.40892157,-3.434893223,10000,-91.12065485,178.033949,0,14.03629709,0,117.1054925 +58.71,50.40891339,-3.434868218,10000,-91.1519892,178.0221877,0,14.03629709,0,117.1125184 +58.72,50.40890521,-3.434843215,10000,-91.18680517,178.0106488,0,14.03629709,0,117.1195443 +58.73,50.40889702,-3.434818213,10000,-91.20769469,177.9997774,0,14.03629709,0,117.1265702 +58.74,50.40888883,-3.434793213,10000,-91.21117616,177.9891285,0,14.03629709,0,117.1335962 +58.75,50.40888065,-3.434768214,10000,-91.22858408,177.9784796,0,14.03629709,0,117.1406221 +58.76,50.40887246,-3.434743217,10000,-91.26340004,177.9676083,0,14.03629709,0,117.147648 +58.77,50.40886426,-3.434718221,10000,-91.28080795,177.9560694,0,14.03629709,0,117.1546739 +58.78,50.40885607,-3.434693227,10000,-91.28428941,177.9443081,0,14.03629709,0,117.1616998 +58.79,50.40884788,-3.434668235,10000,-91.30517893,177.9334367,0,14.03629709,0,117.1687258 +58.8,50.40883968,-3.434643244,10000,-91.3399949,177.9227878,0,14.03629709,0,117.1757517 +58.81,50.40883148,-3.434618254,10000,-91.37132926,177.910804,0,14.03629709,0,117.1827776 +58.82,50.40882328,-3.434593267,10000,-91.39570039,177.8983752,0,14.03629709,0,117.1898035 +58.83,50.40881507,-3.434568281,10000,-91.41310829,177.8875039,0,14.03629709,0,117.1968295 +58.84,50.40880687,-3.434543297,10000,-91.4305162,177.877745,0,14.03629709,0,117.2038554 +58.85,50.40879866,-3.434518313,10000,-91.45488732,177.8670961,0,14.03629709,0,117.2108813 +58.86,50.40879045,-3.434493332,10000,-91.48274006,177.8551123,0,14.03629709,0,117.2179072 +58.87,50.40878224,-3.434468352,10000,-91.50711119,177.842906,0,14.03629709,0,117.2249332 +58.88,50.40877402,-3.434443374,10000,-91.52451912,177.8315897,0,14.03629709,0,117.2319591 +58.89,50.40876581,-3.434418398,10000,-91.54192703,177.8211634,0,14.03629709,0,117.238985 +58.9,50.40875759,-3.434393422,10000,-91.56281654,177.810292,0,14.03629709,0,117.2460109 +58.91,50.40874937,-3.434368449,10000,-91.58022445,177.7985308,0,14.03629709,0,117.2530369 +58.92,50.40874115,-3.434343477,10000,-91.60111397,177.786992,0,14.03629709,0,117.2600627 +58.93,50.40873293,-3.434318507,10000,-91.63244831,177.7761206,0,14.03629709,0,117.2670887 +58.94,50.4087247,-3.434293538,10000,-91.65681944,177.7652493,0,14.03629709,0,117.2741146 +58.95,50.40871647,-3.434268571,10000,-91.67074575,177.7537105,0,14.03629709,0,117.2811405 +58.96,50.40870825,-3.434243605,10000,-91.69163527,177.7417268,0,14.03629709,0,117.2881664 +58.97,50.40870001,-3.434218642,10000,-91.71252478,177.730188,0,14.03629709,0,117.2951924 +58.98,50.40869178,-3.434193679,10000,-91.72645108,177.7195392,0,14.03629709,0,117.3022183 +58.99,50.40868355,-3.434168719,10000,-91.75082221,177.7093354,0,14.03629709,0,117.3092442 +59,50.40867531,-3.434143759,10000,-91.78215655,177.6982416,0,14.03629709,0,117.3162701 +59.01,50.40866707,-3.434118801,10000,-91.80304607,177.6860353,0,14.03629709,0,117.3232961 +59.02,50.40865883,-3.434093846,10000,-91.82393559,177.6744966,0,14.03629709,0,117.330322 +59.03,50.40865059,-3.434068891,10000,-91.85526994,177.6636253,0,14.03629709,0,117.3373479 +59.04,50.40864234,-3.434043938,10000,-91.87615946,177.651864,0,14.03629709,0,117.3443738 +59.05,50.40863409,-3.434018987,10000,-91.87964094,177.6401028,0,14.03629709,0,117.3513998 +59.06,50.40862585,-3.433994038,10000,-91.89704885,177.629454,0,14.03629709,0,117.3584257 +59.07,50.4086176,-3.433969089,10000,-91.93534641,177.6185827,0,14.03629709,0,117.3654516 +59.08,50.40860934,-3.433944143,10000,-91.96668075,177.6068215,0,14.03629709,0,117.3724775 +59.09,50.40860109,-3.433919198,10000,-91.98757026,177.5955053,0,14.03629709,0,117.3795035 +59.1,50.40859283,-3.433894255,10000,-92.00845978,177.5853015,0,14.03629709,0,117.3865294 +59.11,50.40858457,-3.433869313,10000,-92.02238609,177.5748752,0,14.03629709,0,117.3935553 +59.12,50.40857631,-3.433844372,10000,-92.02934918,177.563114,0,14.03629709,0,117.4005812 +59.13,50.40856805,-3.433819434,10000,-92.04675707,177.5511303,0,14.03629709,0,117.4076072 +59.14,50.40855979,-3.433794497,10000,-92.08157301,177.5395915,0,14.03629709,0,117.4146331 +59.15,50.40855152,-3.433769561,10000,-92.11638898,177.5276078,0,14.03629709,0,117.421659 +59.16,50.40854325,-3.433744628,10000,-92.13379691,177.5158466,0,14.03629709,0,117.4286849 +59.17,50.40853498,-3.433719696,10000,-92.14075999,177.5051979,0,14.03629709,0,117.4357108 +59.18,50.40852671,-3.433694765,10000,-92.15816788,177.4943267,0,14.03629709,0,117.4427368 +59.19,50.40851844,-3.433669836,10000,-92.19298382,177.482788,0,14.03629709,0,117.4497627 +59.2,50.40851016,-3.433644909,10000,-92.22779977,177.4719167,0,14.03629709,0,117.4567886 +59.21,50.40850188,-3.433619983,10000,-92.2452077,177.461268,0,14.03629709,0,117.4638145 +59.22,50.4084936,-3.433595058,10000,-92.2521708,177.4495068,0,14.03629709,0,117.4708405 +59.23,50.40848532,-3.433570136,10000,-92.2695787,177.4375231,0,14.03629709,0,117.4778663 +59.24,50.40847704,-3.433545215,10000,-92.30439463,177.4262069,0,14.03629709,0,117.4848923 +59.25,50.40846875,-3.433520295,10000,-92.33921058,177.4151132,0,14.03629709,0,117.4919182 +59.26,50.40846046,-3.433495378,10000,-92.3566185,177.4044645,0,14.03629709,0,117.4989441 +59.27,50.40845217,-3.433470461,10000,-92.36358158,177.3938158,0,14.03629709,0,117.50597 +59.28,50.40844388,-3.433445546,10000,-92.38098947,177.3818322,0,14.03629709,0,117.512996 +59.29,50.40843559,-3.433420633,10000,-92.41580543,177.369181,0,14.03629709,0,117.5200219 +59.3,50.40842729,-3.433395722,10000,-92.4506214,177.3574199,0,14.03629709,0,117.5270478 +59.31,50.40841899,-3.433370812,10000,-92.46802931,177.3465487,0,14.03629709,0,117.5340737 +59.32,50.40841069,-3.433345904,10000,-92.47499237,177.3359,0,14.03629709,0,117.5410997 +59.33,50.40840239,-3.433320997,10000,-92.48891865,177.3252513,0,14.03629709,0,117.5481256 +59.34,50.40839409,-3.433296092,10000,-92.50980817,177.3143801,0,14.03629709,0,117.5551515 +59.35,50.40838578,-3.433271188,10000,-92.5272161,177.3028415,0,14.03629709,0,117.5621774 +59.36,50.40837748,-3.433246286,10000,-92.54810562,177.2908578,0,14.03629709,0,117.5692034 +59.37,50.40836917,-3.433221386,10000,-92.58292156,177.2790967,0,14.03629709,0,117.5762293 +59.38,50.40836086,-3.433196487,10000,-92.61773751,177.2673355,0,14.03629709,0,117.5832552 +59.39,50.40835254,-3.43317159,10000,-92.63862704,177.2553519,0,14.03629709,0,117.5902811 +59.4,50.40834423,-3.433146695,10000,-92.65603495,177.2438133,0,14.03629709,0,117.5973071 +59.41,50.40833591,-3.433121801,10000,-92.67692445,177.2329421,0,14.03629709,0,117.604333 +59.42,50.40832759,-3.433096909,10000,-92.69433236,177.222071,0,14.03629709,0,117.6113589 +59.43,50.40831927,-3.433072018,10000,-92.71174026,177.2107548,0,14.03629709,0,117.6183848 +59.44,50.40831095,-3.433047129,10000,-92.73262977,177.1996612,0,14.03629709,0,117.6254108 +59.45,50.40830262,-3.433022242,10000,-92.75003768,177.1890126,0,14.03629709,0,117.6324367 +59.46,50.4082943,-3.432997355,10000,-92.77092719,177.1774739,0,14.03629709,0,117.6394626 +59.47,50.40828597,-3.432972471,10000,-92.80574314,177.1652678,0,14.03629709,0,117.6464885 +59.48,50.40827764,-3.432947589,10000,-92.84055909,177.1539517,0,14.03629709,0,117.6535145 +59.49,50.4082693,-3.432922707,10000,-92.86144861,177.1428581,0,14.03629709,0,117.6605404 +59.5,50.40826097,-3.432897828,10000,-92.87885652,177.131097,0,14.03629709,0,117.6675663 +59.51,50.40825263,-3.43287295,10000,-92.89974604,177.1195584,0,14.03629709,0,117.6745922 +59.52,50.40824429,-3.432848074,10000,-92.91367234,177.1084648,0,14.03629709,0,117.6816182 +59.53,50.40823595,-3.432823199,10000,-92.92063542,177.0971487,0,14.03629709,0,117.6886441 +59.54,50.40822761,-3.432798326,10000,-92.93804332,177.0860551,0,14.03629709,0,117.69567 +59.55,50.40821927,-3.432773455,10000,-92.97285925,177.0754065,0,14.03629709,0,117.7026959 +59.56,50.40821092,-3.432748584,10000,-93.0076752,177.0636454,0,14.03629709,0,117.7097219 +59.57,50.40820257,-3.432723716,10000,-93.02508312,177.0507719,0,14.03629709,0,117.7167478 +59.58,50.40819422,-3.43269885,10000,-93.0320462,177.0392333,0,14.03629709,0,117.7237736 +59.59,50.40818587,-3.432673985,10000,-93.04945409,177.0292522,0,14.03629709,0,117.7307996 +59.6,50.40817752,-3.432649121,10000,-93.08427003,177.0186036,0,14.03629709,0,117.7378255 +59.61,50.40816916,-3.432624259,10000,-93.11908599,177.00662,0,14.03629709,0,117.7448514 +59.62,50.4081608,-3.432599399,10000,-93.1364939,176.9941915,0,14.03629709,0,117.7518773 +59.63,50.40815244,-3.43257454,10000,-93.14345698,176.9819854,0,14.03629709,0,117.7589033 +59.64,50.40814408,-3.432549684,10000,-93.16086489,176.9704469,0,14.03629709,0,117.7659292 +59.65,50.40813572,-3.432524828,10000,-93.19568083,176.9595758,0,14.03629709,0,117.7729551 +59.66,50.40812735,-3.432499975,10000,-93.23049677,176.9487047,0,14.03629709,0,117.779981 +59.67,50.40811898,-3.432475122,10000,-93.24790468,176.9371662,0,14.03629709,0,117.787007 +59.68,50.40811061,-3.432450272,10000,-93.25486777,176.9251826,0,14.03629709,0,117.7940329 +59.69,50.40810224,-3.432425423,10000,-93.27227566,176.9136441,0,14.03629709,0,117.8010588 +59.7,50.40809387,-3.432400576,10000,-93.3070916,176.902773,0,14.03629709,0,117.8080847 +59.71,50.40808549,-3.43237573,10000,-93.34190755,176.8921245,0,14.03629709,0,117.8151107 +59.72,50.40807711,-3.432350886,10000,-93.35931546,176.8812534,0,14.03629709,0,117.8221366 +59.73,50.40806873,-3.432326043,10000,-93.36627854,176.8697149,0,14.03629709,0,117.8291625 +59.74,50.40806035,-3.432301202,10000,-93.38020483,176.8577314,0,14.03629709,0,117.8361884 +59.75,50.40805197,-3.432276363,10000,-93.40109435,176.8459704,0,14.03629709,0,117.8432144 +59.76,50.40804358,-3.432251525,10000,-93.41850225,176.8342093,0,14.03629709,0,117.8502403 +59.77,50.4080352,-3.432226689,10000,-93.43939176,176.8222258,0,14.03629709,0,117.8572662 +59.78,50.40802681,-3.432201855,10000,-93.4742077,176.8106873,0,14.03629709,0,117.8642921 +59.79,50.40801842,-3.432177022,10000,-93.50902366,176.7998163,0,14.03629709,0,117.8713181 +59.8,50.40801002,-3.432152191,10000,-93.52991316,176.7889453,0,14.03629709,0,117.878344 +59.81,50.40800163,-3.432127361,10000,-93.54732106,176.7774068,0,14.03629709,0,117.8853699 +59.82,50.40799323,-3.432102533,10000,-93.56821057,176.7654233,0,14.03629709,0,117.8923958 +59.83,50.40798483,-3.432077707,10000,-93.58213688,176.7538848,0,14.03629709,0,117.8994218 +59.84,50.40797643,-3.432052882,10000,-93.58909996,176.7430138,0,14.03629709,0,117.9064477 +59.85,50.40796803,-3.432028059,10000,-93.60650785,176.7321427,0,14.03629709,0,117.9134736 +59.86,50.40795963,-3.432003237,10000,-93.64132379,176.7203817,0,14.03629709,0,117.9204995 +59.87,50.40795122,-3.431978417,10000,-93.67613972,176.7077308,0,14.03629709,0,117.9275255 +59.88,50.40794281,-3.431953599,10000,-93.69702924,176.6957473,0,14.03629709,0,117.9345514 +59.89,50.4079344,-3.431928783,10000,-93.71443714,176.6850988,0,14.03629709,0,117.9415773 +59.9,50.40792599,-3.431903967,10000,-93.73532666,176.6742278,0,14.03629709,0,117.9486032 +59.91,50.40791757,-3.431879154,10000,-93.75273458,176.6624669,0,14.03629709,0,117.9556292 +59.92,50.40790916,-3.431854342,10000,-93.77362409,176.6507059,0,14.03629709,0,117.962655 +59.93,50.40790074,-3.431829532,10000,-93.80844003,176.6389449,0,14.03629709,0,117.969681 +59.94,50.40789232,-3.431804723,10000,-93.84325596,176.6269615,0,14.03629709,0,117.9767069 +59.95,50.40788389,-3.431779917,10000,-93.86066387,176.6152005,0,14.03629709,0,117.9837328 +59.96,50.40787547,-3.431755111,10000,-93.86414534,176.6036621,0,14.03629709,0,117.9907587 +59.97,50.40786704,-3.431730308,10000,-93.87110841,176.5925686,0,14.03629709,0,117.9977847 +59.98,50.40785862,-3.431705506,10000,-93.89896113,176.5821426,0,14.03629709,0,118.0048106 +59.99,50.40785019,-3.431680705,10000,-93.94074028,176.5712717,0,14.03629709,0,118.0118365 +60,50.40784175,-3.431655906,10000,-93.96859301,176.5595107,0,14.03629709,0,118.0188624 +60.01,50.40783332,-3.431631109,10000,-93.9755561,176.5477498,0,14.03629709,0,118.0258883 +60.02,50.40782488,-3.431606313,10000,-93.97903758,176.5359888,0,14.03629709,0,118.0329143 +60.03,50.40781645,-3.431581519,10000,-93.99644548,176.5240054,0,14.03629709,0,118.0399402 +60.04,50.40780801,-3.431556727,10000,-94.03126141,176.5122445,0,14.03629709,0,118.0469661 +60.05,50.40779957,-3.431531936,10000,-94.06607735,176.500706,0,14.03629709,0,118.053992 +60.06,50.40779112,-3.431507147,10000,-94.08696687,176.4893901,0,14.03629709,0,118.061018 +60.07,50.40778268,-3.43148236,10000,-94.10437476,176.4780742,0,14.03629709,0,118.0680439 +60.08,50.40777423,-3.431457573,10000,-94.12874588,176.4660908,0,14.03629709,0,118.0750698 +60.09,50.40776578,-3.43143279,10000,-94.1565986,176.4541074,0,14.03629709,0,118.0820957 +60.1,50.40775733,-3.431408007,10000,-94.18096972,176.4427914,0,14.03629709,0,118.0891217 +60.11,50.40774887,-3.431383226,10000,-94.19837762,176.4314755,0,14.03629709,0,118.0961476 +60.12,50.40774042,-3.431358447,10000,-94.21578553,176.4199371,0,14.03629709,0,118.1031735 +60.13,50.40773196,-3.431333669,10000,-94.23667504,176.4081762,0,14.03629709,0,118.1101994 +60.14,50.4077235,-3.431308893,10000,-94.25408293,176.3964153,0,14.03629709,0,118.1172254 +60.15,50.40771504,-3.431284119,10000,-94.27149082,176.3855444,0,14.03629709,0,118.1242513 +60.16,50.40770658,-3.431259346,10000,-94.29238033,176.374896,0,14.03629709,0,118.1312772 +60.17,50.40769811,-3.431234574,10000,-94.30978825,176.3631351,0,14.03629709,0,118.1383031 +60.18,50.40768965,-3.431209805,10000,-94.33067776,176.3511517,0,14.03629709,0,118.1453291 +60.19,50.40768118,-3.431185037,10000,-94.3654937,176.3396133,0,14.03629709,0,118.152355 +60.2,50.40767271,-3.43116027,10000,-94.40030964,176.32763,0,14.03629709,0,118.1593809 +60.21,50.40766423,-3.431135506,10000,-94.42119914,176.3158691,0,14.03629709,0,118.1664068 +60.22,50.40765576,-3.431110743,10000,-94.43860703,176.3052207,0,14.03629709,0,118.1734328 +60.23,50.40764728,-3.431085981,10000,-94.45949653,176.2941273,0,14.03629709,0,118.1804587 +60.24,50.4076388,-3.431061221,10000,-94.47342283,176.2814765,0,14.03629709,0,118.1874846 +60.25,50.40763032,-3.431036463,10000,-94.48038593,176.2686031,0,14.03629709,0,118.1945105 +60.26,50.40762184,-3.431011707,10000,-94.49779382,176.2568422,0,14.03629709,0,118.2015365 +60.27,50.40761336,-3.430986952,10000,-94.53260974,176.2459714,0,14.03629709,0,118.2085623 +60.28,50.40760487,-3.430962199,10000,-94.56742567,176.2351005,0,14.03629709,0,118.2155883 +60.29,50.40759638,-3.430937447,10000,-94.58483358,176.2235622,0,14.03629709,0,118.2226142 +60.3,50.40758789,-3.430912697,10000,-94.59179667,176.2115788,0,14.03629709,0,118.2296401 +60.31,50.4075794,-3.430887949,10000,-94.60920457,176.2000404,0,14.03629709,0,118.236666 +60.32,50.40757091,-3.430863202,10000,-94.64402051,176.1891696,0,14.03629709,0,118.243692 +60.33,50.40756241,-3.430838457,10000,-94.67883645,176.1780762,0,14.03629709,0,118.2507179 +60.34,50.40755391,-3.430813713,10000,-94.69624434,176.1656479,0,14.03629709,0,118.2577438 +60.35,50.40754541,-3.430788971,10000,-94.70320741,176.1525521,0,14.03629709,0,118.2647697 +60.36,50.40753691,-3.430764232,10000,-94.72061531,176.1410138,0,14.03629709,0,118.2717957 +60.37,50.40752841,-3.430739493,10000,-94.75543124,176.1310329,0,14.03629709,0,118.2788216 +60.38,50.4075199,-3.430714756,10000,-94.79024717,176.1201621,0,14.03629709,0,118.2858475 +60.39,50.40751139,-3.43069002,10000,-94.80765506,176.1075113,0,14.03629709,0,118.2928734 +60.4,50.40750288,-3.430665287,10000,-94.81461815,176.094638,0,14.03629709,0,118.2998993 +60.41,50.40749437,-3.430640555,10000,-94.82854445,176.0828771,0,14.03629709,0,118.3069253 +60.42,50.40748586,-3.430615825,10000,-94.84943397,176.0720063,0,14.03629709,0,118.3139512 +60.43,50.40747734,-3.430591096,10000,-94.86684186,176.061358,0,14.03629709,0,118.3209771 +60.44,50.40746883,-3.430566369,10000,-94.88773136,176.0504872,0,14.03629709,0,118.328003 +60.45,50.40746031,-3.430541643,10000,-94.92254729,176.0387263,0,14.03629709,0,118.335029 +60.46,50.40745179,-3.430516919,10000,-94.95736323,176.0258531,0,14.03629709,0,118.3420549 +60.47,50.40744326,-3.430492197,10000,-94.97825274,176.0129798,0,14.03629709,0,118.3490808 +60.48,50.40743474,-3.430467477,10000,-94.99566064,176.001219,0,14.03629709,0,118.3561067 +60.49,50.40742621,-3.430442758,10000,-95.01655013,175.9903482,0,14.03629709,0,118.3631327 +60.5,50.40741768,-3.430418041,10000,-95.03395803,175.9794774,0,14.03629709,0,118.3701586 +60.51,50.40740915,-3.430393325,10000,-95.05136593,175.9679391,0,14.03629709,0,118.3771845 +60.52,50.40740062,-3.430368611,10000,-95.07225544,175.9559558,0,14.03629709,0,118.3842104 +60.53,50.40739208,-3.430343899,10000,-95.08966333,175.9444175,0,14.03629709,0,118.3912364 +60.54,50.40738355,-3.430319188,10000,-95.11055283,175.9333242,0,14.03629709,0,118.3982623 +60.55,50.40737501,-3.430294479,10000,-95.14536877,175.9215634,0,14.03629709,0,118.4052882 +60.56,50.40736647,-3.430269771,10000,-95.18018471,175.9089127,0,14.03629709,0,118.4123141 +60.57,50.40735792,-3.430245066,10000,-95.19759261,175.8969294,0,14.03629709,0,118.4193401 +60.58,50.40734938,-3.430220362,10000,-95.20107408,175.8862811,0,14.03629709,0,118.426366 +60.59,50.40734083,-3.430195659,10000,-95.20803715,175.8754104,0,14.03629709,0,118.4333919 +60.6,50.40733229,-3.430170958,10000,-95.23588987,175.8634271,0,14.03629709,0,118.4404178 +60.61,50.40732374,-3.430146259,10000,-95.27766902,175.8509989,0,14.03629709,0,118.4474437 +60.62,50.40731518,-3.430121561,10000,-95.30900335,175.8387931,0,14.03629709,0,118.4544696 +60.63,50.40730663,-3.430096866,10000,-95.32989285,175.8270324,0,14.03629709,0,118.4614956 +60.64,50.40729807,-3.430072171,10000,-95.35078235,175.8152716,0,14.03629709,0,118.4685215 +60.65,50.40728951,-3.430047479,10000,-95.36470863,175.8032884,0,14.03629709,0,118.4755474 +60.66,50.40728095,-3.430022788,10000,-95.37167171,175.7917501,0,14.03629709,0,118.4825733 +60.67,50.40727239,-3.429998099,10000,-95.38559801,175.7808794,0,14.03629709,0,118.4895993 +60.68,50.40726383,-3.429973411,10000,-95.40648751,175.7700086,0,14.03629709,0,118.4966252 +60.69,50.40725526,-3.429948725,10000,-95.427377,175.7582479,0,14.03629709,0,118.5036511 +60.7,50.4072467,-3.42992404,10000,-95.45871133,175.7455972,0,14.03629709,0,118.510677 +60.71,50.40723813,-3.429899358,10000,-95.49700888,175.7333914,0,14.03629709,0,118.517703 +60.72,50.40722955,-3.429874677,10000,-95.51441678,175.7218532,0,14.03629709,0,118.5247289 +60.73,50.40722098,-3.429849997,10000,-95.51789823,175.70987,0,14.03629709,0,118.5317548 +60.74,50.40721241,-3.42982532,10000,-95.53878773,175.6981093,0,14.03629709,0,118.5387807 +60.75,50.40720383,-3.429800644,10000,-95.57360366,175.687461,0,14.03629709,0,118.5458067 +60.76,50.40719525,-3.429775969,10000,-95.60493798,175.6763678,0,14.03629709,0,118.5528326 +60.77,50.40718667,-3.429751296,10000,-95.6293091,175.6637171,0,14.03629709,0,118.5598585 +60.78,50.40717808,-3.429726625,10000,-95.646717,175.6508439,0,14.03629709,0,118.5668844 +60.79,50.4071695,-3.429701956,10000,-95.6641249,175.6390832,0,14.03629709,0,118.5739103 +60.8,50.40716091,-3.429677288,10000,-95.6850144,175.6282125,0,14.03629709,0,118.5809363 +60.81,50.40715232,-3.429652622,10000,-95.69894069,175.6173418,0,14.03629709,0,118.5879622 +60.82,50.40714373,-3.429627957,10000,-95.70590377,175.6058036,0,14.03629709,0,118.5949881 +60.83,50.40713514,-3.429603294,10000,-95.72331165,175.5935979,0,14.03629709,0,118.602014 +60.84,50.40712655,-3.429578633,10000,-95.75812758,175.5811697,0,14.03629709,0,118.60904 +60.85,50.40711795,-3.429553973,10000,-95.79294352,175.568964,0,14.03629709,0,118.6160659 +60.86,50.40710935,-3.429529316,10000,-95.81383303,175.5574258,0,14.03629709,0,118.6230918 +60.87,50.40710075,-3.429504659,10000,-95.83124092,175.5465551,0,14.03629709,0,118.6301177 +60.88,50.40709215,-3.429480005,10000,-95.8521304,175.535462,0,14.03629709,0,118.6371437 +60.89,50.40708354,-3.429455351,10000,-95.86953829,175.5232563,0,14.03629709,0,118.6441696 +60.9,50.40707494,-3.4294307,10000,-95.8869462,175.5108281,0,14.03629709,0,118.6511955 +60.91,50.40706633,-3.429406051,10000,-95.91131732,175.4995124,0,14.03629709,0,118.6582214 +60.92,50.40705772,-3.429381402,10000,-95.93917003,175.4881968,0,14.03629709,0,118.6652474 +60.93,50.40704911,-3.429356756,10000,-95.96354113,175.4755461,0,14.03629709,0,118.6722732 +60.94,50.40704049,-3.429332111,10000,-95.98094902,175.4628954,0,14.03629709,0,118.6792992 +60.95,50.40703188,-3.429307469,10000,-95.99835691,175.4518023,0,14.03629709,0,118.6863251 +60.96,50.40702326,-3.429282827,10000,-96.02272802,175.4411541,0,14.03629709,0,118.693351 +60.97,50.40701464,-3.429258187,10000,-96.05058074,175.429171,0,14.03629709,0,118.7003769 +60.98,50.40700602,-3.429233549,10000,-96.07495185,175.4165203,0,14.03629709,0,118.7074029 +60.99,50.40699739,-3.429208913,10000,-96.09235974,175.4047597,0,14.03629709,0,118.7144288 +61,50.40698877,-3.429184278,10000,-96.10976764,175.3936665,0,14.03629709,0,118.7214547 +61.01,50.40698014,-3.429159645,10000,-96.13413876,175.3819059,0,14.03629709,0,118.7284806 +61.02,50.40697151,-3.429135013,10000,-96.16199148,175.3692552,0,14.03629709,0,118.7355066 +61.03,50.40696288,-3.429110384,10000,-96.18636258,175.3572721,0,14.03629709,0,118.7425325 +61.04,50.40695424,-3.429085756,10000,-96.20377046,175.346624,0,14.03629709,0,118.7495584 +61.05,50.40694561,-3.429061129,10000,-96.22117835,175.3355308,0,14.03629709,0,118.7565843 +61.06,50.40693697,-3.429036504,10000,-96.24206785,175.3228802,0,14.03629709,0,118.7636103 +61.07,50.40692833,-3.429011881,10000,-96.25947574,175.3100071,0,14.03629709,0,118.7706362 +61.08,50.40691969,-3.42898726,10000,-96.27688364,175.2982465,0,14.03629709,0,118.7776621 +61.09,50.40691105,-3.42896264,10000,-96.29777314,175.2871533,0,14.03629709,0,118.784688 +61.1,50.4069024,-3.428938022,10000,-96.31518103,175.2756152,0,14.03629709,0,118.791714 +61.11,50.40689376,-3.428913405,10000,-96.33607053,175.2636321,0,14.03629709,0,118.7987399 +61.12,50.40688511,-3.428888791,10000,-96.37088645,175.2518715,0,14.03629709,0,118.8057658 +61.13,50.40687646,-3.428864177,10000,-96.40570236,175.2401109,0,14.03629709,0,118.8127917 +61.14,50.4068678,-3.428839566,10000,-96.42311026,175.2279053,0,14.03629709,0,118.8198177 +61.15,50.40685915,-3.428814956,10000,-96.43007335,175.2154772,0,14.03629709,0,118.8268436 +61.16,50.40685049,-3.428790348,10000,-96.44748125,175.2032716,0,14.03629709,0,118.8338695 +61.17,50.40684184,-3.428765742,10000,-96.47881557,175.191511,0,14.03629709,0,118.8408954 +61.18,50.40683317,-3.428741137,10000,-96.50318666,175.1797504,0,14.03629709,0,118.8479213 +61.19,50.40682451,-3.428716534,10000,-96.51711295,175.1679898,0,14.03629709,0,118.8549473 +61.2,50.40681585,-3.428691933,10000,-96.54148405,175.1571192,0,14.03629709,0,118.8619732 +61.21,50.40680718,-3.428667333,10000,-96.57281837,175.1464711,0,14.03629709,0,118.8689991 +61.22,50.40679851,-3.428642734,10000,-96.59022625,175.134488,0,14.03629709,0,118.876025 +61.23,50.40678984,-3.428618138,10000,-96.59718932,175.1216149,0,14.03629709,0,118.883051 +61.24,50.40678117,-3.428593543,10000,-96.61459723,175.1091869,0,14.03629709,0,118.8900769 +61.25,50.4067725,-3.42856895,10000,-96.64941316,175.0976488,0,14.03629709,0,118.8971028 +61.26,50.40676382,-3.428544359,10000,-96.68422909,175.0863332,0,14.03629709,0,118.9041287 +61.27,50.40675514,-3.428519768,10000,-96.70163698,175.0743501,0,14.03629709,0,118.9111547 +61.28,50.40674646,-3.428495181,10000,-96.70860004,175.0623671,0,14.03629709,0,118.9181805 +61.29,50.40673778,-3.428470594,10000,-96.72252632,175.050829,0,14.03629709,0,118.9252065 +61.3,50.4067291,-3.428446009,10000,-96.74341583,175.0386234,0,14.03629709,0,118.9322324 +61.31,50.40672041,-3.428421426,10000,-96.76082373,175.0259729,0,14.03629709,0,118.9392583 +61.32,50.40671173,-3.428396845,10000,-96.78171321,175.0142123,0,14.03629709,0,118.9462842 +61.33,50.40670304,-3.428372265,10000,-96.81652912,175.0031193,0,14.03629709,0,118.9533102 +61.34,50.40669435,-3.428347687,10000,-96.85134505,174.9913587,0,14.03629709,0,118.9603361 +61.35,50.40668565,-3.42832311,10000,-96.87223456,174.9787082,0,14.03629709,0,118.967362 +61.36,50.40667696,-3.428298536,10000,-96.88964245,174.9667251,0,14.03629709,0,118.9743879 +61.37,50.40666826,-3.428273963,10000,-96.91053194,174.9560771,0,14.03629709,0,118.9814139 +61.38,50.40665956,-3.428249391,10000,-96.92793984,174.944984,0,14.03629709,0,118.9884398 +61.39,50.40665086,-3.428224821,10000,-96.94534773,174.9323335,0,14.03629709,0,118.9954657 +61.4,50.40664216,-3.428200253,10000,-96.96623721,174.9194605,0,14.03629709,0,119.0024916 +61.41,50.40663345,-3.428175687,10000,-96.98364509,174.9074774,0,14.03629709,0,119.0095176 +61.42,50.40662475,-3.428151122,10000,-97.00105298,174.8957169,0,14.03629709,0,119.0165435 +61.43,50.40661604,-3.428126559,10000,-97.0254241,174.8837339,0,14.03629709,0,119.0235694 +61.44,50.40660733,-3.428101998,10000,-97.05327682,174.8719733,0,14.03629709,0,119.0305953 +61.45,50.40659862,-3.428077438,10000,-97.07764792,174.8602128,0,14.03629709,0,119.0376213 +61.46,50.4065899,-3.42805288,10000,-97.09505581,174.8482298,0,14.03629709,0,119.0446472 +61.47,50.40658119,-3.428028324,10000,-97.1124637,174.8364693,0,14.03629709,0,119.0516731 +61.48,50.40657247,-3.428003769,10000,-97.1368348,174.8247088,0,14.03629709,0,119.058699 +61.49,50.40656375,-3.427979216,10000,-97.16468749,174.8127258,0,14.03629709,0,119.065725 +61.5,50.40655503,-3.427954665,10000,-97.1890586,174.8009653,0,14.03629709,0,119.0727509 +61.51,50.4065463,-3.427930115,10000,-97.20646649,174.7892047,0,14.03629709,0,119.0797768 +61.52,50.40653758,-3.427905567,10000,-97.22387439,174.7769992,0,14.03629709,0,119.0868027 +61.53,50.40652885,-3.427881021,10000,-97.24824549,174.7645712,0,14.03629709,0,119.0938287 +61.54,50.40652012,-3.427856476,10000,-97.2760982,174.7523657,0,14.03629709,0,119.1008546 +61.55,50.40651139,-3.427831934,10000,-97.3004693,174.7406052,0,14.03629709,0,119.1078805 +61.56,50.40650265,-3.427807392,10000,-97.31787719,174.7288448,0,14.03629709,0,119.1149064 +61.57,50.40649392,-3.427782853,10000,-97.33528508,174.7168618,0,14.03629709,0,119.1219324 +61.58,50.40648518,-3.427758315,10000,-97.35617457,174.7051013,0,14.03629709,0,119.1289583 +61.59,50.40647644,-3.427733779,10000,-97.37358245,174.6931183,0,14.03629709,0,119.1359841 +61.6,50.4064677,-3.427709244,10000,-97.39447194,174.6804678,0,14.03629709,0,119.1430101 +61.61,50.40645896,-3.427684712,10000,-97.42928786,174.6684848,0,14.03629709,0,119.150036 +61.62,50.40645021,-3.427660181,10000,-97.4641038,174.6578369,0,14.03629709,0,119.1570619 +61.63,50.40644146,-3.427635651,10000,-97.4815117,174.6469664,0,14.03629709,0,119.1640878 +61.64,50.40643271,-3.427611123,10000,-97.48499316,174.6349834,0,14.03629709,0,119.1711138 +61.65,50.40642396,-3.427586597,10000,-97.48847461,174.622333,0,14.03629709,0,119.1781397 +61.66,50.40641521,-3.427562072,10000,-97.50588249,174.6092375,0,14.03629709,0,119.1851656 +61.67,50.40640646,-3.42753755,10000,-97.5406984,174.5963645,0,14.03629709,0,119.1921915 +61.68,50.4063977,-3.427513029,10000,-97.57551432,174.584604,0,14.03629709,0,119.1992175 +61.69,50.40638894,-3.42748851,10000,-97.59640382,174.5737336,0,14.03629709,0,119.2062434 +61.7,50.40638018,-3.427463992,10000,-97.61381172,174.5628632,0,14.03629709,0,119.2132693 +61.71,50.40637142,-3.427439476,10000,-97.63470122,174.5511027,0,14.03629709,0,119.2202952 +61.72,50.40636265,-3.427414961,10000,-97.6521091,174.5382297,0,14.03629709,0,119.2273212 +61.73,50.40635389,-3.427390449,10000,-97.66951698,174.5251343,0,14.03629709,0,119.2343471 +61.74,50.40634512,-3.427365938,10000,-97.69388807,174.5124838,0,14.03629709,0,119.241373 +61.75,50.40633635,-3.427341429,10000,-97.72174077,174.5005009,0,14.03629709,0,119.2483989 +61.76,50.40632758,-3.427316922,10000,-97.74611187,174.4896305,0,14.03629709,0,119.2554249 +61.77,50.4063188,-3.427292416,10000,-97.76351978,174.4789825,0,14.03629709,0,119.2624508 +61.78,50.40631003,-3.427267911,10000,-97.78092767,174.4669996,0,14.03629709,0,119.2694767 +61.79,50.40630125,-3.427243409,10000,-97.80181716,174.4543492,0,14.03629709,0,119.2765026 +61.8,50.40629247,-3.427218908,10000,-97.81922503,174.4423662,0,14.03629709,0,119.2835286 +61.81,50.40628369,-3.427194409,10000,-97.84011453,174.4303833,0,14.03629709,0,119.2905545 +61.82,50.40627491,-3.427169911,10000,-97.87493044,174.4175104,0,14.03629709,0,119.2975804 +61.83,50.40626612,-3.427145416,10000,-97.90974636,174.4046374,0,14.03629709,0,119.3046063 +61.84,50.40625733,-3.427120922,10000,-97.92715426,174.392877,0,14.03629709,0,119.3116323 +61.85,50.40624854,-3.42709643,10000,-97.93411733,174.3817841,0,14.03629709,0,119.3186582 +61.86,50.40623975,-3.427071939,10000,-97.94804359,174.3702462,0,14.03629709,0,119.3256841 +61.87,50.40623096,-3.42704745,10000,-97.96893308,174.3582633,0,14.03629709,0,119.33271 +61.88,50.40622216,-3.427022963,10000,-97.98634098,174.3465029,0,14.03629709,0,119.339736 +61.89,50.40621337,-3.426998477,10000,-98.00723048,174.3347425,0,14.03629709,0,119.3467619 +61.9,50.40620457,-3.426973993,10000,-98.04204639,174.3227596,0,14.03629709,0,119.3537878 +61.91,50.40619577,-3.426949511,10000,-98.0768623,174.3107767,0,14.03629709,0,119.3608137 +61.92,50.40618696,-3.42692503,10000,-98.09427018,174.2981263,0,14.03629709,0,119.3678397 +61.93,50.40617816,-3.426900551,10000,-98.10123326,174.2850309,0,14.03629709,0,119.3748656 +61.94,50.40616935,-3.426876075,10000,-98.11864115,174.273048,0,14.03629709,0,119.3818915 +61.95,50.40616055,-3.426851599,10000,-98.14997545,174.2615101,0,14.03629709,0,119.3889174 +61.96,50.40615173,-3.426827125,10000,-98.17434654,174.2493047,0,14.03629709,0,119.3959434 +61.97,50.40614292,-3.426802654,10000,-98.18827281,174.2377668,0,14.03629709,0,119.4029692 +61.98,50.40613411,-3.426778183,10000,-98.21264392,174.2268964,0,14.03629709,0,119.4099951 +61.99,50.40612529,-3.426753714,10000,-98.24397824,174.2149136,0,14.03629709,0,119.4170211 +62,50.40611647,-3.426729247,10000,-98.26138613,174.2020407,0,14.03629709,0,119.424047 +62.01,50.40610765,-3.426704782,10000,-98.2683492,174.1893903,0,14.03629709,0,119.4310729 +62.02,50.40609883,-3.426680318,10000,-98.28575707,174.1771849,0,14.03629709,0,119.4380988 +62.03,50.40609001,-3.426655857,10000,-98.31709137,174.1654245,0,14.03629709,0,119.4451248 +62.04,50.40608118,-3.426631396,10000,-98.34146247,174.1536642,0,14.03629709,0,119.4521507 +62.05,50.40607235,-3.426606938,10000,-98.35538875,174.1414588,0,14.03629709,0,119.4591766 +62.06,50.40606353,-3.426582481,10000,-98.37627825,174.1288084,0,14.03629709,0,119.4662025 +62.07,50.40605469,-3.426558026,10000,-98.39716773,174.115713,0,14.03629709,0,119.4732285 +62.08,50.40604586,-3.426533573,10000,-98.411094,174.1030627,0,14.03629709,0,119.4802544 +62.09,50.40603703,-3.426509122,10000,-98.43546509,174.0919698,0,14.03629709,0,119.4872803 +62.1,50.40602819,-3.426484672,10000,-98.46679941,174.081322,0,14.03629709,0,119.4943062 +62.11,50.40601935,-3.426460223,10000,-98.4876889,174.0695616,0,14.03629709,0,119.5013322 +62.12,50.40601051,-3.426435777,10000,-98.50857839,174.0575788,0,14.03629709,0,119.5083581 +62.13,50.40600167,-3.426411332,10000,-98.54339431,174.0458185,0,14.03629709,0,119.515384 +62.14,50.40599282,-3.426386888,10000,-98.57821023,174.0329456,0,14.03629709,0,119.5224099 +62.15,50.40598397,-3.426362447,10000,-98.59561812,174.0198502,0,14.03629709,0,119.5294359 +62.16,50.40597512,-3.426338008,10000,-98.59909957,174.0083124,0,14.03629709,0,119.5364618 +62.17,50.40596627,-3.426313569,10000,-98.60258103,173.9969971,0,14.03629709,0,119.5434877 +62.18,50.40595742,-3.426289133,10000,-98.61998891,173.9843467,0,14.03629709,0,119.5505136 +62.19,50.40594857,-3.426264698,10000,-98.65480483,173.9714739,0,14.03629709,0,119.5575396 +62.2,50.40593971,-3.426240266,10000,-98.68962074,173.9594911,0,14.03629709,0,119.5645655 +62.21,50.40593085,-3.426215834,10000,-98.70702861,173.9477308,0,14.03629709,0,119.5715914 +62.22,50.40592199,-3.426191405,10000,-98.71399166,173.9355254,0,14.03629709,0,119.5786173 +62.23,50.40591313,-3.426166977,10000,-98.73139955,173.9230976,0,14.03629709,0,119.5856433 +62.24,50.40590427,-3.426142551,10000,-98.76621547,173.9108923,0,14.03629709,0,119.5926692 +62.25,50.4058954,-3.426118127,10000,-98.8010314,173.899132,0,14.03629709,0,119.5996951 +62.26,50.40588653,-3.426093704,10000,-98.81843928,173.8873717,0,14.03629709,0,119.606721 +62.27,50.40587766,-3.426069283,10000,-98.82540234,173.8753888,0,14.03629709,0,119.613747 +62.28,50.40586879,-3.426044864,10000,-98.84281022,173.8636285,0,14.03629709,0,119.6207728 +62.29,50.40585992,-3.426020446,10000,-98.87762613,173.8518682,0,14.03629709,0,119.6277988 +62.3,50.40585104,-3.42599603,10000,-98.91244203,173.8396629,0,14.03629709,0,119.6348247 +62.31,50.40584216,-3.425971616,10000,-98.92984991,173.8272351,0,14.03629709,0,119.6418506 +62.32,50.40583328,-3.425947203,10000,-98.93333138,173.8150298,0,14.03629709,0,119.6488765 +62.33,50.4058244,-3.425922793,10000,-98.93681285,173.803047,0,14.03629709,0,119.6559025 +62.34,50.40581552,-3.425898383,10000,-98.95422072,173.7903967,0,14.03629709,0,119.6629284 +62.35,50.40580664,-3.425873976,10000,-98.98903662,173.7770789,0,14.03629709,0,119.6699543 +62.36,50.40579775,-3.425849571,10000,-99.02385254,173.7646511,0,14.03629709,0,119.6769802 +62.37,50.40578886,-3.425825167,10000,-99.04474203,173.7535583,0,14.03629709,0,119.6840062 +62.38,50.40577997,-3.425800765,10000,-99.06563151,173.7426881,0,14.03629709,0,119.6910321 +62.39,50.40577108,-3.425776364,10000,-99.09696581,173.7309278,0,14.03629709,0,119.698058 +62.4,50.40576218,-3.425751965,10000,-99.1178553,173.718055,0,14.03629709,0,119.7050839 +62.41,50.40575328,-3.425727568,10000,-99.12133677,173.7051822,0,14.03629709,0,119.7121098 +62.42,50.40574439,-3.425703173,10000,-99.13874466,173.6931994,0,14.03629709,0,119.7191358 +62.43,50.40573549,-3.425678779,10000,-99.17704216,173.6814392,0,14.03629709,0,119.7261617 +62.44,50.40572658,-3.425654387,10000,-99.20489486,173.6692339,0,14.03629709,0,119.7331876 +62.45,50.40571768,-3.425629997,10000,-99.21185793,173.6568061,0,14.03629709,0,119.7402135 +62.46,50.40570877,-3.425605608,10000,-99.21882098,173.6446008,0,14.03629709,0,119.7472395 +62.47,50.40569987,-3.425581222,10000,-99.24667368,173.6328406,0,14.03629709,0,119.7542654 +62.48,50.40569096,-3.425556836,10000,-99.28845281,173.6210803,0,14.03629709,0,119.7612913 +62.49,50.40568204,-3.425532453,10000,-99.31630552,173.6088751,0,14.03629709,0,119.7683172 +62.5,50.40567313,-3.425508071,10000,-99.32326858,173.5962248,0,14.03629709,0,119.7753432 +62.51,50.40566421,-3.425483691,10000,-99.32675002,173.5831295,0,14.03629709,0,119.7823691 +62.52,50.4056553,-3.425459313,10000,-99.34415789,173.5702567,0,14.03629709,0,119.789395 +62.53,50.40564638,-3.425434937,10000,-99.3789738,173.558274,0,14.03629709,0,119.7964209 +62.54,50.40563746,-3.425410562,10000,-99.41378971,173.5465137,0,14.03629709,0,119.8034469 +62.55,50.40562853,-3.425386189,10000,-99.4346792,173.534531,0,14.03629709,0,119.8104728 +62.56,50.40561961,-3.425361818,10000,-99.45208708,173.5227708,0,14.03629709,0,119.8174987 +62.57,50.40561068,-3.425337448,10000,-99.47297657,173.510788,0,14.03629709,0,119.8245246 +62.58,50.40560175,-3.42531308,10000,-99.49038446,173.4979153,0,14.03629709,0,119.8315506 +62.59,50.40559282,-3.425288714,10000,-99.50779233,173.4850425,0,14.03629709,0,119.8385765 +62.6,50.40558389,-3.42526435,10000,-99.52868182,173.4732823,0,14.03629709,0,119.8456024 +62.61,50.40557495,-3.425239987,10000,-99.54608969,173.4621896,0,14.03629709,0,119.8526283 +62.62,50.40556602,-3.425215626,10000,-99.56697918,173.4504294,0,14.03629709,0,119.8596543 +62.63,50.40555708,-3.425191266,10000,-99.60179509,173.4375566,0,14.03629709,0,119.8666801 +62.64,50.40554814,-3.425166909,10000,-99.63661101,173.4246839,0,14.03629709,0,119.8737061 +62.65,50.40553919,-3.425142553,10000,-99.65401889,173.4127012,0,14.03629709,0,119.880732 +62.66,50.40553025,-3.425118199,10000,-99.66098194,173.4007185,0,14.03629709,0,119.8877579 +62.67,50.4055213,-3.425093846,10000,-99.6783898,173.3880682,0,14.03629709,0,119.8947838 +62.68,50.40551236,-3.425069496,10000,-99.70972411,173.375863,0,14.03629709,0,119.9018098 +62.69,50.4055034,-3.425045147,10000,-99.73409521,173.3643253,0,14.03629709,0,119.9088357 +62.7,50.40549445,-3.425020799,10000,-99.74453988,173.3521201,0,14.03629709,0,119.9158616 +62.71,50.4054855,-3.424996454,10000,-99.75498453,173.3392474,0,14.03629709,0,119.9228875 +62.72,50.40547654,-3.42497211,10000,-99.7723924,173.3265971,0,14.03629709,0,119.9299135 +62.73,50.40546759,-3.424947768,10000,-99.80372671,173.3143919,0,14.03629709,0,119.9369394 +62.74,50.40545863,-3.424923428,10000,-99.84202424,173.3026318,0,14.03629709,0,119.9439653 +62.75,50.40544966,-3.424899089,10000,-99.85943212,173.2908716,0,14.03629709,0,119.9509912 +62.76,50.4054407,-3.424874752,10000,-99.86291356,173.2788889,0,14.03629709,0,119.9580172 +62.77,50.40543174,-3.424850417,10000,-99.88380304,173.2671287,0,14.03629709,0,119.9650431 +62.78,50.40542277,-3.424826083,10000,-99.91513734,173.255146,0,14.03629709,0,119.972069 +62.79,50.4054138,-3.424801751,10000,-99.93602682,173.2422733,0,14.03629709,0,119.9790949 +62.8,50.40540483,-3.424777421,10000,-99.95691631,173.2294006,0,14.03629709,0,119.9861208 +62.81,50.40539586,-3.424753093,10000,-99.98825061,173.2171954,0,14.03629709,0,119.9931468 +62.82,50.40538688,-3.424728766,10000,-100.0126217,173.2045452,0,14.03629709,0,120.0001727 +62.83,50.4053779,-3.424704441,10000,-100.026548,173.1912275,0,14.03629709,0,120.0071986 +62.84,50.40536893,-3.424680119,10000,-100.0474375,173.1787998,0,14.03629709,0,120.0142245 +62.85,50.40535994,-3.424655797,10000,-100.0683269,173.1677072,0,14.03629709,0,120.0212505 +62.86,50.40535096,-3.424631478,10000,-100.0822532,173.1566145,0,14.03629709,0,120.0282764 +62.87,50.40534198,-3.424607159,10000,-100.1066243,173.1441868,0,14.03629709,0,120.0353023 +62.88,50.40533299,-3.424582843,10000,-100.1379586,173.1308691,0,14.03629709,0,120.0423282 +62.89,50.405324,-3.424558529,10000,-100.1553665,173.118219,0,14.03629709,0,120.0493542 +62.9,50.40531501,-3.424534216,10000,-100.1623295,173.1062363,0,14.03629709,0,120.0563801 +62.91,50.40530602,-3.424509905,10000,-100.1797374,173.0942536,0,14.03629709,0,120.063406 +62.92,50.40529703,-3.424485596,10000,-100.2145533,173.0824935,0,14.03629709,0,120.0704319 +62.93,50.40528803,-3.424461288,10000,-100.2493692,173.0705108,0,14.03629709,0,120.0774579 +62.94,50.40527903,-3.424436982,10000,-100.2667771,173.0576382,0,14.03629709,0,120.0844838 +62.95,50.40527003,-3.424412678,10000,-100.2737402,173.0447655,0,14.03629709,0,120.0915097 +62.96,50.40526103,-3.424388376,10000,-100.2876664,173.0327828,0,14.03629709,0,120.0985356 +62.97,50.40525203,-3.424364075,10000,-100.3085559,173.0208002,0,14.03629709,0,120.1055615 +62.98,50.40524302,-3.424339776,10000,-100.3259638,173.0079275,0,14.03629709,0,120.1125874 +62.99,50.40523402,-3.424315479,10000,-100.3468532,172.9950548,0,14.03629709,0,120.1196134 +63,50.40522501,-3.424291184,10000,-100.3816691,172.9830722,0,14.03629709,0,120.1266393 +63.01,50.405216,-3.42426689,10000,-100.4164851,172.9713121,0,14.03629709,0,120.1336652 +63.02,50.40520698,-3.424242598,10000,-100.4373746,172.9591069,0,14.03629709,0,120.1406911 +63.03,50.40519797,-3.424218308,10000,-100.4547824,172.9466793,0,14.03629709,0,120.1477171 +63.04,50.40518895,-3.424194019,10000,-100.4756719,172.9344742,0,14.03629709,0,120.154743 +63.05,50.40517993,-3.424169733,10000,-100.4895982,172.9224916,0,14.03629709,0,120.1617689 +63.06,50.40517091,-3.424145447,10000,-100.4965612,172.9100639,0,14.03629709,0,120.1687948 +63.07,50.40516189,-3.424121164,10000,-100.5139691,172.8974138,0,14.03629709,0,120.1758208 +63.08,50.40515287,-3.424096883,10000,-100.548785,172.8852086,0,14.03629709,0,120.1828467 +63.09,50.40514384,-3.424072602,10000,-100.5836009,172.872781,0,14.03629709,0,120.1898726 +63.1,50.40513481,-3.424048325,10000,-100.6010088,172.8599084,0,14.03629709,0,120.1968985 +63.11,50.40512578,-3.424024048,10000,-100.6079719,172.8474807,0,14.03629709,0,120.2039245 +63.12,50.40511675,-3.423999774,10000,-100.6253797,172.8359431,0,14.03629709,0,120.2109504 +63.13,50.40510772,-3.423975501,10000,-100.6601956,172.8246281,0,14.03629709,0,120.2179763 +63.14,50.40509868,-3.423951229,10000,-100.6950115,172.812423,0,14.03629709,0,120.2250022 +63.15,50.40508964,-3.42392696,10000,-100.7124194,172.7995503,0,14.03629709,0,120.2320282 +63.16,50.4050806,-3.423902692,10000,-100.7193824,172.7866777,0,14.03629709,0,120.2390541 +63.17,50.40507156,-3.423878426,10000,-100.7333087,172.7735825,0,14.03629709,0,120.24608 +63.18,50.40506252,-3.423854162,10000,-100.7541982,172.7607099,0,14.03629709,0,120.2531059 +63.19,50.40505347,-3.4238299,10000,-100.7716061,172.7487273,0,14.03629709,0,120.2601318 +63.2,50.40504443,-3.423805639,10000,-100.7924956,172.7367447,0,14.03629709,0,120.2671578 +63.21,50.40503538,-3.42378138,10000,-100.8273114,172.7238721,0,14.03629709,0,120.2741837 +63.22,50.40502633,-3.423757123,10000,-100.8621273,172.7109995,0,14.03629709,0,120.2812096 +63.23,50.40501727,-3.423732868,10000,-100.8830168,172.6990169,0,14.03629709,0,120.2882355 +63.24,50.40500822,-3.423708614,10000,-100.9004247,172.6872568,0,14.03629709,0,120.2952615 +63.25,50.40499916,-3.423684362,10000,-100.9213142,172.6752743,0,14.03629709,0,120.3022874 +63.26,50.4049901,-3.423660112,10000,-100.9352405,172.6635142,0,14.03629709,0,120.3093133 +63.27,50.40498104,-3.423635863,10000,-100.9422035,172.6515316,0,14.03629709,0,120.3163392 +63.28,50.40497198,-3.423611616,10000,-100.9596114,172.6384365,0,14.03629709,0,120.3233652 +63.29,50.40496292,-3.423587371,10000,-100.9944273,172.6248964,0,14.03629709,0,120.330391 +63.3,50.40495385,-3.423563128,10000,-101.0292432,172.6124688,0,14.03629709,0,120.337417 +63.31,50.40494478,-3.423538887,10000,-101.0466511,172.6009312,0,14.03629709,0,120.3444429 +63.32,50.40493571,-3.423514646,10000,-101.0536141,172.5889487,0,14.03629709,0,120.3514688 +63.33,50.40492664,-3.423490409,10000,-101.071022,172.5767436,0,14.03629709,0,120.3584947 +63.34,50.40491757,-3.423466172,10000,-101.1058379,172.564316,0,14.03629709,0,120.3655207 +63.35,50.40490849,-3.423441937,10000,-101.1406538,172.5507759,0,14.03629709,0,120.3725466 +63.36,50.40489941,-3.423417705,10000,-101.1580617,172.5372358,0,14.03629709,0,120.3795725 +63.37,50.40489033,-3.423393474,10000,-101.1650247,172.5252532,0,14.03629709,0,120.3865984 +63.38,50.40488125,-3.423369245,10000,-101.178951,172.5141607,0,14.03629709,0,120.3936244 +63.39,50.40487217,-3.423345017,10000,-101.1998405,172.5024007,0,14.03629709,0,120.4006503 +63.4,50.40486308,-3.423320791,10000,-101.2172483,172.4895281,0,14.03629709,0,120.4076762 +63.41,50.404854,-3.423296567,10000,-101.2381378,172.4766555,0,14.03629709,0,120.4147021 +63.42,50.40484491,-3.423272345,10000,-101.2729537,172.464673,0,14.03629709,0,120.4217281 +63.43,50.40483582,-3.423248124,10000,-101.3077696,172.4526904,0,14.03629709,0,120.428754 +63.44,50.40482672,-3.423223905,10000,-101.3286591,172.4398179,0,14.03629709,0,120.4357799 +63.45,50.40481763,-3.423199688,10000,-101.346067,172.4269453,0,14.03629709,0,120.4428058 +63.46,50.40480853,-3.423175473,10000,-101.3669564,172.4147403,0,14.03629709,0,120.4498318 +63.47,50.40479943,-3.423151259,10000,-101.3808827,172.4020902,0,14.03629709,0,120.4568577 +63.48,50.40479033,-3.423127047,10000,-101.3878457,172.3887726,0,14.03629709,0,120.4638836 +63.49,50.40478123,-3.423102838,10000,-101.4052536,172.3763451,0,14.03629709,0,120.4709095 +63.5,50.40477213,-3.423078629,10000,-101.4400695,172.3650301,0,14.03629709,0,120.4779355 +63.51,50.40476302,-3.423054423,10000,-101.4748854,172.3532701,0,14.03629709,0,120.4849614 +63.52,50.40475391,-3.423030217,10000,-101.4922933,172.3403975,0,14.03629709,0,120.4919873 +63.53,50.4047448,-3.423006015,10000,-101.4992563,172.3273024,0,14.03629709,0,120.4990132 +63.54,50.40473569,-3.422981813,10000,-101.5166642,172.3146524,0,14.03629709,0,120.5060392 +63.55,50.40472658,-3.422957614,10000,-101.5479985,172.3024474,0,14.03629709,0,120.5130651 +63.56,50.40471746,-3.422933416,10000,-101.5723696,172.2906874,0,14.03629709,0,120.520091 +63.57,50.40470834,-3.42290922,10000,-101.5862958,172.2787049,0,14.03629709,0,120.5271169 +63.58,50.40469923,-3.422885025,10000,-101.6071853,172.2658323,0,14.03629709,0,120.5341429 +63.59,50.4046901,-3.422860833,10000,-101.6280748,172.2527372,0,14.03629709,0,120.5411688 +63.6,50.40468098,-3.422836642,10000,-101.6420011,172.2400872,0,14.03629709,0,120.5481947 +63.61,50.40467186,-3.422812453,10000,-101.6663721,172.2278822,0,14.03629709,0,120.5552206 +63.62,50.40466273,-3.422788266,10000,-101.6977064,172.2158997,0,14.03629709,0,120.5622465 +63.63,50.4046536,-3.42276408,10000,-101.7185959,172.2032497,0,14.03629709,0,120.5692725 +63.64,50.40464447,-3.422739896,10000,-101.7360038,172.1899321,0,14.03629709,0,120.5762983 +63.65,50.40463534,-3.422715715,10000,-101.7568932,172.1772821,0,14.03629709,0,120.5833243 +63.66,50.4046262,-3.422691534,10000,-101.7743011,172.1652996,0,14.03629709,0,120.5903502 +63.67,50.40461707,-3.422667356,10000,-101.791709,172.1530946,0,14.03629709,0,120.5973761 +63.68,50.40460793,-3.422643179,10000,-101.8160801,172.1406671,0,14.03629709,0,120.604402 +63.69,50.40459879,-3.422619004,10000,-101.8439327,172.1282396,0,14.03629709,0,120.611428 +63.7,50.40458965,-3.422594831,10000,-101.8683038,172.1155896,0,14.03629709,0,120.6184539 +63.71,50.4045805,-3.422570659,10000,-101.8857117,172.1024946,0,14.03629709,0,120.6254798 +63.72,50.40457136,-3.42254649,10000,-101.9031196,172.089622,0,14.03629709,0,120.6325057 +63.73,50.40456221,-3.422522322,10000,-101.9274906,172.0778621,0,14.03629709,0,120.6395317 +63.74,50.40455306,-3.422498156,10000,-101.9553433,172.0667696,0,14.03629709,0,120.6465576 +63.75,50.40454391,-3.422473991,10000,-101.9797144,172.0547872,0,14.03629709,0,120.6535835 +63.76,50.40453475,-3.422449828,10000,-101.9971223,172.0410246,0,14.03629709,0,120.6606094 +63.77,50.4045256,-3.422425667,10000,-102.0145302,172.026817,0,14.03629709,0,120.6676354 +63.78,50.40451644,-3.422401509,10000,-102.0354196,172.0141671,0,14.03629709,0,120.6746613 +63.79,50.40450728,-3.422377351,10000,-102.0528275,172.0028521,0,14.03629709,0,120.6816872 +63.8,50.40449812,-3.422353196,10000,-102.0702353,171.9910922,0,14.03629709,0,120.6887131 +63.81,50.40448896,-3.422329041,10000,-102.0911248,171.9784422,0,14.03629709,0,120.6957391 +63.82,50.40447979,-3.42230489,10000,-102.1085327,171.9660147,0,14.03629709,0,120.702765 +63.83,50.40447063,-3.422280739,10000,-102.1294222,171.9535872,0,14.03629709,0,120.7097909 +63.84,50.40446146,-3.42225659,10000,-102.1642381,171.9402697,0,14.03629709,0,120.7168168 +63.85,50.40445229,-3.422232444,10000,-102.199054,171.9273972,0,14.03629709,0,120.7238428 +63.86,50.40444311,-3.422208299,10000,-102.2164618,171.9156373,0,14.03629709,0,120.7308687 +63.87,50.40443394,-3.422184155,10000,-102.2199433,171.9034323,0,14.03629709,0,120.7378946 +63.88,50.40442476,-3.422160014,10000,-102.2269063,171.8905598,0,14.03629709,0,120.7449205 +63.89,50.40441559,-3.422135874,10000,-102.254759,171.8776874,0,14.03629709,0,120.7519465 +63.9,50.40440641,-3.422111736,10000,-102.2965381,171.8645924,0,14.03629709,0,120.7589724 +63.91,50.40439722,-3.4220876,10000,-102.3243908,171.8517199,0,14.03629709,0,120.7659983 +63.92,50.40438804,-3.422063466,10000,-102.3313538,171.8397375,0,14.03629709,0,120.7730242 +63.93,50.40437885,-3.422039333,10000,-102.3348353,171.8279775,0,14.03629709,0,120.7800502 +63.94,50.40436967,-3.422015202,10000,-102.3522432,171.8157726,0,14.03629709,0,120.7870761 +63.95,50.40436048,-3.421991073,10000,-102.387059,171.8031226,0,14.03629709,0,120.794102 +63.96,50.40435129,-3.421966945,10000,-102.4218749,171.7900276,0,14.03629709,0,120.8011279 +63.97,50.40434209,-3.42194282,10000,-102.4427644,171.7771552,0,14.03629709,0,120.8081539 +63.98,50.4043329,-3.421918696,10000,-102.4601723,171.7651727,0,14.03629709,0,120.8151797 +63.99,50.4043237,-3.421894574,10000,-102.4810618,171.7531903,0,14.03629709,0,120.8222056 +64,50.4043145,-3.421870453,10000,-102.494988,171.7403179,0,14.03629709,0,120.8292316 +64.01,50.4043053,-3.421846335,10000,-102.5019511,171.7272229,0,14.03629709,0,120.8362575 +64.02,50.4042961,-3.421822218,10000,-102.5193589,171.7143504,0,14.03629709,0,120.8432834 +64.03,50.4042869,-3.421798103,10000,-102.5541748,171.7012554,0,14.03629709,0,120.8503093 +64.04,50.40427769,-3.42177399,10000,-102.5889907,171.688383,0,14.03629709,0,120.8573353 +64.05,50.40426848,-3.421749879,10000,-102.6098802,171.6764006,0,14.03629709,0,120.8643612 +64.06,50.40425927,-3.421725769,10000,-102.627288,171.6644182,0,14.03629709,0,120.8713871 +64.07,50.40425006,-3.421701661,10000,-102.6481775,171.6515457,0,14.03629709,0,120.878413 +64.08,50.40424084,-3.421677555,10000,-102.6655854,171.6386733,0,14.03629709,0,120.885439 +64.09,50.40423163,-3.421653451,10000,-102.6829932,171.6266909,0,14.03629709,0,120.8924649 +64.1,50.40422241,-3.421629348,10000,-102.7038827,171.6147085,0,14.03629709,0,120.8994908 +64.11,50.40421319,-3.421605247,10000,-102.7212906,171.6016135,0,14.03629709,0,120.9065167 +64.12,50.40420397,-3.421581148,10000,-102.74218,171.587851,0,14.03629709,0,120.9135427 +64.13,50.40419475,-3.421557051,10000,-102.7769959,171.5747561,0,14.03629709,0,120.9205686 +64.14,50.40418552,-3.421532956,10000,-102.8118118,171.5627737,0,14.03629709,0,120.9275945 +64.15,50.40417629,-3.421508862,10000,-102.8292197,171.5507913,0,14.03629709,0,120.9346204 +64.16,50.40416706,-3.42148477,10000,-102.8327011,171.5381414,0,14.03629709,0,120.9416464 +64.17,50.40415783,-3.42146068,10000,-102.8361826,171.5259365,0,14.03629709,0,120.9486723 +64.18,50.4041486,-3.421436592,10000,-102.8535905,171.5141766,0,14.03629709,0,120.9556982 +64.19,50.40413937,-3.421412504,10000,-102.8884063,171.5010817,0,14.03629709,0,120.9627241 +64.2,50.40413013,-3.42138842,10000,-102.9232222,171.4870967,0,14.03629709,0,120.9697501 +64.21,50.40412089,-3.421364337,10000,-102.9441117,171.4744468,0,14.03629709,0,120.976776 +64.22,50.40411165,-3.421340256,10000,-102.9615196,171.4631319,0,14.03629709,0,120.9838019 +64.23,50.40410241,-3.421316176,10000,-102.982409,171.4513721,0,14.03629709,0,120.9908278 +64.24,50.40409316,-3.421292098,10000,-102.9998169,171.4382771,0,14.03629709,0,120.9978538 +64.25,50.40408392,-3.421268022,10000,-103.0172248,171.4245147,0,14.03629709,0,121.0048797 +64.26,50.40407467,-3.421243948,10000,-103.0415958,171.4114197,0,14.03629709,0,121.0119056 +64.27,50.40406542,-3.421219876,10000,-103.0694485,171.3992149,0,14.03629709,0,121.0189315 +64.28,50.40405617,-3.421195805,10000,-103.0938196,171.386565,0,14.03629709,0,121.0259575 +64.29,50.40404691,-3.421171736,10000,-103.1112274,171.37347,0,14.03629709,0,121.0329834 +64.3,50.40403766,-3.42114767,10000,-103.1286353,171.3614877,0,14.03629709,0,121.0400093 +64.31,50.4040284,-3.421123604,10000,-103.1495248,171.3497278,0,14.03629709,0,121.0470352 +64.32,50.40401914,-3.42109954,10000,-103.1669326,171.3364104,0,14.03629709,0,121.0540612 +64.33,50.40400988,-3.421075479,10000,-103.1843405,171.3228705,0,14.03629709,0,121.061087 +64.34,50.40400062,-3.421051419,10000,-103.20523,171.3106656,0,14.03629709,0,121.068113 +64.35,50.40399135,-3.421027361,10000,-103.2226378,171.2986833,0,14.03629709,0,121.0751389 +64.36,50.40398209,-3.421003304,10000,-103.2435273,171.2858109,0,14.03629709,0,121.0821648 +64.37,50.40397282,-3.42097925,10000,-103.2783432,171.2727159,0,14.03629709,0,121.0891907 +64.38,50.40396355,-3.420955197,10000,-103.3131591,171.2598435,0,14.03629709,0,121.0962167 +64.39,50.40395427,-3.420931146,10000,-103.3305669,171.2467486,0,14.03629709,0,121.1032426 +64.4,50.403945,-3.420907097,10000,-103.3340484,171.2338763,0,14.03629709,0,121.1102685 +64.41,50.40393572,-3.42088305,10000,-103.3410114,171.2218939,0,14.03629709,0,121.1172944 +64.42,50.40392645,-3.420859004,10000,-103.3688641,171.2101341,0,14.03629709,0,121.1243203 +64.43,50.40391717,-3.42083496,10000,-103.4106432,171.1979293,0,14.03629709,0,121.1313463 +64.44,50.40390788,-3.420810918,10000,-103.4384959,171.1852794,0,14.03629709,0,121.1383722 +64.45,50.4038986,-3.420786877,10000,-103.4454589,171.1721845,0,14.03629709,0,121.1453981 +64.46,50.40388931,-3.420762839,10000,-103.4489404,171.1590896,0,14.03629709,0,121.152424 +64.47,50.40388003,-3.420738802,10000,-103.4663482,171.1462172,0,14.03629709,0,121.15945 +64.48,50.40387074,-3.420714767,10000,-103.5011641,171.1331223,0,14.03629709,0,121.1664759 +64.49,50.40386145,-3.420690734,10000,-103.53598,171.1200274,0,14.03629709,0,121.1735018 +64.5,50.40385215,-3.420666703,10000,-103.5568695,171.1073776,0,14.03629709,0,121.1805277 +64.51,50.40384286,-3.420642673,10000,-103.5742773,171.0951727,0,14.03629709,0,121.1875537 +64.52,50.40383356,-3.420618646,10000,-103.5951668,171.0831904,0,14.03629709,0,121.1945796 +64.53,50.40382426,-3.420594619,10000,-103.6125746,171.0705406,0,14.03629709,0,121.2016055 +64.54,50.40381496,-3.420570595,10000,-103.6299825,171.0570007,0,14.03629709,0,121.2086314 +64.55,50.40380566,-3.420546573,10000,-103.650872,171.0436833,0,14.03629709,0,121.2156574 +64.56,50.40379635,-3.420522552,10000,-103.6682798,171.0312559,0,14.03629709,0,121.2226833 +64.57,50.40378705,-3.420498534,10000,-103.6856877,171.0192736,0,14.03629709,0,121.2297092 +64.58,50.40377774,-3.420474516,10000,-103.7100588,171.0066238,0,14.03629709,0,121.2367351 +64.59,50.40376843,-3.420450501,10000,-103.7379114,170.9933064,0,14.03629709,0,121.2437611 +64.6,50.40375912,-3.420426488,10000,-103.7622825,170.9806566,0,14.03629709,0,121.250787 +64.61,50.4037498,-3.420402476,10000,-103.7796904,170.9684517,0,14.03629709,0,121.2578129 +64.62,50.40374049,-3.420378466,10000,-103.7970982,170.9555794,0,14.03629709,0,121.2648388 +64.63,50.40373117,-3.420354458,10000,-103.8179877,170.942707,0,14.03629709,0,121.2718648 +64.64,50.40372185,-3.420330452,10000,-103.8353955,170.9305022,0,14.03629709,0,121.2788906 +64.65,50.40371253,-3.420306447,10000,-103.856285,170.9178524,0,14.03629709,0,121.2859166 +64.66,50.40370321,-3.420282444,10000,-103.8911009,170.904535,0,14.03629709,0,121.2929425 +64.67,50.40369388,-3.420258444,10000,-103.9259168,170.8918852,0,14.03629709,0,121.2999684 +64.68,50.40368455,-3.420234444,10000,-103.9433247,170.8796804,0,14.03629709,0,121.3069943 +64.69,50.40367522,-3.420210447,10000,-103.9468061,170.8665856,0,14.03629709,0,121.3140203 +64.7,50.40366589,-3.420186451,10000,-103.9502875,170.8530457,0,14.03629709,0,121.3210462 +64.71,50.40365656,-3.420162458,10000,-103.9676954,170.8406184,0,14.03629709,0,121.3280721 +64.72,50.40364723,-3.420138466,10000,-104.0025113,170.8290811,0,14.03629709,0,121.335098 +64.73,50.40363789,-3.420114475,10000,-104.0373271,170.8166538,0,14.03629709,0,121.342124 +64.74,50.40362855,-3.420090487,10000,-104.054735,170.8028914,0,14.03629709,0,121.3491499 +64.75,50.40361921,-3.4200665,10000,-104.0616981,170.7889065,0,14.03629709,0,121.3561758 +64.76,50.40360987,-3.420042516,10000,-104.0791059,170.7758116,0,14.03629709,0,121.3632017 +64.77,50.40360053,-3.420018533,10000,-104.1139218,170.7638294,0,14.03629709,0,121.3702277 +64.78,50.40359118,-3.419994552,10000,-104.1487377,170.7518471,0,14.03629709,0,121.3772536 +64.79,50.40358183,-3.419970572,10000,-104.1661455,170.7389748,0,14.03629709,0,121.3842795 +64.8,50.40357248,-3.419946595,10000,-104.1731086,170.72588,0,14.03629709,0,121.3913054 +64.81,50.40356313,-3.419922619,10000,-104.1905164,170.7130076,0,14.03629709,0,121.3983313 +64.82,50.40355378,-3.419898645,10000,-104.2218507,170.6999128,0,14.03629709,0,121.4053573 +64.83,50.40354442,-3.419874673,10000,-104.2462218,170.6870405,0,14.03629709,0,121.4123832 +64.84,50.40353506,-3.419850703,10000,-104.2601481,170.6750582,0,14.03629709,0,121.4194091 +64.85,50.40352571,-3.419826734,10000,-104.2810375,170.663076,0,14.03629709,0,121.426435 +64.86,50.40351634,-3.419802767,10000,-104.301927,170.6499812,0,14.03629709,0,121.433461 +64.87,50.40350698,-3.419778802,10000,-104.3158532,170.6362188,0,14.03629709,0,121.4404869 +64.88,50.40349762,-3.419754839,10000,-104.3402243,170.623124,0,14.03629709,0,121.4475128 +64.89,50.40348825,-3.419730878,10000,-104.3715586,170.6111417,0,14.03629709,0,121.4545387 +64.9,50.40347888,-3.419706918,10000,-104.3889664,170.5991595,0,14.03629709,0,121.4615647 +64.91,50.40346951,-3.41968296,10000,-104.3959295,170.5860647,0,14.03629709,0,121.4685906 +64.92,50.40346014,-3.419659004,10000,-104.4133373,170.5723023,0,14.03629709,0,121.4756165 +64.93,50.40345077,-3.41963505,10000,-104.4481532,170.5589849,0,14.03629709,0,121.4826424 +64.94,50.40344139,-3.419611098,10000,-104.4829691,170.5461127,0,14.03629709,0,121.4896684 +64.95,50.40343201,-3.419587147,10000,-104.5003769,170.5332404,0,14.03629709,0,121.4966943 +64.96,50.40342263,-3.419563199,10000,-104.50734,170.5210356,0,14.03629709,0,121.5037202 +64.97,50.40341325,-3.419539252,10000,-104.5212662,170.5092759,0,14.03629709,0,121.5107461 +64.98,50.40340387,-3.419515306,10000,-104.5421557,170.4961811,0,14.03629709,0,121.5177721 +64.99,50.40339448,-3.419491363,10000,-104.5630451,170.4821962,0,14.03629709,0,121.5247979 +65,50.4033851,-3.419467422,10000,-104.5943794,170.4693239,0,14.03629709,0,121.5318239 +65.01,50.40337571,-3.419443482,10000,-104.6326769,170.4573417,0,14.03629709,0,121.5388498 +65.02,50.40336631,-3.419419544,10000,-104.6500848,170.445137,0,14.03629709,0,121.5458757 +65.03,50.40335692,-3.419395608,10000,-104.6535662,170.4322647,0,14.03629709,0,121.5529016 +65.04,50.40334753,-3.419371673,10000,-104.6744557,170.4182798,0,14.03629709,0,121.5599276 +65.05,50.40333813,-3.419347741,10000,-104.7057899,170.404295,0,14.03629709,0,121.5669535 +65.06,50.40332873,-3.419323811,10000,-104.7231978,170.3923127,0,14.03629709,0,121.5739794 +65.07,50.40331933,-3.419299882,10000,-104.7301608,170.3812206,0,14.03629709,0,121.5810053 +65.08,50.40330993,-3.419275954,10000,-104.7475687,170.3683483,0,14.03629709,0,121.5880313 +65.09,50.40330053,-3.419252029,10000,-104.7823846,170.3543635,0,14.03629709,0,121.5950572 +65.1,50.40329112,-3.419228106,10000,-104.8172005,170.3414912,0,14.03629709,0,121.6020831 +65.11,50.40328171,-3.419204184,10000,-104.8346083,170.3292865,0,14.03629709,0,121.609109 +65.12,50.4032723,-3.419180264,10000,-104.8415714,170.3161917,0,14.03629709,0,121.616135 +65.13,50.40326289,-3.419156346,10000,-104.8589792,170.3024293,0,14.03629709,0,121.6231609 +65.14,50.40325348,-3.41913243,10000,-104.8903135,170.289112,0,14.03629709,0,121.6301868 +65.15,50.40324406,-3.419108516,10000,-104.9146845,170.2762398,0,14.03629709,0,121.6372127 +65.16,50.40323464,-3.419084603,10000,-104.9286108,170.2633675,0,14.03629709,0,121.6442387 +65.17,50.40322523,-3.419060693,10000,-104.9495003,170.2511628,0,14.03629709,0,121.6512646 +65.18,50.4032158,-3.419036784,10000,-104.9703897,170.2394031,0,14.03629709,0,121.6582905 +65.19,50.40320638,-3.419012876,10000,-104.9843159,170.2263084,0,14.03629709,0,121.6653164 +65.2,50.40319696,-3.418988971,10000,-105.008687,170.2123235,0,14.03629709,0,121.6723423 +65.21,50.40318753,-3.418965068,10000,-105.0400213,170.1994513,0,14.03629709,0,121.6793683 +65.22,50.4031781,-3.418941166,10000,-105.0574291,170.1874691,0,14.03629709,0,121.6863942 +65.23,50.40316867,-3.418917266,10000,-105.0643922,170.1752644,0,14.03629709,0,121.6934201 +65.24,50.40315924,-3.418893368,10000,-105.0818,170.1626146,0,14.03629709,0,121.700446 +65.25,50.40314981,-3.418869471,10000,-105.1166159,170.1492974,0,14.03629709,0,121.707472 +65.26,50.40314037,-3.418845577,10000,-105.1514318,170.1353125,0,14.03629709,0,121.7144979 +65.27,50.40313093,-3.418821684,10000,-105.1688397,170.1213277,0,14.03629709,0,121.7215238 +65.28,50.40312149,-3.418797794,10000,-105.1758027,170.1082329,0,14.03629709,0,121.7285497 +65.29,50.40311205,-3.418773905,10000,-105.1932105,170.0964733,0,14.03629709,0,121.7355757 +65.3,50.40310261,-3.418750018,10000,-105.2245448,170.0851587,0,14.03629709,0,121.7426016 +65.31,50.40309316,-3.418726132,10000,-105.2454343,170.0725089,0,14.03629709,0,121.7496275 +65.32,50.40308371,-3.418702248,10000,-105.2489157,170.0583016,0,14.03629709,0,121.7566534 +65.33,50.40307427,-3.418678367,10000,-105.2663236,170.0445393,0,14.03629709,0,121.7636793 +65.34,50.40306482,-3.418654487,10000,-105.304621,170.0323346,0,14.03629709,0,121.7707052 +65.35,50.40305536,-3.418630609,10000,-105.3359553,170.0203524,0,14.03629709,0,121.7777312 +65.36,50.40304591,-3.418606732,10000,-105.3568448,170.0074802,0,14.03629709,0,121.7847571 +65.37,50.40303645,-3.418582858,10000,-105.3777342,169.9943855,0,14.03629709,0,121.791783 +65.38,50.40302699,-3.418558985,10000,-105.3916605,169.9815132,0,14.03629709,0,121.7988089 +65.39,50.40301753,-3.418535114,10000,-105.3986235,169.968196,0,14.03629709,0,121.8058349 +65.4,50.40300807,-3.418511245,10000,-105.4160314,169.9544337,0,14.03629709,0,121.8128608 +65.41,50.40299861,-3.418487378,10000,-105.4508472,169.9411164,0,14.03629709,0,121.8198867 +65.42,50.40298914,-3.418463513,10000,-105.4856631,169.9282442,0,14.03629709,0,121.8269126 +65.43,50.40297967,-3.418439649,10000,-105.503071,169.9151494,0,14.03629709,0,121.8339386 +65.44,50.4029702,-3.418415788,10000,-105.510034,169.9022772,0,14.03629709,0,121.8409645 +65.45,50.40296073,-3.418391928,10000,-105.5239603,169.8902951,0,14.03629709,0,121.8479904 +65.46,50.40295126,-3.41836807,10000,-105.5448497,169.8780904,0,14.03629709,0,121.8550163 +65.47,50.40294178,-3.418344213,10000,-105.5622576,169.8643281,0,14.03629709,0,121.8620423 +65.48,50.40293231,-3.418320359,10000,-105.583147,169.8501208,0,14.03629709,0,121.8690682 +65.49,50.40292283,-3.418296507,10000,-105.6179629,169.8372486,0,14.03629709,0,121.8760941 +65.5,50.40291335,-3.418272656,10000,-105.6527788,169.8252664,0,14.03629709,0,121.88312 +65.51,50.40290386,-3.418248807,10000,-105.6736682,169.8130618,0,14.03629709,0,121.890146 +65.52,50.40289438,-3.41822496,10000,-105.6910761,169.8004121,0,14.03629709,0,121.8971719 +65.53,50.40288489,-3.418201114,10000,-105.7119655,169.7873174,0,14.03629709,0,121.9041978 +65.54,50.4028754,-3.418177271,10000,-105.7258918,169.7742227,0,14.03629709,0,121.9112237 +65.55,50.40286591,-3.418153429,10000,-105.7328548,169.7613505,0,14.03629709,0,121.9182497 +65.56,50.40285642,-3.418129589,10000,-105.7502627,169.7480332,0,14.03629709,0,121.9252756 +65.57,50.40284693,-3.418105751,10000,-105.7850785,169.7342709,0,14.03629709,0,121.9323015 +65.58,50.40283743,-3.418081915,10000,-105.8198944,169.7211762,0,14.03629709,0,121.9393274 +65.59,50.40282793,-3.418058081,10000,-105.8373023,169.7089716,0,14.03629709,0,121.9463534 +65.6,50.40281843,-3.418034248,10000,-105.8407837,169.6960994,0,14.03629709,0,121.9533793 +65.61,50.40280893,-3.418010417,10000,-105.8442651,169.6821146,0,14.03629709,0,121.9604052 +65.62,50.40279943,-3.417986589,10000,-105.861673,169.6690199,0,14.03629709,0,121.9674311 +65.63,50.40278993,-3.417962762,10000,-105.8964888,169.6572603,0,14.03629709,0,121.974457 +65.64,50.40278042,-3.417938936,10000,-105.9313047,169.6448331,0,14.03629709,0,121.981483 +65.65,50.40277091,-3.417915113,10000,-105.9521942,169.6310709,0,14.03629709,0,121.9885088 +65.66,50.4027614,-3.417891291,10000,-105.969602,169.6170861,0,14.03629709,0,121.9955348 +65.67,50.40275189,-3.417867472,10000,-105.9904915,169.6039914,0,14.03629709,0,122.0025607 +65.68,50.40274237,-3.417843654,10000,-106.0078993,169.5920093,0,14.03629709,0,122.0095866 +65.69,50.40273286,-3.417819838,10000,-106.0253072,169.5800272,0,14.03629709,0,122.0166125 +65.7,50.40272334,-3.417796023,10000,-106.0496782,169.5669325,0,14.03629709,0,122.0236385 +65.71,50.40271382,-3.417772211,10000,-106.0775309,169.5529477,0,14.03629709,0,122.0306644 +65.72,50.4027043,-3.4177484,10000,-106.101902,169.5389629,0,14.03629709,0,122.0376903 +65.73,50.40269477,-3.417724592,10000,-106.1193098,169.5258682,0,14.03629709,0,122.0447162 +65.74,50.40268525,-3.417700785,10000,-106.1367177,169.5138861,0,14.03629709,0,122.0517422 +65.75,50.40267572,-3.41767698,10000,-106.1610887,169.5016815,0,14.03629709,0,122.0587681 +65.76,50.40266619,-3.417653176,10000,-106.1889414,169.4879193,0,14.03629709,0,122.065794 +65.77,50.40265666,-3.417629375,10000,-106.2133124,169.473712,0,14.03629709,0,122.0728199 +65.78,50.40264712,-3.417605576,10000,-106.2307203,169.4608398,0,14.03629709,0,122.0798459 +65.79,50.40263759,-3.417581778,10000,-106.2481281,169.4488577,0,14.03629709,0,122.0868718 +65.8,50.40262805,-3.417557982,10000,-106.2690176,169.4366531,0,14.03629709,0,122.0938977 +65.81,50.40261851,-3.417534188,10000,-106.2829438,169.4240035,0,14.03629709,0,122.1009236 +65.82,50.40260897,-3.417510395,10000,-106.2899069,169.4106863,0,14.03629709,0,122.1079496 +65.83,50.40259943,-3.417486605,10000,-106.3073147,169.3967015,0,14.03629709,0,122.1149755 +65.84,50.40258989,-3.417462816,10000,-106.3421306,169.3827167,0,14.03629709,0,122.1220014 +65.85,50.40258034,-3.41743903,10000,-106.3769465,169.3693995,0,14.03629709,0,122.1290273 +65.86,50.40257079,-3.417415245,10000,-106.3943543,169.3567499,0,14.03629709,0,122.1360533 +65.87,50.40256124,-3.417391462,10000,-106.4013173,169.3443228,0,14.03629709,0,122.1430792 +65.88,50.40255169,-3.417367681,10000,-106.4187252,169.3316731,0,14.03629709,0,122.1501051 +65.89,50.40254214,-3.417343901,10000,-106.4535411,169.3185785,0,14.03629709,0,122.157131 +65.9,50.40253258,-3.417320124,10000,-106.4883569,169.3054838,0,14.03629709,0,122.164157 +65.91,50.40252302,-3.417296348,10000,-106.5057648,169.2926117,0,14.03629709,0,122.1711829 +65.92,50.40251346,-3.417272574,10000,-106.5092462,169.279517,0,14.03629709,0,122.1782088 +65.93,50.4025039,-3.417248802,10000,-106.5127276,169.2664223,0,14.03629709,0,122.1852347 +65.94,50.40249434,-3.417225032,10000,-106.5301355,169.2533276,0,14.03629709,0,122.1922607 +65.95,50.40248478,-3.417201263,10000,-106.5649513,169.2393429,0,14.03629709,0,122.1992866 +65.96,50.40247521,-3.417177497,10000,-106.5997672,169.2251356,0,14.03629709,0,122.2063125 +65.97,50.40246564,-3.417153733,10000,-106.6206567,169.2122635,0,14.03629709,0,122.2133384 +65.98,50.40245607,-3.41712997,10000,-106.6380645,169.2002814,0,14.03629709,0,122.2203644 +65.99,50.4024465,-3.417106209,10000,-106.658954,169.1880768,0,14.03629709,0,122.2273903 +66,50.40243692,-3.41708245,10000,-106.6763618,169.1754272,0,14.03629709,0,122.2344161 +66.01,50.40242735,-3.417058692,10000,-106.6937696,169.16211,0,14.03629709,0,122.2414421 +66.02,50.40241777,-3.417034937,10000,-106.7146591,169.1483478,0,14.03629709,0,122.248468 +66.03,50.40240819,-3.417011183,10000,-106.732067,169.1352532,0,14.03629709,0,122.2554939 +66.04,50.40239861,-3.416987432,10000,-106.7529564,169.1230486,0,14.03629709,0,122.2625198 +66.05,50.40238903,-3.416963681,10000,-106.7877723,169.1101765,0,14.03629709,0,122.2695458 +66.06,50.40237944,-3.416939933,10000,-106.8225881,169.0959692,0,14.03629709,0,122.2765717 +66.07,50.40236985,-3.416916187,10000,-106.839996,169.082207,0,14.03629709,0,122.2835976 +66.08,50.40236026,-3.416892443,10000,-106.8434774,169.0697799,0,14.03629709,0,122.2906235 +66.09,50.40235067,-3.4168687,10000,-106.8469588,169.0571303,0,14.03629709,0,122.2976495 +66.1,50.40234108,-3.416844959,10000,-106.8643667,169.0438131,0,14.03629709,0,122.3046754 +66.11,50.40233149,-3.416821221,10000,-106.8991825,169.030941,0,14.03629709,0,122.3117013 +66.12,50.40232189,-3.416797483,10000,-106.9339984,169.0178464,0,14.03629709,0,122.3187272 +66.13,50.40231229,-3.416773748,10000,-106.9514063,169.0036391,0,14.03629709,0,122.3257532 +66.14,50.40230269,-3.416750015,10000,-106.9583693,168.9898769,0,14.03629709,0,122.3327791 +66.15,50.40229309,-3.416726284,10000,-106.9757771,168.9776724,0,14.03629709,0,122.339805 +66.16,50.40228349,-3.416702554,10000,-107.010593,168.9656903,0,14.03629709,0,122.3468309 +66.17,50.40227388,-3.416678826,10000,-107.0454089,168.9525957,0,14.03629709,0,122.3538569 +66.18,50.40226427,-3.4166551,10000,-107.0628167,168.9388335,0,14.03629709,0,122.3608828 +66.19,50.40225466,-3.416631376,10000,-107.0697798,168.9255163,0,14.03629709,0,122.3679087 +66.2,50.40224505,-3.416607654,10000,-107.083706,168.9126442,0,14.03629709,0,122.3749346 +66.21,50.40223544,-3.416583933,10000,-107.1045954,168.8993271,0,14.03629709,0,122.3819606 +66.22,50.40222582,-3.416560215,10000,-107.1220033,168.8853424,0,14.03629709,0,122.3889865 +66.23,50.40221621,-3.416536498,10000,-107.1428927,168.8715802,0,14.03629709,0,122.3960124 +66.24,50.40220659,-3.416512784,10000,-107.1777086,168.8591531,0,14.03629709,0,122.4030383 +66.25,50.40219697,-3.416489071,10000,-107.2125245,168.8476161,0,14.03629709,0,122.4100643 +66.26,50.40218734,-3.416465359,10000,-107.2299323,168.8351891,0,14.03629709,0,122.4170902 +66.27,50.40217772,-3.41644165,10000,-107.2334137,168.8214269,0,14.03629709,0,122.4241161 +66.28,50.40216809,-3.416417942,10000,-107.2403767,168.8072196,0,14.03629709,0,122.431142 +66.29,50.40215847,-3.416394237,10000,-107.2682294,168.7932349,0,14.03629709,0,122.438168 +66.3,50.40214884,-3.416370533,10000,-107.3100085,168.7801403,0,14.03629709,0,122.4451939 +66.31,50.4021392,-3.416346832,10000,-107.3378612,168.7679358,0,14.03629709,0,122.4522198 +66.32,50.40212957,-3.416323131,10000,-107.3448242,168.7550637,0,14.03629709,0,122.4592457 +66.33,50.40211993,-3.416299433,10000,-107.3483056,168.7408565,0,14.03629709,0,122.4662717 +66.34,50.4021103,-3.416275737,10000,-107.3657134,168.7270943,0,14.03629709,0,122.4732975 +66.35,50.40210066,-3.416252043,10000,-107.4005293,168.7148898,0,14.03629709,0,122.4803235 +66.36,50.40209102,-3.41622835,10000,-107.4353452,168.7029078,0,14.03629709,0,122.4873494 +66.37,50.40208137,-3.416204659,10000,-107.4562346,168.6898131,0,14.03629709,0,122.4943753 +66.38,50.40207173,-3.41618097,10000,-107.4736425,168.6758284,0,14.03629709,0,122.5014012 +66.39,50.40206208,-3.416157283,10000,-107.4945319,168.6618437,0,14.03629709,0,122.5084272 +66.4,50.40205243,-3.416133598,10000,-107.5084581,168.6487491,0,14.03629709,0,122.5154531 +66.41,50.40204278,-3.416109915,10000,-107.5154212,168.6367672,0,14.03629709,0,122.522479 +66.42,50.40203313,-3.416086233,10000,-107.532829,168.6245626,0,14.03629709,0,122.5295049 +66.43,50.40202348,-3.416062553,10000,-107.5676449,168.6108005,0,14.03629709,0,122.5365308 +66.44,50.40201382,-3.416038875,10000,-107.6024607,168.5965932,0,14.03629709,0,122.5435568 +66.45,50.40200416,-3.4160152,10000,-107.6198686,168.5834986,0,14.03629709,0,122.5505827 +66.46,50.4019945,-3.415991525,10000,-107.6268316,168.570404,0,14.03629709,0,122.5576086 +66.47,50.40198484,-3.415967853,10000,-107.6407579,168.5561968,0,14.03629709,0,122.5646345 +66.48,50.40197518,-3.415944183,10000,-107.6616473,168.5424347,0,14.03629709,0,122.5716605 +66.49,50.40196551,-3.415920515,10000,-107.6790551,168.5302302,0,14.03629709,0,122.5786864 +66.5,50.40195585,-3.415896848,10000,-107.6999446,168.5182482,0,14.03629709,0,122.5857123 +66.51,50.40194618,-3.415873183,10000,-107.7347604,168.5051536,0,14.03629709,0,122.5927382 +66.52,50.40193651,-3.41584952,10000,-107.7695763,168.4911689,0,14.03629709,0,122.5997642 +66.53,50.40192683,-3.415825859,10000,-107.7869842,168.4769617,0,14.03629709,0,122.6067901 +66.54,50.40191716,-3.4158022,10000,-107.7904656,168.462977,0,14.03629709,0,122.613816 +66.55,50.40190748,-3.415778543,10000,-107.7974286,168.4498824,0,14.03629709,0,122.6208419 +66.56,50.40189781,-3.415754888,10000,-107.8252812,168.4379004,0,14.03629709,0,122.6278679 +66.57,50.40188813,-3.415731234,10000,-107.8670603,168.4259185,0,14.03629709,0,122.6348938 +66.58,50.40187844,-3.415707582,10000,-107.894913,168.4128239,0,14.03629709,0,122.6419197 +66.59,50.40186876,-3.415683932,10000,-107.901876,168.3990617,0,14.03629709,0,122.6489456 +66.6,50.40185907,-3.415660284,10000,-107.9053574,168.3855221,0,14.03629709,0,122.6559716 +66.61,50.40184939,-3.415636638,10000,-107.9227653,168.3717599,0,14.03629709,0,122.6629975 +66.62,50.4018397,-3.415612993,10000,-107.9575811,168.3575527,0,14.03629709,0,122.6700234 +66.63,50.40183001,-3.415589352,10000,-107.992397,168.3444582,0,14.03629709,0,122.6770493 +66.64,50.40182031,-3.415565711,10000,-108.0132864,168.3326987,0,14.03629709,0,122.6840753 +66.65,50.40181062,-3.415542072,10000,-108.0306943,168.3200492,0,14.03629709,0,122.6911012 +66.66,50.40180092,-3.415518435,10000,-108.0515837,168.3056195,0,14.03629709,0,122.6981271 +66.67,50.40179122,-3.4154948,10000,-108.0655099,168.2911898,0,14.03629709,0,122.705153 +66.68,50.40178152,-3.415471168,10000,-108.072473,168.2783177,0,14.03629709,0,122.712179 +66.69,50.40177182,-3.415447536,10000,-108.0898808,168.2661132,0,14.03629709,0,122.7192048 +66.7,50.40176212,-3.415423907,10000,-108.1246967,168.2530187,0,14.03629709,0,122.7262308 +66.71,50.40175241,-3.415400279,10000,-108.1595126,168.2392565,0,14.03629709,0,122.7332567 +66.72,50.4017427,-3.415376654,10000,-108.1769204,168.2259394,0,14.03629709,0,122.7402826 +66.73,50.40173299,-3.41535303,10000,-108.1838834,168.2130674,0,14.03629709,0,122.7473085 +66.74,50.40172328,-3.415329408,10000,-108.1978097,168.1997503,0,14.03629709,0,122.7543345 +66.75,50.40171357,-3.415305788,10000,-108.2186991,168.1859881,0,14.03629709,0,122.7613604 +66.76,50.40170385,-3.41528217,10000,-108.2361069,168.172671,0,14.03629709,0,122.7683863 +66.77,50.40169414,-3.415258554,10000,-108.2569964,168.159799,0,14.03629709,0,122.7754122 +66.78,50.40168442,-3.415234939,10000,-108.2918122,168.1467044,0,14.03629709,0,122.7824382 +66.79,50.4016747,-3.415211327,10000,-108.3266281,168.1336099,0,14.03629709,0,122.7894641 +66.8,50.40166497,-3.415187716,10000,-108.3440359,168.1207378,0,14.03629709,0,122.79649 +66.81,50.40165525,-3.415164107,10000,-108.3475173,168.1074208,0,14.03629709,0,122.8035159 +66.82,50.40164552,-3.4151405,10000,-108.3544804,168.0934361,0,14.03629709,0,122.8105418 +66.83,50.4016358,-3.415116895,10000,-108.382333,168.0794514,0,14.03629709,0,122.8175678 +66.84,50.40162607,-3.415093292,10000,-108.4241121,168.0663569,0,14.03629709,0,122.8245937 +66.85,50.40161633,-3.415069691,10000,-108.4519648,168.0541524,0,14.03629709,0,122.8316196 +66.86,50.4016066,-3.415046091,10000,-108.4589278,168.0412804,0,14.03629709,0,122.8386455 +66.87,50.40159686,-3.415022493,10000,-108.4624092,168.0270732,0,14.03629709,0,122.8456715 +66.88,50.40158713,-3.414998898,10000,-108.479817,168.0130886,0,14.03629709,0,122.8526974 +66.89,50.40157739,-3.414975304,10000,-108.5146329,167.999994,0,14.03629709,0,122.8597233 +66.9,50.40156765,-3.414951712,10000,-108.5494487,167.9866769,0,14.03629709,0,122.8667492 +66.91,50.4015579,-3.414928122,10000,-108.5703382,167.9729148,0,14.03629709,0,122.8737752 +66.92,50.40154816,-3.414904534,10000,-108.587746,167.9595978,0,14.03629709,0,122.8808011 +66.93,50.40153841,-3.414880948,10000,-108.6086355,167.9467257,0,14.03629709,0,122.887827 +66.94,50.40152866,-3.414857363,10000,-108.6225617,167.9336312,0,14.03629709,0,122.8948529 +66.95,50.40151891,-3.414833781,10000,-108.6295247,167.9205367,0,14.03629709,0,122.9018789 +66.96,50.40150916,-3.4148102,10000,-108.6469325,167.9076646,0,14.03629709,0,122.9089048 +66.97,50.40149941,-3.414786621,10000,-108.6817484,167.8943476,0,14.03629709,0,122.9159307 +66.98,50.40148965,-3.414763044,10000,-108.7165643,167.8805854,0,14.03629709,0,122.9229566 +66.99,50.40147989,-3.414739469,10000,-108.7339721,167.8672684,0,14.03629709,0,122.9299826 +67,50.40147013,-3.414715896,10000,-108.7409351,167.8541739,0,14.03629709,0,122.9370084 +67.01,50.40146037,-3.414692324,10000,-108.7548614,167.8401892,0,14.03629709,0,122.9440344 +67.02,50.40145061,-3.414668755,10000,-108.7757508,167.825982,0,14.03629709,0,122.9510603 +67.03,50.40144084,-3.414645188,10000,-108.7931586,167.81311,0,14.03629709,0,122.9580862 +67.04,50.40143108,-3.414621622,10000,-108.8140481,167.8009056,0,14.03629709,0,122.9651121 +67.05,50.40142131,-3.414598058,10000,-108.8488639,167.7878111,0,14.03629709,0,122.9721381 +67.06,50.40141154,-3.414574496,10000,-108.8836798,167.7738264,0,14.03629709,0,122.979164 +67.07,50.40140176,-3.414550936,10000,-108.9010876,167.7598418,0,14.03629709,0,122.9861899 +67.08,50.40139199,-3.414527378,10000,-108.904569,167.7465247,0,14.03629709,0,122.9932158 +67.09,50.40138221,-3.414503822,10000,-108.9115321,167.7336527,0,14.03629709,0,123.0002418 +67.1,50.40137244,-3.414480267,10000,-108.9393847,167.7205582,0,14.03629709,0,123.0072677 +67.11,50.40136266,-3.414456715,10000,-108.9776822,167.7072412,0,14.03629709,0,123.0142936 +67.12,50.40135287,-3.414433164,10000,-108.99509,167.6937016,0,14.03629709,0,123.0213195 +67.13,50.40134309,-3.414409615,10000,-108.9985714,167.680162,0,14.03629709,0,123.0283455 +67.14,50.40133331,-3.414386069,10000,-109.0194609,167.66729,0,14.03629709,0,123.0353714 +67.15,50.40132352,-3.414362523,10000,-109.0542767,167.654418,0,14.03629709,0,123.0423973 +67.16,50.40131373,-3.41433898,10000,-109.085611,167.6408784,0,14.03629709,0,123.0494232 +67.17,50.40130394,-3.414315439,10000,-109.109982,167.6273389,0,14.03629709,0,123.0564492 +67.18,50.40129414,-3.414291899,10000,-109.1239083,167.6137993,0,14.03629709,0,123.0634751 +67.19,50.40128435,-3.414268362,10000,-109.1308713,167.5998147,0,14.03629709,0,123.070501 +67.2,50.40127455,-3.414244826,10000,-109.1482791,167.58583,0,14.03629709,0,123.0775269 +67.21,50.40126476,-3.414221293,10000,-109.1796133,167.572513,0,14.03629709,0,123.0845528 +67.22,50.40125495,-3.414197761,10000,-109.2039844,167.559641,0,14.03629709,0,123.0915788 +67.23,50.40124515,-3.414174231,10000,-109.214429,167.5465465,0,14.03629709,0,123.0986047 +67.24,50.40123535,-3.414150703,10000,-109.2248736,167.533452,0,14.03629709,0,123.1056306 +67.25,50.40122554,-3.414127177,10000,-109.2422815,167.5203575,0,14.03629709,0,123.1126565 +67.26,50.40121574,-3.414103652,10000,-109.2736157,167.5063728,0,14.03629709,0,123.1196825 +67.27,50.40120593,-3.41408013,10000,-109.3119132,167.4919432,0,14.03629709,0,123.1267084 +67.28,50.40119611,-3.41405661,10000,-109.329321,167.4781811,0,14.03629709,0,123.1337343 +67.29,50.4011863,-3.414033091,10000,-109.3328024,167.4648641,0,14.03629709,0,123.1407602 +67.3,50.40117649,-3.414009575,10000,-109.3536919,167.4517695,0,14.03629709,0,123.1477862 +67.31,50.40116667,-3.41398606,10000,-109.3850261,167.4391201,0,14.03629709,0,123.1548121 +67.32,50.40115685,-3.413962547,10000,-109.4059156,167.4266932,0,14.03629709,0,123.161838 +67.33,50.40114703,-3.413939036,10000,-109.4233234,167.4138212,0,14.03629709,0,123.1688639 +67.34,50.40113721,-3.413915526,10000,-109.4442128,167.3998366,0,14.03629709,0,123.1758899 +67.35,50.40112738,-3.413892019,10000,-109.4616207,167.3854069,0,14.03629709,0,123.1829157 +67.36,50.40111756,-3.413868514,10000,-109.4790285,167.3716448,0,14.03629709,0,123.1899417 +67.37,50.40110773,-3.41384501,10000,-109.4999179,167.3583278,0,14.03629709,0,123.1969676 +67.38,50.4010979,-3.413821509,10000,-109.5173258,167.3452333,0,14.03629709,0,123.2039935 +67.39,50.40108807,-3.413798009,10000,-109.5382152,167.3323613,0,14.03629709,0,123.2110194 +67.4,50.40107824,-3.413774511,10000,-109.5730311,167.3190443,0,14.03629709,0,123.2180454 +67.41,50.4010684,-3.413751015,10000,-109.6078469,167.3050597,0,14.03629709,0,123.2250713 +67.42,50.40105856,-3.413727521,10000,-109.6252547,167.2908526,0,14.03629709,0,123.2320972 +67.43,50.40104872,-3.413704029,10000,-109.6287362,167.276868,0,14.03629709,0,123.2391231 +67.44,50.40103888,-3.413680539,10000,-109.6322176,167.263551,0,14.03629709,0,123.2461491 +67.45,50.40102904,-3.413657051,10000,-109.6496254,167.250679,0,14.03629709,0,123.253175 +67.46,50.4010192,-3.413633564,10000,-109.6844413,167.2375845,0,14.03629709,0,123.2602009 +67.47,50.40100935,-3.41361008,10000,-109.7192571,167.22449,0,14.03629709,0,123.2672268 +67.48,50.4009995,-3.413586597,10000,-109.7366649,167.211618,0,14.03629709,0,123.2742528 +67.49,50.40098965,-3.413563116,10000,-109.743628,167.198301,0,14.03629709,0,123.2812787 +67.5,50.4009798,-3.413539637,10000,-109.7610358,167.1843164,0,14.03629709,0,123.2883046 +67.51,50.40096995,-3.41351616,10000,-109.79237,167.1701093,0,14.03629709,0,123.2953305 +67.52,50.40096009,-3.413492685,10000,-109.8167411,167.1561247,0,14.03629709,0,123.3023565 +67.53,50.40095023,-3.413469212,10000,-109.8306673,167.1428077,0,14.03629709,0,123.3093824 +67.54,50.40094038,-3.413445741,10000,-109.8515567,167.1299357,0,14.03629709,0,123.3164083 +67.55,50.40093051,-3.413422271,10000,-109.8724462,167.1166187,0,14.03629709,0,123.3234342 +67.56,50.40092065,-3.413398804,10000,-109.8863724,167.1026341,0,14.03629709,0,123.3304602 +67.57,50.40091079,-3.413375338,10000,-109.9107435,167.0886495,0,14.03629709,0,123.3374861 +67.58,50.40090092,-3.413351875,10000,-109.9420777,167.0753325,0,14.03629709,0,123.344512 +67.59,50.40089105,-3.413328413,10000,-109.9594855,167.0626831,0,14.03629709,0,123.3515379 +67.6,50.40088118,-3.413304953,10000,-109.9664485,167.0502562,0,14.03629709,0,123.3585639 +67.61,50.40087131,-3.413281495,10000,-109.9838563,167.0373842,0,14.03629709,0,123.3655898 +67.62,50.40086144,-3.413258038,10000,-110.0186722,167.0233997,0,14.03629709,0,123.3726157 +67.63,50.40085156,-3.413234584,10000,-110.0534881,167.00897,0,14.03629709,0,123.3796416 +67.64,50.40084168,-3.413211132,10000,-110.0708959,166.9949854,0,14.03629709,0,123.3866675 +67.65,50.4008318,-3.413187681,10000,-110.0778589,166.9807783,0,14.03629709,0,123.3936935 +67.66,50.40082192,-3.413164233,10000,-110.0917851,166.9665712,0,14.03629709,0,123.4007194 +67.67,50.40081204,-3.413140787,10000,-110.1126746,166.9536993,0,14.03629709,0,123.4077453 +67.68,50.40080215,-3.413117342,10000,-110.1300824,166.9414949,0,14.03629709,0,123.4147712 +67.69,50.40079227,-3.413093899,10000,-110.1474902,166.9284004,0,14.03629709,0,123.4217972 +67.7,50.40078238,-3.413070458,10000,-110.1718613,166.9144158,0,14.03629709,0,123.428823 +67.71,50.40077249,-3.413047019,10000,-110.1997139,166.9004312,0,14.03629709,0,123.435849 +67.72,50.4007626,-3.413023582,10000,-110.2240849,166.8871143,0,14.03629709,0,123.4428749 +67.73,50.4007527,-3.413000147,10000,-110.2414928,166.8742423,0,14.03629709,0,123.4499008 +67.74,50.40074281,-3.412976713,10000,-110.2589006,166.8609253,0,14.03629709,0,123.4569267 +67.75,50.40073291,-3.412953282,10000,-110.2832716,166.8469407,0,14.03629709,0,123.4639527 +67.76,50.40072301,-3.412929852,10000,-110.3111243,166.8329562,0,14.03629709,0,123.4709786 +67.77,50.40071311,-3.412906425,10000,-110.3354953,166.8194166,0,14.03629709,0,123.4780045 +67.78,50.4007032,-3.412882999,10000,-110.3529031,166.8058771,0,14.03629709,0,123.4850304 +67.79,50.4006933,-3.412859575,10000,-110.370311,166.7923376,0,14.03629709,0,123.4920564 +67.8,50.40068339,-3.412836154,10000,-110.3912004,166.7794657,0,14.03629709,0,123.4990823 +67.81,50.40067348,-3.412812733,10000,-110.4051266,166.7663712,0,14.03629709,0,123.5061082 +67.82,50.40066357,-3.412789315,10000,-110.4120896,166.7521641,0,14.03629709,0,123.5131341 +67.83,50.40065366,-3.412765899,10000,-110.4294975,166.7381795,0,14.03629709,0,123.5201601 +67.84,50.40064375,-3.412742485,10000,-110.4643133,166.7248625,0,14.03629709,0,123.527186 +67.85,50.40063383,-3.412719072,10000,-110.4991292,166.710878,0,14.03629709,0,123.5342119 +67.86,50.40062391,-3.412695662,10000,-110.516537,166.6964483,0,14.03629709,0,123.5412378 +67.87,50.40061399,-3.412672254,10000,-110.5235,166.6826863,0,14.03629709,0,123.5482638 +67.88,50.40060407,-3.412648847,10000,-110.5409078,166.6693693,0,14.03629709,0,123.5552897 +67.89,50.40059415,-3.412625443,10000,-110.5722421,166.6562749,0,14.03629709,0,123.5623156 +67.9,50.40058422,-3.41260204,10000,-110.5966131,166.6436255,0,14.03629709,0,123.5693415 +67.91,50.40057429,-3.412578639,10000,-110.6105393,166.6311986,0,14.03629709,0,123.5763675 +67.92,50.40056437,-3.41255524,10000,-110.6314288,166.6183267,0,14.03629709,0,123.5833934 +67.93,50.40055443,-3.412531842,10000,-110.6523182,166.6041196,0,14.03629709,0,123.5904193 +67.94,50.4005445,-3.412508447,10000,-110.6662444,166.5890224,0,14.03629709,0,123.5974452 +67.95,50.40053457,-3.412485054,10000,-110.6906155,166.5748153,0,14.03629709,0,123.6044712 +67.96,50.40052463,-3.412461663,10000,-110.7219497,166.5617208,0,14.03629709,0,123.6114971 +67.97,50.40051469,-3.412438273,10000,-110.7393575,166.5486264,0,14.03629709,0,123.618523 +67.98,50.40050475,-3.412414886,10000,-110.7463205,166.5355319,0,14.03629709,0,123.6255489 +67.99,50.40049481,-3.4123915,10000,-110.7602468,166.5224375,0,14.03629709,0,123.6325749 +68,50.40048487,-3.412368116,10000,-110.7811362,166.5082304,0,14.03629709,0,123.6396008 +68.01,50.40047492,-3.412344734,10000,-110.798544,166.4931332,0,14.03629709,0,123.6466266 +68.02,50.40046498,-3.412321355,10000,-110.8194334,166.4789261,0,14.03629709,0,123.6536526 +68.03,50.40045503,-3.412297977,10000,-110.8542493,166.4658316,0,14.03629709,0,123.6606785 +68.04,50.40044508,-3.412274601,10000,-110.8890652,166.4527372,0,14.03629709,0,123.6677044 +68.05,50.40043512,-3.412251227,10000,-110.9099546,166.4396428,0,14.03629709,0,123.6747303 +68.06,50.40042517,-3.412227855,10000,-110.9273624,166.4267709,0,14.03629709,0,123.6817563 +68.07,50.40041521,-3.412204484,10000,-110.9482518,166.4134539,0,14.03629709,0,123.6887822 +68.08,50.40040525,-3.412181116,10000,-110.962178,166.3994693,0,14.03629709,0,123.6958081 +68.09,50.40039529,-3.412157749,10000,-110.9691411,166.3852622,0,14.03629709,0,123.702834 +68.1,50.40038533,-3.412134385,10000,-110.9865489,166.3710552,0,14.03629709,0,123.70986 +68.11,50.40037537,-3.412111022,10000,-111.0213647,166.3570706,0,14.03629709,0,123.7168859 +68.12,50.4003654,-3.412087662,10000,-111.0561806,166.3437536,0,14.03629709,0,123.7239118 +68.13,50.40035543,-3.412064303,10000,-111.0735884,166.3308817,0,14.03629709,0,123.7309377 +68.14,50.40034546,-3.412040946,10000,-111.0770698,166.3177873,0,14.03629709,0,123.7379637 +68.15,50.40033549,-3.412017591,10000,-111.0805512,166.3046929,0,14.03629709,0,123.7449896 +68.16,50.40032552,-3.411994238,10000,-111.097959,166.2915984,0,14.03629709,0,123.7520155 +68.17,50.40031555,-3.411970886,10000,-111.1327749,166.2773913,0,14.03629709,0,123.7590414 +68.18,50.40030557,-3.411947537,10000,-111.1675907,166.2622941,0,14.03629709,0,123.7660674 +68.19,50.40029559,-3.41192419,10000,-111.1884802,166.2480871,0,14.03629709,0,123.7730933 +68.2,50.40028561,-3.411900845,10000,-111.205888,166.2349926,0,14.03629709,0,123.7801192 +68.21,50.40027563,-3.411877501,10000,-111.2267774,166.2218982,0,14.03629709,0,123.7871451 +68.22,50.40026564,-3.41185416,10000,-111.2441852,166.2085812,0,14.03629709,0,123.7941711 +68.23,50.40025566,-3.41183082,10000,-111.2615931,166.1948192,0,14.03629709,0,123.801197 +68.24,50.40024567,-3.411807482,10000,-111.2824825,166.1803896,0,14.03629709,0,123.8082229 +68.25,50.40023568,-3.411784147,10000,-111.2998903,166.1664051,0,14.03629709,0,123.8152488 +68.26,50.40022569,-3.411760813,10000,-111.3172981,166.1533106,0,14.03629709,0,123.8222748 +68.27,50.4002157,-3.411737481,10000,-111.3381875,166.1399937,0,14.03629709,0,123.8293007 +68.28,50.4002057,-3.411714151,10000,-111.3555954,166.1260091,0,14.03629709,0,123.8363266 +68.29,50.40019571,-3.411690823,10000,-111.3764848,166.1120246,0,14.03629709,0,123.8433525 +68.3,50.40018571,-3.411667497,10000,-111.4113006,166.0987076,0,14.03629709,0,123.8503785 +68.31,50.40017571,-3.411644173,10000,-111.4461165,166.0858358,0,14.03629709,0,123.8574044 +68.32,50.4001657,-3.41162085,10000,-111.4635243,166.0725188,0,14.03629709,0,123.8644303 +68.33,50.4001557,-3.41159753,10000,-111.4670057,166.0585343,0,14.03629709,0,123.8714562 +68.34,50.40014569,-3.411574211,10000,-111.4704871,166.0445497,0,14.03629709,0,123.8784822 +68.35,50.40013569,-3.411550895,10000,-111.487895,166.0312328,0,14.03629709,0,123.8855081 +68.36,50.40012568,-3.41152758,10000,-111.5227108,166.0181383,0,14.03629709,0,123.892534 +68.37,50.40011567,-3.411504267,10000,-111.5575266,166.0039313,0,14.03629709,0,123.8995599 +68.38,50.40010565,-3.411480956,10000,-111.578416,165.9888341,0,14.03629709,0,123.9065859 +68.39,50.40009564,-3.411457648,10000,-111.5958239,165.974627,0,14.03629709,0,123.9136117 +68.4,50.40008562,-3.411434341,10000,-111.6167133,165.9615326,0,14.03629709,0,123.9206377 +68.41,50.4000756,-3.411411036,10000,-111.6306395,165.9484382,0,14.03629709,0,123.9276636 +68.42,50.40006558,-3.411387733,10000,-111.6376025,165.9353438,0,14.03629709,0,123.9346895 +68.43,50.40005556,-3.411364432,10000,-111.6550103,165.9222494,0,14.03629709,0,123.9417154 +68.44,50.40004554,-3.411341132,10000,-111.6898262,165.9082648,0,14.03629709,0,123.9487413 +68.45,50.40003551,-3.411317835,10000,-111.724642,165.8938352,0,14.03629709,0,123.9557673 +68.46,50.40002548,-3.41129454,10000,-111.7420499,165.8798507,0,14.03629709,0,123.9627932 +68.47,50.40001545,-3.411271246,10000,-111.7490129,165.8656436,0,14.03629709,0,123.9698191 +68.48,50.40000542,-3.411247955,10000,-111.7629391,165.8514365,0,14.03629709,0,123.976845 +68.49,50.39999539,-3.411224666,10000,-111.7838285,165.8385647,0,14.03629709,0,123.983871 +68.5,50.39998535,-3.411201378,10000,-111.8012363,165.8261378,0,14.03629709,0,123.9908969 +68.51,50.39997532,-3.411178092,10000,-111.8221258,165.8121533,0,14.03629709,0,123.9979228 +68.52,50.39996528,-3.411154808,10000,-111.8569416,165.7970561,0,14.03629709,0,124.0049487 +68.53,50.39995524,-3.411131527,10000,-111.8917574,165.782849,0,14.03629709,0,124.0119747 +68.54,50.39994519,-3.411108247,10000,-111.9091653,165.7697546,0,14.03629709,0,124.0190006 +68.55,50.39993515,-3.411084969,10000,-111.9126467,165.7566602,0,14.03629709,0,124.0260265 +68.56,50.3999251,-3.411061693,10000,-111.9196097,165.7435658,0,14.03629709,0,124.0330524 +68.57,50.39991506,-3.411038419,10000,-111.9474623,165.7304714,0,14.03629709,0,124.0400784 +68.58,50.39990501,-3.411015146,10000,-111.9857597,165.7164869,0,14.03629709,0,124.0471043 +68.59,50.39989495,-3.410991876,10000,-112.0031675,165.7020573,0,14.03629709,0,124.0541302 +68.6,50.3998849,-3.410968608,10000,-112.0066489,165.6880728,0,14.03629709,0,124.0611561 +68.61,50.39987485,-3.410945341,10000,-112.0275384,165.6738657,0,14.03629709,0,124.0681821 +68.62,50.39986479,-3.410922077,10000,-112.0588726,165.6596587,0,14.03629709,0,124.075208 +68.63,50.39985473,-3.410898815,10000,-112.079762,165.6465643,0,14.03629709,0,124.0822339 +68.64,50.39984467,-3.410875554,10000,-112.0971699,165.6334699,0,14.03629709,0,124.0892598 +68.65,50.39983461,-3.410852295,10000,-112.1180593,165.6192628,0,14.03629709,0,124.0962858 +68.66,50.39982454,-3.410829039,10000,-112.1354671,165.6052783,0,14.03629709,0,124.1033117 +68.67,50.39981448,-3.410805784,10000,-112.1528749,165.5921839,0,14.03629709,0,124.1103376 +68.68,50.39980441,-3.410782531,10000,-112.177246,165.5788669,0,14.03629709,0,124.1173635 +68.69,50.39979434,-3.41075928,10000,-112.2050986,165.5648824,0,14.03629709,0,124.1243895 +68.7,50.39978427,-3.410736031,10000,-112.2294696,165.5506754,0,14.03629709,0,124.1314153 +68.71,50.39977419,-3.410712784,10000,-112.2468774,165.5364683,0,14.03629709,0,124.1384413 +68.72,50.39976412,-3.410689539,10000,-112.2642852,165.5224838,0,14.03629709,0,124.1454672 +68.73,50.39975404,-3.410666296,10000,-112.2851747,165.5091669,0,14.03629709,0,124.1524931 +68.74,50.39974396,-3.410643055,10000,-112.2991009,165.4960725,0,14.03629709,0,124.159519 +68.75,50.39973388,-3.410619815,10000,-112.3060639,165.4820879,0,14.03629709,0,124.166545 +68.76,50.3997238,-3.410596578,10000,-112.3234717,165.4676584,0,14.03629709,0,124.1735709 +68.77,50.39971372,-3.410573343,10000,-112.3582875,165.4538964,0,14.03629709,0,124.1805968 +68.78,50.39970363,-3.410550109,10000,-112.3931034,165.4403569,0,14.03629709,0,124.1876227 +68.79,50.39969354,-3.410526878,10000,-112.4105112,165.4263724,0,14.03629709,0,124.1946487 +68.8,50.39968345,-3.410503648,10000,-112.4174742,165.4123879,0,14.03629709,0,124.2016746 +68.81,50.39967336,-3.410480421,10000,-112.4314004,165.3990709,0,14.03629709,0,124.2087005 +68.82,50.39966327,-3.410457195,10000,-112.4522898,165.3859766,0,14.03629709,0,124.2157264 +68.83,50.39965317,-3.410433971,10000,-112.4696977,165.3717695,0,14.03629709,0,124.2227523 +68.84,50.39964308,-3.410410749,10000,-112.4905871,165.3566723,0,14.03629709,0,124.2297783 +68.85,50.39963298,-3.41038753,10000,-112.5254029,165.3426878,0,14.03629709,0,124.2368042 +68.86,50.39962288,-3.410364312,10000,-112.5602187,165.330261,0,14.03629709,0,124.2438301 +68.87,50.39961277,-3.410341096,10000,-112.5811082,165.3173892,0,14.03629709,0,124.250856 +68.88,50.39960267,-3.410317881,10000,-112.5950344,165.3031821,0,14.03629709,0,124.257882 +68.89,50.39959256,-3.41029467,10000,-112.605479,165.2889751,0,14.03629709,0,124.2649079 +68.9,50.39958245,-3.410271459,10000,-112.6159236,165.2749905,0,14.03629709,0,124.2719338 +68.91,50.39957235,-3.410248251,10000,-112.6402946,165.260561,0,14.03629709,0,124.2789597 +68.92,50.39956223,-3.410225045,10000,-112.6716289,165.2465764,0,14.03629709,0,124.2859857 +68.93,50.39955212,-3.410201841,10000,-112.6890367,165.2332595,0,14.03629709,0,124.2930116 +68.94,50.399542,-3.410178638,10000,-112.6959997,165.219275,0,14.03629709,0,124.3000375 +68.95,50.39953189,-3.410155438,10000,-112.7099259,165.205068,0,14.03629709,0,124.3070634 +68.96,50.39952177,-3.41013224,10000,-112.7342969,165.1919736,0,14.03629709,0,124.3140894 +68.97,50.39951165,-3.410109043,10000,-112.7621495,165.1788792,0,14.03629709,0,124.3211153 +68.98,50.39950153,-3.410085848,10000,-112.7865206,165.1646721,0,14.03629709,0,124.3281412 +68.99,50.3994914,-3.410062656,10000,-112.8039284,165.1506876,0,14.03629709,0,124.3351671 +69,50.39948128,-3.410039465,10000,-112.8213362,165.1373707,0,14.03629709,0,124.3421931 +69.01,50.39947115,-3.410016276,10000,-112.8457072,165.1231637,0,14.03629709,0,124.349219 +69.02,50.39946102,-3.409993089,10000,-112.8735599,165.1080665,0,14.03629709,0,124.3562449 +69.03,50.39945089,-3.409969905,10000,-112.8979309,165.0938594,0,14.03629709,0,124.3632708 +69.04,50.39944075,-3.409946722,10000,-112.9153387,165.0807651,0,14.03629709,0,124.3702968 +69.05,50.39943062,-3.409923541,10000,-112.9327465,165.0674482,0,14.03629709,0,124.3773226 +69.06,50.39942048,-3.409900362,10000,-112.9536359,165.0536862,0,14.03629709,0,124.3843486 +69.07,50.39941034,-3.409877185,10000,-112.9710437,165.0403693,0,14.03629709,0,124.3913745 +69.08,50.3994002,-3.40985401,10000,-112.9884516,165.0272749,0,14.03629709,0,124.3984004 +69.09,50.39939006,-3.409830836,10000,-113.009341,165.0130679,0,14.03629709,0,124.4054263 +69.1,50.39937991,-3.409807665,10000,-113.0267488,164.9977481,0,14.03629709,0,124.4124523 +69.11,50.39936977,-3.409784496,10000,-113.0441566,164.9828735,0,14.03629709,0,124.4194782 +69.12,50.39935962,-3.409761329,10000,-113.0685276,164.9695566,0,14.03629709,0,124.4265041 +69.13,50.39934947,-3.409738164,10000,-113.0963802,164.9571298,0,14.03629709,0,124.43353 +69.14,50.39933932,-3.409715,10000,-113.1207513,164.9433679,0,14.03629709,0,124.440556 +69.15,50.39932916,-3.409691838,10000,-113.1381591,164.9280481,0,14.03629709,0,124.4475819 +69.16,50.39931901,-3.40966868,10000,-113.1555669,164.9140636,0,14.03629709,0,124.4546078 +69.17,50.39930885,-3.409645522,10000,-113.1764563,164.9018594,0,14.03629709,0,124.4616337 +69.18,50.39929869,-3.409622366,10000,-113.1903825,164.8885425,0,14.03629709,0,124.4686597 +69.19,50.39928853,-3.409599212,10000,-113.1973455,164.8734453,0,14.03629709,0,124.4756856 +69.2,50.39927837,-3.409576061,10000,-113.2147533,164.8583481,0,14.03629709,0,124.4827115 +69.21,50.39926821,-3.409552911,10000,-113.2495692,164.8441411,0,14.03629709,0,124.4897374 +69.22,50.39925804,-3.409529764,10000,-113.284385,164.8308242,0,14.03629709,0,124.4967633 +69.23,50.39924787,-3.409506618,10000,-113.3017928,164.8179524,0,14.03629709,0,124.5037893 +69.24,50.3992377,-3.409483474,10000,-113.3087558,164.8046355,0,14.03629709,0,124.5108152 +69.25,50.39922753,-3.409460332,10000,-113.322682,164.790651,0,14.03629709,0,124.5178411 +69.26,50.39921736,-3.409437192,10000,-113.3435714,164.7764439,0,14.03629709,0,124.524867 +69.27,50.39920718,-3.409414054,10000,-113.3609793,164.7622369,0,14.03629709,0,124.531893 +69.28,50.39919701,-3.409390918,10000,-113.3818687,164.7480298,0,14.03629709,0,124.5389189 +69.29,50.39918683,-3.409367784,10000,-113.4166845,164.7338228,0,14.03629709,0,124.5459448 +69.3,50.39917665,-3.409344652,10000,-113.4515003,164.7198383,0,14.03629709,0,124.5529707 +69.31,50.39916646,-3.409321522,10000,-113.4689081,164.7065214,0,14.03629709,0,124.5599967 +69.32,50.39915628,-3.409298394,10000,-113.4723895,164.693427,0,14.03629709,0,124.5670226 +69.33,50.39914609,-3.409275267,10000,-113.4793525,164.6794425,0,14.03629709,0,124.5740485 +69.34,50.39913591,-3.409252143,10000,-113.5072052,164.6650129,0,14.03629709,0,124.5810744 +69.35,50.39912572,-3.409229021,10000,-113.5455026,164.6510284,0,14.03629709,0,124.5881004 +69.36,50.39911552,-3.4092059,10000,-113.5629104,164.6368214,0,14.03629709,0,124.5951262 +69.37,50.39910533,-3.409182782,10000,-113.5663918,164.6223918,0,14.03629709,0,124.6021522 +69.38,50.39909514,-3.409159666,10000,-113.5872812,164.6086299,0,14.03629709,0,124.6091781 +69.39,50.39908494,-3.409136551,10000,-113.6186155,164.595313,0,14.03629709,0,124.616204 +69.4,50.39907474,-3.409113439,10000,-113.6395049,164.5819961,0,14.03629709,0,124.6232299 +69.41,50.39906454,-3.409090328,10000,-113.6569127,164.5680116,0,14.03629709,0,124.6302559 +69.42,50.39905434,-3.409067219,10000,-113.6778021,164.5526919,0,14.03629709,0,124.6372818 +69.43,50.39904413,-3.409044113,10000,-113.6952099,164.5375947,0,14.03629709,0,124.6443077 +69.44,50.39903393,-3.409021009,10000,-113.7126177,164.5242778,0,14.03629709,0,124.6513336 +69.45,50.39902372,-3.408997906,10000,-113.7335071,164.511406,0,14.03629709,0,124.6583596 +69.46,50.39901351,-3.408974805,10000,-113.750915,164.4978665,0,14.03629709,0,124.6653855 +69.47,50.3990033,-3.408951707,10000,-113.7718044,164.4841046,0,14.03629709,0,124.6724114 +69.48,50.39899309,-3.408928609,10000,-113.8031386,164.4698975,0,14.03629709,0,124.6794373 +69.49,50.39898287,-3.408905515,10000,-113.8275096,164.455468,0,14.03629709,0,124.6864633 +69.5,50.39897265,-3.408882422,10000,-113.8414358,164.441706,0,14.03629709,0,124.6934892 +69.51,50.39896244,-3.408859331,10000,-113.8623252,164.4281666,0,14.03629709,0,124.7005151 +69.52,50.39895221,-3.408836242,10000,-113.8832146,164.4141821,0,14.03629709,0,124.707541 +69.53,50.39894199,-3.408813155,10000,-113.8971408,164.3999751,0,14.03629709,0,124.714567 +69.54,50.39893177,-3.40879007,10000,-113.9215119,164.385768,0,14.03629709,0,124.7215929 +69.55,50.39892154,-3.408766987,10000,-113.9528461,164.371561,0,14.03629709,0,124.7286188 +69.56,50.39891131,-3.408743906,10000,-113.9702539,164.357354,0,14.03629709,0,124.7356447 +69.57,50.39890108,-3.408720827,10000,-113.9737353,164.3431469,0,14.03629709,0,124.7426707 +69.58,50.39889085,-3.40869775,10000,-113.9772167,164.3291624,0,14.03629709,0,124.7496966 +69.59,50.39888062,-3.408674675,10000,-113.9946245,164.3158455,0,14.03629709,0,124.7567225 +69.6,50.39887039,-3.408651602,10000,-114.0294403,164.3029737,0,14.03629709,0,124.7637484 +69.61,50.39886015,-3.40862853,10000,-114.0642561,164.2896568,0,14.03629709,0,124.7707744 +69.62,50.39884991,-3.408605461,10000,-114.0851456,164.2754498,0,14.03629709,0,124.7778003 +69.63,50.39883967,-3.408582393,10000,-114.1025534,164.2603526,0,14.03629709,0,124.7848262 +69.64,50.39882943,-3.408559328,10000,-114.1234428,164.2450329,0,14.03629709,0,124.7918521 +69.65,50.39881918,-3.408536265,10000,-114.1408506,164.2308259,0,14.03629709,0,124.798878 +69.66,50.39880894,-3.408513204,10000,-114.1582584,164.2177315,0,14.03629709,0,124.805904 +69.67,50.39879869,-3.408490144,10000,-114.1791478,164.2046372,0,14.03629709,0,124.8129299 +69.68,50.39878844,-3.408467087,10000,-114.1965556,164.1913203,0,14.03629709,0,124.8199558 +69.69,50.39877819,-3.408444031,10000,-114.2139634,164.1773358,0,14.03629709,0,124.8269817 +69.7,50.39876794,-3.408420977,10000,-114.2348528,164.1620161,0,14.03629709,0,124.8340077 +69.71,50.39875768,-3.408397926,10000,-114.2522607,164.1469189,0,14.03629709,0,124.8410335 +69.72,50.39874743,-3.408374877,10000,-114.2731501,164.133602,0,14.03629709,0,124.8480595 +69.73,50.39873717,-3.408351829,10000,-114.3079659,164.1205077,0,14.03629709,0,124.8550854 +69.74,50.39872691,-3.408328783,10000,-114.3393001,164.1063006,0,14.03629709,0,124.8621113 +69.75,50.39871664,-3.40830574,10000,-114.3462631,164.0920936,0,14.03629709,0,124.8691372 +69.76,50.39870638,-3.408282698,10000,-114.3462629,164.0781091,0,14.03629709,0,124.8761632 +69.77,50.39869612,-3.408259658,10000,-114.3671523,164.0636795,0,14.03629709,0,124.8831891 +69.78,50.39868585,-3.408236621,10000,-114.4019681,164.049695,0,14.03629709,0,124.890215 +69.79,50.39867558,-3.408213585,10000,-114.4333023,164.0363782,0,14.03629709,0,124.8972409 +69.8,50.39866531,-3.408190551,10000,-114.4576734,164.0221711,0,14.03629709,0,124.9042669 +69.81,50.39865503,-3.408167519,10000,-114.4750812,164.0070739,0,14.03629709,0,124.9112928 +69.82,50.39864476,-3.40814449,10000,-114.492489,163.9928669,0,14.03629709,0,124.9183187 +69.83,50.39863448,-3.408121462,10000,-114.5133784,163.9797726,0,14.03629709,0,124.9253446 +69.84,50.3986242,-3.408098436,10000,-114.5273046,163.9662332,0,14.03629709,0,124.9323706 +69.85,50.39861392,-3.408075412,10000,-114.5342676,163.9515811,0,14.03629709,0,124.9393965 +69.86,50.39860364,-3.40805239,10000,-114.5481938,163.9371515,0,14.03629709,0,124.9464224 +69.87,50.39859336,-3.408029371,10000,-114.5690832,163.9240572,0,14.03629709,0,124.9534483 +69.88,50.39858307,-3.408006352,10000,-114.586491,163.9107403,0,14.03629709,0,124.9604743 +69.89,50.39857279,-3.407983336,10000,-114.6073804,163.8954205,0,14.03629709,0,124.9675002 +69.9,50.3985625,-3.407960322,10000,-114.6421963,163.8796557,0,14.03629709,0,124.9745261 +69.91,50.39855221,-3.407937311,10000,-114.6770121,163.8661163,0,14.03629709,0,124.981552 +69.92,50.39854191,-3.407914301,10000,-114.6979015,163.8541347,0,14.03629709,0,124.988578 +69.93,50.39853162,-3.407891292,10000,-114.7153093,163.8408178,0,14.03629709,0,124.9956039 +69.94,50.39852132,-3.407868286,10000,-114.7361987,163.8257206,0,14.03629709,0,125.0026298 +69.95,50.39851102,-3.407845282,10000,-114.7501249,163.8106235,0,14.03629709,0,125.0096557 +69.96,50.39850072,-3.40782228,10000,-114.7570879,163.7961939,0,14.03629709,0,125.0166817 +69.97,50.39849042,-3.40779928,10000,-114.7710141,163.7819868,0,14.03629709,0,125.0237076 +69.98,50.39848012,-3.407776282,10000,-114.7919035,163.7680024,0,14.03629709,0,125.0307335 +69.99,50.39846981,-3.407753286,10000,-114.8093113,163.7546855,0,14.03629709,0,125.0377594 +70,50.39845951,-3.407730292,10000,-114.8302007,163.7415911,0,14.03629709,0,125.0447854 +70.01,50.3984492,-3.407707299,10000,-114.8650165,163.7273841,0,14.03629709,0,125.0518113 +70.02,50.39843889,-3.407684309,10000,-114.8998324,163.7122869,0,14.03629709,0,125.0588372 +70.03,50.39842857,-3.407661321,10000,-114.9172402,163.6980799,0,14.03629709,0,125.0658631 +70.04,50.39841826,-3.407638335,10000,-114.9207216,163.684763,0,14.03629709,0,125.072889 +70.05,50.39840794,-3.40761535,10000,-114.924203,163.6707785,0,14.03629709,0,125.079915 +70.06,50.39839763,-3.407592368,10000,-114.9416108,163.656349,0,14.03629709,0,125.0869408 +70.07,50.39838731,-3.407569388,10000,-114.9764266,163.6423645,0,14.03629709,0,125.0939668 +70.08,50.39837699,-3.407546409,10000,-115.0112424,163.6279349,0,14.03629709,0,125.1009927 +70.09,50.39836666,-3.407523433,10000,-115.0321318,163.6128377,0,14.03629709,0,125.1080186 +70.1,50.39835634,-3.407500459,10000,-115.0495396,163.5988532,0,14.03629709,0,125.1150445 +70.11,50.39834601,-3.407477487,10000,-115.070429,163.5864265,0,14.03629709,0,125.1220705 +70.12,50.39833568,-3.407454516,10000,-115.0878368,163.5733322,0,14.03629709,0,125.1290964 +70.13,50.39832535,-3.407431547,10000,-115.1052446,163.558235,0,14.03629709,0,125.1361223 +70.14,50.39831502,-3.407408581,10000,-115.126134,163.5429153,0,14.03629709,0,125.1431482 +70.15,50.39830468,-3.407385617,10000,-115.1435418,163.5289308,0,14.03629709,0,125.1501742 +70.16,50.39829435,-3.407362654,10000,-115.1609496,163.5153914,0,14.03629709,0,125.1572001 +70.17,50.39828401,-3.407339694,10000,-115.1818391,163.5011843,0,14.03629709,0,125.164226 +70.18,50.39827367,-3.407316735,10000,-115.1992469,163.4863097,0,14.03629709,0,125.1712519 +70.19,50.39826333,-3.407293779,10000,-115.2201363,163.4716576,0,14.03629709,0,125.1782779 +70.2,50.39825299,-3.407270825,10000,-115.2514705,163.4578956,0,14.03629709,0,125.1853038 +70.21,50.39824264,-3.407247872,10000,-115.2723599,163.4443562,0,14.03629709,0,125.1923297 +70.22,50.39823229,-3.407224922,10000,-115.2758413,163.4303717,0,14.03629709,0,125.1993556 +70.23,50.39822195,-3.407201973,10000,-115.2932491,163.4161647,0,14.03629709,0,125.2063816 +70.24,50.3982116,-3.407179027,10000,-115.3315465,163.4019577,0,14.03629709,0,125.2134075 +70.25,50.39820124,-3.407156082,10000,-115.3593991,163.3877506,0,14.03629709,0,125.2204334 +70.26,50.39819089,-3.40713314,10000,-115.3663621,163.3735436,0,14.03629709,0,125.2274593 +70.27,50.39818053,-3.407110199,10000,-115.3733251,163.3593366,0,14.03629709,0,125.2344853 +70.28,50.39817018,-3.407087261,10000,-115.4011777,163.3451295,0,14.03629709,0,125.2415112 +70.29,50.39815982,-3.407064324,10000,-115.4394751,163.3309225,0,14.03629709,0,125.2485371 +70.3,50.39814945,-3.40704139,10000,-115.4568829,163.3167155,0,14.03629709,0,125.255563 +70.31,50.39813909,-3.407018457,10000,-115.4603643,163.302731,0,14.03629709,0,125.262589 +70.32,50.39812873,-3.406995527,10000,-115.4812537,163.2894141,0,14.03629709,0,125.2696149 +70.33,50.39811836,-3.406972598,10000,-115.5125879,163.2763198,0,14.03629709,0,125.2766408 +70.34,50.39810799,-3.406949671,10000,-115.5299957,163.2618902,0,14.03629709,0,125.2836667 +70.35,50.39809762,-3.406926746,10000,-115.5369587,163.2459029,0,14.03629709,0,125.2906927 +70.36,50.39808725,-3.406903824,10000,-115.5543666,163.2303606,0,14.03629709,0,125.2977186 +70.37,50.39807688,-3.406880904,10000,-115.5891824,163.2163761,0,14.03629709,0,125.3047445 +70.38,50.3980665,-3.406857985,10000,-115.6239982,163.2030593,0,14.03629709,0,125.3117704 +70.39,50.39805612,-3.406835069,10000,-115.641406,163.1899649,0,14.03629709,0,125.3187964 +70.4,50.39804574,-3.406812154,10000,-115.6448874,163.1768706,0,14.03629709,0,125.3258222 +70.41,50.39803536,-3.406789241,10000,-115.6483687,163.1626636,0,14.03629709,0,125.3328482 +70.42,50.39802498,-3.40676633,10000,-115.6657766,163.1473438,0,14.03629709,0,125.3398741 +70.43,50.3980146,-3.406743422,10000,-115.7005924,163.1322466,0,14.03629709,0,125.3469 +70.44,50.39800421,-3.406720515,10000,-115.7354082,163.1178171,0,14.03629709,0,125.3539259 +70.45,50.39799382,-3.406697611,10000,-115.752816,163.10361,0,14.03629709,0,125.3609518 +70.46,50.39798343,-3.406674708,10000,-115.759779,163.0896256,0,14.03629709,0,125.3679778 +70.47,50.39797304,-3.406651808,10000,-115.7771868,163.0763087,0,14.03629709,0,125.3750037 +70.48,50.39796265,-3.406628909,10000,-115.808521,163.0632144,0,14.03629709,0,125.3820296 +70.49,50.39795225,-3.406606012,10000,-115.8294104,163.0487848,0,14.03629709,0,125.3890555 +70.5,50.39794185,-3.406583117,10000,-115.8328918,163.03302,0,14.03629709,0,125.3960815 +70.51,50.39793146,-3.406560225,10000,-115.8502996,163.0183678,0,14.03629709,0,125.4031074 +70.52,50.39792106,-3.406537335,10000,-115.888597,163.0054961,0,14.03629709,0,125.4101333 +70.53,50.39791065,-3.406514445,10000,-115.9199312,162.9919567,0,14.03629709,0,125.4171592 +70.54,50.39790025,-3.406491559,10000,-115.9408206,162.9768595,0,14.03629709,0,125.4241852 +70.55,50.39788984,-3.406468674,10000,-115.96171,162.9617623,0,14.03629709,0,125.4312111 +70.56,50.39787943,-3.406445792,10000,-115.9756362,162.9473327,0,14.03629709,0,125.438237 +70.57,50.39786902,-3.406422911,10000,-115.9791176,162.9333482,0,14.03629709,0,125.4452629 +70.58,50.39785861,-3.406400033,10000,-115.982599,162.9198088,0,14.03629709,0,125.4522889 +70.59,50.3978482,-3.406377156,10000,-116.0000068,162.9060469,0,14.03629709,0,125.4593148 +70.6,50.39783779,-3.406354281,10000,-116.0348226,162.8913947,0,14.03629709,0,125.4663407 +70.61,50.39782737,-3.406331409,10000,-116.0696384,162.8765201,0,14.03629709,0,125.4733666 +70.62,50.39781695,-3.406308538,10000,-116.0905278,162.8620905,0,14.03629709,0,125.4803926 +70.63,50.39780653,-3.40628567,10000,-116.1079356,162.8478835,0,14.03629709,0,125.4874185 +70.64,50.39779611,-3.406262803,10000,-116.128825,162.833899,0,14.03629709,0,125.4944444 +70.65,50.39778568,-3.406239939,10000,-116.1462328,162.8203596,0,14.03629709,0,125.5014703 +70.66,50.39777526,-3.406217076,10000,-116.1636406,162.8065976,0,14.03629709,0,125.5084963 +70.67,50.39776483,-3.406194215,10000,-116.18453,162.7921681,0,14.03629709,0,125.5155222 +70.68,50.3977544,-3.406171357,10000,-116.2019378,162.777961,0,14.03629709,0,125.5225481 +70.69,50.39774397,-3.4061485,10000,-116.2193456,162.7639765,0,14.03629709,0,125.529574 +70.7,50.39773354,-3.406125645,10000,-116.240235,162.7493244,0,14.03629709,0,125.5366 +70.71,50.3977231,-3.406102793,10000,-116.2576428,162.7344497,0,14.03629709,0,125.5436259 +70.72,50.39771267,-3.406079942,10000,-116.2785322,162.7200202,0,14.03629709,0,125.5506518 +70.73,50.39770223,-3.406057094,10000,-116.313348,162.7058131,0,14.03629709,0,125.5576777 +70.74,50.39769179,-3.406034247,10000,-116.3446822,162.6916061,0,14.03629709,0,125.5647037 +70.75,50.39768134,-3.406011403,10000,-116.3516452,162.6773991,0,14.03629709,0,125.5717295 +70.76,50.3976709,-3.40598856,10000,-116.351645,162.663192,0,14.03629709,0,125.5787555 +70.77,50.39766046,-3.40596572,10000,-116.3725344,162.648985,0,14.03629709,0,125.5857814 +70.78,50.39765001,-3.405942881,10000,-116.4038686,162.634778,0,14.03629709,0,125.5928073 +70.79,50.39763956,-3.405920045,10000,-116.424758,162.6205709,0,14.03629709,0,125.5998332 +70.8,50.39762911,-3.40589721,10000,-116.4421658,162.6063639,0,14.03629709,0,125.6068592 +70.81,50.39761866,-3.405874378,10000,-116.4630552,162.5919343,0,14.03629709,0,125.6138851 +70.82,50.3976082,-3.405851547,10000,-116.480463,162.5770596,0,14.03629709,0,125.620911 +70.83,50.39759775,-3.405828719,10000,-116.4978708,162.5624075,0,14.03629709,0,125.6279369 +70.84,50.39758729,-3.405805893,10000,-116.5222418,162.5486456,0,14.03629709,0,125.6349628 +70.85,50.39757683,-3.405783068,10000,-116.5500944,162.5351062,0,14.03629709,0,125.6419888 +70.86,50.39756637,-3.405760246,10000,-116.5744654,162.5211217,0,14.03629709,0,125.6490147 +70.87,50.3975559,-3.405737425,10000,-116.5918732,162.5069147,0,14.03629709,0,125.6560406 +70.88,50.39754544,-3.405714607,10000,-116.609281,162.4927076,0,14.03629709,0,125.6630665 +70.89,50.39753497,-3.40569179,10000,-116.6301704,162.4785006,0,14.03629709,0,125.6700925 +70.9,50.3975245,-3.405668976,10000,-116.6440966,162.464071,0,14.03629709,0,125.6771184 +70.91,50.39751403,-3.405646163,10000,-116.6510596,162.4489738,0,14.03629709,0,125.6841443 +70.92,50.39750356,-3.405623353,10000,-116.6684674,162.433654,0,14.03629709,0,125.6911702 +70.93,50.39749309,-3.405600545,10000,-116.7032832,162.419447,0,14.03629709,0,125.6981962 +70.94,50.39748261,-3.405577739,10000,-116.738099,162.4061301,0,14.03629709,0,125.7052221 +70.95,50.39747213,-3.405554934,10000,-116.7555068,162.3921456,0,14.03629709,0,125.712248 +70.96,50.39746165,-3.405532132,10000,-116.7624698,162.3777161,0,14.03629709,0,125.7192739 +70.97,50.39745117,-3.405509332,10000,-116.776396,162.3637316,0,14.03629709,0,125.7262999 +70.98,50.39744069,-3.405486533,10000,-116.7972854,162.349302,0,14.03629709,0,125.7333258 +70.99,50.3974302,-3.405463737,10000,-116.8146932,162.3339822,0,14.03629709,0,125.7403517 +71,50.39741972,-3.405440943,10000,-116.832101,162.318885,0,14.03629709,0,125.7473776 +71.01,50.39740923,-3.405418151,10000,-116.856472,162.304678,0,14.03629709,0,125.7544036 +71.02,50.39739874,-3.405395361,10000,-116.8843246,162.2913611,0,14.03629709,0,125.7614295 +71.03,50.39738825,-3.405372573,10000,-116.9086956,162.2782668,0,14.03629709,0,125.7684554 +71.04,50.39737775,-3.405349786,10000,-116.9261034,162.2640597,0,14.03629709,0,125.7754813 +71.05,50.39736726,-3.405327002,10000,-116.9435112,162.24874,0,14.03629709,0,125.7825073 +71.06,50.39735676,-3.40530422,10000,-116.9644006,162.2336428,0,14.03629709,0,125.7895331 +71.07,50.39734626,-3.40528144,10000,-116.9818084,162.2192132,0,14.03629709,0,125.7965591 +71.08,50.39733576,-3.405258662,10000,-116.9992162,162.2050061,0,14.03629709,0,125.803585 +71.09,50.39732526,-3.405235886,10000,-117.0201056,162.1907991,0,14.03629709,0,125.8106109 +71.1,50.39731475,-3.405213112,10000,-117.0375133,162.1765921,0,14.03629709,0,125.8176368 +71.11,50.39730425,-3.40519034,10000,-117.0549211,162.162385,0,14.03629709,0,125.8246628 +71.12,50.39729374,-3.40516757,10000,-117.0792921,162.148178,0,14.03629709,0,125.8316887 +71.13,50.39728323,-3.405144802,10000,-117.1071447,162.1339709,0,14.03629709,0,125.8387146 +71.14,50.39727272,-3.405122036,10000,-117.1315157,162.1197639,0,14.03629709,0,125.8457405 +71.15,50.3972622,-3.405099272,10000,-117.1489235,162.1055569,0,14.03629709,0,125.8527665 +71.16,50.39725169,-3.40507651,10000,-117.1663313,162.0911273,0,14.03629709,0,125.8597924 +71.17,50.39724117,-3.40505375,10000,-117.1872207,162.0760301,0,14.03629709,0,125.8668183 +71.18,50.39723065,-3.405030992,10000,-117.2011469,162.0607103,0,14.03629709,0,125.8738442 +71.19,50.39722013,-3.405008237,10000,-117.2081099,162.0465032,0,14.03629709,0,125.8808702 +71.2,50.39720961,-3.404985483,10000,-117.2255177,162.0334089,0,14.03629709,0,125.8878961 +71.21,50.39719909,-3.404962731,10000,-117.2603335,162.0198695,0,14.03629709,0,125.894922 +71.22,50.39718856,-3.404939981,10000,-117.2951493,162.0049948,0,14.03629709,0,125.9019479 +71.23,50.39717803,-3.404917233,10000,-117.3125571,161.9894525,0,14.03629709,0,125.9089738 +71.24,50.3971675,-3.404894488,10000,-117.3195201,161.9743553,0,14.03629709,0,125.9159998 +71.25,50.39715697,-3.404871744,10000,-117.3334463,161.9601482,0,14.03629709,0,125.9230257 +71.26,50.39714644,-3.404849003,10000,-117.3543357,161.9466088,0,14.03629709,0,125.9300516 +71.27,50.3971359,-3.404826263,10000,-117.3717435,161.9328469,0,14.03629709,0,125.9370775 +71.28,50.39712537,-3.404803525,10000,-117.3891513,161.9184173,0,14.03629709,0,125.9441035 +71.29,50.39711483,-3.40478079,10000,-117.4135222,161.9042102,0,14.03629709,0,125.9511294 +71.3,50.39710429,-3.404758056,10000,-117.4413748,161.8900032,0,14.03629709,0,125.9581553 +71.31,50.39709375,-3.404735324,10000,-117.4657458,161.8746834,0,14.03629709,0,125.9651812 +71.32,50.3970832,-3.404712595,10000,-117.4831536,161.8595862,0,14.03629709,0,125.9722072 +71.33,50.39707266,-3.404689868,10000,-117.5005614,161.8462693,0,14.03629709,0,125.9792331 +71.34,50.39706211,-3.404667142,10000,-117.5214508,161.8329525,0,14.03629709,0,125.986259 +71.35,50.39705156,-3.404644418,10000,-117.5388586,161.8178552,0,14.03629709,0,125.9932849 +71.36,50.39704101,-3.404621697,10000,-117.5562664,161.8025355,0,14.03629709,0,126.0003109 +71.37,50.39703046,-3.404598978,10000,-117.5771558,161.7883284,0,14.03629709,0,126.0073368 +71.38,50.3970199,-3.40457626,10000,-117.5945636,161.7738988,0,14.03629709,0,126.0143627 +71.39,50.39700935,-3.404553545,10000,-117.6119714,161.758579,0,14.03629709,0,126.0213886 +71.4,50.39699879,-3.404530832,10000,-117.6363424,161.7437043,0,14.03629709,0,126.0284146 +71.41,50.39698823,-3.404508121,10000,-117.664195,161.7301649,0,14.03629709,0,126.0354404 +71.42,50.39697767,-3.404485412,10000,-117.688566,161.7170706,0,14.03629709,0,126.0424664 +71.43,50.3969671,-3.404462704,10000,-117.7059738,161.7028636,0,14.03629709,0,126.0494923 +71.44,50.39695654,-3.404439999,10000,-117.7233815,161.6875438,0,14.03629709,0,126.0565182 +71.45,50.39694597,-3.404417296,10000,-117.7442709,161.6724466,0,14.03629709,0,126.0635441 +71.46,50.3969354,-3.404394595,10000,-117.7581971,161.658017,0,14.03629709,0,126.0705701 +71.47,50.39692483,-3.404371896,10000,-117.7651601,161.6438099,0,14.03629709,0,126.077596 +71.48,50.39691426,-3.404349199,10000,-117.7825679,161.6296028,0,14.03629709,0,126.0846219 +71.49,50.39690369,-3.404326504,10000,-117.8173837,161.6153958,0,14.03629709,0,126.0916478 +71.5,50.39689311,-3.404303811,10000,-117.8521995,161.6011887,0,14.03629709,0,126.0986738 +71.51,50.39688253,-3.40428112,10000,-117.8696073,161.5867592,0,14.03629709,0,126.1056997 +71.52,50.39687195,-3.404258431,10000,-117.8730887,161.5716619,0,14.03629709,0,126.1127256 +71.53,50.39686137,-3.404235744,10000,-117.8765701,161.5563421,0,14.03629709,0,126.1197515 +71.54,50.39685079,-3.40421306,10000,-117.8939779,161.5421351,0,14.03629709,0,126.1267775 +71.55,50.39684021,-3.404190377,10000,-117.9287937,161.5288182,0,14.03629709,0,126.1338034 +71.56,50.39682962,-3.404167696,10000,-117.9636094,161.5146111,0,14.03629709,0,126.1408293 +71.57,50.39681903,-3.404145017,10000,-117.9810172,161.4992913,0,14.03629709,0,126.1478552 +71.58,50.39680844,-3.404122341,10000,-117.9879802,161.4841941,0,14.03629709,0,126.1548812 +71.59,50.39679785,-3.404099666,10000,-118.005388,161.469987,0,14.03629709,0,126.1619071 +71.6,50.39678726,-3.404076994,10000,-118.0367222,161.4564476,0,14.03629709,0,126.168933 +71.61,50.39677666,-3.404054323,10000,-118.0610932,161.4424631,0,14.03629709,0,126.1759589 +71.62,50.39676606,-3.404031654,10000,-118.0750194,161.4271433,0,14.03629709,0,126.1829849 +71.63,50.39675547,-3.404008988,10000,-118.0959088,161.4118235,0,14.03629709,0,126.1900108 +71.64,50.39674486,-3.403986324,10000,-118.1167982,161.397839,0,14.03629709,0,126.1970367 +71.65,50.39673426,-3.403963661,10000,-118.1307243,161.3842996,0,14.03629709,0,126.2040626 +71.66,50.39672366,-3.403941001,10000,-118.1550953,161.3700926,0,14.03629709,0,126.2110885 +71.67,50.39671305,-3.403918342,10000,-118.1864295,161.3549953,0,14.03629709,0,126.2181145 +71.68,50.39670244,-3.403895686,10000,-118.2038373,161.3396755,0,14.03629709,0,126.2251404 +71.69,50.39669183,-3.403873032,10000,-118.2073187,161.3252459,0,14.03629709,0,126.2321663 +71.7,50.39668122,-3.40385038,10000,-118.2108001,161.3112614,0,14.03629709,0,126.2391922 +71.71,50.39667061,-3.403827729,10000,-118.2282079,161.2968318,0,14.03629709,0,126.2462182 +71.72,50.39666,-3.403805082,10000,-118.2630237,161.2826247,0,14.03629709,0,126.2532441 +71.73,50.39664938,-3.403782435,10000,-118.2978395,161.2686402,0,14.03629709,0,126.26027 +71.74,50.39663876,-3.403759791,10000,-118.3187289,161.253988,0,14.03629709,0,126.2672959 +71.75,50.39662814,-3.403737149,10000,-118.3361367,161.2388908,0,14.03629709,0,126.2743218 +71.76,50.39661752,-3.403714509,10000,-118.357026,161.2237935,0,14.03629709,0,126.2813477 +71.77,50.39660689,-3.403691871,10000,-118.3744338,161.2091414,0,14.03629709,0,126.2883737 +71.78,50.39659627,-3.403669236,10000,-118.3918416,161.1951569,0,14.03629709,0,126.2953996 +71.79,50.39658564,-3.403646601,10000,-118.412731,161.1809498,0,14.03629709,0,126.3024255 +71.8,50.39657501,-3.40362397,10000,-118.4266572,161.1662976,0,14.03629709,0,126.3094514 +71.81,50.39656438,-3.40360134,10000,-118.4336202,161.1514229,0,14.03629709,0,126.3164774 +71.82,50.39655375,-3.403578712,10000,-118.451028,161.1361031,0,14.03629709,0,126.3235033 +71.83,50.39654312,-3.403556087,10000,-118.4858438,161.1216735,0,14.03629709,0,126.3305292 +71.84,50.39653248,-3.403533464,10000,-118.5206596,161.1085792,0,14.03629709,0,126.3375551 +71.85,50.39652184,-3.403510841,10000,-118.5380673,161.0943721,0,14.03629709,0,126.3445811 +71.86,50.3965112,-3.403488222,10000,-118.5450303,161.0788298,0,14.03629709,0,126.351607 +71.87,50.39650056,-3.403465605,10000,-118.5589565,161.063955,0,14.03629709,0,126.3586329 +71.88,50.39648992,-3.403442989,10000,-118.5798459,161.0495254,0,14.03629709,0,126.3656588 +71.89,50.39647927,-3.403420376,10000,-118.5972537,161.0350958,0,14.03629709,0,126.3726848 +71.9,50.39646863,-3.403397765,10000,-118.6181431,161.0211113,0,14.03629709,0,126.3797107 +71.91,50.39645798,-3.403375155,10000,-118.6529589,161.0066817,0,14.03629709,0,126.3867366 +71.92,50.39644733,-3.403352548,10000,-118.6877747,160.9913618,0,14.03629709,0,126.3937625 +71.93,50.39643667,-3.403329943,10000,-118.7051824,160.9762646,0,14.03629709,0,126.4007885 +71.94,50.39642602,-3.40330734,10000,-118.7086638,160.9620575,0,14.03629709,0,126.4078144 +71.95,50.39641536,-3.403284739,10000,-118.7121452,160.9485181,0,14.03629709,0,126.4148403 +71.96,50.39640471,-3.40326214,10000,-118.729553,160.9345336,0,14.03629709,0,126.4218662 +71.97,50.39639405,-3.403239542,10000,-118.7643688,160.9192137,0,14.03629709,0,126.4288922 +71.98,50.39638339,-3.403216948,10000,-118.7991846,160.9036714,0,14.03629709,0,126.4359181 +71.99,50.39637272,-3.403194355,10000,-118.8165923,160.8890192,0,14.03629709,0,126.442944 +72,50.39636206,-3.403171764,10000,-118.8200737,160.8750347,0,14.03629709,0,126.4499699 +72.01,50.39635139,-3.403149176,10000,-118.8270367,160.8612727,0,14.03629709,0,126.4569959 +72.02,50.39634073,-3.403126588,10000,-118.8548893,160.8468431,0,14.03629709,0,126.4640218 +72.03,50.39633006,-3.403104004,10000,-118.8931867,160.8315233,0,14.03629709,0,126.4710477 +72.04,50.39631938,-3.403081421,10000,-118.9105945,160.816426,0,14.03629709,0,126.4780736 +72.05,50.39630871,-3.403058841,10000,-118.9140759,160.8019964,0,14.03629709,0,126.4850995 +72.06,50.39629804,-3.403036262,10000,-118.9349653,160.7877893,0,14.03629709,0,126.4921255 +72.07,50.39628736,-3.403013686,10000,-118.9662994,160.7733597,0,14.03629709,0,126.4991513 +72.08,50.39627668,-3.402991111,10000,-118.9871888,160.7584849,0,14.03629709,0,126.5061773 +72.09,50.396266,-3.402968539,10000,-119.0045966,160.7438328,0,14.03629709,0,126.5132032 +72.1,50.39625532,-3.402945969,10000,-119.025486,160.7298482,0,14.03629709,0,126.5202291 +72.11,50.39624463,-3.4029234,10000,-119.0428938,160.7154186,0,14.03629709,0,126.527255 +72.12,50.39623395,-3.402900834,10000,-119.0603016,160.7000988,0,14.03629709,0,126.534281 +72.13,50.39622326,-3.40287827,10000,-119.0811909,160.6850015,0,14.03629709,0,126.5413069 +72.14,50.39621257,-3.402855708,10000,-119.0985987,160.6705719,0,14.03629709,0,126.5483328 +72.15,50.39620188,-3.402833148,10000,-119.1160065,160.6563648,0,14.03629709,0,126.5553587 +72.16,50.39619119,-3.40281059,10000,-119.1368959,160.6421577,0,14.03629709,0,126.5623847 +72.17,50.39618049,-3.402788034,10000,-119.1543037,160.6277281,0,14.03629709,0,126.5694106 +72.18,50.3961698,-3.40276548,10000,-119.1717115,160.6126308,0,14.03629709,0,126.5764365 +72.19,50.3961591,-3.402742928,10000,-119.1960825,160.5970884,0,14.03629709,0,126.5834624 +72.2,50.3961484,-3.402720379,10000,-119.223935,160.5819911,0,14.03629709,0,126.5904884 +72.21,50.3961377,-3.402697831,10000,-119.248306,160.567784,0,14.03629709,0,126.5975143 +72.22,50.39612699,-3.402675286,10000,-119.2657138,160.5542446,0,14.03629709,0,126.6045402 +72.23,50.39611629,-3.402652742,10000,-119.2831216,160.5404826,0,14.03629709,0,126.6115661 +72.24,50.39610558,-3.4026302,10000,-119.304011,160.5258304,0,14.03629709,0,126.6185921 +72.25,50.39609487,-3.402607661,10000,-119.3179372,160.5107331,0,14.03629709,0,126.625618 +72.26,50.39608416,-3.402585123,10000,-119.3249001,160.4956359,0,14.03629709,0,126.6326439 +72.27,50.39607345,-3.402562588,10000,-119.3423079,160.4807611,0,14.03629709,0,126.6396698 +72.28,50.39606274,-3.402540055,10000,-119.3771237,160.4661089,0,14.03629709,0,126.6466958 +72.29,50.39605202,-3.402517523,10000,-119.4119395,160.4514567,0,14.03629709,0,126.6537217 +72.3,50.3960413,-3.402494995,10000,-119.4293473,160.4372496,0,14.03629709,0,126.6607476 +72.31,50.39603058,-3.402472467,10000,-119.4328287,160.4230426,0,14.03629709,0,126.6677735 +72.32,50.39601986,-3.402449942,10000,-119.43631,160.4075002,0,14.03629709,0,126.6747995 +72.33,50.39600914,-3.402427419,10000,-119.4537178,160.3915126,0,14.03629709,0,126.6818254 +72.34,50.39599842,-3.402404899,10000,-119.4885336,160.377083,0,14.03629709,0,126.6888513 +72.35,50.39598769,-3.40238238,10000,-119.5233494,160.3637661,0,14.03629709,0,126.6958772 +72.36,50.39597696,-3.402359863,10000,-119.5407572,160.349559,0,14.03629709,0,126.7029032 +72.37,50.39596623,-3.402337348,10000,-119.5477201,160.3342392,0,14.03629709,0,126.7099291 +72.38,50.3959555,-3.402314836,10000,-119.5651279,160.3191419,0,14.03629709,0,126.716955 +72.39,50.39594477,-3.402292325,10000,-119.5999437,160.3047122,0,14.03629709,0,126.7239809 +72.4,50.39593403,-3.402269817,10000,-119.6347595,160.2905051,0,14.03629709,0,126.7310069 +72.41,50.39592329,-3.40224731,10000,-119.6521673,160.2762981,0,14.03629709,0,126.7380328 +72.42,50.39591255,-3.402224806,10000,-119.6556487,160.2618684,0,14.03629709,0,126.7450587 +72.43,50.39590181,-3.402202303,10000,-119.65913,160.2467711,0,14.03629709,0,126.7520846 +72.44,50.39589107,-3.402179803,10000,-119.6765378,160.2314512,0,14.03629709,0,126.7591105 +72.45,50.39588033,-3.402157305,10000,-119.707872,160.2172441,0,14.03629709,0,126.7661364 +72.46,50.39586958,-3.402134809,10000,-119.732243,160.2037047,0,14.03629709,0,126.7731623 +72.47,50.39585883,-3.402112314,10000,-119.7461692,160.1886074,0,14.03629709,0,126.7801883 +72.48,50.39584809,-3.402089822,10000,-119.7670586,160.1721748,0,14.03629709,0,126.7872142 +72.49,50.39583733,-3.402067333,10000,-119.7879479,160.1568549,0,14.03629709,0,126.7942401 +72.5,50.39582658,-3.402044845,10000,-119.8018741,160.1426478,0,14.03629709,0,126.801266 +72.51,50.39581583,-3.402022359,10000,-119.8262451,160.1282182,0,14.03629709,0,126.808292 +72.52,50.39580507,-3.401999876,10000,-119.8575793,160.1140111,0,14.03629709,0,126.8153179 +72.53,50.39579431,-3.401977394,10000,-119.8749871,160.1000265,0,14.03629709,0,126.8223438 +72.54,50.39578355,-3.401954914,10000,-119.88195,160.0853743,0,14.03629709,0,126.8293697 +72.55,50.39577279,-3.401932437,10000,-119.8958762,160.070277,0,14.03629709,0,126.8363957 +72.56,50.39576203,-3.401909961,10000,-119.9167656,160.0551797,0,14.03629709,0,126.8434216 +72.57,50.39575126,-3.401887488,10000,-119.9341734,160.0405275,0,14.03629709,0,126.8504475 +72.58,50.3957405,-3.401865017,10000,-119.9550627,160.0265429,0,14.03629709,0,126.8574734 +72.59,50.39572973,-3.401842547,10000,-119.9898785,160.0121132,0,14.03629709,0,126.8644994 +72.6,50.39571896,-3.40182008,10000,-120.0246943,159.9967934,0,14.03629709,0,126.8715253 +72.61,50.39570818,-3.401797615,10000,-120.0421021,159.9816961,0,14.03629709,0,126.8785512 +72.62,50.39569741,-3.401775152,10000,-120.0455835,159.9672664,0,14.03629709,0,126.8855771 +72.63,50.39568663,-3.401752691,10000,-120.0490648,159.9528367,0,14.03629709,0,126.8926031 +72.64,50.39567586,-3.401730232,10000,-120.0664726,159.9377394,0,14.03629709,0,126.899629 +72.65,50.39566508,-3.401707775,10000,-120.1012884,159.9224195,0,14.03629709,0,126.9066549 +72.66,50.3956543,-3.401685321,10000,-120.1361042,159.9079899,0,14.03629709,0,126.9136808 +72.67,50.39564351,-3.401662868,10000,-120.1535119,159.8937828,0,14.03629709,0,126.9207068 +72.68,50.39563273,-3.401640417,10000,-120.1569933,159.8784629,0,14.03629709,0,126.9277327 +72.69,50.39562194,-3.401617969,10000,-120.1639563,159.863143,0,14.03629709,0,126.9347586 +72.7,50.39561116,-3.401595523,10000,-120.1918089,159.8491584,0,14.03629709,0,126.9417845 +72.71,50.39560037,-3.401573078,10000,-120.2301063,159.835619,0,14.03629709,0,126.9488105 +72.72,50.39558957,-3.401550636,10000,-120.2475141,159.8214119,0,14.03629709,0,126.9558364 +72.73,50.39557878,-3.401528195,10000,-120.2509954,159.8063146,0,14.03629709,0,126.9628623 +72.74,50.39556799,-3.401505757,10000,-120.2718848,159.7907721,0,14.03629709,0,126.9698882 +72.75,50.39555719,-3.401483321,10000,-120.303219,159.7754522,0,14.03629709,0,126.9769142 +72.76,50.39554639,-3.401460887,10000,-120.3241084,159.7601323,0,14.03629709,0,126.98394 +72.77,50.39553559,-3.401438455,10000,-120.3415161,159.7448125,0,14.03629709,0,126.990966 +72.78,50.39552479,-3.401416026,10000,-120.3624055,159.7303828,0,14.03629709,0,126.9979919 +72.79,50.39551398,-3.401393598,10000,-120.3798133,159.7163982,0,14.03629709,0,127.0050178 +72.8,50.39550318,-3.401371172,10000,-120.3972211,159.701746,0,14.03629709,0,127.0120437 +72.81,50.39549237,-3.401348749,10000,-120.4181105,159.6868712,0,14.03629709,0,127.0190697 +72.82,50.39548156,-3.401326327,10000,-120.4355182,159.6724415,0,14.03629709,0,127.0260956 +72.83,50.39547075,-3.401303908,10000,-120.452926,159.6580119,0,14.03629709,0,127.0331215 +72.84,50.39545994,-3.40128149,10000,-120.4738154,159.6429145,0,14.03629709,0,127.0401474 +72.85,50.39544912,-3.401259075,10000,-120.4912232,159.6273721,0,14.03629709,0,127.0471733 +72.86,50.39543831,-3.401236662,10000,-120.5086309,159.6124973,0,14.03629709,0,127.0541993 +72.87,50.39542749,-3.401214251,10000,-120.5295203,159.5987353,0,14.03629709,0,127.0612252 +72.88,50.39541667,-3.401191842,10000,-120.5469281,159.5847507,0,14.03629709,0,127.0682511 +72.89,50.39540585,-3.401169434,10000,-120.5678175,159.5692082,0,14.03629709,0,127.075277 +72.9,50.39539503,-3.40114703,10000,-120.5991516,159.5529981,0,14.03629709,0,127.082303 +72.91,50.3953842,-3.401124627,10000,-120.620041,159.5379008,0,14.03629709,0,127.0893289 +72.92,50.39537337,-3.401102227,10000,-120.6235224,159.5241388,0,14.03629709,0,127.0963548 +72.93,50.39536255,-3.401079828,10000,-120.6409302,159.5101542,0,14.03629709,0,127.1033807 +72.94,50.39535172,-3.401057431,10000,-120.6792276,159.4948343,0,14.03629709,0,127.1104067 +72.95,50.39534088,-3.401035037,10000,-120.7070801,159.4795144,0,14.03629709,0,127.1174326 +72.96,50.39533005,-3.401012645,10000,-120.7140431,159.4653073,0,14.03629709,0,127.1244585 +72.97,50.39531921,-3.400990254,10000,-120.7175245,159.4508776,0,14.03629709,0,127.1314844 +72.98,50.39530838,-3.400967866,10000,-120.7349322,159.4355577,0,14.03629709,0,127.1385104 +72.99,50.39529754,-3.40094548,10000,-120.769748,159.4204603,0,14.03629709,0,127.1455363 +73,50.3952867,-3.400923096,10000,-120.8045638,159.4060306,0,14.03629709,0,127.1525622 +73.01,50.39527585,-3.400900714,10000,-120.8219716,159.3918235,0,14.03629709,0,127.1595881 +73.02,50.39526501,-3.400878334,10000,-120.8254529,159.3773938,0,14.03629709,0,127.1666141 +73.03,50.39525416,-3.400855956,10000,-120.8289343,159.3622964,0,14.03629709,0,127.17364 +73.04,50.39524332,-3.40083358,10000,-120.8463421,159.346754,0,14.03629709,0,127.1806659 +73.05,50.39523247,-3.400811207,10000,-120.8811579,159.3316566,0,14.03629709,0,127.1876918 +73.06,50.39522162,-3.400788835,10000,-120.9159737,159.3172269,0,14.03629709,0,127.1947178 +73.07,50.39521076,-3.400766466,10000,-120.936863,159.3027972,0,14.03629709,0,127.2017437 +73.08,50.39519991,-3.400744098,10000,-120.9542708,159.2876999,0,14.03629709,0,127.2087696 +73.09,50.39518905,-3.400721733,10000,-120.9751602,159.2721574,0,14.03629709,0,127.2157955 +73.1,50.39517819,-3.40069937,10000,-120.9890863,159.25706,0,14.03629709,0,127.2228215 +73.11,50.39516733,-3.400677009,10000,-120.9960493,159.2426303,0,14.03629709,0,127.2298473 +73.12,50.39515647,-3.40065465,10000,-121.0099755,159.2282006,0,14.03629709,0,127.2368733 +73.13,50.39514561,-3.400632293,10000,-121.0308649,159.2131033,0,14.03629709,0,127.2438992 +73.14,50.39513474,-3.400609938,10000,-121.0482727,159.1977833,0,14.03629709,0,127.2509251 +73.15,50.39512388,-3.400587586,10000,-121.069162,159.1833536,0,14.03629709,0,127.257951 +73.16,50.39511301,-3.400565235,10000,-121.1039778,159.1691465,0,14.03629709,0,127.264977 +73.17,50.39510214,-3.400542886,10000,-121.1387936,159.1538266,0,14.03629709,0,127.2720029 +73.18,50.39509126,-3.40052054,10000,-121.1562013,159.1385066,0,14.03629709,0,127.2790288 +73.19,50.39508039,-3.400498196,10000,-121.1596827,159.1242995,0,14.03629709,0,127.2860547 +73.2,50.39506951,-3.400475853,10000,-121.1631641,159.1098698,0,14.03629709,0,127.2930807 +73.21,50.39505864,-3.400453513,10000,-121.1805719,159.0945498,0,14.03629709,0,127.3001066 +73.22,50.39504776,-3.400431175,10000,-121.2153876,159.0794525,0,14.03629709,0,127.3071325 +73.23,50.39503688,-3.400408839,10000,-121.2502034,159.0650228,0,14.03629709,0,127.3141584 +73.24,50.39502599,-3.400386505,10000,-121.2710928,159.0505931,0,14.03629709,0,127.3211843 +73.25,50.39501511,-3.400364173,10000,-121.2885005,159.0354957,0,14.03629709,0,127.3282103 +73.26,50.39500422,-3.400341843,10000,-121.3093899,159.0199532,0,14.03629709,0,127.3352362 +73.27,50.39499333,-3.400319516,10000,-121.3233161,159.0046333,0,14.03629709,0,127.3422621 +73.28,50.39498244,-3.40029719,10000,-121.3302791,158.9895359,0,14.03629709,0,127.349288 +73.29,50.39497155,-3.400274867,10000,-121.3442052,158.9748836,0,14.03629709,0,127.356314 +73.3,50.39496066,-3.400252546,10000,-121.3650946,158.960899,0,14.03629709,0,127.3633399 +73.31,50.39494976,-3.400230226,10000,-121.3825024,158.9464693,0,14.03629709,0,127.3703658 +73.32,50.39493887,-3.400207909,10000,-121.3999102,158.9311493,0,14.03629709,0,127.3773917 +73.33,50.39492797,-3.400185594,10000,-121.4242811,158.9160519,0,14.03629709,0,127.3844177 +73.34,50.39491707,-3.400163281,10000,-121.4521337,158.9016222,0,14.03629709,0,127.3914436 +73.35,50.39490617,-3.40014097,10000,-121.4765047,158.8871925,0,14.03629709,0,127.3984695 +73.36,50.39489526,-3.400118661,10000,-121.4939124,158.8720951,0,14.03629709,0,127.4054954 +73.37,50.39488436,-3.400096354,10000,-121.5113202,158.8565526,0,14.03629709,0,127.4125214 +73.38,50.39487345,-3.40007405,10000,-121.5322096,158.8412327,0,14.03629709,0,127.4195473 +73.39,50.39486254,-3.400051747,10000,-121.5496173,158.8259127,0,14.03629709,0,127.4265732 +73.4,50.39485163,-3.400029447,10000,-121.5670251,158.8105928,0,14.03629709,0,127.4335991 +73.41,50.39484072,-3.400007149,10000,-121.5879145,158.7963856,0,14.03629709,0,127.4406251 +73.42,50.3948298,-3.399984853,10000,-121.6053222,158.7828461,0,14.03629709,0,127.4476509 +73.43,50.39481889,-3.399962558,10000,-121.62273,158.7677487,0,14.03629709,0,127.4546769 +73.44,50.39480797,-3.399940266,10000,-121.6436194,158.751316,0,14.03629709,0,127.4617028 +73.45,50.39479705,-3.399917977,10000,-121.6610272,158.7362186,0,14.03629709,0,127.4687287 +73.46,50.39478613,-3.399895689,10000,-121.6819166,158.7226791,0,14.03629709,0,127.4757546 +73.47,50.39477521,-3.399873403,10000,-121.7132507,158.7082493,0,14.03629709,0,127.4827806 +73.48,50.39476428,-3.399851119,10000,-121.7341401,158.6920391,0,14.03629709,0,127.4898065 +73.49,50.39475335,-3.399828838,10000,-121.7376215,158.675829,0,14.03629709,0,127.4968324 +73.5,50.39474243,-3.399806559,10000,-121.7550292,158.6613992,0,14.03629709,0,127.5038583 +73.51,50.3947315,-3.399784282,10000,-121.789845,158.6480823,0,14.03629709,0,127.5108843 +73.52,50.39472056,-3.399762006,10000,-121.8072528,158.6338751,0,14.03629709,0,127.5179102 +73.53,50.39470963,-3.399739733,10000,-121.8107341,158.6183326,0,14.03629709,0,127.5249361 +73.54,50.3946987,-3.399717462,10000,-121.8316235,158.6023449,0,14.03629709,0,127.531962 +73.55,50.39468776,-3.399695193,10000,-121.8629577,158.5868024,0,14.03629709,0,127.538988 +73.56,50.39467682,-3.399672927,10000,-121.883847,158.5723727,0,14.03629709,0,127.5460139 +73.57,50.39466588,-3.399650662,10000,-121.9012548,158.558388,0,14.03629709,0,127.5530398 +73.58,50.39465494,-3.399628399,10000,-121.9221442,158.5437357,0,14.03629709,0,127.5600657 +73.59,50.39464399,-3.399606139,10000,-121.9395519,158.5286383,0,14.03629709,0,127.5670917 +73.6,50.39463305,-3.39958388,10000,-121.9569597,158.5133184,0,14.03629709,0,127.5741176 +73.61,50.3946221,-3.399561624,10000,-121.9778491,158.4977758,0,14.03629709,0,127.5811435 +73.62,50.39461115,-3.39953937,10000,-121.9952569,158.4826784,0,14.03629709,0,127.5881694 +73.63,50.3946002,-3.399517118,10000,-122.0126646,158.4682487,0,14.03629709,0,127.5951954 +73.64,50.39458925,-3.399494868,10000,-122.033554,158.4538189,0,14.03629709,0,127.6022213 +73.65,50.39457829,-3.39947262,10000,-122.0509618,158.4387215,0,14.03629709,0,127.6092472 +73.66,50.39456734,-3.399450374,10000,-122.0683695,158.423179,0,14.03629709,0,127.6162731 +73.67,50.39455638,-3.399428131,10000,-122.0927405,158.407859,0,14.03629709,0,127.623299 +73.68,50.39454542,-3.399405889,10000,-122.1205931,158.392539,0,14.03629709,0,127.630325 +73.69,50.39453446,-3.39938365,10000,-122.144964,158.377219,0,14.03629709,0,127.6373509 +73.7,50.39452349,-3.399361413,10000,-122.1623718,158.3627893,0,14.03629709,0,127.6443768 +73.71,50.39451253,-3.399339178,10000,-122.1797796,158.3485821,0,14.03629709,0,127.6514027 +73.72,50.39450156,-3.399316944,10000,-122.2006689,158.3332621,0,14.03629709,0,127.6584287 +73.73,50.39449059,-3.399294714,10000,-122.2145951,158.3179421,0,14.03629709,0,127.6654546 +73.74,50.39447962,-3.399272485,10000,-122.2215581,158.3037349,0,14.03629709,0,127.6724805 +73.75,50.39446865,-3.399250258,10000,-122.2354842,158.2893051,0,14.03629709,0,127.6795064 +73.76,50.39445768,-3.399228033,10000,-122.2563736,158.2739851,0,14.03629709,0,127.6865324 +73.77,50.3944467,-3.399205811,10000,-122.2737814,158.2586651,0,14.03629709,0,127.6935582 +73.78,50.39443573,-3.39918359,10000,-122.2946707,158.2433451,0,14.03629709,0,127.7005842 +73.79,50.39442475,-3.399161372,10000,-122.3294865,158.2278026,0,14.03629709,0,127.7076101 +73.8,50.39441377,-3.399139156,10000,-122.3643023,158.2127051,0,14.03629709,0,127.714636 +73.81,50.39440278,-3.399116942,10000,-122.38171,158.1982754,0,14.03629709,0,127.7216619 +73.82,50.3943918,-3.39909473,10000,-122.3851914,158.1838456,0,14.03629709,0,127.7286879 +73.83,50.39438081,-3.39907252,10000,-122.3886728,158.1687482,0,14.03629709,0,127.7357138 +73.84,50.39436983,-3.399050312,10000,-122.4060805,158.1534282,0,14.03629709,0,127.7427397 +73.85,50.39435884,-3.399028107,10000,-122.4408963,158.1389984,0,14.03629709,0,127.7497656 +73.86,50.39434785,-3.399005903,10000,-122.4757121,158.1247912,0,14.03629709,0,127.7567916 +73.87,50.39433685,-3.398983701,10000,-122.4966014,158.1092486,0,14.03629709,0,127.7638175 +73.88,50.39432586,-3.398961502,10000,-122.5105276,158.0930384,0,14.03629709,0,127.7708434 +73.89,50.39431486,-3.398939305,10000,-122.5209722,158.0777184,0,14.03629709,0,127.7778693 +73.9,50.39430386,-3.39891711,10000,-122.5314167,158.0632886,0,14.03629709,0,127.7848953 +73.91,50.39429287,-3.398894917,10000,-122.5523061,158.0488588,0,14.03629709,0,127.7919212 +73.92,50.39428186,-3.398872726,10000,-122.5731955,158.0337614,0,14.03629709,0,127.7989471 +73.93,50.39427086,-3.398850537,10000,-122.5871216,158.0182188,0,14.03629709,0,127.805973 +73.94,50.39425986,-3.398828351,10000,-122.6114926,158.0028988,0,14.03629709,0,127.812999 +73.95,50.39424885,-3.398806166,10000,-122.6428267,157.9875788,0,14.03629709,0,127.8200249 +73.96,50.39423784,-3.398783984,10000,-122.6637161,157.9720362,0,14.03629709,0,127.8270508 +73.97,50.39422683,-3.398761804,10000,-122.6811239,157.9569387,0,14.03629709,0,127.8340767 +73.98,50.39421582,-3.398739626,10000,-122.7020132,157.942509,0,14.03629709,0,127.8411027 +73.99,50.3942048,-3.39871745,10000,-122.719421,157.9283017,0,14.03629709,0,127.8481286 +74,50.39419379,-3.398695276,10000,-122.7368288,157.913872,0,14.03629709,0,127.8551545 +74.01,50.39418277,-3.398673104,10000,-122.7577181,157.8985519,0,14.03629709,0,127.8621804 +74.02,50.39417175,-3.398650934,10000,-122.7716443,157.8823417,0,14.03629709,0,127.8692064 +74.03,50.39416073,-3.398628767,10000,-122.7786073,157.8667991,0,14.03629709,0,127.8762323 +74.04,50.39414971,-3.398606602,10000,-122.796015,157.8525918,0,14.03629709,0,127.8832582 +74.05,50.39413869,-3.398584438,10000,-122.8308308,157.8381621,0,14.03629709,0,127.8902841 +74.06,50.39412766,-3.398562277,10000,-122.8656465,157.822842,0,14.03629709,0,127.89731 +74.07,50.39411663,-3.398540118,10000,-122.8830543,157.807522,0,14.03629709,0,127.904336 +74.08,50.3941056,-3.398517961,10000,-122.8900173,157.792202,0,14.03629709,0,127.9113619 +74.09,50.39409457,-3.398495806,10000,-122.9039435,157.7768819,0,14.03629709,0,127.9183878 +74.1,50.39408354,-3.398473654,10000,-122.9248328,157.7624521,0,14.03629709,0,127.9254137 +74.11,50.3940725,-3.398451503,10000,-122.9422406,157.7482449,0,14.03629709,0,127.9324396 +74.12,50.39406147,-3.398429354,10000,-122.9596483,157.7327023,0,14.03629709,0,127.9394655 +74.13,50.39405043,-3.398407208,10000,-122.9805377,157.716492,0,14.03629709,0,127.9464915 +74.14,50.39403939,-3.398385064,10000,-122.9979454,157.701172,0,14.03629709,0,127.9535174 +74.15,50.39402835,-3.398362922,10000,-123.0188348,157.6867422,0,14.03629709,0,127.9605433 +74.16,50.39401731,-3.398340782,10000,-123.050169,157.6725349,0,14.03629709,0,127.9675692 +74.17,50.39400626,-3.398318644,10000,-123.0710583,157.6581051,0,14.03629709,0,127.9745952 +74.18,50.39399521,-3.398296508,10000,-123.0745397,157.6427851,0,14.03629709,0,127.9816211 +74.19,50.39398417,-3.398274374,10000,-123.0919475,157.6263522,0,14.03629709,0,127.988647 +74.2,50.39397312,-3.398252243,10000,-123.1267632,157.6099194,0,14.03629709,0,127.9956729 +74.21,50.39396206,-3.398230114,10000,-123.144171,157.5945993,0,14.03629709,0,128.0026989 +74.22,50.39395101,-3.398207987,10000,-123.1476524,157.5801695,0,14.03629709,0,128.0097248 +74.23,50.39393996,-3.398185862,10000,-123.1685417,157.5659623,0,14.03629709,0,128.0167507 +74.24,50.3939289,-3.398163739,10000,-123.1998759,157.5515325,0,14.03629709,0,128.0237766 +74.25,50.39391784,-3.398141618,10000,-123.2207652,157.536435,0,14.03629709,0,128.0308026 +74.26,50.39390678,-3.398119499,10000,-123.238173,157.5208924,0,14.03629709,0,128.0378285 +74.27,50.39389572,-3.398097383,10000,-123.2590624,157.5055723,0,14.03629709,0,128.0448544 +74.28,50.39388465,-3.398075268,10000,-123.2764701,157.4904748,0,14.03629709,0,128.0518803 +74.29,50.39387359,-3.398053156,10000,-123.2938779,157.4755999,0,14.03629709,0,128.0589063 +74.3,50.39386252,-3.398031046,10000,-123.3147672,157.4607249,0,14.03629709,0,128.0659322 +74.31,50.39385145,-3.398008937,10000,-123.332175,157.4451823,0,14.03629709,0,128.0729581 +74.32,50.39384038,-3.397986832,10000,-123.3495828,157.4296397,0,14.03629709,0,128.079984 +74.33,50.39382931,-3.397964728,10000,-123.3704721,157.4147647,0,14.03629709,0,128.08701 +74.34,50.39381823,-3.397942626,10000,-123.3878799,157.3998898,0,14.03629709,0,128.0940359 +74.35,50.39380716,-3.397920527,10000,-123.4052876,157.3847923,0,14.03629709,0,128.1010618 +74.36,50.39379608,-3.397898429,10000,-123.4296586,157.3694722,0,14.03629709,0,128.1080877 +74.37,50.393785,-3.397876334,10000,-123.4575112,157.3539296,0,14.03629709,0,128.1151137 +74.38,50.39377392,-3.397854241,10000,-123.4818821,157.3388321,0,14.03629709,0,128.1221396 +74.39,50.39376283,-3.39783215,10000,-123.4992899,157.3244022,0,14.03629709,0,128.1291655 +74.4,50.39375175,-3.397810061,10000,-123.513216,157.3099724,0,14.03629709,0,128.1361914 +74.41,50.39374066,-3.397787974,10000,-123.5236606,157.2948749,0,14.03629709,0,128.1432174 +74.42,50.39372957,-3.397765889,10000,-123.5341052,157.2793322,0,14.03629709,0,128.1502433 +74.43,50.39371849,-3.397743807,10000,-123.5584761,157.2640122,0,14.03629709,0,128.1572692 +74.44,50.39370739,-3.397721726,10000,-123.5898103,157.2486921,0,14.03629709,0,128.1642951 +74.45,50.3936963,-3.397699648,10000,-123.607218,157.2331494,0,14.03629709,0,128.171321 +74.46,50.3936852,-3.397677572,10000,-123.614181,157.2180519,0,14.03629709,0,128.1783469 +74.47,50.39367411,-3.397655498,10000,-123.6281072,157.2033995,0,14.03629709,0,128.1853728 +74.48,50.39366301,-3.397633426,10000,-123.6524781,157.1880794,0,14.03629709,0,128.1923988 +74.49,50.39365191,-3.397611356,10000,-123.6803307,157.1718691,0,14.03629709,0,128.1994247 +74.5,50.39364081,-3.397589289,10000,-123.7047016,157.1563264,0,14.03629709,0,128.2064506 +74.51,50.3936297,-3.397567224,10000,-123.7221094,157.1421191,0,14.03629709,0,128.2134765 +74.52,50.3936186,-3.39754516,10000,-123.7395172,157.1276893,0,14.03629709,0,128.2205025 +74.53,50.39360749,-3.397523099,10000,-123.7604065,157.1123692,0,14.03629709,0,128.2275284 +74.54,50.39359638,-3.39750104,10000,-123.7778143,157.0970491,0,14.03629709,0,128.2345543 +74.55,50.39358527,-3.397478983,10000,-123.795222,157.081729,0,14.03629709,0,128.2415802 +74.56,50.39357416,-3.397456928,10000,-123.8161114,157.0661864,0,14.03629709,0,128.2486062 +74.57,50.39356304,-3.397434876,10000,-123.8335192,157.0508663,0,14.03629709,0,128.2556321 +74.58,50.39355193,-3.397412825,10000,-123.8509269,157.0357687,0,14.03629709,0,128.262658 +74.59,50.39354081,-3.397390777,10000,-123.8718163,157.0208937,0,14.03629709,0,128.2696839 +74.6,50.39352969,-3.397368731,10000,-123.889224,157.0060188,0,14.03629709,0,128.2767099 +74.61,50.39351857,-3.397346686,10000,-123.9066318,156.9904761,0,14.03629709,0,128.2837358 +74.62,50.39350745,-3.397324645,10000,-123.9275211,156.9749334,0,14.03629709,0,128.2907617 +74.63,50.39349632,-3.397302605,10000,-123.9449289,156.9598359,0,14.03629709,0,128.2977876 +74.64,50.3934852,-3.397280567,10000,-123.9623366,156.9442932,0,14.03629709,0,128.3048136 +74.65,50.39347407,-3.397258532,10000,-123.9867076,156.9289731,0,14.03629709,0,128.3118395 +74.66,50.39346294,-3.397236499,10000,-124.0145602,156.9147658,0,14.03629709,0,128.3188654 +74.67,50.39345181,-3.397214467,10000,-124.0389311,156.9003359,0,14.03629709,0,128.3258913 +74.68,50.39344067,-3.397192438,10000,-124.0563389,156.8847932,0,14.03629709,0,128.3329173 +74.69,50.39342954,-3.397170411,10000,-124.0737466,156.8688054,0,14.03629709,0,128.3399432 +74.7,50.3934184,-3.397148386,10000,-124.094636,156.8530402,0,14.03629709,0,128.3469691 +74.71,50.39340726,-3.397126364,10000,-124.1085621,156.8379426,0,14.03629709,0,128.353995 +74.72,50.39339612,-3.397104343,10000,-124.1155251,156.8235128,0,14.03629709,0,128.361021 +74.73,50.39338498,-3.397082325,10000,-124.1294513,156.8090829,0,14.03629709,0,128.3680469 +74.74,50.39337384,-3.397060308,10000,-124.1503406,156.7937628,0,14.03629709,0,128.3750728 +74.75,50.39336269,-3.397038294,10000,-124.1677484,156.7773298,0,14.03629709,0,128.3820987 +74.76,50.39335155,-3.397016282,10000,-124.1886377,156.7611194,0,14.03629709,0,128.3891247 +74.77,50.3933404,-3.396994273,10000,-124.2234535,156.746467,0,14.03629709,0,128.3961506 +74.78,50.39332925,-3.396972265,10000,-124.2582692,156.7322597,0,14.03629709,0,128.4031765 +74.79,50.39331809,-3.396950259,10000,-124.275677,156.716717,0,14.03629709,0,128.4102024 +74.8,50.39330694,-3.396928256,10000,-124.2791583,156.7005066,0,14.03629709,0,128.4172284 +74.81,50.39329578,-3.396906255,10000,-124.2826397,156.6851865,0,14.03629709,0,128.4242542 +74.82,50.39328463,-3.396884256,10000,-124.3000475,156.670534,0,14.03629709,0,128.4312802 +74.83,50.39327347,-3.396862259,10000,-124.3348632,156.6554364,0,14.03629709,0,128.4383061 +74.84,50.39326231,-3.396840264,10000,-124.369679,156.6401163,0,14.03629709,0,128.445332 +74.85,50.39325114,-3.396818272,10000,-124.3870867,156.6256864,0,14.03629709,0,128.4523579 +74.86,50.39323998,-3.396796281,10000,-124.3905681,156.6112565,0,14.03629709,0,128.4593838 +74.87,50.39322881,-3.396774292,10000,-124.3940494,156.5950461,0,14.03629709,0,128.4664098 +74.88,50.39321765,-3.396752306,10000,-124.4114572,156.5783906,0,14.03629709,0,128.4734357 +74.89,50.39320648,-3.396730323,10000,-124.4462729,156.563293,0,14.03629709,0,128.4804616 +74.9,50.39319531,-3.39670834,10000,-124.4810887,156.5488631,0,14.03629709,0,128.4874875 +74.91,50.39318413,-3.396686361,10000,-124.5019781,156.5342107,0,14.03629709,0,128.4945135 +74.92,50.39317296,-3.396664383,10000,-124.5193858,156.5193357,0,14.03629709,0,128.5015394 +74.93,50.39316178,-3.396642407,10000,-124.5402752,156.5035704,0,14.03629709,0,128.5085653 +74.94,50.3931506,-3.396620434,10000,-124.5542013,156.48736,0,14.03629709,0,128.5155912 +74.95,50.39313942,-3.396598463,10000,-124.5611643,156.4718172,0,14.03629709,0,128.5226172 +74.96,50.39312824,-3.396576494,10000,-124.5750904,156.4564971,0,14.03629709,0,128.5296431 +74.97,50.39311706,-3.396554527,10000,-124.5959798,156.4409544,0,14.03629709,0,128.536669 +74.98,50.39310587,-3.396532563,10000,-124.6133875,156.4258568,0,14.03629709,0,128.5436949 +74.99,50.39309469,-3.3965106,10000,-124.6307953,156.4114268,0,14.03629709,0,128.5507209 +75,50.3930835,-3.39648864,10000,-124.6551662,156.3969969,0,14.03629709,0,128.5577468 +75.01,50.39307231,-3.396466681,10000,-124.6830188,156.3818993,0,14.03629709,0,128.5647727 +75.02,50.39306112,-3.396444725,10000,-124.7073897,156.366134,0,14.03629709,0,128.5717986 +75.03,50.39304992,-3.396422771,10000,-124.7247975,156.3501462,0,14.03629709,0,128.5788246 +75.04,50.39303873,-3.396400819,10000,-124.7422053,156.3343809,0,14.03629709,0,128.5858505 +75.05,50.39302753,-3.39637887,10000,-124.7630946,156.3190607,0,14.03629709,0,128.5928764 +75.06,50.39301633,-3.396356922,10000,-124.7770207,156.3039631,0,14.03629709,0,128.5999023 +75.07,50.39300513,-3.396334977,10000,-124.7839837,156.2890881,0,14.03629709,0,128.6069283 +75.08,50.39299393,-3.396313034,10000,-124.8013915,156.274213,0,14.03629709,0,128.6139542 +75.09,50.39298273,-3.396291092,10000,-124.8327256,156.2584477,0,14.03629709,0,128.6209801 +75.1,50.39297152,-3.396269154,10000,-124.8570966,156.2422372,0,14.03629709,0,128.628006 +75.11,50.39296031,-3.396247217,10000,-124.8710227,156.2269171,0,14.03629709,0,128.635032 +75.12,50.39294911,-3.396225283,10000,-124.8919121,156.2122646,0,14.03629709,0,128.6420578 +75.13,50.39293789,-3.39620335,10000,-124.9128014,156.197167,0,14.03629709,0,128.6490838 +75.14,50.39292668,-3.39618142,10000,-124.9267276,156.1816242,0,14.03629709,0,128.6561097 +75.15,50.39291547,-3.396159492,10000,-124.9510985,156.1665266,0,14.03629709,0,128.6631356 +75.16,50.39290425,-3.396137566,10000,-124.9824326,156.1518741,0,14.03629709,0,128.6701615 +75.17,50.39289303,-3.396115642,10000,-124.9998404,156.1365539,0,14.03629709,0,128.6771875 +75.18,50.39288181,-3.39609372,10000,-125.0033218,156.1203434,0,14.03629709,0,128.6842134 +75.19,50.39287059,-3.396071801,10000,-125.0068031,156.1048007,0,14.03629709,0,128.6912393 +75.2,50.39285937,-3.396049884,10000,-125.0242109,156.0903707,0,14.03629709,0,128.6982652 +75.21,50.39284815,-3.396027968,10000,-125.0590266,156.0750505,0,14.03629709,0,128.7052912 +75.22,50.39283692,-3.396006055,10000,-125.0938424,156.0586175,0,14.03629709,0,128.7123171 +75.23,50.39282569,-3.395984145,10000,-125.1112501,156.0432973,0,14.03629709,0,128.719343 +75.24,50.39281446,-3.395962236,10000,-125.1182131,156.0288674,0,14.03629709,0,128.7263689 +75.25,50.39280323,-3.395940329,10000,-125.1321392,156.0133246,0,14.03629709,0,128.7333948 +75.26,50.392792,-3.395918425,10000,-125.1530286,155.9971141,0,14.03629709,0,128.7404208 +75.27,50.39278076,-3.395896523,10000,-125.1704363,155.9817939,0,14.03629709,0,128.7474467 +75.28,50.39276953,-3.395874623,10000,-125.1878441,155.967364,0,14.03629709,0,128.7544726 +75.29,50.39275829,-3.395852725,10000,-125.212215,155.952934,0,14.03629709,0,128.7614985 +75.3,50.39274705,-3.395830829,10000,-125.2400676,155.9376138,0,14.03629709,0,128.7685245 +75.31,50.39273581,-3.395808935,10000,-125.2644385,155.9214033,0,14.03629709,0,128.7755504 +75.32,50.39272456,-3.395787044,10000,-125.2818463,155.905638,0,14.03629709,0,128.7825763 +75.33,50.39271332,-3.395765155,10000,-125.299254,155.8905403,0,14.03629709,0,128.7896022 +75.34,50.39270207,-3.395743267,10000,-125.3201434,155.874775,0,14.03629709,0,128.7966282 +75.35,50.39269082,-3.395721383,10000,-125.3340695,155.8585645,0,14.03629709,0,128.8036541 +75.36,50.39267957,-3.3956995,10000,-125.3410325,155.8432443,0,14.03629709,0,128.81068 +75.37,50.39266832,-3.39567762,10000,-125.3549586,155.8285918,0,14.03629709,0,128.8177059 +75.38,50.39265707,-3.395655741,10000,-125.375848,155.8134941,0,14.03629709,0,128.8247319 +75.39,50.39264581,-3.395633865,10000,-125.3932557,155.7979513,0,14.03629709,0,128.8317578 +75.4,50.39263456,-3.395611991,10000,-125.4141451,155.7828536,0,14.03629709,0,128.8387837 +75.41,50.3926233,-3.395590119,10000,-125.4489608,155.7682011,0,14.03629709,0,128.8458096 +75.42,50.39261204,-3.395568249,10000,-125.4837766,155.7528809,0,14.03629709,0,128.8528356 +75.43,50.39260077,-3.395546381,10000,-125.5011843,155.7364478,0,14.03629709,0,128.8598615 +75.44,50.39258951,-3.395524516,10000,-125.5046657,155.7200147,0,14.03629709,0,128.8668874 +75.45,50.39257824,-3.395502653,10000,-125.508147,155.7046945,0,14.03629709,0,128.8739133 +75.46,50.39256698,-3.395480792,10000,-125.5255548,155.6902645,0,14.03629709,0,128.8809393 +75.47,50.39255571,-3.395458933,10000,-125.5603705,155.6758345,0,14.03629709,0,128.8879651 +75.48,50.39254444,-3.395437076,10000,-125.5951862,155.6605143,0,14.03629709,0,128.8949911 +75.49,50.39253316,-3.395415221,10000,-125.612594,155.6440812,0,14.03629709,0,128.902017 +75.5,50.39252189,-3.395393369,10000,-125.6160754,155.6278707,0,14.03629709,0,128.9090429 +75.51,50.39251061,-3.395371519,10000,-125.6195567,155.6132182,0,14.03629709,0,128.9160688 +75.52,50.39249934,-3.395349671,10000,-125.6369645,155.5990107,0,14.03629709,0,128.9230948 +75.53,50.39248806,-3.395327824,10000,-125.6717802,155.5834679,0,14.03629709,0,128.9301207 +75.54,50.39247678,-3.395305981,10000,-125.7065959,155.5670348,0,14.03629709,0,128.9371466 +75.55,50.39246549,-3.395284139,10000,-125.7274853,155.5510469,0,14.03629709,0,128.9441725 +75.56,50.39245421,-3.3952623,10000,-125.744893,155.5359492,0,14.03629709,0,128.9511985 +75.57,50.39244292,-3.395240463,10000,-125.7657824,155.5210741,0,14.03629709,0,128.9582244 +75.58,50.39243163,-3.395218627,10000,-125.7797085,155.5055312,0,14.03629709,0,128.9652503 +75.59,50.39242034,-3.395196795,10000,-125.7831899,155.4899884,0,14.03629709,0,128.9722762 +75.6,50.39240905,-3.395174964,10000,-125.7866712,155.4751133,0,14.03629709,0,128.9793022 +75.61,50.39239776,-3.395153135,10000,-125.804079,155.4600156,0,14.03629709,0,128.9863281 +75.62,50.39238647,-3.395131309,10000,-125.8388947,155.4440276,0,14.03629709,0,128.993354 +75.63,50.39237517,-3.395109484,10000,-125.8737105,155.4275945,0,14.03629709,0,129.0003799 +75.64,50.39236387,-3.395087663,10000,-125.8911182,155.4120517,0,14.03629709,0,129.0074059 +75.65,50.39235257,-3.395065843,10000,-125.8980811,155.3978442,0,14.03629709,0,129.0144318 +75.66,50.39234127,-3.395044025,10000,-125.9154889,155.3831917,0,14.03629709,0,129.0214577 +75.67,50.39232997,-3.395022209,10000,-125.946823,155.3669811,0,14.03629709,0,129.0284836 +75.68,50.39231866,-3.395000396,10000,-125.9677124,155.350548,0,14.03629709,0,129.0355095 +75.69,50.39230735,-3.394978585,10000,-125.9711937,155.3350051,0,14.03629709,0,129.0425355 +75.7,50.39229605,-3.394956776,10000,-125.9886015,155.3196849,0,14.03629709,0,129.0495614 +75.71,50.39228474,-3.394934969,10000,-126.0268988,155.304142,0,14.03629709,0,129.0565873 +75.72,50.39227342,-3.394913165,10000,-126.0547514,155.2888217,0,14.03629709,0,129.0636132 +75.73,50.39226211,-3.394891362,10000,-126.0617143,155.273724,0,14.03629709,0,129.0706392 +75.74,50.39225079,-3.394869562,10000,-126.0651957,155.2588489,0,14.03629709,0,129.0776651 +75.75,50.39223948,-3.394847764,10000,-126.0791218,155.2439737,0,14.03629709,0,129.084691 +75.76,50.39222816,-3.394825967,10000,-126.1034928,155.2282083,0,14.03629709,0,129.0917169 +75.77,50.39221684,-3.394804174,10000,-126.1313453,155.2119977,0,14.03629709,0,129.0987429 +75.78,50.39220552,-3.394782382,10000,-126.1557163,155.1966774,0,14.03629709,0,129.1057687 +75.79,50.39219419,-3.394760593,10000,-126.173124,155.1818022,0,14.03629709,0,129.1127947 +75.8,50.39218287,-3.394738805,10000,-126.1905317,155.1658142,0,14.03629709,0,129.1198206 +75.81,50.39217154,-3.39471702,10000,-126.2114211,155.1491585,0,14.03629709,0,129.1268465 +75.82,50.39216021,-3.394695238,10000,-126.2288288,155.1338382,0,14.03629709,0,129.1338724 +75.83,50.39214888,-3.394673457,10000,-126.2462366,155.1194082,0,14.03629709,0,129.1408984 +75.84,50.39213755,-3.394651678,10000,-126.2671259,155.1038653,0,14.03629709,0,129.1479243 +75.85,50.39212621,-3.394629902,10000,-126.2845336,155.0876547,0,14.03629709,0,129.1549502 +75.86,50.39211488,-3.394608128,10000,-126.3019414,155.0723344,0,14.03629709,0,129.1619761 +75.87,50.39210354,-3.394586356,10000,-126.3228307,155.0576818,0,14.03629709,0,129.1690021 +75.88,50.3920922,-3.394564586,10000,-126.3402385,155.0423615,0,14.03629709,0,129.176028 +75.89,50.39208086,-3.394542818,10000,-126.3576462,155.0261509,0,14.03629709,0,129.1830539 +75.9,50.39206952,-3.394521053,10000,-126.3785356,155.010608,0,14.03629709,0,129.1900798 +75.91,50.39205817,-3.39449929,10000,-126.3959433,154.996178,0,14.03629709,0,129.1971058 +75.92,50.39204683,-3.394477528,10000,-126.413351,154.9808577,0,14.03629709,0,129.2041317 +75.93,50.39203548,-3.394455769,10000,-126.4342404,154.9642019,0,14.03629709,0,129.2111576 +75.94,50.39202413,-3.394434013,10000,-126.4516481,154.9482139,0,14.03629709,0,129.2181835 +75.95,50.39201278,-3.394412258,10000,-126.4725375,154.9333387,0,14.03629709,0,129.2252095 +75.96,50.39200143,-3.394390506,10000,-126.5038716,154.9180184,0,14.03629709,0,129.2322354 +75.97,50.39199007,-3.394368755,10000,-126.524761,154.9018078,0,14.03629709,0,129.2392613 +75.98,50.39197871,-3.394347008,10000,-126.5247607,154.8862649,0,14.03629709,0,129.2462872 +75.99,50.39196736,-3.394325262,10000,-126.5317237,154.8720574,0,14.03629709,0,129.2533132 +76,50.391956,-3.394303518,10000,-126.5630578,154.8574048,0,14.03629709,0,129.2603391 +76.01,50.39194464,-3.394281776,10000,-126.5978735,154.8411941,0,14.03629709,0,129.267365 +76.02,50.39193327,-3.394260037,10000,-126.6187629,154.8245384,0,14.03629709,0,129.2743909 +76.03,50.39192191,-3.3942383,10000,-126.6361706,154.8083278,0,14.03629709,0,129.2814169 +76.04,50.39191054,-3.394216565,10000,-126.6570599,154.7925623,0,14.03629709,0,129.2884428 +76.05,50.39189917,-3.394194833,10000,-126.6709861,154.7772419,0,14.03629709,0,129.2954687 +76.06,50.3918878,-3.394173102,10000,-126.677949,154.7619216,0,14.03629709,0,129.3024946 +76.07,50.39187643,-3.394151374,10000,-126.6918752,154.7463787,0,14.03629709,0,129.3095205 +76.08,50.39186506,-3.394129648,10000,-126.7127645,154.7312809,0,14.03629709,0,129.3165465 +76.09,50.39185368,-3.394107924,10000,-126.7301723,154.7166283,0,14.03629709,0,129.3235724 +76.1,50.39184231,-3.394086202,10000,-126.74758,154.7013079,0,14.03629709,0,129.3305983 +76.11,50.39183093,-3.394064482,10000,-126.771951,154.6848747,0,14.03629709,0,129.3376242 +76.12,50.39181955,-3.394042765,10000,-126.7998035,154.6684415,0,14.03629709,0,129.3446502 +76.13,50.39180817,-3.39402105,10000,-126.8241744,154.6531211,0,14.03629709,0,129.351676 +76.14,50.39179678,-3.393999337,10000,-126.8415822,154.6384685,0,14.03629709,0,129.358702 +76.15,50.3917854,-3.393977626,10000,-126.8589899,154.6233707,0,14.03629709,0,129.3657279 +76.16,50.39177401,-3.393955917,10000,-126.8798793,154.6078277,0,14.03629709,0,129.3727538 +76.17,50.39176262,-3.393934211,10000,-126.8938054,154.5922848,0,14.03629709,0,129.3797797 +76.18,50.39175123,-3.393912506,10000,-126.9007683,154.5760742,0,14.03629709,0,129.3868057 +76.19,50.39173984,-3.393890804,10000,-126.9181761,154.5594184,0,14.03629709,0,129.3938316 +76.2,50.39172845,-3.393869105,10000,-126.9529918,154.544098,0,14.03629709,0,129.4008575 +76.21,50.39171705,-3.393847407,10000,-126.9878075,154.5296679,0,14.03629709,0,129.4078834 +76.22,50.39170565,-3.393825711,10000,-127.0052153,154.5141249,0,14.03629709,0,129.4149094 +76.23,50.39169425,-3.393804018,10000,-127.0086966,154.4979143,0,14.03629709,0,129.4219353 +76.24,50.39168285,-3.393782327,10000,-127.012178,154.4823713,0,14.03629709,0,129.4289612 +76.25,50.39167145,-3.393760638,10000,-127.0295857,154.4668284,0,14.03629709,0,129.4359871 +76.26,50.39166005,-3.393738951,10000,-127.0609198,154.4506177,0,14.03629709,0,129.4430131 +76.27,50.39164864,-3.393717267,10000,-127.0818092,154.4350747,0,14.03629709,0,129.450039 +76.28,50.39163723,-3.393695585,10000,-127.0852905,154.4208672,0,14.03629709,0,129.4570649 +76.29,50.39162583,-3.393673904,10000,-127.1026983,154.4062145,0,14.03629709,0,129.4640908 +76.3,50.39161442,-3.393652226,10000,-127.1409956,154.3897813,0,14.03629709,0,129.4711168 +76.31,50.391603,-3.39363055,10000,-127.1688482,154.3726803,0,14.03629709,0,129.4781427 +76.32,50.39159159,-3.393608877,10000,-127.1758111,154.3569148,0,14.03629709,0,129.4851686 +76.33,50.39158017,-3.393587206,10000,-127.182774,154.3424847,0,14.03629709,0,129.4921945 +76.34,50.39156876,-3.393565536,10000,-127.2106265,154.3271643,0,14.03629709,0,129.4992205 +76.35,50.39155734,-3.393543869,10000,-127.2489239,154.3105084,0,14.03629709,0,129.5062464 +76.36,50.39154591,-3.393522205,10000,-127.2663316,154.2942978,0,14.03629709,0,129.5132723 +76.37,50.39153449,-3.393500542,10000,-127.269813,154.2787548,0,14.03629709,0,129.5202982 +76.38,50.39152307,-3.393478882,10000,-127.2907023,154.2632118,0,14.03629709,0,129.5273242 +76.39,50.39151164,-3.393457224,10000,-127.3220364,154.248114,0,14.03629709,0,129.5343501 +76.4,50.39150021,-3.393435568,10000,-127.3394442,154.2334613,0,14.03629709,0,129.541376 +76.41,50.39148878,-3.393413914,10000,-127.3429255,154.2181409,0,14.03629709,0,129.5484019 +76.42,50.39147735,-3.393392262,10000,-127.3464069,154.2019302,0,14.03629709,0,129.5554279 +76.43,50.39146592,-3.393370613,10000,-127.3638146,154.1861646,0,14.03629709,0,129.5624538 +76.44,50.39145449,-3.393348966,10000,-127.3986304,154.1710667,0,14.03629709,0,129.5694797 +76.45,50.39144305,-3.39332732,10000,-127.4334461,154.1553012,0,14.03629709,0,129.5765056 +76.46,50.39143161,-3.393305678,10000,-127.4508538,154.1388679,0,14.03629709,0,129.5835315 +76.47,50.39142017,-3.393284037,10000,-127.4578167,154.1228797,0,14.03629709,0,129.5905575 +76.48,50.39140873,-3.393262399,10000,-127.4717429,154.1077819,0,14.03629709,0,129.5975833 +76.49,50.39139729,-3.393240763,10000,-127.4926322,154.0929066,0,14.03629709,0,129.6046093 +76.5,50.39138584,-3.393219128,10000,-127.51004,154.077141,0,14.03629709,0,129.6116352 +76.51,50.3913744,-3.393197497,10000,-127.5274477,154.0607077,0,14.03629709,0,129.6186611 +76.52,50.39136295,-3.393175867,10000,-127.5518186,154.0447196,0,14.03629709,0,129.625687 +76.53,50.3913515,-3.39315424,10000,-127.5796712,154.0296217,0,14.03629709,0,129.632713 +76.54,50.39134005,-3.393132615,10000,-127.6040421,154.0147464,0,14.03629709,0,129.6397389 +76.55,50.39132859,-3.393110991,10000,-127.6214498,153.9989808,0,14.03629709,0,129.6467648 +76.56,50.39131714,-3.393089371,10000,-127.6388576,153.9827701,0,14.03629709,0,129.6537907 +76.57,50.39130568,-3.393067752,10000,-127.6597469,153.9674497,0,14.03629709,0,129.6608167 +76.58,50.39129422,-3.393046136,10000,-127.673673,153.9525744,0,14.03629709,0,129.6678426 +76.59,50.39128276,-3.393024521,10000,-127.680636,153.9365862,0,14.03629709,0,129.6748685 +76.6,50.3912713,-3.393002909,10000,-127.6945621,153.9197077,0,14.03629709,0,129.6818944 +76.61,50.39125984,-3.3929813,10000,-127.7154515,153.9037196,0,14.03629709,0,129.6889204 +76.62,50.39124837,-3.392959692,10000,-127.7328592,153.8890668,0,14.03629709,0,129.6959463 +76.63,50.39123691,-3.392938087,10000,-127.7502669,153.8746367,0,14.03629709,0,129.7029722 +76.64,50.39122544,-3.392916483,10000,-127.7746379,153.8593162,0,14.03629709,0,129.7099981 +76.65,50.39121397,-3.392894882,10000,-127.8024904,153.8426603,0,14.03629709,0,129.7170241 +76.66,50.3912025,-3.392873283,10000,-127.8268613,153.8255592,0,14.03629709,0,129.72405 +76.67,50.39119102,-3.392851687,10000,-127.844269,153.8095711,0,14.03629709,0,129.7310759 +76.68,50.39117955,-3.392830093,10000,-127.8616768,153.7944732,0,14.03629709,0,129.7381018 +76.69,50.39116807,-3.3928085,10000,-127.8825661,153.7789301,0,14.03629709,0,129.7451278 +76.7,50.39115659,-3.392786911,10000,-127.8964923,153.7633871,0,14.03629709,0,129.7521537 +76.71,50.39114511,-3.392765323,10000,-127.9034552,153.7482892,0,14.03629709,0,129.7591796 +76.72,50.39113363,-3.392743737,10000,-127.9173813,153.7325236,0,14.03629709,0,129.7662055 +76.73,50.39112215,-3.392722154,10000,-127.9382707,153.7160902,0,14.03629709,0,129.7732315 +76.74,50.39111066,-3.392700573,10000,-127.9556784,153.6998794,0,14.03629709,0,129.7802574 +76.75,50.39109918,-3.392678994,10000,-127.9765677,153.6843364,0,14.03629709,0,129.7872833 +76.76,50.39108769,-3.392657418,10000,-128.0113835,153.6699062,0,14.03629709,0,129.7943092 +76.77,50.3910762,-3.392635843,10000,-128.0461992,153.6556986,0,14.03629709,0,129.8013352 +76.78,50.3910647,-3.39261427,10000,-128.0636069,153.6399329,0,14.03629709,0,129.8083611 +76.79,50.39105321,-3.3925927,10000,-128.0670883,153.6226093,0,14.03629709,0,129.815387 +76.8,50.39104171,-3.392571132,10000,-128.0705696,153.6052856,0,14.03629709,0,129.8224129 +76.81,50.39103022,-3.392549567,10000,-128.0844958,153.58952,0,14.03629709,0,129.8294389 +76.82,50.39101872,-3.392528004,10000,-128.1088667,153.5753124,0,14.03629709,0,129.8364647 +76.83,50.39100722,-3.392506442,10000,-128.1367192,153.5606596,0,14.03629709,0,129.8434907 +76.84,50.39099572,-3.392484883,10000,-128.1610901,153.5444488,0,14.03629709,0,129.8505166 +76.85,50.39098421,-3.392463326,10000,-128.1784979,153.5280154,0,14.03629709,0,129.8575425 +76.86,50.39097271,-3.392441772,10000,-128.1959056,153.5122498,0,14.03629709,0,129.8645684 +76.87,50.3909612,-3.392420219,10000,-128.2167949,153.4960389,0,14.03629709,0,129.8715943 +76.88,50.39094969,-3.392398669,10000,-128.2342027,153.479383,0,14.03629709,0,129.8786203 +76.89,50.39093818,-3.392377122,10000,-128.2516104,153.4640625,0,14.03629709,0,129.8856462 +76.9,50.39092667,-3.392355576,10000,-128.2724997,153.4496323,0,14.03629709,0,129.8926721 +76.91,50.39091515,-3.392334032,10000,-128.2899075,153.4340892,0,14.03629709,0,129.899698 +76.92,50.39090364,-3.392312491,10000,-128.3073152,153.4176558,0,14.03629709,0,129.906724 +76.93,50.39089212,-3.392290952,10000,-128.3282045,153.401445,0,14.03629709,0,129.9137499 +76.94,50.3908806,-3.392269415,10000,-128.3456122,153.3856793,0,14.03629709,0,129.9207758 +76.95,50.39086908,-3.392247881,10000,-128.36302,153.3705814,0,14.03629709,0,129.9278017 +76.96,50.39085756,-3.392226348,10000,-128.3839093,153.3559286,0,14.03629709,0,129.9348277 +76.97,50.39084603,-3.392204818,10000,-128.4013171,153.340608,0,14.03629709,0,129.9418536 +76.98,50.39083451,-3.392183289,10000,-128.4187248,153.3241746,0,14.03629709,0,129.9488795 +76.99,50.39082298,-3.392161764,10000,-128.4396141,153.3075186,0,14.03629709,0,129.9559054 +77,50.39081145,-3.39214024,10000,-128.4570218,153.2913078,0,14.03629709,0,129.9629314 +77.01,50.39079992,-3.392118719,10000,-128.4744296,153.2755421,0,14.03629709,0,129.9699573 +77.02,50.39078839,-3.3920972,10000,-128.4953189,153.2604442,0,14.03629709,0,129.9769832 +77.03,50.39077685,-3.392075683,10000,-128.5127266,153.2457913,0,14.03629709,0,129.9840091 +77.04,50.39076532,-3.392054168,10000,-128.5301344,153.2304708,0,14.03629709,0,129.9910351 +77.05,50.39075378,-3.392032655,10000,-128.5545053,153.2138148,0,14.03629709,0,129.998061 +77.06,50.39074224,-3.392011145,10000,-128.5823578,153.1964911,0,14.03629709,0,130.0050869 +77.07,50.3907307,-3.391989637,10000,-128.6067287,153.1798351,0,14.03629709,0,130.0121128 +77.08,50.39071915,-3.391968132,10000,-128.6206549,153.1645145,0,14.03629709,0,130.0191388 +77.09,50.39070761,-3.391946628,10000,-128.6241362,153.1500843,0,14.03629709,0,130.0261647 +77.1,50.39069606,-3.391925127,10000,-128.6276176,153.1354315,0,14.03629709,0,130.0331906 +77.11,50.39068452,-3.391903627,10000,-128.6450253,153.1194432,0,14.03629709,0,130.0402165 +77.12,50.39067297,-3.39188213,10000,-128.679841,153.1025646,0,14.03629709,0,130.0472425 +77.13,50.39066142,-3.391860636,10000,-128.7146567,153.0863537,0,14.03629709,0,130.0542684 +77.14,50.39064986,-3.391839143,10000,-128.7355461,153.0708106,0,14.03629709,0,130.0612943 +77.15,50.39063831,-3.391817653,10000,-128.7529538,153.0552674,0,14.03629709,0,130.0683202 +77.16,50.39062675,-3.391796165,10000,-128.7738431,153.0399469,0,14.03629709,0,130.0753462 +77.17,50.39061519,-3.391774679,10000,-128.7877693,153.0244037,0,14.03629709,0,130.082372 +77.18,50.39060363,-3.391753195,10000,-128.7912506,153.0081928,0,14.03629709,0,130.089398 +77.19,50.39059207,-3.391731714,10000,-128.7947319,152.9924271,0,14.03629709,0,130.0964239 +77.2,50.39058051,-3.391710235,10000,-128.8121397,152.9773291,0,14.03629709,0,130.1034498 +77.21,50.39056895,-3.391688757,10000,-128.8469554,152.9615634,0,14.03629709,0,130.1104757 +77.22,50.39055738,-3.391667283,10000,-128.8817711,152.9451299,0,14.03629709,0,130.1175017 +77.23,50.39054581,-3.39164581,10000,-128.8991788,152.928919,0,14.03629709,0,130.1245276 +77.24,50.39053424,-3.39162434,10000,-128.9061417,152.9131533,0,14.03629709,0,130.1315535 +77.25,50.39052267,-3.391602872,10000,-128.9200679,152.8978327,0,14.03629709,0,130.1385794 +77.26,50.3905111,-3.391581406,10000,-128.9409572,152.8822895,0,14.03629709,0,130.1456053 +77.27,50.39049952,-3.391559942,10000,-128.9583649,152.8658561,0,14.03629709,0,130.1526313 +77.28,50.39048795,-3.391538481,10000,-128.9757727,152.8494226,0,14.03629709,0,130.1596572 +77.29,50.39047637,-3.391517022,10000,-129.0001436,152.8338794,0,14.03629709,0,130.1666831 +77.3,50.39046479,-3.391495565,10000,-129.0279961,152.8183362,0,14.03629709,0,130.173709 +77.31,50.39045321,-3.39147411,10000,-129.0523671,152.8019027,0,14.03629709,0,130.180735 +77.32,50.39044162,-3.391452658,10000,-129.0697748,152.7854693,0,14.03629709,0,130.1877609 +77.33,50.39043004,-3.391431208,10000,-129.0871825,152.7701487,0,14.03629709,0,130.1947868 +77.34,50.39041845,-3.39140976,10000,-129.1080718,152.7554958,0,14.03629709,0,130.2018127 +77.35,50.39040686,-3.391388314,10000,-129.121998,152.7401752,0,14.03629709,0,130.2088387 +77.36,50.39039527,-3.39136687,10000,-129.1289609,152.7237417,0,14.03629709,0,130.2158646 +77.37,50.39038368,-3.391345429,10000,-129.142887,152.7073082,0,14.03629709,0,130.2228905 +77.38,50.39037209,-3.39132399,10000,-129.1637763,152.691765,0,14.03629709,0,130.2299164 +77.39,50.39036049,-3.391302553,10000,-129.1811841,152.6762218,0,14.03629709,0,130.2369424 +77.4,50.3903489,-3.391281118,10000,-129.1985918,152.6597883,0,14.03629709,0,130.2439683 +77.41,50.3903373,-3.391259686,10000,-129.2229627,152.6433548,0,14.03629709,0,130.2509942 +77.42,50.3903257,-3.391238256,10000,-129.2508152,152.6280341,0,14.03629709,0,130.2580201 +77.43,50.3903141,-3.391216828,10000,-129.2751862,152.6133812,0,14.03629709,0,130.2650461 +77.44,50.39030249,-3.391195402,10000,-129.2925939,152.5980606,0,14.03629709,0,130.272072 +77.45,50.39029089,-3.391173978,10000,-129.3100016,152.5816271,0,14.03629709,0,130.2790979 +77.46,50.39027928,-3.391152557,10000,-129.3308909,152.564971,0,14.03629709,0,130.2861238 +77.47,50.39026767,-3.391131138,10000,-129.3448171,152.5487601,0,14.03629709,0,130.2931498 +77.48,50.39025606,-3.391109721,10000,-129.35178,152.5329943,0,14.03629709,0,130.3001756 +77.49,50.39024445,-3.391088307,10000,-129.3657061,152.5176736,0,14.03629709,0,130.3072016 +77.5,50.39023284,-3.391066894,10000,-129.3865954,152.5021304,0,14.03629709,0,130.3142275 +77.51,50.39022122,-3.391045484,10000,-129.4040032,152.4856969,0,14.03629709,0,130.3212534 +77.52,50.39020961,-3.391024076,10000,-129.4214109,152.4692633,0,14.03629709,0,130.3282793 +77.53,50.39019799,-3.391002671,10000,-129.4457818,152.4537201,0,14.03629709,0,130.3353053 +77.54,50.39018637,-3.390981267,10000,-129.4736343,152.4383994,0,14.03629709,0,130.3423312 +77.55,50.39017475,-3.390959866,10000,-129.4980053,152.4226336,0,14.03629709,0,130.3493571 +77.56,50.39016312,-3.390938467,10000,-129.515413,152.4064227,0,14.03629709,0,130.356383 +77.57,50.3901515,-3.39091707,10000,-129.5328207,152.3899891,0,14.03629709,0,130.363409 +77.58,50.39013987,-3.390895676,10000,-129.55371,152.3742233,0,14.03629709,0,130.3704349 +77.59,50.39012824,-3.390874284,10000,-129.5676362,152.3591252,0,14.03629709,0,130.3774608 +77.6,50.39011661,-3.390852893,10000,-129.5745991,152.3433594,0,14.03629709,0,130.3844867 +77.61,50.39010498,-3.390831506,10000,-129.5920068,152.3269258,0,14.03629709,0,130.3915127 +77.62,50.39009335,-3.39081012,10000,-129.6233409,152.3107148,0,14.03629709,0,130.3985386 +77.63,50.39008171,-3.390788737,10000,-129.6442303,152.2947264,0,14.03629709,0,130.4055645 +77.64,50.39007007,-3.390767356,10000,-129.6477116,152.278738,0,14.03629709,0,130.4125904 +77.65,50.39005844,-3.390745977,10000,-129.6651193,152.2629722,0,14.03629709,0,130.4196163 +77.66,50.3900468,-3.390724601,10000,-129.7034166,152.2476515,0,14.03629709,0,130.4266423 +77.67,50.39003515,-3.390703226,10000,-129.7312691,152.2321082,0,14.03629709,0,130.4336682 +77.68,50.39002351,-3.390681854,10000,-129.7382321,152.2156747,0,14.03629709,0,130.4406941 +77.69,50.39001186,-3.390660484,10000,-129.7417134,152.1992411,0,14.03629709,0,130.44772 +77.7,50.39000022,-3.390639117,10000,-129.7556395,152.1836978,0,14.03629709,0,130.454746 +77.71,50.38998857,-3.390617751,10000,-129.7800105,152.1683771,0,14.03629709,0,130.4617719 +77.72,50.38997692,-3.390596388,10000,-129.807863,152.1526113,0,14.03629709,0,130.4687978 +77.73,50.38996527,-3.390575027,10000,-129.8322339,152.1364003,0,14.03629709,0,130.4758237 +77.74,50.38995361,-3.390553668,10000,-129.8496416,152.1197441,0,14.03629709,0,130.4828497 +77.75,50.38994196,-3.390532312,10000,-129.8670493,152.1033105,0,14.03629709,0,130.4898756 +77.76,50.3899303,-3.390510958,10000,-129.8879387,152.0877672,0,14.03629709,0,130.4969015 +77.77,50.38991864,-3.390489606,10000,-129.9018648,152.0722239,0,14.03629709,0,130.5039274 +77.78,50.38990698,-3.390468256,10000,-129.9088277,152.0560129,0,14.03629709,0,130.5109534 +77.79,50.38989532,-3.390446909,10000,-129.9262354,152.040247,0,14.03629709,0,130.5179793 +77.8,50.38988366,-3.390425564,10000,-129.9610512,152.0251489,0,14.03629709,0,130.5250052 +77.81,50.38987199,-3.39040422,10000,-129.9958669,152.009383,0,14.03629709,0,130.5320311 +77.82,50.38986032,-3.39038288,10000,-130.0132746,151.9929494,0,14.03629709,0,130.5390571 +77.83,50.38984865,-3.390361541,10000,-130.0167559,151.9765158,0,14.03629709,0,130.5460829 +77.84,50.38983698,-3.390340205,10000,-130.0202373,151.9598596,0,14.03629709,0,130.5531089 +77.85,50.38982531,-3.390318871,10000,-130.0341634,151.9436485,0,14.03629709,0,130.5601348 +77.86,50.38981364,-3.39029754,10000,-130.0550527,151.928773,0,14.03629709,0,130.5671607 +77.87,50.38980196,-3.39027621,10000,-130.0724604,151.9136748,0,14.03629709,0,130.5741866 +77.88,50.38979029,-3.390254882,10000,-130.0898681,151.896796,0,14.03629709,0,130.5812126 +77.89,50.38977861,-3.390233558,10000,-130.1142391,151.8796946,0,14.03629709,0,130.5882385 +77.9,50.38976693,-3.390212235,10000,-130.1420916,151.8641513,0,14.03629709,0,130.5952644 +77.91,50.38975525,-3.390190915,10000,-130.1664625,151.8494983,0,14.03629709,0,130.6022903 +77.92,50.38974356,-3.390169596,10000,-130.1838702,151.8344002,0,14.03629709,0,130.6093163 +77.93,50.38973188,-3.39014828,10000,-130.201278,151.8184117,0,14.03629709,0,130.6163422 +77.94,50.38972019,-3.390126966,10000,-130.2221673,151.8015329,0,14.03629709,0,130.6233681 +77.95,50.3897085,-3.390105654,10000,-130.239575,151.7844315,0,14.03629709,0,130.630394 +77.96,50.38969681,-3.390084346,10000,-130.2569827,151.7682204,0,14.03629709,0,130.63742 +77.97,50.38968512,-3.390063038,10000,-130.277872,151.7526771,0,14.03629709,0,130.6444459 +77.98,50.38967342,-3.390041734,10000,-130.2952797,151.7369112,0,14.03629709,0,130.6514718 +77.99,50.38966173,-3.390020431,10000,-130.3126875,151.7209227,0,14.03629709,0,130.6584977 +78,50.38965003,-3.389999131,10000,-130.3335768,151.7051568,0,14.03629709,0,130.6655237 +78.01,50.38963833,-3.389977833,10000,-130.3475029,151.689836,0,14.03629709,0,130.6725496 +78.02,50.38962663,-3.389956537,10000,-130.3544658,151.6742927,0,14.03629709,0,130.6795755 +78.03,50.38961493,-3.389935243,10000,-130.3718736,151.657859,0,14.03629709,0,130.6866014 +78.04,50.38960323,-3.389913952,10000,-130.4066893,151.6412027,0,14.03629709,0,130.6936274 +78.05,50.38959152,-3.389892663,10000,-130.441505,151.6249916,0,14.03629709,0,130.7006533 +78.06,50.38957981,-3.389871376,10000,-130.4589127,151.6092257,0,14.03629709,0,130.7076792 +78.07,50.3895681,-3.389850092,10000,-130.462394,151.5936823,0,14.03629709,0,130.7147051 +78.08,50.38955639,-3.389828809,10000,-130.4658753,151.5774712,0,14.03629709,0,130.721731 +78.09,50.38954468,-3.389807529,10000,-130.4832831,151.5605924,0,14.03629709,0,130.728757 +78.1,50.38953297,-3.389786252,10000,-130.5146172,151.5443813,0,14.03629709,0,130.7357829 +78.11,50.38952125,-3.389764976,10000,-130.5355065,151.5288379,0,14.03629709,0,130.7428088 +78.12,50.38950953,-3.389743703,10000,-130.5389878,151.5132945,0,14.03629709,0,130.7498347 +78.13,50.38949782,-3.389722432,10000,-130.5563955,151.4979737,0,14.03629709,0,130.7568607 +78.14,50.3894861,-3.389701163,10000,-130.5946928,151.4824304,0,14.03629709,0,130.7638865 +78.15,50.38947437,-3.389679896,10000,-130.6225454,151.4659967,0,14.03629709,0,130.7709125 +78.16,50.38946265,-3.389658632,10000,-130.6295083,151.4493404,0,14.03629709,0,130.7779384 +78.17,50.38945092,-3.38963737,10000,-130.6329896,151.4331293,0,14.03629709,0,130.7849643 +78.18,50.3894392,-3.38961611,10000,-130.6469157,151.4173633,0,14.03629709,0,130.7919902 +78.19,50.38942747,-3.389594853,10000,-130.6712866,151.4020425,0,14.03629709,0,130.7990162 +78.2,50.38941574,-3.389573597,10000,-130.6991392,151.3864991,0,14.03629709,0,130.8060421 +78.21,50.38940401,-3.389552344,10000,-130.7235101,151.3698428,0,14.03629709,0,130.813068 +78.22,50.38939227,-3.389531093,10000,-130.7409178,151.3525187,0,14.03629709,0,130.8200939 +78.23,50.38938054,-3.389509845,10000,-130.7583255,151.3358624,0,14.03629709,0,130.8271199 +78.24,50.3893688,-3.389488599,10000,-130.7792148,151.3205416,0,14.03629709,0,130.8341458 +78.25,50.38935706,-3.389467355,10000,-130.7966225,151.305666,0,14.03629709,0,130.8411717 +78.26,50.38934532,-3.389446113,10000,-130.8140303,151.2894548,0,14.03629709,0,130.8481976 +78.27,50.38933358,-3.389424873,10000,-130.8349196,151.2719082,0,14.03629709,0,130.8552236 +78.28,50.38932183,-3.389403637,10000,-130.8523273,151.2554744,0,14.03629709,0,130.8622495 +78.29,50.38931009,-3.389382402,10000,-130.869735,151.2410439,0,14.03629709,0,130.8692754 +78.3,50.38929834,-3.389361169,10000,-130.8906243,151.2263908,0,14.03629709,0,130.8763013 +78.31,50.38928659,-3.389339938,10000,-130.9045505,151.2099571,0,14.03629709,0,130.8833273 +78.32,50.38927484,-3.38931871,10000,-130.9115134,151.192633,0,14.03629709,0,130.8903532 +78.33,50.38926309,-3.389297484,10000,-130.9289211,151.1759767,0,14.03629709,0,130.8973791 +78.34,50.38925134,-3.389276261,10000,-130.9637368,151.1604332,0,14.03629709,0,130.904405 +78.35,50.38923958,-3.389255039,10000,-130.9985525,151.1448898,0,14.03629709,0,130.911431 +78.36,50.38922782,-3.38923382,10000,-131.0159602,151.1284561,0,14.03629709,0,130.9184569 +78.37,50.38921606,-3.389212603,10000,-131.0194415,151.1120223,0,14.03629709,0,130.9254828 +78.38,50.3892043,-3.389191389,10000,-131.0229229,151.0964789,0,14.03629709,0,130.9325087 +78.39,50.38919254,-3.389170176,10000,-131.0403306,151.0809354,0,14.03629709,0,130.9395347 +78.4,50.38918078,-3.389148966,10000,-131.0716647,151.0642791,0,14.03629709,0,130.9465606 +78.41,50.38916901,-3.389127758,10000,-131.092554,151.0471775,0,14.03629709,0,130.9535865 +78.42,50.38915724,-3.389106553,10000,-131.0960353,151.0314115,0,14.03629709,0,130.9606124 +78.43,50.38914548,-3.38908535,10000,-131.1134431,151.016981,0,14.03629709,0,130.9676384 +78.44,50.38913371,-3.389064148,10000,-131.1517404,151.0014375,0,14.03629709,0,130.9746643 +78.45,50.38912193,-3.389042949,10000,-131.1795929,150.9838908,0,14.03629709,0,130.9816902 +78.46,50.38911016,-3.389021753,10000,-131.1865558,150.9665667,0,14.03629709,0,130.9887161 +78.47,50.38909838,-3.389000559,10000,-131.1900371,150.9508007,0,14.03629709,0,130.995742 +78.48,50.38908661,-3.388979367,10000,-131.2039632,150.9354798,0,14.03629709,0,131.002768 +78.49,50.38907483,-3.388958177,10000,-131.2283341,150.9197137,0,14.03629709,0,131.0097938 +78.5,50.38906305,-3.38893699,10000,-131.2561866,150.9035025,0,14.03629709,0,131.0168198 +78.51,50.38905127,-3.388915804,10000,-131.2805575,150.8870687,0,14.03629709,0,131.0238457 +78.52,50.38903948,-3.388894622,10000,-131.2979653,150.8713027,0,14.03629709,0,131.0308716 +78.53,50.3890277,-3.388873441,10000,-131.315373,150.8559818,0,14.03629709,0,131.0378975 +78.54,50.38901591,-3.388852262,10000,-131.3362623,150.8393254,0,14.03629709,0,131.0449235 +78.55,50.38900412,-3.388831086,10000,-131.3501884,150.8217786,0,14.03629709,0,131.0519494 +78.56,50.38899233,-3.388809913,10000,-131.3571513,150.8055674,0,14.03629709,0,131.0589753 +78.57,50.38898054,-3.388788741,10000,-131.3745591,150.7906917,0,14.03629709,0,131.0660012 +78.58,50.38896875,-3.388767572,10000,-131.4093748,150.7753708,0,14.03629709,0,131.0730272 +78.59,50.38895695,-3.388746404,10000,-131.4441904,150.758937,0,14.03629709,0,131.0800531 +78.6,50.38894515,-3.38872524,10000,-131.4615982,150.7422805,0,14.03629709,0,131.087079 +78.61,50.38893335,-3.388704077,10000,-131.4650795,150.7260693,0,14.03629709,0,131.0941049 +78.62,50.38892155,-3.388682917,10000,-131.4685608,150.7100806,0,14.03629709,0,131.1011309 +78.63,50.38890975,-3.388661759,10000,-131.4824869,150.6938694,0,14.03629709,0,131.1081568 +78.64,50.38889795,-3.388640603,10000,-131.5033762,150.677213,0,14.03629709,0,131.1151827 +78.65,50.38888614,-3.38861945,10000,-131.520784,150.6607791,0,14.03629709,0,131.1222086 +78.66,50.38887434,-3.388598299,10000,-131.5381917,150.6452356,0,14.03629709,0,131.1292346 +78.67,50.38886253,-3.38857715,10000,-131.5625626,150.6299147,0,14.03629709,0,131.1362605 +78.68,50.38885072,-3.388556003,10000,-131.5904151,150.6141486,0,14.03629709,0,131.1432864 +78.69,50.38883891,-3.388534859,10000,-131.614786,150.5979373,0,14.03629709,0,131.1503123 +78.7,50.38882709,-3.388513716,10000,-131.6321937,150.5812809,0,14.03629709,0,131.1573383 +78.71,50.38881528,-3.388492577,10000,-131.6496014,150.5646244,0,14.03629709,0,131.1643642 +78.72,50.38880346,-3.388471439,10000,-131.6704907,150.5484131,0,14.03629709,0,131.1713901 +78.73,50.38879164,-3.388450304,10000,-131.6844168,150.5324244,0,14.03629709,0,131.178416 +78.74,50.38877982,-3.388429171,10000,-131.6913798,150.5162132,0,14.03629709,0,131.185442 +78.75,50.388768,-3.38840804,10000,-131.7087875,150.4995567,0,14.03629709,0,131.1924679 +78.76,50.38875618,-3.388386912,10000,-131.7436032,150.4831228,0,14.03629709,0,131.1994938 +78.77,50.38874435,-3.388365786,10000,-131.7784189,150.4678019,0,14.03629709,0,131.2065197 +78.78,50.38873252,-3.388344662,10000,-131.7958266,150.4529261,0,14.03629709,0,131.2135457 +78.79,50.38872069,-3.38832354,10000,-131.7993079,150.4367148,0,14.03629709,0,131.2205716 +78.8,50.38870886,-3.38830242,10000,-131.8027892,150.419168,0,14.03629709,0,131.2275975 +78.81,50.38869703,-3.388281304,10000,-131.8167153,150.4025115,0,14.03629709,0,131.2346234 +78.82,50.3886852,-3.388260189,10000,-131.8376047,150.3871905,0,14.03629709,0,131.2416494 +78.83,50.38867336,-3.388239076,10000,-131.8550124,150.3714244,0,14.03629709,0,131.2486753 +78.84,50.38866153,-3.388217966,10000,-131.8724201,150.3552131,0,14.03629709,0,131.2557012 +78.85,50.38864969,-3.388196858,10000,-131.896791,150.3396695,0,14.03629709,0,131.2627271 +78.86,50.38863785,-3.388175752,10000,-131.9246435,150.324126,0,14.03629709,0,131.269753 +78.87,50.38862601,-3.388154648,10000,-131.9490144,150.3074695,0,14.03629709,0,131.2767789 +78.88,50.38861416,-3.388133547,10000,-131.9664221,150.2901452,0,14.03629709,0,131.2838048 +78.89,50.38860232,-3.388112448,10000,-131.9838298,150.2732661,0,14.03629709,0,131.2908308 +78.9,50.38859047,-3.388091352,10000,-132.0047191,150.2568322,0,14.03629709,0,131.2978567 +78.91,50.38857862,-3.388070257,10000,-132.0186452,150.2401757,0,14.03629709,0,131.3048826 +78.92,50.38856677,-3.388049166,10000,-132.0256081,150.2237418,0,14.03629709,0,131.3119085 +78.93,50.38855492,-3.388028076,10000,-132.0395343,150.2084208,0,14.03629709,0,131.3189345 +78.94,50.38854307,-3.388006989,10000,-132.0604236,150.193545,0,14.03629709,0,131.3259604 +78.95,50.38853121,-3.387985903,10000,-132.0778313,150.1775562,0,14.03629709,0,131.3329863 +78.96,50.38851936,-3.38796482,10000,-132.095239,150.1606771,0,14.03629709,0,131.3400122 +78.97,50.3885075,-3.38794374,10000,-132.1196099,150.1444658,0,14.03629709,0,131.3470382 +78.98,50.38849564,-3.387922661,10000,-132.1474624,150.1286996,0,14.03629709,0,131.3540641 +78.99,50.38848378,-3.387901585,10000,-132.1718333,150.1122657,0,14.03629709,0,131.36109 +79,50.38847191,-3.387880511,10000,-132.189241,150.0958317,0,14.03629709,0,131.3681159 +79.01,50.38846005,-3.38785944,10000,-132.2066487,150.0800655,0,14.03629709,0,131.3751419 +79.02,50.38844818,-3.38783837,10000,-132.227538,150.0638542,0,14.03629709,0,131.3821678 +79.03,50.38843631,-3.387817303,10000,-132.2414641,150.046975,0,14.03629709,0,131.3891937 +79.04,50.38842444,-3.387796239,10000,-132.2484271,150.0305411,0,14.03629709,0,131.3962196 +79.05,50.38841257,-3.387775176,10000,-132.2623532,150.0141071,0,14.03629709,0,131.4032456 +79.06,50.3884007,-3.387754116,10000,-132.2832425,149.997228,0,14.03629709,0,131.4102715 +79.07,50.38838882,-3.387733059,10000,-132.3006502,149.9810166,0,14.03629709,0,131.4172974 +79.08,50.38837695,-3.387712003,10000,-132.3180579,149.965473,0,14.03629709,0,131.4243233 +79.09,50.38836507,-3.38769095,10000,-132.3389472,149.9499294,0,14.03629709,0,131.4313493 +79.1,50.38835319,-3.387669899,10000,-132.3563549,149.9346083,0,14.03629709,0,131.4383752 +79.11,50.38834131,-3.38764885,10000,-132.3772442,149.9190647,0,14.03629709,0,131.4454011 +79.12,50.38832943,-3.387627803,10000,-132.4085783,149.9024081,0,14.03629709,0,131.452427 +79.13,50.38831754,-3.387606759,10000,-132.4294676,149.8850838,0,14.03629709,0,131.459453 +79.14,50.38830565,-3.387585717,10000,-132.4294673,149.8684272,0,14.03629709,0,131.4664789 +79.15,50.38829377,-3.387564678,10000,-132.4364303,149.852661,0,14.03629709,0,131.4735048 +79.16,50.38828188,-3.38754364,10000,-132.4677643,149.8364496,0,14.03629709,0,131.4805307 +79.17,50.38826999,-3.387522605,10000,-132.50258,149.8195704,0,14.03629709,0,131.4875567 +79.18,50.38825809,-3.387501573,10000,-132.5234693,149.803359,0,14.03629709,0,131.4945825 +79.19,50.3882462,-3.387480542,10000,-132.540877,149.7875928,0,14.03629709,0,131.5016085 +79.2,50.3882343,-3.387459514,10000,-132.5617664,149.7709362,0,14.03629709,0,131.5086344 +79.21,50.3882224,-3.387438488,10000,-132.5756925,149.7536118,0,14.03629709,0,131.5156603 +79.22,50.3882105,-3.387417465,10000,-132.5791738,149.7369552,0,14.03629709,0,131.5226862 +79.23,50.3881986,-3.387396444,10000,-132.5826551,149.7216341,0,14.03629709,0,131.5297122 +79.24,50.3881867,-3.387375425,10000,-132.6000628,149.7069808,0,14.03629709,0,131.5367381 +79.25,50.3881748,-3.387354408,10000,-132.6348785,149.6916597,0,14.03629709,0,131.543764 +79.26,50.38816289,-3.387333393,10000,-132.6696942,149.6750031,0,14.03629709,0,131.5507899 +79.27,50.38815098,-3.387312381,10000,-132.6871019,149.6576788,0,14.03629709,0,131.5578158 +79.28,50.38813907,-3.387291371,10000,-132.6940648,149.6410221,0,14.03629709,0,131.5648418 +79.29,50.38812716,-3.387270364,10000,-132.7079909,149.6252559,0,14.03629709,0,131.5718677 +79.3,50.38811525,-3.387249358,10000,-132.7288802,149.6088218,0,14.03629709,0,131.5788936 +79.31,50.38810333,-3.387228355,10000,-132.7462879,149.5912749,0,14.03629709,0,131.5859195 +79.32,50.38809142,-3.387207355,10000,-132.7636956,149.5746182,0,14.03629709,0,131.5929455 +79.33,50.3880795,-3.387186357,10000,-132.784585,149.5592971,0,14.03629709,0,131.5999714 +79.34,50.38806758,-3.38716536,10000,-132.8019927,149.5435308,0,14.03629709,0,131.6069973 +79.35,50.38805566,-3.387144367,10000,-132.8194004,149.5270968,0,14.03629709,0,131.6140232 +79.36,50.38804374,-3.387123375,10000,-132.8402896,149.5108853,0,14.03629709,0,131.6210492 +79.37,50.38803181,-3.387102386,10000,-132.8576974,149.4948965,0,14.03629709,0,131.6280751 +79.38,50.38801989,-3.387081399,10000,-132.8751051,149.478685,0,14.03629709,0,131.635101 +79.39,50.38800796,-3.387060414,10000,-132.8959944,149.4620283,0,14.03629709,0,131.6421269 +79.4,50.38799603,-3.387039432,10000,-132.9134021,149.4453717,0,14.03629709,0,131.6491529 +79.41,50.3879841,-3.387018452,10000,-132.9308098,149.4289376,0,14.03629709,0,131.6561788 +79.42,50.38797217,-3.386997474,10000,-132.9516991,149.412281,0,14.03629709,0,131.6632047 +79.43,50.38796023,-3.386976499,10000,-132.9691068,149.3958469,0,14.03629709,0,131.6702306 +79.44,50.3879483,-3.386955526,10000,-132.9865145,149.3803032,0,14.03629709,0,131.6772566 +79.45,50.38793636,-3.386934555,10000,-133.0074038,149.3647594,0,14.03629709,0,131.6842825 +79.46,50.38792442,-3.386913586,10000,-133.0248115,149.3483253,0,14.03629709,0,131.6913084 +79.47,50.38791248,-3.38689262,10000,-133.0422192,149.3318913,0,14.03629709,0,131.6983343 +79.48,50.38790054,-3.386871656,10000,-133.0631085,149.3163475,0,14.03629709,0,131.7053603 +79.49,50.38788859,-3.386850694,10000,-133.0805162,149.3005812,0,14.03629709,0,131.7123862 +79.5,50.38787665,-3.386829734,10000,-133.0979239,149.2832568,0,14.03629709,0,131.7194121 +79.51,50.3878647,-3.386808777,10000,-133.1188132,149.2654871,0,14.03629709,0,131.726438 +79.52,50.38785275,-3.386787823,10000,-133.1327393,149.249053,0,14.03629709,0,131.733464 +79.53,50.3878408,-3.38676687,10000,-133.1397023,149.2335093,0,14.03629709,0,131.7404898 +79.54,50.38782885,-3.38674592,10000,-133.1571099,149.2177429,0,14.03629709,0,131.7475158 +79.55,50.3878169,-3.386724972,10000,-133.1919256,149.2015314,0,14.03629709,0,131.7545417 +79.56,50.38780494,-3.386704026,10000,-133.2267413,149.1846521,0,14.03629709,0,131.7615676 +79.57,50.38779298,-3.386683083,10000,-133.244149,149.1673276,0,14.03629709,0,131.7685935 +79.58,50.38778102,-3.386662142,10000,-133.2476303,149.1506709,0,14.03629709,0,131.7756195 +79.59,50.38776906,-3.386641204,10000,-133.2511117,149.1351272,0,14.03629709,0,131.7826454 +79.6,50.3877571,-3.386620267,10000,-133.2650378,149.1195834,0,14.03629709,0,131.7896713 +79.61,50.38774514,-3.386599333,10000,-133.2859271,149.1031493,0,14.03629709,0,131.7966972 +79.62,50.38773317,-3.386578401,10000,-133.3033348,149.0867151,0,14.03629709,0,131.8037232 +79.63,50.38772121,-3.386557472,10000,-133.3207425,149.0709488,0,14.03629709,0,131.8107491 +79.64,50.38770924,-3.386536544,10000,-133.3451134,149.0547372,0,14.03629709,0,131.817775 +79.65,50.38769727,-3.386515619,10000,-133.3729658,149.0376353,0,14.03629709,0,131.8248009 +79.66,50.3876853,-3.386494697,10000,-133.3973367,149.0205334,0,14.03629709,0,131.8318268 +79.67,50.38767332,-3.386473776,10000,-133.4147445,149.0038766,0,14.03629709,0,131.8388528 +79.68,50.38766135,-3.386452859,10000,-133.4321522,148.9881103,0,14.03629709,0,131.8458787 +79.69,50.38764937,-3.386431943,10000,-133.4530415,148.9727891,0,14.03629709,0,131.8529046 +79.7,50.38763739,-3.386411029,10000,-133.4669676,148.9561323,0,14.03629709,0,131.8599305 +79.71,50.38762541,-3.386390118,10000,-133.4739305,148.9385852,0,14.03629709,0,131.8669565 +79.72,50.38761343,-3.38636921,10000,-133.4913382,148.922151,0,14.03629709,0,131.8739824 +79.73,50.38760145,-3.386348303,10000,-133.5226723,148.9063846,0,14.03629709,0,131.8810083 +79.74,50.38758946,-3.386327399,10000,-133.5435616,148.8899505,0,14.03629709,0,131.8880342 +79.75,50.38757747,-3.386306497,10000,-133.5435613,148.8735163,0,14.03629709,0,131.8950602 +79.76,50.38756549,-3.386285598,10000,-133.5505242,148.8577499,0,14.03629709,0,131.9020861 +79.77,50.3875535,-3.3862647,10000,-133.5818583,148.8415383,0,14.03629709,0,131.909112 +79.78,50.38754151,-3.386243805,10000,-133.6166739,148.8246589,0,14.03629709,0,131.9161379 +79.79,50.38752951,-3.386222913,10000,-133.6375632,148.8082247,0,14.03629709,0,131.9231639 +79.8,50.38751752,-3.386202022,10000,-133.654971,148.7917906,0,14.03629709,0,131.9301898 +79.81,50.38750552,-3.386181134,10000,-133.6758603,148.7749112,0,14.03629709,0,131.9372157 +79.82,50.38749352,-3.386160249,10000,-133.6897864,148.7586996,0,14.03629709,0,131.9442416 +79.83,50.38748152,-3.386139365,10000,-133.6967493,148.7429332,0,14.03629709,0,131.9512676 +79.84,50.38746952,-3.386118484,10000,-133.7106754,148.7264989,0,14.03629709,0,131.9582934 +79.85,50.38745752,-3.386097605,10000,-133.7315647,148.7100647,0,14.03629709,0,131.9653194 +79.86,50.38744551,-3.386076729,10000,-133.7489724,148.6942983,0,14.03629709,0,131.9723453 +79.87,50.38743351,-3.386055854,10000,-133.7663801,148.6780867,0,14.03629709,0,131.9793712 +79.88,50.3874215,-3.386034982,10000,-133.7872694,148.6612073,0,14.03629709,0,131.9863971 +79.89,50.38740949,-3.386014113,10000,-133.8046771,148.6447731,0,14.03629709,0,131.9934231 +79.9,50.38739748,-3.385993245,10000,-133.8255664,148.6281162,0,14.03629709,0,132.000449 +79.91,50.38738547,-3.38597238,10000,-133.8569005,148.6103465,0,14.03629709,0,132.0074749 +79.92,50.38737345,-3.385951518,10000,-133.8777897,148.5930219,0,14.03629709,0,132.0145008 +79.93,50.38736143,-3.385930658,10000,-133.8777895,148.577478,0,14.03629709,0,132.0215268 +79.94,50.38734942,-3.3859098,10000,-133.8847524,148.5628245,0,14.03629709,0,132.0285527 +79.95,50.3873374,-3.385888944,10000,-133.9160864,148.5475032,0,14.03629709,0,132.0355786 +79.96,50.38732538,-3.38586809,10000,-133.9509021,148.5308464,0,14.03629709,0,132.0426045 +79.97,50.38731335,-3.385847239,10000,-133.9683098,148.5132992,0,14.03629709,0,132.0496305 +79.98,50.38730133,-3.38582639,10000,-133.9717912,148.495752,0,14.03629709,0,132.0566564 +79.99,50.3872893,-3.385805544,10000,-133.9752725,148.4788726,0,14.03629709,0,132.0636823 +80,50.38727728,-3.3857847,10000,-133.9926802,148.4626609,0,14.03629709,0,132.0707082 +80.01,50.38726525,-3.385763858,10000,-134.0274958,148.4468944,0,14.03629709,0,132.0777342 +80.02,50.38725322,-3.385743019,10000,-134.0623115,148.4315731,0,14.03629709,0,132.0847601 +80.03,50.38724118,-3.385722181,10000,-134.0797192,148.4158066,0,14.03629709,0,132.091786 +80.04,50.38722915,-3.385701346,10000,-134.0832005,148.398482,0,14.03629709,0,132.0988119 +80.05,50.38721711,-3.385680513,10000,-134.0866819,148.3807122,0,14.03629709,0,132.1058379 +80.06,50.38720508,-3.385659684,10000,-134.1040896,148.3640553,0,14.03629709,0,132.1128638 +80.07,50.38719304,-3.385638855,10000,-134.1389052,148.3478436,0,14.03629709,0,132.1198897 +80.08,50.387181,-3.38561803,10000,-134.1702393,148.3318545,0,14.03629709,0,132.1269156 +80.09,50.38716895,-3.385597207,10000,-134.1772022,148.3167558,0,14.03629709,0,132.1339415 +80.1,50.38715691,-3.385576385,10000,-134.1772019,148.3009893,0,14.03629709,0,132.1409675 +80.11,50.38714487,-3.385555566,10000,-134.1980912,148.283442,0,14.03629709,0,132.1479934 +80.12,50.38713282,-3.38553475,10000,-134.2294253,148.2658948,0,14.03629709,0,132.1550193 +80.13,50.38712077,-3.385513936,10000,-134.2503146,148.2494605,0,14.03629709,0,132.1620452 +80.14,50.38710872,-3.385493124,10000,-134.2677223,148.2334714,0,14.03629709,0,132.1690712 +80.15,50.38709667,-3.385472315,10000,-134.2886116,148.2172597,0,14.03629709,0,132.1760971 +80.16,50.38708461,-3.385451507,10000,-134.3060193,148.2006028,0,14.03629709,0,132.183123 +80.17,50.38707256,-3.385430703,10000,-134.323427,148.1839459,0,14.03629709,0,132.1901489 +80.18,50.3870605,-3.3854099,10000,-134.3443163,148.1675115,0,14.03629709,0,132.1971749 +80.19,50.38704844,-3.3853891,10000,-134.3582424,148.150632,0,14.03629709,0,132.2042007 +80.2,50.38703638,-3.385368302,10000,-134.3652053,148.1333073,0,14.03629709,0,132.2112267 +80.21,50.38702432,-3.385347507,10000,-134.3791314,148.1166504,0,14.03629709,0,132.2182526 +80.22,50.38701226,-3.385326714,10000,-134.4000207,148.1011065,0,14.03629709,0,132.2252785 +80.23,50.38700019,-3.385305923,10000,-134.4174284,148.0855625,0,14.03629709,0,132.2323044 +80.24,50.38698813,-3.385285134,10000,-134.4383177,148.0691282,0,14.03629709,0,132.2393304 +80.25,50.38697606,-3.385264348,10000,-134.4731334,148.0524713,0,14.03629709,0,132.2463563 +80.26,50.38696399,-3.385243564,10000,-134.5044674,148.0360369,0,14.03629709,0,132.2533822 +80.27,50.38695191,-3.385222782,10000,-134.5114303,148.01938,0,14.03629709,0,132.2604081 +80.28,50.38693984,-3.385202003,10000,-134.51143,148.002723,0,14.03629709,0,132.2674341 +80.29,50.38692777,-3.385181226,10000,-134.5323193,147.9862887,0,14.03629709,0,132.27446 +80.3,50.38691569,-3.385160451,10000,-134.5636534,147.9696317,0,14.03629709,0,132.2814859 +80.31,50.38690361,-3.385139679,10000,-134.5810611,147.9529748,0,14.03629709,0,132.2885118 +80.32,50.38689153,-3.385118909,10000,-134.588024,147.9365404,0,14.03629709,0,132.2955378 +80.33,50.38687945,-3.385098141,10000,-134.6019501,147.9198835,0,14.03629709,0,132.3025637 +80.34,50.38686737,-3.385077376,10000,-134.6228394,147.9034491,0,14.03629709,0,132.3095896 +80.35,50.38685528,-3.385056613,10000,-134.6402471,147.8879051,0,14.03629709,0,132.3166155 +80.36,50.3868432,-3.385035852,10000,-134.6576548,147.8721385,0,14.03629709,0,132.3236415 +80.37,50.38683111,-3.385015093,10000,-134.6785441,147.8548138,0,14.03629709,0,132.3306674 +80.38,50.38681902,-3.384994337,10000,-134.6959518,147.8370438,0,14.03629709,0,132.3376933 +80.39,50.38680693,-3.384973584,10000,-134.7133595,147.8206094,0,14.03629709,0,132.3447192 +80.4,50.38679484,-3.384952832,10000,-134.7342488,147.8048428,0,14.03629709,0,132.3517452 +80.41,50.38678274,-3.384932083,10000,-134.7516565,147.7881859,0,14.03629709,0,132.3587711 +80.42,50.38677065,-3.384911336,10000,-134.7690642,147.7708611,0,14.03629709,0,132.365797 +80.43,50.38675855,-3.384890592,10000,-134.793435,147.7542041,0,14.03629709,0,132.3728229 +80.44,50.38674645,-3.38486985,10000,-134.8212875,147.7386601,0,14.03629709,0,132.3798489 +80.45,50.38673435,-3.38484911,10000,-134.8421768,147.7231161,0,14.03629709,0,132.3868748 +80.46,50.38672224,-3.384828372,10000,-134.8456581,147.7064591,0,14.03629709,0,132.3939007 +80.47,50.38671014,-3.384807637,10000,-134.8456578,147.6889117,0,14.03629709,0,132.4009266 +80.48,50.38669804,-3.384786904,10000,-134.8665471,147.6713643,0,14.03629709,0,132.4079525 +80.49,50.38668593,-3.384766174,10000,-134.8978812,147.6547073,0,14.03629709,0,132.4149785 +80.5,50.38667382,-3.384745446,10000,-134.9187705,147.6391632,0,14.03629709,0,132.4220044 +80.51,50.38666171,-3.38472472,10000,-134.9361782,147.6236192,0,14.03629709,0,132.4290303 +80.52,50.3866496,-3.384703996,10000,-134.9570675,147.6071848,0,14.03629709,0,132.4360562 +80.53,50.38663748,-3.384683275,10000,-134.9744752,147.5905277,0,14.03629709,0,132.4430821 +80.54,50.38662537,-3.384662556,10000,-134.9918828,147.5738707,0,14.03629709,0,132.450108 +80.55,50.38661325,-3.384641839,10000,-135.0127721,147.5563233,0,14.03629709,0,132.457134 +80.56,50.38660113,-3.384621125,10000,-135.0301798,147.5385533,0,14.03629709,0,132.4641599 +80.57,50.38658901,-3.384600414,10000,-135.0475875,147.5221189,0,14.03629709,0,132.4711858 +80.58,50.38657689,-3.384579704,10000,-135.0684768,147.5063522,0,14.03629709,0,132.4782117 +80.59,50.38656476,-3.384558997,10000,-135.0858845,147.4899177,0,14.03629709,0,132.4852377 +80.6,50.38655264,-3.384538292,10000,-135.1032922,147.4734833,0,14.03629709,0,132.4922636 +80.61,50.38654051,-3.38451759,10000,-135.1241815,147.4577166,0,14.03629709,0,132.4992895 +80.62,50.38652838,-3.384496889,10000,-135.1381076,147.4415048,0,14.03629709,0,132.5063154 +80.63,50.38651625,-3.384476191,10000,-135.1450705,147.4244025,0,14.03629709,0,132.5133414 +80.64,50.38650412,-3.384455496,10000,-135.1589966,147.4073003,0,14.03629709,0,132.5203673 +80.65,50.38649199,-3.384434802,10000,-135.1798859,147.3904206,0,14.03629709,0,132.5273932 +80.66,50.38647985,-3.384414112,10000,-135.1972936,147.3737635,0,14.03629709,0,132.5344191 +80.67,50.38646772,-3.384393423,10000,-135.2147013,147.3575516,0,14.03629709,0,132.5414451 +80.68,50.38645558,-3.384372737,10000,-135.2390721,147.3415623,0,14.03629709,0,132.548471 +80.69,50.38644344,-3.384352053,10000,-135.2669246,147.3253505,0,14.03629709,0,132.5554969 +80.7,50.3864313,-3.384331371,10000,-135.2912955,147.3084708,0,14.03629709,0,132.5625228 +80.71,50.38641915,-3.384310692,10000,-135.3087032,147.2911459,0,14.03629709,0,132.5695488 +80.72,50.38640701,-3.384290015,10000,-135.3261109,147.2744888,0,14.03629709,0,132.5765747 +80.73,50.38639486,-3.384269341,10000,-135.3470002,147.2587221,0,14.03629709,0,132.5836006 +80.74,50.38638271,-3.384248668,10000,-135.3609263,147.2422876,0,14.03629709,0,132.5906265 +80.75,50.38637056,-3.384227998,10000,-135.3644076,147.2245175,0,14.03629709,0,132.5976525 +80.76,50.38635841,-3.384207331,10000,-135.3678889,147.2071926,0,14.03629709,0,132.6046784 +80.77,50.38634626,-3.384186666,10000,-135.3852966,147.1914259,0,14.03629709,0,132.6117043 +80.78,50.38633411,-3.384166003,10000,-135.4201122,147.1758818,0,14.03629709,0,132.6187302 +80.79,50.38632195,-3.384145342,10000,-135.4549279,147.1592247,0,14.03629709,0,132.6257562 +80.8,50.38630979,-3.384124684,10000,-135.4723356,147.1416772,0,14.03629709,0,132.6327821 +80.81,50.38629763,-3.384104028,10000,-135.4758169,147.1241297,0,14.03629709,0,132.639808 +80.82,50.38628547,-3.384083375,10000,-135.4792982,147.1074725,0,14.03629709,0,132.6468339 +80.83,50.38627331,-3.384062724,10000,-135.4967059,147.0919284,0,14.03629709,0,132.6538599 +80.84,50.38626115,-3.384042075,10000,-135.5315216,147.0763842,0,14.03629709,0,132.6608858 +80.85,50.38624898,-3.384021428,10000,-135.5663372,147.0597271,0,14.03629709,0,132.6679117 +80.86,50.38623681,-3.384000784,10000,-135.5837449,147.0421796,0,14.03629709,0,132.6749376 +80.87,50.38622464,-3.383980142,10000,-135.5872262,147.0248546,0,14.03629709,0,132.6819635 +80.88,50.38621247,-3.383959503,10000,-135.5907075,147.0088653,0,14.03629709,0,132.6889894 +80.89,50.3862003,-3.383938866,10000,-135.6081152,146.9935437,0,14.03629709,0,132.6960153 +80.9,50.38618813,-3.38391823,10000,-135.6429309,146.9768865,0,14.03629709,0,132.7030413 +80.91,50.38617595,-3.383897598,10000,-135.6777465,146.9591164,0,14.03629709,0,132.7100672 +80.92,50.38616377,-3.383876968,10000,-135.6951543,146.9417915,0,14.03629709,0,132.7170931 +80.93,50.38615159,-3.38385634,10000,-135.6986356,146.9249117,0,14.03629709,0,132.724119 +80.94,50.38613941,-3.383835715,10000,-135.7021169,146.9082545,0,14.03629709,0,132.731145 +80.95,50.38612723,-3.383815092,10000,-135.7160429,146.8920426,0,14.03629709,0,132.7381709 +80.96,50.38611505,-3.383794471,10000,-135.7369322,146.8760532,0,14.03629709,0,132.7451968 +80.97,50.38610286,-3.383773853,10000,-135.7543399,146.8596186,0,14.03629709,0,132.7522227 +80.98,50.38609068,-3.383753236,10000,-135.7717476,146.8422936,0,14.03629709,0,132.7592487 +80.99,50.38607849,-3.383732623,10000,-135.7961185,146.8251912,0,14.03629709,0,132.7662746 +81,50.3860663,-3.383712012,10000,-135.823971,146.8092018,0,14.03629709,0,132.7733005 +81.01,50.38605411,-3.383691402,10000,-135.8483418,146.7932124,0,14.03629709,0,132.7803264 +81.02,50.38604191,-3.383670796,10000,-135.8657495,146.7765552,0,14.03629709,0,132.7873524 +81.03,50.38602972,-3.383650191,10000,-135.8831572,146.7594528,0,14.03629709,0,132.7943783 +81.04,50.38601752,-3.383629589,10000,-135.9040465,146.7423504,0,14.03629709,0,132.8014042 +81.05,50.38600532,-3.38360899,10000,-135.9179726,146.7259158,0,14.03629709,0,132.8084301 +81.06,50.38599312,-3.383588392,10000,-135.9249355,146.7094812,0,14.03629709,0,132.8154561 +81.07,50.38598092,-3.383567797,10000,-135.9388616,146.6926014,0,14.03629709,0,132.822482 +81.08,50.38596872,-3.383547205,10000,-135.9597509,146.6763894,0,14.03629709,0,132.8295079 +81.09,50.38595651,-3.383526614,10000,-135.9771586,146.6604,0,14.03629709,0,132.8365338 +81.1,50.38594431,-3.383506026,10000,-135.9945662,146.6430749,0,14.03629709,0,132.8435598 +81.11,50.3859321,-3.38348544,10000,-136.0154555,146.6253047,0,14.03629709,0,132.8505857 +81.12,50.38591989,-3.383464858,10000,-136.0328632,146.6086475,0,14.03629709,0,132.8576116 +81.13,50.38590768,-3.383444276,10000,-136.0502709,146.5922128,0,14.03629709,0,132.8646375 +81.14,50.38589547,-3.383423698,10000,-136.0711602,146.575333,0,14.03629709,0,132.8716635 +81.15,50.38588325,-3.383403122,10000,-136.0885679,146.559121,0,14.03629709,0,132.8786894 +81.16,50.38587104,-3.383382548,10000,-136.1059755,146.5433541,0,14.03629709,0,132.8857153 +81.17,50.38585882,-3.383361976,10000,-136.1268648,146.5266969,0,14.03629709,0,132.8927412 +81.18,50.3858466,-3.383341407,10000,-136.1442725,146.5091492,0,14.03629709,0,132.8997672 +81.19,50.38583438,-3.38332084,10000,-136.1616802,146.4916016,0,14.03629709,0,132.9067931 +81.2,50.38582216,-3.383300276,10000,-136.1825695,146.4747217,0,14.03629709,0,132.913819 +81.21,50.38580993,-3.383279714,10000,-136.1999771,146.458287,0,14.03629709,0,132.9208449 +81.22,50.38579771,-3.383259154,10000,-136.2173848,146.4416298,0,14.03629709,0,132.9278709 +81.23,50.38578548,-3.383238597,10000,-136.2382741,146.4251951,0,14.03629709,0,132.9348967 +81.24,50.38577325,-3.383218042,10000,-136.2522002,146.4096508,0,14.03629709,0,132.9419227 +81.25,50.38576102,-3.383197489,10000,-136.2591631,146.3938839,0,14.03629709,0,132.9489486 +81.26,50.38574879,-3.383176938,10000,-136.2765708,146.3765588,0,14.03629709,0,132.9559745 +81.27,50.38573656,-3.38315639,10000,-136.3079049,146.358566,0,14.03629709,0,132.9630004 +81.28,50.38572432,-3.383135845,10000,-136.3287941,146.3412409,0,14.03629709,0,132.9700263 +81.29,50.38571208,-3.383115301,10000,-136.3322754,146.3245836,0,14.03629709,0,132.9770523 +81.3,50.38569985,-3.383094761,10000,-136.3496831,146.3085941,0,14.03629709,0,132.9840782 +81.31,50.38568761,-3.383074222,10000,-136.3844988,146.2926046,0,14.03629709,0,132.9911041 +81.32,50.38567536,-3.383053685,10000,-136.4019065,146.2755021,0,14.03629709,0,132.99813 +81.33,50.38566312,-3.383033152,10000,-136.4053878,146.258177,0,14.03629709,0,133.005156 +81.34,50.38565088,-3.38301262,10000,-136.426277,146.2417422,0,14.03629709,0,133.0121819 +81.35,50.38563863,-3.382992091,10000,-136.4576111,146.2257527,0,14.03629709,0,133.0192078 +81.36,50.38562638,-3.382971564,10000,-136.4750188,146.209318,0,14.03629709,0,133.0262337 +81.37,50.38561413,-3.382951039,10000,-136.4819817,146.1917703,0,14.03629709,0,133.0332597 +81.38,50.38560188,-3.382930517,10000,-136.4959078,146.174,0,14.03629709,0,133.0402856 +81.39,50.38558963,-3.382909998,10000,-136.5167971,146.1575652,0,14.03629709,0,133.0473115 +81.4,50.38557737,-3.38288948,10000,-136.5342048,146.1417983,0,14.03629709,0,133.0543374 +81.41,50.38556512,-3.382868965,10000,-136.5516124,146.1251409,0,14.03629709,0,133.0613634 +81.42,50.38555286,-3.382848452,10000,-136.5725017,146.1078158,0,14.03629709,0,133.0683893 +81.43,50.3855406,-3.382827942,10000,-136.5899094,146.0909359,0,14.03629709,0,133.0754152 +81.44,50.38552834,-3.382807434,10000,-136.6073171,146.0745011,0,14.03629709,0,133.0824411 +81.45,50.38551608,-3.382786928,10000,-136.6282063,146.0576211,0,14.03629709,0,133.0894671 +81.46,50.38550381,-3.382766425,10000,-136.645614,146.040296,0,14.03629709,0,133.096493 +81.47,50.38549155,-3.382745924,10000,-136.6630217,146.023416,0,14.03629709,0,133.1035189 +81.48,50.38547928,-3.382725426,10000,-136.683911,146.0069813,0,14.03629709,0,133.1105448 +81.49,50.38546701,-3.382704929,10000,-136.7013187,145.9903239,0,14.03629709,0,133.1175708 +81.5,50.38545474,-3.382684436,10000,-136.7187264,145.9736665,0,14.03629709,0,133.1245967 +81.51,50.38544247,-3.382663944,10000,-136.7396156,145.9572318,0,14.03629709,0,133.1316226 +81.52,50.38543019,-3.382643455,10000,-136.7570233,145.9403518,0,14.03629709,0,133.1386485 +81.53,50.38541792,-3.382622968,10000,-136.774431,145.9230266,0,14.03629709,0,133.1456745 +81.54,50.38540564,-3.382602484,10000,-136.7953203,145.9063692,0,14.03629709,0,133.1527003 +81.55,50.38539336,-3.382582002,10000,-136.8092464,145.8906022,0,14.03629709,0,133.1597263 +81.56,50.38538108,-3.382561522,10000,-136.8162093,145.8741674,0,14.03629709,0,133.1667522 +81.57,50.3853688,-3.382541044,10000,-136.8336169,145.856397,0,14.03629709,0,133.1737781 +81.58,50.38535652,-3.38252057,10000,-136.864951,145.8388492,0,14.03629709,0,133.180804 +81.59,50.38534423,-3.382500097,10000,-136.8858403,145.8221918,0,14.03629709,0,133.18783 +81.6,50.38533194,-3.382479627,10000,-136.8893216,145.8055344,0,14.03629709,0,133.1948559 +81.61,50.38531966,-3.382459159,10000,-136.9067293,145.788877,0,14.03629709,0,133.2018818 +81.62,50.38530737,-3.382438694,10000,-136.9415449,145.7724422,0,14.03629709,0,133.2089077 +81.63,50.38529507,-3.38241823,10000,-136.9589526,145.7557848,0,14.03629709,0,133.2159337 +81.64,50.38528278,-3.38239777,10000,-136.9624339,145.7391273,0,14.03629709,0,133.2229596 +81.65,50.38527049,-3.382377311,10000,-136.9833231,145.7226925,0,14.03629709,0,133.2299855 +81.66,50.38525819,-3.382356855,10000,-137.0146572,145.7058125,0,14.03629709,0,133.2370114 +81.67,50.38524589,-3.382336401,10000,-137.0320649,145.6882646,0,14.03629709,0,133.2440373 +81.68,50.38523359,-3.38231595,10000,-137.0390278,145.6707168,0,14.03629709,0,133.2510633 +81.69,50.38522129,-3.382295501,10000,-137.0529539,145.6540593,0,14.03629709,0,133.2580892 +81.7,50.38520899,-3.382275055,10000,-137.0738432,145.6382923,0,14.03629709,0,133.2651151 +81.71,50.38519668,-3.38225461,10000,-137.0912508,145.6218575,0,14.03629709,0,133.272141 +81.72,50.38518438,-3.382234168,10000,-137.1086585,145.604087,0,14.03629709,0,133.279167 +81.73,50.38517207,-3.382213729,10000,-137.1295478,145.5867617,0,14.03629709,0,133.2861929 +81.74,50.38515976,-3.382193292,10000,-137.1469555,145.5709947,0,14.03629709,0,133.2932188 +81.75,50.38514745,-3.382172857,10000,-137.1643632,145.5552276,0,14.03629709,0,133.3002447 +81.76,50.38513514,-3.382152424,10000,-137.1852524,145.5379023,0,14.03629709,0,133.3072707 +81.77,50.38512282,-3.382131994,10000,-137.2026601,145.5201319,0,14.03629709,0,133.3142966 +81.78,50.38511051,-3.382111567,10000,-137.2200678,145.5034744,0,14.03629709,0,133.3213225 +81.79,50.38509819,-3.382091141,10000,-137.2409571,145.4868169,0,14.03629709,0,133.3283484 +81.8,50.38508587,-3.382070718,10000,-137.2548831,145.469269,0,14.03629709,0,133.3353744 +81.81,50.38507355,-3.382050298,10000,-137.261846,145.4526115,0,14.03629709,0,133.3424003 +81.82,50.38506123,-3.38202988,10000,-137.2792537,145.437067,0,14.03629709,0,133.3494262 +81.83,50.38504891,-3.382009463,10000,-137.3105878,145.4204095,0,14.03629709,0,133.3564521 +81.84,50.38503658,-3.38198905,10000,-137.331477,145.402639,0,14.03629709,0,133.3634781 +81.85,50.38502425,-3.381968639,10000,-137.3349583,145.3853137,0,14.03629709,0,133.370504 +81.86,50.38501193,-3.38194823,10000,-137.352366,145.3684336,0,14.03629709,0,133.3775299 +81.87,50.3849996,-3.381927824,10000,-137.3871817,145.3517761,0,14.03629709,0,133.3845558 +81.88,50.38498726,-3.38190742,10000,-137.4045894,145.3353412,0,14.03629709,0,133.3915818 +81.89,50.38497493,-3.381887018,10000,-137.4080707,145.3184611,0,14.03629709,0,133.3986076 +81.9,50.3849626,-3.381866619,10000,-137.4289599,145.3011357,0,14.03629709,0,133.4056336 +81.91,50.38495026,-3.381846222,10000,-137.460294,145.2842556,0,14.03629709,0,133.4126595 +81.92,50.38493792,-3.381825828,10000,-137.4777016,145.2675981,0,14.03629709,0,133.4196854 +81.93,50.38492558,-3.381805435,10000,-137.4846645,145.2502727,0,14.03629709,0,133.4267113 +81.94,50.38491324,-3.381785046,10000,-137.4985906,145.23317,0,14.03629709,0,133.4337373 +81.95,50.3849009,-3.381764659,10000,-137.5194799,145.2171802,0,14.03629709,0,133.4407632 +81.96,50.38488855,-3.381744273,10000,-137.5368876,145.2011905,0,14.03629709,0,133.4477891 +81.97,50.38487621,-3.381723891,10000,-137.5542952,145.184533,0,14.03629709,0,133.454815 +81.98,50.38486386,-3.38170351,10000,-137.5751845,145.1672076,0,14.03629709,0,133.461841 +81.99,50.38485151,-3.381683132,10000,-137.5925922,145.1492144,0,14.03629709,0,133.4688669 +82,50.38483916,-3.381662757,10000,-137.6099999,145.1316664,0,14.03629709,0,133.4758928 +82.01,50.38482681,-3.381642384,10000,-137.6308891,145.1152315,0,14.03629709,0,133.4829187 +82.02,50.38481445,-3.381622013,10000,-137.6482968,145.0992417,0,14.03629709,0,133.4899447 +82.03,50.3848021,-3.381601645,10000,-137.6657045,145.0828068,0,14.03629709,0,133.4969706 +82.04,50.38478974,-3.381581278,10000,-137.6865938,145.0652588,0,14.03629709,0,133.5039965 +82.05,50.38477738,-3.381560915,10000,-137.7005199,145.0474882,0,14.03629709,0,133.5110224 +82.06,50.38476502,-3.381540554,10000,-137.7074828,145.0310532,0,14.03629709,0,133.5180484 +82.07,50.38475266,-3.381520195,10000,-137.7214088,145.015286,0,14.03629709,0,133.5250743 +82.08,50.3847403,-3.381499838,10000,-137.7422981,144.9986284,0,14.03629709,0,133.5321002 +82.09,50.38472793,-3.381479484,10000,-137.7597058,144.9810804,0,14.03629709,0,133.5391261 +82.1,50.38471557,-3.381459132,10000,-137.7771134,144.9635324,0,14.03629709,0,133.546152 +82.11,50.3847032,-3.381438783,10000,-137.8014843,144.9466522,0,14.03629709,0,133.553178 +82.12,50.38469083,-3.381418436,10000,-137.8293368,144.9302172,0,14.03629709,0,133.5602039 +82.13,50.38467846,-3.381398091,10000,-137.8537076,144.913337,0,14.03629709,0,133.5672298 +82.14,50.38466608,-3.381377749,10000,-137.8711153,144.8960115,0,14.03629709,0,133.5742557 +82.15,50.38465371,-3.381357409,10000,-137.888523,144.8791313,0,14.03629709,0,133.5812817 +82.16,50.38464133,-3.381337072,10000,-137.9094123,144.8626963,0,14.03629709,0,133.5883076 +82.17,50.38462895,-3.381316736,10000,-137.9233383,144.8460387,0,14.03629709,0,133.5953335 +82.18,50.38461657,-3.381296404,10000,-137.9268196,144.8291584,0,14.03629709,0,133.6023594 +82.19,50.38460419,-3.381276073,10000,-137.9303009,144.8120556,0,14.03629709,0,133.6093854 +82.2,50.38459181,-3.381255745,10000,-137.9477086,144.7947301,0,14.03629709,0,133.6164112 +82.21,50.38457943,-3.38123542,10000,-137.9825242,144.7776273,0,14.03629709,0,133.6234372 +82.22,50.38456704,-3.381215096,10000,-138.0173399,144.760747,0,14.03629709,0,133.6304631 +82.23,50.38455465,-3.381194776,10000,-138.0347476,144.7440894,0,14.03629709,0,133.637489 +82.24,50.38454226,-3.381174457,10000,-138.0382289,144.7276543,0,14.03629709,0,133.6445149 +82.25,50.38452987,-3.381154141,10000,-138.0417102,144.7107741,0,14.03629709,0,133.6515409 +82.26,50.38451748,-3.381133827,10000,-138.0556362,144.6934486,0,14.03629709,0,133.6585668 +82.27,50.38450509,-3.381113516,10000,-138.0765255,144.6765683,0,14.03629709,0,133.6655927 +82.28,50.38449269,-3.381093207,10000,-138.0939332,144.6599106,0,14.03629709,0,133.6726186 +82.29,50.3844803,-3.3810729,10000,-138.1148224,144.6423625,0,14.03629709,0,133.6796446 +82.3,50.3844679,-3.381052596,10000,-138.1496381,144.6245918,0,14.03629709,0,133.6866705 +82.31,50.3844555,-3.381032295,10000,-138.1809721,144.6079342,0,14.03629709,0,133.6936964 +82.32,50.38444309,-3.381011995,10000,-138.187935,144.5914991,0,14.03629709,0,133.7007223 +82.33,50.38443069,-3.380991698,10000,-138.1879347,144.5743962,0,14.03629709,0,133.7077483 +82.34,50.38441829,-3.380971404,10000,-138.208824,144.5572933,0,14.03629709,0,133.7147742 +82.35,50.38440588,-3.380951111,10000,-138.240158,144.540413,0,14.03629709,0,133.7218001 +82.36,50.38439347,-3.380930822,10000,-138.2575657,144.5237553,0,14.03629709,0,133.728826 +82.37,50.38438106,-3.380910534,10000,-138.2645286,144.5073202,0,14.03629709,0,133.735852 +82.38,50.38436865,-3.380890249,10000,-138.2784547,144.4904398,0,14.03629709,0,133.7428779 +82.39,50.38435624,-3.380869966,10000,-138.299344,144.4731143,0,14.03629709,0,133.7499038 +82.4,50.38434382,-3.380849686,10000,-138.3167516,144.456234,0,14.03629709,0,133.7569297 +82.41,50.38433141,-3.380829408,10000,-138.3341593,144.4397989,0,14.03629709,0,133.7639557 +82.42,50.38431899,-3.380809132,10000,-138.3550486,144.4229185,0,14.03629709,0,133.7709816 +82.43,50.38430657,-3.380788859,10000,-138.3724562,144.4053704,0,14.03629709,0,133.7780075 +82.44,50.38429415,-3.380768588,10000,-138.3898639,144.3878222,0,14.03629709,0,133.7850334 +82.45,50.38428173,-3.38074832,10000,-138.4107532,144.3709419,0,14.03629709,0,133.7920594 +82.46,50.3842693,-3.380728054,10000,-138.4281608,144.3545068,0,14.03629709,0,133.7990853 +82.47,50.38425688,-3.38070779,10000,-138.4455685,144.3376264,0,14.03629709,0,133.8061112 +82.48,50.38424445,-3.380687529,10000,-138.4664578,144.3200782,0,14.03629709,0,133.8131371 +82.49,50.38423202,-3.38066727,10000,-138.4803839,144.30253,0,14.03629709,0,133.820163 +82.5,50.38421959,-3.380647014,10000,-138.4873467,144.2856497,0,14.03629709,0,133.827189 +82.51,50.38420716,-3.38062676,10000,-138.5047544,144.2692145,0,14.03629709,0,133.8342149 +82.52,50.38419473,-3.380606508,10000,-138.53957,144.2523342,0,14.03629709,0,133.8412408 +82.53,50.38418229,-3.380586259,10000,-138.5709041,144.2350086,0,14.03629709,0,133.8482667 +82.54,50.38416985,-3.380566012,10000,-138.577867,144.2181282,0,14.03629709,0,133.8552927 +82.55,50.38415741,-3.380545768,10000,-138.5778667,144.201693,0,14.03629709,0,133.8623185 +82.56,50.38414498,-3.380525525,10000,-138.5952743,144.1850352,0,14.03629709,0,133.8693445 +82.57,50.38413253,-3.380505286,10000,-138.6161636,144.1681548,0,14.03629709,0,133.8763704 +82.58,50.38412009,-3.380485048,10000,-138.6300897,144.1510518,0,14.03629709,0,133.8833963 +82.59,50.38410765,-3.380464813,10000,-138.6544606,144.1337262,0,14.03629709,0,133.8904222 +82.6,50.3840952,-3.380444581,10000,-138.6857946,144.1166232,0,14.03629709,0,133.8974482 +82.61,50.38408275,-3.38042435,10000,-138.7032023,144.0995202,0,14.03629709,0,133.9044741 +82.62,50.3840703,-3.380404123,10000,-138.7101651,144.081972,0,14.03629709,0,133.9115 +82.63,50.38405785,-3.380383897,10000,-138.7240912,144.0644237,0,14.03629709,0,133.9185259 +82.64,50.3840454,-3.380363675,10000,-138.7449805,144.0475433,0,14.03629709,0,133.9255519 +82.65,50.38403294,-3.380343454,10000,-138.7623882,144.0313307,0,14.03629709,0,133.9325778 +82.66,50.38402049,-3.380323236,10000,-138.7797958,144.0151181,0,14.03629709,0,133.9396037 +82.67,50.38400803,-3.38030302,10000,-138.8006851,143.9980151,0,14.03629709,0,133.9466296 +82.68,50.38399557,-3.380282806,10000,-138.8146112,143.9800216,0,14.03629709,0,133.9536556 +82.69,50.38398311,-3.380262596,10000,-138.8215741,143.9624733,0,14.03629709,0,133.9606815 +82.7,50.38397065,-3.380242387,10000,-138.8389817,143.9458155,0,14.03629709,0,133.9677074 +82.71,50.38395819,-3.380222181,10000,-138.8703158,143.928935,0,14.03629709,0,133.9747333 +82.72,50.38394572,-3.380201977,10000,-138.891205,143.9116094,0,14.03629709,0,133.9817593 +82.73,50.38393325,-3.380181776,10000,-138.8946863,143.8947289,0,14.03629709,0,133.9887852 +82.74,50.38392079,-3.380161577,10000,-138.912094,143.8782936,0,14.03629709,0,133.9958111 +82.75,50.38390832,-3.38014138,10000,-138.9469096,143.8616358,0,14.03629709,0,134.002837 +82.76,50.38389584,-3.380121186,10000,-138.9643173,143.8449779,0,14.03629709,0,134.009863 +82.77,50.38388337,-3.380100994,10000,-138.9677986,143.8283201,0,14.03629709,0,134.0168889 +82.78,50.3838709,-3.380080804,10000,-138.9886878,143.8105491,0,14.03629709,0,134.0239148 +82.79,50.38385842,-3.380060617,10000,-139.0200219,143.7918878,0,14.03629709,0,134.0309407 +82.8,50.38384594,-3.380040433,10000,-139.0374296,143.7743395,0,14.03629709,0,134.0379667 +82.81,50.38383346,-3.380020251,10000,-139.0443924,143.758572,0,14.03629709,0,134.0449926 +82.82,50.38382098,-3.380000071,10000,-139.0583185,143.7428046,0,14.03629709,0,134.0520185 +82.83,50.3838085,-3.379979893,10000,-139.0792078,143.7254789,0,14.03629709,0,134.0590444 +82.84,50.38379601,-3.379959718,10000,-139.0966155,143.7074853,0,14.03629709,0,134.0660704 +82.85,50.38378353,-3.379939546,10000,-139.1140231,143.6901596,0,14.03629709,0,134.0730963 +82.86,50.38377104,-3.379919375,10000,-139.1349124,143.6732791,0,14.03629709,0,134.0801222 +82.87,50.38375855,-3.379899208,10000,-139.15232,143.6566212,0,14.03629709,0,134.0871481 +82.88,50.38374606,-3.379879042,10000,-139.1697277,143.6401859,0,14.03629709,0,134.094174 +82.89,50.38373357,-3.379858879,10000,-139.190617,143.6233054,0,14.03629709,0,134.1011999 +82.9,50.38372107,-3.379838718,10000,-139.2080246,143.605757,0,14.03629709,0,134.1082258 +82.91,50.38370858,-3.37981856,10000,-139.2254323,143.587986,0,14.03629709,0,134.1152518 +82.92,50.38369608,-3.379798404,10000,-139.2463215,143.5702151,0,14.03629709,0,134.1222777 +82.93,50.38368358,-3.379778251,10000,-139.2602476,143.5526667,0,14.03629709,0,134.1293036 +82.94,50.38367108,-3.3797581,10000,-139.2672105,143.5360088,0,14.03629709,0,134.1363295 +82.95,50.38365858,-3.379737952,10000,-139.2811366,143.5202413,0,14.03629709,0,134.1433555 +82.96,50.38364608,-3.379717805,10000,-139.3020258,143.5038059,0,14.03629709,0,134.1503814 +82.97,50.38363357,-3.379697661,10000,-139.3194335,143.4858123,0,14.03629709,0,134.1574073 +82.98,50.38362107,-3.37967752,10000,-139.3368412,143.4675961,0,14.03629709,0,134.1644332 +82.99,50.38360856,-3.379657381,10000,-139.3577304,143.4507155,0,14.03629709,0,134.1714592 +83,50.38359605,-3.379637245,10000,-139.3751381,143.434948,0,14.03629709,0,134.1784851 +83.01,50.38358354,-3.37961711,10000,-139.3925458,143.4185126,0,14.03629709,0,134.185511 +83.02,50.38357103,-3.379596978,10000,-139.413435,143.400519,0,14.03629709,0,134.1925369 +83.03,50.38355851,-3.379576849,10000,-139.4308427,143.3823028,0,14.03629709,0,134.1995629 +83.04,50.383546,-3.379556722,10000,-139.4482504,143.3654222,0,14.03629709,0,134.2065888 +83.05,50.38353348,-3.379536598,10000,-139.4691396,143.3496546,0,14.03629709,0,134.2136147 +83.06,50.38352096,-3.379516475,10000,-139.4865473,143.3332193,0,14.03629709,0,134.2206406 +83.07,50.38350844,-3.379496355,10000,-139.5039549,143.3154482,0,14.03629709,0,134.2276666 +83.08,50.38349592,-3.379476238,10000,-139.5248442,143.2976772,0,14.03629709,0,134.2346925 +83.09,50.38348339,-3.379456123,10000,-139.5422519,143.2801287,0,14.03629709,0,134.2417184 +83.1,50.38347087,-3.37943601,10000,-139.5596595,143.2621351,0,14.03629709,0,134.2487443 +83.11,50.38345834,-3.379415901,10000,-139.5805488,143.2448093,0,14.03629709,0,134.2557703 +83.12,50.38344581,-3.379395793,10000,-139.5944748,143.2290417,0,14.03629709,0,134.2627962 +83.13,50.38343328,-3.379375688,10000,-139.6014377,143.2132741,0,14.03629709,0,134.2698221 +83.14,50.38342075,-3.379355584,10000,-139.6153638,143.1959483,0,14.03629709,0,134.276848 +83.15,50.38340822,-3.379335484,10000,-139.6362531,143.1779546,0,14.03629709,0,134.283874 +83.16,50.38339568,-3.379315386,10000,-139.6536607,143.1606287,0,14.03629709,0,134.2908999 +83.17,50.38338315,-3.37929529,10000,-139.6710684,143.1435255,0,14.03629709,0,134.2979258 +83.18,50.38337061,-3.379275197,10000,-139.6954392,143.125977,0,14.03629709,0,134.3049517 +83.19,50.38335807,-3.379255106,10000,-139.7232917,143.1084285,0,14.03629709,0,134.3119777 +83.2,50.38334553,-3.379235018,10000,-139.7476625,143.0915478,0,14.03629709,0,134.3190036 +83.21,50.38333298,-3.379214932,10000,-139.7615886,143.0751124,0,14.03629709,0,134.3260295 +83.22,50.38332044,-3.379194848,10000,-139.7650699,143.0582317,0,14.03629709,0,134.3330554 +83.23,50.38330789,-3.379174767,10000,-139.7685512,143.0409059,0,14.03629709,0,134.3400814 +83.24,50.38329535,-3.379154688,10000,-139.7824772,143.0240252,0,14.03629709,0,134.3471072 +83.25,50.3832828,-3.379134612,10000,-139.8068481,143.0073671,0,14.03629709,0,134.3541332 +83.26,50.38327025,-3.379114537,10000,-139.8347005,142.9898186,0,14.03629709,0,134.3611591 +83.27,50.3832577,-3.379094466,10000,-139.8590714,142.9720475,0,14.03629709,0,134.368185 +83.28,50.38324514,-3.379074397,10000,-139.8764791,142.9553894,0,14.03629709,0,134.3752109 +83.29,50.38323259,-3.37905433,10000,-139.8938867,142.9387313,0,14.03629709,0,134.3822368 +83.3,50.38322003,-3.379034265,10000,-139.914776,142.9209602,0,14.03629709,0,134.3892628 +83.31,50.38320747,-3.379014204,10000,-139.928702,142.9034116,0,14.03629709,0,134.3962887 +83.32,50.38319491,-3.378994144,10000,-139.9356649,142.8867535,0,14.03629709,0,134.4033146 +83.33,50.38318235,-3.378974087,10000,-139.949591,142.8696502,0,14.03629709,0,134.4103405 +83.34,50.38316979,-3.378954032,10000,-139.9704802,142.8514338,0,14.03629709,0,134.4173665 +83.35,50.38315722,-3.37893398,10000,-139.9878879,142.8334401,0,14.03629709,0,134.4243924 +83.36,50.38314466,-3.378913931,10000,-140.0052956,142.8170046,0,14.03629709,0,134.4314183 +83.37,50.38313209,-3.378893883,10000,-140.0296664,142.8012369,0,14.03629709,0,134.4384442 +83.38,50.38311952,-3.378873838,10000,-140.0575188,142.7845788,0,14.03629709,0,134.4454702 +83.39,50.38310695,-3.378853795,10000,-140.0818897,142.7670302,0,14.03629709,0,134.4524961 +83.4,50.38309437,-3.378833755,10000,-140.0958158,142.749259,0,14.03629709,0,134.459522 +83.41,50.3830818,-3.378813717,10000,-140.099297,142.7314878,0,14.03629709,0,134.4665479 +83.42,50.38306922,-3.378793682,10000,-140.1027783,142.7139392,0,14.03629709,0,134.4735739 +83.43,50.38305665,-3.378773649,10000,-140.1167044,142.6970585,0,14.03629709,0,134.4805998 +83.44,50.38304407,-3.378753619,10000,-140.1410753,142.6804003,0,14.03629709,0,134.4876257 +83.45,50.38303149,-3.37873359,10000,-140.1689277,142.6628517,0,14.03629709,0,134.4946516 +83.46,50.38301891,-3.378713565,10000,-140.1932985,142.6450805,0,14.03629709,0,134.5016776 +83.47,50.38300632,-3.378693542,10000,-140.2107062,142.628645,0,14.03629709,0,134.5087035 +83.48,50.38299374,-3.378673521,10000,-140.2281138,142.6126546,0,14.03629709,0,134.5157294 +83.49,50.38298115,-3.378653502,10000,-140.2490031,142.595106,0,14.03629709,0,134.5227553 +83.5,50.38296856,-3.378633486,10000,-140.2629292,142.5764443,0,14.03629709,0,134.5297813 +83.51,50.38295597,-3.378613473,10000,-140.269892,142.5586731,0,14.03629709,0,134.5368072 +83.52,50.38294338,-3.378593462,10000,-140.2838181,142.5422375,0,14.03629709,0,134.5438331 +83.53,50.38293079,-3.378573453,10000,-140.3047074,142.5262472,0,14.03629709,0,134.550859 +83.54,50.38291819,-3.378553447,10000,-140.322115,142.5098116,0,14.03629709,0,134.557885 +83.55,50.3829056,-3.378533442,10000,-140.3395227,142.492263,0,14.03629709,0,134.5649109 +83.56,50.382893,-3.378513441,10000,-140.3604119,142.4742691,0,14.03629709,0,134.5719368 +83.57,50.3828804,-3.378493442,10000,-140.3778196,142.4567204,0,14.03629709,0,134.5789627 +83.58,50.3828678,-3.378473445,10000,-140.3952272,142.4389492,0,14.03629709,0,134.5859887 +83.59,50.3828552,-3.378453451,10000,-140.4161165,142.4211779,0,14.03629709,0,134.5930145 +83.6,50.38284259,-3.37843346,10000,-140.4335242,142.4047423,0,14.03629709,0,134.6000405 +83.61,50.38282999,-3.37841347,10000,-140.4509318,142.3887519,0,14.03629709,0,134.6070664 +83.62,50.38281738,-3.378393483,10000,-140.4718211,142.3712032,0,14.03629709,0,134.6140923 +83.63,50.38280477,-3.378373498,10000,-140.4857471,142.3525415,0,14.03629709,0,134.6211182 +83.64,50.38279216,-3.378353517,10000,-140.49271,142.3347702,0,14.03629709,0,134.6281442 +83.65,50.38277955,-3.378333537,10000,-140.5066361,142.3183346,0,14.03629709,0,134.6351701 +83.66,50.38276694,-3.37831356,10000,-140.5275254,142.3023442,0,14.03629709,0,134.642196 +83.67,50.38275432,-3.378293585,10000,-140.544933,142.2859085,0,14.03629709,0,134.6492219 +83.68,50.38274171,-3.378273612,10000,-140.5623406,142.2681372,0,14.03629709,0,134.6562478 +83.69,50.38272909,-3.378253642,10000,-140.5867115,142.2494754,0,14.03629709,0,134.6632738 +83.7,50.38271647,-3.378233675,10000,-140.6145639,142.2317041,0,14.03629709,0,134.6702997 +83.71,50.38270385,-3.37821371,10000,-140.6389348,142.2150459,0,14.03629709,0,134.6773256 +83.72,50.38269122,-3.378193747,10000,-140.6528608,142.1983876,0,14.03629709,0,134.6843515 +83.73,50.3826786,-3.378173787,10000,-140.6563421,142.1817293,0,14.03629709,0,134.6913775 +83.74,50.38266597,-3.378153829,10000,-140.6598234,142.1650711,0,14.03629709,0,134.6984034 +83.75,50.38265335,-3.378133873,10000,-140.6772311,142.1475223,0,14.03629709,0,134.7054293 +83.76,50.38264072,-3.37811392,10000,-140.7120467,142.1295283,0,14.03629709,0,134.7124552 +83.77,50.38262809,-3.37809397,10000,-140.7468623,142.1119796,0,14.03629709,0,134.7194812 +83.78,50.38261545,-3.378074021,10000,-140.7642699,142.0942082,0,14.03629709,0,134.7265071 +83.79,50.38260282,-3.378054076,10000,-140.7677512,142.0764369,0,14.03629709,0,134.733533 +83.8,50.38259018,-3.378034133,10000,-140.7712325,142.0597786,0,14.03629709,0,134.7405589 +83.81,50.38257755,-3.378014192,10000,-140.7851586,142.0431203,0,14.03629709,0,134.7475849 +83.82,50.38256491,-3.377994253,10000,-140.8060478,142.0253489,0,14.03629709,0,134.7546108 +83.83,50.38255227,-3.377974318,10000,-140.8234555,142.0078001,0,14.03629709,0,134.7616367 +83.84,50.38253963,-3.377954384,10000,-140.8443447,141.9913644,0,14.03629709,0,134.7686626 +83.85,50.38252699,-3.377934453,10000,-140.8756788,141.9751513,0,14.03629709,0,134.7756886 +83.86,50.38251434,-3.377914524,10000,-140.896568,141.9580478,0,14.03629709,0,134.7827145 +83.87,50.38250169,-3.377894597,10000,-140.8965677,141.9400537,0,14.03629709,0,134.7897404 +83.88,50.38248905,-3.377874674,10000,-140.9035306,141.9222823,0,14.03629709,0,134.7967663 +83.89,50.3824764,-3.377854752,10000,-140.9348646,141.9047335,0,14.03629709,0,134.8037923 +83.9,50.38246375,-3.377834833,10000,-140.9696802,141.8867395,0,14.03629709,0,134.8108181 +83.91,50.38245109,-3.377814917,10000,-140.9870879,141.8691907,0,14.03629709,0,134.8178441 +83.92,50.38243844,-3.377795003,10000,-140.9905692,141.8525323,0,14.03629709,0,134.82487 +83.93,50.38242578,-3.377775091,10000,-140.9940504,141.835874,0,14.03629709,0,134.8318959 +83.94,50.38241313,-3.377755182,10000,-141.0079765,141.818993,0,14.03629709,0,134.8389218 +83.95,50.38240047,-3.377735275,10000,-141.0323474,141.8016668,0,14.03629709,0,134.8459478 +83.96,50.38238781,-3.37771537,10000,-141.0601998,141.7836727,0,14.03629709,0,134.8529737 +83.97,50.38237515,-3.377695469,10000,-141.0845706,141.7661239,0,14.03629709,0,134.8599996 +83.98,50.38236248,-3.377675569,10000,-141.1019783,141.7494655,0,14.03629709,0,134.8670255 +83.99,50.38234982,-3.377655672,10000,-141.1193859,141.7325845,0,14.03629709,0,134.8740515 +84,50.38233715,-3.377635777,10000,-141.1402752,141.7150357,0,14.03629709,0,134.8810774 +84.01,50.38232448,-3.377615885,10000,-141.1542012,141.6972642,0,14.03629709,0,134.8881033 +84.02,50.38231181,-3.377595995,10000,-141.1576825,141.6794927,0,14.03629709,0,134.8951292 +84.03,50.38229914,-3.377576108,10000,-141.1611638,141.6617212,0,14.03629709,0,134.9021552 +84.04,50.38228647,-3.377556223,10000,-141.1785714,141.6441724,0,14.03629709,0,134.9091811 +84.05,50.3822738,-3.377536341,10000,-141.213387,141.6272913,0,14.03629709,0,134.916207 +84.06,50.38226112,-3.377516461,10000,-141.2482027,141.6108555,0,14.03088184,0,134.9232322 +84.07,50.38224844,-3.377496583,10000,-141.2656103,141.5939745,0,13.99297518,0,134.9302476 +84.08,50.38223576,-3.377476708,10000,-141.2690916,141.5764256,0,13.89008565,0,134.9372276 +84.09,50.38222308,-3.377456835,10000,-141.2725729,141.5588767,0,13.68972185,0,134.9441302 +84.1,50.3822104,-3.377436965,10000,-141.286499,141.5422183,0,13.35939232,0,134.9508964 +84.11,50.38219772,-3.377417097,10000,-141.3073882,141.5268955,0,12.86660564,0,134.9574508 +84.12,50.38218503,-3.377397231,10000,-141.3247959,141.5124633,0,12.18970087,0,134.9637034 +84.13,50.38217235,-3.377377367,10000,-141.3422035,141.4984762,0,11.35033901,0,134.9695656 +84.14,50.38215966,-3.377357505,10000,-141.3630927,141.4853796,0,10.38101136,0,134.9749649 +84.15,50.38214697,-3.377337645,10000,-141.3770188,141.4733961,0,9.3142095,0,134.9798469 +84.16,50.38213428,-3.377317786,10000,-141.3805001,141.4618578,0,8.182424711,0,134.9841738 +84.17,50.38212159,-3.377297929,10000,-141.3839814,141.45121,0,7.018148516,0,134.9879246 +84.18,50.3821089,-3.377278074,10000,-141.3979074,141.4430109,0,5.853872379,0,134.9910942 +84.19,50.38209621,-3.377258219,10000,-141.4153151,141.437038,0,4.722087589,0,134.9936934 +84.2,50.38208351,-3.377238365,10000,-141.4187964,141.4321782,0,3.655285668,0,134.9957484 +84.21,50.38207082,-3.377218512,10000,-141.4153145,141.4286541,0,2.685958076,0,134.9973005 +84.22,50.38205813,-3.377198659,10000,-141.4187958,141.4262431,0,1.846596163,0,134.9984067 +84.23,50.38204543,-3.377178806,10000,-141.4187955,141.423832,0,1.169691448,0,134.9991393 +84.24,50.38203274,-3.377158954,10000,-141.4153135,141.4218662,0,0.676904772,0,134.9995849 +84.25,50.38202005,-3.377139102,10000,-141.4187948,141.4216814,0,0.346575237,0,134.99983 +84.26,50.38200735,-3.37711925,10000,-141.4187945,141.4226096,0,0.146211438,0,134.9999462 +84.27,50.38199466,-3.377099397,10000,-141.4153126,141.4226473,0,0.043321912,0,134.9999894 +84.28,50.38198197,-3.377079545,10000,-141.4187939,141.421572,0,0.005415253,0,134.9999994 +84.29,50.38196927,-3.377059693,10000,-141.4187936,141.4207192,0,0,0,135 +84.3,50.38195658,-3.377039841,10000,-141.4153117,141.4205344,0,0,0,135 +84.31,50.38194389,-3.377019989,10000,-141.4222746,141.4205721,0,0,0,135 +84.32,50.38193119,-3.377000137,10000,-141.432719,141.4208325,0,0,0,135 +84.33,50.3819185,-3.376980285,10000,-141.4327187,141.4217607,0,0,0,135 +84.34,50.3819058,-3.376960433,10000,-141.4222736,141.4226889,0,0,0,135 +84.35,50.38189311,-3.37694058,10000,-141.4153101,141.4220588,0,0,0,135 +84.36,50.38188042,-3.376920728,10000,-141.4187914,141.4207609,0,0,0,135 +84.37,50.38186772,-3.376900877,10000,-141.4187911,141.4210212,0,0,0,135 +84.38,50.38185503,-3.376881024,10000,-141.4153092,141.4219494,0,0,0,135 +84.39,50.38184234,-3.376861172,10000,-141.4222721,141.4217646,0,0,0,135 +84.4,50.38182964,-3.37684132,10000,-141.4327165,141.4211344,0,0,0,135 +84.41,50.38181695,-3.376821468,10000,-141.4327162,141.4209496,0,0,0,135 +84.42,50.38180425,-3.376801616,10000,-141.4222712,141.4209873,0,0,0,135 +84.43,50.38179156,-3.376781764,10000,-141.4153077,141.4210251,0,0,0,135 +84.44,50.38177887,-3.376761912,10000,-141.4187889,141.4210628,0,0,0,135 +84.45,50.38176617,-3.37674206,10000,-141.4187886,141.4211006,0,0,0,135 +84.46,50.38175348,-3.376722208,10000,-141.4153067,141.4211383,0,0,0,135 +84.47,50.38174079,-3.376702356,10000,-141.418788,141.421176,0,0,0,135 +84.48,50.38172809,-3.376682504,10000,-141.4187877,141.4212138,0,0,0,135 +84.49,50.3817154,-3.376662652,10000,-141.4153058,141.4212515,0,0,0,135 +84.5,50.38170271,-3.3766428,10000,-141.4222687,141.4212893,0,0,0,135 +84.51,50.38169001,-3.376622948,10000,-141.4327131,141.421327,0,0,0,135 +84.52,50.38167732,-3.376603096,10000,-141.4327128,141.4213648,0,0,0,135 +84.53,50.38166462,-3.376583244,10000,-141.4222678,141.4214025,0,0,0,135 +84.54,50.38165193,-3.376563392,10000,-141.4153043,141.4214403,0,0,0,135 +84.55,50.38163924,-3.37654354,10000,-141.4187855,141.421478,0,0,0,135 +84.56,50.38162654,-3.376523688,10000,-141.4187852,141.4215158,0,0,0,135 +84.57,50.38161385,-3.376503836,10000,-141.4153033,141.4215535,0,0,0,135 +84.58,50.38160116,-3.376483984,10000,-141.4187846,141.4215912,0,0,0,135 +84.59,50.38158846,-3.376464132,10000,-141.4187843,141.421629,0,0,0,135 +84.6,50.38157577,-3.37644428,10000,-141.4153024,141.4216667,0,0,0,135 +84.61,50.38156308,-3.376424428,10000,-141.4222653,141.4217045,0,0,0,135 +84.62,50.38155038,-3.376404576,10000,-141.4327097,141.4217422,0,0,0,135 +84.63,50.38153769,-3.376384724,10000,-141.4327094,141.42178,0,0,0,135 +84.64,50.38152499,-3.376364872,10000,-141.4222643,141.4218177,0,0,0,135 +84.65,50.3815123,-3.37634502,10000,-141.4153009,141.4218555,0,0,0,135 +84.66,50.38149961,-3.376325168,10000,-141.4187821,141.4216706,0,0,0,135 +84.67,50.38148691,-3.376305316,10000,-141.4187818,141.4208179,0,0,0,135 +84.68,50.38147422,-3.376285464,10000,-141.4152999,141.4197425,0,0,0,135 +84.69,50.38146153,-3.376265613,10000,-141.4222628,141.4197802,0,0,0,135 +84.7,50.38144883,-3.376245761,10000,-141.4327073,141.4209311,0,0,0,135 +84.71,50.38143614,-3.376225909,10000,-141.432707,141.4218593,0,0,0,135 +84.72,50.38142344,-3.376206057,10000,-141.4222619,141.4221197,0,0,0,135 +84.73,50.38141075,-3.376186205,10000,-141.4152984,141.4219348,0,0,0,135 +84.74,50.38139806,-3.376166353,10000,-141.4187796,141.4213047,0,0,0,135 +84.75,50.38138536,-3.376146501,10000,-141.4187793,141.4211198,0,0,0,135 +84.76,50.38137267,-3.37612665,10000,-141.4152974,141.422048,0,0,0,135 +84.77,50.38135998,-3.376106797,10000,-141.4187787,141.4223084,0,0,0,135 +84.78,50.38134728,-3.376086945,10000,-141.4187784,141.4210104,0,0,0,135 +84.79,50.38133459,-3.376067094,10000,-141.4152965,141.4203803,0,0,0,135 +84.8,50.3813219,-3.376047242,10000,-141.4222594,141.4213085,0,0,0,135 +84.81,50.3813092,-3.37602739,10000,-141.4327038,141.4222368,0,0,0,135 +84.82,50.38129651,-3.376007538,10000,-141.4327035,141.4224971,0,0,0,135 +84.83,50.38128381,-3.375987686,10000,-141.4222584,141.4223123,0,0,0,135 +84.84,50.38127112,-3.375967834,10000,-141.4152949,141.4214595,0,0,0,135 +84.85,50.38125843,-3.375947982,10000,-141.4187762,141.4201615,0,0,0,135 +84.86,50.38124573,-3.375928131,10000,-141.4187759,141.4193088,0,0,0,135 +84.87,50.38123304,-3.375908279,10000,-141.415294,141.4193465,0,0,0,135 +84.88,50.38122035,-3.375888428,10000,-141.4222569,141.4202748,0,0,0,135 +84.89,50.38120765,-3.375868576,10000,-141.4327014,141.4216482,0,0,0,135 +84.9,50.38119496,-3.375848724,10000,-141.4327011,141.4225765,0,0,0,135 +84.91,50.38118226,-3.375828872,10000,-141.422256,141.4228368,0,0,0,135 +84.92,50.38116957,-3.37580902,10000,-141.4152925,141.422652,0,0,0,135 +84.93,50.38115688,-3.375789168,10000,-141.4187737,141.4217992,0,0,0,135 +84.94,50.38114418,-3.375769316,10000,-141.4187734,141.4207239,0,0,0,135 +84.95,50.38113149,-3.375749465,10000,-141.4152916,141.420539,0,0,0,135 +84.96,50.3811188,-3.375729613,10000,-141.4187728,141.4207993,0,0,0,135 +84.97,50.3811061,-3.375709761,10000,-141.4187725,141.4206145,0,0,0,135 +84.98,50.38109341,-3.37568991,10000,-141.4152906,141.4208748,0,0,0,135 +84.99,50.38108072,-3.375670058,10000,-141.4222535,141.4220257,0,0,0,135 +85,50.38106802,-3.375650206,10000,-141.4326979,141.4229539,0,0,0,135 +85.01,50.38105533,-3.375630354,10000,-141.4326977,141.4229917,0,0,0,135 +85.02,50.38104263,-3.375610502,10000,-141.4222526,141.4221389,0,0,0,135 +85.03,50.38102994,-3.37559065,10000,-141.4152891,141.4208409,0,0,0,135 +85.04,50.38101725,-3.375570799,10000,-141.4187703,141.4199882,0,0,0,135 +85.05,50.38100455,-3.375550947,10000,-141.41877,141.4200259,0,0,0,135 +85.06,50.38099186,-3.375531096,10000,-141.4152881,141.4207315,0,0,0,135 +85.07,50.38097917,-3.375511244,10000,-141.4187694,141.4212145,0,0,0,135 +85.08,50.38096647,-3.375491392,10000,-141.4187691,141.4210297,0,0,0,135 +85.09,50.38095378,-3.375471541,10000,-141.4152872,141.4210674,0,0,0,135 +85.1,50.38094109,-3.375451689,10000,-141.4222501,141.4213278,0,0,0,135 +85.11,50.38092839,-3.375431837,10000,-141.4326945,141.4211429,0,0,0,135 +85.12,50.3809157,-3.375411986,10000,-141.4326942,141.4211806,0,0,0,135 +85.13,50.380903,-3.375392134,10000,-141.4222492,141.421441,0,0,0,135 +85.14,50.38089031,-3.375372282,10000,-141.4152857,141.4212561,0,0,0,135 +85.15,50.38087762,-3.375352431,10000,-141.4187669,141.4215165,0,0,0,135 +85.16,50.38086492,-3.375332579,10000,-141.4187666,141.4224447,0,0,0,135 +85.17,50.38085223,-3.375312727,10000,-141.4152847,141.4224825,0,0,0,135 +85.18,50.38083954,-3.375292875,10000,-141.4222476,141.4214071,0,0,0,135 +85.19,50.38082684,-3.375273024,10000,-141.4326921,141.4205544,0,0,0,135 +85.2,50.38081415,-3.375253172,10000,-141.4326918,141.4205921,0,0,0,135 +85.21,50.38080145,-3.375233321,10000,-141.4222467,141.4212977,0,0,0,135 +85.22,50.38078876,-3.375213469,10000,-141.4152832,141.4217807,0,0,0,135 +85.23,50.38077607,-3.375193617,10000,-141.4187645,141.4215958,0,0,0,135 +85.24,50.38076337,-3.375173766,10000,-141.4187642,141.4216336,0,0,0,135 +85.25,50.38075068,-3.375153914,10000,-141.4152823,141.4218939,0,0,0,135 +85.26,50.38073799,-3.375134062,10000,-141.4187635,141.4214864,0,0,0,135 +85.27,50.38072529,-3.375114211,10000,-141.4187632,141.4208563,0,0,0,135 +85.28,50.3807126,-3.375094359,10000,-141.4152813,141.4206714,0,0,0,135 +85.29,50.38069991,-3.375074508,10000,-141.4222442,141.4207092,0,0,0,135 +85.3,50.38068721,-3.375054656,10000,-141.4326887,141.4207469,0,0,0,135 +85.31,50.38067452,-3.375034805,10000,-141.4326884,141.4207847,0,0,0,135 +85.32,50.38066182,-3.375014953,10000,-141.4222433,141.421045,0,0,0,135 +85.33,50.38064913,-3.374995102,10000,-141.4152798,141.4217506,0,0,0,135 +85.34,50.38063644,-3.37497525,10000,-141.4187611,141.4222336,0,0,0,135 +85.35,50.38062374,-3.374955398,10000,-141.4187608,141.4220487,0,0,0,135 +85.36,50.38061105,-3.374935547,10000,-141.4152789,141.4220865,0,0,0,135 +85.37,50.38059836,-3.374915695,10000,-141.4187601,141.4223469,0,0,0,135 +85.38,50.38058566,-3.374895843,10000,-141.4187598,141.4219394,0,0,0,135 +85.39,50.38057297,-3.374875992,10000,-141.4152779,141.4213092,0,0,0,135 +85.4,50.38056028,-3.37485614,10000,-141.4222408,141.4211243,0,0,0,135 +85.41,50.38054758,-3.374836289,10000,-141.4326853,141.4211621,0,0,0,135 +85.42,50.38053489,-3.374816437,10000,-141.4326849,141.4211998,0,0,0,135 +85.43,50.38052219,-3.374796586,10000,-141.4222399,141.421015,0,0,0,135 +85.44,50.3805095,-3.374776734,10000,-141.4152764,141.4203848,0,0,0,135 +85.45,50.38049681,-3.374756883,10000,-141.4187576,141.4202,0,0,0,135 +85.46,50.38048411,-3.374737032,10000,-141.4187573,141.4213508,0,0,0,135 +85.47,50.38047142,-3.37471718,10000,-141.4152754,141.4225017,0,0,0,135 +85.48,50.38045873,-3.374697328,10000,-141.4222383,141.4223168,0,0,0,135 +85.49,50.38044603,-3.374677477,10000,-141.4326828,141.4216867,0,0,0,135 +85.5,50.38043334,-3.374657625,10000,-141.4326825,141.4215018,0,0,0,135 +85.51,50.38042064,-3.374637774,10000,-141.4222374,141.4213169,0,0,0,135 +85.52,50.38040795,-3.374617922,10000,-141.4152739,141.4206868,0,0,0,135 +85.53,50.38039526,-3.374598071,10000,-141.4187552,141.4202793,0,0,0,135 +85.54,50.38038256,-3.37457822,10000,-141.4187549,141.4207623,0,0,0,135 +85.55,50.38036987,-3.374558368,10000,-141.415273,141.4216905,0,0,0,135 +85.56,50.38035718,-3.374538517,10000,-141.4187543,141.4226187,0,0,0,135 +85.57,50.38034448,-3.374518665,10000,-141.4187539,141.4228791,0,0,0,135 +85.58,50.38033179,-3.374498813,10000,-141.415272,141.4218037,0,0,0,135 +85.59,50.3803191,-3.374478962,10000,-141.4222349,141.4207284,0,0,0,135 +85.6,50.3803064,-3.374459111,10000,-141.4326794,141.4207661,0,0,0,135 +85.61,50.38029371,-3.374439259,10000,-141.4326791,141.4208038,0,0,0,135 +85.62,50.38028101,-3.374419408,10000,-141.422234,141.4208416,0,0,0,135 +85.63,50.38026832,-3.374399557,10000,-141.4152705,141.4219925,0,0,0,135 +85.64,50.38025563,-3.374379705,10000,-141.4187517,141.4229207,0,0,0,135 +85.65,50.38024293,-3.374359853,10000,-141.4187515,141.4218453,0,0,0,135 +85.66,50.38023024,-3.374340002,10000,-141.4152696,141.4201021,0,0,0,135 +85.67,50.38021755,-3.374320151,10000,-141.4187509,141.4199172,0,0,0,135 +85.68,50.38020485,-3.3743003,10000,-141.4187505,141.421068,0,0,0,135 +85.69,50.38019216,-3.374280448,10000,-141.4152686,141.4219963,0,0,0,135 +85.7,50.38017947,-3.374260597,10000,-141.4222315,141.422034,0,0,0,135 +85.71,50.38016677,-3.374240745,10000,-141.432676,141.4214039,0,0,0,135 +85.72,50.38015408,-3.374220894,10000,-141.4326757,141.4209964,0,0,0,135 +85.73,50.38014138,-3.374201043,10000,-141.4222306,141.4212568,0,0,0,135 +85.74,50.38012869,-3.374181191,10000,-141.4152671,141.4212945,0,0,0,135 +85.75,50.380116,-3.37416134,10000,-141.4187483,141.4211096,0,0,0,135 +85.76,50.3801033,-3.374141489,10000,-141.418748,141.42137,0,0,0,135 +85.77,50.38009061,-3.374121637,10000,-141.4152662,141.4214077,0,0,0,135 +85.78,50.38007792,-3.374101786,10000,-141.422229,141.4212228,0,0,0,135 +85.79,50.38006522,-3.374081935,10000,-141.4326735,141.4214832,0,0,0,135 +85.8,50.38005253,-3.374062083,10000,-141.4326732,141.421521,0,0,0,135 +85.81,50.38003983,-3.374042232,10000,-141.4222281,141.4213361,0,0,0,135 +85.82,50.38002714,-3.374022381,10000,-141.4152646,141.4215965,0,0,0,135 +85.83,50.38001445,-3.374002529,10000,-141.4187459,141.4214116,0,0,0,135 +85.84,50.38000175,-3.373982678,10000,-141.4187456,141.4205588,0,0,0,135 +85.85,50.37998906,-3.373962827,10000,-141.4152637,141.4205965,0,0,0,135 +85.86,50.37997637,-3.373942976,10000,-141.4187449,141.4215248,0,0,0,135 +85.87,50.37996367,-3.373923124,10000,-141.4187446,141.4215625,0,0,0,135 +85.88,50.37995098,-3.373903273,10000,-141.4152627,141.4207098,0,0,0,135 +85.89,50.37993829,-3.373883422,10000,-141.4222256,141.4207475,0,0,0,135 +85.9,50.37992559,-3.373863571,10000,-141.4326701,141.4216758,0,0,0,135 +85.91,50.3799129,-3.373843719,10000,-141.4326698,141.4217135,0,0,0,135 +85.92,50.3799002,-3.373823868,10000,-141.4222247,141.4208607,0,0,0,135 +85.93,50.37988751,-3.373804017,10000,-141.4152612,141.4208985,0,0,0,135 +85.94,50.37987482,-3.373784166,10000,-141.4187425,141.4218267,0,0,0,135 +85.95,50.37986212,-3.373764314,10000,-141.4187422,141.4220871,0,0,0,135 +85.96,50.37984943,-3.373744463,10000,-141.4152603,141.4219022,0,0,0,135 +85.97,50.37983674,-3.373724612,10000,-141.4222231,141.4221626,0,0,0,135 +85.98,50.37982404,-3.37370476,10000,-141.4326676,141.4219777,0,0,0,135 +85.99,50.37981135,-3.373684909,10000,-141.4326673,141.4211249,0,0,0,135 +86,50.37979865,-3.373665058,10000,-141.4222222,141.4211627,0,0,0,135 +86.01,50.37978596,-3.373645207,10000,-141.4152587,141.4220909,0,0,0,135 +86.02,50.37977327,-3.373625355,10000,-141.41874,141.4221287,0,0,0,135 +86.03,50.37976057,-3.373605504,10000,-141.4187397,141.4210533,0,0,0,135 +86.04,50.37974788,-3.373585653,10000,-141.4152578,141.4202005,0,0,0,135 +86.05,50.37973519,-3.373565802,10000,-141.418739,141.4202383,0,0,0,135 +86.06,50.37972249,-3.373545951,10000,-141.4187387,141.4211665,0,0,0,135 +86.07,50.3797098,-3.3735261,10000,-141.4152568,141.4223174,0,0,0,135 +86.08,50.37969711,-3.373506248,10000,-141.4222197,141.4223551,0,0,0,135 +86.09,50.37968441,-3.373486397,10000,-141.4326642,141.4212797,0,0,0,135 +86.1,50.37967172,-3.373466546,10000,-141.4326639,141.420427,0,0,0,135 +86.11,50.37965902,-3.373446695,10000,-141.4222188,141.4204647,0,0,0,135 +86.12,50.37964633,-3.373426844,10000,-141.4152553,141.4211703,0,0,0,135 +86.13,50.37963364,-3.373406993,10000,-141.4187366,141.4216533,0,0,0,135 +86.14,50.37962094,-3.373387141,10000,-141.4187363,141.4214685,0,0,0,135 +86.15,50.37960825,-3.373367291,10000,-141.4152544,141.4215062,0,0,0,135 +86.16,50.37959556,-3.373347439,10000,-141.4187356,141.4217666,0,0,0,135 +86.17,50.37958286,-3.373327588,10000,-141.4187353,141.4213591,0,0,0,135 +86.18,50.37957017,-3.373307737,10000,-141.4152534,141.4207289,0,0,0,135 +86.19,50.37955748,-3.373287886,10000,-141.4222163,141.4207667,0,0,0,135 +86.2,50.37954478,-3.373268035,10000,-141.4326608,141.4214723,0,0,0,135 +86.21,50.37953209,-3.373248184,10000,-141.4326605,141.4219553,0,0,0,135 +86.22,50.37951939,-3.373228332,10000,-141.4222154,141.4217704,0,0,0,135 +86.23,50.3795067,-3.373208482,10000,-141.4152519,141.4218081,0,0,0,135 +86.24,50.37949401,-3.37318863,10000,-141.4187332,141.4220685,0,0,0,135 +86.25,50.37948131,-3.373168779,10000,-141.4187329,141.421661,0,0,0,135 +86.26,50.37946862,-3.373148928,10000,-141.415251,141.4210308,0,0,0,135 +86.27,50.37945593,-3.373129077,10000,-141.4222138,141.420846,0,0,0,135 +86.28,50.37944323,-3.373109226,10000,-141.4326583,141.4208837,0,0,0,135 +86.29,50.37943054,-3.373089375,10000,-141.432658,141.4209215,0,0,0,135 +86.3,50.37941784,-3.373069524,10000,-141.4222129,141.4209592,0,0,0,135 +86.31,50.37940515,-3.373049673,10000,-141.4152494,141.4209969,0,0,0,135 +86.32,50.37939246,-3.373029822,10000,-141.4187307,141.4210347,0,0,0,135 +86.33,50.37937976,-3.373009971,10000,-141.4187304,141.4210724,0,0,0,135 +86.34,50.37936707,-3.37299012,10000,-141.4152485,141.4211102,0,0,0,135 +86.35,50.37935438,-3.372970269,10000,-141.4187298,141.4213705,0,0,0,135 +86.36,50.37934168,-3.372950418,10000,-141.4187295,141.4220762,0,0,0,135 +86.37,50.37932899,-3.372930567,10000,-141.4152476,141.4225592,0,0,0,135 +86.38,50.3793163,-3.372910715,10000,-141.4222104,141.4221516,0,0,0,135 +86.39,50.3793036,-3.372890865,10000,-141.4326549,141.4215215,0,0,0,135 +86.4,50.37929091,-3.372871013,10000,-141.4326546,141.4213366,0,0,0,135 +86.41,50.37927821,-3.372851163,10000,-141.4222095,141.4211517,0,0,0,135 +86.42,50.37926552,-3.372831311,10000,-141.415246,141.4205216,0,0,0,135 +86.43,50.37925283,-3.372811461,10000,-141.4187273,141.4201141,0,0,0,135 +86.44,50.37924013,-3.37279161,10000,-141.418727,141.4205971,0,0,0,135 +86.45,50.37922744,-3.372771759,10000,-141.4152451,141.4213027,0,0,0,135 +86.46,50.37921475,-3.372751908,10000,-141.4187263,141.4215631,0,0,0,135 +86.47,50.37920205,-3.372732057,10000,-141.418726,141.4216008,0,0,0,135 +86.48,50.37918936,-3.372712206,10000,-141.4152442,141.4216385,0,0,0,135 +86.49,50.37917667,-3.372692355,10000,-141.422207,141.4216763,0,0,0,135 +86.5,50.37916397,-3.372672504,10000,-141.4326515,141.421714,0,0,0,135 +86.51,50.37915128,-3.372652653,10000,-141.4326512,141.4217518,0,0,0,135 +86.52,50.37913858,-3.372632802,10000,-141.4222061,141.4217895,0,0,0,135 +86.53,50.37912589,-3.372612951,10000,-141.4152426,141.4218273,0,0,0,135 +86.54,50.3791132,-3.3725931,10000,-141.4187239,141.4216424,0,0,0,135 +86.55,50.3791005,-3.372573249,10000,-141.4187236,141.4210122,0,0,0,135 +86.56,50.37908781,-3.372553398,10000,-141.4152417,141.4206047,0,0,0,135 +86.57,50.37907512,-3.372533548,10000,-141.4222045,141.4210877,0,0,0,135 +86.58,50.37906242,-3.372513696,10000,-141.432649,141.4217933,0,0,0,135 +86.59,50.37904973,-3.372493846,10000,-141.4326487,141.4218311,0,0,0,135 +86.6,50.37903703,-3.372473994,10000,-141.4222036,141.4212009,0,0,0,135 +86.61,50.37902434,-3.372454144,10000,-141.4152401,141.4207934,0,0,0,135 +86.62,50.37901165,-3.372434293,10000,-141.4187214,141.4212764,0,0,0,135 +86.63,50.37899895,-3.372414442,10000,-141.4187211,141.421982,0,0,0,135 +86.64,50.37898626,-3.372394591,10000,-141.4152392,141.4222424,0,0,0,135 +86.65,50.37897357,-3.37237474,10000,-141.422202,141.4220575,0,0,0,135 +86.66,50.37896087,-3.372354889,10000,-141.4326465,141.4212047,0,0,0,135 +86.67,50.37894818,-3.372335038,10000,-141.4326462,141.4201293,0,0,0,135 +86.68,50.37893548,-3.372315188,10000,-141.4222012,141.4201671,0,0,0,135 +86.69,50.37892279,-3.372295337,10000,-141.4152377,141.421318,0,0,0,135 +86.7,50.3789101,-3.372275486,10000,-141.4187189,141.4220236,0,0,0,135 +86.71,50.3788974,-3.372255635,10000,-141.4187186,141.4216161,0,0,0,135 +86.72,50.37888471,-3.372235784,10000,-141.4152367,141.4212086,0,0,0,135 +86.73,50.37887202,-3.372215934,10000,-141.418718,141.4214689,0,0,0,135 +86.74,50.37885932,-3.372196082,10000,-141.4187177,141.4215067,0,0,0,135 +86.75,50.37884663,-3.372176232,10000,-141.4152358,141.4210992,0,0,0,135 +86.76,50.37883394,-3.372156381,10000,-141.4221986,141.4209143,0,0,0,135 +86.77,50.37882124,-3.37213653,10000,-141.4326431,141.4211746,0,0,0,135 +86.78,50.37880855,-3.37211668,10000,-141.4326428,141.4216576,0,0,0,135 +86.79,50.37879585,-3.372096828,10000,-141.4221977,141.4216954,0,0,0,135 +86.8,50.37878316,-3.372076978,10000,-141.4152342,141.4212879,0,0,0,135 +86.81,50.37877047,-3.372057127,10000,-141.4187155,141.4208803,0,0,0,135 +86.82,50.37875777,-3.372037276,10000,-141.4187152,141.4204728,0,0,0,135 +86.83,50.37874508,-3.372017426,10000,-141.4152333,141.4207332,0,0,0,135 +86.84,50.37873239,-3.371997575,10000,-141.4187146,141.4218841,0,0,0,135 +86.85,50.37871969,-3.371977724,10000,-141.4187143,141.4228124,0,0,0,135 +86.86,50.378707,-3.371957873,10000,-141.4152324,141.4228501,0,0,0,135 +86.87,50.37869431,-3.371938022,10000,-141.4221952,141.4219973,0,0,0,135 +86.88,50.37868161,-3.371918171,10000,-141.4326397,141.4209219,0,0,0,135 +86.89,50.37866892,-3.371898321,10000,-141.4326394,141.420737,0,0,0,135 +86.9,50.37865622,-3.37187847,10000,-141.4221943,141.4209974,0,0,0,135 +86.91,50.37864353,-3.371858619,10000,-141.4152308,141.4208125,0,0,0,135 +86.92,50.37863084,-3.371838769,10000,-141.4187121,141.4208502,0,0,0,135 +86.93,50.37861814,-3.371818918,10000,-141.4187118,141.4211106,0,0,0,135 +86.94,50.37860545,-3.371799067,10000,-141.4152299,141.4209257,0,0,0,135 +86.95,50.37859276,-3.371779217,10000,-141.4221928,141.4209634,0,0,0,135 +86.96,50.37858006,-3.371759366,10000,-141.4326372,141.4212238,0,0,0,135 +86.97,50.37856737,-3.371739515,10000,-141.4326369,141.4210389,0,0,0,135 +86.98,50.37855467,-3.371719665,10000,-141.4221918,141.4212993,0,0,0,135 +86.99,50.37854198,-3.371699814,10000,-141.4152283,141.4222276,0,0,0,135 +87,50.37852929,-3.371679963,10000,-141.4187096,141.4222653,0,0,0,135 +87.01,50.37851659,-3.371660112,10000,-141.4187093,141.4214125,0,0,0,135 +87.02,50.3785039,-3.371640262,10000,-141.4152274,141.4212276,0,0,0,135 +87.03,50.37849121,-3.371620411,10000,-141.4187087,141.421488,0,0,0,135 +87.04,50.37847851,-3.37160056,10000,-141.4187084,141.4213031,0,0,0,135 +87.05,50.37846582,-3.37158071,10000,-141.4152265,141.4213409,0,0,0,135 +87.06,50.37845313,-3.371560859,10000,-141.4221894,141.4216012,0,0,0,135 +87.07,50.37844043,-3.371541008,10000,-141.4326338,141.4214163,0,0,0,135 +87.08,50.37842774,-3.371521158,10000,-141.4326335,141.4214541,0,0,0,135 +87.09,50.37841504,-3.371501307,10000,-141.4221884,141.4217145,0,0,0,135 +87.1,50.37840235,-3.371481456,10000,-141.4152249,141.4213069,0,0,0,135 +87.11,50.37838966,-3.371461606,10000,-141.4187062,141.4206768,0,0,0,135 +87.12,50.37837696,-3.371441755,10000,-141.4187059,141.4207145,0,0,0,135 +87.13,50.37836427,-3.371421905,10000,-141.415224,141.4214202,0,0,0,135 +87.14,50.37835158,-3.371402054,10000,-141.4187053,141.4219032,0,0,0,135 +87.15,50.37833888,-3.371382203,10000,-141.418705,141.4214956,0,0,0,135 +87.16,50.37832619,-3.371362353,10000,-141.4152231,141.4208655,0,0,0,135 +87.17,50.3783135,-3.371342502,10000,-141.4221859,141.4209032,0,0,0,135 +87.18,50.3783008,-3.371322652,10000,-141.4326304,141.4216089,0,0,0,135 +87.19,50.37828811,-3.371302801,10000,-141.4326301,141.4220919,0,0,0,135 +87.2,50.37827541,-3.37128295,10000,-141.422185,141.4216843,0,0,0,135 +87.21,50.37826272,-3.3712631,10000,-141.4152215,141.4210542,0,0,0,135 +87.22,50.37825003,-3.371243249,10000,-141.4187028,141.4210919,0,0,0,135 +87.23,50.37823733,-3.371223399,10000,-141.4187025,141.4217976,0,0,0,135 +87.24,50.37822464,-3.371203548,10000,-141.4152206,141.4220579,0,0,0,135 +87.25,50.37821195,-3.371183697,10000,-141.4221835,141.4209825,0,0,0,135 +87.26,50.37819925,-3.371163847,10000,-141.4326279,141.4201297,0,0,0,135 +87.27,50.37818656,-3.371143997,10000,-141.4326276,141.421058,0,0,0,135 +87.28,50.37817386,-3.371124146,10000,-141.4221826,141.4222089,0,0,0,135 +87.29,50.37816117,-3.371104295,10000,-141.415219,141.422024,0,0,0,135 +87.3,50.37814848,-3.371084445,10000,-141.4187003,141.4213938,0,0,0,135 +87.31,50.37813578,-3.371064594,10000,-141.4187,141.4212089,0,0,0,135 +87.32,50.37812309,-3.371044744,10000,-141.4152181,141.4212467,0,0,0,135 +87.33,50.3781104,-3.371024893,10000,-141.4186994,141.4212844,0,0,0,135 +87.34,50.3780977,-3.371005043,10000,-141.4186991,141.4213222,0,0,0,135 +87.35,50.37808501,-3.370985192,10000,-141.4152172,141.4213599,0,0,0,135 +87.36,50.37807232,-3.370965342,10000,-141.4221801,141.421175,0,0,0,135 +87.37,50.37805962,-3.370945491,10000,-141.4326245,141.4205448,0,0,0,135 +87.38,50.37804693,-3.370925641,10000,-141.4326242,141.42036,0,0,0,135 +87.39,50.37803423,-3.370905791,10000,-141.4221791,141.4215109,0,0,0,135 +87.4,50.37802154,-3.37088594,10000,-141.4152156,141.4226618,0,0,0,135 +87.41,50.37800885,-3.370866089,10000,-141.4186969,141.4224769,0,0,0,135 +87.42,50.37799615,-3.370846239,10000,-141.4186966,141.4216241,0,0,0,135 +87.43,50.37798346,-3.370826388,10000,-141.4152147,141.4207713,0,0,0,135 +87.44,50.37797077,-3.370806538,10000,-141.4221776,141.4203638,0,0,0,135 +87.45,50.37795807,-3.370786688,10000,-141.432622,141.4208468,0,0,0,135 +87.46,50.37794538,-3.370766837,10000,-141.4326217,141.4215524,0,0,0,135 +87.47,50.37793268,-3.370746987,10000,-141.4221766,141.4218128,0,0,0,135 +87.48,50.37791999,-3.370727136,10000,-141.4152132,141.4218505,0,0,0,135 +87.49,50.3779073,-3.370707286,10000,-141.4186945,141.4218883,0,0,0,135 +87.5,50.3778946,-3.370687435,10000,-141.4186941,141.421926,0,0,0,135 +87.51,50.37788191,-3.370667585,10000,-141.4152122,141.4217411,0,0,0,135 +87.52,50.37786922,-3.370647734,10000,-141.4186935,141.4211109,0,0,0,135 +87.53,50.37785652,-3.370627884,10000,-141.4186932,141.4207034,0,0,0,135 +87.54,50.37784383,-3.370608034,10000,-141.4152113,141.4209638,0,0,0,135 +87.55,50.37783114,-3.370588183,10000,-141.4221742,141.4210015,0,0,0,135 +87.56,50.37781844,-3.370568333,10000,-141.4326186,141.4208166,0,0,0,135 +87.57,50.37780575,-3.370548483,10000,-141.4326183,141.421077,0,0,0,135 +87.58,50.37779305,-3.370528632,10000,-141.4221732,141.4211148,0,0,0,135 +87.59,50.37778036,-3.370508782,10000,-141.4152098,141.4209299,0,0,0,135 +87.6,50.37776767,-3.370488932,10000,-141.418691,141.4214129,0,0,0,135 +87.61,50.37775497,-3.370469081,10000,-141.4186907,141.4221185,0,0,0,135 +87.62,50.37774228,-3.370449231,10000,-141.4152088,141.4221563,0,0,0,135 +87.63,50.37772959,-3.37042938,10000,-141.4221717,141.4215261,0,0,0,135 +87.64,50.37771689,-3.37040953,10000,-141.4326162,141.4211186,0,0,0,135 +87.65,50.3777042,-3.37038968,10000,-141.4326158,141.4216016,0,0,0,135 +87.66,50.3776915,-3.370369829,10000,-141.4221708,141.4223072,0,0,0,135 +87.67,50.37767881,-3.370349979,10000,-141.4152073,141.422345,0,0,0,135 +87.68,50.37766612,-3.370330128,10000,-141.4186886,141.4217148,0,0,0,135 +87.69,50.37765342,-3.370310278,10000,-141.4186882,141.4213073,0,0,0,135 +87.7,50.37764073,-3.370290428,10000,-141.4152063,141.4215676,0,0,0,135 +87.71,50.37762804,-3.370270577,10000,-141.4186876,141.4213827,0,0,0,135 +87.72,50.37761534,-3.370250727,10000,-141.4186873,141.4205299,0,0,0,135 +87.73,50.37760265,-3.370230877,10000,-141.4152054,141.4205677,0,0,0,135 +87.74,50.37758996,-3.370211027,10000,-141.4221683,141.421496,0,0,0,135 +87.75,50.37757726,-3.370191176,10000,-141.4326128,141.4217563,0,0,0,135 +87.76,50.37756457,-3.370171326,10000,-141.4326124,141.4215714,0,0,0,135 +87.77,50.37755187,-3.370151476,10000,-141.4221673,141.4218318,0,0,0,135 +87.78,50.37753918,-3.370131625,10000,-141.4152039,141.4216469,0,0,0,135 +87.79,50.37752649,-3.370111775,10000,-141.4186851,141.4207941,0,0,0,135 +87.8,50.37751379,-3.370091925,10000,-141.4186848,141.4208318,0,0,0,135 +87.81,50.3775011,-3.370072075,10000,-141.4152029,141.4217601,0,0,0,135 +87.82,50.37748841,-3.370052224,10000,-141.4221658,141.4217979,0,0,0,135 +87.83,50.37747571,-3.370032374,10000,-141.4326103,141.4207224,0,0,0,135 +87.84,50.37746302,-3.370012524,10000,-141.43261,141.4200923,0,0,0,135 +87.85,50.37745032,-3.369992674,10000,-141.4221649,141.4207979,0,0,0,135 +87.86,50.37743763,-3.369972824,10000,-141.4152014,141.4219488,0,0,0,135 +87.87,50.37742494,-3.369952973,10000,-141.4186827,141.4219866,0,0,0,135 +87.88,50.37741224,-3.369933123,10000,-141.4186823,141.4209111,0,0,0,135 +87.89,50.37739955,-3.369913273,10000,-141.4152004,141.4200583,0,0,0,135 +87.9,50.37738686,-3.369893423,10000,-141.4186817,141.420096,0,0,0,135 +87.91,50.37737416,-3.369873573,10000,-141.4186815,141.4210243,0,0,0,135 +87.92,50.37736147,-3.369853723,10000,-141.4151996,141.4221753,0,0,0,135 +87.93,50.37734878,-3.369833872,10000,-141.4221624,141.422213,0,0,0,135 +87.94,50.37733608,-3.369814022,10000,-141.4326068,141.4213602,0,0,0,135 +87.95,50.37732339,-3.369794172,10000,-141.4326065,141.4213979,0,0,0,135 +87.96,50.37731069,-3.369774322,10000,-141.4221615,141.4223262,0,0,0,135 +87.97,50.377298,-3.369754471,10000,-141.415198,141.422364,0,0,0,135 +87.98,50.37728531,-3.369734621,10000,-141.4186793,141.4212885,0,0,0,135 +87.99,50.37727261,-3.369714771,10000,-141.418679,141.4204357,0,0,0,135 +88,50.37725992,-3.369694921,10000,-141.415197,141.4202508,0,0,0,135 +88.01,50.37724723,-3.369675071,10000,-141.4186783,141.4202885,0,0,0,135 +88.02,50.37723453,-3.369655221,10000,-141.418678,141.4205489,0,0,0,135 +88.03,50.37722184,-3.369635371,10000,-141.4151961,141.4214772,0,0,0,135 +88.04,50.37720915,-3.369615521,10000,-141.422159,141.4226281,0,0,0,135 +88.05,50.37719645,-3.36959567,10000,-141.4326034,141.4226659,0,0,0,135 +88.06,50.37718376,-3.36957582,10000,-141.4326031,141.4215904,0,0,0,135 +88.07,50.37717106,-3.36955597,10000,-141.4221581,141.4207376,0,0,0,135 +88.08,50.37715837,-3.36953612,10000,-141.4151946,141.4205527,0,0,0,135 +88.09,50.37714568,-3.36951627,10000,-141.4186759,141.4205904,0,0,0,135 +88.1,50.37713298,-3.36949642,10000,-141.4186755,141.4208508,0,0,0,135 +88.11,50.37712029,-3.36947657,10000,-141.4151936,141.4217791,0,0,0,135 +88.12,50.3771076,-3.36945672,10000,-141.4221565,141.4229301,0,0,0,135 +88.13,50.3770949,-3.369436869,10000,-141.432601,141.4229678,0,0,0,135 +88.14,50.37708221,-3.369417019,10000,-141.4326007,141.4218923,0,0,0,135 +88.15,50.37706951,-3.369397169,10000,-141.4221556,141.4210395,0,0,0,135 +88.16,50.37705682,-3.369377319,10000,-141.4151921,141.4208546,0,0,0,135 +88.17,50.37704413,-3.369357469,10000,-141.4186734,141.4208924,0,0,0,135 +88.18,50.37703143,-3.369337619,10000,-141.4186731,141.4209301,0,0,0,135 +88.19,50.37701874,-3.369317769,10000,-141.4151912,141.4209678,0,0,0,135 +88.2,50.37700605,-3.369297919,10000,-141.422154,141.4210056,0,0,0,135 +88.21,50.37699335,-3.369278069,10000,-141.4325985,141.4210433,0,0,0,135 +88.22,50.37698066,-3.369258219,10000,-141.4325982,141.4210811,0,0,0,135 +88.23,50.37696796,-3.369238369,10000,-141.4221531,141.4211188,0,0,0,135 +88.24,50.37695527,-3.369218519,10000,-141.4151896,141.4211565,0,0,0,135 +88.25,50.37694258,-3.369198669,10000,-141.4186709,141.4211943,0,0,0,135 +88.26,50.37692988,-3.369178819,10000,-141.4186706,141.421232,0,0,0,135 +88.27,50.37691719,-3.369158969,10000,-141.4151887,141.4212697,0,0,0,135 +88.28,50.3769045,-3.369139119,10000,-141.41867,141.4213075,0,0,0,135 +88.29,50.3768918,-3.369119269,10000,-141.4186697,141.4213452,0,0,0,135 +88.3,50.37687911,-3.369099419,10000,-141.4151878,141.421383,0,0,0,135 +88.31,50.37686642,-3.369079569,10000,-141.4221506,141.4214207,0,0,0,135 +88.32,50.37685372,-3.369059719,10000,-141.4325951,141.4214584,0,0,0,135 +88.33,50.37684103,-3.369039869,10000,-141.4325948,141.4214962,0,0,0,135 +88.34,50.37682833,-3.369020019,10000,-141.4221497,141.4215339,0,0,0,135 +88.35,50.37681564,-3.369000169,10000,-141.4151862,141.4215717,0,0,0,135 +88.36,50.37680295,-3.368980319,10000,-141.4186675,141.4216094,0,0,0,135 +88.37,50.37679025,-3.368960469,10000,-141.4186672,141.4216471,0,0,0,135 +88.38,50.37677756,-3.368940619,10000,-141.4151853,141.4216849,0,0,0,135 +88.39,50.37676487,-3.368920769,10000,-141.4186666,141.4217226,0,0,0,135 +88.4,50.37675217,-3.368900919,10000,-141.4186663,141.4217604,0,0,0,135 +88.41,50.37673948,-3.368881069,10000,-141.4151843,141.4217981,0,0,0,135 +88.42,50.37672679,-3.368861219,10000,-141.4221472,141.4216132,0,0,0,135 +88.43,50.37671409,-3.368841369,10000,-141.4325917,141.420983,0,0,0,135 +88.44,50.3767014,-3.368821519,10000,-141.4325914,141.4207981,0,0,0,135 +88.45,50.3766887,-3.36880167,10000,-141.4221463,141.4217264,0,0,0,135 +88.46,50.37667601,-3.368781819,10000,-141.4151828,141.4219868,0,0,0,135 +88.47,50.37666332,-3.368761969,10000,-141.4186641,141.4206887,0,0,0,135 +88.48,50.37665062,-3.36874212,10000,-141.4186638,141.4200585,0,0,0,135 +88.49,50.37663793,-3.36872227,10000,-141.4151819,141.4209868,0,0,0,135 +88.5,50.37662524,-3.36870242,10000,-141.4221447,141.4219151,0,0,0,135 +88.51,50.37661254,-3.36868257,10000,-141.4325892,141.4221755,0,0,0,135 +88.52,50.37659985,-3.36866272,10000,-141.4325889,141.4219906,0,0,0,135 +88.53,50.37658715,-3.36864287,10000,-141.4221438,141.4213604,0,0,0,135 +88.54,50.37657446,-3.36862302,10000,-141.4151803,141.4209528,0,0,0,135 +88.55,50.37656177,-3.368603171,10000,-141.4186616,141.4212132,0,0,0,135 +88.56,50.37654907,-3.36858332,10000,-141.4186613,141.421251,0,0,0,135 +88.57,50.37653638,-3.368563471,10000,-141.4151794,141.4210661,0,0,0,135 +88.58,50.37652369,-3.368543621,10000,-141.4186607,141.4213264,0,0,0,135 +88.59,50.37651099,-3.368523771,10000,-141.4186603,141.4213642,0,0,0,135 +88.6,50.3764983,-3.368503921,10000,-141.4151785,141.4211793,0,0,0,135 +88.61,50.37648561,-3.368484072,10000,-141.4221413,141.4214396,0,0,0,135 +88.62,50.37647291,-3.368464221,10000,-141.4325858,141.4214774,0,0,0,135 +88.63,50.37646022,-3.368444372,10000,-141.4325855,141.4212925,0,0,0,135 +88.64,50.37644752,-3.368424522,10000,-141.4221404,141.4215529,0,0,0,135 +88.65,50.37643483,-3.368404672,10000,-141.4151769,141.4215906,0,0,0,135 +88.66,50.37642214,-3.368384822,10000,-141.4186582,141.4214057,0,0,0,135 +88.67,50.37640944,-3.368364973,10000,-141.4186579,141.4216661,0,0,0,135 +88.68,50.37639675,-3.368345122,10000,-141.415176,141.4217038,0,0,0,135 +88.69,50.37638406,-3.368325273,10000,-141.4186573,141.4212963,0,0,0,135 +88.7,50.37637136,-3.368305423,10000,-141.4186569,141.4208887,0,0,0,135 +88.71,50.37635867,-3.368285573,10000,-141.415175,141.4204812,0,0,0,135 +88.72,50.37634598,-3.368265724,10000,-141.4221379,141.4207416,0,0,0,135 +88.73,50.37633328,-3.368245874,10000,-141.4325824,141.4218925,0,0,0,135 +88.74,50.37632059,-3.368226024,10000,-141.4325821,141.4225982,0,0,0,135 +88.75,50.37630789,-3.368206174,10000,-141.422137,141.421968,0,0,0,135 +88.76,50.3762952,-3.368186324,10000,-141.4151735,141.4208925,0,0,0,135 +88.77,50.37628251,-3.368166475,10000,-141.4186548,141.4207076,0,0,0,135 +88.78,50.37626981,-3.368146625,10000,-141.4186545,141.420968,0,0,0,135 +88.79,50.37625712,-3.368126775,10000,-141.4151726,141.4207831,0,0,0,135 +88.8,50.37624443,-3.368106926,10000,-141.4221354,141.4210435,0,0,0,135 +88.81,50.37623173,-3.368087076,10000,-141.4325799,141.4219718,0,0,0,135 +88.82,50.37621904,-3.368067226,10000,-141.4325796,141.4220095,0,0,0,135 +88.83,50.37620634,-3.368047376,10000,-141.4221345,141.4211567,0,0,0,135 +88.84,50.37619365,-3.368027527,10000,-141.415171,141.4209718,0,0,0,135 +88.85,50.37618096,-3.368007677,10000,-141.4186523,141.4212321,0,0,0,135 +88.86,50.37616826,-3.367987827,10000,-141.418652,141.4210472,0,0,0,135 +88.87,50.37615557,-3.367967978,10000,-141.4151701,141.4213076,0,0,0,135 +88.88,50.37614288,-3.367948128,10000,-141.422133,141.4222359,0,0,0,135 +88.89,50.37613018,-3.367928278,10000,-141.4325774,141.4222737,0,0,0,135 +88.9,50.37611749,-3.367908428,10000,-141.4325771,141.4211982,0,0,0,135 +88.91,50.37610479,-3.367888579,10000,-141.422132,141.4203454,0,0,0,135 +88.92,50.3760921,-3.367868729,10000,-141.4151685,141.4203831,0,0,0,135 +88.93,50.37607941,-3.36784888,10000,-141.4186498,141.4213114,0,0,0,135 +88.94,50.37606671,-3.36782903,10000,-141.4186495,141.4224624,0,0,0,135 +88.95,50.37605402,-3.36780918,10000,-141.4151676,141.4225001,0,0,0,135 +88.96,50.37604133,-3.36778933,10000,-141.4186489,141.4214246,0,0,0,135 +88.97,50.37602863,-3.367769481,10000,-141.4186486,141.4205718,0,0,0,135 +88.98,50.37601594,-3.367749631,10000,-141.4151667,141.4206095,0,0,0,135 +88.99,50.37600325,-3.367729782,10000,-141.4221296,141.4213152,0,0,0,135 +89,50.37599055,-3.367709932,10000,-141.432574,141.4217982,0,0,0,135 +89.01,50.37597786,-3.367690082,10000,-141.4325737,141.4216133,0,0,0,135 +89.02,50.37596516,-3.367670233,10000,-141.4221286,141.421651,0,0,0,135 +89.03,50.37595247,-3.367650383,10000,-141.4151651,141.4219114,0,0,0,135 +89.04,50.37593978,-3.367630533,10000,-141.4186464,141.4215039,0,0,0,135 +89.05,50.37592708,-3.367610684,10000,-141.4186461,141.4208737,0,0,0,135 +89.06,50.37591439,-3.367590834,10000,-141.4151642,141.4206888,0,0,0,135 +89.07,50.3759017,-3.367570985,10000,-141.4186455,141.4207265,0,0,0,135 +89.08,50.375889,-3.367551135,10000,-141.4186452,141.4207642,0,0,0,135 +89.09,50.37587631,-3.367531286,10000,-141.4151633,141.420802,0,0,0,135 +89.1,50.37586362,-3.367511436,10000,-141.4221262,141.4208397,0,0,0,135 +89.11,50.37585092,-3.367491587,10000,-141.4325706,141.4208775,0,0,0,135 +89.12,50.37583823,-3.367471737,10000,-141.4325703,141.4211378,0,0,0,135 +89.13,50.37582553,-3.367451888,10000,-141.4221252,141.4218435,0,0,0,135 +89.14,50.37581284,-3.367432038,10000,-141.4151617,141.4223265,0,0,0,135 +89.15,50.37580015,-3.367412188,10000,-141.418643,141.421919,0,0,0,135 +89.16,50.37578745,-3.367392339,10000,-141.4186427,141.4212888,0,0,0,135 +89.17,50.37577476,-3.367372489,10000,-141.4151608,141.4211039,0,0,0,135 +89.18,50.37576207,-3.36735264,10000,-141.4221237,141.4211416,0,0,0,135 +89.19,50.37574937,-3.36733279,10000,-141.4325681,141.4211794,0,0,0,135 +89.2,50.37573668,-3.367312941,10000,-141.4325678,141.4212171,0,0,0,135 +89.21,50.37572398,-3.367293091,10000,-141.4221228,141.4214775,0,0,0,135 +89.22,50.37571129,-3.367273242,10000,-141.4151593,141.4221832,0,0,0,135 +89.23,50.3756986,-3.367253392,10000,-141.4186405,141.4226662,0,0,0,135 +89.24,50.3756859,-3.367233542,10000,-141.4186402,141.4222586,0,0,0,135 +89.25,50.37567321,-3.367213693,10000,-141.4151583,141.4216284,0,0,0,135 +89.26,50.37566052,-3.367193843,10000,-141.4221212,141.4214435,0,0,0,135 +89.27,50.37564782,-3.367173994,10000,-141.4325657,141.4212586,0,0,0,135 +89.28,50.37563513,-3.367154144,10000,-141.4325653,141.4206284,0,0,0,135 +89.29,50.37562243,-3.367134295,10000,-141.4221203,141.4202209,0,0,0,135 +89.3,50.37560974,-3.367114446,10000,-141.4151568,141.4207039,0,0,0,135 +89.31,50.37559705,-3.367094596,10000,-141.4186381,141.4214096,0,0,0,135 +89.32,50.37558435,-3.367074747,10000,-141.4186378,141.4214473,0,0,0,135 +89.33,50.37557166,-3.367054897,10000,-141.4151559,141.4208171,0,0,0,135 +89.34,50.37555897,-3.367035048,10000,-141.4186371,141.4206322,0,0,0,135 +89.35,50.37554627,-3.367015199,10000,-141.4186368,141.4217831,0,0,0,135 +89.36,50.37553358,-3.366995349,10000,-141.4151549,141.4229341,0,0,0,135 +89.37,50.37552089,-3.366975499,10000,-141.4221178,141.4227492,0,0,0,135 +89.38,50.37550819,-3.36695565,10000,-141.4325622,141.4218964,0,0,0,135 +89.39,50.3754955,-3.3669358,10000,-141.4325619,141.4210435,0,0,0,135 +89.4,50.3754828,-3.366915951,10000,-141.4221169,141.420636,0,0,0,135 +89.41,50.37547011,-3.366896102,10000,-141.4151534,141.4208963,0,0,0,135 +89.42,50.37545742,-3.366876252,10000,-141.4186346,141.4209341,0,0,0,135 +89.43,50.37544472,-3.366856403,10000,-141.4186343,141.4207492,0,0,0,135 +89.44,50.37543203,-3.366836554,10000,-141.4151524,141.4212322,0,0,0,135 +89.45,50.37541934,-3.366816704,10000,-141.4186337,141.4219379,0,0,0,135 +89.46,50.37540664,-3.366796855,10000,-141.4186334,141.4219756,0,0,0,135 +89.47,50.37539395,-3.366777005,10000,-141.4151515,141.4213454,0,0,0,135 +89.48,50.37538126,-3.366757156,10000,-141.4221144,141.4209378,0,0,0,135 +89.49,50.37536856,-3.366737307,10000,-141.4325588,141.4211982,0,0,0,135 +89.5,50.37535587,-3.366717457,10000,-141.4325585,141.421236,0,0,0,135 +89.51,50.37534317,-3.366697608,10000,-141.4221135,141.4210511,0,0,0,135 +89.52,50.37533048,-3.366677759,10000,-141.41515,141.4215341,0,0,0,135 +89.53,50.37531779,-3.366657909,10000,-141.4186312,141.4222398,0,0,0,135 +89.54,50.37530509,-3.36663806,10000,-141.4186309,141.4222775,0,0,0,135 +89.55,50.3752924,-3.36661821,10000,-141.415149,141.4216473,0,0,0,135 +89.56,50.37527971,-3.366598361,10000,-141.4221119,141.4212397,0,0,0,135 +89.57,50.37526701,-3.366578512,10000,-141.4325564,141.4215001,0,0,0,135 +89.58,50.37525432,-3.366558662,10000,-141.4325561,141.4213152,0,0,0,135 +89.59,50.37524162,-3.366538813,10000,-141.422111,141.4204624,0,0,0,135 +89.6,50.37522893,-3.366518964,10000,-141.4151475,141.4205001,0,0,0,135 +89.61,50.37521624,-3.366499115,10000,-141.4186287,141.4214284,0,0,0,135 +89.62,50.37520354,-3.366479265,10000,-141.4186284,141.4216888,0,0,0,135 +89.63,50.37519085,-3.366459416,10000,-141.4151466,141.4215039,0,0,0,135 +89.64,50.37517816,-3.366439567,10000,-141.4186278,141.4217643,0,0,0,135 +89.65,50.37516546,-3.366419717,10000,-141.4186275,141.4215794,0,0,0,135 +89.66,50.37515277,-3.366399868,10000,-141.4151456,141.4207265,0,0,0,135 +89.67,50.37514008,-3.366380019,10000,-141.4221085,141.4207642,0,0,0,135 +89.68,50.37512738,-3.36636017,10000,-141.432553,141.4216926,0,0,0,135 +89.69,50.37511469,-3.36634032,10000,-141.4325527,141.4217303,0,0,0,135 +89.7,50.37510199,-3.366320471,10000,-141.4221076,141.4208775,0,0,0,135 +89.71,50.3750893,-3.366300622,10000,-141.4151441,141.4209152,0,0,0,135 +89.72,50.37507661,-3.366280773,10000,-141.4186253,141.4218435,0,0,0,135 +89.73,50.37506391,-3.366260923,10000,-141.418625,141.4218813,0,0,0,135 +89.74,50.37505122,-3.366241074,10000,-141.4151432,141.4208057,0,0,0,135 +89.75,50.37503853,-3.366221225,10000,-141.422106,141.4201755,0,0,0,135 +89.76,50.37502583,-3.366201376,10000,-141.4325505,141.4208812,0,0,0,135 +89.77,50.37501314,-3.366181527,10000,-141.4325501,141.4220322,0,0,0,135 +89.78,50.37500044,-3.366161677,10000,-141.4221051,141.4220699,0,0,0,135 +89.79,50.37498775,-3.366141828,10000,-141.4151416,141.4209944,0,0,0,135 +89.8,50.37497506,-3.366121979,10000,-141.4186229,141.4203642,0,0,0,135 +89.81,50.37496236,-3.36610213,10000,-141.4186226,141.4210699,0,0,0,135 +89.82,50.37494967,-3.366082281,10000,-141.4151407,141.4222209,0,0,0,135 +89.83,50.37493698,-3.366062431,10000,-141.4186219,141.4222586,0,0,0,135 +89.84,50.37492428,-3.366042582,10000,-141.4186216,141.4211831,0,0,0,135 +89.85,50.37491159,-3.366022733,10000,-141.4151397,141.4203302,0,0,0,135 +89.86,50.3748989,-3.366002884,10000,-141.4221026,141.420368,0,0,0,135 +89.87,50.3748862,-3.365983035,10000,-141.4325471,141.4212963,0,0,0,135 +89.88,50.37487351,-3.365963186,10000,-141.4325467,141.4224473,0,0,0,135 +89.89,50.37486081,-3.365943336,10000,-141.4221017,141.422485,0,0,0,135 +89.9,50.37484812,-3.365923487,10000,-141.4151382,141.4214095,0,0,0,135 +89.91,50.37483543,-3.365903638,10000,-141.4186195,141.4205567,0,0,0,135 +89.92,50.37482273,-3.365883789,10000,-141.4186192,141.4203717,0,0,0,135 +89.93,50.37481004,-3.36586394,10000,-141.4151373,141.4206321,0,0,0,135 +89.94,50.37479735,-3.365844091,10000,-141.4221001,141.4215605,0,0,0,135 +89.95,50.37478465,-3.365824242,10000,-141.4325446,141.4227115,0,0,0,135 +89.96,50.37477196,-3.365804392,10000,-141.4325443,141.4227492,0,0,0,135 +89.97,50.37475926,-3.365784543,10000,-141.4220992,141.4216737,0,0,0,135 +89.98,50.37474657,-3.365764694,10000,-141.4151357,141.4208208,0,0,0,135 +89.99,50.37473388,-3.365744845,10000,-141.418617,141.4206359,0,0,0,135 +90,50.37472118,-3.365724996,10000,-141.4186167,141.4206736,0,0,0,135 +90.01,50.37470849,-3.365705147,10000,-141.4151348,141.4207114,0,0,0,135 +90.02,50.3746958,-3.365685298,10000,-141.4186161,141.4207491,0,0,0,135 +90.03,50.3746831,-3.365665449,10000,-141.4186157,141.4210095,0,0,0,135 +90.04,50.37467041,-3.3656456,10000,-141.4151339,141.4219378,0,0,0,135 +90.05,50.37465772,-3.365625751,10000,-141.4220967,141.4230888,0,0,0,135 +90.06,50.37464502,-3.365605901,10000,-141.4325412,141.4231266,0,0,0,135 +90.07,50.37463233,-3.365586052,10000,-141.4325409,141.422051,0,0,0,135 +90.08,50.37461963,-3.365566203,10000,-141.4220958,141.4211982,0,0,0,135 +90.09,50.37460694,-3.365546354,10000,-141.4151323,141.4210133,0,0,0,135 +90.1,50.37459425,-3.365526505,10000,-141.4186136,141.421051,0,0,0,135 +90.11,50.37458155,-3.365506656,10000,-141.4186133,141.4210887,0,0,0,135 +90.12,50.37456886,-3.365486807,10000,-141.4151314,141.4211265,0,0,0,135 +90.13,50.37455617,-3.365466958,10000,-141.4220942,141.4211642,0,0,0,135 +90.14,50.37454347,-3.365447109,10000,-141.4325387,141.4212019,0,0,0,135 +90.15,50.37453078,-3.36542726,10000,-141.4325384,141.4212397,0,0,0,135 +90.16,50.37451808,-3.365407411,10000,-141.4220933,141.4212774,0,0,0,135 +90.17,50.37450539,-3.365387562,10000,-141.4151298,141.4213151,0,0,0,135 +90.18,50.3744927,-3.365367713,10000,-141.4186111,141.4213529,0,0,0,135 +90.19,50.37448,-3.365347864,10000,-141.4186108,141.4213906,0,0,0,135 +90.2,50.37446731,-3.365328015,10000,-141.4151289,141.4214283,0,0,0,135 +90.21,50.37445462,-3.365308166,10000,-141.4186102,141.4214661,0,0,0,135 +90.22,50.37444192,-3.365288317,10000,-141.4186099,141.4215038,0,0,0,135 +90.23,50.37442923,-3.365268468,10000,-141.415128,141.4215415,0,0,0,135 +90.24,50.37441654,-3.365248619,10000,-141.4220908,141.4215793,0,0,0,135 +90.25,50.37440384,-3.36522877,10000,-141.4325353,141.421617,0,0,0,135 +90.26,50.37439115,-3.365208921,10000,-141.432535,141.4216548,0,0,0,135 +90.27,50.37437845,-3.365189072,10000,-141.4220899,141.4216925,0,0,0,135 +90.28,50.37436576,-3.365169223,10000,-141.4151264,141.4215076,0,0,0,135 +90.29,50.37435307,-3.365149374,10000,-141.4186077,141.4206547,0,0,0,135 +90.3,50.37434037,-3.365129525,10000,-141.4186074,141.4195792,0,0,0,135 +90.31,50.37432768,-3.365109677,10000,-141.4151255,141.4196169,0,0,0,135 +90.32,50.37431499,-3.365089828,10000,-141.4220883,141.4207679,0,0,0,135 +90.33,50.37430229,-3.365069979,10000,-141.4325328,141.4216963,0,0,0,135 +90.34,50.3742896,-3.36505013,10000,-141.4325325,141.4219566,0,0,0,135 +90.35,50.3742769,-3.365030281,10000,-141.4220874,141.4219944,0,0,0,135 +90.36,50.37426421,-3.365010432,10000,-141.4151239,141.4220321,0,0,0,135 +90.37,50.37425152,-3.364990583,10000,-141.4186052,141.4218472,0,0,0,135 +90.38,50.37423882,-3.364970734,10000,-141.4186049,141.4209943,0,0,0,135 +90.39,50.37422613,-3.364950885,10000,-141.415123,141.4199188,0,0,0,135 +90.4,50.37421344,-3.364931037,10000,-141.4186043,141.4199565,0,0,0,135 +90.41,50.37420074,-3.364911188,10000,-141.418604,141.4211075,0,0,0,135 +90.42,50.37418805,-3.364891339,10000,-141.4151221,141.4220359,0,0,0,135 +90.43,50.37417536,-3.36487149,10000,-141.4220849,141.4222963,0,0,0,135 +90.44,50.37416266,-3.364851641,10000,-141.4325294,141.422334,0,0,0,135 +90.45,50.37414997,-3.364831792,10000,-141.4325291,141.4223717,0,0,0,135 +90.46,50.37413727,-3.364811943,10000,-141.422084,141.4224095,0,0,0,135 +90.47,50.37412458,-3.364792094,10000,-141.4151205,141.4222245,0,0,0,135 +90.48,50.37411189,-3.364772245,10000,-141.4186018,141.4213717,0,0,0,135 +90.49,50.37409919,-3.364752396,10000,-141.4186015,141.4202961,0,0,0,135 +90.5,50.3740865,-3.364732548,10000,-141.4151196,141.4203339,0,0,0,135 +90.51,50.37407381,-3.364712699,10000,-141.4220825,141.4212622,0,0,0,135 +90.52,50.37406111,-3.36469285,10000,-141.4325269,141.4213,0,0,0,135 +90.53,50.37404842,-3.364673001,10000,-141.4325266,141.4204471,0,0,0,135 +90.54,50.37403572,-3.364653153,10000,-141.4220815,141.4204848,0,0,0,135 +90.55,50.37402303,-3.364633304,10000,-141.415118,141.4216358,0,0,0,135 +90.56,50.37401034,-3.364613455,10000,-141.4185993,141.4225642,0,0,0,135 +90.57,50.37399764,-3.364593606,10000,-141.418599,141.4226019,0,0,0,135 +90.58,50.37398495,-3.364573757,10000,-141.4151171,141.421749,0,0,0,135 +90.59,50.37397226,-3.364553908,10000,-141.4185984,141.4206735,0,0,0,135 +90.6,50.37395956,-3.36453406,10000,-141.4185981,141.4207112,0,0,0,135 +90.61,50.37394687,-3.364514211,10000,-141.4151162,141.4216396,0,0,0,135 +90.62,50.37393418,-3.364494362,10000,-141.4220791,141.4216773,0,0,0,135 +90.63,50.37392148,-3.364474513,10000,-141.4325235,141.4208244,0,0,0,135 +90.64,50.37390879,-3.364454665,10000,-141.4325232,141.4208622,0,0,0,135 +90.65,50.37389609,-3.364434816,10000,-141.4220781,141.4217905,0,0,0,135 +90.66,50.3738834,-3.364414967,10000,-141.4151146,141.4218282,0,0,0,135 +90.67,50.37387071,-3.364395118,10000,-141.4185959,141.4209754,0,0,0,135 +90.68,50.37385801,-3.36437527,10000,-141.4185956,141.4210131,0,0,0,135 +90.69,50.37384532,-3.364355421,10000,-141.4151137,141.4219414,0,0,0,135 +90.7,50.37383263,-3.364335572,10000,-141.4220766,141.4219792,0,0,0,135 +90.71,50.37381993,-3.364315723,10000,-141.432521,141.4211263,0,0,0,135 +90.72,50.37380724,-3.364295875,10000,-141.4325207,141.4209414,0,0,0,135 +90.73,50.37379454,-3.364276026,10000,-141.4220756,141.4212018,0,0,0,135 +90.74,50.37378185,-3.364256177,10000,-141.4151122,141.4210169,0,0,0,135 +90.75,50.37376916,-3.364236329,10000,-141.4185934,141.4212772,0,0,0,135 +90.76,50.37375646,-3.36421648,10000,-141.4185931,141.4222056,0,0,0,135 +90.77,50.37374377,-3.364196631,10000,-141.4151112,141.4222433,0,0,0,135 +90.78,50.37373108,-3.364176782,10000,-141.4185925,141.4213904,0,0,0,135 +90.79,50.37371838,-3.364156934,10000,-141.4185922,141.4212055,0,0,0,135 +90.8,50.37370569,-3.364137085,10000,-141.4151103,141.4214659,0,0,0,135 +90.81,50.373693,-3.364117236,10000,-141.4220732,141.4210583,0,0,0,135 +90.82,50.3736803,-3.364097388,10000,-141.4325176,141.4204281,0,0,0,135 +90.83,50.37366761,-3.364077539,10000,-141.4325173,141.4204658,0,0,0,135 +90.84,50.37365491,-3.364057691,10000,-141.4220722,141.4213942,0,0,0,135 +90.85,50.37364222,-3.364037842,10000,-141.4151087,141.4225452,0,0,0,135 +90.86,50.37362953,-3.364017993,10000,-141.41859,141.4223603,0,0,0,135 +90.87,50.37361683,-3.363998144,10000,-141.4185897,141.4206168,0,0,0,135 +90.88,50.37360414,-3.363978296,10000,-141.4151078,141.4195412,0,0,0,135 +90.89,50.37359145,-3.363958448,10000,-141.4220707,141.4204696,0,0,0,135 +90.9,50.37357875,-3.363938599,10000,-141.4325151,141.4216206,0,0,0,135 +90.91,50.37356606,-3.36391875,10000,-141.4325148,141.4216583,0,0,0,135 +90.92,50.37355336,-3.363898902,10000,-141.4220698,141.4216961,0,0,0,135 +90.93,50.37354067,-3.363879053,10000,-141.4151063,141.4219565,0,0,0,135 +90.94,50.37352798,-3.363859204,10000,-141.4185876,141.4215489,0,0,0,135 +90.95,50.37351528,-3.363839356,10000,-141.4185872,141.4209186,0,0,0,135 +90.96,50.37350259,-3.363819507,10000,-141.4151053,141.4209564,0,0,0,135 +90.97,50.3734899,-3.363799659,10000,-141.4185866,141.4216621,0,0,0,135 +90.98,50.3734772,-3.36377981,10000,-141.4185863,141.4221451,0,0,0,135 +90.99,50.37346451,-3.363759961,10000,-141.4151044,141.4219602,0,0,0,135 +91,50.37345182,-3.363740113,10000,-141.4220673,141.4219979,0,0,0,135 +91.01,50.37343912,-3.363720264,10000,-141.4325117,141.4220357,0,0,0,135 +91.02,50.37342643,-3.363700415,10000,-141.4325114,141.4209601,0,0,0,135 +91.03,50.37341373,-3.363680567,10000,-141.4220664,141.4201072,0,0,0,135 +91.04,50.37340104,-3.363660719,10000,-141.4151029,141.4210356,0,0,0,135 +91.05,50.37338835,-3.36364087,10000,-141.4185842,141.4221866,0,0,0,135 +91.06,50.37337565,-3.363621021,10000,-141.4185838,141.4220017,0,0,0,135 +91.07,50.37336296,-3.363601173,10000,-141.4151019,141.4211488,0,0,0,135 +91.08,50.37335027,-3.363581324,10000,-141.4220648,141.4202959,0,0,0,135 +91.09,50.37333757,-3.363561476,10000,-141.4325093,141.420111,0,0,0,135 +91.1,50.37332488,-3.363541628,10000,-141.432509,141.421262,0,0,0,135 +91.11,50.37331218,-3.363521779,10000,-141.4220639,141.422413,0,0,0,135 +91.12,50.37329949,-3.36350193,10000,-141.4151004,141.4222281,0,0,0,135 +91.13,50.3732868,-3.363482082,10000,-141.4185817,141.4213752,0,0,0,135 +91.14,50.3732741,-3.363462233,10000,-141.4185814,141.4205223,0,0,0,135 +91.15,50.37326141,-3.363442385,10000,-141.4150995,141.4203374,0,0,0,135 +91.16,50.37324872,-3.363422537,10000,-141.4220623,141.4214884,0,0,0,135 +91.17,50.37323602,-3.363402688,10000,-141.4325068,141.4226394,0,0,0,135 +91.18,50.37322333,-3.363382839,10000,-141.4325065,141.4224545,0,0,0,135 +91.19,50.37321063,-3.363362991,10000,-141.4220614,141.4216016,0,0,0,135 +91.2,50.37319794,-3.363343142,10000,-141.4150979,141.4207487,0,0,0,135 +91.21,50.37318525,-3.363323294,10000,-141.4185792,141.4203411,0,0,0,135 +91.22,50.37317255,-3.363303446,10000,-141.4185789,141.4208242,0,0,0,135 +91.23,50.37315986,-3.363283597,10000,-141.415097,141.4215299,0,0,0,135 +91.24,50.37314717,-3.363263749,10000,-141.4185783,141.4215676,0,0,0,135 +91.25,50.37313447,-3.3632439,10000,-141.4185779,141.4209374,0,0,0,135 +91.26,50.37312178,-3.363224052,10000,-141.415096,141.4205298,0,0,0,135 +91.27,50.37310909,-3.363204204,10000,-141.4220589,141.4210128,0,0,0,135 +91.28,50.37309639,-3.363184355,10000,-141.4325034,141.4217186,0,0,0,135 +91.29,50.3730837,-3.363164507,10000,-141.4325031,141.4217563,0,0,0,135 +91.3,50.373071,-3.363144658,10000,-141.422058,141.421126,0,0,0,135 +91.31,50.37305831,-3.36312481,10000,-141.4150945,141.4207185,0,0,0,135 +91.32,50.37304562,-3.363104962,10000,-141.4185758,141.4212015,0,0,0,135 +91.33,50.37303292,-3.363085113,10000,-141.4185755,141.4219072,0,0,0,135 +91.34,50.37302023,-3.363065265,10000,-141.4150936,141.421945,0,0,0,135 +91.35,50.37300754,-3.363045416,10000,-141.4185749,141.4213147,0,0,0,135 +91.36,50.37299484,-3.363025568,10000,-141.4185745,141.4209071,0,0,0,135 +91.37,50.37298215,-3.36300572,10000,-141.4150926,141.4213902,0,0,0,135 +91.38,50.37296946,-3.362985871,10000,-141.4220555,141.4220959,0,0,0,135 +91.39,50.37295676,-3.362966023,10000,-141.4324999,141.4221336,0,0,0,135 +91.4,50.37294407,-3.362946174,10000,-141.4324997,141.4215034,0,0,0,135 +91.41,50.37293137,-3.362926326,10000,-141.4220546,141.4210958,0,0,0,135 +91.42,50.37291868,-3.362906478,10000,-141.4150911,141.4213562,0,0,0,135 +91.43,50.37290599,-3.362886629,10000,-141.4185724,141.4211713,0,0,0,135 +91.44,50.37289329,-3.362866781,10000,-141.4185721,141.4203184,0,0,0,135 +91.45,50.3728806,-3.362846933,10000,-141.4150902,141.4203561,0,0,0,135 +91.46,50.37286791,-3.362827085,10000,-141.422053,141.4215071,0,0,0,135 +91.47,50.37285521,-3.362807236,10000,-141.4324975,141.4224355,0,0,0,135 +91.48,50.37284252,-3.362787388,10000,-141.4324972,141.4224732,0,0,0,135 +91.49,50.37282982,-3.362767539,10000,-141.4220521,141.4216203,0,0,0,135 +91.5,50.37281713,-3.362747691,10000,-141.4150886,141.4205448,0,0,0,135 +91.51,50.37280444,-3.362727843,10000,-141.4185699,141.4205825,0,0,0,135 +91.52,50.37279174,-3.362707995,10000,-141.4185696,141.4217335,0,0,0,135 +91.53,50.37277905,-3.362688146,10000,-141.4150877,141.4224392,0,0,0,135 +91.54,50.37276636,-3.362668298,10000,-141.4220505,141.421809,0,0,0,135 +91.55,50.37275366,-3.362648449,10000,-141.432495,141.4207334,0,0,0,135 +91.56,50.37274097,-3.362628602,10000,-141.4324947,141.4207712,0,0,0,135 +91.57,50.37272827,-3.362608753,10000,-141.4220496,141.4216995,0,0,0,135 +91.58,50.37271558,-3.362588905,10000,-141.4150862,141.4217373,0,0,0,135 +91.59,50.37270289,-3.362569056,10000,-141.4185674,141.4208844,0,0,0,135 +91.6,50.37269019,-3.362549209,10000,-141.4185671,141.4209221,0,0,0,135 +91.61,50.3726775,-3.36252936,10000,-141.4150852,141.4218505,0,0,0,135 +91.62,50.37266481,-3.362509512,10000,-141.4185665,141.4218882,0,0,0,135 +91.63,50.37265211,-3.362489663,10000,-141.4185662,141.4210353,0,0,0,135 +91.64,50.37263942,-3.362469816,10000,-141.4150843,141.4208504,0,0,0,135 +91.65,50.37262673,-3.362449967,10000,-141.4220471,141.4213334,0,0,0,135 +91.66,50.37261403,-3.362430119,10000,-141.4324916,141.4218165,0,0,0,135 +91.67,50.37260134,-3.362410271,10000,-141.4324913,141.4222995,0,0,0,135 +91.68,50.37258864,-3.362390422,10000,-141.4220462,141.4221146,0,0,0,135 +91.69,50.37257595,-3.362370574,10000,-141.4150827,141.421039,0,0,0,135 +91.7,50.37256326,-3.362350726,10000,-141.418564,141.4201861,0,0,0,135 +91.71,50.37255056,-3.362330878,10000,-141.4185637,141.4202238,0,0,0,135 +91.72,50.37253787,-3.36231103,10000,-141.4150818,141.4211522,0,0,0,135 +91.73,50.37252518,-3.362291182,10000,-141.4185631,141.4223033,0,0,0,135 +91.74,50.37251248,-3.362271333,10000,-141.4185628,141.422341,0,0,0,135 +91.75,50.37249979,-3.362251485,10000,-141.4150809,141.4212654,0,0,0,135 +91.76,50.3724871,-3.362231637,10000,-141.4220437,141.4206352,0,0,0,135 +91.77,50.3724744,-3.362211789,10000,-141.4324882,141.4211182,0,0,0,135 +91.78,50.37246171,-3.362191941,10000,-141.4324879,141.4216013,0,0,0,135 +91.79,50.37244901,-3.362172092,10000,-141.4220428,141.4214164,0,0,0,135 +91.8,50.37243632,-3.362152245,10000,-141.4150793,141.4214541,0,0,0,135 +91.81,50.37242363,-3.362132396,10000,-141.4185606,141.4217145,0,0,0,135 +91.82,50.37241093,-3.362112548,10000,-141.4185603,141.4213069,0,0,0,135 +91.83,50.37239824,-3.3620927,10000,-141.4150784,141.4206766,0,0,0,135 +91.84,50.37238555,-3.362072852,10000,-141.4220413,141.4207144,0,0,0,135 +91.85,50.37237285,-3.362053004,10000,-141.4324857,141.4214201,0,0,0,135 +91.86,50.37236016,-3.362033156,10000,-141.4324854,141.4219031,0,0,0,135 +91.87,50.37234746,-3.362013307,10000,-141.4220403,141.4217182,0,0,0,135 +91.88,50.37233477,-3.36199346,10000,-141.4150768,141.421756,0,0,0,135 +91.89,50.37232208,-3.361973611,10000,-141.4185581,141.4220163,0,0,0,135 +91.9,50.37230938,-3.361953763,10000,-141.4185578,141.4216088,0,0,0,135 +91.91,50.37229669,-3.361933915,10000,-141.4150759,141.4209785,0,0,0,135 +91.92,50.372284,-3.361914067,10000,-141.4220388,141.4207936,0,0,0,135 +91.93,50.3722713,-3.361894219,10000,-141.4324832,141.4208313,0,0,0,135 +91.94,50.37225861,-3.361874371,10000,-141.4324829,141.420869,0,0,0,135 +91.95,50.37224591,-3.361854523,10000,-141.4220379,141.4209068,0,0,0,135 +91.96,50.37223322,-3.361834675,10000,-141.4150743,141.4209445,0,0,0,135 +91.97,50.37222053,-3.361814827,10000,-141.4185556,141.4209822,0,0,0,135 +91.98,50.37220783,-3.361794979,10000,-141.4185553,141.42102,0,0,0,135 +91.99,50.37219514,-3.361775131,10000,-141.4150735,141.4212804,0,0,0,135 +92,50.37218245,-3.361755283,10000,-141.4185547,141.4219861,0,0,0,135 +92.01,50.37216975,-3.361735435,10000,-141.4185544,141.4222465,0,0,0,135 +92.02,50.37215706,-3.361715586,10000,-141.4150725,141.4213936,0,0,0,135 +92.03,50.37214437,-3.361695739,10000,-141.4220353,141.420986,0,0,0,135 +92.04,50.37213167,-3.361675891,10000,-141.4324798,141.421469,0,0,0,135 +92.05,50.37211898,-3.361656042,10000,-141.4324795,141.4212841,0,0,0,135 +92.06,50.37210628,-3.361636195,10000,-141.4220345,141.4210992,0,0,0,135 +92.07,50.37209359,-3.361616347,10000,-141.415071,141.4215822,0,0,0,135 +92.08,50.3720809,-3.361596498,10000,-141.4185522,141.4213973,0,0,0,135 +92.09,50.3720682,-3.361576651,10000,-141.4185519,141.421435,0,0,0,135 +92.1,50.37205551,-3.361556803,10000,-141.41507,141.4225861,0,0,0,135 +92.11,50.37204282,-3.361536954,10000,-141.4220329,141.4224011,0,0,0,135 +92.12,50.37203012,-3.361517106,10000,-141.4324773,141.4204349,0,0,0,135 +92.13,50.37201743,-3.361497259,10000,-141.432477,141.419582,0,0,0,135 +92.14,50.37200473,-3.361477411,10000,-141.4220319,141.4205104,0,0,0,135 +92.15,50.37199204,-3.361457563,10000,-141.4150685,141.4214388,0,0,0,135 +92.16,50.37197935,-3.361437715,10000,-141.4185498,141.4216991,0,0,0,135 +92.17,50.37196665,-3.361417867,10000,-141.4185494,141.4217369,0,0,0,135 +92.18,50.37195396,-3.361398019,10000,-141.4150675,141.4217746,0,0,0,135 +92.19,50.37194127,-3.361378171,10000,-141.4185488,141.4218123,0,0,0,135 +92.2,50.37192857,-3.361358323,10000,-141.4185485,141.4218501,0,0,0,135 +92.21,50.37191588,-3.361338475,10000,-141.4150666,141.4218878,0,0,0,135 +92.22,50.37190319,-3.361318627,10000,-141.4220295,141.4217029,0,0,0,135 +92.23,50.37189049,-3.361298779,10000,-141.4324739,141.42085,0,0,0,135 +92.24,50.3718778,-3.361278931,10000,-141.4324736,141.4197744,0,0,0,135 +92.25,50.3718651,-3.361259084,10000,-141.4220285,141.4200348,0,0,0,135 +92.26,50.37185241,-3.361239236,10000,-141.4150651,141.4218538,0,0,0,135 +92.27,50.37183972,-3.361219388,10000,-141.4185463,141.4230049,0,0,0,135 +92.28,50.37182702,-3.361199539,10000,-141.418546,141.4221519,0,0,0,135 +92.29,50.37181433,-3.361179692,10000,-141.4150641,141.4210763,0,0,0,135 +92.3,50.37180164,-3.361159844,10000,-141.422027,141.4213367,0,0,0,135 +92.31,50.37178894,-3.361139996,10000,-141.4324714,141.4220425,0,0,0,135 +92.32,50.37177625,-3.361120148,10000,-141.4324711,141.4220802,0,0,0,135 +92.33,50.37176355,-3.3611003,10000,-141.4220261,141.4212273,0,0,0,135 +92.34,50.37175086,-3.361080452,10000,-141.4150626,141.4201517,0,0,0,135 +92.35,50.37173817,-3.361060605,10000,-141.4185439,141.4201894,0,0,0,135 +92.36,50.37172547,-3.361040757,10000,-141.4185436,141.4213405,0,0,0,135 +92.37,50.37171278,-3.361020909,10000,-141.4150617,141.4222689,0,0,0,135 +92.38,50.37170009,-3.361001061,10000,-141.4185429,141.4223066,0,0,0,135 +92.39,50.37168739,-3.360981213,10000,-141.4185426,141.4214537,0,0,0,135 +92.4,50.3716747,-3.360961365,10000,-141.4150607,141.4203781,0,0,0,135 +92.41,50.37166201,-3.360941518,10000,-141.4220236,141.4204158,0,0,0,135 +92.42,50.37164931,-3.36092167,10000,-141.4324681,141.4215669,0,0,0,135 +92.43,50.37163662,-3.360901822,10000,-141.4324677,141.4224953,0,0,0,135 +92.44,50.37162392,-3.360881974,10000,-141.4220226,141.422533,0,0,0,135 +92.45,50.37161123,-3.360862126,10000,-141.4150592,141.4216801,0,0,0,135 +92.46,50.37159854,-3.360842278,10000,-141.4185404,141.4206045,0,0,0,135 +92.47,50.37158584,-3.360822431,10000,-141.4185402,141.4206422,0,0,0,135 +92.48,50.37157315,-3.360802583,10000,-141.4150583,141.4215706,0,0,0,135 +92.49,50.37156046,-3.360782735,10000,-141.4220211,141.4216083,0,0,0,135 +92.5,50.37154776,-3.360762887,10000,-141.4324655,141.4207554,0,0,0,135 +92.51,50.37153507,-3.36074304,10000,-141.4324652,141.4207931,0,0,0,135 +92.52,50.37152237,-3.360723192,10000,-141.4220202,141.4217215,0,0,0,135 +92.53,50.37150968,-3.360703344,10000,-141.4150567,141.4217592,0,0,0,135 +92.54,50.37149699,-3.360683496,10000,-141.418538,141.4209063,0,0,0,135 +92.55,50.37148429,-3.360663649,10000,-141.4185377,141.4207214,0,0,0,135 +92.56,50.3714716,-3.360643801,10000,-141.4150558,141.4209818,0,0,0,135 +92.57,50.37145891,-3.360623953,10000,-141.4220186,141.4207968,0,0,0,135 +92.58,50.37144621,-3.360604106,10000,-141.4324631,141.4210572,0,0,0,135 +92.59,50.37143352,-3.360584258,10000,-141.4324628,141.4222083,0,0,0,135 +92.6,50.37142082,-3.36056441,10000,-141.4220177,141.422914,0,0,0,135 +92.61,50.37140813,-3.360544562,10000,-141.4150542,141.4222838,0,0,0,135 +92.62,50.37139544,-3.360524714,10000,-141.4185355,141.4212082,0,0,0,135 +92.63,50.37138274,-3.360504867,10000,-141.4185352,141.4210232,0,0,0,135 +92.64,50.37137005,-3.360485019,10000,-141.4150533,141.4212836,0,0,0,135 +92.65,50.37135736,-3.360465171,10000,-141.4185346,141.420876,0,0,0,135 +92.66,50.37134466,-3.360445324,10000,-141.4185343,141.4202458,0,0,0,135 +92.67,50.37133197,-3.360425476,10000,-141.4150523,141.4202835,0,0,0,135 +92.68,50.37131928,-3.360405629,10000,-141.4220152,141.4209892,0,0,0,135 +92.69,50.37130658,-3.360385781,10000,-141.4324597,141.4214723,0,0,0,135 +92.7,50.37129389,-3.360365933,10000,-141.4324594,141.4212873,0,0,0,135 +92.71,50.37128119,-3.360346086,10000,-141.4220143,141.4213251,0,0,0,135 +92.72,50.3712685,-3.360326238,10000,-141.4150508,141.4215855,0,0,0,135 +92.73,50.37125581,-3.36030639,10000,-141.4185321,141.4214005,0,0,0,135 +92.74,50.37124311,-3.360286543,10000,-141.4185318,141.4214383,0,0,0,135 +92.75,50.37123042,-3.360266695,10000,-141.4150499,141.4216987,0,0,0,135 +92.76,50.37121773,-3.360246847,10000,-141.4185312,141.4215137,0,0,0,135 +92.77,50.37120503,-3.360227,10000,-141.4185309,141.4215515,0,0,0,135 +92.78,50.37119234,-3.360207152,10000,-141.4150489,141.4218119,0,0,0,135 +92.79,50.37117965,-3.360187304,10000,-141.4220118,141.4214043,0,0,0,135 +92.8,50.37116695,-3.360167457,10000,-141.4324563,141.420774,0,0,0,135 +92.81,50.37115426,-3.360147609,10000,-141.432456,141.4208117,0,0,0,135 +92.82,50.37114156,-3.360127762,10000,-141.4220109,141.4215175,0,0,0,135 +92.83,50.37112887,-3.360107914,10000,-141.4150474,141.4220005,0,0,0,135 +92.84,50.37111618,-3.360088066,10000,-141.4185287,141.4215929,0,0,0,135 +92.85,50.37110348,-3.360068219,10000,-141.4185284,141.4209626,0,0,0,135 +92.86,50.37109079,-3.360048371,10000,-141.4150465,141.4207777,0,0,0,135 +92.87,50.3710781,-3.360028524,10000,-141.4220093,141.4208154,0,0,0,135 +92.88,50.3710654,-3.360008676,10000,-141.4324538,141.4210758,0,0,0,135 +92.89,50.37105271,-3.359988829,10000,-141.4324535,141.4217816,0,0,0,135 +92.9,50.37104001,-3.359968981,10000,-141.4220084,141.4222646,0,0,0,135 +92.91,50.37102732,-3.359949133,10000,-141.4150449,141.421857,0,0,0,135 +92.92,50.37101463,-3.359929286,10000,-141.4185262,141.4212268,0,0,0,135 +92.93,50.37100193,-3.359909438,10000,-141.4185259,141.4210418,0,0,0,135 +92.94,50.37098924,-3.359889591,10000,-141.415044,141.4210796,0,0,0,135 +92.95,50.37097655,-3.359869743,10000,-141.4220069,141.42134,0,0,0,135 +92.96,50.37096385,-3.359849896,10000,-141.4324513,141.4220457,0,0,0,135 +92.97,50.37095116,-3.359830048,10000,-141.432451,141.4225288,0,0,0,135 +92.98,50.37093846,-3.3598102,10000,-141.4220059,141.4221212,0,0,0,135 +92.99,50.37092577,-3.359790353,10000,-141.4150424,141.4214909,0,0,0,135 +93,50.37091308,-3.359770505,10000,-141.4185237,141.4213059,0,0,0,135 +93.01,50.37090038,-3.359750658,10000,-141.4185234,141.421121,0,0,0,135 +93.02,50.37088769,-3.35973081,10000,-141.4150415,141.4204907,0,0,0,135 +93.03,50.370875,-3.359710963,10000,-141.4185228,141.4200831,0,0,0,135 +93.04,50.3708623,-3.359691116,10000,-141.4185225,141.4205662,0,0,0,135 +93.05,50.37084961,-3.359671268,10000,-141.4150406,141.4212719,0,0,0,135 +93.06,50.37083692,-3.359651421,10000,-141.4220035,141.4215323,0,0,0,135 +93.07,50.37082422,-3.359631573,10000,-141.4324479,141.4217927,0,0,0,135 +93.08,50.37081153,-3.359611726,10000,-141.4324476,141.4224985,0,0,0,135 +93.09,50.37079883,-3.359591878,10000,-141.4220025,141.4227589,0,0,0,135 +93.1,50.37078614,-3.35957203,10000,-141.415039,141.4216832,0,0,0,135 +93.11,50.37077345,-3.359552183,10000,-141.4185203,141.4206076,0,0,0,135 +93.12,50.37076075,-3.359532336,10000,-141.41852,141.4206454,0,0,0,135 +93.13,50.37074806,-3.359512488,10000,-141.4150381,141.4206831,0,0,0,135 +93.14,50.37073537,-3.359492641,10000,-141.422001,141.4204981,0,0,0,135 +93.15,50.37072267,-3.359472794,10000,-141.4324454,141.4209812,0,0,0,135 +93.16,50.37070998,-3.359452946,10000,-141.4324451,141.421687,0,0,0,135 +93.17,50.37069728,-3.359433099,10000,-141.422,141.4219474,0,0,0,135 +93.18,50.37068459,-3.359413251,10000,-141.4150366,141.4219851,0,0,0,135 +93.19,50.3706719,-3.359393404,10000,-141.4185178,141.4218002,0,0,0,135 +93.2,50.3706592,-3.359373556,10000,-141.4185175,141.4211699,0,0,0,135 +93.21,50.37064651,-3.359353709,10000,-141.4150356,141.4207623,0,0,0,135 +93.22,50.37063382,-3.359333862,10000,-141.4185169,141.4212453,0,0,0,135 +93.23,50.37062112,-3.359314014,10000,-141.4185166,141.4219511,0,0,0,135 +93.24,50.37060843,-3.359294167,10000,-141.4150347,141.4219888,0,0,0,135 +93.25,50.37059574,-3.359274319,10000,-141.4219976,141.4211359,0,0,0,135 +93.26,50.37058304,-3.359254472,10000,-141.432442,141.4200602,0,0,0,135 +93.27,50.37057035,-3.359234625,10000,-141.4324417,141.4203206,0,0,0,135 +93.28,50.37055765,-3.359214778,10000,-141.4219966,141.4221397,0,0,0,135 +93.29,50.37054496,-3.35919493,10000,-141.4150332,141.4232908,0,0,0,135 +93.3,50.37053227,-3.359175082,10000,-141.4185144,141.4222152,0,0,0,135 +93.31,50.37051957,-3.359155235,10000,-141.4185141,141.4204716,0,0,0,135 +93.32,50.37050688,-3.359135388,10000,-141.4150322,141.4202866,0,0,0,135 +93.33,50.37049419,-3.359115541,10000,-141.4219951,141.421215,0,0,0,135 +93.34,50.37048149,-3.359095693,10000,-141.4324395,141.4214754,0,0,0,135 +93.35,50.3704688,-3.359075846,10000,-141.4324392,141.4212905,0,0,0,135 +93.36,50.3704561,-3.359055999,10000,-141.4219942,141.4215509,0,0,0,135 +93.37,50.37044341,-3.359036151,10000,-141.4150307,141.4215886,0,0,0,135 +93.38,50.37043072,-3.359016304,10000,-141.4185119,141.4214037,0,0,0,135 +93.39,50.37041802,-3.358996457,10000,-141.4185116,141.4216641,0,0,0,135 +93.4,50.37040533,-3.358976609,10000,-141.4150298,141.4214791,0,0,0,135 +93.41,50.37039264,-3.358956762,10000,-141.4219926,141.4206262,0,0,0,135 +93.42,50.37037994,-3.358936915,10000,-141.4324371,141.4206639,0,0,0,135 +93.43,50.37036725,-3.358917068,10000,-141.4324367,141.4215923,0,0,0,135 +93.44,50.37035455,-3.35889722,10000,-141.4219917,141.4216301,0,0,0,135 +93.45,50.37034186,-3.358877373,10000,-141.4150282,141.4207771,0,0,0,135 +93.46,50.37032917,-3.358857526,10000,-141.4185095,141.4208148,0,0,0,135 +93.47,50.37031647,-3.358837679,10000,-141.4185092,141.4217433,0,0,0,135 +93.48,50.37030378,-3.358817831,10000,-141.4150273,141.4220037,0,0,0,135 +93.49,50.37029109,-3.358797984,10000,-141.4185085,141.4218187,0,0,0,135 +93.5,50.37027839,-3.358778137,10000,-141.4185082,141.4220791,0,0,0,135 +93.51,50.3702657,-3.358758289,10000,-141.4150263,141.4218942,0,0,0,135 +93.52,50.37025301,-3.358738442,10000,-141.4219892,141.4210412,0,0,0,135 +93.53,50.37024031,-3.358718595,10000,-141.4324336,141.4210789,0,0,0,135 +93.54,50.37022762,-3.358698748,10000,-141.4324333,141.4220074,0,0,0,135 +93.55,50.37021492,-3.3586789,10000,-141.4219883,141.4220451,0,0,0,135 +93.56,50.37020223,-3.358659053,10000,-141.4150248,141.4209695,0,0,0,135 +93.57,50.37018954,-3.358639206,10000,-141.4185061,141.4201165,0,0,0,135 +93.58,50.37017684,-3.358619359,10000,-141.4185057,141.4201542,0,0,0,135 +93.59,50.37016415,-3.358599512,10000,-141.4150239,141.4210826,0,0,0,135 +93.6,50.37015146,-3.358579665,10000,-141.4219867,141.4222337,0,0,0,135 +93.61,50.37013876,-3.358559817,10000,-141.4324312,141.4222715,0,0,0,135 +93.62,50.37012607,-3.35853997,10000,-141.4324309,141.4214185,0,0,0,135 +93.63,50.37011337,-3.358520123,10000,-141.4219858,141.4212336,0,0,0,135 +93.64,50.37010068,-3.358500276,10000,-141.4150223,141.421494,0,0,0,135 +93.65,50.37008799,-3.358480428,10000,-141.4185036,141.421309,0,0,0,135 +93.66,50.37007529,-3.358460582,10000,-141.4185033,141.4213468,0,0,0,135 +93.67,50.3700626,-3.358440734,10000,-141.4150214,141.4216072,0,0,0,135 +93.68,50.37004991,-3.358420887,10000,-141.4185026,141.4211995,0,0,0,135 +93.69,50.37003721,-3.35840104,10000,-141.4185023,141.4205693,0,0,0,135 +93.7,50.37002452,-3.358381193,10000,-141.4150204,141.4203843,0,0,0,135 +93.71,50.37001183,-3.358361346,10000,-141.4219833,141.4206447,0,0,0,135 +93.72,50.36999913,-3.358341499,10000,-141.4324278,141.4213505,0,0,0,135 +93.73,50.36998644,-3.358321652,10000,-141.4324274,141.4218335,0,0,0,135 +93.74,50.36997374,-3.358301804,10000,-141.4219824,141.4216486,0,0,0,135 +93.75,50.36996105,-3.358281958,10000,-141.4150189,141.4216863,0,0,0,135 +93.76,50.36994836,-3.35826211,10000,-141.4185002,141.4219467,0,0,0,135 +93.77,50.36993566,-3.358242263,10000,-141.4184999,141.4215391,0,0,0,135 +93.78,50.36992297,-3.358222416,10000,-141.415018,141.4209088,0,0,0,135 +93.79,50.36991028,-3.358202569,10000,-141.4219808,141.4207239,0,0,0,135 +93.8,50.36989758,-3.358182722,10000,-141.4324253,141.4207616,0,0,0,135 +93.81,50.36988489,-3.358162875,10000,-141.432425,141.421022,0,0,0,135 +93.82,50.36987219,-3.358143028,10000,-141.4219799,141.4217278,0,0,0,135 +93.83,50.3698595,-3.358123181,10000,-141.4150164,141.4222108,0,0,0,135 +93.84,50.36984681,-3.358103333,10000,-141.4184977,141.4220259,0,0,0,135 +93.85,50.36983411,-3.358083487,10000,-141.4184974,141.4218409,0,0,0,135 +93.86,50.36982142,-3.358063639,10000,-141.4150155,141.4214333,0,0,0,135 +93.87,50.36980873,-3.358043792,10000,-141.4184968,141.4205804,0,0,0,135 +93.88,50.36979603,-3.358023946,10000,-141.4184965,141.4203954,0,0,0,135 +93.89,50.36978334,-3.358004098,10000,-141.4150146,141.4211012,0,0,0,135 +93.9,50.36977065,-3.357984252,10000,-141.4219774,141.4220296,0,0,0,135 +93.91,50.36975795,-3.357964404,10000,-141.4324219,141.4225127,0,0,0,135 +93.92,50.36974526,-3.357944557,10000,-141.4324215,141.4221051,0,0,0,135 +93.93,50.36973256,-3.35792471,10000,-141.4219765,141.4214748,0,0,0,135 +93.94,50.36971987,-3.357904863,10000,-141.415013,141.4212898,0,0,0,135 +93.95,50.36970718,-3.357885016,10000,-141.4184943,141.4213275,0,0,0,135 +93.96,50.36969448,-3.357865169,10000,-141.418494,141.4213653,0,0,0,135 +93.97,50.36968179,-3.357845322,10000,-141.4150121,141.421403,0,0,0,135 +93.98,50.3696691,-3.357825475,10000,-141.4219749,141.4214407,0,0,0,135 +93.99,50.3696564,-3.357805628,10000,-141.4324194,141.4214785,0,0,0,135 +94,50.36964371,-3.357785781,10000,-141.4324191,141.4215162,0,0,0,135 +94.01,50.36963101,-3.357765934,10000,-141.421974,141.4215539,0,0,0,135 +94.02,50.36961832,-3.357746087,10000,-141.4150105,141.421369,0,0,0,135 +94.03,50.36960563,-3.35772624,10000,-141.4184918,141.4207387,0,0,0,135 +94.04,50.36959293,-3.357706393,10000,-141.4184915,141.4203311,0,0,0,135 +94.05,50.36958024,-3.357686547,10000,-141.4150096,141.4205915,0,0,0,135 +94.06,50.36956755,-3.357666699,10000,-141.4219725,141.4206292,0,0,0,135 +94.07,50.36955485,-3.357646853,10000,-141.4324169,141.4204442,0,0,0,135 +94.08,50.36954216,-3.357627006,10000,-141.4324166,141.4209273,0,0,0,135 +94.09,50.36952946,-3.357607159,10000,-141.4219715,141.4216331,0,0,0,135 +94.1,50.36951677,-3.357587312,10000,-141.4150081,141.4218935,0,0,0,135 +94.11,50.36950408,-3.357567465,10000,-141.4184893,141.4219312,0,0,0,135 +94.12,50.36949138,-3.357547618,10000,-141.418489,141.4219689,0,0,0,135 +94.13,50.36947869,-3.357527771,10000,-141.4150071,141.4220067,0,0,0,135 +94.14,50.369466,-3.357507924,10000,-141.4184884,141.4218217,0,0,0,135 +94.15,50.3694533,-3.357488077,10000,-141.4184881,141.4211914,0,0,0,135 +94.16,50.36944061,-3.35746823,10000,-141.4150062,141.4207838,0,0,0,135 +94.17,50.36942792,-3.357448384,10000,-141.4219691,141.4210442,0,0,0,135 +94.18,50.36941522,-3.357428536,10000,-141.4324135,141.4210819,0,0,0,135 +94.19,50.36940253,-3.35740869,10000,-141.4324132,141.420897,0,0,0,135 +94.2,50.36938983,-3.357388843,10000,-141.4219681,141.4213801,0,0,0,135 +94.21,50.36937714,-3.357368996,10000,-141.4150046,141.4220858,0,0,0,135 +94.22,50.36936445,-3.357349149,10000,-141.4184859,141.4223462,0,0,0,135 +94.23,50.36935175,-3.357329302,10000,-141.4184856,141.4221613,0,0,0,135 +94.24,50.36933906,-3.357309455,10000,-141.4150037,141.4213083,0,0,0,135 +94.25,50.36932637,-3.357289608,10000,-141.4219666,141.4202327,0,0,0,135 +94.26,50.36931367,-3.357269762,10000,-141.432411,141.4202704,0,0,0,135 +94.27,50.36930098,-3.357249915,10000,-141.4324107,141.4214215,0,0,0,135 +94.28,50.36928828,-3.357230068,10000,-141.4219656,141.4221273,0,0,0,135 +94.29,50.36927559,-3.357210221,10000,-141.4150022,141.4217196,0,0,0,135 +94.3,50.3692629,-3.357190374,10000,-141.4184835,141.421312,0,0,0,135 +94.31,50.3692502,-3.357170528,10000,-141.4184832,141.4215724,0,0,0,135 +94.32,50.36923751,-3.35715068,10000,-141.4150013,141.4216101,0,0,0,135 +94.33,50.36922482,-3.357130834,10000,-141.4184825,141.4212025,0,0,0,135 +94.34,50.36921212,-3.357110987,10000,-141.4184822,141.4210176,0,0,0,135 +94.35,50.36919943,-3.35709114,10000,-141.4150003,141.421278,0,0,0,135 +94.36,50.36918674,-3.357071294,10000,-141.4219632,141.421761,0,0,0,135 +94.37,50.36917404,-3.357051446,10000,-141.4324076,141.4217988,0,0,0,135 +94.38,50.36916135,-3.3570316,10000,-141.4324073,141.4213912,0,0,0,135 +94.39,50.36914865,-3.357011753,10000,-141.4219622,141.4209835,0,0,0,135 +94.4,50.36913596,-3.356991906,10000,-141.4149987,141.4205759,0,0,0,135 +94.41,50.36912327,-3.35697206,10000,-141.41848,141.4208363,0,0,0,135 +94.42,50.36911057,-3.356952213,10000,-141.4184797,141.4219874,0,0,0,135 +94.43,50.36909788,-3.356932366,10000,-141.4149978,141.4226932,0,0,0,135 +94.44,50.36908519,-3.356912519,10000,-141.4219607,141.4220629,0,0,0,135 +94.45,50.36907249,-3.356892672,10000,-141.4324051,141.4209872,0,0,0,135 +94.46,50.3690598,-3.356872826,10000,-141.4324048,141.4208023,0,0,0,135 +94.47,50.3690471,-3.356852979,10000,-141.4219598,141.4210627,0,0,0,135 +94.48,50.36903441,-3.356833132,10000,-141.4149963,141.4208777,0,0,0,135 +94.49,50.36902172,-3.356813286,10000,-141.4184776,141.4209155,0,0,0,135 +94.5,50.36900902,-3.356793439,10000,-141.4184772,141.4211759,0,0,0,135 +94.51,50.36899633,-3.356773592,10000,-141.4149953,141.4209909,0,0,0,135 +94.52,50.36898364,-3.356753746,10000,-141.4219582,141.4210286,0,0,0,135 +94.53,50.36897094,-3.356733899,10000,-141.4324027,141.421289,0,0,0,135 +94.54,50.36895825,-3.356714052,10000,-141.4324024,141.4211041,0,0,0,135 +94.55,50.36894555,-3.356694206,10000,-141.4219573,141.4211418,0,0,0,135 +94.56,50.36893286,-3.356674359,10000,-141.4149938,141.4214022,0,0,0,135 +94.57,50.36892017,-3.356654512,10000,-141.4184751,141.4212173,0,0,0,135 +94.58,50.36890747,-3.356634666,10000,-141.4184748,141.4214777,0,0,0,135 +94.59,50.36889478,-3.356614819,10000,-141.4149929,141.4224061,0,0,0,135 +94.6,50.36888209,-3.356594972,10000,-141.4184742,141.4224439,0,0,0,135 +94.61,50.36886939,-3.356575125,10000,-141.4184738,141.4215909,0,0,0,135 +94.62,50.3688567,-3.356555279,10000,-141.414992,141.4214059,0,0,0,135 +94.63,50.36884401,-3.356535432,10000,-141.4219548,141.4216663,0,0,0,135 +94.64,50.36883131,-3.356515585,10000,-141.4323992,141.4214814,0,0,0,135 +94.65,50.36881862,-3.356495739,10000,-141.4323989,141.4215191,0,0,0,135 +94.66,50.36880592,-3.356475892,10000,-141.4219539,141.4215568,0,0,0,135 +94.67,50.36879323,-3.356456045,10000,-141.4149904,141.4204812,0,0,0,135 +94.68,50.36878054,-3.356436199,10000,-141.4184717,141.4196282,0,0,0,135 +94.69,50.36876784,-3.356416353,10000,-141.4184714,141.4205566,0,0,0,135 +94.7,50.36875515,-3.356396506,10000,-141.4149895,141.4217077,0,0,0,135 +94.71,50.36874246,-3.356376659,10000,-141.4219523,141.4217455,0,0,0,135 +94.72,50.36872976,-3.356356813,10000,-141.4323968,141.4217832,0,0,0,135 +94.73,50.36871707,-3.356336966,10000,-141.4323965,141.4220436,0,0,0,135 +94.74,50.36870437,-3.356317119,10000,-141.4219514,141.421636,0,0,0,135 +94.75,50.36869168,-3.356297273,10000,-141.4149879,141.4210057,0,0,0,135 +94.76,50.36867899,-3.356277426,10000,-141.4184692,141.4210434,0,0,0,135 +94.77,50.36866629,-3.35625758,10000,-141.4184689,141.4217492,0,0,0,135 +94.78,50.3686536,-3.356237733,10000,-141.414987,141.4222322,0,0,0,135 +94.79,50.36864091,-3.356217886,10000,-141.4184683,141.4218246,0,0,0,135 +94.8,50.36862821,-3.35619804,10000,-141.418468,141.4211943,0,0,0,135 +94.81,50.36861552,-3.356178193,10000,-141.414986,141.4210094,0,0,0,135 +94.82,50.36860283,-3.356158347,10000,-141.4219489,141.4210471,0,0,0,135 +94.83,50.36859013,-3.3561385,10000,-141.4323934,141.4210848,0,0,0,135 +94.84,50.36857744,-3.356118654,10000,-141.4323931,141.4208999,0,0,0,135 +94.85,50.36856474,-3.356098807,10000,-141.421948,141.4202695,0,0,0,135 +94.86,50.36855205,-3.356078961,10000,-141.4149845,141.4200846,0,0,0,135 +94.87,50.36853936,-3.356059115,10000,-141.4184658,141.4214584,0,0,0,135 +94.88,50.36852666,-3.356039268,10000,-141.4184655,141.4232776,0,0,0,135 +94.89,50.36851397,-3.356019421,10000,-141.4149836,141.4233153,0,0,0,135 +94.9,50.36850128,-3.355999574,10000,-141.4219465,141.4215716,0,0,0,135 +94.91,50.36848858,-3.355979728,10000,-141.4323909,141.4202732,0,0,0,135 +94.92,50.36847589,-3.355959882,10000,-141.4323906,141.4205336,0,0,0,135 +94.93,50.36846319,-3.355940035,10000,-141.4219455,141.4212394,0,0,0,135 +94.94,50.3684505,-3.355920189,10000,-141.414982,141.4214998,0,0,0,135 +94.95,50.36843781,-3.355900342,10000,-141.4184633,141.4215375,0,0,0,135 +94.96,50.36842511,-3.355880496,10000,-141.418463,141.4213526,0,0,0,135 +94.97,50.36841242,-3.355860649,10000,-141.4149811,141.4207223,0,0,0,135 +94.98,50.36839973,-3.355840803,10000,-141.4219439,141.4203146,0,0,0,135 +94.99,50.36838703,-3.355820957,10000,-141.4323884,141.4207977,0,0,0,135 +95,50.36837434,-3.35580111,10000,-141.4323881,141.4217262,0,0,0,135 +95.01,50.36836164,-3.355781264,10000,-141.421943,141.4226546,0,0,0,135 +95.02,50.36834895,-3.355761417,10000,-141.4149796,141.422915,0,0,0,135 +95.03,50.36833626,-3.35574157,10000,-141.4184608,141.4216167,0,0,0,135 +95.04,50.36832356,-3.355721724,10000,-141.4184605,141.419873,0,0,0,135 +95.05,50.36831087,-3.355701878,10000,-141.4149786,141.419688,0,0,0,135 +95.06,50.36829818,-3.355682032,10000,-141.4184599,141.4208391,0,0,0,135 +95.07,50.36828548,-3.355662185,10000,-141.4184596,141.4217676,0,0,0,135 +95.08,50.36827279,-3.355642339,10000,-141.4149777,141.422028,0,0,0,135 +95.09,50.3682601,-3.355622492,10000,-141.4219405,141.4220657,0,0,0,135 +95.1,50.3682474,-3.355602646,10000,-141.432385,141.4221035,0,0,0,135 +95.11,50.36823471,-3.355582799,10000,-141.4323847,141.4221412,0,0,0,135 +95.12,50.36822201,-3.355562953,10000,-141.4219396,141.4219562,0,0,0,135 +95.13,50.36820932,-3.355543106,10000,-141.4149762,141.4211032,0,0,0,135 +95.14,50.36819663,-3.35552326,10000,-141.4184574,141.4200275,0,0,0,135 +95.15,50.36818393,-3.355503414,10000,-141.4184571,141.4200653,0,0,0,135 +95.16,50.36817124,-3.355483568,10000,-141.4149752,141.4209937,0,0,0,135 +95.17,50.36815855,-3.355463721,10000,-141.4219381,141.4212541,0,0,0,135 +95.18,50.36814585,-3.355443875,10000,-141.4323825,141.4210692,0,0,0,135 +95.19,50.36813316,-3.355424029,10000,-141.4323822,141.4215523,0,0,0,135 +95.2,50.36812046,-3.355404182,10000,-141.4219371,141.422258,0,0,0,135 +95.21,50.36810777,-3.355384336,10000,-141.4149737,141.4222958,0,0,0,135 +95.22,50.36809508,-3.355364489,10000,-141.4184549,141.4216655,0,0,0,135 +95.23,50.36808238,-3.355344643,10000,-141.4184546,141.4212578,0,0,0,135 +95.24,50.36806969,-3.355324797,10000,-141.4149727,141.4215182,0,0,0,135 +95.25,50.368057,-3.35530495,10000,-141.4219356,141.421556,0,0,0,135 +95.26,50.3680443,-3.355285104,10000,-141.43238,141.421371,0,0,0,135 +95.27,50.36803161,-3.355265258,10000,-141.4323797,141.4216314,0,0,0,135 +95.28,50.36801891,-3.355245411,10000,-141.4219347,141.4216691,0,0,0,135 +95.29,50.36800622,-3.355225565,10000,-141.4149712,141.4214842,0,0,0,135 +95.3,50.36799353,-3.355205719,10000,-141.4184525,141.4217446,0,0,0,135 +95.31,50.36798083,-3.355185872,10000,-141.4184522,141.4215596,0,0,0,135 +95.32,50.36796814,-3.355166026,10000,-141.4149703,141.4207066,0,0,0,135 +95.33,50.36795545,-3.35514618,10000,-141.4184515,141.4207444,0,0,0,135 +95.34,50.36794275,-3.355126334,10000,-141.4184512,141.4216728,0,0,0,135 +95.35,50.36793006,-3.355106487,10000,-141.4149693,141.4219332,0,0,0,135 +95.36,50.36791737,-3.355086641,10000,-141.4219322,141.4217483,0,0,0,135 +95.37,50.36790467,-3.355066795,10000,-141.4323766,141.4220087,0,0,0,135 +95.38,50.36789198,-3.355046948,10000,-141.4323763,141.4218237,0,0,0,135 +95.39,50.36787928,-3.355027102,10000,-141.4219313,141.420748,0,0,0,135 +95.4,50.36786659,-3.355007256,10000,-141.4149678,141.4201177,0,0,0,135 +95.41,50.3678539,-3.35498741,10000,-141.418449,141.4208235,0,0,0,135 +95.42,50.3678412,-3.354967564,10000,-141.4184487,141.4219746,0,0,0,135 +95.43,50.36782851,-3.354947717,10000,-141.4149669,141.4220124,0,0,0,135 +95.44,50.36781582,-3.354927871,10000,-141.4219297,141.4209367,0,0,0,135 +95.45,50.36780312,-3.354908025,10000,-141.4323741,141.4200837,0,0,0,135 +95.46,50.36779043,-3.354888179,10000,-141.4323738,141.4201214,0,0,0,135 +95.47,50.36777773,-3.354868333,10000,-141.4219288,141.4210499,0,0,0,135 +95.48,50.36776504,-3.354848487,10000,-141.4149653,141.422201,0,0,0,135 +95.49,50.36775235,-3.35482864,10000,-141.4184466,141.4222387,0,0,0,135 +95.5,50.36773965,-3.354808794,10000,-141.4184463,141.421163,0,0,0,135 +95.51,50.36772696,-3.354788948,10000,-141.4149644,141.42031,0,0,0,135 +95.52,50.36771427,-3.354769102,10000,-141.4184456,141.4203477,0,0,0,135 +95.53,50.36770157,-3.354749256,10000,-141.4184453,141.4212762,0,0,0,135 +95.54,50.36768888,-3.35472941,10000,-141.4149635,141.4224273,0,0,0,135 +95.55,50.36767619,-3.354709563,10000,-141.4219263,141.4224651,0,0,0,135 +95.56,50.36766349,-3.354689717,10000,-141.4323707,141.4213894,0,0,0,135 +95.57,50.3676508,-3.354669871,10000,-141.4323704,141.4205364,0,0,0,135 +95.58,50.3676381,-3.354650025,10000,-141.4219254,141.4203514,0,0,0,135 +95.59,50.36762541,-3.354630179,10000,-141.4149619,141.4203891,0,0,0,135 +95.6,50.36761272,-3.354610333,10000,-141.4184432,141.4206496,0,0,0,135 +95.61,50.36760002,-3.354590487,10000,-141.4184429,141.421578,0,0,0,135 +95.62,50.36758733,-3.354570641,10000,-141.414961,141.4227292,0,0,0,135 +95.63,50.36757464,-3.354550794,10000,-141.4219238,141.4227669,0,0,0,135 +95.64,50.36756194,-3.354530948,10000,-141.4323682,141.4216912,0,0,0,135 +95.65,50.36754925,-3.354511102,10000,-141.432368,141.4208382,0,0,0,135 +95.66,50.36753655,-3.354491256,10000,-141.4219229,141.4206532,0,0,0,135 +95.67,50.36752386,-3.35447141,10000,-141.4149594,141.420691,0,0,0,135 +95.68,50.36751117,-3.354451564,10000,-141.4184407,141.4207287,0,0,0,135 +95.69,50.36749847,-3.354431718,10000,-141.4184404,141.4207664,0,0,0,135 +95.7,50.36748578,-3.354411872,10000,-141.4149585,141.4210268,0,0,0,135 +95.71,50.36747309,-3.354392026,10000,-141.4219214,141.4219553,0,0,0,135 +95.72,50.36746039,-3.35437218,10000,-141.4323658,141.4231064,0,0,0,135 +95.73,50.3674477,-3.354352333,10000,-141.4323655,141.4231442,0,0,0,135 +95.74,50.367435,-3.354332487,10000,-141.4219204,141.4220685,0,0,0,135 +95.75,50.36742231,-3.354312641,10000,-141.4149569,141.4212155,0,0,0,135 +95.76,50.36740962,-3.354292795,10000,-141.4184382,141.4210305,0,0,0,135 +95.77,50.36739692,-3.354272949,10000,-141.4184379,141.4210682,0,0,0,135 +95.78,50.36738423,-3.354253103,10000,-141.414956,141.4211059,0,0,0,135 +95.79,50.36737154,-3.354233257,10000,-141.4184373,141.4211437,0,0,0,135 +95.8,50.36735884,-3.354213411,10000,-141.418437,141.4211814,0,0,0,135 +95.81,50.36734615,-3.354193565,10000,-141.4149551,141.4212191,0,0,0,135 +95.82,50.36733346,-3.354173719,10000,-141.4219179,141.4212568,0,0,0,135 +95.83,50.36732076,-3.354153873,10000,-141.4323624,141.4212946,0,0,0,135 +95.84,50.36730807,-3.354134027,10000,-141.4323621,141.4213323,0,0,0,135 +95.85,50.36729537,-3.354114181,10000,-141.421917,141.42137,0,0,0,135 +95.86,50.36728268,-3.354094335,10000,-141.4149535,141.4214077,0,0,0,135 +95.87,50.36726999,-3.354074489,10000,-141.4184348,141.4214455,0,0,0,135 +95.88,50.36725729,-3.354054643,10000,-141.4184345,141.4214832,0,0,0,135 +95.89,50.3672446,-3.354034797,10000,-141.4149526,141.4215209,0,0,0,135 +95.9,50.36723191,-3.354014951,10000,-141.4219155,141.4215586,0,0,0,135 +95.91,50.36721921,-3.353995105,10000,-141.4323599,141.4215964,0,0,0,135 +95.92,50.36720652,-3.353975259,10000,-141.4323596,141.4216341,0,0,0,135 +95.93,50.36719382,-3.353955413,10000,-141.4219145,141.4216718,0,0,0,135 +95.94,50.36718113,-3.353935567,10000,-141.414951,141.4214869,0,0,0,135 +95.95,50.36716844,-3.353915721,10000,-141.4184323,141.4208565,0,0,0,135 +95.96,50.36715574,-3.353895875,10000,-141.418432,141.4206716,0,0,0,135 +95.97,50.36714305,-3.35387603,10000,-141.4149501,141.4216,0,0,0,135 +95.98,50.36713036,-3.353856183,10000,-141.421913,141.4218605,0,0,0,135 +95.99,50.36711766,-3.353836337,10000,-141.4323574,141.4205621,0,0,0,135 +96,50.36710497,-3.353816492,10000,-141.4323571,141.4199317,0,0,0,135 +96.01,50.36709227,-3.353796646,10000,-141.421912,141.4208602,0,0,0,135 +96.02,50.36707958,-3.3537768,10000,-141.4149486,141.4217887,0,0,0,135 +96.03,50.36706689,-3.353756954,10000,-141.4184299,141.4220491,0,0,0,135 +96.04,50.36705419,-3.353737108,10000,-141.4184295,141.4220868,0,0,0,135 +96.05,50.3670415,-3.353717262,10000,-141.4149476,141.4219019,0,0,0,135 +96.06,50.36702881,-3.353697416,10000,-141.4184289,141.4210488,0,0,0,135 +96.07,50.36701611,-3.35367757,10000,-141.4184286,141.4199731,0,0,0,135 +96.08,50.36700342,-3.353657725,10000,-141.4149467,141.4200108,0,0,0,135 +96.09,50.36699073,-3.353637879,10000,-141.4219096,141.421162,0,0,0,135 +96.1,50.36697803,-3.353618033,10000,-141.432354,141.4220905,0,0,0,135 +96.11,50.36696534,-3.353598187,10000,-141.4323537,141.4223509,0,0,0,135 +96.12,50.36695264,-3.353578341,10000,-141.4219086,141.4221659,0,0,0,135 +96.13,50.36693995,-3.353558495,10000,-141.4149452,141.4215356,0,0,0,135 +96.14,50.36692726,-3.353538649,10000,-141.4184265,141.4211279,0,0,0,135 +96.15,50.36691456,-3.353518804,10000,-141.4184261,141.4213884,0,0,0,135 +96.16,50.36690187,-3.353498957,10000,-141.4149442,141.4214261,0,0,0,135 +96.17,50.36688918,-3.353479112,10000,-141.4219071,141.4212411,0,0,0,135 +96.18,50.36687648,-3.353459266,10000,-141.4323515,141.4215015,0,0,0,135 +96.19,50.36686379,-3.35343942,10000,-141.4323512,141.4213166,0,0,0,135 +96.2,50.36685109,-3.353419574,10000,-141.4219062,141.4204636,0,0,0,135 +96.21,50.3668384,-3.353399729,10000,-141.4149427,141.4205013,0,0,0,135 +96.22,50.36682571,-3.353379883,10000,-141.4184239,141.4216524,0,0,0,135 +96.23,50.36681301,-3.353360037,10000,-141.4184236,141.4223582,0,0,0,135 +96.24,50.36680032,-3.353340191,10000,-141.4149418,141.4217279,0,0,0,135 +96.25,50.36678763,-3.353320345,10000,-141.418423,141.4206522,0,0,0,135 +96.26,50.36677493,-3.3533005,10000,-141.4184227,141.4206899,0,0,0,135 +96.27,50.36676224,-3.353280654,10000,-141.4149408,141.4218411,0,0,0,135 +96.28,50.36674955,-3.353260808,10000,-141.4219037,141.4225469,0,0,0,135 +96.29,50.36673685,-3.353240962,10000,-141.4323481,141.4219165,0,0,0,135 +96.3,50.36672416,-3.353221116,10000,-141.4323478,141.4208408,0,0,0,135 +96.31,50.36671146,-3.353201271,10000,-141.4219028,141.4208785,0,0,0,135 +96.32,50.36669877,-3.353181425,10000,-141.4149393,141.421807,0,0,0,135 +96.33,50.36668608,-3.353161579,10000,-141.4184205,141.4218447,0,0,0,135 +96.34,50.36667338,-3.353141733,10000,-141.4184202,141.4209917,0,0,0,135 +96.35,50.36666069,-3.353121888,10000,-141.4149383,141.4210294,0,0,0,135 +96.36,50.366648,-3.353102042,10000,-141.4219012,141.4219579,0,0,0,135 +96.37,50.3666353,-3.353082196,10000,-141.4323456,141.4219956,0,0,0,135 +96.38,50.36662261,-3.35306235,10000,-141.4323453,141.4211426,0,0,0,135 +96.39,50.36660991,-3.353042505,10000,-141.4219003,141.4209576,0,0,0,135 +96.4,50.36659722,-3.353022659,10000,-141.4149368,141.4212181,0,0,0,135 +96.41,50.36658453,-3.353002813,10000,-141.4184181,141.4210331,0,0,0,135 +96.42,50.36657183,-3.352982968,10000,-141.4184178,141.4210708,0,0,0,135 +96.43,50.36655914,-3.352963122,10000,-141.4149359,141.4213312,0,0,0,135 +96.44,50.36654645,-3.352943276,10000,-141.4218987,141.4211463,0,0,0,135 +96.45,50.36653375,-3.352923431,10000,-141.4323432,141.421184,0,0,0,135 +96.46,50.36652106,-3.352903585,10000,-141.4323428,141.4214444,0,0,0,135 +96.47,50.36650836,-3.352883739,10000,-141.4218978,141.4212594,0,0,0,135 +96.48,50.36649567,-3.352863894,10000,-141.4149343,141.4212972,0,0,0,135 +96.49,50.36648298,-3.352844048,10000,-141.4184156,141.4215576,0,0,0,135 +96.5,50.36647028,-3.352824202,10000,-141.4184153,141.4211499,0,0,0,135 +96.51,50.36645759,-3.352804357,10000,-141.4149334,141.4205196,0,0,0,135 +96.52,50.3664449,-3.352784511,10000,-141.4218962,141.4205573,0,0,0,135 +96.53,50.3664322,-3.352764666,10000,-141.4323407,141.4214858,0,0,0,135 +96.54,50.36641951,-3.35274482,10000,-141.4323404,141.422637,0,0,0,135 +96.55,50.36640681,-3.352724974,10000,-141.4218953,141.4226747,0,0,0,135 +96.56,50.36639412,-3.352705128,10000,-141.4149319,141.421599,0,0,0,135 +96.57,50.36638143,-3.352685283,10000,-141.4184131,141.4207459,0,0,0,135 +96.58,50.36636873,-3.352665437,10000,-141.4184128,141.4207837,0,0,0,135 +96.59,50.36635604,-3.352645592,10000,-141.4149309,141.4214894,0,0,0,135 +96.6,50.36634335,-3.352625746,10000,-141.4184122,141.4219725,0,0,0,135 +96.61,50.36633065,-3.3526059,10000,-141.4184119,141.4215649,0,0,0,135 +96.62,50.36631796,-3.352586055,10000,-141.41493,141.4209345,0,0,0,135 +96.63,50.36630527,-3.352566209,10000,-141.4218928,141.4209723,0,0,0,135 +96.64,50.36629257,-3.352546364,10000,-141.4323373,141.4216781,0,0,0,135 +96.65,50.36627988,-3.352526518,10000,-141.4323369,141.4221612,0,0,0,135 +96.66,50.36626718,-3.352506672,10000,-141.4218919,141.4217535,0,0,0,135 +96.67,50.36625449,-3.352486827,10000,-141.4149284,141.4211232,0,0,0,135 +96.68,50.3662418,-3.352466981,10000,-141.4184097,141.4209382,0,0,0,135 +96.69,50.3662291,-3.352447136,10000,-141.4184094,141.4209759,0,0,0,135 +96.7,50.36621641,-3.35242729,10000,-141.4149275,141.4210137,0,0,0,135 +96.71,50.36620372,-3.352407445,10000,-141.4218903,141.4210514,0,0,0,135 +96.72,50.36619102,-3.352387599,10000,-141.4323348,141.4210891,0,0,0,135 +96.73,50.36617833,-3.352367754,10000,-141.4323345,141.4211268,0,0,0,135 +96.74,50.36616563,-3.352347908,10000,-141.4218894,141.4211646,0,0,0,135 +96.75,50.36615294,-3.352328063,10000,-141.4149259,141.4212023,0,0,0,135 +96.76,50.36614025,-3.352308217,10000,-141.4184072,141.4214627,0,0,0,135 +96.77,50.36612755,-3.352288372,10000,-141.4184069,141.4221685,0,0,0,135 +96.78,50.36611486,-3.352268526,10000,-141.414925,141.4226516,0,0,0,135 +96.79,50.36610217,-3.35224868,10000,-141.4184063,141.4222439,0,0,0,135 +96.8,50.36608947,-3.352228835,10000,-141.418406,141.4213909,0,0,0,135 +96.81,50.36607678,-3.352208989,10000,-141.4149241,141.4205379,0,0,0,135 +96.82,50.36606409,-3.352189144,10000,-141.4218869,141.4201302,0,0,0,135 +96.83,50.36605139,-3.352169299,10000,-141.4323314,141.4206133,0,0,0,135 +96.84,50.3660387,-3.352149453,10000,-141.4323311,141.4213191,0,0,0,135 +96.85,50.366026,-3.352129608,10000,-141.421886,141.4215795,0,0,0,135 +96.86,50.36601331,-3.352109762,10000,-141.4149225,141.4216172,0,0,0,135 +96.87,50.36600062,-3.352089917,10000,-141.4184038,141.421655,0,0,0,135 +96.88,50.36598792,-3.352070071,10000,-141.4184035,141.4216927,0,0,0,135 +96.89,50.36597523,-3.352050226,10000,-141.4149216,141.4215077,0,0,0,135 +96.9,50.36596254,-3.35203038,10000,-141.4218845,141.4208774,0,0,0,135 +96.91,50.36594984,-3.352010535,10000,-141.4323289,141.4204697,0,0,0,135 +96.92,50.36593715,-3.35199069,10000,-141.4323286,141.4209528,0,0,0,135 +96.93,50.36592445,-3.351970844,10000,-141.4218835,141.4216586,0,0,0,135 +96.94,50.36591176,-3.351950999,10000,-141.4149201,141.421919,0,0,0,135 +96.95,50.36589907,-3.351931153,10000,-141.4184013,141.4219568,0,0,0,135 +96.96,50.36588637,-3.351911308,10000,-141.418401,141.4219945,0,0,0,135 +96.97,50.36587368,-3.351891462,10000,-141.4149191,141.4220322,0,0,0,135 +96.98,50.36586099,-3.351871617,10000,-141.421882,141.4218472,0,0,0,135 +96.99,50.36584829,-3.351851771,10000,-141.4323264,141.4212169,0,0,0,135 +97,50.3658356,-3.351831926,10000,-141.4323261,141.4208092,0,0,0,135 +97.01,50.3658229,-3.351812081,10000,-141.421881,141.4210696,0,0,0,135 +97.02,50.36581021,-3.351792235,10000,-141.4149176,141.4211074,0,0,0,135 +97.03,50.36579752,-3.35177239,10000,-141.4183989,141.4209224,0,0,0,135 +97.04,50.36578482,-3.351752545,10000,-141.4183985,141.4211828,0,0,0,135 +97.05,50.36577213,-3.351732699,10000,-141.4149167,141.4212205,0,0,0,135 +97.06,50.36575944,-3.351712854,10000,-141.4183979,141.4210356,0,0,0,135 +97.07,50.36574674,-3.351693009,10000,-141.4183976,141.421296,0,0,0,135 +97.08,50.36573405,-3.351673163,10000,-141.4149157,141.4213337,0,0,0,135 +97.09,50.36572136,-3.351653318,10000,-141.4218786,141.4211487,0,0,0,135 +97.1,50.36570866,-3.351633473,10000,-141.432323,141.4214092,0,0,0,135 +97.11,50.36569597,-3.351613627,10000,-141.4323227,141.4214469,0,0,0,135 +97.12,50.36568327,-3.351593782,10000,-141.4218776,141.4212619,0,0,0,135 +97.13,50.36567058,-3.351573937,10000,-141.4149142,141.4215223,0,0,0,135 +97.14,50.36565789,-3.351554091,10000,-141.4183955,141.4215601,0,0,0,135 +97.15,50.36564519,-3.351534246,10000,-141.4183952,141.4213751,0,0,0,135 +97.16,50.3656325,-3.351514401,10000,-141.4149133,141.4216355,0,0,0,135 +97.17,50.36561981,-3.351494555,10000,-141.4218761,141.4214505,0,0,0,135 +97.18,50.36560711,-3.35147471,10000,-141.4323205,141.4205975,0,0,0,135 +97.19,50.36559442,-3.351454865,10000,-141.4323202,141.4206352,0,0,0,135 +97.2,50.36558172,-3.35143502,10000,-141.4218752,141.4215637,0,0,0,135 +97.21,50.36556903,-3.351415174,10000,-141.4149117,141.4216014,0,0,0,135 +97.22,50.36555634,-3.351395329,10000,-141.418393,141.4207484,0,0,0,135 +97.23,50.36554364,-3.351375484,10000,-141.4183926,141.4207861,0,0,0,135 +97.24,50.36553095,-3.351355639,10000,-141.4149107,141.4217146,0,0,0,135 +97.25,50.36551826,-3.351335793,10000,-141.4218736,141.4217523,0,0,0,135 +97.26,50.36550556,-3.351315948,10000,-141.4323181,141.4208993,0,0,0,135 +97.27,50.36549287,-3.351296103,10000,-141.4323178,141.420937,0,0,0,135 +97.28,50.36548017,-3.351276258,10000,-141.4218727,141.4218655,0,0,0,135 +97.29,50.36546748,-3.351256412,10000,-141.4149092,141.4219032,0,0,0,135 +97.3,50.36545479,-3.351236567,10000,-141.4183905,141.4210502,0,0,0,135 +97.31,50.36544209,-3.351216722,10000,-141.4183902,141.4210879,0,0,0,135 +97.32,50.3654294,-3.351196877,10000,-141.4149083,141.4220164,0,0,0,135 +97.33,50.36541671,-3.351177031,10000,-141.4183896,141.4220541,0,0,0,135 +97.34,50.36540401,-3.351157186,10000,-141.4183892,141.4209784,0,0,0,135 +97.35,50.36539132,-3.351137341,10000,-141.4149073,141.420348,0,0,0,135 +97.36,50.36537863,-3.351117496,10000,-141.4218702,141.4210538,0,0,0,135 +97.37,50.36536593,-3.351097651,10000,-141.4323147,141.422205,0,0,0,135 +97.38,50.36535324,-3.351077805,10000,-141.4323144,141.4222427,0,0,0,135 +97.39,50.36534054,-3.35105796,10000,-141.4218693,141.421167,0,0,0,135 +97.4,50.36532785,-3.351038115,10000,-141.4149058,141.4205366,0,0,0,135 +97.41,50.36531516,-3.35101827,10000,-141.4183871,141.4212424,0,0,0,135 +97.42,50.36530246,-3.350998425,10000,-141.4183868,141.4223936,0,0,0,135 +97.43,50.36528977,-3.350978579,10000,-141.4149049,141.4224313,0,0,0,135 +97.44,50.36527708,-3.350958734,10000,-141.4218677,141.4213556,0,0,0,135 +97.45,50.36526438,-3.350938889,10000,-141.4323122,141.4205025,0,0,0,135 +97.46,50.36525169,-3.350919044,10000,-141.4323118,141.4203176,0,0,0,135 +97.47,50.36523899,-3.350899199,10000,-141.4218668,141.420578,0,0,0,135 +97.48,50.3652263,-3.350879354,10000,-141.4149033,141.4215065,0,0,0,135 +97.49,50.36521361,-3.350859509,10000,-141.4183846,141.4226577,0,0,0,135 +97.5,50.36520091,-3.350839663,10000,-141.4183843,141.4226954,0,0,0,135 +97.51,50.36518822,-3.350819818,10000,-141.4149024,141.4216197,0,0,0,135 +97.52,50.36517553,-3.350799973,10000,-141.4218652,141.4207666,0,0,0,135 +97.53,50.36516283,-3.350780128,10000,-141.4323097,141.4205816,0,0,0,135 +97.54,50.36515014,-3.350760283,10000,-141.4323094,141.4206194,0,0,0,135 +97.55,50.36513744,-3.350740438,10000,-141.4218643,141.4208798,0,0,0,135 +97.56,50.36512475,-3.350720593,10000,-141.4149009,141.4218083,0,0,0,135 +97.57,50.36511206,-3.350700748,10000,-141.4183821,141.4229595,0,0,0,135 +97.58,50.36509936,-3.350680902,10000,-141.4183818,141.4229972,0,0,0,135 +97.59,50.36508667,-3.350661057,10000,-141.4148999,141.4216987,0,0,0,135 +97.6,50.36507398,-3.350641212,10000,-141.4183812,141.4201776,0,0,0,135 +97.61,50.36506128,-3.350621367,10000,-141.4183809,141.4197699,0,0,0,135 +97.62,50.36504859,-3.350601523,10000,-141.414899,141.4209211,0,0,0,135 +97.63,50.3650359,-3.350581677,10000,-141.4218619,141.4220723,0,0,0,135 +97.64,50.3650232,-3.350561832,10000,-141.4323063,141.4218874,0,0,0,135 +97.65,50.36501051,-3.350541987,10000,-141.432306,141.421257,0,0,0,135 +97.66,50.36499781,-3.350522142,10000,-141.4218609,141.421072,0,0,0,135 +97.67,50.36498512,-3.350502297,10000,-141.4148974,141.4211097,0,0,0,135 +97.68,50.36497243,-3.350482452,10000,-141.4183787,141.4211475,0,0,0,135 +97.69,50.36495973,-3.350462607,10000,-141.4183784,141.4211852,0,0,0,135 +97.7,50.36494704,-3.350442762,10000,-141.4148965,141.4212229,0,0,0,135 +97.71,50.36493435,-3.350422917,10000,-141.4218594,141.4212606,0,0,0,135 +97.72,50.36492165,-3.350403072,10000,-141.4323038,141.4212984,0,0,0,135 +97.73,50.36490896,-3.350383227,10000,-141.4323035,141.4213361,0,0,0,135 +97.74,50.36489626,-3.350363382,10000,-141.4218584,141.4213738,0,0,0,135 +97.75,50.36488357,-3.350343537,10000,-141.414895,141.4214115,0,0,0,135 +97.76,50.36487088,-3.350323692,10000,-141.4183762,141.4214493,0,0,0,135 +97.77,50.36485818,-3.350303847,10000,-141.4183759,141.421487,0,0,0,135 +97.78,50.36484549,-3.350284002,10000,-141.414894,141.4215247,0,0,0,135 +97.79,50.3648328,-3.350264157,10000,-141.4218569,141.4215624,0,0,0,135 +97.8,50.3648201,-3.350244312,10000,-141.4323013,141.4216001,0,0,0,135 +97.81,50.36480741,-3.350224467,10000,-141.432301,141.4216379,0,0,0,135 +97.82,50.36479471,-3.350204622,10000,-141.4218559,141.4216756,0,0,0,135 +97.83,50.36478202,-3.350184777,10000,-141.4148925,141.4217133,0,0,0,135 +97.84,50.36476933,-3.350164932,10000,-141.4183738,141.421751,0,0,0,135 +97.85,50.36475663,-3.350145087,10000,-141.4183735,141.4217888,0,0,0,135 +97.86,50.36474394,-3.350125242,10000,-141.4148916,141.4216038,0,0,0,135 +97.87,50.36473125,-3.350105397,10000,-141.4183728,141.4207507,0,0,0,135 +97.88,50.36471855,-3.350085552,10000,-141.4183725,141.4196749,0,0,0,135 +97.89,50.36470586,-3.350065708,10000,-141.4148906,141.4197127,0,0,0,135 +97.9,50.36469317,-3.350045863,10000,-141.4218535,141.4208639,0,0,0,135 +97.91,50.36468047,-3.350026018,10000,-141.4322979,141.4217924,0,0,0,135 +97.92,50.36466778,-3.350006173,10000,-141.4322976,141.4220528,0,0,0,135 +97.93,50.36465508,-3.349986328,10000,-141.4218525,141.4220905,0,0,0,135 +97.94,50.36464239,-3.349966483,10000,-141.4148891,141.4221283,0,0,0,135 +97.95,50.3646297,-3.349946638,10000,-141.4183703,141.4219433,0,0,0,135 +97.96,50.364617,-3.349926793,10000,-141.41837,141.4210902,0,0,0,135 +97.97,50.36460431,-3.349906948,10000,-141.4148882,141.4200144,0,0,0,135 +97.98,50.36459162,-3.349887104,10000,-141.421851,141.4200522,0,0,0,135 +97.99,50.36457892,-3.349867259,10000,-141.4322954,141.4212034,0,0,0,135 +98,50.36456623,-3.349847414,10000,-141.4322951,141.4221319,0,0,0,135 +98.01,50.36455353,-3.349827569,10000,-141.4218501,141.4223923,0,0,0,135 +98.02,50.36454084,-3.349807724,10000,-141.4148866,141.4222073,0,0,0,135 +98.03,50.36452815,-3.349787879,10000,-141.4183679,141.4213543,0,0,0,135 +98.04,50.36451545,-3.349768034,10000,-141.4183676,141.4202785,0,0,0,135 +98.05,50.36450276,-3.34974819,10000,-141.4148857,141.4203162,0,0,0,135 +98.06,50.36449007,-3.349728345,10000,-141.4218485,141.4214674,0,0,0,135 +98.07,50.36447737,-3.3497085,10000,-141.432293,141.422396,0,0,0,135 +98.08,50.36446468,-3.349688655,10000,-141.4322927,141.4224337,0,0,0,135 +98.09,50.36445198,-3.34966881,10000,-141.4218476,141.4215806,0,0,0,135 +98.1,50.36443929,-3.349648965,10000,-141.4148841,141.4205048,0,0,0,135 +98.11,50.3644266,-3.349629121,10000,-141.4183654,141.4205426,0,0,0,135 +98.12,50.3644139,-3.349609276,10000,-141.4183651,141.4214711,0,0,0,135 +98.13,50.36440121,-3.349589431,10000,-141.4148832,141.4215088,0,0,0,135 +98.14,50.36438852,-3.349569586,10000,-141.4183645,141.4206557,0,0,0,135 +98.15,50.36437582,-3.349549742,10000,-141.4183642,141.4206934,0,0,0,135 +98.16,50.36436313,-3.349529897,10000,-141.4148822,141.4218447,0,0,0,135 +98.17,50.36435044,-3.349510052,10000,-141.4218451,141.4225505,0,0,0,135 +98.18,50.36433774,-3.349490207,10000,-141.4322895,141.4219201,0,0,0,135 +98.19,50.36432505,-3.349470362,10000,-141.4322892,141.4208443,0,0,0,135 +98.2,50.36431235,-3.349450518,10000,-141.4218442,141.4206594,0,0,0,135 +98.21,50.36429966,-3.349430673,10000,-141.4148807,141.4209198,0,0,0,135 +98.22,50.36428697,-3.349410828,10000,-141.418362,141.4207348,0,0,0,135 +98.23,50.36427427,-3.349390984,10000,-141.4183617,141.4209952,0,0,0,135 +98.24,50.36426158,-3.349371139,10000,-141.4148798,141.4221464,0,0,0,135 +98.25,50.36424889,-3.349351294,10000,-141.4218426,141.4228523,0,0,0,135 +98.26,50.36423619,-3.349331449,10000,-141.4322871,141.4222219,0,0,0,135 +98.27,50.3642235,-3.349311604,10000,-141.4322868,141.4209234,0,0,0,135 +98.28,50.3642108,-3.34929176,10000,-141.4218417,141.4200703,0,0,0,135 +98.29,50.36419811,-3.349271915,10000,-141.4148782,141.420108,0,0,0,135 +98.3,50.36418542,-3.349252071,10000,-141.4183595,141.4210366,0,0,0,135 +98.31,50.36417272,-3.349232226,10000,-141.4183592,141.4221878,0,0,0,135 +98.32,50.36416003,-3.349212381,10000,-141.4148773,141.4222255,0,0,0,135 +98.33,50.36414734,-3.349192536,10000,-141.4218402,141.4213724,0,0,0,135 +98.34,50.36413464,-3.349172692,10000,-141.4322846,141.4214102,0,0,0,135 +98.35,50.36412195,-3.349152847,10000,-141.4322843,141.4223387,0,0,0,135 +98.36,50.36410925,-3.349133002,10000,-141.4218392,141.4223764,0,0,0,135 +98.37,50.36409656,-3.349113157,10000,-141.4148757,141.4213006,0,0,0,135 +98.38,50.36408387,-3.349093313,10000,-141.418357,141.4204475,0,0,0,135 +98.39,50.36407117,-3.349073468,10000,-141.4183567,141.4204853,0,0,0,135 +98.4,50.36405848,-3.349053624,10000,-141.4148748,141.4211911,0,0,0,135 +98.41,50.36404579,-3.349033779,10000,-141.4218377,141.4216742,0,0,0,135 +98.42,50.36403309,-3.349013934,10000,-141.4322821,141.4212665,0,0,0,135 +98.43,50.3640204,-3.34899409,10000,-141.4322818,141.4206361,0,0,0,135 +98.44,50.3640077,-3.348974245,10000,-141.4218368,141.4206739,0,0,0,135 +98.45,50.36399501,-3.348954401,10000,-141.4148733,141.4213797,0,0,0,135 +98.46,50.36398232,-3.348934556,10000,-141.4183545,141.4218628,0,0,0,135 +98.47,50.36396962,-3.348914711,10000,-141.4183542,141.4214551,0,0,0,135 +98.48,50.36395693,-3.348894867,10000,-141.4148723,141.4208248,0,0,0,135 +98.49,50.36394424,-3.348875022,10000,-141.4183536,141.4208625,0,0,0,135 +98.5,50.36393154,-3.348855178,10000,-141.4183533,141.4215683,0,0,0,135 +98.51,50.36391885,-3.348835333,10000,-141.4148714,141.4220514,0,0,0,135 +98.52,50.36390616,-3.348815488,10000,-141.4218343,141.4218664,0,0,0,135 +98.53,50.36389346,-3.348795644,10000,-141.4322787,141.4219042,0,0,0,135 +98.54,50.36388077,-3.348775799,10000,-141.4322784,141.4219419,0,0,0,135 +98.55,50.36386807,-3.348755954,10000,-141.4218333,141.4208661,0,0,0,135 +98.56,50.36385538,-3.34873611,10000,-141.4148699,141.420013,0,0,0,135 +98.57,50.36384269,-3.348716266,10000,-141.4183511,141.4209415,0,0,0,135 +98.58,50.36382999,-3.348696421,10000,-141.4183508,141.4220928,0,0,0,135 +98.59,50.3638173,-3.348676576,10000,-141.4148689,141.4221305,0,0,0,135 +98.6,50.36380461,-3.348656732,10000,-141.4218318,141.4221682,0,0,0,135 +98.61,50.36379191,-3.348636887,10000,-141.4322762,141.4222059,0,0,0,135 +98.62,50.36377922,-3.348617042,10000,-141.4322759,141.4211302,0,0,0,135 +98.63,50.36376652,-3.348597198,10000,-141.4218309,141.4202771,0,0,0,135 +98.64,50.36375383,-3.348577354,10000,-141.4148674,141.4212056,0,0,0,135 +98.65,50.36374114,-3.348557509,10000,-141.4183486,141.4221341,0,0,0,135 +98.66,50.36372844,-3.348537664,10000,-141.4183483,141.421281,0,0,0,135 +98.67,50.36371575,-3.34851782,10000,-141.4148665,141.4202052,0,0,0,135 +98.68,50.36370306,-3.348497976,10000,-141.4218293,141.4204657,0,0,0,135 +98.69,50.36369036,-3.348478131,10000,-141.4322737,141.4213942,0,0,0,135 +98.7,50.36367767,-3.348458287,10000,-141.4322734,141.4223227,0,0,0,135 +98.71,50.36366497,-3.348438442,10000,-141.4218284,141.4225832,0,0,0,135 +98.72,50.36365228,-3.348418597,10000,-141.4148649,141.4215074,0,0,0,135 +98.73,50.36363959,-3.348398753,10000,-141.4183462,141.4204316,0,0,0,135 +98.74,50.36362689,-3.348378909,10000,-141.4183459,141.420692,0,0,0,135 +98.75,50.3636142,-3.348359064,10000,-141.414864,141.4213978,0,0,0,135 +98.76,50.36360151,-3.34833922,10000,-141.4183452,141.4216582,0,0,0,135 +98.77,50.36358881,-3.348319375,10000,-141.4183449,141.421696,0,0,0,135 +98.78,50.36357612,-3.348299531,10000,-141.4148631,141.4217337,0,0,0,135 +98.79,50.36356343,-3.348279686,10000,-141.4218259,141.4217714,0,0,0,135 +98.8,50.36355073,-3.348259842,10000,-141.4322703,141.4215864,0,0,0,135 +98.81,50.36353804,-3.348239997,10000,-141.43227,141.420956,0,0,0,135 +98.82,50.36352534,-3.348220153,10000,-141.421825,141.4205484,0,0,0,135 +98.83,50.36351265,-3.348200309,10000,-141.4148615,141.4210315,0,0,0,135 +98.84,50.36349996,-3.348180464,10000,-141.4183428,141.4217373,0,0,0,135 +98.85,50.36348726,-3.34816062,10000,-141.4183425,141.421775,0,0,0,135 +98.86,50.36347457,-3.348140775,10000,-141.4148606,141.4211446,0,0,0,135 +98.87,50.36346188,-3.348120931,10000,-141.4218234,141.420737,0,0,0,135 +98.88,50.36344918,-3.348101087,10000,-141.4322679,141.4212201,0,0,0,135 +98.89,50.36343649,-3.348081242,10000,-141.4322675,141.4219259,0,0,0,135 +98.9,50.36342379,-3.348061398,10000,-141.4218225,141.4219636,0,0,0,135 +98.91,50.3634111,-3.348041553,10000,-141.414859,141.4213332,0,0,0,135 +98.92,50.36339841,-3.348021709,10000,-141.4183403,141.4209256,0,0,0,135 +98.93,50.36338571,-3.348001865,10000,-141.41834,141.4214087,0,0,0,135 +98.94,50.36337302,-3.34798202,10000,-141.4148581,141.4221145,0,0,0,135 +98.95,50.36336033,-3.347962176,10000,-141.4218209,141.4221522,0,0,0,135 +98.96,50.36334763,-3.347942331,10000,-141.4322654,141.4212991,0,0,0,135 +98.97,50.36333494,-3.347922487,10000,-141.4322651,141.4202233,0,0,0,135 +98.98,50.36332224,-3.347902643,10000,-141.42182,141.4202611,0,0,0,135 +98.99,50.36330955,-3.347882799,10000,-141.4148566,141.4211896,0,0,0,135 +99,50.36329686,-3.347862954,10000,-141.4183378,141.42145,0,0,0,135 +99.01,50.36328416,-3.34784311,10000,-141.4183375,141.421265,0,0,0,135 +99.02,50.36327147,-3.347823266,10000,-141.4148556,141.4217482,0,0,0,135 +99.03,50.36325878,-3.347803421,10000,-141.4183369,141.4222313,0,0,0,135 +99.04,50.36324608,-3.347783577,10000,-141.4183366,141.4216009,0,0,0,135 +99.05,50.36323339,-3.347763732,10000,-141.4148547,141.4205251,0,0,0,135 +99.06,50.3632207,-3.347743889,10000,-141.4218175,141.4205628,0,0,0,135 +99.07,50.363208,-3.347724044,10000,-141.432262,141.4217141,0,0,0,135 +99.08,50.36319531,-3.3477042,10000,-141.4322617,141.4224199,0,0,0,135 +99.09,50.36318261,-3.347684355,10000,-141.4218166,141.4217895,0,0,0,135 +99.1,50.36316992,-3.347664511,10000,-141.4148532,141.4207137,0,0,0,135 +99.11,50.36315723,-3.347644667,10000,-141.4183344,141.4207514,0,0,0,135 +99.12,50.36314453,-3.347624823,10000,-141.4183341,141.42168,0,0,0,135 +99.13,50.36313184,-3.347604978,10000,-141.4148522,141.4217177,0,0,0,135 +99.14,50.36311915,-3.347585134,10000,-141.4218151,141.4208646,0,0,0,135 +99.15,50.36310645,-3.34756529,10000,-141.4322595,141.4209023,0,0,0,135 +99.16,50.36309376,-3.347545446,10000,-141.4322592,141.4218309,0,0,0,135 +99.17,50.36308106,-3.347525601,10000,-141.4218141,141.4218686,0,0,0,135 +99.18,50.36306837,-3.347505757,10000,-141.4148506,141.4210155,0,0,0,135 +99.19,50.36305568,-3.347485913,10000,-141.4183319,141.4210532,0,0,0,135 +99.2,50.36304298,-3.347466069,10000,-141.4183316,141.4219817,0,0,0,135 +99.21,50.36303029,-3.347446224,10000,-141.4148497,141.4220195,0,0,0,135 +99.22,50.3630176,-3.34742638,10000,-141.4218126,141.4211664,0,0,0,135 +99.23,50.3630049,-3.347406536,10000,-141.432257,141.4209814,0,0,0,135 +99.24,50.36299221,-3.347386692,10000,-141.4322567,141.4212418,0,0,0,135 +99.25,50.36297951,-3.347366847,10000,-141.4218116,141.4210568,0,0,0,135 +99.26,50.36296682,-3.347347004,10000,-141.4148482,141.4210945,0,0,0,135 +99.27,50.36295413,-3.347327159,10000,-141.4183295,141.421355,0,0,0,135 +99.28,50.36294143,-3.347307315,10000,-141.4183291,141.4209473,0,0,0,135 +99.29,50.36292874,-3.347287471,10000,-141.4148472,141.4205396,0,0,0,135 +99.3,50.36291605,-3.347267627,10000,-141.4183285,141.4212454,0,0,0,135 +99.31,50.36290335,-3.347247783,10000,-141.4183282,141.4223967,0,0,0,135 +99.32,50.36289066,-3.347227938,10000,-141.4148463,141.4224344,0,0,0,135 +99.33,50.36287797,-3.347208094,10000,-141.4218092,141.4213586,0,0,0,135 +99.34,50.36286527,-3.34718825,10000,-141.4322536,141.4205055,0,0,0,135 +99.35,50.36285258,-3.347168406,10000,-141.4322533,141.4203205,0,0,0,135 +99.36,50.36283988,-3.347148562,10000,-141.4218082,141.4205809,0,0,0,135 +99.37,50.36282719,-3.347128718,10000,-141.4148448,141.4215094,0,0,0,135 +99.38,50.3628145,-3.347108874,10000,-141.418326,141.4226607,0,0,0,135 +99.39,50.3628018,-3.347089029,10000,-141.4183257,141.4226984,0,0,0,135 +99.4,50.36278911,-3.347069185,10000,-141.4148438,141.4216226,0,0,0,135 +99.41,50.36277642,-3.347049341,10000,-141.4218067,141.4207695,0,0,0,135 +99.42,50.36276372,-3.347029497,10000,-141.4322511,141.4205845,0,0,0,135 +99.43,50.36275103,-3.347009653,10000,-141.4322508,141.4206222,0,0,0,135 +99.44,50.36273833,-3.346989809,10000,-141.4218058,141.42066,0,0,0,135 +99.45,50.36272564,-3.346969965,10000,-141.4148423,141.4206977,0,0,0,135 +99.46,50.36271295,-3.346950121,10000,-141.4183236,141.4209581,0,0,0,135 +99.47,50.36270025,-3.346930277,10000,-141.4183233,141.4218866,0,0,0,135 +99.48,50.36268756,-3.346910433,10000,-141.4148414,141.4230379,0,0,0,135 +99.49,50.36267487,-3.346890588,10000,-141.4218042,141.4230756,0,0,0,135 +99.5,50.36266217,-3.346870744,10000,-141.4322486,141.4219998,0,0,0,135 +99.51,50.36264948,-3.3468509,10000,-141.4322483,141.4211467,0,0,0,135 +99.52,50.36263678,-3.346831056,10000,-141.4218033,141.4209617,0,0,0,135 +99.53,50.36262409,-3.346811212,10000,-141.4148398,141.4209994,0,0,0,135 +99.54,50.3626114,-3.346791368,10000,-141.4183211,141.4210372,0,0,0,135 +99.55,50.3625987,-3.346771524,10000,-141.4183208,141.4210749,0,0,0,135 +99.56,50.36258601,-3.34675168,10000,-141.4148389,141.4211126,0,0,0,135 +99.57,50.36257332,-3.346731836,10000,-141.4218017,141.4211503,0,0,0,135 +99.58,50.36256062,-3.346711992,10000,-141.4322462,141.421188,0,0,0,135 +99.59,50.36254793,-3.346692148,10000,-141.4322458,141.4212258,0,0,0,135 +99.6,50.36253523,-3.346672304,10000,-141.4218008,141.4212635,0,0,0,135 +99.61,50.36252254,-3.34665246,10000,-141.4148373,141.4213012,0,0,0,135 +99.62,50.36250985,-3.346632616,10000,-141.4183186,141.4213389,0,0,0,135 +99.63,50.36249715,-3.346612772,10000,-141.4183183,141.4213766,0,0,0,135 +99.64,50.36248446,-3.346592928,10000,-141.4148364,141.4214143,0,0,0,135 +99.65,50.36247177,-3.346573084,10000,-141.4217992,141.4214521,0,0,0,135 +99.66,50.36245907,-3.34655324,10000,-141.4322437,141.4214898,0,0,0,135 +99.67,50.36244638,-3.346533396,10000,-141.4322434,141.4215275,0,0,0,135 +99.68,50.36243368,-3.346513552,10000,-141.4217983,141.4215652,0,0,0,135 +99.69,50.36242099,-3.346493708,10000,-141.4148349,141.4216029,0,0,0,135 +99.7,50.3624083,-3.346473864,10000,-141.4183161,141.4216407,0,0,0,135 +99.71,50.3623956,-3.34645402,10000,-141.4183158,141.4216784,0,0,0,135 +99.72,50.36238291,-3.346434176,10000,-141.4148339,141.4217161,0,0,0,135 +99.73,50.36237022,-3.346414332,10000,-141.4183152,141.4215311,0,0,0,135 +99.74,50.36235752,-3.346394488,10000,-141.4183149,141.420678,0,0,0,135 +99.75,50.36234483,-3.346374644,10000,-141.414833,141.4198249,0,0,0,135 +99.76,50.36233214,-3.346354801,10000,-141.4217958,141.4205307,0,0,0,135 +99.77,50.36231944,-3.346334957,10000,-141.4322403,141.4219047,0,0,0,135 +99.78,50.36230675,-3.346315112,10000,-141.43224,141.4217197,0,0,0,135 +99.79,50.36229405,-3.346295269,10000,-141.4217949,141.4208666,0,0,0,135 +99.8,50.36228136,-3.346275425,10000,-141.4148315,141.421127,0,0,0,135 +99.81,50.36226867,-3.346255581,10000,-141.4183127,141.4218329,0,0,0,135 +99.82,50.36225597,-3.346235737,10000,-141.4183124,141.4220933,0,0,0,135 +99.83,50.36224328,-3.346215893,10000,-141.4148305,141.422131,0,0,0,135 +99.84,50.36223059,-3.346196049,10000,-141.4217934,141.4221687,0,0,0,135 +99.85,50.36221789,-3.346176205,10000,-141.4322378,141.4219837,0,0,0,135 +99.86,50.3622052,-3.346156361,10000,-141.4322375,141.4211306,0,0,0,135 +99.87,50.3621925,-3.346136517,10000,-141.4217924,141.4200548,0,0,0,135 +99.88,50.36217981,-3.346116674,10000,-141.414829,141.4200925,0,0,0,135 +99.89,50.36216712,-3.34609683,10000,-141.4183102,141.4212438,0,0,0,135 +99.9,50.36215442,-3.346076986,10000,-141.4183099,141.4221723,0,0,0,135 +99.91,50.36214173,-3.346057142,10000,-141.414828,141.4222101,0,0,0,135 +99.92,50.36212904,-3.346037298,10000,-141.4217909,141.4213569,0,0,0,135 +99.93,50.36211634,-3.346017454,10000,-141.4322353,141.4202811,0,0,0,135 +99.94,50.36210365,-3.345997611,10000,-141.432235,141.4203188,0,0,0,135 +99.95,50.36209095,-3.345977767,10000,-141.42179,141.4214701,0,0,0,135 +99.96,50.36207826,-3.345957923,10000,-141.4148265,141.422176,0,0,0,135 +99.97,50.36206557,-3.345938079,10000,-141.4183078,141.4215455,0,0,0,135 +99.98,50.36205287,-3.345918235,10000,-141.4183074,141.4204697,0,0,0,135 +99.99,50.36204018,-3.345898392,10000,-141.4148255,141.4205074,0,0,0,135 +100,50.36202749,-3.345878548,10000,-141.4183068,141.4216587,0,0,0,135 +100.01,50.36201479,-3.345858704,10000,-141.4183065,141.4225873,0,0,0,135 +100.02,50.3620021,-3.34583886,10000,-141.4148246,141.422625,0,0,0,135 +100.03,50.36198941,-3.345819016,10000,-141.4217875,141.4217718,0,0,0,135 +100.04,50.36197671,-3.345799172,10000,-141.4322319,141.420696,0,0,0,135 +100.05,50.36196402,-3.345779329,10000,-141.4322316,141.4207337,0,0,0,135 +100.06,50.36195132,-3.345759485,10000,-141.4217866,141.4216623,0,0,0,135 +100.07,50.36193863,-3.345739641,10000,-141.4148231,141.4217,0,0,0,135 +100.08,50.36192594,-3.345719797,10000,-141.4183043,141.4208469,0,0,0,135 +100.09,50.36191324,-3.345699954,10000,-141.418304,141.4208846,0,0,0,135 +100.1,50.36190055,-3.34568011,10000,-141.4148222,141.4218132,0,0,0,135 +100.11,50.36188786,-3.345660266,10000,-141.421785,141.4218509,0,0,0,135 +100.12,50.36187516,-3.345640422,10000,-141.4322294,141.4209978,0,0,0,135 +100.13,50.36186247,-3.345620579,10000,-141.4322291,141.4208128,0,0,0,135 +100.14,50.36184977,-3.345600735,10000,-141.421784,141.4210732,0,0,0,135 +100.15,50.36183708,-3.345580891,10000,-141.4148206,141.4208882,0,0,0,135 +100.16,50.36182439,-3.345561048,10000,-141.4183019,141.4211486,0,0,0,135 +100.17,50.36181169,-3.345541204,10000,-141.4183016,141.4222999,0,0,0,135 +100.18,50.361799,-3.34552136,10000,-141.4148197,141.4230058,0,0,0,135 +100.19,50.36178631,-3.345501516,10000,-141.4217825,141.4223754,0,0,0,135 +100.2,50.36177361,-3.345481672,10000,-141.4322269,141.4210768,0,0,0,135 +100.21,50.36176092,-3.345461829,10000,-141.4322266,141.4202237,0,0,0,135 +100.22,50.36174822,-3.345441985,10000,-141.4217816,141.4200387,0,0,0,135 +100.23,50.36173553,-3.345422142,10000,-141.4148181,141.4200764,0,0,0,135 +100.24,50.36172284,-3.345402298,10000,-141.4182994,141.4203368,0,0,0,135 +100.25,50.36171014,-3.345382455,10000,-141.4182991,141.4212654,0,0,0,135 +100.26,50.36169745,-3.345362611,10000,-141.4148172,141.4224167,0,0,0,135 +100.27,50.36168476,-3.345342767,10000,-141.4182985,141.4224544,0,0,0,135 +100.28,50.36167206,-3.345322923,10000,-141.4182982,141.4216013,0,0,0,135 +100.29,50.36165937,-3.34530308,10000,-141.4148163,141.4214163,0,0,0,135 +100.3,50.36164668,-3.345283236,10000,-141.4217791,141.4216767,0,0,0,135 +100.31,50.36163398,-3.345263392,10000,-141.4322235,141.4214917,0,0,0,135 +100.32,50.36162129,-3.345243549,10000,-141.4322232,141.4215294,0,0,0,135 +100.33,50.36160859,-3.345223705,10000,-141.4217782,141.4217899,0,0,0,135 +100.34,50.3615959,-3.345203861,10000,-141.4148147,141.4216049,0,0,0,135 +100.35,50.36158321,-3.345184018,10000,-141.418296,141.4216426,0,0,0,135 +100.36,50.36157051,-3.345164174,10000,-141.4182957,141.421903,0,0,0,135 +100.37,50.36155782,-3.34514433,10000,-141.4148138,141.4214953,0,0,0,135 +100.38,50.36154513,-3.345124487,10000,-141.4217766,141.4208649,0,0,0,135 +100.39,50.36153243,-3.345104643,10000,-141.4322211,141.4209026,0,0,0,135 +100.4,50.36151974,-3.3450848,10000,-141.4322208,141.4216085,0,0,0,135 +100.41,50.36150704,-3.345064956,10000,-141.4217757,141.4220916,0,0,0,135 +100.42,50.36149435,-3.345045112,10000,-141.4148122,141.4216839,0,0,0,135 +100.43,50.36148166,-3.345025269,10000,-141.4182935,141.4210535,0,0,0,135 +100.44,50.36146896,-3.345005425,10000,-141.4182932,141.4208685,0,0,0,135 +100.45,50.36145627,-3.344985582,10000,-141.4148113,141.4209062,0,0,0,135 +100.46,50.36144358,-3.344965738,10000,-141.4217742,141.4209439,0,0,0,135 +100.47,50.36143088,-3.344945895,10000,-141.4322186,141.4209816,0,0,0,135 +100.48,50.36141819,-3.344926051,10000,-141.4322183,141.4210194,0,0,0,135 +100.49,50.36140549,-3.344906208,10000,-141.4217732,141.4210571,0,0,0,135 +100.5,50.3613928,-3.344886364,10000,-141.4148098,141.4210948,0,0,0,135 +100.51,50.36138011,-3.344866521,10000,-141.418291,141.4211325,0,0,0,135 +100.52,50.36136741,-3.344846677,10000,-141.4182907,141.4211702,0,0,0,135 +100.53,50.36135472,-3.344826834,10000,-141.4148088,141.4212079,0,0,0,135 +100.54,50.36134203,-3.34480699,10000,-141.4217717,141.4212457,0,0,0,135 +100.55,50.36132933,-3.344787147,10000,-141.4322161,141.4212834,0,0,0,135 +100.56,50.36131664,-3.344767303,10000,-141.4322158,141.4213211,0,0,0,135 +100.57,50.36130394,-3.34474746,10000,-141.4217707,141.4213588,0,0,0,135 +100.58,50.36129125,-3.344727616,10000,-141.4148073,141.4213965,0,0,0,135 +100.59,50.36127856,-3.344707773,10000,-141.4182885,141.4214343,0,0,0,135 +100.6,50.36126586,-3.344687929,10000,-141.4182882,141.421472,0,0,0,135 +100.61,50.36125317,-3.344668086,10000,-141.4148063,141.4215097,0,0,0,135 +100.62,50.36124048,-3.344648242,10000,-141.4182876,141.4215474,0,0,0,135 +100.63,50.36122778,-3.344628399,10000,-141.4182873,141.4215851,0,0,0,135 +100.64,50.36121509,-3.344608555,10000,-141.4148054,141.4216228,0,0,0,135 +100.65,50.3612024,-3.344588712,10000,-141.4217683,141.4216606,0,0,0,135 +100.66,50.3611897,-3.344568868,10000,-141.4322127,141.4216983,0,0,0,135 +100.67,50.36117701,-3.344549025,10000,-141.4322124,141.4215133,0,0,0,135 +100.68,50.36116431,-3.344529181,10000,-141.4217673,141.4208829,0,0,0,135 +100.69,50.36115162,-3.344509338,10000,-141.4148039,141.4204751,0,0,0,135 +100.7,50.36113893,-3.344489495,10000,-141.4182851,141.4209583,0,0,0,135 +100.71,50.36112623,-3.344469651,10000,-141.4182848,141.4216641,0,0,0,135 +100.72,50.36111354,-3.344449808,10000,-141.4148029,141.4219246,0,0,0,135 +100.73,50.36110085,-3.344429964,10000,-141.4217658,141.4219623,0,0,0,135 +100.74,50.36108815,-3.344410121,10000,-141.4322102,141.4217773,0,0,0,135 +100.75,50.36107546,-3.344390277,10000,-141.4322099,141.4209242,0,0,0,135 +100.76,50.36106276,-3.344370434,10000,-141.4217649,141.4198483,0,0,0,135 +100.77,50.36105007,-3.344350591,10000,-141.4148014,141.4201087,0,0,0,135 +100.78,50.36103738,-3.344330748,10000,-141.4182826,141.4219282,0,0,0,135 +100.79,50.36102468,-3.344310904,10000,-141.4182823,141.4230795,0,0,0,135 +100.8,50.36101199,-3.34429106,10000,-141.4148005,141.4222263,0,0,0,135 +100.81,50.3609993,-3.344271217,10000,-141.4217633,141.4211505,0,0,0,135 +100.82,50.3609866,-3.344251374,10000,-141.4322078,141.4211882,0,0,0,135 +100.83,50.36097391,-3.34423153,10000,-141.4322074,141.4212259,0,0,0,135 +100.84,50.36096121,-3.344211687,10000,-141.4217624,141.4210409,0,0,0,135 +100.85,50.36094852,-3.344191844,10000,-141.4147989,141.4213013,0,0,0,135 +100.86,50.36093583,-3.344172,10000,-141.4182802,141.4213391,0,0,0,135 +100.87,50.36092313,-3.344152157,10000,-141.4182799,141.4211541,0,0,0,135 +100.88,50.36091044,-3.344132314,10000,-141.414798,141.4214145,0,0,0,135 +100.89,50.36089775,-3.34411247,10000,-141.4182792,141.4214522,0,0,0,135 +100.9,50.36088505,-3.344092627,10000,-141.4182789,141.4212672,0,0,0,135 +100.91,50.36087236,-3.344072784,10000,-141.414797,141.4215276,0,0,0,135 +100.92,50.36085967,-3.34405294,10000,-141.4217599,141.4213426,0,0,0,135 +100.93,50.36084697,-3.344033097,10000,-141.4322043,141.4204895,0,0,0,135 +100.94,50.36083428,-3.344013254,10000,-141.432204,141.4205272,0,0,0,135 +100.95,50.36082158,-3.343993411,10000,-141.421759,141.4216785,0,0,0,135 +100.96,50.36080889,-3.343973567,10000,-141.4147955,141.4226071,0,0,0,135 +100.97,50.3607962,-3.343953724,10000,-141.4182768,141.4226448,0,0,0,135 +100.98,50.3607835,-3.34393388,10000,-141.4182765,141.4217917,0,0,0,135 +100.99,50.36077081,-3.343914037,10000,-141.4147946,141.4207158,0,0,0,135 +101,50.36075812,-3.343894194,10000,-141.4217574,141.4207535,0,0,0,135 +101.01,50.36074542,-3.343874351,10000,-141.4322018,141.4216821,0,0,0,135 +101.02,50.36073273,-3.343854507,10000,-141.4322015,141.4217198,0,0,0,135 +101.03,50.36072003,-3.343834664,10000,-141.4217565,141.4208667,0,0,0,135 +101.04,50.36070734,-3.343814821,10000,-141.414793,141.4209044,0,0,0,135 +101.05,50.36069465,-3.343794978,10000,-141.4182743,141.421833,0,0,0,135 +101.06,50.36068195,-3.343775134,10000,-141.418274,141.4218707,0,0,0,135 +101.07,50.36066926,-3.343755291,10000,-141.4147921,141.4210175,0,0,0,135 +101.08,50.36065657,-3.343735448,10000,-141.4217549,141.4210553,0,0,0,135 +101.09,50.36064387,-3.343715605,10000,-141.4321994,141.4219838,0,0,0,135 +101.1,50.36063118,-3.343695761,10000,-141.4321991,141.4220216,0,0,0,135 +101.11,50.36061848,-3.343675918,10000,-141.421754,141.4209457,0,0,0,135 +101.12,50.36060579,-3.343656075,10000,-141.4147905,141.4200925,0,0,0,135 +101.13,50.3605931,-3.343636232,10000,-141.4182718,141.4201303,0,0,0,135 +101.14,50.3605804,-3.343616389,10000,-141.4182715,141.4210588,0,0,0,135 +101.15,50.36056771,-3.343596546,10000,-141.4147896,141.4222101,0,0,0,135 +101.16,50.36055502,-3.343576702,10000,-141.4217525,141.4222479,0,0,0,135 +101.17,50.36054232,-3.343556859,10000,-141.4321969,141.4213947,0,0,0,135 +101.18,50.36052963,-3.343537016,10000,-141.4321966,141.4214324,0,0,0,135 +101.19,50.36051693,-3.343517173,10000,-141.4217515,141.422361,0,0,0,135 +101.2,50.36050424,-3.343497329,10000,-141.4147881,141.4223987,0,0,0,135 +101.21,50.36049155,-3.343477486,10000,-141.4182693,141.4213229,0,0,0,135 +101.22,50.36047885,-3.343457643,10000,-141.418269,141.4204697,0,0,0,135 +101.23,50.36046616,-3.3434378,10000,-141.4147871,141.4202847,0,0,0,135 +101.24,50.36045347,-3.343417957,10000,-141.42175,141.4203224,0,0,0,135 +101.25,50.36044077,-3.343398114,10000,-141.4321944,141.4203601,0,0,0,135 +101.26,50.36042808,-3.343378271,10000,-141.4321941,141.4206206,0,0,0,135 +101.27,50.36041538,-3.343358428,10000,-141.421749,141.4215492,0,0,0,135 +101.28,50.36040269,-3.343338585,10000,-141.4147856,141.4227005,0,0,0,135 +101.29,50.36039,-3.343318741,10000,-141.4182669,141.4227382,0,0,0,135 +101.3,50.3603773,-3.343298898,10000,-141.4182666,141.4216623,0,0,0,135 +101.31,50.36036461,-3.343279055,10000,-141.4147847,141.4208092,0,0,0,135 +101.32,50.36035192,-3.343259212,10000,-141.4182659,141.4208469,0,0,0,135 +101.33,50.36033922,-3.343239369,10000,-141.4182656,141.4215527,0,0,0,135 +101.34,50.36032653,-3.343219526,10000,-141.4147837,141.4218132,0,0,0,135 +101.35,50.36031384,-3.343199682,10000,-141.4217466,141.42096,0,0,0,135 +101.36,50.36030114,-3.34317984,10000,-141.432191,141.4205523,0,0,0,135 +101.37,50.36028845,-3.343159997,10000,-141.4321907,141.4212582,0,0,0,135 +101.38,50.36027575,-3.343140153,10000,-141.4217456,141.4217413,0,0,0,135 +101.39,50.36026306,-3.343120311,10000,-141.4147822,141.4220018,0,0,0,135 +101.4,50.36025037,-3.343100467,10000,-141.4182635,141.4222622,0,0,0,135 +101.41,50.36023767,-3.343080624,10000,-141.4182632,141.4218545,0,0,0,135 +101.42,50.36022498,-3.343060781,10000,-141.4147812,141.421224,0,0,0,135 +101.43,50.36021229,-3.343040938,10000,-141.4217441,141.421039,0,0,0,135 +101.44,50.36019959,-3.343021095,10000,-141.4321885,141.4210767,0,0,0,135 +101.45,50.3601869,-3.343001252,10000,-141.4321882,141.4211145,0,0,0,135 +101.46,50.3601742,-3.342981409,10000,-141.4217432,141.4211522,0,0,0,135 +101.47,50.36016151,-3.342961566,10000,-141.4147797,141.4211899,0,0,0,135 +101.48,50.36014882,-3.342941723,10000,-141.418261,141.4212276,0,0,0,135 +101.49,50.36013612,-3.34292188,10000,-141.4182606,141.4212653,0,0,0,135 +101.5,50.36012343,-3.342902037,10000,-141.4147788,141.421303,0,0,0,135 +101.51,50.36011074,-3.342882194,10000,-141.4217416,141.4213408,0,0,0,135 +101.52,50.36009804,-3.342862351,10000,-141.4321861,141.4213785,0,0,0,135 +101.53,50.36008535,-3.342842508,10000,-141.4321857,141.4214162,0,0,0,135 +101.54,50.36007265,-3.342822665,10000,-141.4217407,141.4214539,0,0,0,135 +101.55,50.36005996,-3.342802822,10000,-141.4147772,141.4214916,0,0,0,135 +101.56,50.36004727,-3.342782979,10000,-141.4182585,141.4215293,0,0,0,135 +101.57,50.36003457,-3.342763136,10000,-141.4182582,141.4215671,0,0,0,135 +101.58,50.36002188,-3.342743293,10000,-141.4147763,141.4216048,0,0,0,135 +101.59,50.36000919,-3.34272345,10000,-141.4217391,141.4216425,0,0,0,135 +101.6,50.35999649,-3.342703607,10000,-141.4321835,141.4216802,0,0,0,135 +101.61,50.3599838,-3.342683764,10000,-141.4321832,141.4217179,0,0,0,135 +101.62,50.3599711,-3.342663921,10000,-141.4217382,141.4217556,0,0,0,135 +101.63,50.35995841,-3.342644078,10000,-141.4147748,141.4215706,0,0,0,135 +101.64,50.35994572,-3.342624235,10000,-141.418256,141.4207175,0,0,0,135 +101.65,50.35993302,-3.342604392,10000,-141.4182557,141.4196416,0,0,0,135 +101.66,50.35992033,-3.34258455,10000,-141.4147738,141.4196793,0,0,0,135 +101.67,50.35990764,-3.342564707,10000,-141.4182551,141.4208306,0,0,0,135 +101.68,50.35989494,-3.342544864,10000,-141.4182548,141.4217592,0,0,0,135 +101.69,50.35988225,-3.342525021,10000,-141.4147729,141.4220197,0,0,0,135 +101.7,50.35986956,-3.342505178,10000,-141.4217357,141.4220574,0,0,0,135 +101.71,50.35985686,-3.342485335,10000,-141.4321801,141.4220951,0,0,0,135 +101.72,50.35984417,-3.342465492,10000,-141.4321798,141.4221328,0,0,0,135 +101.73,50.35983147,-3.342445649,10000,-141.4217348,141.4219478,0,0,0,135 +101.74,50.35981878,-3.342425806,10000,-141.4147713,141.4213174,0,0,0,135 +101.75,50.35980609,-3.342405963,10000,-141.4182526,141.4209096,0,0,0,135 +101.76,50.35979339,-3.342386121,10000,-141.4182523,141.4211701,0,0,0,135 +101.77,50.3597807,-3.342366277,10000,-141.4147704,141.4212078,0,0,0,135 +101.78,50.35976801,-3.342346435,10000,-141.4217332,141.4210228,0,0,0,135 +101.79,50.35975531,-3.342326592,10000,-141.4321777,141.4212832,0,0,0,135 +101.8,50.35974262,-3.342306749,10000,-141.4321774,141.4210982,0,0,0,135 +101.81,50.35972992,-3.342286906,10000,-141.4217323,141.420245,0,0,0,135 +101.82,50.35971723,-3.342267064,10000,-141.4147689,141.4202828,0,0,0,135 +101.83,50.35970454,-3.342247221,10000,-141.4182501,141.4214341,0,0,0,135 +101.84,50.35969184,-3.342227378,10000,-141.4182498,141.42214,0,0,0,135 +101.85,50.35967915,-3.342207535,10000,-141.4147679,141.4217322,0,0,0,135 +101.86,50.35966646,-3.342187692,10000,-141.4217308,141.4213245,0,0,0,135 +101.87,50.35965376,-3.34216785,10000,-141.4321752,141.4215849,0,0,0,135 +101.88,50.35964107,-3.342148006,10000,-141.4321749,141.4216227,0,0,0,135 +101.89,50.35962837,-3.342128164,10000,-141.4217299,141.4214377,0,0,0,135 +101.9,50.35961568,-3.342108321,10000,-141.4147664,141.4219208,0,0,0,135 +101.91,50.35960299,-3.342088478,10000,-141.4182476,141.422404,0,0,0,135 +101.92,50.35959029,-3.342068635,10000,-141.4182473,141.4217735,0,0,0,135 +101.93,50.3595776,-3.342048792,10000,-141.4147655,141.4206976,0,0,0,135 +101.94,50.35956491,-3.34202895,10000,-141.4217283,141.4205126,0,0,0,135 +101.95,50.35955221,-3.342009107,10000,-141.4321727,141.4209958,0,0,0,135 +101.96,50.35953952,-3.341989264,10000,-141.4321724,141.4214789,0,0,0,135 +101.97,50.35952682,-3.341969422,10000,-141.4217273,141.4219621,0,0,0,135 +101.98,50.35951413,-3.341949578,10000,-141.4147639,141.4219998,0,0,0,135 +101.99,50.35950144,-3.341929736,10000,-141.4182452,141.4215921,0,0,0,135 +102,50.35948874,-3.341909893,10000,-141.4182449,141.4211844,0,0,0,135 +102.01,50.35947605,-3.34189005,10000,-141.414763,141.4207766,0,0,0,135 +102.02,50.35946336,-3.341870208,10000,-141.4217258,141.4208143,0,0,0,135 +102.03,50.35945066,-3.341850365,10000,-141.4321702,141.4210748,0,0,0,135 +102.04,50.35943797,-3.341830522,10000,-141.4321699,141.4208898,0,0,0,135 +102.05,50.35942527,-3.34181068,10000,-141.4217249,141.4209275,0,0,0,135 +102.06,50.35941258,-3.341790837,10000,-141.4147614,141.4211879,0,0,0,135 +102.07,50.35939989,-3.341770994,10000,-141.4182427,141.4210029,0,0,0,135 +102.08,50.35938719,-3.341751152,10000,-141.4182424,141.4212634,0,0,0,135 +102.09,50.3593745,-3.341731309,10000,-141.4147605,141.4224147,0,0,0,135 +102.1,50.35936181,-3.341711466,10000,-141.4182418,141.4231206,0,0,0,135 +102.11,50.35934911,-3.341691623,10000,-141.4182415,141.4224901,0,0,0,135 +102.12,50.35933642,-3.34167178,10000,-141.4147596,141.4214142,0,0,0,135 +102.13,50.35932373,-3.341651938,10000,-141.4217224,141.4212292,0,0,0,135 +102.14,50.35931103,-3.341632095,10000,-141.4321668,141.4212669,0,0,0,135 +102.15,50.35929834,-3.341612252,10000,-141.4321665,141.420191,0,0,0,135 +102.16,50.35928564,-3.34159241,10000,-141.4217215,141.4193379,0,0,0,135 +102.17,50.35927295,-3.341572568,10000,-141.414758,141.4202665,0,0,0,135 +102.18,50.35926026,-3.341552725,10000,-141.4182393,141.4214178,0,0,0,135 +102.19,50.35924756,-3.341532882,10000,-141.418239,141.4214555,0,0,0,135 +102.2,50.35923487,-3.34151304,10000,-141.4147571,141.4214932,0,0,0,135 +102.21,50.35922218,-3.341493197,10000,-141.4217199,141.4217537,0,0,0,135 +102.22,50.35920948,-3.341473354,10000,-141.4321644,141.4215686,0,0,0,135 +102.23,50.35919679,-3.341453512,10000,-141.432164,141.4216064,0,0,0,135 +102.24,50.35918409,-3.341433669,10000,-141.421719,141.4218668,0,0,0,135 +102.25,50.3591714,-3.341413826,10000,-141.4147555,141.4216818,0,0,0,135 +102.26,50.35915871,-3.341393984,10000,-141.4182368,141.4217195,0,0,0,135 +102.27,50.35914601,-3.341374141,10000,-141.4182365,141.4219799,0,0,0,135 +102.28,50.35913332,-3.341354298,10000,-141.4147546,141.4215722,0,0,0,135 +102.29,50.35912063,-3.341334456,10000,-141.4217175,141.4209418,0,0,0,135 +102.3,50.35910793,-3.341314613,10000,-141.4321619,141.4209795,0,0,0,135 +102.31,50.35909524,-3.341294771,10000,-141.4321616,141.4216854,0,0,0,135 +102.32,50.35908254,-3.341274928,10000,-141.4217165,141.4219458,0,0,0,135 +102.33,50.35906985,-3.341255085,10000,-141.4147531,141.4208699,0,0,0,135 +102.34,50.35905716,-3.341235243,10000,-141.4182343,141.4200167,0,0,0,135 +102.35,50.35904446,-3.341215401,10000,-141.418234,141.4209453,0,0,0,135 +102.36,50.35903177,-3.341195558,10000,-141.4147521,141.4218739,0,0,0,135 +102.37,50.35901908,-3.341175715,10000,-141.421715,141.4210208,0,0,0,135 +102.38,50.35900638,-3.341155873,10000,-141.4321594,141.4201676,0,0,0,135 +102.39,50.35899369,-3.341136031,10000,-141.4321591,141.4210962,0,0,0,135 +102.4,50.35898099,-3.341116188,10000,-141.421714,141.4222475,0,0,0,135 +102.41,50.3589683,-3.341096345,10000,-141.4147506,141.4220625,0,0,0,135 +102.42,50.35895561,-3.341076503,10000,-141.4182318,141.4214321,0,0,0,135 +102.43,50.35894291,-3.34105666,10000,-141.4182315,141.4214698,0,0,0,135 +102.44,50.35893022,-3.341036818,10000,-141.4147496,141.4221757,0,0,0,135 +102.45,50.35891753,-3.341016975,10000,-141.4217125,141.4224361,0,0,0,135 +102.46,50.35890483,-3.340997132,10000,-141.4321569,141.4213602,0,0,0,135 +102.47,50.35889214,-3.34097729,10000,-141.4321566,141.4202843,0,0,0,135 +102.48,50.35887944,-3.340957448,10000,-141.4217116,141.4205447,0,0,0,135 +102.49,50.35886675,-3.340937605,10000,-141.4147481,141.4214733,0,0,0,135 +102.5,50.35885406,-3.340917763,10000,-141.4182293,141.4224019,0,0,0,135 +102.51,50.35884136,-3.34089792,10000,-141.418229,141.4226624,0,0,0,135 +102.52,50.35882867,-3.340878077,10000,-141.4147472,141.4213637,0,0,0,135 +102.53,50.35881598,-3.340858235,10000,-141.4182285,141.4196197,0,0,0,135 +102.54,50.35880328,-3.340838393,10000,-141.4182281,141.4196574,0,0,0,135 +102.55,50.35879059,-3.340818551,10000,-141.4147462,141.4214769,0,0,0,135 +102.56,50.3587779,-3.340798708,10000,-141.4217091,141.422851,0,0,0,135 +102.57,50.3587652,-3.340778865,10000,-141.4321535,141.4226659,0,0,0,135 +102.58,50.35875251,-3.340759023,10000,-141.4321532,141.4218128,0,0,0,135 +102.59,50.35873981,-3.34073918,10000,-141.4217082,141.4207369,0,0,0,135 +102.6,50.35872712,-3.340719338,10000,-141.4147447,141.4196609,0,0,0,135 +102.61,50.35871443,-3.340699496,10000,-141.4182259,141.4199214,0,0,0,135 +102.62,50.35870173,-3.340679654,10000,-141.4182256,141.4217409,0,0,0,135 +102.63,50.35868904,-3.340659811,10000,-141.4147438,141.423115,0,0,0,135 +102.64,50.35867635,-3.340639968,10000,-141.4217066,141.42293,0,0,0,135 +102.65,50.35866365,-3.340620126,10000,-141.432151,141.4220768,0,0,0,135 +102.66,50.35865096,-3.340600283,10000,-141.4321507,141.4210009,0,0,0,135 +102.67,50.35863826,-3.340580441,10000,-141.4217057,141.4199249,0,0,0,135 +102.68,50.35862557,-3.340560599,10000,-141.4147422,141.4199627,0,0,0,135 +102.69,50.35861288,-3.340540757,10000,-141.4182235,141.4208913,0,0,0,135 +102.7,50.35860018,-3.340520914,10000,-141.4182232,141.4211517,0,0,0,135 +102.71,50.35858749,-3.340501072,10000,-141.4147413,141.4209667,0,0,0,135 +102.72,50.3585748,-3.34048123,10000,-141.4217041,141.4214499,0,0,0,135 +102.73,50.3585621,-3.340461387,10000,-141.4321485,141.4221558,0,0,0,135 +102.74,50.35854941,-3.340441545,10000,-141.4321482,141.4221935,0,0,0,135 +102.75,50.35853671,-3.340421702,10000,-141.4217032,141.421563,0,0,0,135 +102.76,50.35852402,-3.34040186,10000,-141.4147397,141.4211553,0,0,0,135 +102.77,50.35851133,-3.340382018,10000,-141.418221,141.4214157,0,0,0,135 +102.78,50.35849863,-3.340362175,10000,-141.4182207,141.4212307,0,0,0,135 +102.79,50.35848594,-3.340342333,10000,-141.4147388,141.4203775,0,0,0,135 +102.8,50.35847325,-3.340322491,10000,-141.4217016,141.4204152,0,0,0,135 +102.81,50.35846055,-3.340302649,10000,-141.4321461,141.4213438,0,0,0,135 +102.82,50.35844786,-3.340282806,10000,-141.4321458,141.4216043,0,0,0,135 +102.83,50.35843516,-3.340262964,10000,-141.4217007,141.4214193,0,0,0,135 +102.84,50.35842247,-3.340243122,10000,-141.4147372,141.4216797,0,0,0,135 +102.85,50.35840978,-3.340223279,10000,-141.4182185,141.4217174,0,0,0,135 +102.86,50.35839708,-3.340203437,10000,-141.4182182,141.4215324,0,0,0,135 +102.87,50.35838439,-3.340183595,10000,-141.4147363,141.4217928,0,0,0,135 +102.88,50.3583717,-3.340163752,10000,-141.4182176,141.4216078,0,0,0,135 +102.89,50.358359,-3.34014391,10000,-141.4182173,141.4207546,0,0,0,135 +102.9,50.35834631,-3.340124068,10000,-141.4147354,141.4207924,0,0,0,135 +102.91,50.35833362,-3.340104226,10000,-141.4216982,141.421721,0,0,0,135 +102.92,50.35832092,-3.340084383,10000,-141.4321427,141.4217587,0,0,0,135 +102.93,50.35830823,-3.340064541,10000,-141.4321424,141.4209055,0,0,0,135 +102.94,50.35829553,-3.340044699,10000,-141.4216973,141.4209432,0,0,0,135 +102.95,50.35828284,-3.340024857,10000,-141.4147338,141.4218718,0,0,0,135 +102.96,50.35827015,-3.340005014,10000,-141.4182151,141.4219095,0,0,0,135 +102.97,50.35825745,-3.339985172,10000,-141.4182148,141.4210563,0,0,0,135 +102.98,50.35824476,-3.33996533,10000,-141.4147329,141.4210941,0,0,0,135 +102.99,50.35823207,-3.339945488,10000,-141.4216958,141.4220227,0,0,0,135 +103,50.35821937,-3.339925645,10000,-141.4321402,141.4220604,0,0,0,135 +103.01,50.35820668,-3.339905803,10000,-141.4321399,141.4209845,0,0,0,135 +103.02,50.35819398,-3.339885961,10000,-141.4216948,141.4201313,0,0,0,135 +103.03,50.35818129,-3.339866119,10000,-141.4147314,141.420169,0,0,0,135 +103.04,50.3581686,-3.339846277,10000,-141.4182126,141.4210976,0,0,0,135 +103.05,50.3581559,-3.339826435,10000,-141.4182123,141.422249,0,0,0,135 +103.06,50.35814321,-3.339806592,10000,-141.4147304,141.4222867,0,0,0,135 +103.07,50.35813052,-3.33978675,10000,-141.4216933,141.4212108,0,0,0,135 +103.08,50.35811782,-3.339766908,10000,-141.4321377,141.4205803,0,0,0,135 +103.09,50.35810513,-3.339747066,10000,-141.4321374,141.4212862,0,0,0,135 +103.1,50.35809243,-3.339727224,10000,-141.4216923,141.4224375,0,0,0,135 +103.11,50.35807974,-3.339707381,10000,-141.4147289,141.4224753,0,0,0,135 +103.12,50.35806705,-3.339687539,10000,-141.4182102,141.4213993,0,0,0,135 +103.13,50.35805435,-3.339667697,10000,-141.4182098,141.4207689,0,0,0,135 +103.14,50.35804166,-3.339647855,10000,-141.414728,141.4214748,0,0,0,135 +103.15,50.35802897,-3.339628013,10000,-141.4216908,141.4226261,0,0,0,135 +103.16,50.35801627,-3.33960817,10000,-141.4321352,141.4226638,0,0,0,135 +103.17,50.35800358,-3.339588328,10000,-141.4321349,141.4215879,0,0,0,135 +103.18,50.35799088,-3.339568486,10000,-141.4216899,141.4207347,0,0,0,135 +103.19,50.35797819,-3.339548644,10000,-141.4147264,141.4205497,0,0,0,135 +103.2,50.3579655,-3.339528802,10000,-141.4182077,141.4205874,0,0,0,135 +103.21,50.3579528,-3.33950896,10000,-141.4182073,141.4206251,0,0,0,135 +103.22,50.35794011,-3.339489118,10000,-141.4147255,141.4208855,0,0,0,135 +103.23,50.35792742,-3.339469276,10000,-141.4216883,141.4218142,0,0,0,135 +103.24,50.35791472,-3.339449434,10000,-141.4321328,141.4227428,0,0,0,135 +103.25,50.35790203,-3.339429591,10000,-141.4321324,141.4218896,0,0,0,135 +103.26,50.35788933,-3.339409749,10000,-141.4216874,141.4197,0,0,0,135 +103.27,50.35787664,-3.339389908,10000,-141.4147239,141.4188468,0,0,0,135 +103.28,50.35786395,-3.339370066,10000,-141.4182052,141.4199982,0,0,0,135 +103.29,50.35785125,-3.339350224,10000,-141.4182049,141.4218177,0,0,0,135 +103.3,50.35783856,-3.339330382,10000,-141.414723,141.4231918,0,0,0,135 +103.31,50.35782587,-3.339310539,10000,-141.4182043,141.4232295,0,0,0,135 +103.32,50.35781317,-3.339290697,10000,-141.4182039,141.4221536,0,0,0,135 +103.33,50.35780048,-3.339270855,10000,-141.4147221,141.4213004,0,0,0,135 +103.34,50.35778779,-3.339251013,10000,-141.4216849,141.4211154,0,0,0,135 +103.35,50.35777509,-3.339231171,10000,-141.4321294,141.4211531,0,0,0,135 +103.36,50.3577624,-3.339211329,10000,-141.432129,141.4211908,0,0,0,135 +103.37,50.3577497,-3.339191487,10000,-141.421684,141.4212285,0,0,0,135 +103.38,50.35773701,-3.339171645,10000,-141.4147205,141.4212662,0,0,0,135 +103.39,50.35772432,-3.339151803,10000,-141.4182018,141.4213039,0,0,0,135 +103.4,50.35771162,-3.339131961,10000,-141.4182015,141.4213417,0,0,0,135 +103.41,50.35769893,-3.339112119,10000,-141.4147196,141.4213794,0,0,0,135 +103.42,50.35768624,-3.339092277,10000,-141.4216824,141.4214171,0,0,0,135 +103.43,50.35767354,-3.339072435,10000,-141.4321268,141.4214548,0,0,0,135 +103.44,50.35766085,-3.339052593,10000,-141.4321265,141.4214925,0,0,0,135 +103.45,50.35764815,-3.339032751,10000,-141.4216815,141.4215302,0,0,0,135 +103.46,50.35763546,-3.339012909,10000,-141.414718,141.4215679,0,0,0,135 +103.47,50.35762277,-3.338993067,10000,-141.4181993,141.4216056,0,0,0,135 +103.48,50.35761007,-3.338973225,10000,-141.418199,141.4216434,0,0,0,135 +103.49,50.35759738,-3.338953383,10000,-141.4147171,141.4214583,0,0,0,135 +103.5,50.35758469,-3.338933541,10000,-141.42168,141.4206051,0,0,0,135 +103.51,50.35757199,-3.338913699,10000,-141.4321244,141.4197519,0,0,0,135 +103.52,50.3575593,-3.338893858,10000,-141.4321241,141.4204578,0,0,0,135 +103.53,50.3575466,-3.338874016,10000,-141.421679,141.4218319,0,0,0,135 +103.54,50.35753391,-3.338854173,10000,-141.4147155,141.4216469,0,0,0,135 +103.55,50.35752122,-3.338834332,10000,-141.4181968,141.4207937,0,0,0,135 +103.56,50.35750852,-3.33881449,10000,-141.4181965,141.4210541,0,0,0,135 +103.57,50.35749583,-3.338794648,10000,-141.4147146,141.42176,0,0,0,135 +103.58,50.35748314,-3.338774806,10000,-141.4216775,141.4220205,0,0,0,135 +103.59,50.35747044,-3.338754964,10000,-141.4321219,141.4220582,0,0,0,135 +103.6,50.35745775,-3.338735122,10000,-141.4321216,141.4220959,0,0,0,135 +103.61,50.35744505,-3.33871528,10000,-141.4216766,141.4219109,0,0,0,135 +103.62,50.35743236,-3.338695438,10000,-141.4147131,141.4210577,0,0,0,135 +103.63,50.35741967,-3.338675596,10000,-141.4181943,141.4199817,0,0,0,135 +103.64,50.35740697,-3.338655755,10000,-141.418194,141.4200194,0,0,0,135 +103.65,50.35739428,-3.338635913,10000,-141.4147122,141.4211708,0,0,0,135 +103.66,50.35738159,-3.338616071,10000,-141.421675,141.4220995,0,0,0,135 +103.67,50.35736889,-3.338596229,10000,-141.4321194,141.4223599,0,0,0,135 +103.68,50.3573562,-3.338576387,10000,-141.4321191,141.4221749,0,0,0,135 +103.69,50.3573435,-3.338556545,10000,-141.421674,141.4213217,0,0,0,135 +103.7,50.35733081,-3.338536703,10000,-141.4147106,141.4202457,0,0,0,135 +103.71,50.35731812,-3.338516862,10000,-141.4181919,141.4202834,0,0,0,135 +103.72,50.35730542,-3.33849702,10000,-141.4181916,141.4214348,0,0,0,135 +103.73,50.35729273,-3.338477178,10000,-141.4147097,141.4223635,0,0,0,135 +103.74,50.35728004,-3.338457336,10000,-141.4181909,141.4224012,0,0,0,135 +103.75,50.35726734,-3.338437494,10000,-141.4181906,141.4215479,0,0,0,135 +103.76,50.35725465,-3.338417652,10000,-141.4147087,141.420472,0,0,0,135 +103.77,50.35724196,-3.338397811,10000,-141.4216716,141.4205097,0,0,0,135 +103.78,50.35722926,-3.338377969,10000,-141.432116,141.4214383,0,0,0,135 +103.79,50.35721657,-3.338358127,10000,-141.4321157,141.4216988,0,0,0,135 +103.8,50.35720387,-3.338338285,10000,-141.4216706,141.4215138,0,0,0,135 +103.81,50.35719118,-3.338318444,10000,-141.4147072,141.4217742,0,0,0,135 +103.82,50.35717849,-3.338298601,10000,-141.4181885,141.4218119,0,0,0,135 +103.83,50.35716579,-3.33827876,10000,-141.4181882,141.4214042,0,0,0,135 +103.84,50.3571531,-3.338258918,10000,-141.4147063,141.4209964,0,0,0,135 +103.85,50.35714041,-3.338239076,10000,-141.4216691,141.4205887,0,0,0,135 +103.86,50.35712771,-3.338219235,10000,-141.4321135,141.4206264,0,0,0,135 +103.87,50.35711502,-3.338199393,10000,-141.4321132,141.4208868,0,0,0,135 +103.88,50.35710232,-3.338179551,10000,-141.4216682,141.4207018,0,0,0,135 +103.89,50.35708963,-3.33815971,10000,-141.4147047,141.4209623,0,0,0,135 +103.9,50.35707694,-3.338139868,10000,-141.418186,141.4221136,0,0,0,135 +103.91,50.35706424,-3.338120026,10000,-141.4181857,141.4228195,0,0,0,135 +103.92,50.35705155,-3.338100184,10000,-141.4147038,141.4221891,0,0,0,135 +103.93,50.35703886,-3.338080342,10000,-141.4216666,141.4211131,0,0,0,135 +103.94,50.35702616,-3.338060501,10000,-141.4321111,141.4209281,0,0,0,135 +103.95,50.35701347,-3.338040659,10000,-141.4321107,141.4211885,0,0,0,135 +103.96,50.35700077,-3.338020817,10000,-141.4216657,141.4210035,0,0,0,135 +103.97,50.35698808,-3.338000976,10000,-141.4147022,141.421264,0,0,0,135 +103.98,50.35697539,-3.337981134,10000,-141.4181835,141.4221926,0,0,0,135 +103.99,50.35696269,-3.337961292,10000,-141.4181832,141.4222303,0,0,0,135 +104,50.35695,-3.33794145,10000,-141.4147013,141.4213771,0,0,0,135 +104.01,50.35693731,-3.337921609,10000,-141.4216642,141.4211921,0,0,0,135 +104.02,50.35692461,-3.337901767,10000,-141.4321086,141.4214525,0,0,0,135 +104.03,50.35691192,-3.337881925,10000,-141.4321082,141.4210448,0,0,0,135 +104.04,50.35689922,-3.337862084,10000,-141.4216632,141.4204143,0,0,0,135 +104.05,50.35688653,-3.337842242,10000,-141.4146998,141.420452,0,0,0,135 +104.06,50.35687384,-3.337822401,10000,-141.418181,141.4211579,0,0,0,135 +104.07,50.35686114,-3.337802559,10000,-141.4181807,141.4216411,0,0,0,135 +104.08,50.35684845,-3.337782717,10000,-141.4146988,141.4212333,0,0,0,135 +104.09,50.35683576,-3.337762876,10000,-141.4181801,141.4208256,0,0,0,135 +104.1,50.35682306,-3.337743034,10000,-141.4181798,141.4215315,0,0,0,135 +104.11,50.35681037,-3.337723193,10000,-141.4146979,141.4226829,0,0,0,135 +104.12,50.35679768,-3.33770335,10000,-141.4216607,141.4227206,0,0,0,135 +104.13,50.35678498,-3.337683509,10000,-141.4321052,141.4216446,0,0,0,135 +104.14,50.35677229,-3.337663667,10000,-141.4321048,141.4207914,0,0,0,135 +104.15,50.35675959,-3.337643826,10000,-141.4216598,141.4206064,0,0,0,135 +104.16,50.3567469,-3.337623984,10000,-141.4146964,141.4208668,0,0,0,135 +104.17,50.35673421,-3.337604143,10000,-141.4181776,141.4215727,0,0,0,135 +104.18,50.35672151,-3.337584301,10000,-141.4181773,141.4220559,0,0,0,135 +104.19,50.35670882,-3.337564459,10000,-141.4146954,141.4216481,0,0,0,135 +104.2,50.35669613,-3.337544618,10000,-141.4216583,141.4210176,0,0,0,135 +104.21,50.35668343,-3.337524776,10000,-141.4321027,141.4208326,0,0,0,135 +104.22,50.35667074,-3.337504935,10000,-141.4321024,141.4208703,0,0,0,135 +104.23,50.35665804,-3.337485093,10000,-141.4216573,141.4211308,0,0,0,135 +104.24,50.35664535,-3.337465252,10000,-141.4146939,141.4218367,0,0,0,135 +104.25,50.35663266,-3.33744541,10000,-141.4181751,141.4223199,0,0,0,135 +104.26,50.35661996,-3.337425568,10000,-141.4181748,141.4219121,0,0,0,135 +104.27,50.35660727,-3.337405727,10000,-141.4146929,141.4212816,0,0,0,135 +104.28,50.35659458,-3.337385885,10000,-141.4216558,141.4210966,0,0,0,135 +104.29,50.35658188,-3.337366044,10000,-141.4321002,141.4211343,0,0,0,135 +104.3,50.35656919,-3.337346202,10000,-141.4320999,141.421172,0,0,0,135 +104.31,50.35655649,-3.337326361,10000,-141.4216549,141.4212097,0,0,0,135 +104.32,50.3565438,-3.337306519,10000,-141.4146914,141.4212475,0,0,0,135 +104.33,50.35653111,-3.337286678,10000,-141.4181726,141.4212852,0,0,0,135 +104.34,50.35651841,-3.337266836,10000,-141.4181723,141.4213229,0,0,0,135 +104.35,50.35650572,-3.337246995,10000,-141.4146905,141.4213606,0,0,0,135 +104.36,50.35649303,-3.337227153,10000,-141.4216533,141.4213983,0,0,0,135 +104.37,50.35648033,-3.337207312,10000,-141.4320977,141.421436,0,0,0,135 +104.38,50.35646764,-3.33718747,10000,-141.4320974,141.4214737,0,0,0,135 +104.39,50.35645494,-3.337167629,10000,-141.4216524,141.4212887,0,0,0,135 +104.4,50.35644225,-3.337147787,10000,-141.4146889,141.4206582,0,0,0,135 +104.41,50.35642956,-3.337127946,10000,-141.4181702,141.4202504,0,0,0,135 +104.42,50.35641686,-3.337108105,10000,-141.4181699,141.4207336,0,0,0,135 +104.43,50.35640417,-3.337088263,10000,-141.414688,141.4216623,0,0,0,135 +104.44,50.35639148,-3.337068422,10000,-141.4216508,141.4225909,0,0,0,135 +104.45,50.35637878,-3.33704858,10000,-141.4320952,141.4228514,0,0,0,135 +104.46,50.35636609,-3.337028738,10000,-141.4320949,141.4217754,0,0,0,135 +104.47,50.35635339,-3.337008897,10000,-141.4216499,141.4206994,0,0,0,135 +104.48,50.3563407,-3.336989056,10000,-141.4146864,141.4209599,0,0,0,135 +104.49,50.35632801,-3.336969214,10000,-141.4181677,141.4216658,0,0,0,135 +104.5,50.35631531,-3.336949373,10000,-141.4181674,141.4217035,0,0,0,135 +104.51,50.35630262,-3.336929531,10000,-141.4146855,141.421073,0,0,0,135 +104.52,50.35628993,-3.33690969,10000,-141.4181668,141.4206653,0,0,0,135 +104.53,50.35627723,-3.336889849,10000,-141.4181665,141.4211484,0,0,0,135 +104.54,50.35626454,-3.336870007,10000,-141.4146846,141.4218544,0,0,0,135 +104.55,50.35625185,-3.336850166,10000,-141.4216474,141.4218921,0,0,0,135 +104.56,50.35623915,-3.336830324,10000,-141.4320918,141.4212616,0,0,0,135 +104.57,50.35622646,-3.336810483,10000,-141.4320915,141.4208538,0,0,0,135 +104.58,50.35621376,-3.336790642,10000,-141.4216465,141.4211143,0,0,0,135 +104.59,50.35620107,-3.3367708,10000,-141.414683,141.421152,0,0,0,135 +104.6,50.35618838,-3.336750959,10000,-141.4181643,141.420967,0,0,0,135 +104.61,50.35617568,-3.336731118,10000,-141.418164,141.4214501,0,0,0,135 +104.62,50.35616299,-3.336711276,10000,-141.4146821,141.4221561,0,0,0,135 +104.63,50.3561503,-3.336691435,10000,-141.4216449,141.4221938,0,0,0,135 +104.64,50.3561376,-3.336671593,10000,-141.4320894,141.4215633,0,0,0,135 +104.65,50.35612491,-3.336651752,10000,-141.4320891,141.4211555,0,0,0,135 +104.66,50.35611221,-3.336631911,10000,-141.421644,141.421416,0,0,0,135 +104.67,50.35609952,-3.336612069,10000,-141.4146805,141.4212309,0,0,0,135 +104.68,50.35608683,-3.336592228,10000,-141.4181618,141.4203777,0,0,0,135 +104.69,50.35607413,-3.336572387,10000,-141.4181615,141.4204154,0,0,0,135 +104.7,50.35606144,-3.336552546,10000,-141.4146796,141.4213441,0,0,0,135 +104.71,50.35604875,-3.336532704,10000,-141.4216425,141.4216045,0,0,0,135 +104.72,50.35603605,-3.336512863,10000,-141.4320869,141.4214195,0,0,0,135 +104.73,50.35602336,-3.336493022,10000,-141.4320866,141.4216799,0,0,0,135 +104.74,50.35601066,-3.33647318,10000,-141.4216415,141.4217176,0,0,0,135 +104.75,50.35599797,-3.336453339,10000,-141.4146781,141.4215326,0,0,0,135 +104.76,50.35598528,-3.336433498,10000,-141.4181593,141.4217931,0,0,0,135 +104.77,50.35597258,-3.336413656,10000,-141.418159,141.421608,0,0,0,135 +104.78,50.35595989,-3.336393815,10000,-141.4146771,141.4207548,0,0,0,135 +104.79,50.3559472,-3.336373974,10000,-141.42164,141.4207925,0,0,0,135 +104.8,50.3559345,-3.336354133,10000,-141.4320844,141.4217212,0,0,0,135 +104.81,50.35592181,-3.336334291,10000,-141.4320841,141.4217589,0,0,0,135 +104.82,50.35590911,-3.33631445,10000,-141.421639,141.4209056,0,0,0,135 +104.83,50.35589642,-3.336294609,10000,-141.4146756,141.4209434,0,0,0,135 +104.84,50.35588373,-3.336274768,10000,-141.4181569,141.421872,0,0,0,135 +104.85,50.35587103,-3.336254926,10000,-141.4181566,141.4219097,0,0,0,135 +104.86,50.35585834,-3.336235085,10000,-141.4146747,141.4210565,0,0,0,135 +104.87,50.35584565,-3.336215244,10000,-141.4216375,141.4210942,0,0,0,135 +104.88,50.35583295,-3.336195403,10000,-141.4320819,141.4220229,0,0,0,135 +104.89,50.35582026,-3.336175561,10000,-141.4320816,141.4220606,0,0,0,135 +104.9,50.35580756,-3.33615572,10000,-141.4216366,141.4209846,0,0,0,135 +104.91,50.35579487,-3.336135879,10000,-141.4146731,141.4203541,0,0,0,135 +104.92,50.35578218,-3.336116038,10000,-141.4181544,141.42106,0,0,0,135 +104.93,50.35576948,-3.336096197,10000,-141.418154,141.4222114,0,0,0,135 +104.94,50.35575679,-3.336076355,10000,-141.4146722,141.4222491,0,0,0,135 +104.95,50.3557441,-3.336056514,10000,-141.421635,141.4211731,0,0,0,135 +104.96,50.3557314,-3.336036673,10000,-141.4320795,141.4205426,0,0,0,135 +104.97,50.35571871,-3.336016832,10000,-141.4320791,141.4210258,0,0,0,135 +104.98,50.35570601,-3.335996991,10000,-141.4216341,141.4212863,0,0,0,135 +104.99,50.35569332,-3.335977149,10000,-141.4146706,141.420433,0,0,0,135 +105,50.35568063,-3.335957309,10000,-141.4181519,141.420248,0,0,0,135 +105.01,50.35566793,-3.335937468,10000,-141.4181516,141.4216221,0,0,0,135 +105.02,50.35565524,-3.335917626,10000,-141.4146697,141.4223281,0,0,0,135 +105.03,50.35564255,-3.335897785,10000,-141.4216325,141.4214748,0,0,0,135 +105.04,50.35562985,-3.335877944,10000,-141.4320769,141.4206216,0,0,0,135 +105.05,50.35561716,-3.335858103,10000,-141.4320767,141.4206593,0,0,0,135 +105.06,50.35560446,-3.335838262,10000,-141.4216316,141.421588,0,0,0,135 +105.07,50.35559177,-3.335818421,10000,-141.4146682,141.4227394,0,0,0,135 +105.08,50.35557908,-3.335798579,10000,-141.4181494,141.4227771,0,0,0,135 +105.09,50.35556638,-3.335778738,10000,-141.4181491,141.4217011,0,0,0,135 +105.1,50.35555369,-3.335758897,10000,-141.4146672,141.4208478,0,0,0,135 +105.11,50.355541,-3.335739056,10000,-141.4181485,141.4206628,0,0,0,135 +105.12,50.3555283,-3.335719215,10000,-141.4181482,141.4207005,0,0,0,135 +105.13,50.35551561,-3.335699374,10000,-141.4146663,141.4207382,0,0,0,135 +105.14,50.35550292,-3.335679533,10000,-141.4216291,141.4209987,0,0,0,135 +105.15,50.35549022,-3.335659692,10000,-141.4320735,141.4219273,0,0,0,135 +105.16,50.35547753,-3.335639851,10000,-141.4320732,141.422856,0,0,0,135 +105.17,50.35546483,-3.335620009,10000,-141.4216282,141.4220028,0,0,0,135 +105.18,50.35545214,-3.335600168,10000,-141.4146648,141.4198131,0,0,0,135 +105.19,50.35543945,-3.335580328,10000,-141.418146,141.4191825,0,0,0,135 +105.2,50.35542675,-3.335560487,10000,-141.4181457,141.4210022,0,0,0,135 +105.21,50.35541406,-3.335540646,10000,-141.4146638,141.4230446,0,0,0,135 +105.22,50.35540137,-3.335520804,10000,-141.4216266,141.423305,0,0,0,135 +105.23,50.35538867,-3.335500963,10000,-141.4320711,141.422229,0,0,0,135 +105.24,50.35537598,-3.335481122,10000,-141.4320708,141.4213758,0,0,0,135 +105.25,50.35536328,-3.335461281,10000,-141.4216257,141.4211907,0,0,0,135 +105.26,50.35535059,-3.33544144,10000,-141.4146623,141.4212284,0,0,0,135 +105.27,50.3553379,-3.335421599,10000,-141.4181435,141.4212662,0,0,0,135 +105.28,50.3553252,-3.335401758,10000,-141.4181432,141.4213039,0,0,0,135 +105.29,50.35531251,-3.335381917,10000,-141.4146613,141.4213416,0,0,0,135 +105.3,50.35529982,-3.335362076,10000,-141.4216242,141.4213793,0,0,0,135 +105.31,50.35528712,-3.335342235,10000,-141.4320686,141.421417,0,0,0,135 +105.32,50.35527443,-3.335322394,10000,-141.4320683,141.4214547,0,0,0,135 +105.33,50.35526173,-3.335302553,10000,-141.4216232,141.4214924,0,0,0,135 +105.34,50.35524904,-3.335282712,10000,-141.4146598,141.4215301,0,0,0,135 +105.35,50.35523635,-3.335262871,10000,-141.418141,141.4215678,0,0,0,135 +105.36,50.35522365,-3.33524303,10000,-141.4181407,141.4216055,0,0,0,135 +105.37,50.35521096,-3.335223189,10000,-141.4146589,141.4216433,0,0,0,135 +105.38,50.35519827,-3.335203348,10000,-141.4216217,141.421681,0,0,0,135 +105.39,50.35518557,-3.335183507,10000,-141.4320661,141.4217187,0,0,0,135 +105.4,50.35517288,-3.335163666,10000,-141.4320658,141.4217564,0,0,0,135 +105.41,50.35516018,-3.335143825,10000,-141.4216208,141.4215714,0,0,0,135 +105.42,50.35514749,-3.335123984,10000,-141.4146573,141.4207181,0,0,0,135 +105.43,50.3551348,-3.335104143,10000,-141.4181386,141.4196421,0,0,0,135 +105.44,50.3551221,-3.335084303,10000,-141.4181383,141.4196798,0,0,0,135 +105.45,50.35510941,-3.335064462,10000,-141.4146564,141.4208312,0,0,0,135 +105.46,50.35509672,-3.335044621,10000,-141.4216192,141.4217599,0,0,0,135 +105.47,50.35508402,-3.33502478,10000,-141.4320636,141.4220204,0,0,0,135 +105.48,50.35507133,-3.335004939,10000,-141.4320633,141.4220581,0,0,0,135 +105.49,50.35505863,-3.334985098,10000,-141.4216183,141.4220958,0,0,0,135 +105.5,50.35504594,-3.334965257,10000,-141.4146548,141.4221335,0,0,0,135 +105.51,50.35503325,-3.334945416,10000,-141.4181361,141.4219485,0,0,0,135 +105.52,50.35502055,-3.334925575,10000,-141.4181358,141.4210952,0,0,0,135 +105.53,50.35500786,-3.334905734,10000,-141.4146539,141.4200192,0,0,0,135 +105.54,50.35499517,-3.334885894,10000,-141.4216167,141.4200569,0,0,0,135 +105.55,50.35498247,-3.334866053,10000,-141.4320612,141.4212083,0,0,0,135 +105.56,50.35496978,-3.334846212,10000,-141.4320609,141.422137,0,0,0,135 +105.57,50.35495708,-3.334826371,10000,-141.4216158,141.4221747,0,0,0,135 +105.58,50.35494439,-3.33480653,10000,-141.4146523,141.4213214,0,0,0,135 +105.59,50.3549317,-3.334786689,10000,-141.4181336,141.4202454,0,0,0,135 +105.6,50.354919,-3.334766849,10000,-141.4181333,141.4202831,0,0,0,135 +105.61,50.35490631,-3.334747008,10000,-141.4146514,141.4214346,0,0,0,135 +105.62,50.35489362,-3.334727167,10000,-141.4216143,141.4221405,0,0,0,135 +105.63,50.35488092,-3.334707326,10000,-141.4320587,141.42151,0,0,0,135 +105.64,50.35486823,-3.334687485,10000,-141.4320583,141.420434,0,0,0,135 +105.65,50.35485553,-3.334667645,10000,-141.4216133,141.4204717,0,0,0,135 +105.66,50.35484284,-3.334647804,10000,-141.4146499,141.4216231,0,0,0,135 +105.67,50.35483015,-3.334627963,10000,-141.4181311,141.4223291,0,0,0,135 +105.68,50.35481745,-3.334608122,10000,-141.4181308,141.4216985,0,0,0,135 +105.69,50.35480476,-3.334588281,10000,-141.4146489,141.4206225,0,0,0,135 +105.7,50.35479207,-3.334568441,10000,-141.4181302,141.4206602,0,0,0,135 +105.71,50.35477937,-3.3345486,10000,-141.4181299,141.4218117,0,0,0,135 +105.72,50.35476668,-3.334528759,10000,-141.414648,141.4225176,0,0,0,135 +105.73,50.35475399,-3.334508918,10000,-141.4216108,141.4218871,0,0,0,135 +105.74,50.35474129,-3.334489077,10000,-141.4320552,141.4208111,0,0,0,135 +105.75,50.3547286,-3.334469237,10000,-141.4320549,141.420626,0,0,0,135 +105.76,50.3547159,-3.334449396,10000,-141.4216099,141.4208865,0,0,0,135 +105.77,50.35470321,-3.334429555,10000,-141.4146465,141.4207015,0,0,0,135 +105.78,50.35469052,-3.334409715,10000,-141.4181277,141.4209619,0,0,0,135 +105.79,50.35467782,-3.334389874,10000,-141.4181274,141.4221133,0,0,0,135 +105.8,50.35466513,-3.334370033,10000,-141.4146455,141.4228193,0,0,0,135 +105.81,50.35465244,-3.334350192,10000,-141.4216084,141.4221888,0,0,0,135 +105.82,50.35463974,-3.334330351,10000,-141.4320528,141.42089,0,0,0,135 +105.83,50.35462705,-3.334310511,10000,-141.4320525,141.4200367,0,0,0,135 +105.84,50.35461435,-3.33429067,10000,-141.4216074,141.4200744,0,0,0,135 +105.85,50.35460166,-3.33427083,10000,-141.414644,141.4210031,0,0,0,135 +105.86,50.35458897,-3.334250989,10000,-141.4181252,141.4223773,0,0,0,135 +105.87,50.35457627,-3.334231148,10000,-141.4181249,141.4230833,0,0,0,135 +105.88,50.35456358,-3.334211307,10000,-141.4146431,141.4224527,0,0,0,135 +105.89,50.35455089,-3.334191466,10000,-141.4216059,141.421154,0,0,0,135 +105.9,50.35453819,-3.334171626,10000,-141.4320503,141.4203007,0,0,0,135 +105.91,50.3545255,-3.334151785,10000,-141.43205,141.4203384,0,0,0,135 +105.92,50.3545128,-3.334131945,10000,-141.421605,141.4212671,0,0,0,135 +105.93,50.35450011,-3.334112104,10000,-141.4146415,141.4224185,0,0,0,135 +105.94,50.35448742,-3.334092263,10000,-141.4181228,141.4222335,0,0,0,135 +105.95,50.35447472,-3.334072422,10000,-141.4181225,141.4204892,0,0,0,135 +105.96,50.35446203,-3.334052582,10000,-141.4146406,141.4194132,0,0,0,135 +105.97,50.35444934,-3.334032742,10000,-141.4216034,141.4205647,0,0,0,135 +105.98,50.35443664,-3.334012901,10000,-141.4320478,141.4223843,0,0,0,135 +105.99,50.35442395,-3.33399306,10000,-141.4320475,141.4226448,0,0,0,135 +106,50.35441125,-3.333973219,10000,-141.4216025,141.4215688,0,0,0,135 +106.01,50.35439856,-3.333953379,10000,-141.414639,141.4207155,0,0,0,135 +106.02,50.35438587,-3.333933538,10000,-141.4181203,141.4207532,0,0,0,135 +106.03,50.35437317,-3.333913698,10000,-141.41812,141.4214591,0,0,0,135 +106.04,50.35436048,-3.333893857,10000,-141.4146381,141.4219423,0,0,0,135 +106.05,50.35434779,-3.333874016,10000,-141.4216009,141.4215346,0,0,0,135 +106.06,50.35433509,-3.333854176,10000,-141.4320453,141.420904,0,0,0,135 +106.07,50.3543224,-3.333834335,10000,-141.432045,141.4209417,0,0,0,135 +106.08,50.3543097,-3.333814495,10000,-141.4216,141.4216477,0,0,0,135 +106.09,50.35429701,-3.333794654,10000,-141.4146366,141.4221309,0,0,0,135 +106.1,50.35428432,-3.333774813,10000,-141.4181178,141.4219458,0,0,0,135 +106.11,50.35427162,-3.333754973,10000,-141.4181175,141.4219836,0,0,0,135 +106.12,50.35425893,-3.333735132,10000,-141.4146356,141.4220213,0,0,0,135 +106.13,50.35424624,-3.333715291,10000,-141.4181169,141.4209452,0,0,0,135 +106.14,50.35423354,-3.333695451,10000,-141.4181166,141.420092,0,0,0,135 +106.15,50.35422085,-3.333675611,10000,-141.4146347,141.4210207,0,0,0,135 +106.16,50.35420816,-3.33365577,10000,-141.4215975,141.4219493,0,0,0,135 +106.17,50.35419546,-3.333635929,10000,-141.4320419,141.4210961,0,0,0,135 +106.18,50.35418277,-3.333616089,10000,-141.4320416,141.4202428,0,0,0,135 +106.19,50.35417007,-3.333596249,10000,-141.4215966,141.4211715,0,0,0,135 +106.2,50.35415738,-3.333576408,10000,-141.4146332,141.4223229,0,0,0,135 +106.21,50.35414469,-3.333556567,10000,-141.4181144,141.4221379,0,0,0,135 +106.22,50.35413199,-3.333536727,10000,-141.4181141,141.4215074,0,0,0,135 +106.23,50.3541193,-3.333516886,10000,-141.4146322,141.4213223,0,0,0,135 +106.24,50.35410661,-3.333497046,10000,-141.421595,141.42136,0,0,0,135 +106.25,50.35409391,-3.333477205,10000,-141.4320395,141.4213977,0,0,0,135 +106.26,50.35408122,-3.333457365,10000,-141.4320392,141.4212127,0,0,0,135 +106.27,50.35406852,-3.333437524,10000,-141.4215941,141.4205822,0,0,0,135 +106.28,50.35405583,-3.333417684,10000,-141.4146306,141.4203971,0,0,0,135 +106.29,50.35404314,-3.333397844,10000,-141.4181119,141.4215486,0,0,0,135 +106.3,50.35403044,-3.333378003,10000,-141.4181116,141.4224773,0,0,0,135 +106.31,50.35401775,-3.333358162,10000,-141.4146297,141.421624,0,0,0,135 +106.32,50.35400506,-3.333338322,10000,-141.4215926,141.420548,0,0,0,135 +106.33,50.35399236,-3.333318482,10000,-141.432037,141.4208084,0,0,0,135 +106.34,50.35397967,-3.333298641,10000,-141.4320367,141.4215144,0,0,0,135 +106.35,50.35396697,-3.333278801,10000,-141.4215916,141.4215521,0,0,0,135 +106.36,50.35395428,-3.33325896,10000,-141.4146282,141.4209215,0,0,0,135 +106.37,50.35394159,-3.33323912,10000,-141.4181095,141.4205138,0,0,0,135 +106.38,50.35392889,-3.33321928,10000,-141.4181091,141.420997,0,0,0,135 +106.39,50.3539162,-3.333199439,10000,-141.4146272,141.4219257,0,0,0,135 +106.4,50.35390351,-3.333179599,10000,-141.4215901,141.4228544,0,0,0,135 +106.41,50.35389081,-3.333159758,10000,-141.4320345,141.4231148,0,0,0,135 +106.42,50.35387812,-3.333139917,10000,-141.4320342,141.4220388,0,0,0,135 +106.43,50.35386542,-3.333120077,10000,-141.4215892,141.4209627,0,0,0,135 +106.44,50.35385273,-3.333100237,10000,-141.4146257,141.4210005,0,0,0,135 +106.45,50.35384004,-3.333080396,10000,-141.4181069,141.4210382,0,0,0,135 +106.46,50.35382734,-3.333060556,10000,-141.4181067,141.4208531,0,0,0,135 +106.47,50.35381465,-3.333040716,10000,-141.4146248,141.4213363,0,0,0,135 +106.48,50.35380196,-3.333020875,10000,-141.4215876,141.4220423,0,0,0,135 +106.49,50.35378926,-3.333001035,10000,-141.432032,141.42208,0,0,0,135 +106.5,50.35377657,-3.332981194,10000,-141.4320317,141.4212267,0,0,0,135 +106.51,50.35376387,-3.332961354,10000,-141.4215867,141.4201507,0,0,0,135 +106.52,50.35375118,-3.332941514,10000,-141.4146232,141.4201884,0,0,0,135 +106.53,50.35373849,-3.332921674,10000,-141.4181045,141.4211171,0,0,0,135 +106.54,50.35372579,-3.332901833,10000,-141.4181042,141.4213775,0,0,0,135 +106.55,50.3537131,-3.332881993,10000,-141.4146223,141.4211925,0,0,0,135 +106.56,50.35370041,-3.332862153,10000,-141.4215851,141.4214529,0,0,0,135 +106.57,50.35368771,-3.332842312,10000,-141.4320295,141.4214907,0,0,0,135 +106.58,50.35367502,-3.332822472,10000,-141.4320292,141.4213056,0,0,0,135 +106.59,50.35366232,-3.332802632,10000,-141.4215842,141.4215661,0,0,0,135 +106.6,50.35364963,-3.332782791,10000,-141.4146207,141.421381,0,0,0,135 +106.61,50.35363694,-3.332762951,10000,-141.418102,141.4205277,0,0,0,135 +106.62,50.35362424,-3.332743111,10000,-141.4181017,141.4205654,0,0,0,135 +106.63,50.35361155,-3.332723271,10000,-141.4146198,141.4217169,0,0,0,135 +106.64,50.35359886,-3.33270343,10000,-141.4215826,141.4226456,0,0,0,135 +106.65,50.35358616,-3.33268359,10000,-141.4320271,141.4226833,0,0,0,135 +106.66,50.35357347,-3.332663749,10000,-141.4320268,141.42183,0,0,0,135 +106.67,50.35356077,-3.332643909,10000,-141.4215817,141.4205312,0,0,0,135 +106.68,50.35354808,-3.332624069,10000,-141.4146183,141.4199007,0,0,0,135 +106.69,50.35353539,-3.332604229,10000,-141.4180995,141.4206067,0,0,0,135 +106.7,50.35352269,-3.332584389,10000,-141.4180992,141.4217581,0,0,0,135 +106.71,50.35351,-3.332564548,10000,-141.4146173,141.4217958,0,0,0,135 +106.72,50.35349731,-3.332544708,10000,-141.4215802,141.4209425,0,0,0,135 +106.73,50.35348461,-3.332524868,10000,-141.4320246,141.4209802,0,0,0,135 +106.74,50.35347192,-3.332505028,10000,-141.4320243,141.4219089,0,0,0,135 +106.75,50.35345922,-3.332485187,10000,-141.4215792,141.4219467,0,0,0,135 +106.76,50.35344653,-3.332465347,10000,-141.4146158,141.4210934,0,0,0,135 +106.77,50.35343384,-3.332445507,10000,-141.418097,141.4211311,0,0,0,135 +106.78,50.35342114,-3.332425667,10000,-141.4180967,141.4220598,0,0,0,135 +106.79,50.35340845,-3.332405826,10000,-141.4146149,141.4220975,0,0,0,135 +106.8,50.35339576,-3.332385986,10000,-141.4180961,141.4210214,0,0,0,135 +106.81,50.35338306,-3.332366146,10000,-141.4180958,141.4203909,0,0,0,135 +106.82,50.35337037,-3.332346306,10000,-141.4146139,141.4210968,0,0,0,135 +106.83,50.35335768,-3.332326466,10000,-141.4215768,141.4222483,0,0,0,135 +106.84,50.35334498,-3.332306625,10000,-141.4320212,141.422286,0,0,0,135 +106.85,50.35333229,-3.332286785,10000,-141.4320209,141.4214327,0,0,0,135 +106.86,50.35331959,-3.332266945,10000,-141.4215758,141.4212477,0,0,0,135 +106.87,50.3533069,-3.332247105,10000,-141.4146124,141.4215081,0,0,0,135 +106.88,50.35329421,-3.332227264,10000,-141.4180936,141.4213231,0,0,0,135 +106.89,50.35328151,-3.332207425,10000,-141.4180933,141.4213608,0,0,0,135 +106.9,50.35326882,-3.332187584,10000,-141.4146115,141.4216213,0,0,0,135 +106.91,50.35325613,-3.332167744,10000,-141.4215743,141.4212135,0,0,0,135 +106.92,50.35324343,-3.332147904,10000,-141.4320187,141.4205829,0,0,0,135 +106.93,50.35323074,-3.332128064,10000,-141.4320184,141.4203979,0,0,0,135 +106.94,50.35321804,-3.332108224,10000,-141.4215733,141.4206583,0,0,0,135 +106.95,50.35320535,-3.332088384,10000,-141.4146099,141.4213643,0,0,0,135 +106.96,50.35319266,-3.332068544,10000,-141.4180912,141.4218475,0,0,0,135 +106.97,50.35317996,-3.332048703,10000,-141.4180908,141.4216625,0,0,0,135 +106.98,50.35316727,-3.332028864,10000,-141.4146089,141.4217002,0,0,0,135 +106.99,50.35315458,-3.332009023,10000,-141.4215718,141.4219606,0,0,0,135 +107,50.35314188,-3.331989183,10000,-141.4320162,141.4215528,0,0,0,135 +107.01,50.35312919,-3.331969343,10000,-141.4320159,141.4209223,0,0,0,135 +107.02,50.35311649,-3.331949503,10000,-141.4215709,141.4207372,0,0,0,135 +107.03,50.3531038,-3.331929663,10000,-141.4146074,141.4207749,0,0,0,135 +107.04,50.35309111,-3.331909823,10000,-141.4180887,141.4210354,0,0,0,135 +107.05,50.35307841,-3.331889983,10000,-141.4180884,141.4217414,0,0,0,135 +107.06,50.35306572,-3.331870143,10000,-141.4146065,141.4220018,0,0,0,135 +107.07,50.35305303,-3.331850302,10000,-141.4215693,141.4211485,0,0,0,135 +107.08,50.35304033,-3.331830463,10000,-141.4320137,141.4207407,0,0,0,135 +107.09,50.35302764,-3.331810623,10000,-141.4320134,141.4214467,0,0,0,135 +107.1,50.35301494,-3.331790782,10000,-141.4215684,141.4219299,0,0,0,135 +107.11,50.35300225,-3.331770943,10000,-141.4146049,141.4219676,0,0,0,135 +107.12,50.35298956,-3.331751102,10000,-141.4180862,141.4215598,0,0,0,135 +107.13,50.35297686,-3.331731262,10000,-141.4180859,141.4209293,0,0,0,135 +107.14,50.35296417,-3.331711423,10000,-141.414604,141.4211897,0,0,0,135 +107.15,50.35295148,-3.331691582,10000,-141.4215669,141.4214502,0,0,0,135 +107.16,50.35293878,-3.331671742,10000,-141.4320113,141.4210424,0,0,0,135 +107.17,50.35292609,-3.331651903,10000,-141.4320109,141.4213028,0,0,0,135 +107.18,50.35291339,-3.331632062,10000,-141.4215659,141.4215633,0,0,0,135 +107.19,50.3529007,-3.331612222,10000,-141.4146024,141.4211555,0,0,0,135 +107.2,50.35288801,-3.331592383,10000,-141.4180837,141.421416,0,0,0,135 +107.21,50.35287531,-3.331572542,10000,-141.4180834,141.4216764,0,0,0,135 +107.22,50.35286262,-3.331552702,10000,-141.4146015,141.4212686,0,0,0,135 +107.23,50.35284993,-3.331532863,10000,-141.4215644,141.4215291,0,0,0,135 +107.24,50.35283723,-3.331513022,10000,-141.4320088,141.4215668,0,0,0,135 +107.25,50.35282454,-3.331493182,10000,-141.4320085,141.4204907,0,0,0,135 +107.26,50.35281184,-3.331473343,10000,-141.4215634,141.4205284,0,0,0,135 +107.27,50.35279915,-3.331453503,10000,-141.4146,141.4216799,0,0,0,135 +107.28,50.35278646,-3.331433662,10000,-141.4180812,141.4214949,0,0,0,135 +107.29,50.35277376,-3.331413823,10000,-141.4180809,141.4206415,0,0,0,135 +107.3,50.35276107,-3.331393983,10000,-141.414599,141.420902,0,0,0,135 +107.31,50.35274838,-3.331374143,10000,-141.4215619,141.421608,0,0,0,135 +107.32,50.35273568,-3.331354303,10000,-141.4320063,141.4218684,0,0,0,135 +107.33,50.35272299,-3.331334463,10000,-141.432006,141.4219061,0,0,0,135 +107.34,50.35271029,-3.331314623,10000,-141.4215609,141.4217211,0,0,0,135 +107.35,50.3526976,-3.331294783,10000,-141.4145975,141.4210905,0,0,0,135 +107.36,50.35268491,-3.331274943,10000,-141.4180788,141.4209055,0,0,0,135 +107.37,50.35267221,-3.331255104,10000,-141.4180785,141.4218342,0,0,0,135 +107.38,50.35265952,-3.331235263,10000,-141.4145966,141.4220947,0,0,0,135 +107.39,50.35264683,-3.331215423,10000,-141.4180778,141.4207958,0,0,0,135 +107.4,50.35263413,-3.331195584,10000,-141.4180775,141.4201653,0,0,0,135 +107.41,50.35262144,-3.331175744,10000,-141.4145956,141.421094,0,0,0,135 +107.42,50.35260875,-3.331155904,10000,-141.4215585,141.4220227,0,0,0,135 +107.43,50.35259605,-3.331136064,10000,-141.4320029,141.4222832,0,0,0,135 +107.44,50.35258336,-3.331116224,10000,-141.4320026,141.4223209,0,0,0,135 +107.45,50.35257066,-3.331096384,10000,-141.4215575,141.4223586,0,0,0,135 +107.46,50.35255797,-3.331076544,10000,-141.4145941,141.4221736,0,0,0,135 +107.47,50.35254528,-3.331056704,10000,-141.4180753,141.4213203,0,0,0,135 +107.48,50.35253258,-3.331036864,10000,-141.418075,141.4202442,0,0,0,135 +107.49,50.35251989,-3.331017025,10000,-141.4145932,141.4202819,0,0,0,135 +107.5,50.3525072,-3.330997185,10000,-141.421556,141.4214334,0,0,0,135 +107.51,50.3524945,-3.330977345,10000,-141.4320004,141.4221393,0,0,0,135 +107.52,50.35248181,-3.330957505,10000,-141.4320001,141.4215088,0,0,0,135 +107.53,50.35246911,-3.330937665,10000,-141.4215551,141.4204327,0,0,0,135 +107.54,50.35245642,-3.330917826,10000,-141.4145916,141.4204704,0,0,0,135 +107.55,50.35244373,-3.330897986,10000,-141.4180729,141.4216219,0,0,0,135 +107.56,50.35243103,-3.330878146,10000,-141.4180726,141.4223279,0,0,0,135 +107.57,50.35241834,-3.330858306,10000,-141.4145907,141.4216973,0,0,0,135 +107.58,50.35240565,-3.330838466,10000,-141.4215535,141.4206212,0,0,0,135 +107.59,50.35239295,-3.330818627,10000,-141.4319979,141.420659,0,0,0,135 +107.6,50.35238026,-3.330798787,10000,-141.4319976,141.4218104,0,0,0,135 +107.61,50.35236756,-3.330778947,10000,-141.4215526,141.4225164,0,0,0,135 +107.62,50.35235487,-3.330759107,10000,-141.4145891,141.4218858,0,0,0,135 +107.63,50.35234218,-3.330739267,10000,-141.4180704,141.4208098,0,0,0,135 +107.64,50.35232948,-3.330719428,10000,-141.4180701,141.4206247,0,0,0,135 +107.65,50.35231679,-3.330699588,10000,-141.4145882,141.4208852,0,0,0,135 +107.66,50.3523041,-3.330679748,10000,-141.4215511,141.4207001,0,0,0,135 +107.67,50.3522914,-3.330659909,10000,-141.4319955,141.4209606,0,0,0,135 +107.68,50.35227871,-3.330640069,10000,-141.4319951,141.4221121,0,0,0,135 +107.69,50.35226601,-3.330620229,10000,-141.4215501,141.4228181,0,0,0,135 +107.7,50.35225332,-3.330600389,10000,-141.4145867,141.4221875,0,0,0,135 +107.71,50.35224063,-3.330580549,10000,-141.4180679,141.4208887,0,0,0,135 +107.72,50.35222793,-3.33056071,10000,-141.4180676,141.4200353,0,0,0,135 +107.73,50.35221524,-3.33054087,10000,-141.4145857,141.4200731,0,0,0,135 +107.74,50.35220255,-3.330521031,10000,-141.4215486,141.4210018,0,0,0,135 +107.75,50.35218985,-3.330501191,10000,-141.431993,141.4221533,0,0,0,135 +107.76,50.35217716,-3.330481351,10000,-141.4319927,141.422191,0,0,0,135 +107.77,50.35216446,-3.330461511,10000,-141.4215476,141.4213377,0,0,0,135 +107.78,50.35215177,-3.330441672,10000,-141.4145842,141.4213754,0,0,0,135 +107.79,50.35213908,-3.330421832,10000,-141.4180654,141.4223041,0,0,0,135 +107.8,50.35212638,-3.330401992,10000,-141.4180651,141.4223418,0,0,0,135 +107.81,50.35211369,-3.330382152,10000,-141.4145833,141.4212657,0,0,0,135 +107.82,50.352101,-3.330362313,10000,-141.4215461,141.4204124,0,0,0,135 +107.83,50.3520883,-3.330342473,10000,-141.4319905,141.4202274,0,0,0,135 +107.84,50.35207561,-3.330322634,10000,-141.4319902,141.4202651,0,0,0,135 +107.85,50.35206291,-3.330302794,10000,-141.4215452,141.4205255,0,0,0,135 +107.86,50.35205022,-3.330282955,10000,-141.4145817,141.4212315,0,0,0,135 +107.87,50.35203753,-3.330263115,10000,-141.418063,141.4217147,0,0,0,135 +107.88,50.35202483,-3.330243275,10000,-141.4180626,141.4215297,0,0,0,135 +107.89,50.35201214,-3.330223436,10000,-141.4145808,141.4215674,0,0,0,135 +107.9,50.35199945,-3.330203596,10000,-141.4215436,141.4218278,0,0,0,135 +107.91,50.35198675,-3.330183756,10000,-141.431988,141.4216428,0,0,0,135 +107.92,50.35197406,-3.330163917,10000,-141.4319877,141.4216805,0,0,0,135 +107.93,50.35196136,-3.330144077,10000,-141.4215427,141.421941,0,0,0,135 +107.94,50.35194867,-3.330124237,10000,-141.4145792,141.4217559,0,0,0,135 +107.95,50.35193598,-3.330104398,10000,-141.4180605,141.4217936,0,0,0,135 +107.96,50.35192328,-3.330084558,10000,-141.4180602,141.4220541,0,0,0,135 +107.97,50.35191059,-3.330064718,10000,-141.4145783,141.4216463,0,0,0,135 +107.98,50.3518979,-3.330044879,10000,-141.4215411,141.4210157,0,0,0,135 +107.99,50.3518852,-3.330025039,10000,-141.4319855,141.4208306,0,0,0,135 +108,50.35187251,-3.3300052,10000,-141.4319852,141.4208683,0,0,0,135 +108.01,50.35185981,-3.32998536,10000,-141.4215402,141.4211288,0,0,0,135 +108.02,50.35184712,-3.329965521,10000,-141.4145768,141.4218348,0,0,0,135 +108.03,50.35183443,-3.329945681,10000,-141.418058,141.422318,0,0,0,135 +108.04,50.35182173,-3.329925841,10000,-141.4180577,141.4219102,0,0,0,135 +108.05,50.35180904,-3.329906002,10000,-141.4145758,141.4212796,0,0,0,135 +108.06,50.35179635,-3.329886162,10000,-141.4215386,141.4210946,0,0,0,135 +108.07,50.35178365,-3.329866323,10000,-141.4319831,141.4211323,0,0,0,135 +108.08,50.35177096,-3.329846483,10000,-141.4319828,141.42117,0,0,0,135 +108.09,50.35175826,-3.329826644,10000,-141.4215377,141.4212077,0,0,0,135 +108.1,50.35174557,-3.329806804,10000,-141.4145743,141.4212454,0,0,0,135 +108.11,50.35173288,-3.329786965,10000,-141.4180555,141.4210603,0,0,0,135 +108.12,50.35172018,-3.329767125,10000,-141.4180552,141.4204298,0,0,0,135 +108.13,50.35170749,-3.329747286,10000,-141.4145733,141.420022,0,0,0,135 +108.14,50.3516948,-3.329727447,10000,-141.4215362,141.4205052,0,0,0,135 +108.15,50.3516821,-3.329707607,10000,-141.4319806,141.4212112,0,0,0,135 +108.16,50.35166941,-3.329687768,10000,-141.4319803,141.4214716,0,0,0,135 +108.17,50.35165671,-3.329667928,10000,-141.4215352,141.4215093,0,0,0,135 +108.18,50.35164402,-3.329648089,10000,-141.4145718,141.421547,0,0,0,135 +108.19,50.35163133,-3.329628249,10000,-141.4180531,141.4215847,0,0,0,135 +108.2,50.35161863,-3.32960841,10000,-141.4180527,141.4216224,0,0,0,135 +108.21,50.35160594,-3.32958857,10000,-141.4145708,141.4216601,0,0,0,135 +108.22,50.35159325,-3.329568731,10000,-141.4180521,141.4216979,0,0,0,135 +108.23,50.35158055,-3.329548891,10000,-141.4180518,141.4217356,0,0,0,135 +108.24,50.35156786,-3.329529052,10000,-141.4145699,141.4217733,0,0,0,135 +108.25,50.35155517,-3.329509212,10000,-141.4215328,141.421811,0,0,0,135 +108.26,50.35154247,-3.329489373,10000,-141.4319772,141.4216259,0,0,0,135 +108.27,50.35152978,-3.329469533,10000,-141.4319769,141.4209953,0,0,0,135 +108.28,50.35151708,-3.329449694,10000,-141.4215318,141.4205875,0,0,0,135 +108.29,50.35150439,-3.329429855,10000,-141.4145684,141.4210708,0,0,0,135 +108.3,50.3514917,-3.329410015,10000,-141.4180496,141.4217767,0,0,0,135 +108.31,50.351479,-3.329390176,10000,-141.4180493,141.4220372,0,0,0,135 +108.32,50.35146631,-3.329370336,10000,-141.4145674,141.4220749,0,0,0,135 +108.33,50.35145362,-3.329350497,10000,-141.4215303,141.4218898,0,0,0,135 +108.34,50.35144092,-3.329330657,10000,-141.4319747,141.4210365,0,0,0,135 +108.35,50.35142823,-3.329310818,10000,-141.4319744,141.4199604,0,0,0,135 +108.36,50.35141553,-3.329290979,10000,-141.4215294,141.4199981,0,0,0,135 +108.37,50.35140284,-3.32927114,10000,-141.4145659,141.4211496,0,0,0,135 +108.38,50.35139015,-3.3292513,10000,-141.4180472,141.4220784,0,0,0,135 +108.39,50.35137745,-3.329231461,10000,-141.4180469,141.4221161,0,0,0,135 +108.4,50.35136476,-3.329211621,10000,-141.414565,141.4214855,0,0,0,135 +108.41,50.35135207,-3.329191782,10000,-141.4215278,141.4210777,0,0,0,135 +108.42,50.35133937,-3.329171943,10000,-141.4319722,141.4213381,0,0,0,135 +108.43,50.35132668,-3.329152103,10000,-141.4319719,141.4213759,0,0,0,135 +108.44,50.35131398,-3.329132264,10000,-141.4215269,141.4211908,0,0,0,135 +108.45,50.35130129,-3.329112425,10000,-141.4145634,141.4214513,0,0,0,135 +108.46,50.3512886,-3.329092585,10000,-141.4180447,141.421489,0,0,0,135 +108.47,50.3512759,-3.329072746,10000,-141.4180444,141.4213039,0,0,0,135 +108.48,50.35126321,-3.329052907,10000,-141.4145625,141.4215644,0,0,0,135 +108.49,50.35125052,-3.329033067,10000,-141.4215253,141.4216021,0,0,0,135 +108.5,50.35123782,-3.329013228,10000,-141.4319697,141.421417,0,0,0,135 +108.51,50.35122513,-3.328993389,10000,-141.4319694,141.4216775,0,0,0,135 +108.52,50.35121243,-3.328973549,10000,-141.4215244,141.4214924,0,0,0,135 +108.53,50.35119974,-3.32895371,10000,-141.4145609,141.4204163,0,0,0,135 +108.54,50.35118705,-3.328933871,10000,-141.4180422,141.4197858,0,0,0,135 +108.55,50.35117435,-3.328914032,10000,-141.4180419,141.4204917,0,0,0,135 +108.56,50.35116166,-3.328894193,10000,-141.41456,141.4216433,0,0,0,135 +108.57,50.35114897,-3.328874353,10000,-141.4215229,141.421681,0,0,0,135 +108.58,50.35113627,-3.328854514,10000,-141.4319672,141.4208276,0,0,0,135 +108.59,50.35112358,-3.328834675,10000,-141.4319669,141.4208653,0,0,0,135 +108.6,50.35111088,-3.328814836,10000,-141.4215219,141.4217941,0,0,0,135 +108.61,50.35109819,-3.328794996,10000,-141.4145585,141.4218318,0,0,0,135 +108.62,50.3510855,-3.328775157,10000,-141.4180397,141.4209784,0,0,0,135 +108.63,50.3510728,-3.328755318,10000,-141.4180394,141.4210161,0,0,0,135 +108.64,50.35106011,-3.328735479,10000,-141.4145575,141.4219449,0,0,0,135 +108.65,50.35104742,-3.328715639,10000,-141.4215203,141.4219826,0,0,0,135 +108.66,50.35103472,-3.3286958,10000,-141.4319648,141.4211292,0,0,0,135 +108.67,50.35102203,-3.328675961,10000,-141.4319645,141.421167,0,0,0,135 +108.68,50.35100933,-3.328656122,10000,-141.4215195,141.4220957,0,0,0,135 +108.69,50.35099664,-3.328636282,10000,-141.414556,141.4221334,0,0,0,135 +108.7,50.35098395,-3.328616443,10000,-141.4180372,141.4212801,0,0,0,135 +108.71,50.35097125,-3.328596604,10000,-141.4180369,141.4213178,0,0,0,135 +108.72,50.35095856,-3.328576765,10000,-141.4145551,141.4222465,0,0,0,135 +108.73,50.35094587,-3.328556925,10000,-141.4215179,141.4222842,0,0,0,135 +108.74,50.35093317,-3.328537086,10000,-141.4319623,141.4212081,0,0,0,135 +108.75,50.35092048,-3.328517247,10000,-141.431962,141.4203548,0,0,0,135 +108.76,50.35090778,-3.328497408,10000,-141.4215169,141.4201697,0,0,0,135 +108.77,50.35089509,-3.328477569,10000,-141.4145535,141.4204302,0,0,0,135 +108.78,50.3508824,-3.32845773,10000,-141.4180348,141.4213589,0,0,0,135 +108.79,50.3508697,-3.328437891,10000,-141.4180345,141.4225105,0,0,0,135 +108.8,50.35085701,-3.328418051,10000,-141.4145526,141.4225482,0,0,0,135 +108.81,50.35084432,-3.328398212,10000,-141.4215154,141.421472,0,0,0,135 +108.82,50.35083162,-3.328378373,10000,-141.4319598,141.4206187,0,0,0,135 +108.83,50.35081893,-3.328358534,10000,-141.4319595,141.4204336,0,0,0,135 +108.84,50.35080623,-3.328338695,10000,-141.4215145,141.4206941,0,0,0,135 +108.85,50.35079354,-3.328318856,10000,-141.414551,141.4216229,0,0,0,135 +108.86,50.35078085,-3.328299017,10000,-141.4180323,141.4227744,0,0,0,135 +108.87,50.35076815,-3.328279177,10000,-141.418032,141.4228121,0,0,0,135 +108.88,50.35075546,-3.328259338,10000,-141.4145501,141.421736,0,0,0,135 +108.89,50.35074277,-3.328239499,10000,-141.4215129,141.4208826,0,0,0,135 +108.9,50.35073007,-3.32821966,10000,-141.4319573,141.4206976,0,0,0,135 +108.91,50.35071738,-3.328199821,10000,-141.431957,141.4207353,0,0,0,135 +108.92,50.35070468,-3.328179982,10000,-141.421512,141.420773,0,0,0,135 +108.93,50.35069199,-3.328160143,10000,-141.4145485,141.4208107,0,0,0,135 +108.94,50.3506793,-3.328140304,10000,-141.4180298,141.4208484,0,0,0,135 +108.95,50.3506666,-3.328120465,10000,-141.4180295,141.4211089,0,0,0,135 +108.96,50.35065391,-3.328100626,10000,-141.4145476,141.4218148,0,0,0,135 +108.97,50.35064122,-3.328080787,10000,-141.4215104,141.4220753,0,0,0,135 +108.98,50.35062852,-3.328060947,10000,-141.4319548,141.421222,0,0,0,135 +108.99,50.35061583,-3.328041109,10000,-141.4319545,141.4208141,0,0,0,135 +109,50.35060313,-3.32802127,10000,-141.4215095,141.4215201,0,0,0,135 +109.01,50.35059044,-3.32800143,10000,-141.4145461,141.4220034,0,0,0,135 +109.02,50.35057775,-3.327981592,10000,-141.4180273,141.4220411,0,0,0,135 +109.03,50.35056505,-3.327961752,10000,-141.418027,141.4216332,0,0,0,135 +109.04,50.35055236,-3.327941913,10000,-141.4145451,141.4207799,0,0,0,135 +109.05,50.35053967,-3.327922075,10000,-141.4180264,141.4205948,0,0,0,135 +109.06,50.35052697,-3.327902235,10000,-141.4180261,141.4213008,0,0,0,135 +109.07,50.35051428,-3.327882397,10000,-141.4145442,141.4222296,0,0,0,135 +109.08,50.35050159,-3.327862557,10000,-141.421507,141.4227128,0,0,0,135 +109.09,50.35048889,-3.327842718,10000,-141.4319515,141.4220822,0,0,0,135 +109.1,50.3504762,-3.327822879,10000,-141.4319511,141.4207833,0,0,0,135 +109.11,50.3504635,-3.32780304,10000,-141.4215061,141.4201528,0,0,0,135 +109.12,50.35045081,-3.327783202,10000,-141.4145426,141.420636,0,0,0,135 +109.13,50.35043812,-3.327763362,10000,-141.4180239,141.421342,0,0,0,135 +109.14,50.35042542,-3.327743524,10000,-141.4180236,141.4213797,0,0,0,135 +109.15,50.35041273,-3.327723684,10000,-141.4145417,141.4207491,0,0,0,135 +109.16,50.35040004,-3.327703846,10000,-141.4215046,141.4203413,0,0,0,135 +109.17,50.35038734,-3.327684007,10000,-141.431949,141.4208245,0,0,0,135 +109.18,50.35037465,-3.327664168,10000,-141.4319486,141.4215305,0,0,0,135 +109.19,50.35036195,-3.327644329,10000,-141.4215036,141.421791,0,0,0,135 +109.2,50.35034926,-3.32762449,10000,-141.4145402,141.4218287,0,0,0,135 +109.21,50.35033657,-3.327604651,10000,-141.4180215,141.4218664,0,0,0,135 +109.22,50.35032387,-3.327584812,10000,-141.4180211,141.4219041,0,0,0,135 +109.23,50.35031118,-3.327564973,10000,-141.4145392,141.4219418,0,0,0,135 +109.24,50.35029849,-3.327545134,10000,-141.4215021,141.4217567,0,0,0,135 +109.25,50.35028579,-3.327525295,10000,-141.4319465,141.4211261,0,0,0,135 +109.26,50.3502731,-3.327505456,10000,-141.4319462,141.4207183,0,0,0,135 +109.27,50.3502604,-3.327485618,10000,-141.4215012,141.4212015,0,0,0,135 +109.28,50.35024771,-3.327465778,10000,-141.4145377,141.4219075,0,0,0,135 +109.29,50.35023502,-3.32744594,10000,-141.4180189,141.4219452,0,0,0,135 +109.3,50.35022232,-3.3274261,10000,-141.4180186,141.4213146,0,0,0,135 +109.31,50.35020963,-3.327406262,10000,-141.4145368,141.4209068,0,0,0,135 +109.32,50.35019694,-3.327386423,10000,-141.4214996,141.4211673,0,0,0,135 +109.33,50.35018424,-3.327366584,10000,-141.431944,141.421205,0,0,0,135 +109.34,50.35017155,-3.327346745,10000,-141.4319437,141.4210199,0,0,0,135 +109.35,50.35015885,-3.327326907,10000,-141.4214986,141.4212804,0,0,0,135 +109.36,50.35014616,-3.327307067,10000,-141.4145352,141.4213181,0,0,0,135 +109.37,50.35013347,-3.327287229,10000,-141.4180165,141.421133,0,0,0,135 +109.38,50.35012077,-3.32726739,10000,-141.4180162,141.4216163,0,0,0,135 +109.39,50.35010808,-3.327247551,10000,-141.4145343,141.4220995,0,0,0,135 +109.4,50.35009539,-3.327227712,10000,-141.4214971,141.4214689,0,0,0,135 +109.41,50.35008269,-3.327207873,10000,-141.4319415,141.4203928,0,0,0,135 +109.42,50.35007,-3.327188035,10000,-141.4319412,141.4204305,0,0,0,135 +109.43,50.3500573,-3.327168196,10000,-141.4214962,141.4213593,0,0,0,135 +109.44,50.35004461,-3.327148357,10000,-141.4145328,141.4216197,0,0,0,135 +109.45,50.35003192,-3.327128518,10000,-141.418014,141.4214347,0,0,0,135 +109.46,50.35001922,-3.32710868,10000,-141.4180137,141.4216951,0,0,0,135 +109.47,50.35000653,-3.32708884,10000,-141.4145318,141.4217328,0,0,0,135 +109.48,50.34999384,-3.327069002,10000,-141.4214946,141.421325,0,0,0,135 +109.49,50.34998114,-3.327049163,10000,-141.4319391,141.4211399,0,0,0,135 +109.5,50.34996845,-3.327029324,10000,-141.4319387,141.4214004,0,0,0,135 +109.51,50.34995575,-3.327009486,10000,-141.4214937,141.4218836,0,0,0,135 +109.52,50.34994306,-3.326989646,10000,-141.4145302,141.4219213,0,0,0,135 +109.53,50.34993037,-3.326969808,10000,-141.4180115,141.4215135,0,0,0,135 +109.54,50.34991767,-3.326949969,10000,-141.4180112,141.4211057,0,0,0,135 +109.55,50.34990498,-3.32693013,10000,-141.4145293,141.4206979,0,0,0,135 +109.56,50.34989229,-3.326910292,10000,-141.4214922,141.4209583,0,0,0,135 +109.57,50.34987959,-3.326890453,10000,-141.4319366,141.4218871,0,0,0,135 +109.58,50.3498669,-3.326870614,10000,-141.4319362,141.4219248,0,0,0,135 +109.59,50.3498542,-3.326850775,10000,-141.4214912,141.4210714,0,0,0,135 +109.6,50.34984151,-3.326830937,10000,-141.4145278,141.4208864,0,0,0,135 +109.61,50.34982882,-3.326811098,10000,-141.418009,141.4211468,0,0,0,135 +109.62,50.34981612,-3.326791259,10000,-141.4180087,141.4209618,0,0,0,135 +109.63,50.34980343,-3.326771421,10000,-141.4145269,141.4209995,0,0,0,135 +109.64,50.34979074,-3.326751582,10000,-141.4214897,141.4212599,0,0,0,135 +109.65,50.34977804,-3.326731743,10000,-141.4319341,141.4210749,0,0,0,135 +109.66,50.34976535,-3.326711905,10000,-141.4319338,141.4211126,0,0,0,135 +109.67,50.34975265,-3.326692066,10000,-141.4214887,141.4213731,0,0,0,135 +109.68,50.34973996,-3.326672227,10000,-141.4145253,141.421188,0,0,0,135 +109.69,50.34972727,-3.326652389,10000,-141.4180066,141.4212257,0,0,0,135 +109.7,50.34971457,-3.32663255,10000,-141.4180063,141.4214862,0,0,0,135 +109.71,50.34970188,-3.326612711,10000,-141.4145244,141.4213011,0,0,0,135 +109.72,50.34968919,-3.326592873,10000,-141.4214872,141.4213388,0,0,0,135 +109.73,50.34967649,-3.326573034,10000,-141.4319316,141.4215993,0,0,0,135 +109.74,50.3496638,-3.326553195,10000,-141.4319313,141.4214142,0,0,0,135 +109.75,50.3496511,-3.326533357,10000,-141.4214863,141.4214519,0,0,0,135 +109.76,50.34963841,-3.326513518,10000,-141.4145228,141.4217124,0,0,0,135 +109.77,50.34962572,-3.326493679,10000,-141.4180041,141.4215273,0,0,0,135 +109.78,50.34961302,-3.326473841,10000,-141.4180038,141.421565,0,0,0,135 +109.79,50.34960033,-3.326454002,10000,-141.4145219,141.4218255,0,0,0,135 +109.8,50.34958764,-3.326434163,10000,-141.4214847,141.4216404,0,0,0,135 +109.81,50.34957494,-3.326414325,10000,-141.4319291,141.4216781,0,0,0,135 +109.82,50.34956225,-3.326394486,10000,-141.4319288,141.4217158,0,0,0,135 +109.83,50.34954955,-3.326374647,10000,-141.4214838,141.4206397,0,0,0,135 +109.84,50.34953686,-3.326354809,10000,-141.4145203,141.4197863,0,0,0,135 +109.85,50.34952417,-3.326334971,10000,-141.4180016,141.4207151,0,0,0,135 +109.86,50.34951147,-3.326315132,10000,-141.4180013,141.4218666,0,0,0,135 +109.87,50.34949878,-3.326295293,10000,-141.4145194,141.4219043,0,0,0,135 +109.88,50.34948609,-3.326275455,10000,-141.4180007,141.421942,0,0,0,135 +109.89,50.34947339,-3.326255616,10000,-141.4180003,141.4222025,0,0,0,135 +109.9,50.3494607,-3.326235777,10000,-141.4145185,141.4217947,0,0,0,135 +109.91,50.34944801,-3.326215939,10000,-141.4214813,141.4211641,0,0,0,135 +109.92,50.34943531,-3.3261961,10000,-141.4319257,141.4212018,0,0,0,135 +109.93,50.34942262,-3.326176262,10000,-141.4319254,141.4219078,0,0,0,135 +109.94,50.34940992,-3.326156423,10000,-141.4214804,141.4221682,0,0,0,135 +109.95,50.34939723,-3.326136584,10000,-141.4145169,141.4210921,0,0,0,135 +109.96,50.34938454,-3.326116746,10000,-141.4179982,141.4202387,0,0,0,135 +109.97,50.34937184,-3.326096908,10000,-141.4179979,141.4211675,0,0,0,135 +109.98,50.34935915,-3.326077069,10000,-141.414516,141.4220963,0,0,0,135 +109.99,50.34934646,-3.32605723,10000,-141.4214788,141.4212429,0,0,0,135 +110,50.34933376,-3.326037392,10000,-141.4319232,141.4203895,0,0,0,135 +110.01,50.34932107,-3.326017554,10000,-141.4319229,141.4213183,0,0,0,135 +110.02,50.34930837,-3.325997715,10000,-141.4214779,141.4222471,0,0,0,135 +110.03,50.34929568,-3.325977876,10000,-141.4145145,141.4213937,0,0,0,135 +110.04,50.34928299,-3.325958038,10000,-141.4179957,141.4203176,0,0,0,135 +110.05,50.34927029,-3.3259382,10000,-141.4179954,141.420578,0,0,0,135 +110.06,50.3492576,-3.325918361,10000,-141.4145135,141.4215068,0,0,0,135 +110.07,50.34924491,-3.325898523,10000,-141.4214764,141.4224356,0,0,0,135 +110.08,50.34923221,-3.325878684,10000,-141.4319208,141.4226961,0,0,0,135 +110.09,50.34921952,-3.325858845,10000,-141.4319205,141.4216199,0,0,0,135 +110.1,50.34920682,-3.325839007,10000,-141.4214754,141.4205438,0,0,0,135 +110.11,50.34919413,-3.325819169,10000,-141.414512,141.4208043,0,0,0,135 +110.12,50.34918144,-3.32579933,10000,-141.4179932,141.4215103,0,0,0,135 +110.13,50.34916874,-3.325779492,10000,-141.4179929,141.421548,0,0,0,135 +110.14,50.34915605,-3.325759653,10000,-141.4145111,141.4209174,0,0,0,135 +110.15,50.34914336,-3.325739815,10000,-141.4214739,141.4205095,0,0,0,135 +110.16,50.34913066,-3.325719977,10000,-141.4319183,141.4209928,0,0,0,135 +110.17,50.34911797,-3.325700138,10000,-141.431918,141.4216988,0,0,0,135 +110.18,50.34910527,-3.3256803,10000,-141.4214729,141.4219592,0,0,0,135 +110.19,50.34909258,-3.325660461,10000,-141.4145095,141.4219969,0,0,0,135 +110.2,50.34907989,-3.325640623,10000,-141.4179908,141.4218119,0,0,0,135 +110.21,50.34906719,-3.325620784,10000,-141.4179904,141.4209585,0,0,0,135 +110.22,50.3490545,-3.325600946,10000,-141.4145086,141.4198823,0,0,0,135 +110.23,50.34904181,-3.325581108,10000,-141.4214714,141.41992,0,0,0,135 +110.24,50.34902911,-3.32556127,10000,-141.4319158,141.4210716,0,0,0,135 +110.25,50.34901642,-3.325541431,10000,-141.4319155,141.4220004,0,0,0,135 +110.26,50.34900372,-3.325521593,10000,-141.4214705,141.4222609,0,0,0,135 +110.27,50.34899103,-3.325501754,10000,-141.414507,141.4222986,0,0,0,135 +110.28,50.34897834,-3.325481916,10000,-141.4179883,141.4221135,0,0,0,135 +110.29,50.34896564,-3.325462077,10000,-141.417988,141.4212601,0,0,0,135 +110.3,50.34895295,-3.325442239,10000,-141.4145061,141.4201839,0,0,0,135 +110.31,50.34894026,-3.325422401,10000,-141.4214689,141.4202217,0,0,0,135 +110.32,50.34892756,-3.325402563,10000,-141.4319133,141.4211504,0,0,0,135 +110.33,50.34891487,-3.325382724,10000,-141.431913,141.4214109,0,0,0,135 +110.34,50.34890217,-3.325362886,10000,-141.421468,141.4212258,0,0,0,135 +110.35,50.34888948,-3.325343048,10000,-141.4145045,141.4217091,0,0,0,135 +110.36,50.34887679,-3.325323209,10000,-141.4179858,141.4224151,0,0,0,135 +110.37,50.34886409,-3.325303371,10000,-141.4179855,141.4224528,0,0,0,135 +110.38,50.3488514,-3.325283532,10000,-141.4145036,141.4218222,0,0,0,135 +110.39,50.34883871,-3.325263694,10000,-141.4214664,141.4214143,0,0,0,135 +110.4,50.34882601,-3.325243856,10000,-141.4319109,141.4216748,0,0,0,135 +110.41,50.34881332,-3.325224017,10000,-141.4319105,141.4214898,0,0,0,135 +110.42,50.34880062,-3.325204179,10000,-141.4214655,141.4206364,0,0,0,135 +110.43,50.34878793,-3.325184341,10000,-141.414502,141.4206741,0,0,0,135 +110.44,50.34877524,-3.325164503,10000,-141.4179833,141.4216029,0,0,0,135 +110.45,50.34876254,-3.325144664,10000,-141.417983,141.4216406,0,0,0,135 +110.46,50.34874985,-3.325124826,10000,-141.4145011,141.4205644,0,0,0,135 +110.47,50.34873716,-3.325104988,10000,-141.4214639,141.4199338,0,0,0,135 +110.48,50.34872446,-3.32508515,10000,-141.4319084,141.4206398,0,0,0,135 +110.49,50.34871177,-3.325065312,10000,-141.4319081,141.4217914,0,0,0,135 +110.5,50.34869907,-3.325045473,10000,-141.4214631,141.4218291,0,0,0,135 +110.51,50.34868638,-3.325025635,10000,-141.4144996,141.4209757,0,0,0,135 +110.52,50.34867369,-3.325005797,10000,-141.4179808,141.4210134,0,0,0,135 +110.53,50.34866099,-3.324985959,10000,-141.4179805,141.4219422,0,0,0,135 +110.54,50.3486483,-3.32496612,10000,-141.4144986,141.4219799,0,0,0,135 +110.55,50.34863561,-3.324946282,10000,-141.4214615,141.4209037,0,0,0,135 +110.56,50.34862291,-3.324926444,10000,-141.4319059,141.4202731,0,0,0,135 +110.57,50.34861022,-3.324906606,10000,-141.4319056,141.4209791,0,0,0,135 +110.58,50.34859752,-3.324886768,10000,-141.4214606,141.4221307,0,0,0,135 +110.59,50.34858483,-3.324866929,10000,-141.4144971,141.4221684,0,0,0,135 +110.6,50.34857214,-3.324847091,10000,-141.4179783,141.4210922,0,0,0,135 +110.61,50.34855944,-3.324827253,10000,-141.4179781,141.4204616,0,0,0,135 +110.62,50.34854675,-3.324807415,10000,-141.4144962,141.4211676,0,0,0,135 +110.63,50.34853406,-3.324787577,10000,-141.421459,141.4223192,0,0,0,135 +110.64,50.34852136,-3.324767738,10000,-141.4319034,141.4223569,0,0,0,135 +110.65,50.34850867,-3.3247479,10000,-141.4319031,141.4212807,0,0,0,135 +110.66,50.34849597,-3.324728062,10000,-141.4214581,141.4206501,0,0,0,135 +110.67,50.34848328,-3.324708224,10000,-141.4144946,141.4213561,0,0,0,135 +110.68,50.34847059,-3.324688386,10000,-141.4179759,141.4225077,0,0,0,135 +110.69,50.34845789,-3.324668547,10000,-141.4179756,141.4225454,0,0,0,135 +110.7,50.3484452,-3.324648709,10000,-141.4144937,141.4214692,0,0,0,135 +110.71,50.34843251,-3.324628871,10000,-141.4214565,141.4206158,0,0,0,135 +110.72,50.34841981,-3.324609033,10000,-141.4319009,141.4204307,0,0,0,135 +110.73,50.34840712,-3.324589195,10000,-141.4319006,141.4206912,0,0,0,135 +110.74,50.34839442,-3.324569357,10000,-141.4214556,141.42162,0,0,0,135 +110.75,50.34838173,-3.324549519,10000,-141.4144921,141.4227716,0,0,0,135 +110.76,50.34836904,-3.32452968,10000,-141.4179734,141.4228093,0,0,0,135 +110.77,50.34835634,-3.324509842,10000,-141.4179731,141.4217331,0,0,0,135 +110.78,50.34834365,-3.324490004,10000,-141.4144912,141.4208797,0,0,0,135 +110.79,50.34833096,-3.324470166,10000,-141.4214541,141.4206946,0,0,0,135 +110.8,50.34831826,-3.324450328,10000,-141.4318985,141.4207324,0,0,0,135 +110.81,50.34830557,-3.32443049,10000,-141.4318981,141.4207701,0,0,0,135 +110.82,50.34829287,-3.324410652,10000,-141.4214531,141.4208078,0,0,0,135 +110.83,50.34828018,-3.324390814,10000,-141.4144897,141.4208455,0,0,0,135 +110.84,50.34826749,-3.324370976,10000,-141.4179709,141.4208832,0,0,0,135 +110.85,50.34825479,-3.324351138,10000,-141.4179706,141.4209209,0,0,0,135 +110.86,50.3482421,-3.3243313,10000,-141.4144887,141.4209586,0,0,0,135 +110.87,50.34822941,-3.324311462,10000,-141.4214516,141.4209963,0,0,0,135 +110.88,50.34821671,-3.324291624,10000,-141.431896,141.4212567,0,0,0,135 +110.89,50.34820402,-3.324271786,10000,-141.4318957,141.4221855,0,0,0,135 +110.9,50.34819132,-3.324251948,10000,-141.4214506,141.4233371,0,0,0,135 +110.91,50.34817863,-3.324232109,10000,-141.4144872,141.4233748,0,0,0,135 +110.92,50.34816594,-3.324212271,10000,-141.4179685,141.4220759,0,0,0,135 +110.93,50.34815324,-3.324192433,10000,-141.4179682,141.4203314,0,0,0,135 +110.94,50.34814055,-3.324172595,10000,-141.4144863,141.4192552,0,0,0,135 +110.95,50.34812786,-3.324152758,10000,-141.4214491,141.420184,0,0,0,135 +110.96,50.34811516,-3.32413292,10000,-141.4318935,141.4224494,0,0,0,135 +110.97,50.34810247,-3.324113081,10000,-141.4318932,141.4233782,0,0,0,135 +110.98,50.34808977,-3.324093243,10000,-141.4214482,141.4223021,0,0,0,135 +110.99,50.34807708,-3.324073405,10000,-141.4144847,141.4205576,0,0,0,135 +111,50.34806439,-3.324053567,10000,-141.417966,141.4194814,0,0,0,135 +111.01,50.34805169,-3.32403373,10000,-141.4179656,141.4204102,0,0,0,135 +111.02,50.348039,-3.324013892,10000,-141.4144838,141.4226756,0,0,0,135 +111.03,50.34802631,-3.323994053,10000,-141.4214466,141.4233817,0,0,0,135 +111.04,50.34801361,-3.323974215,10000,-141.431891,141.4216372,0,0,0,135 +111.05,50.34800092,-3.323954377,10000,-141.4318907,141.4196699,0,0,0,135 +111.06,50.34798822,-3.32393454,10000,-141.4214457,141.4194848,0,0,0,135 +111.07,50.34797553,-3.323914702,10000,-141.4144822,141.4206364,0,0,0,135 +111.08,50.34796284,-3.323894864,10000,-141.4179635,141.4215652,0,0,0,135 +111.09,50.34795014,-3.323875026,10000,-141.4179632,141.4218257,0,0,0,135 +111.1,50.34793745,-3.323855188,10000,-141.4144813,141.4218634,0,0,0,135 +111.11,50.34792476,-3.32383535,10000,-141.4179626,141.4219011,0,0,0,135 +111.12,50.34791206,-3.323815512,10000,-141.4179622,141.4219388,0,0,0,135 +111.13,50.34789937,-3.323795674,10000,-141.4144803,141.4217537,0,0,0,135 +111.14,50.34788668,-3.323775836,10000,-141.4214432,141.4209003,0,0,0,135 +111.15,50.34787398,-3.323755998,10000,-141.4318876,141.4200469,0,0,0,135 +111.16,50.34786129,-3.323736161,10000,-141.4318873,141.4207529,0,0,0,135 +111.17,50.34784859,-3.323716323,10000,-141.4214423,141.4221273,0,0,0,135 +111.18,50.3478359,-3.323696484,10000,-141.4144788,141.4219422,0,0,0,135 +111.19,50.34782321,-3.323676647,10000,-141.4179601,141.4210888,0,0,0,135 +111.2,50.34781051,-3.323656809,10000,-141.4179598,141.4213493,0,0,0,135 +111.21,50.34779782,-3.323636971,10000,-141.4144779,141.4218325,0,0,0,135 +111.22,50.34778513,-3.323617133,10000,-141.4214407,141.4214247,0,0,0,135 +111.23,50.34777243,-3.323597295,10000,-141.4318851,141.4212396,0,0,0,135 +111.24,50.34775974,-3.323577458,10000,-141.4318848,141.4221684,0,0,0,135 +111.25,50.34774704,-3.323557619,10000,-141.4214398,141.4224289,0,0,0,135 +111.26,50.34773435,-3.323537781,10000,-141.4144763,141.4211299,0,0,0,135 +111.27,50.34772166,-3.323517944,10000,-141.4214392,141.4204993,0,0,0,135 +111.28,50.34770896,-3.323498106,10000,-141.4318836,141.4212053,0,0,0,135 +111.29,50.34769627,-3.323478268,10000,-141.4318833,141.421243,0,0,0,135 +111.3,50.34768357,-3.32345843,10000,-141.4214382,141.4203896,0,0,0,135 +111.31,50.34767088,-3.323438593,10000,-141.4144748,141.4204273,0,0,0,135 +111.32,50.34765819,-3.323418755,10000,-141.4179561,141.4215789,0,0,0,135 +111.33,50.34764549,-3.323398917,10000,-141.4179557,141.4225077,0,0,0,135 +111.34,50.3476328,-3.323379079,10000,-141.4144739,141.4225454,0,0,0,135 +111.35,50.34762011,-3.323359241,10000,-141.4214367,141.421692,0,0,0,135 +111.36,50.34760741,-3.323339403,10000,-141.4318811,141.4206158,0,0,0,135 +111.37,50.34759472,-3.323319566,10000,-141.4318808,141.4206535,0,0,0,135 +111.38,50.34758202,-3.323299728,10000,-141.4214358,141.4215823,0,0,0,135 +111.39,50.34756933,-3.32327989,10000,-141.4144723,141.42162,0,0,0,135 +111.4,50.34755664,-3.323260052,10000,-141.4179536,141.4207666,0,0,0,135 +111.41,50.34754394,-3.323240215,10000,-141.4179532,141.4205815,0,0,0,135 +111.42,50.34753125,-3.323220377,10000,-141.4144714,141.4210648,0,0,0,135 +111.43,50.34751856,-3.323200539,10000,-141.4214342,141.421548,0,0,0,135 +111.44,50.34750586,-3.323180702,10000,-141.4318786,141.4220313,0,0,0,135 +111.45,50.34749317,-3.323160863,10000,-141.4318783,141.422069,0,0,0,135 +111.46,50.34748047,-3.323141026,10000,-141.4214333,141.4216611,0,0,0,135 +111.47,50.34746778,-3.323121188,10000,-141.4144698,141.4212533,0,0,0,135 +111.48,50.34745509,-3.32310135,10000,-141.4179511,141.4208454,0,0,0,135 +111.49,50.34744239,-3.323081513,10000,-141.4179508,141.4208831,0,0,0,135 +111.5,50.3474297,-3.323061675,10000,-141.4144689,141.4211436,0,0,0,135 +111.51,50.34741701,-3.323041837,10000,-141.4214317,141.4209585,0,0,0,135 +111.52,50.34740431,-3.323022,10000,-141.4318761,141.4209962,0,0,0,135 +111.53,50.34739162,-3.323002162,10000,-141.4318758,141.4214795,0,0,0,135 +111.54,50.34737892,-3.322982324,10000,-141.4214308,141.4219627,0,0,0,135 +111.55,50.34736623,-3.322962487,10000,-141.4144673,141.422446,0,0,0,135 +111.56,50.34735354,-3.322942648,10000,-141.4179486,141.4222609,0,0,0,135 +111.57,50.34734084,-3.322922811,10000,-141.4179483,141.4211847,0,0,0,135 +111.58,50.34732815,-3.322902973,10000,-141.4144664,141.4205541,0,0,0,135 +111.59,50.34731546,-3.322883136,10000,-141.4179477,141.4210373,0,0,0,135 +111.6,50.34730276,-3.322863298,10000,-141.4179474,141.4215206,0,0,0,135 +111.61,50.34729007,-3.32284346,10000,-141.4144655,141.4213355,0,0,0,135 +111.62,50.34727738,-3.322823623,10000,-141.4214283,141.4213732,0,0,0,135 +111.63,50.34726468,-3.322803785,10000,-141.4318727,141.4216337,0,0,0,135 +111.64,50.34725199,-3.322783947,10000,-141.4318724,141.4212258,0,0,0,135 +111.65,50.34723929,-3.32276411,10000,-141.4214274,141.4205952,0,0,0,135 +111.66,50.3472266,-3.322744272,10000,-141.4144639,141.4206329,0,0,0,135 +111.67,50.34721391,-3.322724435,10000,-141.4179452,141.4215617,0,0,0,135 +111.68,50.34720121,-3.322704597,10000,-141.4179449,141.4227133,0,0,0,135 +111.69,50.34718852,-3.322684759,10000,-141.414463,141.422751,0,0,0,135 +111.7,50.34717583,-3.322664921,10000,-141.4214259,141.4216748,0,0,0,135 +111.71,50.34716313,-3.322645084,10000,-141.4318702,141.4208214,0,0,0,135 +111.72,50.34715044,-3.322625246,10000,-141.4318699,141.4206363,0,0,0,135 +111.73,50.34713774,-3.322605409,10000,-141.4214249,141.420674,0,0,0,135 +111.74,50.34712505,-3.322585571,10000,-141.4144615,141.4209345,0,0,0,135 +111.75,50.34711236,-3.322565734,10000,-141.4179427,141.4216405,0,0,0,135 +111.76,50.34709966,-3.322545896,10000,-141.4179424,141.4221238,0,0,0,135 +111.77,50.34708697,-3.322526058,10000,-141.4144605,141.4217159,0,0,0,135 +111.78,50.34707428,-3.322506221,10000,-141.4214233,141.4210853,0,0,0,135 +111.79,50.34706158,-3.322486383,10000,-141.4318678,141.4209002,0,0,0,135 +111.8,50.34704889,-3.322466546,10000,-141.4318675,141.4209379,0,0,0,135 +111.81,50.34703619,-3.322446708,10000,-141.4214225,141.4209756,0,0,0,135 +111.82,50.3470235,-3.322426871,10000,-141.414459,141.4210133,0,0,0,135 +111.83,50.34701081,-3.322407033,10000,-141.4179402,141.421051,0,0,0,135 +111.84,50.34699811,-3.322387196,10000,-141.4179399,141.4210887,0,0,0,135 +111.85,50.34698542,-3.322367358,10000,-141.4144581,141.4211264,0,0,0,135 +111.86,50.34697273,-3.322347521,10000,-141.4214209,141.4211641,0,0,0,135 +111.87,50.34696003,-3.322327683,10000,-141.4318653,141.4212018,0,0,0,135 +111.88,50.34694734,-3.322307846,10000,-141.431865,141.4212395,0,0,0,135 +111.89,50.34693464,-3.322288008,10000,-141.4214199,141.4214999,0,0,0,135 +111.9,50.34692195,-3.322268171,10000,-141.4144565,141.422206,0,0,0,135 +111.91,50.34690926,-3.322248333,10000,-141.4179378,141.4226892,0,0,0,135 +111.92,50.34689656,-3.322228495,10000,-141.4179375,141.4222814,0,0,0,135 +111.93,50.34688387,-3.322208658,10000,-141.4144556,141.4216507,0,0,0,135 +111.94,50.34687118,-3.32218882,10000,-141.4214184,141.4214657,0,0,0,135 +111.95,50.34685848,-3.322168983,10000,-141.4318628,141.4215034,0,0,0,135 +111.96,50.34684579,-3.322149145,10000,-141.4318625,141.4215411,0,0,0,135 +111.97,50.34683309,-3.322129308,10000,-141.4214175,141.421356,0,0,0,135 +111.98,50.3468204,-3.32210947,10000,-141.414454,141.4207253,0,0,0,135 +111.99,50.34680771,-3.322089633,10000,-141.4179353,141.4203175,0,0,0,135 +112,50.34679501,-3.322069796,10000,-141.417935,141.4208007,0,0,0,135 +112.01,50.34678232,-3.322049958,10000,-141.4144531,141.4215068,0,0,0,135 +112.02,50.34676963,-3.322030121,10000,-141.4214159,141.4217672,0,0,0,135 +112.03,50.34675693,-3.322010283,10000,-141.4318603,141.4218049,0,0,0,135 +112.04,50.34674424,-3.321990446,10000,-141.43186,141.4216199,0,0,0,135 +112.05,50.34673154,-3.321970608,10000,-141.421415,141.4209892,0,0,0,135 +112.06,50.34671885,-3.321950771,10000,-141.4144516,141.4205813,0,0,0,135 +112.07,50.34670616,-3.321930934,10000,-141.4179328,141.4210646,0,0,0,135 +112.08,50.34669346,-3.321911096,10000,-141.4179325,141.4217707,0,0,0,135 +112.09,50.34668077,-3.321891259,10000,-141.4144506,141.4218084,0,0,0,135 +112.1,50.34666808,-3.321871421,10000,-141.4214134,141.4211777,0,0,0,135 +112.11,50.34665538,-3.321851584,10000,-141.4318579,141.4207698,0,0,0,135 +112.12,50.34664269,-3.321831747,10000,-141.4318576,141.4212531,0,0,0,135 +112.13,50.34662999,-3.321811909,10000,-141.4214125,141.4219591,0,0,0,135 +112.14,50.3466173,-3.321792072,10000,-141.4144491,141.4219968,0,0,0,135 +112.15,50.34660461,-3.321772234,10000,-141.4179303,141.4213662,0,0,0,135 +112.16,50.34659191,-3.321752397,10000,-141.41793,141.4209583,0,0,0,135 +112.17,50.34657922,-3.32173256,10000,-141.4144482,141.4212188,0,0,0,135 +112.18,50.34656653,-3.321712722,10000,-141.421411,141.4212565,0,0,0,135 +112.19,50.34655383,-3.321692885,10000,-141.4318554,141.4210714,0,0,0,135 +112.2,50.34654114,-3.321673048,10000,-141.431855,141.4213319,0,0,0,135 +112.21,50.34652844,-3.32165321,10000,-141.42141,141.4213696,0,0,0,135 +112.22,50.34651575,-3.321633373,10000,-141.4144466,141.4211845,0,0,0,135 +112.23,50.34650306,-3.321613536,10000,-141.4179279,141.421445,0,0,0,135 +112.24,50.34649036,-3.321593698,10000,-141.4179275,141.4214827,0,0,0,135 +112.25,50.34647767,-3.321573861,10000,-141.4144456,141.4212976,0,0,0,135 +112.26,50.34646498,-3.321554024,10000,-141.4214085,141.4215581,0,0,0,135 +112.27,50.34645228,-3.321534186,10000,-141.4318529,141.4215958,0,0,0,135 +112.28,50.34643959,-3.321514349,10000,-141.4318526,141.4214107,0,0,0,135 +112.29,50.34642689,-3.321494512,10000,-141.4214076,141.4216712,0,0,0,135 +112.3,50.3464142,-3.321474674,10000,-141.4144441,141.4217089,0,0,0,135 +112.31,50.34640151,-3.321454837,10000,-141.4179254,141.4215238,0,0,0,135 +112.32,50.34638881,-3.321435,10000,-141.417925,141.4217843,0,0,0,135 +112.33,50.34637612,-3.321415162,10000,-141.4144432,141.4215992,0,0,0,135 +112.34,50.34636343,-3.321395325,10000,-141.421406,141.420523,0,0,0,135 +112.35,50.34635073,-3.321375488,10000,-141.4318504,141.4196695,0,0,0,135 +112.36,50.34633804,-3.321355651,10000,-141.4318501,141.4197072,0,0,0,135 +112.37,50.34632534,-3.321335814,10000,-141.4214051,141.4206361,0,0,0,135 +112.38,50.34631265,-3.321315977,10000,-141.4144416,141.4217877,0,0,0,135 +112.39,50.34629996,-3.321296139,10000,-141.4179229,141.4220482,0,0,0,135 +112.4,50.34628726,-3.321276302,10000,-141.4179226,141.4218631,0,0,0,135 +112.41,50.34627457,-3.321256465,10000,-141.4144407,141.4221236,0,0,0,135 +112.42,50.34626188,-3.321236627,10000,-141.4214035,141.4219385,0,0,0,135 +112.43,50.34624918,-3.32121679,10000,-141.4318479,141.4208623,0,0,0,135 +112.44,50.34623649,-3.321196953,10000,-141.4318476,141.4202316,0,0,0,135 +112.45,50.34622379,-3.321177116,10000,-141.4214026,141.4209377,0,0,0,135 +112.46,50.3462111,-3.321157279,10000,-141.4144392,141.4220893,0,0,0,135 +112.47,50.34619841,-3.321137441,10000,-141.4179204,141.422127,0,0,0,135 +112.48,50.34618571,-3.321117604,10000,-141.4179201,141.4212735,0,0,0,135 +112.49,50.34617302,-3.321097767,10000,-141.4144382,141.4213112,0,0,0,135 +112.5,50.34616033,-3.32107793,10000,-141.4214011,141.4222401,0,0,0,135 +112.51,50.34614763,-3.321058092,10000,-141.4318455,141.4222778,0,0,0,135 +112.52,50.34613494,-3.321038255,10000,-141.4318451,141.4212015,0,0,0,135 +112.53,50.34612224,-3.321018418,10000,-141.4214001,141.4205709,0,0,0,135 +112.54,50.34610955,-3.320998581,10000,-141.4144367,141.4212769,0,0,0,135 +112.55,50.34609686,-3.320978744,10000,-141.4179179,141.4222058,0,0,0,135 +112.56,50.34608416,-3.320958906,10000,-141.4179176,141.4215751,0,0,0,135 +112.57,50.34607147,-3.320939069,10000,-141.4144357,141.4202761,0,0,0,135 +112.58,50.34605878,-3.320919233,10000,-141.4213986,141.4205366,0,0,0,135 +112.59,50.34604608,-3.320899395,10000,-141.431843,141.4214654,0,0,0,135 +112.6,50.34603339,-3.320879558,10000,-141.4318427,141.4212803,0,0,0,135 +112.61,50.34602069,-3.320859721,10000,-141.4213976,141.4206497,0,0,0,135 +112.62,50.346008,-3.320839884,10000,-141.4144342,141.4206874,0,0,0,135 +112.63,50.34599531,-3.320820047,10000,-141.4179155,141.4216162,0,0,0,135 +112.64,50.34598261,-3.32080021,10000,-141.4179151,141.4227678,0,0,0,135 +112.65,50.34596992,-3.320780372,10000,-141.4144333,141.4228055,0,0,0,135 +112.66,50.34595723,-3.320760535,10000,-141.4213961,141.4217293,0,0,0,135 +112.67,50.34594453,-3.320740698,10000,-141.4318405,141.4208759,0,0,0,135 +112.68,50.34593184,-3.320720861,10000,-141.4318402,141.4206908,0,0,0,135 +112.69,50.34591914,-3.320701024,10000,-141.4213952,141.4207285,0,0,0,135 +112.7,50.34590645,-3.320681187,10000,-141.4144317,141.420989,0,0,0,135 +112.71,50.34589376,-3.32066135,10000,-141.417913,141.421695,0,0,0,135 +112.72,50.34588106,-3.320641513,10000,-141.4179127,141.4219555,0,0,0,135 +112.73,50.34586837,-3.320621675,10000,-141.4144308,141.4208793,0,0,0,135 +112.74,50.34585568,-3.320601839,10000,-141.4213936,141.419803,0,0,0,135 +112.75,50.34584298,-3.320582002,10000,-141.431838,141.4202863,0,0,0,135 +112.76,50.34583029,-3.320562165,10000,-141.4318377,141.4218835,0,0,0,135 +112.77,50.34581759,-3.320542328,10000,-141.4213927,141.4232579,0,0,0,135 +112.78,50.3458049,-3.32052249,10000,-141.4144292,141.4232956,0,0,0,135 +112.79,50.34579221,-3.320502653,10000,-141.4179105,141.4222194,0,0,0,135 +112.8,50.34577951,-3.320482816,10000,-141.4179102,141.4213659,0,0,0,135 +112.81,50.34576682,-3.320462979,10000,-141.4144283,141.420958,0,0,0,135 +112.82,50.34575413,-3.320443142,10000,-141.4213912,141.4203274,0,0,0,135 +112.83,50.34574143,-3.320423305,10000,-141.4318355,141.4201423,0,0,0,135 +112.84,50.34572874,-3.320403469,10000,-141.4318352,141.4212939,0,0,0,135 +112.85,50.34571604,-3.320383631,10000,-141.4213902,141.4224456,0,0,0,135 +112.86,50.34570335,-3.320363794,10000,-141.4144267,141.4222605,0,0,0,135 +112.87,50.34569066,-3.320343957,10000,-141.417908,141.4216298,0,0,0,135 +112.88,50.34567796,-3.32032412,10000,-141.4179077,141.4214447,0,0,0,135 +112.89,50.34566527,-3.320304283,10000,-141.4144258,141.4214824,0,0,0,135 +112.9,50.34565258,-3.320284446,10000,-141.4213886,141.4215201,0,0,0,135 +112.91,50.34563988,-3.320264609,10000,-141.431833,141.4215578,0,0,0,135 +112.92,50.34562719,-3.320244772,10000,-141.4318327,141.4213727,0,0,0,135 +112.93,50.34561449,-3.320224935,10000,-141.4213877,141.4205193,0,0,0,135 +112.94,50.3456018,-3.320205098,10000,-141.4144243,141.419443,0,0,0,135 +112.95,50.34558911,-3.320185262,10000,-141.4179055,141.4194807,0,0,0,135 +112.96,50.34557641,-3.320165425,10000,-141.4179052,141.4206324,0,0,0,135 +112.97,50.34556372,-3.320145588,10000,-141.4144233,141.4215612,0,0,0,135 +112.98,50.34555103,-3.320125751,10000,-141.4213862,141.4218217,0,0,0,135 +112.99,50.34553833,-3.320105914,10000,-141.4318306,141.4218594,0,0,0,135 +113,50.34552564,-3.320086077,10000,-141.4318303,141.4218971,0,0,0,135 +113.01,50.34551294,-3.32006624,10000,-141.4213852,141.4219348,0,0,0,135 +113.02,50.34550025,-3.320046403,10000,-141.4144218,141.4219725,0,0,0,135 +113.03,50.34548756,-3.320026566,10000,-141.4179031,141.4220102,0,0,0,135 +113.04,50.34547486,-3.320006729,10000,-141.4179028,141.4220479,0,0,0,135 +113.05,50.34546217,-3.319986892,10000,-141.4144209,141.4218628,0,0,0,135 +113.06,50.34544948,-3.319967055,10000,-141.4213837,141.4210093,0,0,0,135 +113.07,50.34543678,-3.319947218,10000,-141.4318281,141.4199331,0,0,0,135 +113.08,50.34542409,-3.319927382,10000,-141.4318278,141.4199708,0,0,0,135 +113.09,50.34541139,-3.319907545,10000,-141.4213828,141.4211224,0,0,0,135 +113.1,50.3453987,-3.319887708,10000,-141.4144193,141.4220513,0,0,0,135 +113.11,50.34538601,-3.319867871,10000,-141.4179006,141.4223117,0,0,0,135 +113.12,50.34537331,-3.319848034,10000,-141.4179003,141.4221267,0,0,0,135 +113.13,50.34536062,-3.319828197,10000,-141.4144184,141.4212732,0,0,0,135 +113.14,50.34534793,-3.31980836,10000,-141.4213812,141.4201969,0,0,0,135 +113.15,50.34533523,-3.319788524,10000,-141.4318256,141.4202346,0,0,0,135 +113.16,50.34532254,-3.319768687,10000,-141.4318253,141.4213863,0,0,0,135 +113.17,50.34530984,-3.31974885,10000,-141.4213803,141.4220924,0,0,0,135 +113.18,50.34529715,-3.319729013,10000,-141.4144168,141.4214617,0,0,0,135 +113.19,50.34528446,-3.319709176,10000,-141.4178981,141.4203854,0,0,0,135 +113.2,50.34527176,-3.31968934,10000,-141.4178978,141.4204231,0,0,0,135 +113.21,50.34525907,-3.319669503,10000,-141.4144159,141.4215748,0,0,0,135 +113.22,50.34524638,-3.319649666,10000,-141.4213787,141.4225036,0,0,0,135 +113.23,50.34523368,-3.319629829,10000,-141.4318231,141.4225413,0,0,0,135 +113.24,50.34522099,-3.319609992,10000,-141.4318228,141.4216879,0,0,0,135 +113.25,50.34520829,-3.319590155,10000,-141.4213778,141.4206116,0,0,0,135 +113.26,50.3451956,-3.319570319,10000,-141.4144144,141.4206493,0,0,0,135 +113.27,50.34518291,-3.319550482,10000,-141.4178956,141.4218009,0,0,0,135 +113.28,50.34517021,-3.319530645,10000,-141.4178953,141.422507,0,0,0,135 +113.29,50.34515752,-3.319510808,10000,-141.4144134,141.4218763,0,0,0,135 +113.3,50.34514483,-3.319490971,10000,-141.4213762,141.4208001,0,0,0,135 +113.31,50.34513213,-3.319471135,10000,-141.4318207,141.420615,0,0,0,135 +113.32,50.34511944,-3.319451298,10000,-141.4318204,141.4208755,0,0,0,135 +113.33,50.34510674,-3.319431461,10000,-141.4213753,141.4206904,0,0,0,135 +113.34,50.34509405,-3.319411625,10000,-141.4144119,141.4209509,0,0,0,135 +113.35,50.34508136,-3.319391788,10000,-141.4178931,141.4221025,0,0,0,135 +113.36,50.34506866,-3.319371951,10000,-141.4178928,141.4228086,0,0,0,135 +113.37,50.34505597,-3.319352114,10000,-141.4144109,141.4221779,0,0,0,135 +113.38,50.34504328,-3.319332277,10000,-141.4213738,141.4211017,0,0,0,135 +113.39,50.34503058,-3.319312441,10000,-141.4318182,141.4209166,0,0,0,135 +113.4,50.34501789,-3.319292604,10000,-141.4318179,141.4211771,0,0,0,135 +113.41,50.34500519,-3.319272767,10000,-141.4213729,141.4207692,0,0,0,135 +113.42,50.3449925,-3.319252931,10000,-141.4144094,141.4201385,0,0,0,135 +113.43,50.34497981,-3.319233094,10000,-141.4178906,141.4201762,0,0,0,135 +113.44,50.34496711,-3.319213258,10000,-141.4178903,141.421105,0,0,0,135 +113.45,50.34495442,-3.319193421,10000,-141.4144085,141.4224795,0,0,0,135 +113.46,50.34494173,-3.319173584,10000,-141.4213713,141.4231855,0,0,0,135 +113.47,50.34492903,-3.319153747,10000,-141.4318157,141.4225549,0,0,0,135 +113.48,50.34491634,-3.31913391,10000,-141.4318154,141.4212558,0,0,0,135 +113.49,50.34490364,-3.319114074,10000,-141.4213704,141.4204024,0,0,0,135 +113.5,50.34489095,-3.319094237,10000,-141.4144069,141.4204401,0,0,0,135 +113.51,50.34487826,-3.319074401,10000,-141.4178882,141.4213689,0,0,0,135 +113.52,50.34486556,-3.319054564,10000,-141.4178879,141.4225206,0,0,0,135 +113.53,50.34485287,-3.319034727,10000,-141.414406,141.4225583,0,0,0,135 +113.54,50.34484018,-3.31901489,10000,-141.4213688,141.421482,0,0,0,135 +113.55,50.34482748,-3.318995054,10000,-141.4318132,141.4206285,0,0,0,135 +113.56,50.34481479,-3.318975217,10000,-141.4318129,141.4206662,0,0,0,135 +113.57,50.34480209,-3.318955381,10000,-141.4213679,141.4213723,0,0,0,135 +113.58,50.3447894,-3.318935544,10000,-141.4144045,141.4218556,0,0,0,135 +113.59,50.34477671,-3.318915707,10000,-141.4178857,141.4214477,0,0,0,135 +113.6,50.34476401,-3.318895871,10000,-141.4178854,141.420817,0,0,0,135 +113.61,50.34475132,-3.318876034,10000,-141.4144035,141.4208547,0,0,0,135 +113.62,50.34473863,-3.318856198,10000,-141.4213663,141.4215608,0,0,0,135 +113.63,50.34472593,-3.318836361,10000,-141.4318108,141.4220441,0,0,0,135 +113.64,50.34471324,-3.318816524,10000,-141.4318105,141.4216362,0,0,0,135 +113.65,50.34470054,-3.318796688,10000,-141.4213654,141.4210055,0,0,0,135 +113.66,50.34468785,-3.318776851,10000,-141.4144019,141.4210432,0,0,0,135 +113.67,50.34467516,-3.318757015,10000,-141.4178832,141.4217493,0,0,0,135 +113.68,50.34466246,-3.318737178,10000,-141.4178829,141.4220097,0,0,0,135 +113.69,50.34464977,-3.318717341,10000,-141.4144011,141.4209335,0,0,0,135 +113.7,50.34463708,-3.318697505,10000,-141.4213639,141.42008,0,0,0,135 +113.71,50.34462438,-3.318677669,10000,-141.4318083,141.4210089,0,0,0,135 +113.72,50.34461169,-3.318657832,10000,-141.4318079,141.4219377,0,0,0,135 +113.73,50.34459899,-3.318637995,10000,-141.4213629,141.4210843,0,0,0,135 +113.74,50.3445863,-3.318618159,10000,-141.4143995,141.4202308,0,0,0,135 +113.75,50.34457361,-3.318598323,10000,-141.4178808,141.4211597,0,0,0,135 +113.76,50.34456091,-3.318578486,10000,-141.4178804,141.4220885,0,0,0,135 +113.77,50.34454822,-3.318558649,10000,-141.4143985,141.421235,0,0,0,135 +113.78,50.34453553,-3.318538813,10000,-141.4213614,141.4203816,0,0,0,135 +113.79,50.34452283,-3.318518977,10000,-141.4318058,141.4213104,0,0,0,135 +113.8,50.34451014,-3.31849914,10000,-141.4318055,141.4224621,0,0,0,135 +113.81,50.34449744,-3.318479303,10000,-141.4213605,141.422277,0,0,0,135 +113.82,50.34448475,-3.318459467,10000,-141.414397,141.4216463,0,0,0,135 +113.83,50.34447206,-3.31843963,10000,-141.4178783,141.4214612,0,0,0,135 +113.84,50.34445936,-3.318419794,10000,-141.4178779,141.4214989,0,0,0,135 +113.85,50.34444667,-3.318399957,10000,-141.4143961,141.4215366,0,0,0,135 +113.86,50.34443398,-3.318380121,10000,-141.4213589,141.4213515,0,0,0,135 +113.87,50.34442128,-3.318360284,10000,-141.4318033,141.4207208,0,0,0,135 +113.88,50.34440859,-3.318340448,10000,-141.431803,141.4205357,0,0,0,135 +113.89,50.34439589,-3.318320612,10000,-141.421358,141.4216874,0,0,0,135 +113.9,50.3443832,-3.318300775,10000,-141.4143945,141.4226163,0,0,0,135 +113.91,50.34437051,-3.318280938,10000,-141.4178758,141.4217628,0,0,0,135 +113.92,50.34435781,-3.318261102,10000,-141.4178755,141.4206865,0,0,0,135 +113.93,50.34434512,-3.318241266,10000,-141.4143936,141.420947,0,0,0,135 +113.94,50.34433243,-3.318221429,10000,-141.4213564,141.4216531,0,0,0,135 +113.95,50.34431973,-3.318201593,10000,-141.4318008,141.4216908,0,0,0,135 +113.96,50.34430704,-3.318181756,10000,-141.4318005,141.4210601,0,0,0,135 +113.97,50.34429434,-3.31816192,10000,-141.4213555,141.4206522,0,0,0,135 +113.98,50.34428165,-3.318142084,10000,-141.414392,141.4209127,0,0,0,135 +113.99,50.34426896,-3.318122247,10000,-141.4178733,141.4209504,0,0,0,135 +114,50.34425626,-3.318102411,10000,-141.417873,141.4207653,0,0,0,135 +114.01,50.34424357,-3.318082575,10000,-141.4143911,141.4212486,0,0,0,135 +114.02,50.34423088,-3.318062738,10000,-141.4213539,141.4219546,0,0,0,135 +114.03,50.34421818,-3.318042902,10000,-141.4317983,141.4219923,0,0,0,135 +114.04,50.34420549,-3.318023065,10000,-141.431798,141.4213617,0,0,0,135 +114.05,50.34419279,-3.318003229,10000,-141.421353,141.4209538,0,0,0,135 +114.06,50.3441801,-3.317983393,10000,-141.4143896,141.4212143,0,0,0,135 +114.07,50.34416741,-3.317963556,10000,-141.4178708,141.4212519,0,0,0,135 +114.08,50.34415471,-3.31794372,10000,-141.4178705,141.4210668,0,0,0,135 +114.09,50.34414202,-3.317923884,10000,-141.4143886,141.4213273,0,0,0,135 +114.1,50.34412933,-3.317904047,10000,-141.4213515,141.421365,0,0,0,135 +114.11,50.34411663,-3.317884211,10000,-141.4317959,141.4211799,0,0,0,135 +114.12,50.34410394,-3.317864375,10000,-141.4317956,141.4216632,0,0,0,135 +114.13,50.34409124,-3.317844538,10000,-141.4213505,141.4223693,0,0,0,135 +114.14,50.34407855,-3.317824702,10000,-141.4143871,141.422407,0,0,0,135 +114.15,50.34406586,-3.317804865,10000,-141.4178683,141.4217763,0,0,0,135 +114.16,50.34405316,-3.317785029,10000,-141.417868,141.4213684,0,0,0,135 +114.17,50.34404047,-3.317765193,10000,-141.4143862,141.4216289,0,0,0,135 +114.18,50.34402778,-3.317745356,10000,-141.421349,141.4214438,0,0,0,135 +114.19,50.34401508,-3.31772552,10000,-141.4317934,141.4205903,0,0,0,135 +114.2,50.34400239,-3.317705684,10000,-141.4317931,141.420628,0,0,0,135 +114.21,50.34398969,-3.317685848,10000,-141.421348,141.4215569,0,0,0,135 +114.22,50.343977,-3.317666011,10000,-141.4143846,141.4215946,0,0,0,135 +114.23,50.34396431,-3.317646175,10000,-141.4178659,141.4207411,0,0,0,135 +114.24,50.34395161,-3.317626339,10000,-141.4178656,141.4207788,0,0,0,135 +114.25,50.34393892,-3.317606503,10000,-141.4143837,141.4217077,0,0,0,135 +114.26,50.34392623,-3.317586666,10000,-141.4213465,141.4219681,0,0,0,135 +114.27,50.34391353,-3.31756683,10000,-141.4317909,141.4215603,0,0,0,135 +114.28,50.34390084,-3.317546994,10000,-141.4317906,141.4211524,0,0,0,135 +114.29,50.34388814,-3.317527157,10000,-141.4213456,141.4207445,0,0,0,135 +114.3,50.34387545,-3.317507322,10000,-141.4143821,141.421005,0,-0.005415253,0,134.9999994 +114.31,50.34386276,-3.317487485,10000,-141.4178634,141.4221566,0,-0.043321912,0,134.9999894 +114.32,50.34385006,-3.317467649,10000,-141.4178631,141.4228627,0,-0.146211438,0,134.9999462 +114.33,50.34383737,-3.317447812,10000,-141.4143812,141.4224548,0,-0.346575237,0,134.99983 +114.34,50.34382468,-3.317427976,10000,-141.4178625,141.4222697,0,-0.676904772,0,134.9995849 +114.35,50.34381198,-3.31740814,10000,-141.4178622,141.4236442,0,-1.169691448,0,134.9991393 +114.36,50.34379929,-3.317388303,10000,-141.4143803,141.4259098,0,-1.846596163,0,134.9984067 +114.37,50.3437866,-3.317368466,10000,-141.4178615,141.4283983,0,-2.685958076,0,134.9973005 +114.38,50.3437739,-3.317348629,10000,-141.4143797,141.4322235,0,-3.655285668,0,134.9957484 +114.39,50.34376121,-3.317328791,10000,-141.3969715,141.4380539,0,-4.722087589,0,134.9936934 +114.4,50.34374852,-3.317308952,10000,-141.3830449,141.4449982,0,-5.853872379,0,134.9910942 +114.41,50.34373583,-3.317289112,10000,-141.379563,141.4523882,0,-7.018148516,0,134.9879246 +114.42,50.34372314,-3.317269271,10000,-141.3795627,141.4608921,0,-8.182424711,0,134.9841738 +114.43,50.34371045,-3.317249429,10000,-141.3795624,141.471624,0,-9.3142095,0,134.9798469 +114.44,50.34369776,-3.317229585,10000,-141.3760805,141.4843611,0,-10.38101136,0,134.9749649 +114.45,50.34368507,-3.317209739,10000,-141.3621539,141.4975437,0,-11.35033901,0,134.9695656 +114.46,50.34367238,-3.317189891,10000,-141.3412642,141.5109492,0,-12.18970087,0,134.9637034 +114.47,50.3436597,-3.317170042,10000,-141.3238561,141.526137,0,-12.86660564,0,134.9574508 +114.48,50.34364701,-3.31715019,10000,-141.3064479,141.5428845,0,-13.35939232,0,134.9508964 +114.49,50.34363433,-3.317130335,10000,-141.2820766,141.5594091,0,-13.68972185,0,134.9441302 +114.5,50.34362165,-3.317110479,10000,-141.2542238,141.5761565,0,-13.89008565,0,134.9372276 +114.51,50.34360897,-3.31709062,10000,-141.233334,141.5940179,0,-13.99297518,0,134.9302476 +114.52,50.3435963,-3.317070758,10000,-141.2298522,141.6114337,0,-14.03088184,0,134.9232322 +114.53,50.34358362,-3.317050894,10000,-141.2298518,141.6275127,0,-14.03629709,0,134.916207 +114.54,50.34357094,-3.317031028,10000,-141.2089621,141.6440374,0,-14.03629709,0,134.9091811 +114.55,50.34355827,-3.31701116,10000,-141.1776277,141.6618988,0,-14.03629709,0,134.9021552 +114.56,50.3435456,-3.316991288,10000,-141.156738,141.6797602,0,-14.03629709,0,134.8951292 +114.57,50.34353293,-3.316971415,10000,-141.1393298,141.6973989,0,-14.03629709,0,134.8881033 +114.58,50.34352026,-3.316951539,10000,-141.1184401,141.7154831,0,-14.03629709,0,134.8810774 +114.59,50.3435076,-3.31693166,10000,-141.1010319,141.7331217,0,-14.03629709,0,134.8740515 +114.6,50.34349493,-3.316911779,10000,-141.0836238,141.7498692,0,-14.03629709,0,134.8670255 +114.61,50.34348227,-3.316891896,10000,-141.0627341,141.7666167,0,-14.03629709,0,134.8599996 +114.62,50.34346961,-3.31687201,10000,-141.0488075,141.7833641,0,-14.03629709,0,134.8529737 +114.63,50.34345695,-3.316852122,10000,-141.0453256,141.8001116,0,-14.03629709,0,134.8459478 +114.64,50.34344429,-3.316832232,10000,-141.0418437,141.8177503,0,-14.03629709,0,134.8389218 +114.65,50.34343163,-3.316812339,10000,-141.0244356,141.8356117,0,-14.03629709,0,134.8318959 +114.66,50.34341897,-3.316792443,10000,-140.9896196,141.8523592,0,-14.03629709,0,134.82487 +114.67,50.34340632,-3.316772546,10000,-140.9548036,141.8691067,0,-14.03629709,0,134.8178441 +114.68,50.34339367,-3.316752646,10000,-140.9373954,141.887191,0,-14.03629709,0,134.8108181 +114.69,50.34338102,-3.316732743,10000,-140.9339135,141.9054981,0,-14.03629709,0,134.8037923 +114.7,50.34336837,-3.316712838,10000,-140.9304317,141.9226912,0,-14.03629709,0,134.7967663 +114.71,50.34335572,-3.31669293,10000,-140.9165051,141.9394387,0,-14.03629709,0,134.7897404 +114.72,50.34334307,-3.316673021,10000,-140.8956154,141.9570774,0,-14.03629709,0,134.7827145 +114.73,50.34333043,-3.316653108,10000,-140.8782072,141.9751617,0,-14.03629709,0,134.7756886 +114.74,50.34331778,-3.316633193,10000,-140.8607991,141.9923548,0,-14.03629709,0,134.7686626 +114.75,50.34330514,-3.316613276,10000,-140.8364278,142.0086568,0,-14.03629709,0,134.7616367 +114.76,50.3432925,-3.316593356,10000,-140.8085749,142.0251815,0,-14.03629709,0,134.7546108 +114.77,50.34327986,-3.316573435,10000,-140.7842036,142.0428202,0,-14.03629709,0,134.7475849 +114.78,50.34326723,-3.31655351,10000,-140.7667954,142.0606818,0,-14.03629709,0,134.7405589 +114.79,50.34325459,-3.316533583,10000,-140.7493873,142.0772065,0,-14.03629709,0,134.733533 +114.8,50.34324196,-3.316513654,10000,-140.7284976,142.0932856,0,-14.03629709,0,134.7265071 +114.81,50.34322933,-3.316493723,10000,-140.714571,142.1109244,0,-14.03629709,0,134.7194812 +114.82,50.3432167,-3.316473789,10000,-140.7110891,142.1296771,0,-14.03629709,0,134.7124552 +114.83,50.34320407,-3.316453852,10000,-140.7076073,142.1475387,0,-14.03629709,0,134.7054293 +114.84,50.34319144,-3.316433913,10000,-140.6901991,142.1642863,0,-14.03629709,0,134.6984034 +114.85,50.34317881,-3.316413972,10000,-140.6588647,142.1812566,0,-14.03629709,0,134.6913775 +114.86,50.34316619,-3.316394028,10000,-140.637975,142.1988954,0,-14.03629709,0,134.6843515 +114.87,50.34315357,-3.316374082,10000,-140.6344931,142.2165342,0,-14.03629709,0,134.6773256 +114.88,50.34314094,-3.316354133,10000,-140.6170849,142.2332818,0,-14.03629709,0,134.6702997 +114.89,50.34312832,-3.316334182,10000,-140.5787874,142.2491381,0,-14.03629709,0,134.6632738 +114.9,50.34311571,-3.316314229,10000,-140.5509345,142.2656629,0,-14.03629709,0,134.6562478 +114.91,50.34310309,-3.316294274,10000,-140.5439711,142.2835245,0,-14.03629709,0,134.6492219 +114.92,50.34309048,-3.316274315,10000,-140.5404892,142.3013861,0,-14.03629709,0,134.642196 +114.93,50.34307786,-3.316254355,10000,-140.5265626,142.3190249,0,-14.03629709,0,134.6351701 +114.94,50.34306525,-3.316234392,10000,-140.5056729,142.3371093,0,-14.03629709,0,134.6281442 +114.95,50.34305264,-3.316214426,10000,-140.4882647,142.3547481,0,-14.03629709,0,134.6211182 +114.96,50.34304003,-3.316194458,10000,-140.4708566,142.3714958,0,-14.03629709,0,134.6140923 +114.97,50.34302742,-3.316174488,10000,-140.4499669,142.3882434,0,-14.03629709,0,134.6070664 +114.98,50.34301482,-3.316154515,10000,-140.4325587,142.404991,0,-14.03629709,0,134.6000405 +114.99,50.34300221,-3.31613454,10000,-140.4151506,142.4217386,0,-14.03629709,0,134.5930145 +115,50.34298961,-3.316114563,10000,-140.3942609,142.4393775,0,-14.03629709,0,134.5859887 +115.01,50.34297701,-3.316094583,10000,-140.3768527,142.4572391,0,-14.03629709,0,134.5789627 +115.02,50.34296441,-3.3160746,10000,-140.3594445,142.4739867,0,-14.03629709,0,134.5719368 +115.03,50.34295181,-3.316054616,10000,-140.3385548,142.4905116,0,-14.03629709,0,134.5649109 +115.04,50.34293922,-3.316034629,10000,-140.3211467,142.5077048,0,-14.03629709,0,134.557885 +115.05,50.34292662,-3.316014639,10000,-140.3037385,142.5251209,0,-14.03629709,0,134.550859 +115.06,50.34291403,-3.315994648,10000,-140.2828488,142.5429825,0,-14.03629709,0,134.5438331 +115.07,50.34290144,-3.315974653,10000,-140.2689222,142.5608442,0,-14.03629709,0,134.5368072 +115.08,50.34288885,-3.315954656,10000,-140.2619588,142.5773691,0,-14.03629709,0,134.5297813 +115.09,50.34287626,-3.315934657,10000,-140.2480322,142.5934484,0,-14.03629709,0,134.5227553 +115.1,50.34286367,-3.315914656,10000,-140.2271425,142.6108644,0,-14.03629709,0,134.5157294 +115.11,50.34285109,-3.315894652,10000,-140.2097344,142.6289489,0,-14.03629709,0,134.5087035 +115.12,50.3428385,-3.315874645,10000,-140.1923262,142.646365,0,-14.03629709,0,134.5016776 +115.13,50.34282592,-3.315854637,10000,-140.1714365,142.6633355,0,-14.03629709,0,134.4946516 +115.14,50.34281334,-3.315834625,10000,-140.1540283,142.680306,0,-14.03629709,0,134.4876257 +115.15,50.34280076,-3.315814612,10000,-140.1366202,142.6974993,0,-14.03629709,0,134.4805998 +115.16,50.34278818,-3.315794596,10000,-140.1157305,142.7149154,0,-14.03629709,0,134.4735739 +115.17,50.34277561,-3.315774577,10000,-140.0983223,142.7321087,0,-14.03629709,0,134.4665479 +115.18,50.34276303,-3.315754557,10000,-140.0809142,142.7490792,0,-14.03629709,0,134.459522 +115.19,50.34275046,-3.315734533,10000,-140.0600245,142.7658269,0,-14.03629709,0,134.4524961 +115.2,50.34273789,-3.315714508,10000,-140.0426163,142.7823518,0,-14.03629709,0,134.4454702 +115.21,50.34272532,-3.31569448,10000,-140.0252082,142.7993224,0,-14.03629709,0,134.4384442 +115.22,50.34271275,-3.31567445,10000,-140.0043185,142.8171841,0,-14.03629709,0,134.4314183 +115.23,50.34270019,-3.315654417,10000,-139.9869103,142.8357142,0,-14.03629709,0,134.4243924 +115.24,50.34268762,-3.315634382,10000,-139.9695022,142.8537988,0,-14.03629709,0,134.4173665 +115.25,50.34267506,-3.315614343,10000,-139.9486124,142.8703237,0,-14.03629709,0,134.4103405 +115.26,50.3426625,-3.315594304,10000,-139.9346859,142.8861802,0,-14.03629709,0,134.4033146 +115.27,50.34264994,-3.315574261,10000,-139.9277224,142.9031508,0,-14.03629709,0,134.3962887 +115.28,50.34263738,-3.315554217,10000,-139.9137959,142.9212354,0,-14.03629709,0,134.3892628 +115.29,50.34262482,-3.315534169,10000,-139.8929061,142.9386515,0,-14.03629709,0,134.3822368 +115.3,50.34261227,-3.315514119,10000,-139.875498,142.9547309,0,-14.03629709,0,134.3752109 +115.31,50.34259971,-3.315494068,10000,-139.8580898,142.971033,0,-14.03629709,0,134.368185 +115.32,50.34258716,-3.315474013,10000,-139.8372001,142.988672,0,-14.03629709,0,134.3611591 +115.33,50.34257461,-3.315453957,10000,-139.819792,143.0072022,0,-14.03629709,0,134.3541332 +115.34,50.34256206,-3.315433897,10000,-139.8023838,143.0252868,0,-14.03629709,0,134.3471072 +115.35,50.34254951,-3.315413835,10000,-139.7814941,143.0418118,0,-14.03629709,0,134.3400814 +115.36,50.34253697,-3.315393771,10000,-139.764086,143.0576683,0,-14.03629709,0,134.3330554 +115.37,50.34252442,-3.315373705,10000,-139.7466778,143.0744161,0,-14.03629709,0,134.3260295 +115.38,50.34251188,-3.315353636,10000,-139.7257881,143.0920551,0,-14.03629709,0,134.3190036 +115.39,50.34249934,-3.315333565,10000,-139.7118615,143.1096941,0,-14.03629709,0,134.3119777 +115.4,50.3424868,-3.315313491,10000,-139.7048981,143.1266647,0,-14.03629709,0,134.3049517 +115.41,50.34247426,-3.315293415,10000,-139.68749,143.1431898,0,-14.03629709,0,134.2979258 +115.42,50.34246172,-3.315273337,10000,-139.652674,143.1601604,0,-14.03629709,0,134.2908999 +115.43,50.34244919,-3.315253256,10000,-139.6213396,143.1777994,0,-14.03629709,0,134.283874 +115.44,50.34243666,-3.315233173,10000,-139.6143761,143.1954384,0,-14.03629709,0,134.276848 +115.45,50.34242413,-3.315213087,10000,-139.6143758,143.212409,0,-14.03629709,0,134.2698221 +115.46,50.34241159,-3.315192999,10000,-139.5969677,143.2289341,0,-14.03629709,0,134.2627962 +115.47,50.34239907,-3.315172909,10000,-139.576078,143.2459047,0,-14.03629709,0,134.2557703 +115.48,50.34238654,-3.315152816,10000,-139.5621514,143.2635437,0,-14.03629709,0,134.2487443 +115.49,50.34237401,-3.315132721,10000,-139.5377801,143.2811828,0,-14.03629709,0,134.2417184 +115.5,50.34236149,-3.315112623,10000,-139.5064457,143.2981534,0,-14.03629709,0,134.2346925 +115.51,50.34234897,-3.315092523,10000,-139.4890375,143.3146785,0,-14.03629709,0,134.2276666 +115.52,50.34233645,-3.315072421,10000,-139.4855557,143.3314263,0,-14.03629709,0,134.2206406 +115.53,50.34232393,-3.315052316,10000,-139.4820738,143.3481742,0,-14.03629709,0,134.2136147 +115.54,50.34231141,-3.315032209,10000,-139.4646657,143.3649221,0,-14.03629709,0,134.2065888 +115.55,50.34229889,-3.3150121,10000,-139.4298497,143.3825611,0,-14.03629709,0,134.1995629 +115.56,50.34228638,-3.314991988,10000,-139.3950337,143.4006458,0,-14.03629709,0,134.1925369 +115.57,50.34227387,-3.314971873,10000,-139.3776255,143.4180621,0,-14.03629709,0,134.185511 +115.58,50.34226136,-3.314951757,10000,-139.3741437,143.4350328,0,-14.03629709,0,134.1784851 +115.59,50.34224885,-3.314931637,10000,-139.3706618,143.4517807,0,-14.03629709,0,134.1714592 +115.6,50.34223634,-3.314911516,10000,-139.3567352,143.4683057,0,-14.03629709,0,134.1644332 +115.61,50.34222383,-3.314891392,10000,-139.3358455,143.4852764,0,-14.03629709,0,134.1574073 +115.62,50.34221133,-3.314871266,10000,-139.3184374,143.5026927,0,-14.03629709,0,134.1503814 +115.63,50.34219882,-3.314851137,10000,-139.3010292,143.5196634,0,-14.03629709,0,134.1433555 +115.64,50.34218632,-3.314831006,10000,-139.276658,143.5364113,0,-14.03629709,0,134.1363295 +115.65,50.34217382,-3.314810873,10000,-139.2488051,143.5540505,0,-14.03629709,0,134.1293036 +115.66,50.34216132,-3.314790737,10000,-139.2244338,143.5719124,0,-14.03629709,0,134.1222777 +115.67,50.34214883,-3.314770598,10000,-139.2105073,143.5886603,0,-14.03629709,0,134.1152518 +115.68,50.34213633,-3.314750458,10000,-139.2070254,143.6051854,0,-14.03629709,0,134.1082258 +115.69,50.34212384,-3.314730315,10000,-139.2035435,143.6223789,0,-14.03629709,0,134.1011999 +115.7,50.34211134,-3.314710169,10000,-139.1861354,143.6395725,0,-14.03629709,0,134.094174 +115.71,50.34209885,-3.314690022,10000,-139.1513194,143.6565432,0,-14.03629709,0,134.0871481 +115.72,50.34208636,-3.314669871,10000,-139.1165034,143.673514,0,-14.03629709,0,134.0801222 +115.73,50.34207388,-3.314649719,10000,-139.0990953,143.6907075,0,-14.03629709,0,134.0730963 +115.74,50.34206139,-3.314629564,10000,-139.0956134,143.7079011,0,-14.03629709,0,134.0660704 +115.75,50.34204891,-3.314609406,10000,-139.0921316,143.7244262,0,-14.03629709,0,134.0590444 +115.76,50.34203642,-3.314589247,10000,-139.078205,143.7411742,0,-14.03629709,0,134.0520185 +115.77,50.34202394,-3.314569085,10000,-139.0538337,143.7590361,0,-14.03629709,0,134.0449926 +115.78,50.34201146,-3.31454892,10000,-139.0259809,143.7766753,0,-14.03629709,0,134.0379667 +115.79,50.34199898,-3.314528753,10000,-139.0016096,143.7934233,0,-14.03629709,0,134.0309407 +115.8,50.34198651,-3.314508584,10000,-138.9842014,143.8101712,0,-14.03629709,0,134.0239148 +115.81,50.34197403,-3.314488412,10000,-138.9667933,143.8269192,0,-14.03629709,0,134.0168889 +115.82,50.34196156,-3.314468238,10000,-138.9459036,143.8434444,0,-14.03629709,0,134.009863 +115.83,50.34194909,-3.314448062,10000,-138.931977,143.8604152,0,-14.03629709,0,134.002837 +115.84,50.34193662,-3.314427883,10000,-138.9250136,143.8780544,0,-14.03629709,0,133.9958111 +115.85,50.34192415,-3.314407702,10000,-138.911087,143.8956936,0,-14.03629709,0,133.9887852 +115.86,50.34191168,-3.314387518,10000,-138.8901973,143.9126644,0,-14.03629709,0,133.9817593 +115.87,50.34189922,-3.314367332,10000,-138.8727892,143.9291895,0,-14.03629709,0,133.9747333 +115.88,50.34188675,-3.314347144,10000,-138.855381,143.9459375,0,-14.03629709,0,133.9677074 +115.89,50.34187429,-3.314326953,10000,-138.8344913,143.9626856,0,-14.03629709,0,133.9606815 +115.9,50.34186183,-3.31430676,10000,-138.8170832,143.9792108,0,-14.03629709,0,133.9536556 +115.91,50.34184937,-3.314286565,10000,-138.799675,143.9961816,0,-14.03629709,0,133.9466296 +115.92,50.34183691,-3.314266367,10000,-138.7787853,144.0138208,0,-14.03629709,0,133.9396037 +115.93,50.34182446,-3.314246167,10000,-138.7613772,144.0316828,0,-14.03629709,0,133.9325778 +115.94,50.341812,-3.314225964,10000,-138.743969,144.0493221,0,-14.03629709,0,133.9255519 +115.95,50.34179955,-3.314205759,10000,-138.7230793,144.0660701,0,-14.03629709,0,133.9185259 +115.96,50.3417871,-3.314185551,10000,-138.7056712,144.0819269,0,-14.03629709,0,133.9115 +115.97,50.34177465,-3.314165342,10000,-138.6882631,144.0984522,0,-14.03629709,0,133.9044741 +115.98,50.3417622,-3.31414513,10000,-138.6673734,144.1163142,0,-14.03629709,0,133.8974482 +115.99,50.34174976,-3.314124915,10000,-138.6499652,144.1339535,0,-14.03629709,0,133.8904222 +116,50.34173731,-3.314104698,10000,-138.6325571,144.1507015,0,-14.03629709,0,133.8833963 +116.01,50.34172487,-3.314084479,10000,-138.6116674,144.1676724,0,-14.03629709,0,133.8763704 +116.02,50.34171243,-3.314064257,10000,-138.5977408,144.1853117,0,-14.03629709,0,133.8693445 +116.03,50.34169999,-3.314044033,10000,-138.5907774,144.2029509,0,-14.03629709,0,133.8623185 +116.04,50.34168755,-3.314023806,10000,-138.5768508,144.219699,0,-14.03629709,0,133.8552927 +116.05,50.34167511,-3.314003577,10000,-138.5559611,144.2353331,0,-14.03629709,0,133.8482667 +116.06,50.34166268,-3.313983346,10000,-138.5385529,144.2509671,0,-14.03629709,0,133.8412408 +116.07,50.34165024,-3.313963113,10000,-138.5211448,144.2677152,0,-14.03629709,0,133.8342149 +116.08,50.34163781,-3.313942877,10000,-138.5002551,144.2853545,0,-14.03629709,0,133.827189 +116.09,50.34162538,-3.313922639,10000,-138.482847,144.3032166,0,-14.03629709,0,133.820163 +116.1,50.34161295,-3.313902398,10000,-138.4654389,144.3210787,0,-14.03629709,0,133.8131371 +116.11,50.34160052,-3.313882155,10000,-138.4445491,144.338718,0,-14.03629709,0,133.8061112 +116.12,50.3415881,-3.313861909,10000,-138.427141,144.3554661,0,-14.03629709,0,133.7990853 +116.13,50.34157567,-3.313841661,10000,-138.4097329,144.3711002,0,-14.03629709,0,133.7920594 +116.14,50.34156325,-3.313821411,10000,-138.3888432,144.3869571,0,-14.03629709,0,133.7850334 +116.15,50.34155083,-3.313801159,10000,-138.371435,144.4045964,0,-14.03629709,0,133.7780075 +116.16,50.34153841,-3.313780904,10000,-138.3540269,144.423127,0,-14.03629709,0,133.7709816 +116.17,50.34152599,-3.313760646,10000,-138.3331372,144.4400979,0,-14.03629709,0,133.7639557 +116.18,50.34151358,-3.313740386,10000,-138.315729,144.455732,0,-14.03629709,0,133.7569297 +116.19,50.34150116,-3.313720125,10000,-138.2983209,144.4724801,0,-14.03629709,0,133.7499038 +116.2,50.34148875,-3.31369986,10000,-138.2774312,144.4901194,0,-14.03629709,0,133.7428779 +116.21,50.34147634,-3.313679593,10000,-138.2635046,144.5068676,0,-14.03629709,0,133.735852 +116.22,50.34146393,-3.313659324,10000,-138.2565412,144.5233929,0,-14.03629709,0,133.728826 +116.23,50.34145152,-3.313639053,10000,-138.2426146,144.5403638,0,-14.03629709,0,133.7218001 +116.24,50.34143911,-3.313618778,10000,-138.2217249,144.557112,0,-14.03629709,0,133.7147742 +116.25,50.34142671,-3.313598503,10000,-138.2043168,144.5745286,0,-14.03629709,0,133.7077483 +116.26,50.3414143,-3.313578224,10000,-138.1869087,144.5926136,0,-14.03629709,0,133.7007223 +116.27,50.3414019,-3.313557942,10000,-138.1625374,144.6091389,0,-14.03629709,0,133.6936964 +116.28,50.3413895,-3.313537659,10000,-138.1346846,144.624773,0,-14.03629709,0,133.6866705 +116.29,50.3413771,-3.313517374,10000,-138.1103133,144.641744,0,-14.03629709,0,133.6796446 +116.3,50.34136471,-3.313497085,10000,-138.0929052,144.6591606,0,-14.03629709,0,133.6726186 +116.31,50.34135231,-3.313476795,10000,-138.0789786,144.6759087,0,-14.03629709,0,133.6655927 +116.32,50.34133992,-3.313456502,10000,-138.0685336,144.6928797,0,-14.03629709,0,133.6585668 +116.33,50.34132753,-3.313436207,10000,-138.0580886,144.7105191,0,-14.03629709,0,133.6515409 +116.34,50.34131513,-3.313415909,10000,-138.0371989,144.7281585,0,-14.03629709,0,133.6445149 +116.35,50.34130275,-3.313395609,10000,-138.0163092,144.7449067,0,-14.03629709,0,133.637489 +116.36,50.34129036,-3.313375306,10000,-138.0023826,144.7607637,0,-14.03629709,0,133.6304631 +116.37,50.34127797,-3.313355002,10000,-137.9814929,144.7770663,0,-14.03629709,0,133.6234372 +116.38,50.34126559,-3.313334695,10000,-137.9640848,144.7942601,0,-14.03629709,0,133.6164112 +116.39,50.34125321,-3.313314385,10000,-137.9606029,144.8116767,0,-14.03629709,0,133.6093854 +116.4,50.34124082,-3.313294074,10000,-137.9431948,144.8295389,0,-14.03629709,0,133.6023594 +116.41,50.34122844,-3.313273759,10000,-137.9083788,144.8474012,0,-14.03629709,0,133.5953335 +116.42,50.34121607,-3.313253442,10000,-137.8909707,144.8639266,0,-14.03629709,0,133.5883076 +116.43,50.34120369,-3.313233123,10000,-137.8874888,144.8795608,0,-14.03629709,0,133.5812817 +116.44,50.34119131,-3.313212802,10000,-137.8665991,144.8954178,0,-14.03629709,0,133.5742557 +116.45,50.34117894,-3.313192478,10000,-137.8352647,144.9119432,0,-14.03629709,0,133.5672298 +116.46,50.34116657,-3.313172153,10000,-137.814375,144.9295826,0,-14.03629709,0,133.5602039 +116.47,50.3411542,-3.313151824,10000,-137.7969669,144.9474449,0,-14.03629709,0,133.553178 +116.48,50.34114183,-3.313131493,10000,-137.7760772,144.9641931,0,-14.03629709,0,133.546152 +116.49,50.34112947,-3.31311116,10000,-137.7621506,144.9809414,0,-14.03629709,0,133.5391261 +116.5,50.3411171,-3.313090825,10000,-137.7586688,144.9985809,0,-14.03629709,0,133.5321002 +116.51,50.34110474,-3.313070486,10000,-137.7517053,145.0153291,0,-14.03629709,0,133.5250743 +116.52,50.34109237,-3.313050146,10000,-137.7238525,145.0307405,0,-14.03629709,0,133.5180484 +116.53,50.34108001,-3.313029804,10000,-137.6855549,145.0468203,0,-14.03629709,0,133.5110224 +116.54,50.34106766,-3.313009459,10000,-137.6681468,145.064237,0,-14.03629709,0,133.5039965 +116.55,50.3410553,-3.312989112,10000,-137.664665,145.0820993,0,-14.03629709,0,133.4969706 +116.56,50.34104294,-3.312968762,10000,-137.6472568,145.0997388,0,-14.03629709,0,133.4899447 +116.57,50.34103059,-3.31294841,10000,-137.6263671,145.1167099,0,-14.03629709,0,133.4829187 +116.58,50.34101824,-3.312928055,10000,-137.6124406,145.1332354,0,-14.03629709,0,133.4758928 +116.59,50.34100588,-3.312907699,10000,-137.5915509,145.1499836,0,-14.03629709,0,133.4688669 +116.6,50.34099354,-3.312887339,10000,-137.5706612,145.1667319,0,-14.03629709,0,133.461841 +116.61,50.34098119,-3.312866978,10000,-137.5602162,145.1832574,0,-14.03629709,0,133.454815 +116.62,50.34096884,-3.312846614,10000,-137.5497712,145.2002285,0,-14.03629709,0,133.4477891 +116.63,50.3409565,-3.312826248,10000,-137.5358446,145.2176452,0,-14.03629709,0,133.4407632 +116.64,50.34094415,-3.312805879,10000,-137.5149549,145.2346163,0,-14.03629709,0,133.4337373 +116.65,50.34093181,-3.312785508,10000,-137.4801389,145.250919,0,-14.03629709,0,133.4267113 +116.66,50.34091947,-3.312765135,10000,-137.4488045,145.2669989,0,-14.03629709,0,133.4196854 +116.67,50.34090714,-3.312744759,10000,-137.4418411,145.2833016,0,-14.03629709,0,133.4126595 +116.68,50.3408948,-3.312724382,10000,-137.4418408,145.3002727,0,-14.03629709,0,133.4056336 +116.69,50.34088246,-3.312704001,10000,-137.4209511,145.3179123,0,-14.03629709,0,133.3986076 +116.7,50.34087013,-3.312683619,10000,-137.3896167,145.3355518,0,-14.03629709,0,133.3915818 +116.71,50.3408578,-3.312663233,10000,-137.3722086,145.352523,0,-14.03629709,0,133.3845558 +116.72,50.34084547,-3.312642846,10000,-137.3652452,145.3690485,0,-14.03629709,0,133.3775299 +116.73,50.34083314,-3.312622456,10000,-137.3513186,145.3857968,0,-14.03629709,0,133.370504 +116.74,50.34082081,-3.312602064,10000,-137.3304289,145.4023223,0,-14.03629709,0,133.3634781 +116.75,50.34080849,-3.312581669,10000,-137.3130208,145.4181794,0,-14.03629709,0,133.3564521 +116.76,50.34079616,-3.312561273,10000,-137.2956127,145.4349278,0,-14.03629709,0,133.3494262 +116.77,50.34078384,-3.312540874,10000,-137.2712414,145.4534586,0,-14.03629709,0,133.3424003 +116.78,50.34077152,-3.312520472,10000,-137.2433885,145.471321,0,-14.03629709,0,133.3353744 +116.79,50.3407592,-3.312500067,10000,-137.2190173,145.4869553,0,-14.03629709,0,133.3283484 +116.8,50.34074689,-3.312479662,10000,-137.2050907,145.5028124,0,-14.03629709,0,133.3213225 +116.81,50.34073457,-3.312459253,10000,-137.2016089,145.520452,0,-14.03629709,0,133.3142966 +116.82,50.34072226,-3.312438842,10000,-137.198127,145.5378688,0,-14.03629709,0,133.3072707 +116.83,50.34070994,-3.312418428,10000,-137.1807189,145.5539488,0,-14.03629709,0,133.3002447 +116.84,50.34069763,-3.312398013,10000,-137.1459029,145.5702515,0,-14.03629709,0,133.2932188 +116.85,50.34068532,-3.312377595,10000,-137.111087,145.5874455,0,-14.03629709,0,133.2861929 +116.86,50.34067302,-3.312357174,10000,-137.0936788,145.6046395,0,-14.03629709,0,133.279167 +116.87,50.34066071,-3.312336752,10000,-137.090197,145.6216107,0,-14.03629709,0,133.272141 +116.88,50.34064841,-3.312316326,10000,-137.0867151,145.6383591,0,-14.03629709,0,133.2651151 +116.89,50.3406361,-3.312295899,10000,-137.0727885,145.6548847,0,-14.03629709,0,133.2580892 +116.9,50.3406238,-3.312275469,10000,-137.0484173,145.6716331,0,-14.03629709,0,133.2510633 +116.91,50.3406115,-3.312255037,10000,-137.0205645,145.6883815,0,-14.03629709,0,133.2440373 +116.92,50.3405992,-3.312234602,10000,-136.9961932,145.7051299,0,-14.03629709,0,133.2370114 +116.93,50.34058691,-3.312214166,10000,-136.9787851,145.7225467,0,-14.03629709,0,133.2299855 +116.94,50.34057461,-3.312193726,10000,-136.9613769,145.7395179,0,-14.03629709,0,133.2229596 +116.95,50.34056232,-3.312173284,10000,-136.9404872,145.7549295,0,-14.03629709,0,133.2159337 +116.96,50.34055003,-3.312152841,10000,-136.9265607,145.7707866,0,-14.03629709,0,133.2089077 +116.97,50.34053774,-3.312132395,10000,-136.9195973,145.7886491,0,-14.03629709,0,133.2018818 +116.98,50.34052545,-3.312111946,10000,-136.9056707,145.8069572,0,-14.03629709,0,133.1948559 +116.99,50.34051316,-3.312091495,10000,-136.884781,145.8239285,0,-14.03629709,0,133.18783 +117,50.34050088,-3.312071041,10000,-136.8673729,145.8397857,0,-14.03629709,0,133.180804 +117.01,50.34048859,-3.312050586,10000,-136.8499647,145.8560885,0,-14.03629709,0,133.1737781 +117.02,50.34047631,-3.312030128,10000,-136.8255935,145.8730597,0,-14.03629709,0,133.1667522 +117.03,50.34046403,-3.312009667,10000,-136.7977407,145.8895854,0,-14.03629709,0,133.1597263 +117.04,50.34045175,-3.311989205,10000,-136.7733694,145.9063338,0,-14.03629709,0,133.1527003 +117.05,50.34043948,-3.31196874,10000,-136.7594428,145.9239735,0,-14.03629709,0,133.1456745 +117.06,50.3404272,-3.311948272,10000,-136.755961,145.9407219,0,-14.03629709,0,133.1386485 +117.07,50.34041493,-3.311927802,10000,-136.7524791,145.9563564,0,-14.03629709,0,133.1316226 +117.08,50.34040265,-3.311907331,10000,-136.735071,145.9731048,0,-14.03629709,0,133.1245967 +117.09,50.34039038,-3.311886856,10000,-136.700255,145.9909673,0,-14.03629709,0,133.1175708 +117.1,50.34037811,-3.311866379,10000,-136.6654391,146.0083842,0,-14.03629709,0,133.1105448 +117.11,50.34036585,-3.3118459,10000,-136.648031,146.0253555,0,-14.03629709,0,133.1035189 +117.12,50.34035358,-3.311825418,10000,-136.6445491,146.0418812,0,-14.03629709,0,133.096493 +117.13,50.34034132,-3.311804934,10000,-136.6410672,146.0575156,0,-14.03629709,0,133.0894671 +117.14,50.34032905,-3.311784448,10000,-136.6236591,146.07315,0,-14.03629709,0,133.0824411 +117.15,50.34031679,-3.31176396,10000,-136.5888431,146.0898985,0,-14.03629709,0,133.0754152 +117.16,50.34030453,-3.311743469,10000,-136.5575088,146.1075383,0,-14.03629709,0,133.0683893 +117.17,50.34029228,-3.311722976,10000,-136.5505453,146.125178,0,-14.03629709,0,133.0613634 +117.18,50.34028002,-3.31170248,10000,-136.5505451,146.1419265,0,-14.03629709,0,133.0543374 +117.19,50.34026776,-3.311681982,10000,-136.5296554,146.157561,0,-14.03629709,0,133.0473115 +117.2,50.34025551,-3.311661482,10000,-136.498321,146.1734182,0,-14.03629709,0,133.0402856 +117.21,50.34024326,-3.31164098,10000,-136.4809129,146.1908352,0,-14.03629709,0,133.0332597 +117.22,50.34023101,-3.311620475,10000,-136.4739494,146.2086977,0,-14.03629709,0,133.0262337 +117.23,50.34021876,-3.311599967,10000,-136.4565413,146.2252234,0,-14.03629709,0,133.0192078 +117.24,50.34020651,-3.311579458,10000,-136.4252069,146.2410807,0,-14.03629709,0,133.0121819 +117.25,50.34019427,-3.311558946,10000,-136.4043172,146.2578292,0,-14.03629709,0,133.005156 +117.26,50.34018203,-3.311538432,10000,-136.4008354,146.2752462,0,-14.03629709,0,132.99813 +117.27,50.34016978,-3.311517915,10000,-136.3834272,146.2922175,0,-14.03629709,0,132.9911041 +117.28,50.34015754,-3.311497396,10000,-136.3486113,146.3087433,0,-14.03629709,0,132.9840782 +117.29,50.34014531,-3.311476875,10000,-136.3312031,146.3254918,0,-14.03629709,0,132.9770523 +117.3,50.34013307,-3.311456351,10000,-136.3277213,146.3422403,0,-14.03629709,0,132.9700263 +117.31,50.34012083,-3.311435825,10000,-136.3068316,146.3587661,0,-14.03629709,0,132.9630004 +117.32,50.3401086,-3.311415297,10000,-136.2754972,146.3755146,0,-14.03629709,0,132.9559745 +117.33,50.34009637,-3.311394766,10000,-136.2580891,146.3922632,0,-14.03629709,0,132.9489486 +117.34,50.34008414,-3.311374233,10000,-136.2511257,146.4087889,0,-14.03629709,0,132.9419227 +117.35,50.34007191,-3.311353698,10000,-136.2371991,146.4255375,0,-14.03629709,0,132.9348967 +117.36,50.34005968,-3.31133316,10000,-136.2163094,146.4422861,0,-14.03629709,0,132.9278709 +117.37,50.34004746,-3.31131262,10000,-136.1989013,146.4588118,0,-14.03629709,0,132.9208449 +117.38,50.34003523,-3.311292078,10000,-136.1814932,146.4755604,0,-14.03629709,0,132.913819 +117.39,50.34002301,-3.311271533,10000,-136.1606035,146.492309,0,-14.03629709,0,132.9067931 +117.4,50.34001079,-3.311250986,10000,-136.1431954,146.5088347,0,-14.03629709,0,132.8997672 +117.41,50.33999857,-3.311230437,10000,-136.1257872,146.5258061,0,-14.03629709,0,132.8927412 +117.42,50.33998635,-3.311209885,10000,-136.1048975,146.543446,0,-14.03629709,0,132.8857153 +117.43,50.33997414,-3.311189331,10000,-136.0874894,146.560863,0,-14.03629709,0,132.8786894 +117.44,50.33996192,-3.311168774,10000,-136.0700813,146.5769431,0,-14.03629709,0,132.8716635 +117.45,50.33994971,-3.311148215,10000,-136.0491916,146.592132,0,-14.03629709,0,132.8646375 +117.46,50.3399375,-3.311127655,10000,-136.0352651,146.6079894,0,-14.03629709,0,132.8576116 +117.47,50.33992529,-3.311107091,10000,-136.0283016,146.624738,0,-14.03629709,0,132.8505857 +117.48,50.33991308,-3.311086526,10000,-136.0108935,146.6419322,0,-14.03629709,0,132.8435598 +117.49,50.33990087,-3.311065958,10000,-135.9795591,146.6593493,0,-14.03629709,0,132.8365338 +117.5,50.33988867,-3.311045387,10000,-135.9586694,146.6765435,0,-14.03629709,0,132.8295079 +117.51,50.33987647,-3.311024815,10000,-135.9551876,146.693515,0,-14.03629709,0,132.822482 +117.52,50.33986426,-3.311004239,10000,-135.9377795,146.7102636,0,-14.03629709,0,132.8154561 +117.53,50.33985206,-3.310983662,10000,-135.9029635,146.7265666,0,-14.03629709,0,132.8084301 +117.54,50.33983987,-3.310963082,10000,-135.8855554,146.7426468,0,-14.03629709,0,132.8014042 +117.55,50.33982767,-3.3109425,10000,-135.8820735,146.7589498,0,-14.03629709,0,132.7943783 +117.56,50.33981547,-3.310921916,10000,-135.8611839,146.7756984,0,-14.03629709,0,132.7873524 +117.57,50.33980328,-3.310901329,10000,-135.8298495,146.792447,0,-14.03629709,0,132.7803264 +117.58,50.33979109,-3.31088074,10000,-135.8124413,146.8089729,0,-14.03629709,0,132.7733005 +117.59,50.3397789,-3.310860149,10000,-135.8054779,146.8259443,0,-14.03629709,0,132.7662746 +117.6,50.33976671,-3.310839555,10000,-135.7915514,146.8433614,0,-14.03629709,0,132.7592487 +117.61,50.33975452,-3.310818959,10000,-135.7706617,146.8601101,0,-14.03629709,0,132.7522227 +117.62,50.33974234,-3.31079836,10000,-135.7532536,146.8757447,0,-14.03629709,0,132.7451968 +117.63,50.33973015,-3.31077776,10000,-135.7358454,146.8913793,0,-14.03629709,0,132.7381709 +117.64,50.33971797,-3.310757157,10000,-135.7114742,146.9081279,0,-14.03629709,0,132.731145 +117.65,50.33970579,-3.310736552,10000,-135.6836214,146.925545,0,-14.03629709,0,132.724119 +117.66,50.33969361,-3.310715944,10000,-135.6592501,146.9425165,0,-14.03629709,0,132.7170931 +117.67,50.33968144,-3.310695334,10000,-135.6453236,146.9590424,0,-14.03629709,0,132.7100672 +117.68,50.33966926,-3.310674722,10000,-135.6418417,146.975791,0,-14.03629709,0,132.7030413 +117.69,50.33965709,-3.310654107,10000,-135.6383599,146.9925397,0,-14.03629709,0,132.6960153 +117.7,50.33964491,-3.31063349,10000,-135.6209518,147.0090656,0,-14.03629709,0,132.6889894 +117.71,50.33963274,-3.310612871,10000,-135.5861358,147.0258143,0,-14.03629709,0,132.6819635 +117.72,50.33962057,-3.310592249,10000,-135.5513198,147.042563,0,-14.03629709,0,132.6749376 +117.73,50.33960841,-3.310571625,10000,-135.5339117,147.0590889,0,-14.03629709,0,132.6679117 +117.74,50.33959624,-3.310550999,10000,-135.5304299,147.0758376,0,-14.03629709,0,132.6608858 +117.75,50.33958408,-3.31053037,10000,-135.526948,147.0925863,0,-14.03629709,0,132.6538599 +117.76,50.33957191,-3.310509739,10000,-135.5095399,147.1091122,0,-14.03629709,0,132.6468339 +117.77,50.33955975,-3.310489106,10000,-135.4747239,147.1258609,0,-14.03629709,0,132.639808 +117.78,50.33954759,-3.31046847,10000,-135.4433896,147.1423868,0,-14.03629709,0,132.6327821 +117.79,50.33953544,-3.310447832,10000,-135.4364262,147.1580214,0,-14.03629709,0,132.6257562 +117.8,50.33952328,-3.310427192,10000,-135.4364259,147.173656,0,-14.03629709,0,132.6187302 +117.81,50.33951112,-3.31040655,10000,-135.4155362,147.1904048,0,-14.03629709,0,132.6117043 +117.82,50.33949897,-3.310385905,10000,-135.3842018,147.2080448,0,-14.03629709,0,132.6046784 +117.83,50.33948682,-3.310365258,10000,-135.3633121,147.2256848,0,-14.03629709,0,132.5976525 +117.84,50.33947467,-3.310344608,10000,-135.345904,147.2424335,0,-14.03629709,0,132.5906265 +117.85,50.33946252,-3.310323956,10000,-135.3250143,147.2580681,0,-14.03629709,0,132.5836006 +117.86,50.33945038,-3.310303302,10000,-135.3076062,147.2737028,0,-14.03629709,0,132.5765747 +117.87,50.33943823,-3.310282646,10000,-135.2901981,147.2904515,0,-14.03629709,0,132.5695488 +117.88,50.33942609,-3.310261987,10000,-135.2693084,147.3078687,0,-14.03629709,0,132.5625228 +117.89,50.33941395,-3.310241326,10000,-135.2553819,147.3248403,0,-14.03629709,0,132.5554969 +117.9,50.33940181,-3.310220662,10000,-135.2484184,147.3413662,0,-14.03629709,0,132.548471 +117.91,50.33938967,-3.310199997,10000,-135.2344919,147.358115,0,-14.03629709,0,132.5414451 +117.92,50.33937753,-3.310179328,10000,-135.2136022,147.3748638,0,-14.03629709,0,132.5344191 +117.93,50.3393654,-3.310158658,10000,-135.1961941,147.3911669,0,-14.03629709,0,132.5273932 +117.94,50.33935326,-3.310137985,10000,-135.178786,147.4072472,0,-14.03629709,0,132.5203673 +117.95,50.33934113,-3.31011731,10000,-135.1578963,147.4235504,0,-14.03629709,0,132.5133414 +117.96,50.339329,-3.310096633,10000,-135.1404882,147.4402991,0,-14.03629709,0,132.5063154 +117.97,50.33931687,-3.310075953,10000,-135.1195985,147.4570479,0,-14.03629709,0,132.4992895 +117.98,50.33930474,-3.310055271,10000,-135.0882641,147.4735739,0,-14.03629709,0,132.4922636 +117.99,50.33929262,-3.310034587,10000,-135.0673744,147.4903227,0,-14.03629709,0,132.4852377 +118,50.3392805,-3.3100139,10000,-135.0673741,147.5070715,0,-14.03629709,0,132.4782117 +118.01,50.33926837,-3.309993211,10000,-135.0604107,147.5235974,0,-14.03629709,0,132.4711858 +118.02,50.33925625,-3.30997252,10000,-135.0290764,147.5403462,0,-14.03629709,0,132.4641599 +118.03,50.33924413,-3.309951826,10000,-134.9942604,147.557095,0,-14.03629709,0,132.457134 +118.04,50.33923202,-3.30993113,10000,-134.9768523,147.5733982,0,-14.03629709,0,132.450108 +118.05,50.3392199,-3.309910432,10000,-134.9733704,147.5894786,0,-14.03629709,0,132.4430821 +118.06,50.33920779,-3.309889731,10000,-134.9698886,147.6057817,0,-14.03629709,0,132.4360562 +118.07,50.33919567,-3.309869029,10000,-134.9524805,147.6225306,0,-14.03629709,0,132.4290303 +118.08,50.33918356,-3.309848323,10000,-134.9176645,147.6392794,0,-14.03629709,0,132.4220044 +118.09,50.33917145,-3.309827616,10000,-134.8828486,147.6555826,0,-14.03629709,0,132.4149785 +118.1,50.33915935,-3.309806906,10000,-134.8654404,147.6716629,0,-14.03629709,0,132.4079525 +118.11,50.33914724,-3.309786194,10000,-134.8619586,147.6881889,0,-14.03629709,0,132.4009266 +118.12,50.33913514,-3.30976548,10000,-134.8584768,147.705829,0,-14.03629709,0,132.3939007 +118.13,50.33912303,-3.309744763,10000,-134.8410687,147.7234691,0,-14.03629709,0,132.3868748 +118.14,50.33911093,-3.309724043,10000,-134.8062527,147.7393267,0,-14.03629709,0,132.3798489 +118.15,50.33909883,-3.309703322,10000,-134.7714367,147.7547386,0,-14.03629709,0,132.3728229 +118.16,50.33908674,-3.309682599,10000,-134.7540286,147.7714875,0,-14.03629709,0,132.365797 +118.17,50.33907464,-3.309661872,10000,-134.7505468,147.7880135,0,-14.03629709,0,132.3587711 +118.18,50.33906255,-3.309641144,10000,-134.7470649,147.8036483,0,-14.03629709,0,132.3517452 +118.19,50.33905045,-3.309620414,10000,-134.7331384,147.8203971,0,-14.03629709,0,132.3447192 +118.2,50.33903836,-3.309599681,10000,-134.7087671,147.8380373,0,-14.03629709,0,132.3376933 +118.21,50.33902627,-3.309578945,10000,-134.6809143,147.8545633,0,-14.03629709,0,132.3306674 +118.22,50.33901418,-3.309558208,10000,-134.6565431,147.8704209,0,-14.03629709,0,132.3236415 +118.23,50.3390021,-3.309537468,10000,-134.639135,147.8871698,0,-14.03629709,0,132.3166155 +118.24,50.33899001,-3.309516726,10000,-134.6217269,147.9045871,0,-14.03629709,0,132.3095896 +118.25,50.33897793,-3.309495981,10000,-134.6008372,147.921336,0,-14.03629709,0,132.3025637 +118.26,50.33896585,-3.309475234,10000,-134.5869106,147.9369707,0,-14.03629709,0,132.2955378 +118.27,50.33895377,-3.309454485,10000,-134.5799472,147.9526055,0,-14.03629709,0,132.2885118 +118.28,50.33894169,-3.309433734,10000,-134.5660207,147.9691316,0,-14.03629709,0,132.2814859 +118.29,50.33892961,-3.30941298,10000,-134.545131,147.9858805,0,-14.03629709,0,132.27446 +118.3,50.33891754,-3.309392224,10000,-134.5277229,148.0024066,0,-14.03629709,0,132.2674341 +118.31,50.33890546,-3.309371466,10000,-134.5103148,148.0191555,0,-14.03629709,0,132.2604081 +118.32,50.33889339,-3.309350705,10000,-134.4859435,148.0359044,0,-14.03629709,0,132.2533822 +118.33,50.33888132,-3.309329942,10000,-134.4580907,148.0522076,0,-14.03629709,0,132.2463563 +118.34,50.33886925,-3.309309177,10000,-134.4337195,148.0682881,0,-14.03629709,0,132.2393304 +118.35,50.33885719,-3.309288409,10000,-134.4163114,148.0845913,0,-14.03629709,0,132.2323044 +118.36,50.33884512,-3.30926764,10000,-134.3989033,148.1013402,0,-14.03629709,0,132.2252785 +118.37,50.33883306,-3.309246867,10000,-134.3780136,148.1180892,0,-14.03629709,0,132.2182526 +118.38,50.338821,-3.309226093,10000,-134.364087,148.1346153,0,-14.03629709,0,132.2112267 +118.39,50.33880894,-3.309205316,10000,-134.3571236,148.151587,0,-14.03629709,0,132.2042007 +118.4,50.33879688,-3.309184537,10000,-134.3431971,148.1687816,0,-14.03629709,0,132.1971749 +118.41,50.33878482,-3.309163755,10000,-134.3223074,148.1846392,0,-14.03629709,0,132.1901489 +118.42,50.33877277,-3.309142971,10000,-134.3048993,148.19916,0,-14.03629709,0,132.183123 +118.43,50.33876071,-3.309122186,10000,-134.2874912,148.2147948,0,-14.03629709,0,132.1760971 +118.44,50.33874866,-3.309101398,10000,-134.2666015,148.232435,0,-14.03629709,0,132.1690712 +118.45,50.33873661,-3.309080607,10000,-134.2491934,148.2500752,0,-14.03629709,0,132.1620452 +118.46,50.33872456,-3.309059814,10000,-134.2317853,148.2668242,0,-14.03629709,0,132.1550193 +118.47,50.33871251,-3.309039019,10000,-134.2108956,148.2835731,0,-14.03629709,0,132.1479934 +118.48,50.33870047,-3.309018221,10000,-134.1934875,148.3000992,0,-14.03629709,0,132.1409675 +118.49,50.33868842,-3.308997421,10000,-134.1760794,148.3157341,0,-14.03629709,0,132.1339415 +118.5,50.33867638,-3.308976619,10000,-134.1551897,148.331369,0,-14.03629709,0,132.1269156 +118.51,50.33866434,-3.308955815,10000,-134.1377816,148.3478951,0,-14.03629709,0,132.1198897 +118.52,50.3386523,-3.308935008,10000,-134.1203735,148.3646441,0,-14.03629709,0,132.1128638 +118.53,50.33864026,-3.308914199,10000,-134.0994838,148.3811702,0,-14.03629709,0,132.1058379 +118.54,50.33862823,-3.308893388,10000,-134.0820757,148.3979192,0,-14.03629709,0,132.0988119 +118.55,50.33861619,-3.308872574,10000,-134.0646676,148.4146682,0,-14.03629709,0,132.091786 +118.56,50.33860416,-3.308851758,10000,-134.0437779,148.4311943,0,-14.03629709,0,132.0847601 +118.57,50.33859213,-3.30883094,10000,-134.0263698,148.4479433,0,-14.03629709,0,132.0777342 +118.58,50.3385801,-3.308810119,10000,-134.0089617,148.4644695,0,-14.03629709,0,132.0707082 +118.59,50.33856807,-3.308789296,10000,-133.988072,148.4801043,0,-14.03629709,0,132.0636823 +118.6,50.33855605,-3.308768471,10000,-133.9706639,148.4957392,0,-14.03629709,0,132.0566564 +118.61,50.33854402,-3.308747644,10000,-133.9532558,148.5124882,0,-14.03629709,0,132.0496305 +118.62,50.338532,-3.308726814,10000,-133.9323661,148.5301285,0,-14.03629709,0,132.0426045 +118.63,50.33851998,-3.308705982,10000,-133.914958,148.547546,0,-14.03629709,0,132.0355786 +118.64,50.33850796,-3.308685147,10000,-133.8975499,148.5634037,0,-14.03629709,0,132.0285527 +118.65,50.33849594,-3.30866431,10000,-133.8766602,148.5779245,0,-14.03629709,0,132.0215268 +118.66,50.33848393,-3.308643472,10000,-133.8592521,148.5935594,0,-14.03629709,0,132.0145008 +118.67,50.33847191,-3.308622631,10000,-133.841844,148.6111997,0,-14.03629709,0,132.0074749 +118.68,50.3384599,-3.308601787,10000,-133.8209544,148.62884,0,-14.03629709,0,132.000449 +118.69,50.33844789,-3.308580941,10000,-133.8070278,148.6453662,0,-14.03629709,0,131.9934231 +118.7,50.33843588,-3.308560093,10000,-133.8000644,148.6612239,0,-14.03629709,0,131.9863971 +118.71,50.33842387,-3.308539242,10000,-133.7861379,148.676636,0,-14.03629709,0,131.9793712 +118.72,50.33841186,-3.30851839,10000,-133.7652482,148.692271,0,-14.03629709,0,131.9723453 +118.73,50.33839986,-3.308497535,10000,-133.7478401,148.70902,0,-14.03629709,0,131.9653194 +118.74,50.33838785,-3.308476678,10000,-133.7269504,148.7264375,0,-14.03629709,0,131.9582934 +118.75,50.33837585,-3.308455818,10000,-133.6921345,148.7434094,0,-14.03629709,0,131.9512676 +118.76,50.33836385,-3.308434956,10000,-133.6608001,148.7599356,0,-14.03629709,0,131.9442416 +118.77,50.33835186,-3.308414092,10000,-133.6538367,148.7764618,0,-14.03629709,0,131.9372157 +118.78,50.33833986,-3.308393225,10000,-133.6538364,148.7923196,0,-14.03629709,0,131.9301898 +118.79,50.33832786,-3.308372356,10000,-133.6329467,148.8075089,0,-14.03629709,0,131.9231639 +118.8,50.33831587,-3.308351486,10000,-133.6016124,148.8233666,0,-14.03629709,0,131.9161379 +118.81,50.33830388,-3.308330612,10000,-133.5842043,148.8401157,0,-14.03629709,0,131.909112 +118.82,50.33829189,-3.308309737,10000,-133.5772408,148.8573104,0,-14.03629709,0,131.9020861 +118.83,50.3382799,-3.308288859,10000,-133.5633143,148.8745051,0,-14.03629709,0,131.8950602 +118.84,50.33826791,-3.308267978,10000,-133.5424246,148.8908085,0,-14.03629709,0,131.8880342 +118.85,50.33825593,-3.308247096,10000,-133.5250165,148.9066663,0,-14.03629709,0,131.8810083 +118.86,50.33824394,-3.308226211,10000,-133.5076084,148.9231926,0,-14.03629709,0,131.8739824 +118.87,50.33823196,-3.308205324,10000,-133.4832372,148.9397188,0,-14.03629709,0,131.8669565 +118.88,50.33821998,-3.308184434,10000,-133.4553844,148.9553538,0,-14.03629709,0,131.8599305 +118.89,50.338208,-3.308163543,10000,-133.4310132,148.9709888,0,-14.03629709,0,131.8529046 +118.9,50.33819603,-3.308142649,10000,-133.413605,148.9877378,0,-14.03629709,0,131.8458787 +118.91,50.33818405,-3.308121753,10000,-133.3961969,149.0051554,0,-14.03629709,0,131.8388528 +118.92,50.33817208,-3.308100854,10000,-133.3753073,149.0221273,0,-14.03629709,0,131.8318268 +118.93,50.33816011,-3.308079953,10000,-133.3613807,149.0384308,0,-14.03629709,0,131.8248009 +118.94,50.33814814,-3.30805905,10000,-133.3578989,149.0542886,0,-14.03629709,0,131.817775 +118.95,50.33813617,-3.308038144,10000,-133.354417,149.0697007,0,-14.03629709,0,131.8107491 +118.96,50.3381242,-3.308017237,10000,-133.3370089,149.0853357,0,-14.03629709,0,131.8037232 +118.97,50.33811223,-3.307996327,10000,-133.302193,149.1020849,0,-14.03629709,0,131.7966972 +118.98,50.33810027,-3.307975415,10000,-133.2673771,149.1195024,0,-14.03629709,0,131.7896713 +118.99,50.33808831,-3.3079545,10000,-133.249969,149.1362515,0,-14.03629709,0,131.7826454 +119,50.33807635,-3.307933583,10000,-133.2430056,149.1518865,0,-14.03629709,0,131.7756195 +119.01,50.33806439,-3.307912664,10000,-133.229079,149.1675216,0,-14.03629709,0,131.7685935 +119.02,50.33805243,-3.307891743,10000,-133.2081894,149.1842707,0,-14.03629709,0,131.7615676 +119.03,50.33804048,-3.307870819,10000,-133.1907812,149.2016883,0,-14.03629709,0,131.7545417 +119.04,50.33802852,-3.307849893,10000,-133.1733731,149.2184374,0,-14.03629709,0,131.7475158 +119.05,50.33801657,-3.307828964,10000,-133.1524835,149.2340724,0,-14.03629709,0,131.7404898 +119.06,50.33800462,-3.307808034,10000,-133.1350754,149.2494846,0,-14.03629709,0,131.733464 +119.07,50.33799267,-3.307787101,10000,-133.1176673,149.2653425,0,-14.03629709,0,131.726438 +119.08,50.33798072,-3.307766166,10000,-133.0967776,149.281646,0,-14.03629709,0,131.7194121 +119.09,50.33796878,-3.307745229,10000,-133.0793695,149.2983951,0,-14.03629709,0,131.7123862 +119.1,50.33795683,-3.307724289,10000,-133.0619614,149.3151443,0,-14.03629709,0,131.7053603 +119.11,50.33794489,-3.307703347,10000,-133.0410717,149.3316706,0,-14.03629709,0,131.6983343 +119.12,50.33793295,-3.307682403,10000,-133.0236636,149.3484198,0,-14.03629709,0,131.6913084 +119.13,50.33792101,-3.307661456,10000,-133.0062555,149.3649461,0,-14.03629709,0,131.6842825 +119.14,50.33790907,-3.307640507,10000,-132.9853659,149.3805811,0,-14.03629709,0,131.6772566 +119.15,50.33789714,-3.307619556,10000,-132.9679577,149.3962162,0,-14.03629709,0,131.6702306 +119.16,50.3378852,-3.307598603,10000,-132.9505496,149.4127425,0,-14.03629709,0,131.6632047 +119.17,50.33787327,-3.307577647,10000,-132.92966,149.4294917,0,-14.03629709,0,131.6561788 +119.18,50.33786134,-3.307556689,10000,-132.9122519,149.4460181,0,-14.03629709,0,131.6491529 +119.19,50.33784941,-3.307535729,10000,-132.8948438,149.4627672,0,-14.03629709,0,131.6421269 +119.2,50.33783748,-3.307514766,10000,-132.8739541,149.4792936,0,-14.03629709,0,131.635101 +119.21,50.33782556,-3.307493801,10000,-132.856546,149.4949287,0,-14.03629709,0,131.6280751 +119.22,50.33781363,-3.307472834,10000,-132.8391379,149.5103409,0,-14.03629709,0,131.6210492 +119.23,50.33780171,-3.307451865,10000,-132.8182482,149.5261988,0,-14.03629709,0,131.6140232 +119.24,50.33778979,-3.307430893,10000,-132.8008401,149.5425023,0,-14.03629709,0,131.6069973 +119.25,50.33777787,-3.30740992,10000,-132.783432,149.5592515,0,-14.03629709,0,131.5999714 +119.26,50.33776595,-3.307388943,10000,-132.7625424,149.5760007,0,-14.03629709,0,131.5929455 +119.27,50.33775404,-3.307367965,10000,-132.7451343,149.5923043,0,-14.03629709,0,131.5859195 +119.28,50.33774212,-3.307346984,10000,-132.7277262,149.608385,0,-14.03629709,0,131.5788936 +119.29,50.33773021,-3.307326001,10000,-132.7068365,149.6246886,0,-14.03629709,0,131.5718677 +119.3,50.3377183,-3.307305016,10000,-132.6929099,149.6414378,0,-14.03629709,0,131.5648418 +119.31,50.33770639,-3.307284028,10000,-132.6859466,149.6579642,0,-14.03629709,0,131.5578158 +119.32,50.33769448,-3.307263038,10000,-132.6685385,149.6735993,0,-14.03629709,0,131.5507899 +119.33,50.33768257,-3.307242046,10000,-132.6372041,149.6892344,0,-14.03629709,0,131.543764 +119.34,50.33767067,-3.307221052,10000,-132.6163144,149.7057608,0,-14.03629709,0,131.5367381 +119.35,50.33765877,-3.307200055,10000,-132.6128326,149.72251,0,-14.03629709,0,131.5297122 +119.36,50.33764686,-3.307179056,10000,-132.5954245,149.7388136,0,-14.03629709,0,131.5226862 +119.37,50.33763496,-3.307158055,10000,-132.557127,149.7548943,0,-14.03629709,0,131.5156603 +119.38,50.33762307,-3.307137051,10000,-132.5292742,149.7711979,0,-14.03629709,0,131.5086344 +119.39,50.33761117,-3.307116046,10000,-132.5223108,149.7879472,0,-14.03629709,0,131.5016085 +119.4,50.33759928,-3.307095037,10000,-132.518829,149.8046964,0,-14.03629709,0,131.4945825 +119.41,50.33758738,-3.307074027,10000,-132.5049024,149.821,0,-14.03629709,0,131.4875567 +119.42,50.33757549,-3.307053014,10000,-132.4805312,149.836858,0,-14.03629709,0,131.4805307 +119.43,50.3375636,-3.307031999,10000,-132.4526784,149.8522703,0,-14.03629709,0,131.4735048 +119.44,50.33755171,-3.307010982,10000,-132.4283072,149.8679054,0,-14.03629709,0,131.4664789 +119.45,50.33753983,-3.306989963,10000,-132.4108991,149.8844318,0,-14.03629709,0,131.459453 +119.46,50.33752794,-3.306968941,10000,-132.393491,149.9011811,0,-14.03629709,0,131.452427 +119.47,50.33751606,-3.306947917,10000,-132.3726013,149.9174847,0,-14.03629709,0,131.4454011 +119.48,50.33750418,-3.306926891,10000,-132.3586748,149.9333427,0,-14.03629709,0,131.4383752 +119.49,50.3374923,-3.306905862,10000,-132.3517114,149.948755,0,-14.03629709,0,131.4313493 +119.5,50.33748042,-3.306884832,10000,-132.3377848,149.9643901,0,-14.03629709,0,131.4243233 +119.51,50.33746854,-3.306863799,10000,-132.3168952,149.9811394,0,-14.03629709,0,131.4172974 +119.52,50.33745667,-3.306842764,10000,-132.2994871,149.9985572,0,-14.03629709,0,131.4102715 +119.53,50.33744479,-3.306821726,10000,-132.282079,150.0153064,0,-14.03629709,0,131.4032456 +119.54,50.33743292,-3.306800686,10000,-132.2577077,150.0311644,0,-14.03629709,0,131.3962196 +119.55,50.33742105,-3.306779644,10000,-132.2298549,150.0474681,0,-14.03629709,0,131.3891937 +119.56,50.33740918,-3.3067586,10000,-132.2054837,150.0642173,0,-14.03629709,0,131.3821678 +119.57,50.33739732,-3.306737552,10000,-132.1880756,150.0798525,0,-14.03629709,0,131.3751419 +119.58,50.33738545,-3.306716504,10000,-132.1706675,150.0952648,0,-14.03629709,0,131.3681159 +119.59,50.33737359,-3.306695453,10000,-132.1497779,150.112237,0,-14.03629709,0,131.36109 +119.6,50.33736173,-3.306674399,10000,-132.1358513,150.1294319,0,-14.03629709,0,131.3540641 +119.61,50.33734987,-3.306653343,10000,-132.1288879,150.1450671,0,-14.03629709,0,131.3470382 +119.62,50.33733801,-3.306632285,10000,-132.1149614,150.159811,0,-14.03629709,0,131.3400122 +119.63,50.33732615,-3.306611225,10000,-132.0940717,150.1752233,0,-14.03629709,0,131.3329863 +119.64,50.3373143,-3.306590163,10000,-132.0766636,150.1919726,0,-14.03629709,0,131.3259604 +119.65,50.33730244,-3.306569098,10000,-132.0592555,150.2093904,0,-14.03629709,0,131.3189345 +119.66,50.33729059,-3.306548031,10000,-132.0348843,150.2261398,0,-14.03629709,0,131.3119085 +119.67,50.33727874,-3.306526961,10000,-132.0070315,150.241775,0,-14.03629709,0,131.3048826 +119.68,50.33726689,-3.30650589,10000,-131.9826603,150.2574101,0,-14.03629709,0,131.2978567 +119.69,50.33725505,-3.306484816,10000,-131.9652522,150.2739366,0,-14.03629709,0,131.2908308 +119.7,50.3372432,-3.30646374,10000,-131.9478441,150.290686,0,-14.03629709,0,131.2838048 +119.71,50.33723136,-3.306442661,10000,-131.9269544,150.3069897,0,-14.03629709,0,131.2767789 +119.72,50.33721952,-3.306421581,10000,-131.9130279,150.3228477,0,-14.03629709,0,131.269753 +119.73,50.33720768,-3.306400497,10000,-131.9060645,150.3384829,0,-14.03629709,0,131.2627271 +119.74,50.33719584,-3.306379413,10000,-131.892138,150.3547866,0,-14.03629709,0,131.2557012 +119.75,50.337184,-3.306358325,10000,-131.8712483,150.3717588,0,-14.03629709,0,131.2486753 +119.76,50.33717217,-3.306337235,10000,-131.8538402,150.3878396,0,-14.03629709,0,131.2416494 +119.77,50.33716033,-3.306316143,10000,-131.8364321,150.4028064,0,-14.03629709,0,131.2346234 +119.78,50.3371485,-3.306295049,10000,-131.8155425,150.4182188,0,-14.03629709,0,131.2275975 +119.79,50.33713667,-3.306273953,10000,-131.7981344,150.4347453,0,-14.03629709,0,131.2205716 +119.8,50.33712484,-3.306252854,10000,-131.7772447,150.4514947,0,-14.03629709,0,131.2135457 +119.81,50.33711301,-3.306231753,10000,-131.7459103,150.4680212,0,-14.03629709,0,131.2065197 +119.82,50.33710119,-3.30621065,10000,-131.7250207,150.4847706,0,-14.03629709,0,131.1994938 +119.83,50.33708937,-3.306189544,10000,-131.7250204,150.5012971,0,-14.03629709,0,131.1924679 +119.84,50.33707754,-3.306168436,10000,-131.718057,150.5169323,0,-14.03629709,0,131.185442 +119.85,50.33706572,-3.306147326,10000,-131.6867227,150.5325676,0,-14.03629709,0,131.178416 +119.86,50.3370539,-3.306126214,10000,-131.6519067,150.5490941,0,-14.03629709,0,131.1713901 +119.87,50.33704209,-3.306105099,10000,-131.6310171,150.5656207,0,-14.03629709,0,131.1643642 +119.88,50.33703027,-3.306083982,10000,-131.613609,150.5812559,0,-14.03629709,0,131.1573383 +119.89,50.33701846,-3.306062863,10000,-131.5927193,150.5968912,0,-14.03629709,0,131.1503123 +119.9,50.33700665,-3.306041742,10000,-131.5787928,150.6134177,0,-14.03629709,0,131.1432864 +119.91,50.33699484,-3.306020618,10000,-131.575311,150.6299443,0,-14.03629709,0,131.1362605 +119.92,50.33698303,-3.305999492,10000,-131.5718291,150.6455796,0,-14.03629709,0,131.1292346 +119.93,50.33697122,-3.305978364,10000,-131.554421,150.6612148,0,-14.03629709,0,131.1222086 +119.94,50.33695941,-3.305957234,10000,-131.5196051,150.6777414,0,-14.03629709,0,131.1151827 +119.95,50.33694761,-3.305936101,10000,-131.4847892,150.694268,0,-14.03629709,0,131.1081568 +119.96,50.33693581,-3.305914966,10000,-131.4673811,150.7099032,0,-14.03629709,0,131.1011309 +119.97,50.33692401,-3.305893829,10000,-131.4604177,150.7255385,0,-14.03629709,0,131.0941049 +119.98,50.33691221,-3.30587269,10000,-131.4464912,150.7420651,0,-14.03629709,0,131.087079 +119.99,50.33690041,-3.305851548,10000,-131.4256015,150.7585917,0,-14.03629709,0,131.0800531 +120,50.33688862,-3.305830404,10000,-131.4081934,150.774227,0,-14.03629709,0,131.0730272 +120.01,50.33687682,-3.305809258,10000,-131.3907853,150.7898623,0,-14.03629709,0,131.0660012 +120.02,50.33686503,-3.30578811,10000,-131.3664141,150.8063888,0,-14.03629709,0,131.0589753 +120.03,50.33685324,-3.305766959,10000,-131.3385613,150.8231383,0,-14.03629709,0,131.0519494 +120.04,50.33684145,-3.305745806,10000,-131.3141901,150.839442,0,-14.03629709,0,131.0449235 +120.05,50.33682967,-3.305724651,10000,-131.3002636,150.8553002,0,-14.03629709,0,131.0378975 +120.06,50.33681788,-3.305703493,10000,-131.2967817,150.8707126,0,-14.03629709,0,131.0308716 +120.07,50.3368061,-3.305682334,10000,-131.2932999,150.8863479,0,-14.03629709,0,131.0238457 +120.08,50.33679431,-3.305661172,10000,-131.2758918,150.9030974,0,-14.03629709,0,131.0168198 +120.09,50.33678253,-3.305640008,10000,-131.2410759,150.9202925,0,-14.03629709,0,131.0097938 +120.1,50.33677075,-3.305618841,10000,-131.20626,150.9361506,0,-14.03629709,0,131.002768 +120.11,50.33675898,-3.305597672,10000,-131.1853703,150.9506718,0,-14.03629709,0,130.995742 +120.12,50.3367472,-3.305576502,10000,-131.1714438,150.9663071,0,-14.03629709,0,130.9887161 +120.13,50.33673543,-3.305555329,10000,-131.1609988,150.9839478,0,-14.03629709,0,130.9816902 +120.14,50.33672366,-3.305534153,10000,-131.1505539,151.0013658,0,-14.03629709,0,130.9746643 +120.15,50.33671188,-3.305512975,10000,-131.1296642,151.0170011,0,-14.03629709,0,130.9676384 +120.16,50.33670012,-3.305491795,10000,-131.1087745,151.0317451,0,-14.03629709,0,130.9606124 +120.17,50.33668835,-3.305470613,10000,-131.094848,151.0471576,0,-14.03629709,0,130.9535865 +120.18,50.33667658,-3.305449429,10000,-131.0704768,151.0639071,0,-14.03629709,0,130.9465606 +120.19,50.33666482,-3.305428242,10000,-131.0391425,151.081325,0,-14.03629709,0,130.9395347 +120.2,50.33665306,-3.305407053,10000,-131.0217344,151.0980745,0,-14.03629709,0,130.9325087 +120.21,50.3366413,-3.305385861,10000,-131.0182526,151.113487,0,-14.03629709,0,130.9254828 +120.22,50.33662954,-3.305364668,10000,-131.0147707,151.1280082,0,-14.03629709,0,130.9184569 +120.23,50.33661778,-3.305343472,10000,-130.9973626,151.1427522,0,-14.03629709,0,130.911431 +120.24,50.33660602,-3.305322275,10000,-130.9625467,151.1590561,0,-14.03629709,0,130.904405 +120.25,50.33659427,-3.305301075,10000,-130.9277308,151.1769197,0,-14.03629709,0,130.8973791 +120.26,50.33658252,-3.305279872,10000,-130.9103227,151.1943377,0,-14.03629709,0,130.8903532 +120.27,50.33657077,-3.305258667,10000,-130.9033593,151.209973,0,-14.03629709,0,130.8833273 +120.28,50.33655902,-3.30523746,10000,-130.8894328,151.224717,0,-14.03629709,0,130.8763013 +120.29,50.33654727,-3.305216251,10000,-130.8685431,151.2401296,0,-14.03629709,0,130.8692754 +120.3,50.33653553,-3.30519504,10000,-130.851135,151.2566562,0,-14.03629709,0,130.8622495 +120.31,50.33652378,-3.305173826,10000,-130.8337269,151.2731829,0,-14.03629709,0,130.8552236 +120.32,50.33651204,-3.30515261,10000,-130.8128373,151.2888183,0,-14.03629709,0,130.8481976 +120.33,50.3365003,-3.305131392,10000,-130.7954292,151.3044536,0,-14.03629709,0,130.8411717 +120.34,50.33648856,-3.305110172,10000,-130.7780211,151.3209803,0,-14.03629709,0,130.8341458 +120.35,50.33647682,-3.305088949,10000,-130.7571315,151.337507,0,-14.03629709,0,130.8271199 +120.36,50.33646509,-3.305067724,10000,-130.7397234,151.3531424,0,-14.03629709,0,130.8200939 +120.37,50.33645335,-3.305046497,10000,-130.7223153,151.3687778,0,-14.03629709,0,130.813068 +120.38,50.33644162,-3.305025268,10000,-130.7014256,151.3853045,0,-14.03629709,0,130.8060421 +120.39,50.33642989,-3.305004036,10000,-130.6840175,151.4018312,0,-14.03629709,0,130.7990162 +120.4,50.33641816,-3.304982802,10000,-130.6666095,151.4174665,0,-14.03629709,0,130.7919902 +120.41,50.33640643,-3.304961566,10000,-130.6457198,151.4328791,0,-14.03629709,0,130.7849643 +120.42,50.33639471,-3.304940328,10000,-130.6283117,151.4487373,0,-14.03629709,0,130.7779384 +120.43,50.33638298,-3.304919087,10000,-130.6109036,151.4650412,0,-14.03629709,0,130.7709125 +120.44,50.33637126,-3.304897845,10000,-130.5865324,151.4817907,0,-14.03629709,0,130.7638865 +120.45,50.33635954,-3.304876599,10000,-130.5586796,151.4983174,0,-14.03629709,0,130.7568607 +120.46,50.33634782,-3.304855352,10000,-130.5343084,151.5139528,0,-14.03629709,0,130.7498347 +120.47,50.33633611,-3.304834102,10000,-130.5203819,151.5295882,0,-14.03629709,0,130.7428088 +120.48,50.33632439,-3.304812851,10000,-130.5169,151.5458921,0,-14.03629709,0,130.7357829 +120.49,50.33631268,-3.304791596,10000,-130.5134182,151.5617503,0,-14.03629709,0,130.728757 +120.5,50.33630096,-3.30477034,10000,-130.4960101,151.5769401,0,-14.03629709,0,130.721731 +120.51,50.33628925,-3.304749082,10000,-130.4611942,151.5927983,0,-14.03629709,0,130.7147051 +120.52,50.33627754,-3.304727821,10000,-130.4263783,151.6091022,0,-14.03629709,0,130.7076792 +120.53,50.33626584,-3.304706558,10000,-130.4054886,151.6247376,0,-14.03629709,0,130.7006533 +120.54,50.33625413,-3.304685293,10000,-130.3915621,151.6403731,0,-14.03629709,0,130.6936274 +120.55,50.33624243,-3.304664026,10000,-130.3811172,151.6568998,0,-14.03629709,0,130.6866014 +120.56,50.33623073,-3.304642756,10000,-130.3706722,151.6736494,0,-14.03629709,0,130.6795755 +120.57,50.33621902,-3.304621484,10000,-130.3497826,151.6899533,0,-14.03629709,0,130.6725496 +120.58,50.33620733,-3.30460021,10000,-130.3288929,151.7058115,0,-14.03629709,0,130.6655237 +120.59,50.33619563,-3.304578933,10000,-130.3149664,151.7212241,0,-14.03629709,0,130.6584977 +120.6,50.33618393,-3.304557655,10000,-130.2905952,151.7366367,0,-14.03629709,0,130.6514718 +120.61,50.33617224,-3.304536374,10000,-130.2592608,151.752495,0,-14.03629709,0,130.6444459 +120.62,50.33616055,-3.304515091,10000,-130.2418527,151.7687989,0,-14.03629709,0,130.63742 +120.63,50.33614886,-3.304493806,10000,-130.2383709,151.7855485,0,-14.03629709,0,130.630394 +120.64,50.33613717,-3.304472518,10000,-130.2348891,151.8020753,0,-14.03629709,0,130.6233681 +120.65,50.33612548,-3.304451228,10000,-130.217481,151.8177107,0,-14.03629709,0,130.6163422 +120.66,50.33611379,-3.304429936,10000,-130.1826651,151.8333462,0,-14.03629709,0,130.6093163 +120.67,50.33610211,-3.304408642,10000,-130.1478492,151.8496501,0,-14.03629709,0,130.6022903 +120.68,50.33609043,-3.304387345,10000,-130.1304411,151.8655084,0,-14.03629709,0,130.5952644 +120.69,50.33607875,-3.304366046,10000,-130.1234777,151.8806982,0,-14.03629709,0,130.5882385 +120.7,50.33606707,-3.304344746,10000,-130.1095512,151.8965565,0,-14.03629709,0,130.5812126 +120.71,50.33605539,-3.304323442,10000,-130.0886615,151.9130832,0,-14.03629709,0,130.5741866 +120.72,50.33604372,-3.304302137,10000,-130.0712535,151.9293872,0,-14.03629709,0,130.5671607 +120.73,50.33603204,-3.304280829,10000,-130.0538454,151.9452455,0,-14.03629709,0,130.5601348 +120.74,50.33602037,-3.304259519,10000,-130.0329557,151.9604353,0,-14.03629709,0,130.5531089 +120.75,50.3360087,-3.304238207,10000,-130.0155476,151.9754023,0,-14.03629709,0,130.5460829 +120.76,50.33599703,-3.304216893,10000,-129.9981395,151.9917062,0,-14.03629709,0,130.5390571 +120.77,50.33598536,-3.304195577,10000,-129.9772499,152.0093472,0,-14.03629709,0,130.5320311 +120.78,50.3359737,-3.304174257,10000,-129.9598418,152.025874,0,-14.03629709,0,130.5250052 +120.79,50.33596203,-3.304152936,10000,-129.9424337,152.0403953,0,-14.03629709,0,130.5179793 +120.8,50.33595037,-3.304131613,10000,-129.9180625,152.0551394,0,-14.03629709,0,130.5109534 +120.81,50.33593871,-3.304110288,10000,-129.8902097,152.0714434,0,-14.03629709,0,130.5039274 +120.82,50.33592705,-3.30408896,10000,-129.8658385,152.0881931,0,-14.03629709,0,130.4969015 +120.83,50.3359154,-3.30406763,10000,-129.851912,152.1047199,0,-14.03629709,0,130.4898756 +120.84,50.33590374,-3.304046298,10000,-129.8484302,152.1212467,0,-14.03629709,0,130.4828497 +120.85,50.33589209,-3.304024963,10000,-129.8414668,152.1368822,0,-14.03629709,0,130.4758237 +120.86,50.33588043,-3.304003626,10000,-129.813614,152.1511807,0,-14.03629709,0,130.4687978 +120.87,50.33586878,-3.303982288,10000,-129.7753165,152.1659248,0,-14.03629709,0,130.4617719 +120.88,50.33585714,-3.303960947,10000,-129.7579085,152.1824517,0,-14.03629709,0,130.454746 +120.89,50.33584549,-3.303939604,10000,-129.7544266,152.1998698,0,-14.03629709,0,130.44772 +120.9,50.33583384,-3.303918258,10000,-129.733537,152.2166195,0,-14.03629709,0,130.4406941 +120.91,50.3358222,-3.30389691,10000,-129.7022027,152.2320321,0,-14.03629709,0,130.4336682 +120.92,50.33581056,-3.30387556,10000,-129.6847946,152.2467763,0,-14.03629709,0,130.4266423 +120.93,50.33579892,-3.303854208,10000,-129.6778312,152.262189,0,-14.03629709,0,130.4196163 +120.94,50.33578728,-3.303832854,10000,-129.6639047,152.2787158,0,-14.03629709,0,130.4125904 +120.95,50.33577564,-3.303811497,10000,-129.643015,152.2952427,0,-14.03629709,0,130.4055645 +120.96,50.33576401,-3.303790138,10000,-129.6256069,152.3108782,0,-14.03629709,0,130.3985386 +120.97,50.33575237,-3.303768777,10000,-129.6081988,152.3265137,0,-14.03629709,0,130.3915127 +120.98,50.33574074,-3.303747414,10000,-129.5873092,152.3430406,0,-14.03629709,0,130.3844867 +120.99,50.33572911,-3.303726048,10000,-129.5699011,152.3595674,0,-14.03629709,0,130.3774608 +121,50.33571748,-3.30370468,10000,-129.5490115,152.3752029,0,-14.03629709,0,130.3704349 +121.01,50.33570585,-3.30368331,10000,-129.5176771,152.3906156,0,-14.03629709,0,130.363409 +121.02,50.33569423,-3.303661938,10000,-129.4967875,152.4062512,0,-14.03629709,0,130.356383 +121.03,50.33568261,-3.303640563,10000,-129.4967872,152.4216639,0,-14.03629709,0,130.3493571 +121.04,50.33567098,-3.303619187,10000,-129.4898238,152.4370766,0,-14.03629709,0,130.3423312 +121.05,50.33565936,-3.303597808,10000,-129.4584895,152.4529349,0,-14.03629709,0,130.3353053 +121.06,50.33564774,-3.303576427,10000,-129.4236736,152.469239,0,-14.03629709,0,130.3282793 +121.07,50.33563613,-3.303555044,10000,-129.4027839,152.4859887,0,-14.03629709,0,130.3212534 +121.08,50.33562451,-3.303533658,10000,-129.3853759,152.5025156,0,-14.03629709,0,130.3142275 +121.09,50.3356129,-3.30351227,10000,-129.3644862,152.5181511,0,-14.03629709,0,130.3072016 +121.1,50.33560129,-3.30349088,10000,-129.3505597,152.5337866,0,-14.03629709,0,130.3001756 +121.11,50.33558968,-3.303469488,10000,-129.3435963,152.5500907,0,-14.03629709,0,130.2931498 +121.12,50.33557807,-3.303448093,10000,-129.3296698,152.5659491,0,-14.03629709,0,130.2861238 +121.13,50.33556646,-3.303426696,10000,-129.3087801,152.581139,0,-14.03629709,0,130.2790979 +121.14,50.33555486,-3.303405298,10000,-129.2913721,152.5967745,0,-14.03629709,0,130.272072 +121.15,50.33554325,-3.303383896,10000,-129.273964,152.6124101,0,-14.03629709,0,130.2650461 +121.16,50.33553165,-3.303362493,10000,-129.2495928,152.6276,0,-14.03629709,0,130.2580201 +121.17,50.33552005,-3.303341088,10000,-129.22174,152.6434584,0,-14.03629709,0,130.2509942 +121.18,50.33550845,-3.30331968,10000,-129.1973688,152.6599853,0,-14.03629709,0,130.2439683 +121.19,50.33549686,-3.30329827,10000,-129.1799607,152.6762893,0,-14.03629709,0,130.2369424 +121.2,50.33548526,-3.303276858,10000,-129.1625526,152.6921477,0,-14.03629709,0,130.2299164 +121.21,50.33547367,-3.303255443,10000,-129.141663,152.7075605,0,-14.03629709,0,130.2228905 +121.22,50.33546208,-3.303234027,10000,-129.1277365,152.7229732,0,-14.03629709,0,130.2158646 +121.23,50.33545049,-3.303212608,10000,-129.1207731,152.7388316,0,-14.03629709,0,130.2088387 +121.24,50.3354389,-3.303191187,10000,-129.1068466,152.7549129,0,-14.03629709,0,130.2018127 +121.25,50.33542731,-3.303169764,10000,-129.0859569,152.7707713,0,-14.03629709,0,130.1947868 +121.26,50.33541573,-3.303148338,10000,-129.0685488,152.786184,0,-14.03629709,0,130.1877609 +121.27,50.33540414,-3.303126911,10000,-129.0511408,152.8018196,0,-14.03629709,0,130.180735 +121.28,50.33539256,-3.303105481,10000,-129.0267696,152.8183466,0,-14.03629709,0,130.173709 +121.29,50.33538098,-3.303084049,10000,-128.9989168,152.8348735,0,-14.03629709,0,130.1666831 +121.3,50.3353694,-3.303062614,10000,-128.9745456,152.8505091,0,-14.03629709,0,130.1596572 +121.31,50.33535783,-3.303041178,10000,-128.9571375,152.8659218,0,-14.03629709,0,130.1526313 +121.32,50.33534625,-3.303019739,10000,-128.9397294,152.8817803,0,-14.03629709,0,130.1456053 +121.33,50.33533468,-3.302998298,10000,-128.9188398,152.8978615,0,-14.03629709,0,130.1385794 +121.34,50.33532311,-3.302976855,10000,-128.9049133,152.91372,0,-14.03629709,0,130.1315535 +121.35,50.33531154,-3.302955409,10000,-128.8979499,152.9291327,0,-14.03629709,0,130.1245276 +121.36,50.33529997,-3.302933962,10000,-128.8840234,152.9447683,0,-14.03629709,0,130.1175017 +121.37,50.3352884,-3.302912512,10000,-128.8631337,152.9612953,0,-14.03629709,0,130.1104757 +121.38,50.33527684,-3.30289106,10000,-128.8457256,152.9778222,0,-14.03629709,0,130.1034498 +121.39,50.33526527,-3.302869605,10000,-128.8283176,152.993235,0,-14.03629709,0,130.0964239 +121.4,50.33525371,-3.302848149,10000,-128.8039464,153.0077565,0,-14.03629709,0,130.089398 +121.41,50.33524215,-3.30282669,10000,-128.7760936,153.0225007,0,-14.03629709,0,130.082372 +121.42,50.33523059,-3.30280523,10000,-128.7517224,153.038582,0,-14.03629709,0,130.0753462 +121.43,50.33521904,-3.302783767,10000,-128.7343143,153.0555546,0,-14.03629709,0,130.0683202 +121.44,50.33520748,-3.302762301,10000,-128.7169062,153.0718588,0,-14.03629709,0,130.0612943 +121.45,50.33519593,-3.302740834,10000,-128.6960166,153.0874944,0,-14.03629709,0,130.0542684 +121.46,50.33518438,-3.302719364,10000,-128.6786085,153.10313,0,-14.03629709,0,130.0472425 +121.47,50.33517283,-3.302697892,10000,-128.6612005,153.1185428,0,-14.03629709,0,130.0402165 +121.48,50.33516128,-3.302676418,10000,-128.6403108,153.1341784,0,-14.03629709,0,130.0331906 +121.49,50.33514974,-3.302654942,10000,-128.6229027,153.1507054,0,-14.03629709,0,130.0261647 +121.5,50.33513819,-3.302633463,10000,-128.6054946,153.1670096,0,-14.03629709,0,130.0191388 +121.51,50.33512665,-3.302611982,10000,-128.584605,153.1817539,0,-14.03629709,0,130.0121128 +121.52,50.33511511,-3.302590499,10000,-128.5706785,153.1960525,0,-14.03629709,0,130.0050869 +121.53,50.33510357,-3.302569015,10000,-128.5637151,153.2116881,0,-14.03629709,0,129.998061 +121.54,50.33509203,-3.302547527,10000,-128.546307,153.2282151,0,-14.03629709,0,129.9910351 +121.55,50.33508049,-3.302526038,10000,-128.5114911,153.2445193,0,-14.03629709,0,129.9840091 +121.56,50.33506896,-3.302504546,10000,-128.4766753,153.2606006,0,-14.03629709,0,129.9769832 +121.57,50.33505743,-3.302483052,10000,-128.4592672,153.2766819,0,-14.03629709,0,129.9699573 +121.58,50.3350459,-3.302461556,10000,-128.4557853,153.2925404,0,-14.03629709,0,129.9629314 +121.59,50.33503437,-3.302440057,10000,-128.4523035,153.3079532,0,-14.03629709,0,129.9559054 +121.6,50.33502284,-3.302418557,10000,-128.4348955,153.3235889,0,-14.03629709,0,129.9488795 +121.61,50.33501131,-3.302397054,10000,-128.4035611,153.339893,0,-14.03629709,0,129.9418536 +121.62,50.33499979,-3.302375549,10000,-128.3826715,153.3555287,0,-14.03629709,0,129.9348277 +121.63,50.33498827,-3.302354041,10000,-128.3791897,153.3700502,0,-14.03629709,0,129.9278017 +121.64,50.33497674,-3.302332533,10000,-128.3617816,153.385463,0,-14.03629709,0,129.9207758 +121.65,50.33496522,-3.302311021,10000,-128.3234841,153.4022129,0,-14.03629709,0,129.9137499 +121.66,50.33495371,-3.302289507,10000,-128.2956314,153.4185171,0,-14.03629709,0,129.906724 +121.67,50.33494219,-3.302267991,10000,-128.288668,153.4341527,0,-14.03629709,0,129.899698 +121.68,50.33493068,-3.302246473,10000,-128.2817046,153.4497884,0,-14.03629709,0,129.8926721 +121.69,50.33491916,-3.302224952,10000,-128.2538518,153.4652012,0,-14.03629709,0,129.8856462 +121.7,50.33490765,-3.30220343,10000,-128.2155544,153.4806141,0,-14.03629709,0,129.8786203 +121.71,50.33489615,-3.302181905,10000,-128.1981463,153.4962498,0,-14.03629709,0,129.8715943 +121.72,50.33488464,-3.302160378,10000,-128.1946645,153.5116626,0,-14.03629709,0,129.8645684 +121.73,50.33487313,-3.302138849,10000,-128.1772564,153.5272983,0,-14.03629709,0,129.8575425 +121.74,50.33486163,-3.302117318,10000,-128.1563668,153.5438253,0,-14.03629709,0,129.8505166 +121.75,50.33485013,-3.302095784,10000,-128.1424403,153.5603524,0,-14.03629709,0,129.8434907 +121.76,50.33483862,-3.302074248,10000,-128.1215506,153.575988,0,-14.03629709,0,129.8364647 +121.77,50.33482713,-3.30205271,10000,-128.100661,153.5914009,0,-14.03629709,0,129.8294389 +121.78,50.33481563,-3.30203117,10000,-128.0867345,153.6070366,0,-14.03629709,0,129.8224129 +121.79,50.33480413,-3.302009627,10000,-128.0623633,153.6224495,0,-14.03629709,0,129.815387 +121.8,50.33479264,-3.301988083,10000,-128.031029,153.6378623,0,-14.03629709,0,129.8083611 +121.81,50.33478115,-3.301966536,10000,-128.0136209,153.653498,0,-14.03629709,0,129.8013352 +121.82,50.33476966,-3.301944987,10000,-128.010139,153.6689109,0,-14.03629709,0,129.7943092 +121.83,50.33475817,-3.301923436,10000,-128.0066572,153.6845466,0,-14.03629709,0,129.7872833 +121.84,50.33474668,-3.301901883,10000,-127.9892492,153.7010737,0,-14.03629709,0,129.7802574 +121.85,50.33473519,-3.301880327,10000,-127.9544333,153.7176007,0,-14.03629709,0,129.7732315 +121.86,50.33472371,-3.301858769,10000,-127.9196174,153.7330136,0,-14.03629709,0,129.7662055 +121.87,50.33471223,-3.301837209,10000,-127.9022093,153.7477579,0,-14.03629709,0,129.7591796 +121.88,50.33470075,-3.301815647,10000,-127.8952459,153.762948,0,-14.03629709,0,129.7521537 +121.89,50.33468927,-3.301794083,10000,-127.8813194,153.7785837,0,-14.03629709,0,129.7451278 +121.9,50.33467779,-3.301772516,10000,-127.8604298,153.7939966,0,-14.03629709,0,129.7381018 +121.91,50.33466632,-3.301750948,10000,-127.8430217,153.8096323,0,-14.03629709,0,129.7310759 +121.92,50.33465484,-3.301729377,10000,-127.8256136,153.8261594,0,-14.03629709,0,129.72405 +121.93,50.33464337,-3.301707804,10000,-127.8012424,153.8426865,0,-14.03629709,0,129.7170241 +121.94,50.3346319,-3.301686228,10000,-127.7733897,153.8583222,0,-14.03629709,0,129.7099981 +121.95,50.33462043,-3.301664651,10000,-127.7490185,153.8737351,0,-14.03629709,0,129.7029722 +121.96,50.33460897,-3.301643071,10000,-127.7316104,153.8893708,0,-14.03629709,0,129.6959463 +121.97,50.3345975,-3.301621489,10000,-127.7142023,153.9045609,0,-14.03629709,0,129.6889204 +121.98,50.33458604,-3.301599905,10000,-127.6933127,153.9193053,0,-14.03629709,0,129.6818944 +121.99,50.33457458,-3.301578319,10000,-127.6793862,153.9347181,0,-14.03629709,0,129.6748685 +122,50.33456312,-3.301556731,10000,-127.6724228,153.9512452,0,-14.03629709,0,129.6678426 +122.01,50.33455166,-3.30153514,10000,-127.6584963,153.9677723,0,-14.03629709,0,129.6608167 +122.02,50.3345402,-3.301513547,10000,-127.6376067,153.9831853,0,-14.03629709,0,129.6537907 +122.03,50.33452875,-3.301491952,10000,-127.6201986,153.9979296,0,-14.03629709,0,129.6467648 +122.04,50.33451729,-3.301470355,10000,-127.6027905,154.0133426,0,-14.03629709,0,129.6397389 +122.05,50.33450584,-3.301448756,10000,-127.5784193,154.0298697,0,-14.03629709,0,129.632713 +122.06,50.33449439,-3.301427154,10000,-127.5505666,154.0463968,0,-14.03629709,0,129.625687 +122.07,50.33448294,-3.30140555,10000,-127.5261954,154.0620325,0,-14.03629709,0,129.6186611 +122.08,50.3344715,-3.301383944,10000,-127.5087873,154.0774454,0,-14.03629709,0,129.6116352 +122.09,50.33446005,-3.301362336,10000,-127.4913792,154.0930812,0,-14.03629709,0,129.6046093 +122.1,50.33444861,-3.301340725,10000,-127.4704896,154.1082713,0,-14.03629709,0,129.5975833 +122.11,50.33443717,-3.301319113,10000,-127.4565631,154.1230157,0,-14.03629709,0,129.5905575 +122.12,50.33442573,-3.301297498,10000,-127.4495997,154.1384286,0,-14.03629709,0,129.5835315 +122.13,50.33441429,-3.301275882,10000,-127.4321916,154.1547329,0,-14.03629709,0,129.5765056 +122.14,50.33440285,-3.301254262,10000,-127.4008573,154.1705915,0,-14.03629709,0,129.5694797 +122.15,50.33439142,-3.301232641,10000,-127.3799677,154.1857816,0,-14.03629709,0,129.5624538 +122.16,50.33437999,-3.301211018,10000,-127.3764859,154.2016402,0,-14.03629709,0,129.5554279 +122.17,50.33436855,-3.301189392,10000,-127.3590778,154.2179445,0,-14.03629709,0,129.5484019 +122.18,50.33435712,-3.301167764,10000,-127.3207803,154.2335803,0,-14.03629709,0,129.541376 +122.19,50.3343457,-3.301146134,10000,-127.2929276,154.2489932,0,-14.03629709,0,129.5343501 +122.2,50.33433427,-3.301124502,10000,-127.2859642,154.264629,0,-14.03629709,0,129.5273242 +122.21,50.33432285,-3.301102867,10000,-127.2824824,154.2800419,0,-14.03629709,0,129.5202982 +122.22,50.33431142,-3.301081231,10000,-127.2650743,154.2954549,0,-14.03629709,0,129.5132723 +122.23,50.3343,-3.301059592,10000,-127.2302584,154.3110907,0,-14.03629709,0,129.5062464 +122.24,50.33428858,-3.301037951,10000,-127.1954426,154.3262808,0,-14.03629709,0,129.4992205 +122.25,50.33427717,-3.301016308,10000,-127.1780345,154.3410252,0,-14.03629709,0,129.4921945 +122.26,50.33426575,-3.300994663,10000,-127.1745527,154.3564382,0,-14.03629709,0,129.4851686 +122.27,50.33425434,-3.300973016,10000,-127.1710708,154.3729653,0,-14.03629709,0,129.4781427 +122.28,50.33424292,-3.300951366,10000,-127.1536628,154.3894925,0,-14.03629709,0,129.4711168 +122.29,50.33423151,-3.300929714,10000,-127.1188469,154.4051283,0,-14.03629709,0,129.4640908 +122.3,50.3342201,-3.30090806,10000,-127.084031,154.4205412,0,-14.03629709,0,129.4570649 +122.31,50.3342087,-3.300886404,10000,-127.0666229,154.436177,0,-14.03629709,0,129.450039 +122.32,50.33419729,-3.300864745,10000,-127.0631411,154.45159,0,-14.03629709,0,129.4430131 +122.33,50.33418589,-3.300843085,10000,-127.0596593,154.467003,0,-14.03629709,0,129.4359871 +122.34,50.33417448,-3.300821422,10000,-127.0422512,154.4826388,0,-14.03629709,0,129.4289612 +122.35,50.33416308,-3.300799757,10000,-127.0074354,154.4980517,0,-14.03629709,0,129.4219353 +122.36,50.33415168,-3.30077809,10000,-126.9726195,154.5136876,0,-14.03629709,0,129.4149094 +122.37,50.33414029,-3.300756421,10000,-126.9552114,154.5299919,0,-14.03629709,0,129.4078834 +122.38,50.33412889,-3.300734749,10000,-126.9517296,154.5456277,0,-14.03629709,0,129.4008575 +122.39,50.3341175,-3.300713075,10000,-126.9447662,154.5599265,0,-14.03629709,0,129.3938316 +122.4,50.3341061,-3.3006914,10000,-126.9169135,154.5746709,0,-14.03629709,0,129.3868057 +122.41,50.33409471,-3.300669722,10000,-126.878616,154.5909753,0,-14.03629709,0,129.3797797 +122.42,50.33408333,-3.300648042,10000,-126.861208,154.6075025,0,-14.03629709,0,129.3727538 +122.43,50.33407194,-3.300626359,10000,-126.8577261,154.6231383,0,-14.03629709,0,129.3657279 +122.44,50.33406055,-3.300604675,10000,-126.8368365,154.6385513,0,-14.03629709,0,129.358702 +122.45,50.33404917,-3.300582988,10000,-126.8055022,154.6541871,0,-14.03629709,0,129.351676 +122.46,50.33403779,-3.300561299,10000,-126.7880941,154.6693772,0,-14.03629709,0,129.3446502 +122.47,50.33402641,-3.300539608,10000,-126.7811307,154.6841217,0,-14.03629709,0,129.3376242 +122.48,50.33401503,-3.300517915,10000,-126.7672042,154.6995347,0,-14.03629709,0,129.3305983 +122.49,50.33400365,-3.30049622,10000,-126.7463146,154.7158391,0,-14.03629709,0,129.3235724 +122.5,50.33399228,-3.300474522,10000,-126.7289066,154.7316977,0,-14.03629709,0,129.3165465 +122.51,50.3339809,-3.300452822,10000,-126.7114985,154.7468879,0,-14.03629709,0,129.3095205 +122.52,50.33396953,-3.300431121,10000,-126.6871273,154.7625238,0,-14.03629709,0,129.3024946 +122.53,50.33395816,-3.300409416,10000,-126.6592745,154.7781596,0,-14.03629709,0,129.2954687 +122.54,50.33394679,-3.30038771,10000,-126.6349034,154.7933498,0,-14.03629709,0,129.2884428 +122.55,50.33393543,-3.300366002,10000,-126.6174953,154.8092084,0,-14.03629709,0,129.2814169 +122.56,50.33392406,-3.300344291,10000,-126.6000872,154.8255128,0,-14.03629709,0,129.2743909 +122.57,50.3339127,-3.300322578,10000,-126.5791976,154.8409258,0,-14.03629709,0,129.267365 +122.58,50.33390134,-3.300300863,10000,-126.5652711,154.8556703,0,-14.03629709,0,129.2603391 +122.59,50.33388998,-3.300279146,10000,-126.5583077,154.8708605,0,-14.03629709,0,129.2533132 +122.6,50.33387862,-3.300257427,10000,-126.5443812,154.8864963,0,-14.03629709,0,129.2462872 +122.61,50.33386726,-3.300235705,10000,-126.5234916,154.9019094,0,-14.03629709,0,129.2392613 +122.62,50.33385591,-3.300213982,10000,-126.5060835,154.9173224,0,-14.03629709,0,129.2322354 +122.63,50.33384455,-3.300192256,10000,-126.4851939,154.9329582,0,-14.03629709,0,129.2252095 +122.64,50.3338332,-3.300170528,10000,-126.450378,154.9483713,0,-14.03629709,0,129.2181835 +122.65,50.33382185,-3.300148798,10000,-126.4155621,154.9640071,0,-14.03629709,0,129.2111576 +122.66,50.33381051,-3.300127066,10000,-126.3981541,154.9803115,0,-14.03629709,0,129.2041317 +122.67,50.33379916,-3.300105331,10000,-126.3946723,154.9959474,0,-14.03629709,0,129.1971058 +122.68,50.33378782,-3.300083594,10000,-126.3911904,155.0102462,0,-14.03629709,0,129.1900798 +122.69,50.33377647,-3.300061856,10000,-126.3772639,155.0249907,0,-14.03629709,0,129.1830539 +122.7,50.33376513,-3.300040115,10000,-126.3528927,155.041518,0,-14.03629709,0,129.176028 +122.71,50.33375379,-3.300018372,10000,-126.32504,155.0587137,0,-14.03629709,0,129.1690021 +122.72,50.33374245,-3.299996626,10000,-126.3006688,155.0745725,0,-14.03629709,0,129.1619761 +122.73,50.33373112,-3.299974878,10000,-126.2832607,155.0888713,0,-14.03629709,0,129.1549502 +122.74,50.33371978,-3.299953129,10000,-126.2658527,155.103393,0,-14.03629709,0,129.1479243 +122.75,50.33370845,-3.299931377,10000,-126.2449631,155.118806,0,-14.03629709,0,129.1408984 +122.76,50.33369712,-3.299909623,10000,-126.227555,155.134219,0,-14.03629709,0,129.1338724 +122.77,50.33368579,-3.299887867,10000,-126.2066654,155.1496321,0,-14.03629709,0,129.1268465 +122.78,50.33367446,-3.299866109,10000,-126.175331,155.165268,0,-14.03629709,0,129.1198206 +122.79,50.33366314,-3.299844348,10000,-126.1544414,155.180681,0,-14.03629709,0,129.1127947 +122.8,50.33365182,-3.299822586,10000,-126.1544412,155.1963169,0,-14.03629709,0,129.1057687 +122.81,50.33364049,-3.299800821,10000,-126.1474778,155.2128442,0,-14.03629709,0,129.0987429 +122.82,50.33362917,-3.299779054,10000,-126.1161435,155.2291486,0,-14.03629709,0,129.0917169 +122.83,50.33361785,-3.299757284,10000,-126.0813276,155.2438931,0,-14.03629709,0,129.084691 +122.84,50.33360654,-3.299735513,10000,-126.060438,155.258192,0,-14.03629709,0,129.0776651 +122.85,50.33359522,-3.29971374,10000,-126.0430299,155.2738279,0,-14.03629709,0,129.0706392 +122.86,50.33358391,-3.299691964,10000,-126.0221403,155.2901323,0,-14.03629709,0,129.0636132 +122.87,50.3335726,-3.299670186,10000,-126.0082138,155.3055454,0,-14.03629709,0,129.0565873 +122.88,50.33356129,-3.299648406,10000,-126.004732,155.3200671,0,-14.03629709,0,129.0495614 +122.89,50.33354998,-3.299626624,10000,-126.0012502,155.3345888,0,-14.03629709,0,129.0425355 +122.9,50.33353867,-3.29960484,10000,-125.9838421,155.349779,0,-14.03629709,0,129.0355095 +122.91,50.33352736,-3.299583054,10000,-125.9490262,155.3654149,0,-14.03629709,0,129.0284836 +122.92,50.33351606,-3.299561265,10000,-125.9142104,155.3810508,0,-14.03629709,0,129.0214577 +122.93,50.33350476,-3.299539475,10000,-125.8968023,155.3973553,0,-14.03629709,0,129.0144318 +122.94,50.33349346,-3.299517682,10000,-125.8898389,155.4141054,0,-14.03629709,0,129.0074059 +122.95,50.33348216,-3.299495886,10000,-125.8724309,155.4295185,0,-14.03629709,0,129.0003799 +122.96,50.33347086,-3.299474089,10000,-125.8410966,155.4440402,0,-14.03629709,0,128.993354 +122.97,50.33345957,-3.29945229,10000,-125.8167254,155.4594533,0,-14.03629709,0,128.9863281 +122.98,50.33344828,-3.299430488,10000,-125.8027989,155.4748663,0,-14.03629709,0,128.9793022 +122.99,50.33343698,-3.299408684,10000,-125.7819093,155.4891652,0,-14.03629709,0,128.9722762 +123,50.3334257,-3.299386879,10000,-125.7610196,155.5039098,0,-14.03629709,0,128.9652503 +123.01,50.33341441,-3.299365071,10000,-125.7505747,155.5202142,0,-14.03629709,0,128.9582244 +123.02,50.33340312,-3.299343261,10000,-125.7401298,155.5367415,0,-14.03629709,0,128.9511985 +123.03,50.33339184,-3.299321448,10000,-125.7262033,155.5521546,0,-14.03629709,0,128.9441725 +123.04,50.33338055,-3.299299634,10000,-125.7087952,155.5668992,0,-14.03629709,0,128.9371466 +123.05,50.33336927,-3.299277817,10000,-125.684424,155.5823123,0,-14.03629709,0,128.9301207 +123.06,50.33335799,-3.299255999,10000,-125.6565713,155.5986168,0,-14.03629709,0,128.9230948 +123.07,50.33334671,-3.299234177,10000,-125.6322001,155.6142527,0,-14.03629709,0,128.9160688 +123.08,50.33333544,-3.299212354,10000,-125.614792,155.6285516,0,-14.03629709,0,128.9090429 +123.09,50.33332416,-3.299190529,10000,-125.597384,155.6432961,0,-14.03629709,0,128.902017 +123.1,50.33331289,-3.299168702,10000,-125.5764943,155.6596006,0,-14.03629709,0,128.8949911 +123.11,50.33330162,-3.299146872,10000,-125.5590863,155.6761279,0,-14.03629709,0,128.8879651 +123.12,50.33329035,-3.29912504,10000,-125.5416782,155.6915411,0,-14.03629709,0,128.8809393 +123.13,50.33327908,-3.299103206,10000,-125.5207886,155.7060628,0,-14.03629709,0,128.8739133 +123.14,50.33326782,-3.29908137,10000,-125.5033805,155.7205845,0,-14.03629709,0,128.8668874 +123.15,50.33325655,-3.299059532,10000,-125.4859725,155.7359976,0,-14.03629709,0,128.8598615 +123.16,50.33324529,-3.299037692,10000,-125.4616013,155.7523021,0,-14.03629709,0,128.8528356 +123.17,50.33323403,-3.299015849,10000,-125.4337486,155.7679381,0,-14.03629709,0,128.8458096 +123.18,50.33322277,-3.298994004,10000,-125.4093774,155.7824598,0,-14.03629709,0,128.8387837 +123.19,50.33321152,-3.298972158,10000,-125.3954509,155.7978729,0,-14.03629709,0,128.8317578 +123.2,50.33320026,-3.298950309,10000,-125.3919691,155.8144003,0,-14.03629709,0,128.8247319 +123.21,50.33318901,-3.298928457,10000,-125.3884873,155.8295905,0,-14.03629709,0,128.8177059 +123.22,50.33317775,-3.298906604,10000,-125.3710792,155.8432209,0,-14.03629709,0,128.81068 +123.23,50.3331665,-3.298884749,10000,-125.3362633,155.8577426,0,-14.03629709,0,128.8036541 +123.24,50.33315525,-3.298862892,10000,-125.3014475,155.8740472,0,-14.03629709,0,128.7966282 +123.25,50.33314401,-3.298841032,10000,-125.2805578,155.8905745,0,-14.03629709,0,128.7896022 +123.26,50.33313276,-3.29881917,10000,-125.2631498,155.9062105,0,-14.03629709,0,128.7825763 +123.27,50.33312152,-3.298797306,10000,-125.2422602,155.9216236,0,-14.03629709,0,128.7755504 +123.28,50.33311028,-3.29877544,10000,-125.2283337,155.9372596,0,-14.03629709,0,128.7685245 +123.29,50.33309904,-3.298753571,10000,-125.2213703,155.9524499,0,-14.03629709,0,128.7614985 +123.3,50.3330878,-3.298731701,10000,-125.2074438,155.9669716,0,-14.03629709,0,128.7544726 +123.31,50.33307656,-3.298709828,10000,-125.1865542,155.9814934,0,-14.03629709,0,128.7474467 +123.32,50.33306533,-3.298687954,10000,-125.1691461,155.9969065,0,-14.03629709,0,128.7404208 +123.33,50.33305409,-3.298666077,10000,-125.1517381,156.0134339,0,-14.03629709,0,128.7333948 +123.34,50.33304286,-3.298644198,10000,-125.1273669,156.0297384,0,-14.03629709,0,128.7263689 +123.35,50.33303163,-3.298622316,10000,-125.0995142,156.044483,0,-14.03629709,0,128.719343 +123.36,50.3330204,-3.298600433,10000,-125.075143,156.0587819,0,-14.03629709,0,128.7123171 +123.37,50.33300918,-3.298578548,10000,-125.0577349,156.0741951,0,-14.03629709,0,128.7052912 +123.38,50.33299795,-3.29855666,10000,-125.0403268,156.0896082,0,-14.03629709,0,128.6982652 +123.39,50.33298673,-3.29853477,10000,-125.0194372,156.10413,0,-14.03629709,0,128.6912393 +123.4,50.33297551,-3.298512879,10000,-125.0020292,156.1195431,0,-14.03629709,0,128.6842134 +123.41,50.33296429,-3.298490985,10000,-124.9846211,156.1362934,0,-14.03629709,0,128.6771875 +123.42,50.33295307,-3.298469088,10000,-124.9637315,156.1523751,0,-14.03629709,0,128.6701615 +123.43,50.33294186,-3.29844719,10000,-124.9463234,156.1671197,0,-14.03629709,0,128.6631356 +123.44,50.33293064,-3.298425289,10000,-124.9289154,156.1816414,0,-14.03629709,0,128.6561097 +123.45,50.33291943,-3.298403387,10000,-124.9080258,156.1968318,0,-14.03629709,0,128.6490838 +123.46,50.33290822,-3.298381482,10000,-124.8906177,156.2124678,0,-14.03629709,0,128.6420578 +123.47,50.33289701,-3.298359575,10000,-124.8732097,156.2278809,0,-14.03629709,0,128.635032 +123.48,50.3328858,-3.298337666,10000,-124.8523201,156.2432941,0,-14.03629709,0,128.628006 +123.49,50.3328746,-3.298315755,10000,-124.834912,156.2589301,0,-14.03629709,0,128.6209801 +123.5,50.33286339,-3.298293841,10000,-124.8175039,156.2741204,0,-14.03629709,0,128.6139542 +123.51,50.33285219,-3.298271926,10000,-124.7966143,156.2886422,0,-14.03629709,0,128.6069283 +123.52,50.33284099,-3.298250008,10000,-124.7792062,156.303164,0,-14.03629709,0,128.5999023 +123.53,50.33282979,-3.298228089,10000,-124.7617982,156.3183543,0,-14.03629709,0,128.5928764 +123.54,50.33281859,-3.298206167,10000,-124.7409086,156.3342132,0,-14.03629709,0,128.5858505 +123.55,50.3328074,-3.298184243,10000,-124.7235005,156.3502949,0,-14.03629709,0,128.5788246 +123.56,50.3327962,-3.298162317,10000,-124.7060925,156.3661538,0,-14.03629709,0,128.5717986 +123.57,50.33278501,-3.298140388,10000,-124.6817213,156.3815669,0,-14.03629709,0,128.5647727 +123.58,50.33277382,-3.298118458,10000,-124.6538686,156.3967573,0,-14.03629709,0,128.5577468 +123.59,50.33276263,-3.298096525,10000,-124.6294974,156.4115019,0,-14.03629709,0,128.5507209 +123.6,50.33275145,-3.29807459,10000,-124.6120893,156.4258009,0,-14.03629709,0,128.5436949 +123.61,50.33274026,-3.298052654,10000,-124.5946813,156.441214,0,-14.03629709,0,128.536669 +123.62,50.33272908,-3.298030715,10000,-124.5737917,156.4577415,0,-14.03629709,0,128.5296431 +123.63,50.3327179,-3.298008773,10000,-124.5598652,156.4731546,0,-14.03629709,0,128.5226172 +123.64,50.33270672,-3.29798683,10000,-124.5529018,156.4876764,0,-14.03629709,0,128.5155912 +123.65,50.33269554,-3.297964885,10000,-124.5354937,156.5030896,0,-14.03629709,0,128.5085653 +123.66,50.33268436,-3.297942937,10000,-124.5041594,156.5185028,0,-14.03629709,0,128.5015394 +123.67,50.33267319,-3.297920987,10000,-124.4832698,156.5330246,0,-14.03629709,0,128.4945135 +123.68,50.33266202,-3.297899036,10000,-124.479788,156.5484378,0,-14.03629709,0,128.4874875 +123.69,50.33265084,-3.297877082,10000,-124.46238,156.5649653,0,-14.03629709,0,128.4804616 +123.7,50.33263967,-3.297855125,10000,-124.4240825,156.5803785,0,-14.03629709,0,128.4734357 +123.71,50.33262851,-3.297833167,10000,-124.3962298,156.5946774,0,-14.03629709,0,128.4664098 +123.72,50.33261734,-3.297811207,10000,-124.3892664,156.6094221,0,-14.03629709,0,128.4593838 +123.73,50.33260618,-3.297789244,10000,-124.3857846,156.6246124,0,-14.03629709,0,128.4523579 +123.74,50.33259501,-3.29776728,10000,-124.3683766,156.6400256,0,-14.03629709,0,128.445332 +123.75,50.33258385,-3.297745313,10000,-124.3335607,156.6556617,0,-14.03629709,0,128.4383061 +123.76,50.33257269,-3.297723344,10000,-124.2987448,156.6710749,0,-14.03629709,0,128.4312802 +123.77,50.33256154,-3.297701373,10000,-124.2813368,156.6864881,0,-14.03629709,0,128.4242542 +123.78,50.33255038,-3.2976794,10000,-124.277855,156.7019013,0,-14.03629709,0,128.4172284 +123.79,50.33253923,-3.297657424,10000,-124.2743732,156.7164231,0,-14.03629709,0,128.4102024 +123.8,50.33252807,-3.297635447,10000,-124.2569651,156.7307221,0,-14.03629709,0,128.4031765 +123.81,50.33251692,-3.297613468,10000,-124.2221493,156.7463582,0,-14.03629709,0,128.3961506 +123.82,50.33250577,-3.297591486,10000,-124.1873334,156.7626628,0,-14.03629709,0,128.3891247 +123.83,50.33249463,-3.297569502,10000,-124.1664438,156.778076,0,-14.03629709,0,128.3820987 +123.84,50.33248348,-3.297547516,10000,-124.1490357,156.7928207,0,-14.03629709,0,128.3750728 +123.85,50.33247234,-3.297525528,10000,-124.1281461,156.808011,0,-14.03629709,0,128.3680469 +123.86,50.3324612,-3.297503538,10000,-124.1142196,156.8236471,0,-14.03629709,0,128.361021 +123.87,50.33245006,-3.297481545,10000,-124.1072563,156.8388375,0,-14.03629709,0,128.353995 +123.88,50.33243892,-3.297459551,10000,-124.0933298,156.8533593,0,-14.03629709,0,128.3469691 +123.89,50.33242778,-3.297437554,10000,-124.0724402,156.8678811,0,-14.03629709,0,128.3399432 +123.9,50.33241665,-3.297415556,10000,-124.0550322,156.8830715,0,-14.03629709,0,128.3329173 +123.91,50.33240551,-3.297393555,10000,-124.0376241,156.8989304,0,-14.03629709,0,128.3258913 +123.92,50.33239438,-3.297371552,10000,-124.0132529,156.9150122,0,-14.03629709,0,128.3188654 +123.93,50.33238325,-3.297349547,10000,-123.9854002,156.9306483,0,-14.03629709,0,128.3118395 +123.94,50.33237212,-3.297327539,10000,-123.961029,156.9451701,0,-14.03629709,0,128.3048136 +123.95,50.332361,-3.29730553,10000,-123.9436209,156.9592463,0,-14.03629709,0,128.2977876 +123.96,50.33234987,-3.297283519,10000,-123.9262129,156.9742138,0,-14.03629709,0,128.2907617 +123.97,50.33233875,-3.297261505,10000,-123.9053233,156.9902956,0,-14.03629709,0,128.2837358 +123.98,50.33232763,-3.29723949,10000,-123.8913968,157.0068231,0,-14.03629709,0,128.2767099 +123.99,50.33231651,-3.297217471,10000,-123.8844334,157.0224592,0,-14.03629709,0,128.2696839 +124,50.33230539,-3.297195451,10000,-123.8670254,157.0365353,0,-14.03629709,0,128.262658 +124.01,50.33229427,-3.297173429,10000,-123.8322095,157.0503886,0,-14.03629709,0,128.2556321 +124.02,50.33228316,-3.297151405,10000,-123.7973937,157.0653562,0,-14.03629709,0,128.2486062 +124.03,50.33227205,-3.297129379,10000,-123.7799856,157.0809922,0,-14.03629709,0,128.2415802 +124.04,50.33226094,-3.29710735,10000,-123.7765038,157.0964055,0,-14.03629709,0,128.2345543 +124.05,50.33224983,-3.29708532,10000,-123.773022,157.1118187,0,-14.03629709,0,128.2275284 +124.06,50.33223872,-3.297063287,10000,-123.755614,157.1274548,0,-14.03629709,0,128.2205025 +124.07,50.33222761,-3.297041252,10000,-123.7207981,157.1426452,0,-14.03629709,0,128.2134765 +124.08,50.33221651,-3.297019215,10000,-123.6859822,157.1573899,0,-14.03629709,0,128.2064506 +124.09,50.33220541,-3.296997176,10000,-123.6685742,157.1725803,0,-14.03629709,0,128.1994247 +124.1,50.33219431,-3.296975135,10000,-123.6616108,157.1882165,0,-14.03629709,0,128.1923988 +124.11,50.33218321,-3.296953091,10000,-123.6476843,157.2034069,0,-14.03629709,0,128.1853728 +124.12,50.33217211,-3.296931046,10000,-123.6267947,157.2179287,0,-14.03629709,0,128.1783469 +124.13,50.33216102,-3.296908998,10000,-123.6093867,157.2324506,0,-14.03629709,0,128.171321 +124.14,50.33214992,-3.296886949,10000,-123.5919787,157.247641,0,-14.03629709,0,128.1642951 +124.15,50.33213883,-3.296864897,10000,-123.5676075,157.2632771,0,-14.03629709,0,128.1572692 +124.16,50.33212774,-3.296842843,10000,-123.5397547,157.2786904,0,-14.03629709,0,128.1502433 +124.17,50.33211665,-3.296820787,10000,-123.5153835,157.2941036,0,-14.03629709,0,128.1432174 +124.18,50.33210557,-3.296798729,10000,-123.4979755,157.3097397,0,-14.03629709,0,128.1361914 +124.19,50.33209448,-3.296776668,10000,-123.4805675,157.3249302,0,-14.03629709,0,128.1291655 +124.2,50.3320834,-3.296754606,10000,-123.4596779,157.339452,0,-14.03629709,0,128.1221396 +124.21,50.33207232,-3.296732541,10000,-123.4457514,157.3539739,0,-14.03629709,0,128.1151137 +124.22,50.33206124,-3.296710475,10000,-123.438788,157.3691643,0,-14.03629709,0,128.1080877 +124.23,50.33205016,-3.296688406,10000,-123.42138,157.3848004,0,-14.03629709,0,128.1010618 +124.24,50.33203908,-3.296666335,10000,-123.3900457,157.3999909,0,-14.03629709,0,128.0940359 +124.25,50.33202801,-3.296644262,10000,-123.3691561,157.4147356,0,-14.03629709,0,128.08701 +124.26,50.33201694,-3.296622187,10000,-123.3656743,157.429926,0,-14.03629709,0,128.079984 +124.27,50.33200586,-3.29660011,10000,-123.3482662,157.4455622,0,-14.03629709,0,128.0729581 +124.28,50.33199479,-3.29657803,10000,-123.3099688,157.4609754,0,-14.03629709,0,128.0659322 +124.29,50.33198373,-3.296555949,10000,-123.2821161,157.4761659,0,-14.03629709,0,128.0589063 +124.3,50.33197266,-3.296533865,10000,-123.2751527,157.4909106,0,-14.03629709,0,128.0518803 +124.31,50.3319616,-3.296511779,10000,-123.2681893,157.5049868,0,-14.03629709,0,128.0448544 +124.32,50.33195053,-3.296489692,10000,-123.2403366,157.5197315,0,-14.03629709,0,128.0378285 +124.33,50.33193947,-3.296467602,10000,-123.2020392,157.5360362,0,-14.03629709,0,128.0308026 +124.34,50.33192842,-3.29644551,10000,-123.1846311,157.5523409,0,-14.03629709,0,128.0237766 +124.35,50.33191736,-3.296423415,10000,-123.1811493,157.5670856,0,-14.03629709,0,128.0167507 +124.36,50.3319063,-3.296401319,10000,-123.1602597,157.5811618,0,-14.03629709,0,128.0097248 +124.37,50.33189525,-3.296379221,10000,-123.1289254,157.5959065,0,-14.03629709,0,128.0026989 +124.38,50.3318842,-3.29635712,10000,-123.1115174,157.611097,0,-14.03629709,0,127.9956729 +124.39,50.33187315,-3.296335018,10000,-123.1045541,157.6265103,0,-14.03629709,0,127.988647 +124.4,50.3318621,-3.296312913,10000,-123.0906276,157.6421464,0,-14.03629709,0,127.9816211 +124.41,50.33185105,-3.296290806,10000,-123.069738,157.6573369,0,-14.03629709,0,127.9745952 +124.42,50.33184001,-3.296268697,10000,-123.0523299,157.6718588,0,-14.03629709,0,127.9675692 +124.43,50.33182896,-3.296246586,10000,-123.0349219,157.6861578,0,-14.03629709,0,127.9605433 +124.44,50.33181792,-3.296224473,10000,-123.0105507,157.7006797,0,-14.03629709,0,127.9535174 +124.45,50.33180688,-3.296202358,10000,-122.982698,157.716093,0,-14.03629709,0,127.9464915 +124.46,50.33179584,-3.296180241,10000,-122.9583268,157.7323977,0,-14.03629709,0,127.9394655 +124.47,50.33178481,-3.296158121,10000,-122.9409187,157.7480339,0,-14.03629709,0,127.9324396 +124.48,50.33177377,-3.296135999,10000,-122.9235107,157.7623329,0,-14.03629709,0,127.9254137 +124.49,50.33176274,-3.296113876,10000,-122.9026211,157.7768548,0,-14.03629709,0,127.9183878 +124.5,50.33175171,-3.29609175,10000,-122.885213,157.7922681,0,-14.03629709,0,127.9113619 +124.51,50.33174068,-3.296069622,10000,-122.867805,157.8076814,0,-14.03629709,0,127.904336 +124.52,50.33172965,-3.296047492,10000,-122.8469154,157.8230947,0,-14.03629709,0,127.89731 +124.53,50.33171863,-3.29602536,10000,-122.8295074,157.8385081,0,-14.03629709,0,127.8902841 +124.54,50.3317076,-3.296003225,10000,-122.8120993,157.85303,0,-14.03629709,0,127.8832582 +124.55,50.33169658,-3.295981089,10000,-122.7912097,157.867329,0,-14.03629709,0,127.8762323 +124.56,50.33168556,-3.295958951,10000,-122.7738017,157.8827423,0,-14.03629709,0,127.8692064 +124.57,50.33167454,-3.29593681,10000,-122.7563936,157.8981557,0,-14.03629709,0,127.8621804 +124.58,50.33166352,-3.295914667,10000,-122.735504,157.9124547,0,-14.03629709,0,127.8551545 +124.59,50.33165251,-3.295892523,10000,-122.718096,157.9269766,0,-14.03629709,0,127.8481286 +124.6,50.33164149,-3.295870376,10000,-122.7006879,157.94239,0,-14.03629709,0,127.8411027 +124.61,50.33163048,-3.295848227,10000,-122.6763168,157.9578033,0,-14.03629709,0,127.8340767 +124.62,50.33161947,-3.295826076,10000,-122.648464,157.9732166,0,-14.03629709,0,127.8270508 +124.63,50.33160846,-3.295803923,10000,-122.6240929,157.9888528,0,-14.03629709,0,127.8200249 +124.64,50.33159746,-3.295781767,10000,-122.6101664,158.0040432,0,-14.03629709,0,127.812999 +124.65,50.33158645,-3.29575961,10000,-122.603203,158.0185652,0,-14.03629709,0,127.805973 +124.66,50.33157545,-3.29573745,10000,-122.585795,158.0330871,0,-14.03629709,0,127.7989471 +124.67,50.33156444,-3.295715289,10000,-122.5544607,158.0482776,0,-14.03629709,0,127.7919212 +124.68,50.33155345,-3.295693125,10000,-122.5300895,158.0639137,0,-14.03629709,0,127.7848953 +124.69,50.33154245,-3.295670959,10000,-122.5196446,158.0791042,0,-14.03629709,0,127.7778693 +124.7,50.33153145,-3.295648791,10000,-122.5091997,158.0936261,0,-14.03629709,0,127.7708434 +124.71,50.33152046,-3.295626621,10000,-122.4952732,158.1079252,0,-14.03629709,0,127.7638175 +124.72,50.33150946,-3.295604449,10000,-122.4778652,158.1224471,0,-14.03629709,0,127.7567916 +124.73,50.33149847,-3.295582275,10000,-122.453494,158.1376376,0,-14.03629709,0,127.7497656 +124.74,50.33148748,-3.295560099,10000,-122.4256413,158.1532738,0,-14.03629709,0,127.7427397 +124.75,50.33147649,-3.29553792,10000,-122.4012701,158.1686872,0,-14.03629709,0,127.7357138 +124.76,50.33146551,-3.29551574,10000,-122.3838621,158.1838777,0,-14.03629709,0,127.7286879 +124.77,50.33145452,-3.295493557,10000,-122.366454,158.1986224,0,-14.03629709,0,127.7216619 +124.78,50.33144354,-3.295471372,10000,-122.3455644,158.2126987,0,-14.03629709,0,127.714636 +124.79,50.33143256,-3.295449186,10000,-122.3281564,158.2274434,0,-14.03629709,0,127.7076101 +124.8,50.33142158,-3.295426997,10000,-122.3072668,158.2437482,0,-14.03629709,0,127.7005842 +124.81,50.3314106,-3.295404806,10000,-122.2759325,158.260053,0,-14.03629709,0,127.6935582 +124.82,50.33139963,-3.295382612,10000,-122.2550429,158.2745749,0,-14.03629709,0,127.6865324 +124.83,50.33138866,-3.295360417,10000,-122.2515611,158.2879826,0,-14.03629709,0,127.6795064 +124.84,50.33137768,-3.29533822,10000,-122.2341531,158.3022816,0,-14.03629709,0,127.6724805 +124.85,50.33136671,-3.295316021,10000,-122.1993372,158.317695,0,-14.03629709,0,127.6654546 +124.86,50.33135575,-3.295293819,10000,-122.1819292,158.3331084,0,-14.03629709,0,127.6584287 +124.87,50.33134478,-3.295271616,10000,-122.1784474,158.3485217,0,-14.03629709,0,127.6514027 +124.88,50.33133381,-3.29524941,10000,-122.1575578,158.3641579,0,-14.03629709,0,127.6443768 +124.89,50.33132285,-3.295227202,10000,-122.1262235,158.3793484,0,-14.03629709,0,127.6373509 +124.9,50.33131189,-3.295204992,10000,-122.1088154,158.3938704,0,-14.03629709,0,127.630325 +124.91,50.33130093,-3.29518278,10000,-122.1018521,158.4081694,0,-14.03629709,0,127.623299 +124.92,50.33128997,-3.295160566,10000,-122.0844441,158.4224685,0,-14.03629709,0,127.6162731 +124.93,50.33127901,-3.29513835,10000,-122.0496282,158.4369905,0,-14.03629709,0,127.6092472 +124.94,50.33126806,-3.295116132,10000,-122.0148124,158.4524038,0,-14.03629709,0,127.6022213 +124.95,50.33125711,-3.295093912,10000,-121.9974043,158.4687086,0,-14.03629709,0,127.5951954 +124.96,50.33124616,-3.295071689,10000,-121.9939225,158.4843448,0,-14.03629709,0,127.5881694 +124.97,50.33123521,-3.295049464,10000,-121.9904407,158.4986439,0,-14.03629709,0,127.5811435 +124.98,50.33122426,-3.295027238,10000,-121.9730327,158.5131659,0,-14.03629709,0,127.5741176 +124.99,50.33121331,-3.295005009,10000,-121.9382169,158.5283564,0,-14.03629709,0,127.5670917 +125,50.33120237,-3.294982778,10000,-121.903401,158.5426555,0,-14.03629709,0,127.5600657 +125.01,50.33119143,-3.294960545,10000,-121.885993,158.556286,0,-14.03629709,0,127.5530398 +125.02,50.33118049,-3.294938311,10000,-121.8825112,158.5714765,0,-14.03629709,0,127.5460139 +125.03,50.33116955,-3.294916074,10000,-121.8790294,158.5880042,0,-14.03629709,0,127.538988 +125.04,50.33115861,-3.294893834,10000,-121.8616213,158.6034176,0,-14.03629709,0,127.531962 +125.05,50.33114767,-3.294871593,10000,-121.8268055,158.6177167,0,-14.03629709,0,127.5249361 +125.06,50.33113674,-3.29484935,10000,-121.7919896,158.6324615,0,-14.03629709,0,127.5179102 +125.07,50.33112581,-3.294827104,10000,-121.7745816,158.647652,0,-14.03629709,0,127.5108843 +125.08,50.33111488,-3.294804857,10000,-121.7676183,158.6630654,0,-14.03629709,0,127.5038583 +125.09,50.33110395,-3.294782607,10000,-121.7502102,158.6787016,0,-14.03629709,0,127.4968324 +125.1,50.33109302,-3.294760355,10000,-121.7188759,158.6936693,0,-14.03629709,0,127.4898065 +125.11,50.3310821,-3.294738101,10000,-121.6979863,158.7072998,0,-14.03629709,0,127.4827806 +125.12,50.33107118,-3.294715845,10000,-121.6945045,158.7207075,0,-14.03629709,0,127.4757546 +125.13,50.33106025,-3.294693588,10000,-121.6770965,158.7358981,0,-14.03629709,0,127.4687287 +125.14,50.33104933,-3.294671328,10000,-121.6387991,158.7524257,0,-14.03629709,0,127.4617028 +125.15,50.33103842,-3.294649065,10000,-121.6109464,158.7676162,0,-14.03629709,0,127.4546769 +125.16,50.3310275,-3.294626801,10000,-121.603983,158.7812468,0,-14.03629709,0,127.4476509 +125.17,50.33101659,-3.294604535,10000,-121.6005012,158.7955459,0,-14.03629709,0,127.4406251 +125.18,50.33100567,-3.294582267,10000,-121.5830932,158.8109593,0,-14.03629709,0,127.4335991 +125.19,50.33099476,-3.294559996,10000,-121.5482774,158.8263727,0,-14.03629709,0,127.4265732 +125.2,50.33098385,-3.294537724,10000,-121.5134615,158.8417861,0,-14.03629709,0,127.4195473 +125.21,50.33097295,-3.294515449,10000,-121.4960535,158.8574223,0,-14.03629709,0,127.4125214 +125.22,50.33096204,-3.294493172,10000,-121.4925717,158.8726129,0,-14.03629709,0,127.4054954 +125.23,50.33095114,-3.294470893,10000,-121.4856083,158.8871348,0,-14.03629709,0,127.3984695 +125.24,50.33094023,-3.294448612,10000,-121.4577556,158.901434,0,-14.03629709,0,127.3914436 +125.25,50.33092933,-3.294426329,10000,-121.4194582,158.9157331,0,-14.03629709,0,127.3844177 +125.26,50.33091844,-3.294404044,10000,-121.4020502,158.9302551,0,-14.03629709,0,127.3773917 +125.27,50.33090754,-3.294381757,10000,-121.3985684,158.9454456,0,-14.03629709,0,127.3703658 +125.28,50.33089664,-3.294359468,10000,-121.3776788,158.960859,0,-14.03629709,0,127.3633399 +125.29,50.33088575,-3.294337176,10000,-121.3463445,158.975381,0,-14.03629709,0,127.356314 +125.3,50.33087486,-3.294314883,10000,-121.3289365,158.9896801,0,-14.03629709,0,127.349288 +125.31,50.33086397,-3.294292588,10000,-121.3219731,159.0050935,0,-14.03629709,0,127.3422621 +125.32,50.33085308,-3.29427029,10000,-121.3045651,159.0205069,0,-14.03629709,0,127.3352362 +125.33,50.33084219,-3.29424799,10000,-121.2732308,159.034806,0,-14.03629709,0,127.3282103 +125.34,50.33083131,-3.294225689,10000,-121.2523412,159.049328,0,-14.03629709,0,127.3211843 +125.35,50.33082043,-3.294203385,10000,-121.2488594,159.0647414,0,-14.03629709,0,127.3141584 +125.36,50.33080954,-3.294181079,10000,-121.2314514,159.079932,0,-14.03629709,0,127.3071325 +125.37,50.33079866,-3.294158771,10000,-121.193154,159.094454,0,-14.03629709,0,127.3001066 +125.38,50.33078779,-3.294136461,10000,-121.1653012,159.1087531,0,-14.03629709,0,127.2930807 +125.39,50.33077691,-3.294114149,10000,-121.1583379,159.1232751,0,-14.03629709,0,127.2860547 +125.4,50.33076604,-3.294091835,10000,-121.1513746,159.1384656,0,-14.03629709,0,127.2790288 +125.41,50.33075516,-3.294069519,10000,-121.1235218,159.1541019,0,-14.03629709,0,127.2720029 +125.42,50.33074429,-3.2940472,10000,-121.0852244,159.1695153,0,-14.03629709,0,127.264977 +125.43,50.33073343,-3.29402488,10000,-121.0678164,159.1847059,0,-14.03629709,0,127.257951 +125.44,50.33072256,-3.294002557,10000,-121.0643346,159.1994507,0,-14.03629709,0,127.2509251 +125.45,50.33071169,-3.293980232,10000,-121.043445,159.2133041,0,-14.03629709,0,127.2438992 +125.46,50.33070083,-3.293957906,10000,-121.0121107,159.2271576,0,-14.03629709,0,127.2368733 +125.47,50.33068997,-3.293935577,10000,-120.9947027,159.2423481,0,-14.03629709,0,127.2298473 +125.48,50.33067911,-3.293913247,10000,-120.9877393,159.2584301,0,-14.03629709,0,127.2228215 +125.49,50.33066825,-3.293890913,10000,-120.9738129,159.273175,0,-14.03629709,0,127.2157955 +125.5,50.33065739,-3.293868578,10000,-120.9529233,159.2863598,0,-14.03629709,0,127.2087696 +125.51,50.33064654,-3.293846242,10000,-120.9355152,159.3008818,0,-14.03629709,0,127.2017437 +125.52,50.33063568,-3.293823903,10000,-120.9181072,159.3171867,0,-14.03629709,0,127.1947178 +125.53,50.33062483,-3.293801561,10000,-120.893736,159.3326001,0,-14.03629709,0,127.1876918 +125.54,50.33061398,-3.293779218,10000,-120.8658833,159.3468993,0,-14.03629709,0,127.1806659 +125.55,50.33060313,-3.293756873,10000,-120.8415122,159.3616441,0,-14.03629709,0,127.17364 +125.56,50.33059229,-3.293734525,10000,-120.8241041,159.3766118,0,-14.03629709,0,127.1666141 +125.57,50.33058144,-3.293712176,10000,-120.8066961,159.3911338,0,-14.03629709,0,127.1595881 +125.58,50.3305706,-3.293689824,10000,-120.7858065,159.4056558,0,-14.03629709,0,127.1525622 +125.59,50.33055976,-3.293667471,10000,-120.7683985,159.4208464,0,-14.03629709,0,127.1455363 +125.6,50.33054892,-3.293645115,10000,-120.7509905,159.4364827,0,-14.03629709,0,127.1385104 +125.61,50.33053808,-3.293622757,10000,-120.7301009,159.4516733,0,-14.03629709,0,127.1314844 +125.62,50.33052725,-3.293600397,10000,-120.7126928,159.4661953,0,-14.03629709,0,127.1244585 +125.63,50.33051641,-3.293578035,10000,-120.6952848,159.4802716,0,-14.03629709,0,127.1174326 +125.64,50.33050558,-3.293555671,10000,-120.6709136,159.4939021,0,-14.03629709,0,127.1104067 +125.65,50.33049475,-3.293533305,10000,-120.6430609,159.5079784,0,-14.03629709,0,127.1033807 +125.66,50.33048392,-3.293510938,10000,-120.6186898,159.5233919,0,-14.03629709,0,127.0963548 +125.67,50.3304731,-3.293488567,10000,-120.6012817,159.5390282,0,-14.03629709,0,127.0893289 +125.68,50.33046227,-3.293466195,10000,-120.5838737,159.5539959,0,-14.03629709,0,127.082303 +125.69,50.33045145,-3.293443821,10000,-120.5629841,159.5689636,0,-14.03629709,0,127.075277 +125.7,50.33044063,-3.293421444,10000,-120.5490577,159.5841542,0,-14.03629709,0,127.0682511 +125.71,50.33042981,-3.293399066,10000,-120.5420943,159.5993448,0,-14.03629709,0,127.0612252 +125.72,50.33041899,-3.293376685,10000,-120.5246863,159.6140897,0,-14.03629709,0,127.0541993 +125.73,50.33040817,-3.293354302,10000,-120.493352,159.628166,0,-14.03629709,0,127.0471733 +125.74,50.33039736,-3.293331918,10000,-120.4689808,159.642688,0,-14.03629709,0,127.0401474 +125.75,50.33038655,-3.293309531,10000,-120.4550544,159.6581014,0,-14.03629709,0,127.0331215 +125.76,50.33037573,-3.293287142,10000,-120.4341648,159.6730691,0,-14.03629709,0,127.0260956 +125.77,50.33036493,-3.293264751,10000,-120.4132752,159.6869226,0,-14.03629709,0,127.0190697 +125.78,50.33035412,-3.293242358,10000,-120.3993487,159.700776,0,-14.03629709,0,127.0120437 +125.79,50.33034331,-3.293219964,10000,-120.3749776,159.7155209,0,-14.03629709,0,127.0050178 +125.8,50.33033251,-3.293197566,10000,-120.3436433,159.7307115,0,-14.03629709,0,126.9979919 +125.81,50.33032171,-3.293175168,10000,-120.3262353,159.7459021,0,-14.03629709,0,126.990966 +125.82,50.33031091,-3.293152766,10000,-120.3227535,159.7608698,0,-14.03629709,0,126.98394 +125.83,50.33030011,-3.293130363,10000,-120.3192717,159.7756147,0,-14.03629709,0,126.9769142 +125.84,50.33028931,-3.293107958,10000,-120.3018637,159.7905825,0,-14.03629709,0,126.9698882 +125.85,50.33027851,-3.29308555,10000,-120.2670478,159.8055502,0,-14.03629709,0,126.9628623 +125.86,50.33026772,-3.293063141,10000,-120.232232,159.8200722,0,-14.03629709,0,126.9558364 +125.87,50.33025693,-3.293040729,10000,-120.2113424,159.8345942,0,-14.03629709,0,126.9488105 +125.88,50.33024614,-3.293018316,10000,-120.1939344,159.849562,0,-14.03629709,0,126.9417845 +125.89,50.33023535,-3.2929959,10000,-120.1730448,159.8643069,0,-14.03629709,0,126.9347586 +125.9,50.33022457,-3.292973482,10000,-120.1556368,159.8783832,0,-14.03629709,0,126.9277327 +125.91,50.33021378,-3.292951063,10000,-120.1382287,159.8929052,0,-14.03629709,0,126.9207068 +125.92,50.330203,-3.292928641,10000,-120.1173391,159.9083187,0,-14.03629709,0,126.9136808 +125.93,50.33019222,-3.292906217,10000,-120.1034127,159.9235093,0,-14.03629709,0,126.9066549 +125.94,50.33018144,-3.292883791,10000,-120.0964493,159.9380313,0,-14.03629709,0,126.899629 +125.95,50.33017066,-3.292861363,10000,-120.0790413,159.9523305,0,-14.03629709,0,126.8926031 +125.96,50.33015988,-3.292838933,10000,-120.0442255,159.9666296,0,-14.03629709,0,126.8855771 +125.97,50.33014911,-3.292816501,10000,-120.0094096,159.9811517,0,-14.03629709,0,126.8785512 +125.98,50.33013834,-3.292794067,10000,-119.9920016,159.9963423,0,-14.03629709,0,126.8715253 +125.99,50.33012757,-3.292771631,10000,-119.9850382,160.0117557,0,-14.03629709,0,126.8644994 +126,50.3301168,-3.292749192,10000,-119.9711118,160.0262778,0,-14.03629709,0,126.8574734 +126.01,50.33010603,-3.292726752,10000,-119.9502222,160.0403541,0,-14.03629709,0,126.8504475 +126.02,50.33009527,-3.29270431,10000,-119.9328142,160.055099,0,-14.03629709,0,126.8434216 +126.03,50.3300845,-3.292681865,10000,-119.9154061,160.0702896,0,-14.03629709,0,126.8363957 +126.04,50.33007374,-3.292659419,10000,-119.891035,160.0854802,0,-14.03629709,0,126.8293697 +126.05,50.33006298,-3.29263697,10000,-119.8631823,160.1002251,0,-14.03629709,0,126.8223438 +126.06,50.33005222,-3.292614519,10000,-119.8388111,160.1143014,0,-14.03629709,0,126.8153179 +126.07,50.33004147,-3.292592067,10000,-119.8214031,160.1286006,0,-14.03629709,0,126.808292 +126.08,50.33003071,-3.292569612,10000,-119.8039951,160.1431226,0,-14.03629709,0,126.801266 +126.09,50.33001996,-3.292547155,10000,-119.7831055,160.157199,0,-14.03629709,0,126.7942401 +126.1,50.33000921,-3.292524697,10000,-119.769179,160.171721,0,-14.03629709,0,126.7872142 +126.11,50.32999846,-3.292502236,10000,-119.7622157,160.1871345,0,-14.03629709,0,126.7801883 +126.12,50.32998771,-3.292479773,10000,-119.7448076,160.2023251,0,-14.03629709,0,126.7731623 +126.13,50.32997696,-3.292457308,10000,-119.7099918,160.21707,0,-14.03629709,0,126.7661364 +126.14,50.32996622,-3.292434841,10000,-119.675176,160.2322606,0,-14.03629709,0,126.7591105 +126.15,50.32995548,-3.292412372,10000,-119.657768,160.2476741,0,-14.03629709,0,126.7520846 +126.16,50.32994474,-3.2923899,10000,-119.6508046,160.2619733,0,-14.03629709,0,126.7450587 +126.17,50.329934,-3.292367427,10000,-119.6368782,160.275381,0,-14.03629709,0,126.7380328 +126.18,50.32992326,-3.292344952,10000,-119.6159886,160.2896802,0,-14.03629709,0,126.7310069 +126.19,50.32991253,-3.292322475,10000,-119.5985805,160.3050937,0,-14.03629709,0,126.7239809 +126.2,50.32990179,-3.292299995,10000,-119.5811725,160.3202843,0,-14.03629709,0,126.716955 +126.21,50.32989106,-3.292277514,10000,-119.5568013,160.3348064,0,-14.03629709,0,126.7099291 +126.22,50.32988033,-3.29225503,10000,-119.5289486,160.3491056,0,-14.03629709,0,126.7029032 +126.23,50.3298696,-3.292232545,10000,-119.5045775,160.3634047,0,-14.03629709,0,126.6958772 +126.24,50.32985888,-3.292210057,10000,-119.4871695,160.3779268,0,-14.03629709,0,126.6888513 +126.25,50.32984815,-3.292187568,10000,-119.4697615,160.3931174,0,-14.03629709,0,126.6818254 +126.26,50.32983743,-3.292165076,10000,-119.4488719,160.4085309,0,-14.03629709,0,126.6747995 +126.27,50.32982671,-3.292142582,10000,-119.4349454,160.4228301,0,-14.03629709,0,126.6677735 +126.28,50.32981599,-3.292120086,10000,-119.427982,160.4362378,0,-14.03629709,0,126.6607476 +126.29,50.32980527,-3.292097589,10000,-119.410574,160.450537,0,-14.03629709,0,126.6537217 +126.3,50.32979455,-3.292075089,10000,-119.3757582,160.4659505,0,-14.03629709,0,126.6466958 +126.31,50.32978384,-3.292052587,10000,-119.3409424,160.4811412,0,-14.03629709,0,126.6396698 +126.32,50.32977313,-3.292030083,10000,-119.3235344,160.4956632,0,-14.03629709,0,126.6326439 +126.33,50.32976242,-3.292007577,10000,-119.316571,160.5099624,0,-14.03629709,0,126.625618 +126.34,50.32975171,-3.291985069,10000,-119.3026445,160.5244845,0,-14.03629709,0,126.6185921 +126.35,50.329741,-3.291962559,10000,-119.2817549,160.5396751,0,-14.03629709,0,126.6115661 +126.36,50.3297303,-3.291940047,10000,-119.2643469,160.5550886,0,-14.03629709,0,126.6045402 +126.37,50.32971959,-3.291917532,10000,-119.2469389,160.5693878,0,-14.03629709,0,126.5975143 +126.38,50.32970889,-3.291895016,10000,-119.2225678,160.5827956,0,-14.03629709,0,126.5904884 +126.39,50.32969819,-3.291872498,10000,-119.1947151,160.5973176,0,-14.03629709,0,126.5834624 +126.4,50.32968749,-3.291849978,10000,-119.1703439,160.6133997,0,-14.03629709,0,126.5764365 +126.41,50.3296768,-3.291827455,10000,-119.1529359,160.6288132,0,-14.03629709,0,126.5694106 +126.42,50.3296661,-3.29180493,10000,-119.1355279,160.6419981,0,-14.03629709,0,126.5623847 +126.43,50.32965541,-3.291782404,10000,-119.1146383,160.6545144,0,-14.03629709,0,126.5553587 +126.44,50.32964472,-3.291759876,10000,-119.1007118,160.6688136,0,-14.03629709,0,126.5483328 +126.45,50.32963403,-3.291737346,10000,-119.0937485,160.6848957,0,-14.03629709,0,126.5413069 +126.46,50.32962334,-3.291714813,10000,-119.0763404,160.7005321,0,-14.03629709,0,126.534281 +126.47,50.32961265,-3.291692278,10000,-119.0415246,160.7148313,0,-14.03629709,0,126.527255 +126.48,50.32960197,-3.291669742,10000,-119.0067088,160.7293533,0,-14.03629709,0,126.5202291 +126.49,50.32959129,-3.291647203,10000,-118.9893008,160.7447668,0,-14.03629709,0,126.5132032 +126.5,50.32958061,-3.291624662,10000,-118.9823374,160.7597346,0,-14.03629709,0,126.5061773 +126.51,50.32956993,-3.291602119,10000,-118.968411,160.7735881,0,-14.03629709,0,126.4991513 +126.52,50.32955925,-3.291579574,10000,-118.9475214,160.7876644,0,-14.03629709,0,126.4921255 +126.53,50.32954858,-3.291557028,10000,-118.9301134,160.8028551,0,-14.03629709,0,126.4850995 +126.54,50.3295379,-3.291534478,10000,-118.9127053,160.8176,0,-14.03629709,0,126.4780736 +126.55,50.32952723,-3.291511927,10000,-118.8883342,160.8312306,0,-14.03629709,0,126.4710477 +126.56,50.32951656,-3.291489375,10000,-118.8604815,160.8450841,0,-14.03629709,0,126.4640218 +126.57,50.32950589,-3.291466819,10000,-118.8361104,160.8593833,0,-14.03629709,0,126.4569959 +126.58,50.32949523,-3.291444263,10000,-118.8187023,160.8743511,0,-14.03629709,0,126.4499699 +126.59,50.32948456,-3.291421704,10000,-118.8012943,160.8902103,0,-14.03629709,0,126.442944 +126.6,50.3294739,-3.291399142,10000,-118.7804047,160.9051781,0,-14.03629709,0,126.4359181 +126.61,50.32946324,-3.291376579,10000,-118.7629967,160.9188087,0,-14.03629709,0,126.4288922 +126.62,50.32945258,-3.291354014,10000,-118.7455887,160.933108,0,-14.03629709,0,126.4218662 +126.63,50.32944192,-3.291331447,10000,-118.7246991,160.9482986,0,-14.03629709,0,126.4148403 +126.64,50.32943127,-3.291308877,10000,-118.7072911,160.9628207,0,-14.03629709,0,126.4078144 +126.65,50.32942061,-3.291286306,10000,-118.6898831,160.976897,0,-14.03629709,0,126.4007885 +126.66,50.32940996,-3.291263733,10000,-118.6689935,160.991642,0,-14.03629709,0,126.3937625 +126.67,50.32939931,-3.291241157,10000,-118.6515854,161.0066098,0,-14.03629709,0,126.3867366 +126.68,50.32938866,-3.29121858,10000,-118.6341774,161.0211318,0,-14.03629709,0,126.3797107 +126.69,50.32937801,-3.291196,10000,-118.6132878,161.035431,0,-14.03629709,0,126.3726848 +126.7,50.32936737,-3.291173419,10000,-118.5958798,161.0497303,0,-14.03629709,0,126.3656588 +126.71,50.32935672,-3.291150835,10000,-118.5749902,161.0642523,0,-14.03629709,0,126.3586329 +126.72,50.32934608,-3.29112825,10000,-118.5401744,161.0792201,0,-14.03629709,0,126.351607 +126.73,50.32933544,-3.291105662,10000,-118.5088401,161.0939651,0,-14.03629709,0,126.3445811 +126.74,50.32932481,-3.291083072,10000,-118.5018768,161.1080414,0,-14.03629709,0,126.3375551 +126.75,50.32931417,-3.291060481,10000,-118.5018766,161.1225635,0,-14.03629709,0,126.3305292 +126.76,50.32930353,-3.291037887,10000,-118.480987,161.1377542,0,-14.03629709,0,126.3235033 +126.77,50.3292929,-3.291015291,10000,-118.4496527,161.1520534,0,-14.03629709,0,126.3164774 +126.78,50.32928227,-3.290992693,10000,-118.4287632,161.1654611,0,-14.03629709,0,126.3094514 +126.79,50.32927164,-3.290970094,10000,-118.4078736,161.1797603,0,-14.03629709,0,126.3024255 +126.8,50.32926101,-3.290947492,10000,-118.3765393,161.1951739,0,-14.03629709,0,126.2953996 +126.81,50.32925039,-3.290924888,10000,-118.3556498,161.2101417,0,-14.03629709,0,126.2883737 +126.82,50.32923977,-3.290902282,10000,-118.3556495,161.2239952,0,-14.03629709,0,126.2813477 +126.83,50.32922914,-3.290879674,10000,-118.3486862,161.2380715,0,-14.03629709,0,126.2743218 +126.84,50.32921852,-3.290857065,10000,-118.3173519,161.253485,0,-14.03629709,0,126.2672959 +126.85,50.3292079,-3.290834452,10000,-118.2825361,161.2688986,0,-14.03629709,0,126.26027 +126.86,50.32919729,-3.290811838,10000,-118.2616465,161.2829749,0,-14.03629709,0,126.2532441 +126.87,50.32918667,-3.290789222,10000,-118.2442385,161.2966056,0,-14.03629709,0,126.2462182 +126.88,50.32917606,-3.290766604,10000,-118.2233489,161.3106819,0,-14.03629709,0,126.2391922 +126.89,50.32916545,-3.290743984,10000,-118.2094225,161.3249811,0,-14.03629709,0,126.2321663 +126.9,50.32915484,-3.290721362,10000,-118.2024591,161.3392803,0,-14.03629709,0,126.2251404 +126.91,50.32914423,-3.290698738,10000,-118.1850511,161.3538024,0,-14.03629709,0,126.2181145 +126.92,50.32913362,-3.290676112,10000,-118.1502353,161.3689931,0,-14.03629709,0,126.2110885 +126.93,50.32912302,-3.290653484,10000,-118.1154195,161.3844066,0,-14.03629709,0,126.2040626 +126.94,50.32911242,-3.290630853,10000,-118.0980114,161.3989287,0,-14.03629709,0,126.1970367 +126.95,50.32910182,-3.290608221,10000,-118.0910481,161.4130051,0,-14.03629709,0,126.1900108 +126.96,50.32909122,-3.290585587,10000,-118.0771217,161.4275272,0,-14.03629709,0,126.1829849 +126.97,50.32908062,-3.29056295,10000,-118.0562321,161.4418264,0,-14.03629709,0,126.1759589 +126.98,50.32907003,-3.290540312,10000,-118.0388241,161.4559027,0,-14.03629709,0,126.168933 +126.99,50.32905943,-3.290517672,10000,-118.021416,161.4704248,0,-14.03629709,0,126.1619071 +127,50.32904884,-3.290495029,10000,-118.0005265,161.484724,0,-14.03629709,0,126.1548812 +127.01,50.32903825,-3.290472385,10000,-117.9831184,161.4988004,0,-14.03629709,0,126.1478552 +127.02,50.32902766,-3.290449739,10000,-117.9622289,161.5135454,0,-14.03629709,0,126.1408293 +127.03,50.32901707,-3.29042709,10000,-117.9274131,161.5285132,0,-14.03629709,0,126.1338034 +127.04,50.32900649,-3.29040444,10000,-117.8925972,161.5430353,0,-14.03629709,0,126.1267775 +127.05,50.32899591,-3.290381787,10000,-117.8751892,161.5573345,0,-14.03629709,0,126.1197515 +127.06,50.32898533,-3.290359133,10000,-117.8717074,161.5716337,0,-14.03629709,0,126.1127256 +127.07,50.32897475,-3.290336476,10000,-117.8682257,161.5861558,0,-14.03629709,0,126.1056997 +127.08,50.32896417,-3.290313818,10000,-117.8508177,161.6011236,0,-14.03629709,0,126.0986738 +127.09,50.32895359,-3.290291157,10000,-117.8160018,161.6158686,0,-14.03629709,0,126.0916478 +127.1,50.32894302,-3.290268494,10000,-117.781186,161.6297221,0,-14.03629709,0,126.0846219 +127.11,50.32893245,-3.29024583,10000,-117.763778,161.6433527,0,-14.03629709,0,126.077596 +127.12,50.32892188,-3.290223163,10000,-117.7568147,161.6576519,0,-14.03629709,0,126.0705701 +127.13,50.32891131,-3.290200495,10000,-117.7428882,161.6728426,0,-14.03629709,0,126.0635441 +127.14,50.32890074,-3.290177824,10000,-117.7219986,161.6882562,0,-14.03629709,0,126.0565182 +127.15,50.32889018,-3.290155151,10000,-117.7045906,161.7025554,0,-14.03629709,0,126.0494923 +127.16,50.32887961,-3.290132476,10000,-117.6871826,161.7159631,0,-14.03629709,0,126.0424664 +127.17,50.32886905,-3.2901098,10000,-117.6628115,161.7302624,0,-14.03629709,0,126.0354404 +127.18,50.32885849,-3.290087121,10000,-117.6349588,161.7454531,0,-14.03629709,0,126.0284146 +127.19,50.32884793,-3.29006444,10000,-117.6105876,161.7597523,0,-14.03629709,0,126.0213886 +127.2,50.32883738,-3.290041757,10000,-117.5931796,161.7731601,0,-14.03629709,0,126.0143627 +127.21,50.32882682,-3.290019073,10000,-117.5757716,161.7874593,0,-14.03629709,0,126.0073368 +127.22,50.32881627,-3.289996386,10000,-117.554882,161.8028728,0,-14.03629709,0,126.0003109 +127.23,50.32880572,-3.289973697,10000,-117.537474,161.8180635,0,-14.03629709,0,125.9932849 +127.24,50.32879517,-3.289951006,10000,-117.520066,161.8325856,0,-14.03629709,0,125.986259 +127.25,50.32878462,-3.289928313,10000,-117.4991764,161.8468849,0,-14.03629709,0,125.9792331 +127.26,50.32877408,-3.289905618,10000,-117.4817684,161.8609612,0,-14.03629709,0,125.9722072 +127.27,50.32876353,-3.289882921,10000,-117.4643604,161.874369,0,-14.03629709,0,125.9651812 +127.28,50.32875299,-3.289860222,10000,-117.4434708,161.8875539,0,-14.03629709,0,125.9581553 +127.29,50.32874245,-3.289837522,10000,-117.4260628,161.9018531,0,-14.03629709,0,125.9511294 +127.3,50.32873191,-3.289814819,10000,-117.4051732,161.9172667,0,-14.03629709,0,125.9441035 +127.31,50.32872137,-3.289792114,10000,-117.3703574,161.9324574,0,-14.03629709,0,125.9370775 +127.32,50.32871084,-3.289769407,10000,-117.3355416,161.9469795,0,-14.03629709,0,125.9300516 +127.33,50.32870031,-3.289746698,10000,-117.3181336,161.9612787,0,-14.03629709,0,125.9230257 +127.34,50.32868978,-3.289723987,10000,-117.3146518,161.9755779,0,-14.03629709,0,125.9159998 +127.35,50.32867925,-3.289701274,10000,-117.31117,161.9901,0,-14.03629709,0,125.9089738 +127.36,50.32866872,-3.289678559,10000,-117.2972436,162.0050679,0,-14.03629709,0,125.9019479 +127.37,50.32865819,-3.289655842,10000,-117.276354,162.0198128,0,-14.03629709,0,125.894922 +127.38,50.32864767,-3.289633122,10000,-117.2554644,162.0336663,0,-14.03629709,0,125.8878961 +127.39,50.32863714,-3.289610402,10000,-117.2241302,162.047297,0,-14.03629709,0,125.8808702 +127.4,50.32862662,-3.289587678,10000,-117.1858328,162.0613733,0,-14.03629709,0,125.8738442 +127.41,50.32861611,-3.289564954,10000,-117.1684248,162.0756726,0,-14.03629709,0,125.8668183 +127.42,50.32860559,-3.289542226,10000,-117.164943,162.0901947,0,-14.03629709,0,125.8597924 +127.43,50.32859507,-3.289519498,10000,-117.1440534,162.1051625,0,-14.03629709,0,125.8527665 +127.44,50.32858456,-3.289496766,10000,-117.1127192,162.1199075,0,-14.03629709,0,125.8457405 +127.45,50.32857405,-3.289474033,10000,-117.0953112,162.133761,0,-14.03629709,0,125.8387146 +127.46,50.32856354,-3.289451298,10000,-117.0883478,162.1473916,0,-14.03629709,0,125.8316887 +127.47,50.32855303,-3.289428561,10000,-117.0709398,162.1616908,0,-14.03629709,0,125.8246628 +127.48,50.32854252,-3.289405822,10000,-117.036124,162.1768815,0,-14.03629709,0,125.8176368 +127.49,50.32853202,-3.289383081,10000,-117.0013082,162.1922951,0,-14.03629709,0,125.8106109 +127.5,50.32852152,-3.289360337,10000,-116.9839002,162.2065943,0,-14.03629709,0,125.803585 +127.51,50.32851102,-3.289337592,10000,-116.9804184,162.2197792,0,-14.03629709,0,125.7965591 +127.52,50.32850052,-3.289314845,10000,-116.9769367,162.2334099,0,-14.03629709,0,125.7895331 +127.53,50.32849002,-3.289292096,10000,-116.9595286,162.2483777,0,-14.03629709,0,125.7825073 +127.54,50.32847952,-3.289269345,10000,-116.9247128,162.2637913,0,-14.03629709,0,125.7754813 +127.55,50.32846903,-3.289246591,10000,-116.889897,162.2780905,0,-14.03629709,0,125.7684554 +127.56,50.32845854,-3.289223836,10000,-116.872489,162.2912754,0,-14.03629709,0,125.7614295 +127.57,50.32844805,-3.289201079,10000,-116.8655257,162.3046832,0,-14.03629709,0,125.7544036 +127.58,50.32843756,-3.28917832,10000,-116.8515992,162.3189824,0,-14.03629709,0,125.7473776 +127.59,50.32842707,-3.289155559,10000,-116.8307096,162.3341731,0,-14.03629709,0,125.7403517 +127.6,50.32841659,-3.289132796,10000,-116.8133016,162.3495867,0,-14.03629709,0,125.7333258 +127.61,50.3284061,-3.28911003,10000,-116.7958936,162.363886,0,-14.03629709,0,125.7262999 +127.62,50.32839562,-3.289087263,10000,-116.7715225,162.3770709,0,-14.03629709,0,125.7192739 +127.63,50.32838514,-3.289064494,10000,-116.7436698,162.3907015,0,-14.03629709,0,125.712248 +127.64,50.32837466,-3.289041723,10000,-116.7192986,162.4056693,0,-14.03629709,0,125.7052221 +127.65,50.32836419,-3.28901895,10000,-116.7018906,162.4210829,0,-14.03629709,0,125.6981962 +127.66,50.32835371,-3.288996174,10000,-116.6844826,162.4353822,0,-14.03629709,0,125.6911702 +127.67,50.32834324,-3.288973397,10000,-116.6635931,162.4485671,0,-14.03629709,0,125.6841443 +127.68,50.32833277,-3.288950618,10000,-116.6461851,162.4621977,0,-14.03629709,0,125.6771184 +127.69,50.3283223,-3.288927837,10000,-116.6252955,162.4771655,0,-14.03629709,0,125.6700925 +127.7,50.32831183,-3.288905054,10000,-116.5939613,162.4925791,0,-14.03629709,0,125.6630665 +127.71,50.32830137,-3.288882268,10000,-116.5730717,162.5068784,0,-14.03629709,0,125.6560406 +127.72,50.32829091,-3.288859481,10000,-116.5695899,162.5200633,0,-14.03629709,0,125.6490147 +127.73,50.32828044,-3.288836692,10000,-116.5521819,162.5336939,0,-14.03629709,0,125.6419888 +127.74,50.32826998,-3.288813901,10000,-116.5138845,162.5486617,0,-14.03629709,0,125.6349628 +127.75,50.32825953,-3.288791108,10000,-116.4860318,162.5640753,0,-14.03629709,0,125.6279369 +127.76,50.32824907,-3.288768312,10000,-116.4790685,162.5783745,0,-14.03629709,0,125.620911 +127.77,50.32823862,-3.288745515,10000,-116.4755867,162.5917823,0,-14.03629709,0,125.6138851 +127.78,50.32822816,-3.288722716,10000,-116.4581787,162.6060816,0,-14.03629709,0,125.6068592 +127.79,50.32821771,-3.288699915,10000,-116.4233629,162.6212723,0,-14.03629709,0,125.5998332 +127.8,50.32820726,-3.288677111,10000,-116.3885471,162.6355715,0,-14.03629709,0,125.5928073 +127.81,50.32819682,-3.288654306,10000,-116.3711391,162.6487564,0,-14.03629709,0,125.5857814 +127.82,50.32818637,-3.288631499,10000,-116.3676573,162.662387,0,-14.03629709,0,125.5787555 +127.83,50.32817593,-3.28860869,10000,-116.360694,162.6773549,0,-14.03629709,0,125.5717295 +127.84,50.32816548,-3.288585879,10000,-116.3328413,162.6927685,0,-14.03629709,0,125.5647037 +127.85,50.32815504,-3.288563065,10000,-116.2945439,162.7070677,0,-14.03629709,0,125.5576777 +127.86,50.32814461,-3.28854025,10000,-116.2771359,162.7202526,0,-14.03629709,0,125.5506518 +127.87,50.32813417,-3.288517433,10000,-116.2736541,162.7338833,0,-14.03629709,0,125.5436259 +127.88,50.32812373,-3.288494614,10000,-116.2527646,162.7488511,0,-14.03629709,0,125.5366 +127.89,50.3281133,-3.288471793,10000,-116.2214303,162.7642647,0,-14.03629709,0,125.529574 +127.9,50.32810287,-3.288448969,10000,-116.2005408,162.7785639,0,-14.03629709,0,125.5225481 +127.91,50.32809244,-3.288426144,10000,-116.1831327,162.7917488,0,-14.03629709,0,125.5155222 +127.92,50.32808201,-3.288403317,10000,-116.1622432,162.8051566,0,-14.03629709,0,125.5084963 +127.93,50.32807159,-3.288380488,10000,-116.1448352,162.819233,0,-14.03629709,0,125.5014703 +127.94,50.32806116,-3.288357657,10000,-116.1274272,162.8335322,0,-14.03629709,0,125.4944444 +127.95,50.32805074,-3.288334824,10000,-116.1065376,162.8478315,0,-14.03629709,0,125.4874185 +127.96,50.32804032,-3.288311989,10000,-116.0891296,162.8621307,0,-14.03629709,0,125.4803926 +127.97,50.3280299,-3.288289152,10000,-116.06824,162.8764299,0,-14.03629709,0,125.4733666 +127.98,50.32801948,-3.288266313,10000,-116.0369058,162.8907292,0,-14.03629709,0,125.4663407 +127.99,50.32800907,-3.288243472,10000,-116.0160162,162.9052513,0,-14.03629709,0,125.4593148 +128,50.32799866,-3.288220629,10000,-116.0125345,162.920442,0,-14.03629709,0,125.4522889 +128.01,50.32798824,-3.288197784,10000,-115.9951264,162.9356327,0,-14.03629709,0,125.4452629 +128.02,50.32797783,-3.288174936,10000,-115.9568291,162.9490405,0,-14.03629709,0,125.438237 +128.03,50.32796743,-3.288152087,10000,-115.9289764,162.9613339,0,-14.03629709,0,125.4312111 +128.04,50.32795702,-3.288129237,10000,-115.9220131,162.9756332,0,-14.03629709,0,125.4241852 +128.05,50.32794662,-3.288106384,10000,-115.9185313,162.9917154,0,-14.03629709,0,125.4171592 +128.06,50.32793621,-3.288083528,10000,-115.9011233,163.0060146,0,-14.03629709,0,125.4101333 +128.07,50.32792581,-3.288060671,10000,-115.8663075,163.0185309,0,-14.03629709,0,125.4031074 +128.08,50.32791541,-3.288037813,10000,-115.8314917,163.0326073,0,-14.03629709,0,125.3960815 +128.09,50.32790502,-3.288014952,10000,-115.8106021,163.0480209,0,-14.03629709,0,125.3890555 +128.1,50.32789462,-3.287992088,10000,-115.7931941,163.0620972,0,-14.03629709,0,125.3820296 +128.11,50.32788423,-3.287969224,10000,-115.7723045,163.075505,0,-14.03629709,0,125.3750037 +128.12,50.32787384,-3.287946357,10000,-115.7583781,163.0900271,0,-14.03629709,0,125.3679778 +128.13,50.32786345,-3.287923488,10000,-115.7514148,163.104995,0,-14.03629709,0,125.3609518 +128.14,50.32785306,-3.287900617,10000,-115.7374883,163.1195171,0,-14.03629709,0,125.3539259 +128.15,50.32784267,-3.287877744,10000,-115.7165987,163.1335935,0,-14.03629709,0,125.3469 +128.16,50.32783229,-3.287854869,10000,-115.6991908,163.1470012,0,-14.03629709,0,125.3398741 +128.17,50.3278219,-3.287831992,10000,-115.6783012,163.1601861,0,-14.03629709,0,125.3328482 +128.18,50.32781152,-3.287809114,10000,-115.6434854,163.1744854,0,-14.03629709,0,125.3258222 +128.19,50.32780114,-3.287786233,10000,-115.6086696,163.189899,0,-14.03629709,0,125.3187964 +128.2,50.32779077,-3.28776335,10000,-115.5912616,163.2050897,0,-14.03629709,0,125.3117704 +128.21,50.32778039,-3.287740465,10000,-115.5877798,163.2193889,0,-14.03629709,0,125.3047445 +128.22,50.32777002,-3.287717578,10000,-115.5808165,163.2327967,0,-14.03629709,0,125.2977186 +128.23,50.32775964,-3.287694689,10000,-115.5529638,163.2457587,0,-14.03629709,0,125.2906927 +128.24,50.32774927,-3.287671799,10000,-115.5146664,163.2591665,0,-14.03629709,0,125.2836667 +128.25,50.32773891,-3.287648906,10000,-115.4972584,163.2734657,0,-14.03629709,0,125.2766408 +128.26,50.32772854,-3.287626012,10000,-115.4937767,163.2884336,0,-14.03629709,0,125.2696149 +128.27,50.32771817,-3.287603115,10000,-115.4728871,163.3031786,0,-14.03629709,0,125.262589 +128.28,50.32770781,-3.287580216,10000,-115.4415528,163.3172549,0,-14.03629709,0,125.255563 +128.29,50.32769745,-3.287557316,10000,-115.4206633,163.3315542,0,-14.03629709,0,125.2485371 +128.3,50.32768709,-3.287534413,10000,-115.4032553,163.3460763,0,-14.03629709,0,125.2415112 +128.31,50.32767673,-3.287511508,10000,-115.3823657,163.3599298,0,-14.03629709,0,125.2344853 +128.32,50.32766638,-3.287488602,10000,-115.3649577,163.3735604,0,-14.03629709,0,125.2274593 +128.33,50.32765602,-3.287465693,10000,-115.3475497,163.3876368,0,-14.03629709,0,125.2204334 +128.34,50.32764567,-3.287442783,10000,-115.3266601,163.401936,0,-14.03629709,0,125.2134075 +128.35,50.32763532,-3.28741987,10000,-115.3092521,163.4162353,0,-14.03629709,0,125.2063816 +128.36,50.32762497,-3.287396956,10000,-115.2883626,163.4305345,0,-14.03629709,0,125.1993556 +128.37,50.32761462,-3.287374039,10000,-115.2570283,163.4448338,0,-14.03629709,0,125.1923297 +128.38,50.32760428,-3.287351121,10000,-115.2361388,163.4589101,0,-14.03629709,0,125.1853038 +128.39,50.32759394,-3.2873282,10000,-115.232657,163.4723179,0,-14.03629709,0,125.1782779 +128.4,50.32758359,-3.287305278,10000,-115.215249,163.4855028,0,-14.03629709,0,125.1712519 +128.41,50.32757325,-3.287282354,10000,-115.1769517,163.499802,0,-14.03629709,0,125.164226 +128.42,50.32756292,-3.287259428,10000,-115.149099,163.5149928,0,-14.03629709,0,125.1572001 +128.43,50.32755258,-3.287236499,10000,-115.1421356,163.5295149,0,-14.03629709,0,125.1501742 +128.44,50.32754225,-3.287213569,10000,-115.1386539,163.5435913,0,-14.03629709,0,125.1431482 +128.45,50.32753191,-3.287190637,10000,-115.1212459,163.5581134,0,-14.03629709,0,125.1361223 +128.46,50.32752158,-3.287167702,10000,-115.0864301,163.5721898,0,-14.03629709,0,125.1290964 +128.47,50.32751125,-3.287144766,10000,-115.0516143,163.5853746,0,-14.03629709,0,125.1220705 +128.48,50.32750093,-3.287121828,10000,-115.0307247,163.5987824,0,-14.03629709,0,125.1150445 +128.49,50.3274906,-3.287098888,10000,-115.0133167,163.6130816,0,-14.03629709,0,125.1080186 +128.5,50.32748028,-3.287075946,10000,-114.9924271,163.6282724,0,-14.03629709,0,125.1009927 +128.51,50.32746996,-3.287053002,10000,-114.9785007,163.6434631,0,-14.03629709,0,125.0939668 +128.52,50.32745964,-3.287030055,10000,-114.9715374,163.6570937,0,-14.03629709,0,125.0869408 +128.53,50.32744932,-3.287007107,10000,-114.9576109,163.6698329,0,-14.03629709,0,125.079915 +128.54,50.327439,-3.286984158,10000,-114.9367214,163.6836864,0,-14.03629709,0,125.072889 +128.55,50.32742869,-3.286961205,10000,-114.9193134,163.6984314,0,-14.03629709,0,125.0658631 +128.56,50.32741837,-3.286938252,10000,-114.8984238,163.7127306,0,-14.03629709,0,125.0588372 +128.57,50.32740806,-3.286915295,10000,-114.863608,163.7263612,0,-14.03629709,0,125.0518113 +128.58,50.32739775,-3.286892338,10000,-114.8287922,163.7402147,0,-14.03629709,0,125.0447854 +128.59,50.32738745,-3.286869378,10000,-114.8079026,163.7549597,0,-14.03629709,0,125.0377594 +128.6,50.32737714,-3.286846416,10000,-114.7904947,163.7697047,0,-14.03629709,0,125.0307335 +128.61,50.32736684,-3.286823452,10000,-114.7696051,163.7833353,0,-14.03629709,0,125.0237076 +128.62,50.32735654,-3.286800486,10000,-114.7556787,163.7965202,0,-14.03629709,0,125.0166817 +128.63,50.32734624,-3.286777519,10000,-114.7487153,163.8105966,0,-14.03629709,0,125.0096557 +128.64,50.32733594,-3.286754549,10000,-114.7347889,163.8251187,0,-14.03629709,0,125.0026298 +128.65,50.32732564,-3.286731577,10000,-114.7138993,163.8391951,0,-14.03629709,0,124.9956039 +128.66,50.32731535,-3.286708604,10000,-114.6964913,163.8534943,0,-14.03629709,0,124.988578 +128.67,50.32730505,-3.286685628,10000,-114.6756018,163.8680164,0,-14.03629709,0,124.981552 +128.68,50.32729476,-3.28666265,10000,-114.640786,163.8818699,0,-14.03629709,0,124.9745261 +128.69,50.32728447,-3.286639671,10000,-114.6059702,163.8955005,0,-14.03629709,0,124.9675002 +128.7,50.32727419,-3.286616689,10000,-114.5850806,163.9095769,0,-14.03629709,0,124.9604743 +128.71,50.3272639,-3.286593706,10000,-114.5711542,163.9236533,0,-14.03629709,0,124.9534483 +128.72,50.32725362,-3.28657072,10000,-114.5607093,163.9372839,0,-14.03629709,0,124.9464224 +128.73,50.32724334,-3.286547733,10000,-114.5502644,163.9511374,0,-14.03629709,0,124.9393965 +128.74,50.32723305,-3.286524744,10000,-114.5293748,163.9656595,0,-14.03629709,0,124.9323706 +128.75,50.32722278,-3.286501752,10000,-114.5084853,163.9799588,0,-14.03629709,0,124.9253446 +128.76,50.3272125,-3.286478759,10000,-114.4945589,163.9940351,0,-14.03629709,0,124.9183187 +128.77,50.32720222,-3.286455764,10000,-114.4701877,164.0083344,0,-14.03629709,0,124.9112928 +128.78,50.32719195,-3.286432766,10000,-114.4388535,164.0217421,0,-14.03629709,0,124.9042669 +128.79,50.32718168,-3.286409767,10000,-114.4179639,164.0347041,0,-14.03629709,0,124.8972409 +128.8,50.32717141,-3.286386767,10000,-114.4005559,164.0492262,0,-14.03629709,0,124.890215 +128.81,50.32716114,-3.286363763,10000,-114.3796664,164.064417,0,-14.03629709,0,124.8831891 +128.82,50.32715088,-3.286340758,10000,-114.3622584,164.0784933,0,-14.03629709,0,124.8761632 +128.83,50.32714061,-3.286317751,10000,-114.3448504,164.092124,0,-14.03629709,0,124.8691372 +128.84,50.32713035,-3.286294742,10000,-114.3204793,164.1059775,0,-14.03629709,0,124.8621113 +128.85,50.32712009,-3.286271731,10000,-114.2926266,164.1193852,0,-14.03629709,0,124.8550854 +128.86,50.32710983,-3.286248718,10000,-114.2682555,164.1325701,0,-14.03629709,0,124.8480595 +128.87,50.32709958,-3.286225704,10000,-114.2508475,164.1468693,0,-14.03629709,0,124.8410335 +128.88,50.32708932,-3.286202687,10000,-114.2334395,164.1622829,0,-14.03629709,0,124.8340077 +128.89,50.32707907,-3.286179668,10000,-114.2125499,164.1772508,0,-14.03629709,0,124.8269817 +128.9,50.32706882,-3.286156647,10000,-114.1986235,164.1908814,0,-14.03629709,0,124.8199558 +128.91,50.32705857,-3.286133624,10000,-114.1916602,164.2040663,0,-14.03629709,0,124.8129299 +128.92,50.32704832,-3.2861106,10000,-114.1742522,164.2181426,0,-14.03629709,0,124.805904 +128.93,50.32703807,-3.286087573,10000,-114.1394364,164.2326647,0,-14.03629709,0,124.798878 +128.94,50.32702783,-3.286064544,10000,-114.1046206,164.2465182,0,-14.03629709,0,124.7918521 +128.95,50.32701759,-3.286041514,10000,-114.0872126,164.2601488,0,-14.03629709,0,124.7848262 +128.96,50.32700735,-3.286018481,10000,-114.0802492,164.2742252,0,-14.03629709,0,124.7778003 +128.97,50.32699711,-3.285995447,10000,-114.0663228,164.2883016,0,-14.03629709,0,124.7707744 +128.98,50.32698687,-3.28597241,10000,-114.0454333,164.3019322,0,-14.03629709,0,124.7637484 +128.99,50.32697664,-3.285949372,10000,-114.0280253,164.3157857,0,-14.03629709,0,124.7567225 +129,50.3269664,-3.285926332,10000,-114.0106173,164.3303078,0,-14.03629709,0,124.7496966 +129.01,50.32695617,-3.285903289,10000,-113.9862462,164.3443842,0,-14.03629709,0,124.7426707 +129.02,50.32694594,-3.285880245,10000,-113.9583935,164.357569,0,-14.03629709,0,124.7356447 +129.03,50.32693571,-3.285857199,10000,-113.9340224,164.3709768,0,-14.03629709,0,124.7286188 +129.04,50.32692549,-3.285834151,10000,-113.9166144,164.3850531,0,-14.03629709,0,124.7215929 +129.05,50.32691526,-3.285811101,10000,-113.8992064,164.3993524,0,-14.03629709,0,124.714567 +129.06,50.32690504,-3.285788049,10000,-113.8783168,164.4136516,0,-14.03629709,0,124.707541 +129.07,50.32689482,-3.285764995,10000,-113.8609088,164.4279508,0,-14.03629709,0,124.7005151 +129.08,50.3268846,-3.285741939,10000,-113.8400193,164.4422501,0,-14.03629709,0,124.6934892 +129.09,50.32687438,-3.285718881,10000,-113.808685,164.4565493,0,-14.03629709,0,124.6864633 +129.1,50.32686417,-3.285695821,10000,-113.7843139,164.4706257,0,-14.03629709,0,124.6794373 +129.11,50.32685396,-3.285672759,10000,-113.7703875,164.4840334,0,-14.03629709,0,124.6724114 +129.12,50.32684374,-3.285649695,10000,-113.7494979,164.4972183,0,-14.03629709,0,124.6653855 +129.13,50.32683354,-3.28562663,10000,-113.7286084,164.5112946,0,-14.03629709,0,124.6583596 +129.14,50.32682333,-3.285603562,10000,-113.7181635,164.5258167,0,-14.03629709,0,124.6513336 +129.15,50.32681312,-3.285580492,10000,-113.7077186,164.5396702,0,-14.03629709,0,124.6443077 +129.16,50.32680292,-3.285557421,10000,-113.6937922,164.553078,0,-14.03629709,0,124.6372818 +129.17,50.32679271,-3.285534347,10000,-113.6729026,164.5664857,0,-14.03629709,0,124.6302559 +129.18,50.32678251,-3.285511272,10000,-113.6380868,164.5803392,0,-14.03629709,0,124.6232299 +129.19,50.32677231,-3.285488195,10000,-113.603271,164.5948613,0,-14.03629709,0,124.616204 +129.2,50.32676212,-3.285465115,10000,-113.5823815,164.6091605,0,-14.03629709,0,124.6091781 +129.21,50.32675192,-3.285442034,10000,-113.5649735,164.6232369,0,-14.03629709,0,124.6021522 +129.22,50.32674173,-3.285418951,10000,-113.5440839,164.637759,0,-14.03629709,0,124.5951262 +129.23,50.32673154,-3.285395865,10000,-113.5301575,164.6518353,0,-14.03629709,0,124.5881004 +129.24,50.32672135,-3.285372778,10000,-113.5231942,164.6650202,0,-14.03629709,0,124.5810744 +129.25,50.32671116,-3.285349689,10000,-113.5057862,164.6784279,0,-14.03629709,0,124.5740485 +129.26,50.32670097,-3.285326598,10000,-113.4709704,164.6925043,0,-14.03629709,0,124.5670226 +129.27,50.32669079,-3.285303505,10000,-113.4361546,164.7068035,0,-14.03629709,0,124.5599967 +129.28,50.32668061,-3.28528041,10000,-113.4187466,164.7208799,0,-14.03629709,0,124.5529707 +129.29,50.32667043,-3.285257313,10000,-113.4152648,164.7342876,0,-14.03629709,0,124.5459448 +129.3,50.32666025,-3.285234214,10000,-113.4117831,164.7472496,0,-14.03629709,0,124.5389189 +129.31,50.32665007,-3.285211114,10000,-113.3943751,164.7606573,0,-14.03629709,0,124.531893 +129.32,50.32663989,-3.285188011,10000,-113.3595593,164.7749566,0,-14.03629709,0,124.524867 +129.33,50.32662972,-3.285164907,10000,-113.3247435,164.7899244,0,-14.03629709,0,124.5178411 +129.34,50.32661955,-3.2851418,10000,-113.303854,164.8046694,0,-14.03629709,0,124.5108152 +129.35,50.32660938,-3.285118691,10000,-113.286446,164.8185229,0,-14.03629709,0,124.5037893 +129.36,50.32659921,-3.285095581,10000,-113.2655564,164.8319306,0,-14.03629709,0,124.4967633 +129.37,50.32658905,-3.285072468,10000,-113.2481484,164.8453383,0,-14.03629709,0,124.4897374 +129.38,50.32657888,-3.285049354,10000,-113.2307404,164.8591918,0,-14.03629709,0,124.4827115 +129.39,50.32656872,-3.285026238,10000,-113.2098509,164.8737139,0,-14.03629709,0,124.4756856 +129.4,50.32655856,-3.285003119,10000,-113.1924429,164.8877902,0,-14.03629709,0,124.4686597 +129.41,50.3265484,-3.284979999,10000,-113.1750349,164.9009751,0,-14.03629709,0,124.4616337 +129.42,50.32653824,-3.284956877,10000,-113.1541454,164.9143828,0,-14.03629709,0,124.4546078 +129.43,50.32652809,-3.284933753,10000,-113.1367374,164.9284592,0,-14.03629709,0,124.4475819 +129.44,50.32651793,-3.284910627,10000,-113.1193294,164.9425355,0,-14.03629709,0,124.440556 +129.45,50.32650778,-3.284887499,10000,-113.0949583,164.9559432,0,-14.03629709,0,124.43353 +129.46,50.32649763,-3.284864369,10000,-113.0671056,164.9691281,0,-14.03629709,0,124.4265041 +129.47,50.32648748,-3.284841238,10000,-113.0427345,164.9834273,0,-14.03629709,0,124.4194782 +129.48,50.32647734,-3.284818104,10000,-113.0253265,164.9986181,0,-14.03629709,0,124.4124523 +129.49,50.32646719,-3.284794968,10000,-113.0079185,165.0129173,0,-14.03629709,0,124.4054263 +129.5,50.32645705,-3.28477183,10000,-112.9870289,165.0261021,0,-14.03629709,0,124.3984004 +129.51,50.32644691,-3.284748691,10000,-112.9696209,165.0395098,0,-14.03629709,0,124.3913745 +129.52,50.32643677,-3.284725549,10000,-112.952213,165.0535862,0,-14.03629709,0,124.3843486 +129.53,50.32642663,-3.284702406,10000,-112.9313234,165.0678854,0,-14.03629709,0,124.3773226 +129.54,50.3264165,-3.28467926,10000,-112.9139154,165.0821846,0,-14.03629709,0,124.3702968 +129.55,50.32640636,-3.284656113,10000,-112.8965074,165.096261,0,-14.03629709,0,124.3632708 +129.56,50.32639623,-3.284632963,10000,-112.8721363,165.1096687,0,-14.03629709,0,124.3562449 +129.57,50.3263861,-3.284609812,10000,-112.8442836,165.1226307,0,-14.03629709,0,124.349219 +129.58,50.32637597,-3.284586659,10000,-112.8199125,165.1360384,0,-14.03629709,0,124.3421931 +129.59,50.32636585,-3.284563504,10000,-112.8025045,165.1501147,0,-14.03629709,0,124.3351671 +129.6,50.32635572,-3.284540347,10000,-112.7850966,165.1644139,0,-14.03629709,0,124.3281412 +129.61,50.3263456,-3.284517188,10000,-112.764207,165.1784903,0,-14.03629709,0,124.3211153 +129.62,50.32633548,-3.284494027,10000,-112.746799,165.191898,0,-14.03629709,0,124.3140894 +129.63,50.32632536,-3.284470864,10000,-112.729391,165.20486,0,-14.03629709,0,124.3070634 +129.64,50.32631524,-3.2844477,10000,-112.7085015,165.2182677,0,-14.03629709,0,124.3000375 +129.65,50.32630513,-3.284424533,10000,-112.6910935,165.232344,0,-14.03629709,0,124.2930116 +129.66,50.32629501,-3.284401365,10000,-112.6736855,165.2466432,0,-14.03629709,0,124.2859857 +129.67,50.3262849,-3.284378194,10000,-112.6493144,165.2609425,0,-14.03629709,0,124.2789597 +129.68,50.32627479,-3.284355022,10000,-112.6214617,165.2750188,0,-14.03629709,0,124.2719338 +129.69,50.32626468,-3.284331847,10000,-112.5970906,165.2886494,0,-14.03629709,0,124.2649079 +129.7,50.32625458,-3.284308671,10000,-112.5796826,165.3025029,0,-14.03629709,0,124.257882 +129.71,50.32624447,-3.284285493,10000,-112.5622746,165.3170249,0,-14.03629709,0,124.250856 +129.72,50.32623437,-3.284262312,10000,-112.5413851,165.3311013,0,-14.03629709,0,124.2438301 +129.73,50.32622427,-3.28423913,10000,-112.5239771,165.3442861,0,-14.03629709,0,124.2368042 +129.74,50.32621417,-3.284215946,10000,-112.5030875,165.3576938,0,-14.03629709,0,124.2297783 +129.75,50.32620407,-3.28419276,10000,-112.4717533,165.3717702,0,-14.03629709,0,124.2227523 +129.76,50.32619398,-3.284169572,10000,-112.4508638,165.3858465,0,-14.03629709,0,124.2157264 +129.77,50.32618389,-3.284146382,10000,-112.447382,165.3992542,0,-14.03629709,0,124.2087005 +129.78,50.32617379,-3.28412319,10000,-112.429974,165.412439,0,-14.03629709,0,124.2016746 +129.79,50.3261637,-3.284099997,10000,-112.3916767,165.4265154,0,-14.03629709,0,124.1946487 +129.8,50.32615362,-3.284076801,10000,-112.363824,165.4408146,0,-14.03629709,0,124.1876227 +129.81,50.32614353,-3.284053603,10000,-112.3568607,165.4539994,0,-14.03629709,0,124.1805968 +129.82,50.32613345,-3.284030404,10000,-112.353379,165.4671842,0,-14.03629709,0,124.1735709 +129.83,50.32612336,-3.284007203,10000,-112.335971,165.4814834,0,-14.03629709,0,124.166545 +129.84,50.32611328,-3.283983999,10000,-112.3011552,165.4955598,0,-14.03629709,0,124.159519 +129.85,50.3261032,-3.283960794,10000,-112.2663394,165.5087446,0,-14.03629709,0,124.1524931 +129.86,50.32609313,-3.283937587,10000,-112.2454499,165.5221523,0,-14.03629709,0,124.1454672 +129.87,50.32608305,-3.283914378,10000,-112.2280418,165.5362286,0,-14.03629709,0,124.1384413 +129.88,50.32607298,-3.283891167,10000,-112.2071523,165.5505278,0,-14.03629709,0,124.1314153 +129.89,50.32606291,-3.283867954,10000,-112.1932259,165.564827,0,-14.03629709,0,124.1243895 +129.9,50.32605284,-3.283844739,10000,-112.1862626,165.5789034,0,-14.03629709,0,124.1173635 +129.91,50.32604277,-3.283821522,10000,-112.1723362,165.5923111,0,-14.03629709,0,124.1103376 +129.92,50.3260327,-3.283798303,10000,-112.1514466,165.6054959,0,-14.03629709,0,124.1033117 +129.93,50.32602264,-3.283775083,10000,-112.1340386,165.6195722,0,-14.03629709,0,124.0962858 +129.94,50.32601257,-3.28375186,10000,-112.1131491,165.6338714,0,-14.03629709,0,124.0892598 +129.95,50.32600251,-3.283728635,10000,-112.0783333,165.6468334,0,-14.03629709,0,124.0822339 +129.96,50.32599245,-3.283705409,10000,-112.0435175,165.6593496,0,-14.03629709,0,124.075208 +129.97,50.3259824,-3.283682181,10000,-112.022628,165.6734259,0,-14.03629709,0,124.0681821 +129.98,50.32597234,-3.283658951,10000,-112.00522,165.6886166,0,-14.03629709,0,124.0611561 +129.99,50.32596229,-3.283635718,10000,-111.9843304,165.7029158,0,-14.03629709,0,124.0541302 +130,50.32595224,-3.283612484,10000,-111.970404,165.7161006,0,-14.03629709,0,124.0471043 +130.01,50.32594219,-3.283589248,10000,-111.9634407,165.7292854,0,-14.03629709,0,124.0400784 +130.02,50.32593214,-3.28356601,10000,-111.9460327,165.7424702,0,-14.03629709,0,124.0330524 +130.03,50.32592209,-3.28354277,10000,-111.9112169,165.755655,0,-14.03629709,0,124.0260265 +130.04,50.32591205,-3.283519529,10000,-111.8764011,165.7697314,0,-14.03629709,0,124.0190006 +130.05,50.32590201,-3.283496285,10000,-111.8589931,165.7842534,0,-14.03629709,0,124.0119747 +130.06,50.32589197,-3.283473039,10000,-111.8555114,165.7981069,0,-14.03629709,0,124.0049487 +130.07,50.32588193,-3.283449792,10000,-111.8520296,165.8115146,0,-14.03629709,0,123.9979228 +130.08,50.32587189,-3.283426542,10000,-111.8346217,165.8249223,0,-14.03629709,0,123.9908969 +130.09,50.32586185,-3.283403291,10000,-111.7998059,165.8387757,0,-14.03629709,0,123.983871 +130.1,50.32585182,-3.283380038,10000,-111.7649901,165.8532978,0,-14.03629709,0,123.976845 +130.11,50.32584179,-3.283356782,10000,-111.7441006,165.8673741,0,-14.03629709,0,123.9698191 +130.12,50.32583176,-3.283333525,10000,-111.7266926,165.8805589,0,-14.03629709,0,123.9627932 +130.13,50.32582173,-3.283310266,10000,-111.705803,165.8937437,0,-14.03629709,0,123.9557673 +130.14,50.32581171,-3.283287005,10000,-111.688395,165.9069285,0,-14.03629709,0,123.9487413 +130.15,50.32580168,-3.283263742,10000,-111.6709871,165.9201133,0,-14.03629709,0,123.9417154 +130.16,50.32579166,-3.283240478,10000,-111.6500975,165.9344125,0,-14.03629709,0,123.9346895 +130.17,50.32578164,-3.283217211,10000,-111.6326895,165.9496032,0,-14.03629709,0,123.9276636 +130.18,50.32577162,-3.283193942,10000,-111.6152815,165.9636796,0,-14.03629709,0,123.9206377 +130.19,50.3257616,-3.283170671,10000,-111.594392,165.9761957,0,-14.03629709,0,123.9136117 +130.2,50.32575159,-3.283147399,10000,-111.576984,165.9891576,0,-14.03629709,0,123.9065859 +130.21,50.32574157,-3.283124125,10000,-111.5560945,166.0034568,0,-14.03629709,0,123.8995599 +130.22,50.32573156,-3.283100848,10000,-111.5212787,166.0175332,0,-14.03629709,0,123.892534 +130.23,50.32572155,-3.28307757,10000,-111.4864629,166.0307179,0,-14.03629709,0,123.8855081 +130.24,50.32571155,-3.28305429,10000,-111.4690549,166.0441256,0,-14.03629709,0,123.8784822 +130.25,50.32570154,-3.283031008,10000,-111.4655732,166.0582019,0,-14.03629709,0,123.8714562 +130.26,50.32569154,-3.283007724,10000,-111.4620914,166.0722782,0,-14.03629709,0,123.8644303 +130.27,50.32568153,-3.282984438,10000,-111.4446835,166.085463,0,-14.03629709,0,123.8574044 +130.28,50.32567153,-3.28296115,10000,-111.4098677,166.0977563,0,-14.03629709,0,123.8503785 +130.29,50.32566153,-3.282937861,10000,-111.3750519,166.1107182,0,-14.03629709,0,123.8433525 +130.3,50.32565154,-3.28291457,10000,-111.3541624,166.1252403,0,-14.03629709,0,123.8363266 +130.31,50.32564154,-3.282891276,10000,-111.3367544,166.1402081,0,-14.03629709,0,123.8293007 +130.32,50.32563155,-3.282867981,10000,-111.3158648,166.1545073,0,-14.03629709,0,123.8222748 +130.33,50.32562156,-3.282844683,10000,-111.3019384,166.167915,0,-14.03629709,0,123.8152488 +130.34,50.32561157,-3.282821384,10000,-111.2949751,166.1808769,0,-14.03629709,0,123.8082229 +130.35,50.32560158,-3.282798083,10000,-111.2775671,166.1942846,0,-14.03629709,0,123.801197 +130.36,50.32559159,-3.28277478,10000,-111.2427513,166.208138,0,-14.03629709,0,123.7941711 +130.37,50.32558161,-3.282751475,10000,-111.2079356,166.2215456,0,-14.03629709,0,123.7871451 +130.38,50.32557163,-3.282728168,10000,-111.1905276,166.2347304,0,-14.03629709,0,123.7801192 +130.39,50.32556165,-3.28270486,10000,-111.1835643,166.2490296,0,-14.03629709,0,123.7730933 +130.4,50.32555167,-3.282681549,10000,-111.1696378,166.2642203,0,-14.03629709,0,123.7660674 +130.41,50.32554169,-3.282658236,10000,-111.1487483,166.2782966,0,-14.03629709,0,123.7590414 +130.42,50.32553172,-3.282634921,10000,-111.1313403,166.2905899,0,-14.03629709,0,123.7520155 +130.43,50.32552174,-3.282611605,10000,-111.1104508,166.3028832,0,-14.03629709,0,123.7449896 +130.44,50.32551177,-3.282588287,10000,-111.075635,166.3167366,0,-14.03629709,0,123.7379637 +130.45,50.3255018,-3.282564967,10000,-111.0408192,166.3310358,0,-14.03629709,0,123.7309377 +130.46,50.32549184,-3.282541644,10000,-111.0234113,166.3442205,0,-14.03629709,0,123.7239118 +130.47,50.32548187,-3.282518321,10000,-111.0199295,166.3574053,0,-14.03629709,0,123.7168859 +130.48,50.32547191,-3.282494995,10000,-111.0129662,166.3717045,0,-14.03629709,0,123.70986 +130.49,50.32546194,-3.282471667,10000,-110.9851135,166.3857808,0,-14.03629709,0,123.702834 +130.5,50.32545198,-3.282448337,10000,-110.9468162,166.3989656,0,-14.03629709,0,123.6958081 +130.51,50.32544203,-3.282425006,10000,-110.9294082,166.4123732,0,-14.03629709,0,123.6887822 +130.52,50.32543207,-3.282401672,10000,-110.9259265,166.4262266,0,-14.03629709,0,123.6817563 +130.53,50.32542211,-3.282378337,10000,-110.9050369,166.4396343,0,-14.03629709,0,123.6747303 +130.54,50.32541216,-3.282354999,10000,-110.8737027,166.4528191,0,-14.03629709,0,123.6677044 +130.55,50.32540221,-3.282331661,10000,-110.8528132,166.4668954,0,-14.03629709,0,123.6606785 +130.56,50.32539226,-3.282308319,10000,-110.8354052,166.4811945,0,-14.03629709,0,123.6536526 +130.57,50.32538231,-3.282284976,10000,-110.8145157,166.4941564,0,-14.03629709,0,123.6466266 +130.58,50.32537237,-3.282261631,10000,-110.7971077,166.5066725,0,-14.03629709,0,123.6396008 +130.59,50.32536242,-3.282238285,10000,-110.7796997,166.5207488,0,-14.03629709,0,123.6325749 +130.6,50.32535248,-3.282214936,10000,-110.7553286,166.5359395,0,-14.03629709,0,123.6255489 +130.61,50.32534254,-3.282191585,10000,-110.7274759,166.5500158,0,-14.03629709,0,123.618523 +130.62,50.3253326,-3.282168232,10000,-110.7031049,166.5623091,0,-14.03629709,0,123.6114971 +130.63,50.32532267,-3.282144878,10000,-110.6856969,166.5743794,0,-14.03629709,0,123.6044712 +130.64,50.32531273,-3.282121522,10000,-110.6682889,166.5875642,0,-14.03629709,0,123.5974452 +130.65,50.3253028,-3.282098164,10000,-110.6473993,166.6016405,0,-14.03629709,0,123.5904193 +130.66,50.32529287,-3.282074804,10000,-110.6299914,166.6159396,0,-14.03629709,0,123.5833934 +130.67,50.32528294,-3.282051442,10000,-110.6125834,166.6302388,0,-14.03629709,0,123.5763675 +130.68,50.32527301,-3.282028078,10000,-110.5916938,166.6443151,0,-14.03629709,0,123.5693415 +130.69,50.32526309,-3.282004712,10000,-110.5742859,166.6577227,0,-14.03629709,0,123.5623156 +130.7,50.32525316,-3.281981344,10000,-110.5568779,166.6706846,0,-14.03629709,0,123.5552897 +130.71,50.32524324,-3.281957975,10000,-110.5325068,166.6840923,0,-14.03629709,0,123.5482638 +130.72,50.32523332,-3.281934603,10000,-110.5046541,166.6981685,0,-14.03629709,0,123.5412378 +130.73,50.3252234,-3.28191123,10000,-110.480283,166.7122448,0,-14.03629709,0,123.5342119 +130.74,50.32521349,-3.281887854,10000,-110.4628751,166.7256525,0,-14.03629709,0,123.527186 +130.75,50.32520357,-3.281864477,10000,-110.4454671,166.7386143,0,-14.03629709,0,123.5201601 +130.76,50.32519366,-3.281841098,10000,-110.4245775,166.7517991,0,-14.03629709,0,123.5131341 +130.77,50.32518375,-3.281817717,10000,-110.4071696,166.7649838,0,-14.03629709,0,123.5061082 +130.78,50.32517384,-3.281794334,10000,-110.38628,166.7779457,0,-14.03629709,0,123.4990823 +130.79,50.32516393,-3.28177095,10000,-110.3549458,166.7913533,0,-14.03629709,0,123.4920564 +130.8,50.32515403,-3.281747563,10000,-110.3305747,166.8054296,0,-14.03629709,0,123.4850304 +130.81,50.32514413,-3.281724175,10000,-110.3166483,166.8195059,0,-14.03629709,0,123.4780045 +130.82,50.32513422,-3.281700784,10000,-110.2957588,166.8331364,0,-14.03629709,0,123.4709786 +130.83,50.32512433,-3.281677392,10000,-110.2748692,166.8467669,0,-14.03629709,0,123.4639527 +130.84,50.32511443,-3.281653998,10000,-110.2644244,166.8606203,0,-14.03629709,0,123.4569267 +130.85,50.32510453,-3.281630601,10000,-110.2539795,166.8742508,0,-14.03629709,0,123.4499008 +130.86,50.32509464,-3.281607204,10000,-110.2365715,166.8874356,0,-14.03629709,0,123.4428749 +130.87,50.32508474,-3.281583803,10000,-110.2052373,166.8999517,0,-14.03629709,0,123.435849 +130.88,50.32507485,-3.281560402,10000,-110.16694,166.9124677,0,-14.03629709,0,123.428823 +130.89,50.32506497,-3.281536999,10000,-110.149532,166.9263211,0,-14.03629709,0,123.4217972 +130.9,50.32505508,-3.281513593,10000,-110.1460503,166.941066,0,-14.03629709,0,123.4147712 +130.91,50.32504519,-3.281490186,10000,-110.1251607,166.9553652,0,-14.03629709,0,123.4077453 +130.92,50.32503531,-3.281466776,10000,-110.0938265,166.9687728,0,-14.03629709,0,123.4007194 +130.93,50.32502543,-3.281443365,10000,-110.072937,166.9817347,0,-14.03629709,0,123.3936935 +130.94,50.32501555,-3.281419952,10000,-110.055529,166.9951423,0,-14.03629709,0,123.3866675 +130.95,50.32500567,-3.281396537,10000,-110.0346395,167.0089957,0,-14.03629709,0,123.3796416 +130.96,50.3249958,-3.28137312,10000,-110.0172315,167.0224033,0,-14.03629709,0,123.3726157 +130.97,50.32498592,-3.281349701,10000,-109.9998235,167.035588,0,-14.03629709,0,123.3655898 +130.98,50.32497605,-3.281326281,10000,-109.978934,167.0496643,0,-14.03629709,0,123.3585639 +130.99,50.32496618,-3.281302858,10000,-109.961526,167.0639634,0,-14.03629709,0,123.3515379 +131,50.32495631,-3.281279433,10000,-109.9406364,167.0769253,0,-14.03629709,0,123.344512 +131.01,50.32494644,-3.281256007,10000,-109.9058207,167.0892185,0,-14.03629709,0,123.3374861 +131.02,50.32493658,-3.281232579,10000,-109.8710049,167.1024032,0,-14.03629709,0,123.3304602 +131.03,50.32492672,-3.281209149,10000,-109.853597,167.1164795,0,-14.03629709,0,123.3234342 +131.04,50.32491686,-3.281185717,10000,-109.8501152,167.1305557,0,-14.03629709,0,123.3164083 +131.05,50.324907,-3.281162283,10000,-109.8466335,167.1439633,0,-14.03629709,0,123.3093824 +131.06,50.32489714,-3.281138847,10000,-109.8292255,167.1569252,0,-14.03629709,0,123.3023565 +131.07,50.32488728,-3.28111541,10000,-109.7944097,167.1701099,0,-14.03629709,0,123.2953305 +131.08,50.32487743,-3.28109197,10000,-109.759594,167.1832946,0,-14.03629709,0,123.2883046 +131.09,50.32486758,-3.281068529,10000,-109.742186,167.1962565,0,-14.03629709,0,123.2812787 +131.1,50.32485773,-3.281045086,10000,-109.7352227,167.2096641,0,-14.03629709,0,123.2742528 +131.11,50.32484788,-3.281021641,10000,-109.7178147,167.2237403,0,-14.03629709,0,123.2672268 +131.12,50.32483803,-3.280998194,10000,-109.6864805,167.2380395,0,-14.03629709,0,123.2602009 +131.13,50.32482819,-3.280974745,10000,-109.6621094,167.2521157,0,-14.03629709,0,123.253175 +131.14,50.32481835,-3.280951294,10000,-109.648183,167.2655233,0,-14.03629709,0,123.2461491 +131.15,50.3248085,-3.280927841,10000,-109.6272935,167.2784852,0,-14.03629709,0,123.2391231 +131.16,50.32479867,-3.280904387,10000,-109.6064039,167.2916699,0,-14.03629709,0,123.2320972 +131.17,50.32478883,-3.28088093,10000,-109.5924775,167.3048546,0,-14.03629709,0,123.2250713 +131.18,50.32477899,-3.280857472,10000,-109.5681064,167.3178164,0,-14.03629709,0,123.2180454 +131.19,50.32476916,-3.280834012,10000,-109.5367722,167.331224,0,-14.03629709,0,123.2110194 +131.2,50.32475933,-3.28081055,10000,-109.5193642,167.3453003,0,-14.03629709,0,123.2039935 +131.21,50.3247495,-3.280787086,10000,-109.5124009,167.3593765,0,-14.03629709,0,123.1969676 +131.22,50.32473967,-3.28076362,10000,-109.494993,167.3725612,0,-14.03629709,0,123.1899417 +131.23,50.32472984,-3.280740152,10000,-109.4601772,167.3848544,0,-14.03629709,0,123.1829157 +131.24,50.32472002,-3.280716683,10000,-109.4253614,167.3978162,0,-14.03629709,0,123.1758899 +131.25,50.3247102,-3.280693212,10000,-109.4079535,167.4121153,0,-14.03629709,0,123.1688639 +131.26,50.32470038,-3.280669738,10000,-109.4009901,167.4261916,0,-14.03629709,0,123.161838 +131.27,50.32469056,-3.280646263,10000,-109.3870637,167.4393763,0,-14.03629709,0,123.1548121 +131.28,50.32468074,-3.280622786,10000,-109.3661742,167.452561,0,-14.03629709,0,123.1477862 +131.29,50.32467093,-3.280599307,10000,-109.3487662,167.4657457,0,-14.03629709,0,123.1407602 +131.3,50.32466111,-3.280575826,10000,-109.3313583,167.4787075,0,-14.03629709,0,123.1337343 +131.31,50.3246513,-3.280552344,10000,-109.3069872,167.4921151,0,-14.03629709,0,123.1267084 +131.32,50.32464149,-3.280528859,10000,-109.2791345,167.5061913,0,-14.03629709,0,123.1196825 +131.33,50.32463168,-3.280505373,10000,-109.2547634,167.5202676,0,-14.03629709,0,123.1126565 +131.34,50.32462188,-3.280481884,10000,-109.2373555,167.5336752,0,-14.03629709,0,123.1056306 +131.35,50.32461207,-3.280458394,10000,-109.2199475,167.546637,0,-14.03629709,0,123.0986047 +131.36,50.32460227,-3.280434902,10000,-109.1955764,167.5598217,0,-14.03629709,0,123.0915788 +131.37,50.32459247,-3.280411408,10000,-109.1677238,167.5730064,0,-14.03629709,0,123.0845528 +131.38,50.32458267,-3.280387912,10000,-109.1433527,167.586191,0,-14.03629709,0,123.0775269 +131.39,50.32457288,-3.280364415,10000,-109.1259447,167.6002673,0,-14.03629709,0,123.070501 +131.4,50.32456308,-3.280340915,10000,-109.1085367,167.6145664,0,-14.03629709,0,123.0634751 +131.41,50.32455329,-3.280317413,10000,-109.0876472,167.6275282,0,-14.03629709,0,123.0564492 +131.42,50.3245435,-3.28029391,10000,-109.0737208,167.6398213,0,-14.03629709,0,123.0494232 +131.43,50.32453371,-3.280270405,10000,-109.0667575,167.653006,0,-14.03629709,0,123.0423973 +131.44,50.32452392,-3.280246898,10000,-109.0493495,167.6668594,0,-14.03629709,0,123.0353714 +131.45,50.32451413,-3.280223389,10000,-109.0145337,167.6802669,0,-14.03629709,0,123.0283455 +131.46,50.32450435,-3.280199878,10000,-108.979718,167.6932287,0,-14.03629709,0,123.0213195 +131.47,50.32449457,-3.280176366,10000,-108.96231,167.7066363,0,-14.03629709,0,123.0142936 +131.48,50.32448479,-3.280152851,10000,-108.9553467,167.7207125,0,-14.03629709,0,123.0072677 +131.49,50.32447501,-3.280129335,10000,-108.9379387,167.7347888,0,-14.03629709,0,123.0002418 +131.5,50.32446523,-3.280105816,10000,-108.903123,167.7481963,0,-14.03629709,0,122.9932158 +131.51,50.32445546,-3.280082296,10000,-108.8683072,167.7609352,0,-14.03629709,0,122.9861899 +131.52,50.32444569,-3.280058774,10000,-108.8508992,167.7734512,0,-14.03629709,0,122.979164 +131.53,50.32443592,-3.28003525,10000,-108.8474175,167.7861901,0,-14.03629709,0,122.9721381 +131.54,50.32442615,-3.280011725,10000,-108.8439357,167.7995977,0,-14.03629709,0,122.9651121 +131.55,50.32441638,-3.279988197,10000,-108.8265278,167.8136739,0,-14.03629709,0,122.9580862 +131.56,50.32440661,-3.279964668,10000,-108.791712,167.8277502,0,-14.03629709,0,122.9510603 +131.57,50.32439685,-3.279941136,10000,-108.7568963,167.8411577,0,-14.03629709,0,122.9440344 +131.58,50.32438709,-3.279917603,10000,-108.7360067,167.8541195,0,-14.03629709,0,122.9370084 +131.59,50.32437733,-3.279894068,10000,-108.7185988,167.8673042,0,-14.03629709,0,122.9299826 +131.6,50.32436757,-3.279870531,10000,-108.6977092,167.8802659,0,-14.03629709,0,122.9229566 +131.61,50.32435782,-3.279846992,10000,-108.6803013,167.8925591,0,-14.03629709,0,122.9159307 +131.62,50.32434806,-3.279823452,10000,-108.6628933,167.9055209,0,-14.03629709,0,122.9089048 +131.63,50.32433831,-3.27979991,10000,-108.6420038,167.9198199,0,-14.03629709,0,122.9018789 +131.64,50.32432856,-3.279776365,10000,-108.6245958,167.9338962,0,-14.03629709,0,122.8948529 +131.65,50.32431881,-3.279752819,10000,-108.6037063,167.9470808,0,-14.03629709,0,122.887827 +131.66,50.32430906,-3.279729271,10000,-108.5723721,167.9604884,0,-14.03629709,0,122.8808011 +131.67,50.32429932,-3.279705721,10000,-108.5514825,167.9743417,0,-14.03629709,0,122.8737752 +131.68,50.32428958,-3.279682169,10000,-108.5480008,167.9877492,0,-14.03629709,0,122.8667492 +131.69,50.32427983,-3.279658615,10000,-108.5305928,168.000711,0,-14.03629709,0,122.8597233 +131.7,50.32427009,-3.27963506,10000,-108.4922955,168.0138957,0,-14.03629709,0,122.8526974 +131.71,50.32426036,-3.279611502,10000,-108.4609613,168.0270803,0,-14.03629709,0,122.8456715 +131.72,50.32425062,-3.279587943,10000,-108.4400718,168.0400421,0,-14.03629709,0,122.8386455 +131.73,50.32424089,-3.279564382,10000,-108.4191823,168.0532267,0,-14.03629709,0,122.8316196 +131.74,50.32423116,-3.279540819,10000,-108.4052558,168.0664114,0,-14.03629709,0,122.8245937 +131.75,50.32422143,-3.279517254,10000,-108.3982925,168.0793732,0,-14.03629709,0,122.8175678 +131.76,50.3242117,-3.279493688,10000,-108.3843661,168.0927807,0,-14.03629709,0,122.8105418 +131.77,50.32420197,-3.279470119,10000,-108.3634766,168.1068569,0,-14.03629709,0,122.8035159 +131.78,50.32419225,-3.279446549,10000,-108.3460686,168.1209331,0,-14.03629709,0,122.79649 +131.79,50.32418252,-3.279422976,10000,-108.3251791,168.1341178,0,-14.03629709,0,122.7894641 +131.8,50.3241728,-3.279399402,10000,-108.2903634,168.146188,0,-14.03629709,0,122.7824382 +131.81,50.32416308,-3.279375826,10000,-108.2555476,168.1584811,0,-14.03629709,0,122.7754122 +131.82,50.32415337,-3.279352249,10000,-108.2346581,168.1723344,0,-14.03629709,0,122.7683863 +131.83,50.32414365,-3.279328669,10000,-108.2172501,168.1866334,0,-14.03629709,0,122.7613604 +131.84,50.32413394,-3.279305087,10000,-108.1963606,168.1995952,0,-14.03629709,0,122.7543345 +131.85,50.32412423,-3.279281504,10000,-108.1824342,168.2121112,0,-14.03629709,0,122.7473085 +131.86,50.32411452,-3.279257919,10000,-108.1754709,168.2259645,0,-14.03629709,0,122.7402826 +131.87,50.32410481,-3.279234332,10000,-108.1580629,168.2402635,0,-14.03629709,0,122.7332567 +131.88,50.3240951,-3.279210742,10000,-108.1267287,168.2532253,0,-14.03629709,0,122.7262308 +131.89,50.3240854,-3.279187152,10000,-108.1023576,168.2655184,0,-14.03629709,0,122.7192048 +131.9,50.3240757,-3.279163559,10000,-108.0884312,168.278703,0,-14.03629709,0,122.712179 +131.91,50.32406599,-3.279139965,10000,-108.0675417,168.2925563,0,-14.03629709,0,122.705153 +131.92,50.3240563,-3.279116368,10000,-108.0466522,168.3059638,0,-14.03629709,0,122.6981271 +131.93,50.3240466,-3.27909277,10000,-108.0327258,168.3189256,0,-14.03629709,0,122.6911012 +131.94,50.3240369,-3.27906917,10000,-108.0083547,168.3323331,0,-14.03629709,0,122.6840753 +131.95,50.32402721,-3.279045568,10000,-107.9770205,168.3461864,0,-14.03629709,0,122.6770493 +131.96,50.32401752,-3.279021964,10000,-107.9561309,168.3595939,0,-14.03629709,0,122.6700234 +131.97,50.32400783,-3.278998358,10000,-107.938723,168.3725556,0,-14.03629709,0,122.6629975 +131.98,50.32399814,-3.278974751,10000,-107.9178335,168.3855174,0,-14.03629709,0,122.6559716 +131.99,50.32398846,-3.278951141,10000,-107.9004255,168.3978105,0,-14.03629709,0,122.6489456 +132,50.32397877,-3.27892753,10000,-107.8830175,168.4096578,0,-14.03629709,0,122.6419197 +132.01,50.32396909,-3.278903918,10000,-107.8586464,168.4230653,0,-14.03629709,0,122.6348938 +132.02,50.32395941,-3.278880303,10000,-107.8307938,168.438033,0,-14.03629709,0,122.6278679 +132.03,50.32394973,-3.278856686,10000,-107.8064227,168.4521092,0,-14.03629709,0,122.6208419 +132.04,50.32394006,-3.278833067,10000,-107.7890148,168.4644022,0,-14.03629709,0,122.613816 +132.05,50.32393038,-3.278809447,10000,-107.7716068,168.4764724,0,-14.03629709,0,122.6067901 +132.06,50.32392071,-3.278785825,10000,-107.7507173,168.4898799,0,-14.03629709,0,122.5997642 +132.07,50.32391104,-3.278762201,10000,-107.7333093,168.5046247,0,-14.03629709,0,122.5927382 +132.08,50.32390137,-3.278738575,10000,-107.7159013,168.5191467,0,-14.03629709,0,122.5857123 +132.09,50.3238917,-3.278714946,10000,-107.6950118,168.5321084,0,-14.03629709,0,122.5786864 +132.1,50.32388204,-3.278691317,10000,-107.6776038,168.5441786,0,-14.03629709,0,122.5716605 +132.11,50.32387237,-3.278667685,10000,-107.6601959,168.5564716,0,-14.03629709,0,122.5646345 +132.12,50.32386271,-3.278644052,10000,-107.6358248,168.5692105,0,-14.03629709,0,122.5576086 +132.13,50.32385305,-3.278620417,10000,-107.6079722,168.582618,0,-14.03629709,0,122.5505827 +132.14,50.32384339,-3.27859678,10000,-107.5836011,168.5966941,0,-14.03629709,0,122.5435568 +132.15,50.32383374,-3.278573141,10000,-107.5661931,168.6107703,0,-14.03629709,0,122.5365308 +132.16,50.32382408,-3.2785495,10000,-107.5487851,168.6239549,0,-14.03629709,0,122.5295049 +132.17,50.32381443,-3.278525857,10000,-107.5244141,168.636025,0,-14.03629709,0,122.522479 +132.18,50.32380478,-3.278502213,10000,-107.4965614,168.6480952,0,-14.03629709,0,122.5154531 +132.19,50.32379513,-3.278478567,10000,-107.4721903,168.6612798,0,-14.03629709,0,122.5084272 +132.2,50.32378549,-3.278454919,10000,-107.4547824,168.6753559,0,-14.03629709,0,122.5014012 +132.21,50.32377584,-3.278431269,10000,-107.4373744,168.6894321,0,-14.03629709,0,122.4943753 +132.22,50.3237662,-3.278407617,10000,-107.4164849,168.7028396,0,-14.03629709,0,122.4873494 +132.23,50.32375656,-3.278383963,10000,-107.4025585,168.7158013,0,-14.03629709,0,122.4803235 +132.24,50.32374692,-3.278360308,10000,-107.3955952,168.7289859,0,-14.03629709,0,122.4732975 +132.25,50.32373728,-3.27833665,10000,-107.3781872,168.7421705,0,-14.03629709,0,122.4662717 +132.26,50.32372764,-3.278312991,10000,-107.3433715,168.7551322,0,-14.03629709,0,122.4592457 +132.27,50.32371801,-3.27828933,10000,-107.3085557,168.7683168,0,-14.03629709,0,122.4522198 +132.28,50.32370838,-3.278265667,10000,-107.2911478,168.7812785,0,-14.03629709,0,122.4451939 +132.29,50.32369875,-3.278242002,10000,-107.2841845,168.7933486,0,-14.03629709,0,122.438168 +132.3,50.32368912,-3.278218336,10000,-107.2667765,168.8054187,0,-14.03629709,0,122.431142 +132.31,50.32367949,-3.278194668,10000,-107.2319608,168.8186033,0,-14.03629709,0,122.4241161 +132.32,50.32366987,-3.278170998,10000,-107.197145,168.8326795,0,-14.03629709,0,122.4170902 +132.33,50.32366025,-3.278147326,10000,-107.179737,168.8469785,0,-14.03629709,0,122.4100643 +132.34,50.32365063,-3.278123652,10000,-107.1762553,168.8610546,0,-14.03629709,0,122.4030383 +132.35,50.32364101,-3.278099976,10000,-107.1727736,168.8742392,0,-14.03629709,0,122.3960124 +132.36,50.32363139,-3.278076298,10000,-107.1553656,168.8863093,0,-14.03629709,0,122.3889865 +132.37,50.32362177,-3.278052619,10000,-107.1205499,168.8983795,0,-14.03629709,0,122.3819606 +132.38,50.32361216,-3.278028938,10000,-107.0857341,168.911564,0,-14.03629709,0,122.3749346 +132.39,50.32360255,-3.278005255,10000,-107.0648446,168.9254173,0,-14.03629709,0,122.3679087 +132.4,50.32359294,-3.27798157,10000,-107.0474366,168.9388248,0,-14.03629709,0,122.3608828 +132.41,50.32358333,-3.277957883,10000,-107.0265471,168.9517864,0,-14.03629709,0,122.3538569 +132.42,50.32357373,-3.277934195,10000,-107.0091391,168.9651939,0,-14.03629709,0,122.3468309 +132.43,50.32356412,-3.277910504,10000,-106.9917312,168.9790471,0,-14.03629709,0,122.339805 +132.44,50.32355452,-3.277886812,10000,-106.9673601,168.9922317,0,-14.03629709,0,122.3327791 +132.45,50.32354492,-3.277863117,10000,-106.9395075,169.0045247,0,-14.03629709,0,122.3257532 +132.46,50.32353532,-3.277839422,10000,-106.9151364,169.0172635,0,-14.03629709,0,122.3187272 +132.47,50.32352573,-3.277815724,10000,-106.8977284,169.0306709,0,-14.03629709,0,122.3117013 +132.48,50.32351613,-3.277792024,10000,-106.8803205,169.0434097,0,-14.03629709,0,122.3046754 +132.49,50.32350654,-3.277768323,10000,-106.859431,169.0557027,0,-14.03629709,0,122.2976495 +132.5,50.32349695,-3.27774462,10000,-106.8455045,169.0688873,0,-14.03629709,0,122.2906235 +132.51,50.32348736,-3.277720915,10000,-106.8385413,169.0829634,0,-14.03629709,0,122.2835976 +132.52,50.32347777,-3.277697208,10000,-106.8211333,169.0970395,0,-14.03629709,0,122.2765717 +132.53,50.32346818,-3.277673499,10000,-106.7863175,169.1102241,0,-14.03629709,0,122.2695458 +132.54,50.3234586,-3.277649788,10000,-106.7515018,169.1222942,0,-14.03629709,0,122.2625198 +132.55,50.32344902,-3.277626076,10000,-106.7306123,169.1343643,0,-14.03629709,0,122.2554939 +132.56,50.32343944,-3.277602362,10000,-106.7132043,169.1475488,0,-14.03629709,0,122.248468 +132.57,50.32342986,-3.277578646,10000,-106.6923148,169.1614021,0,-14.03629709,0,122.2414421 +132.58,50.32342029,-3.277554928,10000,-106.6749068,169.1748095,0,-14.03629709,0,122.2344161 +132.59,50.32341071,-3.277531208,10000,-106.6574989,169.1877711,0,-14.03629709,0,122.2273903 +132.6,50.32340114,-3.277507487,10000,-106.6366093,169.2009557,0,-14.03629709,0,122.2203644 +132.61,50.32339157,-3.277483763,10000,-106.6192014,169.2141402,0,-14.03629709,0,122.2133384 +132.62,50.323382,-3.277460038,10000,-106.5983119,169.2271019,0,-14.03629709,0,122.2063125 +132.63,50.32337243,-3.277436311,10000,-106.5669777,169.2402864,0,-14.03629709,0,122.1992866 +132.64,50.32336287,-3.277412582,10000,-106.5426066,169.253471,0,-14.03629709,0,122.1922607 +132.65,50.32335331,-3.277388851,10000,-106.5286802,169.2664326,0,-14.03629709,0,122.1852347 +132.66,50.32334374,-3.277365119,10000,-106.5077907,169.2796172,0,-14.03629709,0,122.1782088 +132.67,50.32333419,-3.277341384,10000,-106.4869012,169.2928017,0,-14.03629709,0,122.1711829 +132.68,50.32332463,-3.277317648,10000,-106.4729748,169.3055404,0,-14.03629709,0,122.164157 +132.69,50.32331507,-3.27729391,10000,-106.4486037,169.3180563,0,-14.03629709,0,122.157131 +132.7,50.32330552,-3.27727017,10000,-106.4172695,169.3307951,0,-14.03629709,0,122.1501051 +132.71,50.32329597,-3.277246429,10000,-106.3998615,169.3439796,0,-14.03629709,0,122.1430792 +132.72,50.32328642,-3.277222685,10000,-106.3928982,169.3571641,0,-14.03629709,0,122.1360533 +132.73,50.32327687,-3.27719894,10000,-106.3789719,169.3701257,0,-14.03629709,0,122.1290273 +132.74,50.32326732,-3.277175193,10000,-106.3580823,169.3835332,0,-14.03629709,0,122.1220014 +132.75,50.32325778,-3.277151444,10000,-106.3406744,169.3973864,0,-14.03629709,0,122.1149755 +132.76,50.32324823,-3.277127693,10000,-106.3197849,169.4105709,0,-14.03629709,0,122.1079496 +132.77,50.32323869,-3.27710394,10000,-106.2849691,169.422641,0,-14.03629709,0,122.1009236 +132.78,50.32322915,-3.277080186,10000,-106.2501533,169.434711,0,-14.03629709,0,122.0938977 +132.79,50.32321962,-3.27705643,10000,-106.2292638,169.4478956,0,-14.03629709,0,122.0868718 +132.8,50.32321008,-3.277032672,10000,-106.2118559,169.4617487,0,-14.03629709,0,122.0798459 +132.81,50.32320055,-3.277008912,10000,-106.1909664,169.4749333,0,-14.03629709,0,122.0728199 +132.82,50.32319102,-3.27698515,10000,-106.1735584,169.4872262,0,-14.03629709,0,122.065794 +132.83,50.32318149,-3.276961387,10000,-106.1561505,169.5001878,0,-14.03629709,0,122.0587681 +132.84,50.32317196,-3.276937622,10000,-106.135261,169.5142639,0,-14.03629709,0,122.0517422 +132.85,50.32316244,-3.276913854,10000,-106.117853,169.5274484,0,-14.03629709,0,122.0447162 +132.86,50.32315291,-3.276890085,10000,-106.100445,169.5395185,0,-14.03629709,0,122.0376903 +132.87,50.32314339,-3.276866315,10000,-106.0795555,169.552703,0,-14.03629709,0,122.0306644 +132.88,50.32313387,-3.276842542,10000,-106.0621475,169.5667791,0,-14.03629709,0,122.0236385 +132.89,50.32312435,-3.276818767,10000,-106.041258,169.5797407,0,-14.03629709,0,122.0166125 +132.9,50.32311483,-3.276794991,10000,-106.0064423,169.5918107,0,-14.03629709,0,122.0095866 +132.91,50.32310532,-3.276771213,10000,-105.9716266,169.6041036,0,-14.03629709,0,122.0025607 +132.92,50.32309581,-3.276747433,10000,-105.9542186,169.6170652,0,-14.03629709,0,121.9955348 +132.93,50.3230863,-3.276723652,10000,-105.9507369,169.6309184,0,-14.03629709,0,121.9885088 +132.94,50.32307679,-3.276699868,10000,-105.9472551,169.6445487,0,-14.03629709,0,121.981483 +132.95,50.32306728,-3.276676082,10000,-105.9298472,169.6572874,0,-14.03629709,0,121.974457 +132.96,50.32305777,-3.276652296,10000,-105.8950314,169.6704719,0,-14.03629709,0,121.9674311 +132.97,50.32304827,-3.276628506,10000,-105.8602157,169.6838793,0,-14.03629709,0,121.9604052 +132.98,50.32303877,-3.276604715,10000,-105.8393262,169.6963951,0,-14.03629709,0,121.9533793 +132.99,50.32302927,-3.276580923,10000,-105.8219182,169.7089109,0,-14.03629709,0,121.9463534 +133,50.32301977,-3.276557128,10000,-105.8010287,169.7218725,0,-14.03629709,0,121.9393274 +133.01,50.32301028,-3.276533332,10000,-105.7836208,169.7346112,0,-14.03629709,0,121.9323015 +133.02,50.32300078,-3.276509534,10000,-105.7662128,169.747127,0,-14.03629709,0,121.9252756 +133.03,50.32299129,-3.276485734,10000,-105.7418417,169.7598657,0,-14.03629709,0,121.9182497 +133.04,50.3229818,-3.276461933,10000,-105.7139891,169.7730502,0,-14.03629709,0,121.9112237 +133.05,50.32297231,-3.276438129,10000,-105.689618,169.7862347,0,-14.03629709,0,121.9041978 +133.06,50.32296283,-3.276414324,10000,-105.6722101,169.7991963,0,-14.03629709,0,121.8971719 +133.07,50.32295334,-3.276390517,10000,-105.6548021,169.8126037,0,-14.03629709,0,121.890146 +133.08,50.32294386,-3.276366708,10000,-105.6339126,169.8262339,0,-14.03629709,0,121.88312 +133.09,50.32293438,-3.276342897,10000,-105.6199862,169.8387497,0,-14.03629709,0,121.8760941 +133.1,50.3229249,-3.276319084,10000,-105.6130229,169.8505968,0,-14.03629709,0,121.8690682 +133.11,50.32291542,-3.276295271,10000,-105.5956149,169.8637813,0,-14.03629709,0,121.8620423 +133.12,50.32290594,-3.276271454,10000,-105.5607992,169.8778574,0,-14.03629709,0,121.8550163 +133.13,50.32289647,-3.276247636,10000,-105.5259835,169.8905961,0,-14.03629709,0,121.8479904 +133.14,50.322887,-3.276223816,10000,-105.505094,169.9022203,0,-14.03629709,0,121.8409645 +133.15,50.32287753,-3.276199995,10000,-105.487686,169.914959,0,-14.03629709,0,121.8339386 +133.16,50.32286806,-3.276176172,10000,-105.4667965,169.929035,0,-14.03629709,0,121.8269126 +133.17,50.3228586,-3.276152346,10000,-105.4493885,169.9422195,0,-14.03629709,0,121.8198867 +133.18,50.32284913,-3.276128519,10000,-105.4319806,169.9542894,0,-14.03629709,0,121.8128608 +133.19,50.32283967,-3.276104691,10000,-105.4110911,169.9674739,0,-14.03629709,0,121.8058349 +133.2,50.32283021,-3.27608086,10000,-105.3936831,169.9815499,0,-14.03629709,0,121.7988089 +133.21,50.32282075,-3.276057027,10000,-105.3727936,169.9945115,0,-14.03629709,0,121.791783 +133.22,50.32281129,-3.276033193,10000,-105.3379779,170.0065815,0,-14.03629709,0,121.7847571 +133.23,50.32280184,-3.276009357,10000,-105.3031621,170.0188744,0,-14.03629709,0,121.7777312 +133.24,50.32279239,-3.275985519,10000,-105.2857542,170.031613,0,-14.03629709,0,121.7707052 +133.25,50.32278294,-3.27596168,10000,-105.2822724,170.0450204,0,-14.03629709,0,121.7636793 +133.26,50.32277349,-3.275937838,10000,-105.2787907,170.0588735,0,-14.03629709,0,121.7566534 +133.27,50.32276404,-3.275913995,10000,-105.2613828,170.072058,0,-14.03629709,0,121.7496275 +133.28,50.32275459,-3.275890149,10000,-105.226567,170.084128,0,-14.03629709,0,121.7426016 +133.29,50.32274515,-3.275866303,10000,-105.1917513,170.0961979,0,-14.03629709,0,121.7355757 +133.3,50.32273571,-3.275842454,10000,-105.1743433,170.1093824,0,-14.03629709,0,121.7285497 +133.31,50.32272627,-3.275818604,10000,-105.1673801,170.1232355,0,-14.03629709,0,121.7215238 +133.32,50.32271683,-3.275794751,10000,-105.1499721,170.1364199,0,-14.03629709,0,121.7144979 +133.33,50.32270739,-3.275770897,10000,-105.1151563,170.1484899,0,-14.03629709,0,121.707472 +133.34,50.32269796,-3.275747041,10000,-105.0803406,170.1605599,0,-14.03629709,0,121.700446 +133.35,50.32268853,-3.275723184,10000,-105.0629326,170.1735214,0,-14.03629709,0,121.6934201 +133.36,50.3226791,-3.275699324,10000,-105.0559694,170.1867059,0,-14.03629709,0,121.6863942 +133.37,50.32266967,-3.275675463,10000,-105.042043,170.1996674,0,-14.03629709,0,121.6793683 +133.38,50.32266024,-3.2756516,10000,-105.0211535,170.2130747,0,-14.03629709,0,121.6723423 +133.39,50.32265082,-3.275627735,10000,-105.0037455,170.2269278,0,-14.03629709,0,121.6653164 +133.4,50.32264139,-3.275603868,10000,-104.982856,170.2401123,0,-14.03629709,0,121.6582905 +133.41,50.32263197,-3.275579999,10000,-104.9480403,170.2521822,0,-14.03629709,0,121.6512646 +133.42,50.32262255,-3.275556129,10000,-104.9132245,170.2642522,0,-14.03629709,0,121.6442387 +133.43,50.32261314,-3.275532257,10000,-104.892335,170.2772137,0,-14.03629709,0,121.6372127 +133.44,50.32260372,-3.275508383,10000,-104.8749271,170.2901752,0,-14.03629709,0,121.6301868 +133.45,50.32259431,-3.275484507,10000,-104.8540376,170.3024681,0,-14.03629709,0,121.6231609 +133.46,50.3225849,-3.27546063,10000,-104.8401112,170.3152067,0,-14.03629709,0,121.616135 +133.47,50.32257549,-3.275436751,10000,-104.8331479,170.328614,0,-14.03629709,0,121.609109 +133.48,50.32256608,-3.275412869,10000,-104.8157399,170.3413527,0,-14.03629709,0,121.6020831 +133.49,50.32255667,-3.275388987,10000,-104.7809242,170.3536455,0,-14.03629709,0,121.5950572 +133.5,50.32254727,-3.275365102,10000,-104.7461084,170.3668299,0,-14.03629709,0,121.5880313 +133.51,50.32253787,-3.275341216,10000,-104.7287005,170.380683,0,-14.03629709,0,121.5810053 +133.52,50.32252847,-3.275317327,10000,-104.7217372,170.3940903,0,-14.03629709,0,121.5739794 +133.53,50.32251907,-3.275293437,10000,-104.7078108,170.4068289,0,-14.03629709,0,121.5669535 +133.54,50.32250967,-3.275269545,10000,-104.6869213,170.4191217,0,-14.03629709,0,121.5599276 +133.55,50.32250028,-3.275245651,10000,-104.6695134,170.4309688,0,-14.03629709,0,121.5529016 +133.56,50.32249088,-3.275221756,10000,-104.6486239,170.4430387,0,-14.03629709,0,121.5458757 +133.57,50.32248149,-3.275197859,10000,-104.6138081,170.4562231,0,-14.03629709,0,121.5388498 +133.58,50.3224721,-3.27517396,10000,-104.5789924,170.4700762,0,-14.03629709,0,121.5318239 +133.59,50.32246272,-3.275150059,10000,-104.5615844,170.4832606,0,-14.03629709,0,121.5247979 +133.6,50.32245333,-3.275126156,10000,-104.5581027,170.4953305,0,-14.03629709,0,121.5177721 +133.61,50.32244395,-3.275102252,10000,-104.5511394,170.5074004,0,-14.03629709,0,121.5107461 +133.62,50.32243456,-3.275078346,10000,-104.5232868,170.5205848,0,-14.03629709,0,121.5037202 +133.63,50.32242518,-3.275054438,10000,-104.481508,170.5344379,0,-14.03629709,0,121.4966943 +133.64,50.32241581,-3.275030528,10000,-104.4536554,170.5476223,0,-14.03629709,0,121.4896684 +133.65,50.32240643,-3.275006616,10000,-104.4466921,170.5596922,0,-14.03629709,0,121.4826424 +133.66,50.32239706,-3.274982703,10000,-104.4432103,170.5717621,0,-14.03629709,0,121.4756165 +133.67,50.32238768,-3.274958788,10000,-104.4258024,170.5849465,0,-14.03629709,0,121.4685906 +133.68,50.32237831,-3.274934871,10000,-104.3909867,170.5987996,0,-14.03629709,0,121.4615647 +133.69,50.32236894,-3.274910952,10000,-104.3561709,170.611984,0,-14.03629709,0,121.4545387 +133.7,50.32235958,-3.274887031,10000,-104.3352814,170.6240539,0,-14.03629709,0,121.4475128 +133.71,50.32235021,-3.274863109,10000,-104.3178734,170.6361238,0,-14.03629709,0,121.4404869 +133.72,50.32234085,-3.274839185,10000,-104.2969839,170.6490853,0,-14.03629709,0,121.433461 +133.73,50.32233149,-3.274815259,10000,-104.279576,170.6620467,0,-14.03629709,0,121.426435 +133.74,50.32232213,-3.274791331,10000,-104.2621681,170.6743395,0,-14.03629709,0,121.4194091 +133.75,50.32231277,-3.274767402,10000,-104.2412786,170.687301,0,-14.03629709,0,121.4123832 +133.76,50.32230342,-3.274743471,10000,-104.2238706,170.701377,0,-14.03629709,0,121.4053573 +133.77,50.32229406,-3.274719537,10000,-104.2064627,170.7145613,0,-14.03629709,0,121.3983313 +133.78,50.32228471,-3.274695602,10000,-104.1820916,170.7264083,0,-14.03629709,0,121.3913054 +133.79,50.32227536,-3.274671666,10000,-104.1542389,170.7387011,0,-14.03629709,0,121.3842795 +133.8,50.32226601,-3.274647727,10000,-104.1298679,170.7516626,0,-14.03629709,0,121.3772536 +133.81,50.32225667,-3.274623787,10000,-104.1124599,170.7644012,0,-14.03629709,0,121.3702277 +133.82,50.32224732,-3.274599845,10000,-104.095052,170.7766939,0,-14.03629709,0,121.3632017 +133.83,50.32223798,-3.274575901,10000,-104.0706809,170.7887638,0,-14.03629709,0,121.3561758 +133.84,50.32222864,-3.274551956,10000,-104.0428283,170.8017253,0,-14.03629709,0,121.3491499 +133.85,50.3222193,-3.274528009,10000,-104.0184573,170.8158012,0,-14.03629709,0,121.342124 +133.86,50.32220997,-3.274504059,10000,-104.0010493,170.8289856,0,-14.03629709,0,121.335098 +133.87,50.32220063,-3.274480108,10000,-103.9836414,170.8408325,0,-14.03629709,0,121.3280721 +133.88,50.3221913,-3.274456156,10000,-103.9627519,170.8531253,0,-14.03629709,0,121.3210462 +133.89,50.32218197,-3.274432201,10000,-103.9453439,170.8660868,0,-14.03629709,0,121.3140203 +133.9,50.32217264,-3.274408245,10000,-103.927936,170.8790482,0,-14.03629709,0,121.3069943 +133.91,50.32216331,-3.274384287,10000,-103.9070465,170.8922326,0,-14.03629709,0,121.2999684 +133.92,50.32215399,-3.274360327,10000,-103.8896385,170.905194,0,-14.03629709,0,121.2929425 +133.93,50.32214466,-3.274336365,10000,-103.8722306,170.9172639,0,-14.03629709,0,121.2859166 +133.94,50.32213534,-3.274312402,10000,-103.8478595,170.9293337,0,-14.03629709,0,121.2788906 +133.95,50.32212602,-3.274288437,10000,-103.8200069,170.9425181,0,-14.03629709,0,121.2718648 +133.96,50.3221167,-3.27426447,10000,-103.7956358,170.9563711,0,-14.03629709,0,121.2648388 +133.97,50.32210739,-3.274240501,10000,-103.7782279,170.9695554,0,-14.03629709,0,121.2578129 +133.98,50.32209807,-3.27421653,10000,-103.7608199,170.9816253,0,-14.03629709,0,121.250787 +133.99,50.32208876,-3.274192558,10000,-103.7364489,170.9934722,0,-14.03629709,0,121.2437611 +134,50.32207945,-3.274168584,10000,-103.7085962,171.005765,0,-14.03629709,0,121.2367351 +134.01,50.32207014,-3.274144608,10000,-103.6842252,171.0185035,0,-14.03629709,0,121.2297092 +134.02,50.32206084,-3.274120631,10000,-103.6668172,171.0316878,0,-14.03629709,0,121.2226833 +134.03,50.32205153,-3.274096651,10000,-103.6494093,171.0448722,0,-14.03629709,0,121.2156574 +134.04,50.32204223,-3.27407267,10000,-103.6285198,171.0576107,0,-14.03629709,0,121.2086314 +134.05,50.32203293,-3.274048687,10000,-103.6111118,171.0699034,0,-14.03629709,0,121.2016055 +134.06,50.32202363,-3.274024702,10000,-103.5937039,171.0817504,0,-14.03629709,0,121.1945796 +134.07,50.32201433,-3.274000716,10000,-103.5728144,171.0938202,0,-14.03629709,0,121.1875537 +134.08,50.32200504,-3.273976728,10000,-103.5554064,171.1070045,0,-14.03629709,0,121.1805277 +134.09,50.32199574,-3.273952738,10000,-103.5345169,171.1208575,0,-14.03629709,0,121.1735018 +134.1,50.32198645,-3.273928746,10000,-103.4997012,171.1342647,0,-14.03629709,0,121.1664759 +134.11,50.32197716,-3.273904752,10000,-103.4648855,171.1472262,0,-14.03629709,0,121.15945 +134.12,50.32196788,-3.273880757,10000,-103.4474775,171.1601876,0,-14.03629709,0,121.152424 +134.13,50.32195859,-3.273856759,10000,-103.4439958,171.1722574,0,-14.03629709,0,121.1453981 +134.14,50.32194931,-3.27383276,10000,-103.4370325,171.1832127,0,-14.03629709,0,121.1383722 +134.15,50.32194002,-3.27380876,10000,-103.4091799,171.1952825,0,-14.03629709,0,121.1313463 +134.16,50.32193074,-3.273784758,10000,-103.3708827,171.2091355,0,-14.03629709,0,121.1243203 +134.17,50.32192147,-3.273760753,10000,-103.3534747,171.2223198,0,-14.03629709,0,121.1172944 +134.18,50.32191219,-3.273736747,10000,-103.349993,171.2343896,0,-14.03629709,0,121.1102685 +134.19,50.32190291,-3.27371274,10000,-103.3291035,171.2473511,0,-14.03629709,0,121.1032426 +134.2,50.32189364,-3.27368873,10000,-103.2942877,171.2605354,0,-14.03629709,0,121.0962167 +134.21,50.32188437,-3.273664718,10000,-103.2629536,171.2723823,0,-14.03629709,0,121.0891907 +134.22,50.3218751,-3.273640706,10000,-103.2385825,171.2844521,0,-14.03629709,0,121.0821648 +134.23,50.32186584,-3.273616691,10000,-103.2211746,171.2978592,0,-14.03629709,0,121.0751389 +134.24,50.32185657,-3.273592674,10000,-103.2037666,171.3114893,0,-14.03629709,0,121.068113 +134.25,50.32184731,-3.273568656,10000,-103.1828771,171.3246736,0,-14.03629709,0,121.061087 +134.26,50.32183805,-3.273544635,10000,-103.1689507,171.3369663,0,-14.03629709,0,121.0540612 +134.27,50.32182879,-3.273520613,10000,-103.1619875,171.3485903,0,-14.03629709,0,121.0470352 +134.28,50.32181953,-3.27349659,10000,-103.1445795,171.3611059,0,-14.03629709,0,121.0400093 +134.29,50.32181027,-3.273472564,10000,-103.1097638,171.374736,0,-14.03629709,0,121.0329834 +134.3,50.32180102,-3.273448537,10000,-103.0749481,171.3879203,0,-14.03629709,0,121.0259575 +134.31,50.32179177,-3.273424507,10000,-103.0575401,171.39999,0,-14.03629709,0,121.0189315 +134.32,50.32178252,-3.273400477,10000,-103.0505768,171.4118369,0,-14.03629709,0,121.0119056 +134.33,50.32177327,-3.273376444,10000,-103.0331689,171.4241296,0,-14.03629709,0,121.0048797 +134.34,50.32176402,-3.27335241,10000,-102.9983532,171.4368681,0,-14.03629709,0,120.9978538 +134.35,50.32175478,-3.273328374,10000,-102.9635375,171.4500523,0,-14.03629709,0,120.9908278 +134.36,50.32174554,-3.273304336,10000,-102.9461295,171.4630137,0,-14.03629709,0,120.9838019 +134.37,50.3217363,-3.273280296,10000,-102.9391662,171.4750835,0,-14.03629709,0,120.976776 +134.38,50.32172706,-3.273256255,10000,-102.9252398,171.4871533,0,-14.03629709,0,120.9697501 +134.39,50.32171782,-3.273232212,10000,-102.9043503,171.5001146,0,-14.03629709,0,120.9627241 +134.4,50.32170859,-3.273208167,10000,-102.8869424,171.5132989,0,-14.03629709,0,120.9556982 +134.41,50.32169935,-3.27318412,10000,-102.8660529,171.5262602,0,-14.03629709,0,120.9486723 +134.42,50.32169012,-3.273160072,10000,-102.8312372,171.5392216,0,-14.03629709,0,120.9416464 +134.43,50.32168089,-3.273136021,10000,-102.7964215,171.5515143,0,-14.03629709,0,120.9346204 +134.44,50.32167167,-3.273111969,10000,-102.7790135,171.5631382,0,-14.03629709,0,120.9275945 +134.45,50.32166244,-3.273087916,10000,-102.7720502,171.5754309,0,-14.03629709,0,120.9205686 +134.46,50.32165322,-3.27306386,10000,-102.7546423,171.5883922,0,-14.03629709,0,120.9135427 +134.47,50.32164399,-3.273039803,10000,-102.7233081,171.6011307,0,-14.03629709,0,120.9065167 +134.48,50.32163478,-3.273015744,10000,-102.6989371,171.6136462,0,-14.03629709,0,120.8994908 +134.49,50.32162556,-3.272991683,10000,-102.6884922,171.6263847,0,-14.03629709,0,120.8924649 +134.5,50.32161634,-3.272967621,10000,-102.6780474,171.6395689,0,-14.03629709,0,120.885439 +134.51,50.32160713,-3.272943556,10000,-102.6606395,171.6525303,0,-14.03629709,0,120.878413 +134.52,50.32159791,-3.27291949,10000,-102.6293053,171.6643771,0,-14.03629709,0,120.8713871 +134.53,50.3215887,-3.272895422,10000,-102.591008,171.6757782,0,-14.03629709,0,120.8643612 +134.54,50.3215795,-3.272871353,10000,-102.5736001,171.6882937,0,-14.03629709,0,120.8573353 +134.55,50.32157029,-3.272847282,10000,-102.5701183,171.7017008,0,-14.03629709,0,120.8503093 +134.56,50.32156108,-3.272823208,10000,-102.5492289,171.7146622,0,-14.03629709,0,120.8432834 +134.57,50.32155188,-3.272799134,10000,-102.5144131,171.7274006,0,-14.03629709,0,120.8362575 +134.58,50.32154268,-3.272775057,10000,-102.483079,171.7399161,0,-14.03629709,0,120.8292316 +134.59,50.32153348,-3.272750978,10000,-102.4587079,171.75154,0,-14.03629709,0,120.8222056 +134.6,50.32152429,-3.272726899,10000,-102.4413,171.7636098,0,-14.03629709,0,120.8151797 +134.61,50.32151509,-3.272702817,10000,-102.423892,171.7770169,0,-14.03629709,0,120.8081539 +134.62,50.3215059,-3.272678733,10000,-102.4030025,171.790424,0,-14.03629709,0,120.8011279 +134.63,50.32149671,-3.272654648,10000,-102.3890761,171.8029395,0,-14.03629709,0,120.794102 +134.64,50.32148752,-3.27263056,10000,-102.3821129,171.8150092,0,-14.03629709,0,120.7870761 +134.65,50.32147833,-3.272606472,10000,-102.3647049,171.8277477,0,-14.03629709,0,120.7800502 +134.66,50.32146914,-3.272582381,10000,-102.3298892,171.8411548,0,-14.03629709,0,120.7730242 +134.67,50.32145996,-3.272558288,10000,-102.2950735,171.8538932,0,-14.03629709,0,120.7659983 +134.68,50.32145078,-3.272534194,10000,-102.2776655,171.8659629,0,-14.03629709,0,120.7589724 +134.69,50.3214416,-3.272510098,10000,-102.2707023,171.8780326,0,-14.03629709,0,120.7519465 +134.7,50.32143242,-3.272486,10000,-102.2532943,171.8898794,0,-14.03629709,0,120.7449205 +134.71,50.32142324,-3.272461901,10000,-102.2219602,171.9019491,0,-14.03629709,0,120.7378946 +134.72,50.32141407,-3.2724378,10000,-102.1975891,171.9151333,0,-14.03629709,0,120.7308687 +134.73,50.3214049,-3.272413697,10000,-102.1836627,171.9287633,0,-14.03629709,0,120.7238428 +134.74,50.32139572,-3.272389592,10000,-102.1627732,171.9410559,0,-14.03629709,0,120.7168168 +134.75,50.32138656,-3.272365485,10000,-102.1418837,171.9520111,0,-14.03629709,0,120.7097909 +134.76,50.32137739,-3.272341378,10000,-102.1279573,171.9640808,0,-14.03629709,0,120.702765 +134.77,50.32136822,-3.272317268,10000,-102.1035863,171.9781566,0,-14.03629709,0,120.6957391 +134.78,50.32135906,-3.272293156,10000,-102.0722521,171.9920095,0,-14.03629709,0,120.6887131 +134.79,50.3213499,-3.272269042,10000,-102.0513626,172.0040792,0,-14.03629709,0,120.6816872 +134.8,50.32134074,-3.272244927,10000,-102.0339547,172.0152572,0,-14.03629709,0,120.6746613 +134.81,50.32133158,-3.27222081,10000,-102.0130652,172.027104,0,-14.03629709,0,120.6676354 +134.82,50.32132243,-3.272196692,10000,-101.9956573,172.0400653,0,-14.03629709,0,120.6606094 +134.83,50.32131327,-3.272172571,10000,-101.9782493,172.0532495,0,-14.03629709,0,120.6535835 +134.84,50.32130412,-3.272148449,10000,-101.9538783,172.0659879,0,-14.03629709,0,120.6465576 +134.85,50.32129497,-3.272124325,10000,-101.9260257,172.0785034,0,-14.03629709,0,120.6395317 +134.86,50.32128582,-3.272100199,10000,-101.9016546,172.0910188,0,-14.03629709,0,120.6325057 +134.87,50.32127668,-3.272076072,10000,-101.8842467,172.1033114,0,-14.03629709,0,120.6254798 +134.88,50.32126753,-3.272051942,10000,-101.8668387,172.1151582,0,-14.03629709,0,120.6184539 +134.89,50.32125839,-3.272027812,10000,-101.8424677,172.1272278,0,-14.03629709,0,120.611428 +134.9,50.32124925,-3.272003679,10000,-101.8146151,172.1401891,0,-14.03629709,0,120.604402 +134.91,50.32124011,-3.271979545,10000,-101.790244,172.1531504,0,-14.03629709,0,120.5973761 +134.92,50.32123098,-3.271955408,10000,-101.7728361,172.1654429,0,-14.03629709,0,120.5903502 +134.93,50.32122184,-3.271931271,10000,-101.7554281,172.1781813,0,-14.03629709,0,120.5833243 +134.94,50.32121271,-3.271907131,10000,-101.7345386,172.1915883,0,-14.03629709,0,120.5762983 +134.95,50.32120358,-3.271882989,10000,-101.7171307,172.2041038,0,-14.03629709,0,120.5692725 +134.96,50.32119445,-3.271858846,10000,-101.6997228,172.2155047,0,-14.03629709,0,120.5622465 +134.97,50.32118532,-3.271834701,10000,-101.6788333,172.2273515,0,-14.03629709,0,120.5552206 +134.98,50.3211762,-3.271810555,10000,-101.6614253,172.2403127,0,-14.03629709,0,120.5481947 +134.99,50.32116707,-3.271786406,10000,-101.6405358,172.253274,0,-14.03629709,0,120.5411688 +135,50.32115795,-3.271762256,10000,-101.6057201,172.2653436,0,-14.03629709,0,120.5341429 +135.01,50.32114883,-3.271738104,10000,-101.5709044,172.2774133,0,-14.03629709,0,120.5271169 +135.02,50.32113972,-3.271713951,10000,-101.5500149,172.2903745,0,-14.03629709,0,120.520091 +135.03,50.3211306,-3.271689795,10000,-101.5360885,172.3033357,0,-14.03629709,0,120.5130651 +135.04,50.32112149,-3.271665638,10000,-101.5256437,172.3151825,0,-14.03629709,0,120.5060392 +135.05,50.32111238,-3.271641479,10000,-101.5151989,172.3263605,0,-14.03629709,0,120.4990132 +135.06,50.32110326,-3.271617319,10000,-101.4908278,172.3382072,0,-14.03629709,0,120.4919873 +135.07,50.32109416,-3.271593157,10000,-101.4594937,172.3513913,0,-14.03629709,0,120.4849614 +135.08,50.32108505,-3.271568993,10000,-101.4420857,172.3652442,0,-14.03629709,0,120.4779355 +135.09,50.32107595,-3.271544827,10000,-101.4351225,172.3784283,0,-14.03629709,0,120.4709095 +135.1,50.32106684,-3.271520659,10000,-101.4177145,172.3904979,0,-14.03629709,0,120.4638836 +135.11,50.32105774,-3.27149649,10000,-101.3828988,172.4025676,0,-14.03629709,0,120.4568577 +135.12,50.32104864,-3.271472319,10000,-101.3480831,172.4155288,0,-14.03629709,0,120.4498318 +135.13,50.32103955,-3.271448146,10000,-101.3271936,172.42849,0,-14.03629709,0,120.4428058 +135.14,50.32103045,-3.271423971,10000,-101.3097857,172.4403367,0,-14.03629709,0,120.4357799 +135.15,50.32102136,-3.271399795,10000,-101.2888962,172.4515147,0,-14.03629709,0,120.428754 +135.16,50.32101227,-3.271375617,10000,-101.2714883,172.4633614,0,-14.03629709,0,120.4217281 +135.17,50.32100318,-3.271351438,10000,-101.2540803,172.4763226,0,-14.03629709,0,120.4147021 +135.18,50.32099409,-3.271327256,10000,-101.2331908,172.4892838,0,-14.03629709,0,120.4076762 +135.19,50.32098501,-3.271303073,10000,-101.2157829,172.5013534,0,-14.03629709,0,120.4006503 +135.2,50.32097592,-3.271278888,10000,-101.1948934,172.513423,0,-14.03629709,0,120.3936244 +135.21,50.32096684,-3.271254702,10000,-101.1600777,172.5263842,0,-14.03629709,0,120.3865984 +135.22,50.32095776,-3.271230513,10000,-101.125262,172.5393454,0,-14.03629709,0,120.3795725 +135.23,50.32094869,-3.271206323,10000,-101.107854,172.5511921,0,-14.03629709,0,120.3725466 +135.24,50.32093961,-3.271182131,10000,-101.1043723,172.562593,0,-14.03629709,0,120.3655207 +135.25,50.32093054,-3.271157938,10000,-101.097409,172.5753313,0,-14.03629709,0,120.3584947 +135.26,50.32092146,-3.271133743,10000,-101.0695564,172.589407,0,-14.03629709,0,120.3514688 +135.27,50.32091239,-3.271109545,10000,-101.0312592,172.6023682,0,-14.03629709,0,120.3444429 +135.28,50.32090333,-3.271085346,10000,-101.0138512,172.6133233,0,-14.03629709,0,120.337417 +135.29,50.32089426,-3.271061146,10000,-101.0103695,172.6245012,0,-14.03629709,0,120.330391 +135.3,50.32088519,-3.271036944,10000,-100.98948,172.6372395,0,-14.03629709,0,120.3233652 +135.31,50.32087613,-3.27101274,10000,-100.9546643,172.6502007,0,-14.03629709,0,120.3163392 +135.32,50.32086707,-3.270988534,10000,-100.9233302,172.6622703,0,-14.03629709,0,120.3093133 +135.33,50.32085801,-3.270964327,10000,-100.8989591,172.6743398,0,-14.03629709,0,120.3022874 +135.34,50.32084896,-3.270940118,10000,-100.8815512,172.687301,0,-14.03629709,0,120.2952615 +135.35,50.3208399,-3.270915907,10000,-100.8641432,172.7002622,0,-14.03629709,0,120.2882355 +135.36,50.32083085,-3.270891694,10000,-100.8432537,172.7123317,0,-14.03629709,0,120.2812096 +135.37,50.3208218,-3.27086748,10000,-100.8258458,172.7241784,0,-14.03629709,0,120.2741837 +135.38,50.32081275,-3.270843264,10000,-100.8084379,172.7364708,0,-14.03629709,0,120.2671578 +135.39,50.3208037,-3.270819046,10000,-100.7875484,172.7492091,0,-14.03629709,0,120.2601318 +135.4,50.32079466,-3.270794827,10000,-100.7701405,172.7621703,0,-14.03629709,0,120.2531059 +135.41,50.32078561,-3.270770605,10000,-100.7527325,172.7744627,0,-14.03629709,0,120.24608 +135.42,50.32077657,-3.270746382,10000,-100.7283615,172.7860865,0,-14.03629709,0,120.2390541 +135.43,50.32076753,-3.270722158,10000,-100.7005089,172.7983789,0,-14.03629709,0,120.2320282 +135.44,50.32075849,-3.270697931,10000,-100.6761378,172.8113401,0,-14.03629709,0,120.2250022 +135.45,50.32074946,-3.270673703,10000,-100.6587299,172.8240783,0,-14.03629709,0,120.2179763 +135.46,50.32074042,-3.270649473,10000,-100.641322,172.8363708,0,-14.03629709,0,120.2109504 +135.47,50.32073139,-3.270625241,10000,-100.6169509,172.8482174,0,-14.03629709,0,120.2039245 +135.48,50.32072236,-3.270601008,10000,-100.5890983,172.8602869,0,-14.03629709,0,120.1968985 +135.49,50.32071333,-3.270576773,10000,-100.5647273,172.8732481,0,-14.03629709,0,120.1898726 +135.5,50.32070431,-3.270552536,10000,-100.5473193,172.8862092,0,-14.03629709,0,120.1828467 +135.51,50.32069528,-3.270528297,10000,-100.5299114,172.8980558,0,-14.03629709,0,120.1758208 +135.52,50.32068626,-3.270504057,10000,-100.5090219,172.9090109,0,-14.03629709,0,120.1687948 +135.53,50.32067724,-3.270479815,10000,-100.491614,172.9201888,0,-14.03629709,0,120.1617689 +135.54,50.32066822,-3.270455572,10000,-100.474206,172.932927,0,-14.03629709,0,120.154743 +135.55,50.3206592,-3.270431327,10000,-100.4533166,172.9470026,0,-14.03629709,0,120.1477171 +135.56,50.32065019,-3.270407079,10000,-100.4359086,172.9599638,0,-14.03629709,0,120.1406911 +135.57,50.32064117,-3.27038283,10000,-100.4150191,172.9711417,0,-14.03629709,0,120.1336652 +135.58,50.32063216,-3.27035858,10000,-100.3802034,172.9829883,0,-14.03629709,0,120.1266393 +135.59,50.32062315,-3.270334328,10000,-100.3453877,172.9961723,0,-14.03629709,0,120.1196134 +135.6,50.32061415,-3.270310073,10000,-100.3244982,173.0089105,0,-14.03629709,0,120.1125874 +135.61,50.32060514,-3.270285818,10000,-100.3070903,173.02098,0,-14.03629709,0,120.1055615 +135.62,50.32059614,-3.27026156,10000,-100.2862008,173.0330495,0,-14.03629709,0,120.0985356 +135.63,50.32058714,-3.270237301,10000,-100.2722744,173.0448961,0,-14.03629709,0,120.0915097 +135.64,50.32057814,-3.27021304,10000,-100.2653112,173.0569656,0,-14.03629709,0,120.0844838 +135.65,50.32056914,-3.270188778,10000,-100.2479032,173.0699267,0,-14.03629709,0,120.0774579 +135.66,50.32056014,-3.270164513,10000,-100.2130875,173.0828878,0,-14.03629709,0,120.0704319 +135.67,50.32055115,-3.270140247,10000,-100.1782718,173.0947344,0,-14.03629709,0,120.063406 +135.68,50.32054216,-3.270115979,10000,-100.1608639,173.1059123,0,-14.03629709,0,120.0563801 +135.69,50.32053317,-3.27009171,10000,-100.1539006,173.1177589,0,-14.03629709,0,120.0493542 +135.7,50.32052418,-3.270067439,10000,-100.1399742,173.13072,0,-14.03629709,0,120.0423282 +135.71,50.32051519,-3.270043166,10000,-100.1190848,173.1436811,0,-14.03629709,0,120.0353023 +135.72,50.32050621,-3.270018891,10000,-100.1016768,173.1557506,0,-14.03629709,0,120.0282764 +135.73,50.32049722,-3.269994615,10000,-100.0807873,173.1675971,0,-14.03629709,0,120.0212505 +135.74,50.32048824,-3.269970337,10000,-100.0459716,173.1798895,0,-14.03629709,0,120.0142245 +135.75,50.32047926,-3.269946057,10000,-100.0111559,173.1926277,0,-14.03629709,0,120.0071986 +135.76,50.32047029,-3.269921776,10000,-99.99026645,173.2055888,0,-14.03629709,0,120.0001727 +135.77,50.32046131,-3.269897492,10000,-99.97285851,173.2176582,0,-14.03629709,0,119.9931468 +135.78,50.32045234,-3.269873207,10000,-99.95196901,173.2283903,0,-14.03629709,0,119.9861208 +135.79,50.32044337,-3.269848921,10000,-99.93456108,173.2395681,0,-14.03629709,0,119.9790949 +135.8,50.3204344,-3.269824633,10000,-99.91715316,173.2525292,0,-14.03629709,0,119.972069 +135.81,50.32042543,-3.269800343,10000,-99.89626367,173.2663819,0,-14.03629709,0,119.9650431 +135.82,50.32041647,-3.269776051,10000,-99.87885574,173.2795659,0,-14.03629709,0,119.9580172 +135.83,50.3204075,-3.269751757,10000,-99.86144782,173.2916353,0,-14.03629709,0,119.9509912 +135.84,50.32039854,-3.269727462,10000,-99.83707677,173.3034819,0,-14.03629709,0,119.9439653 +135.85,50.32038958,-3.269703165,10000,-99.80922417,173.3155513,0,-14.03629709,0,119.9369394 +135.86,50.32038062,-3.269678866,10000,-99.78485312,173.3273979,0,-14.03629709,0,119.9299135 +135.87,50.32037167,-3.269654566,10000,-99.76744519,173.3392444,0,-14.03629709,0,119.9228875 +135.88,50.32036271,-3.269630264,10000,-99.75003727,173.3513138,0,-14.03629709,0,119.9158616 +135.89,50.32035376,-3.26960596,10000,-99.72566623,173.3631604,0,-14.03629709,0,119.9088357 +135.9,50.32034481,-3.269581655,10000,-99.69781364,173.3752298,0,-14.03629709,0,119.9018098 +135.91,50.32033586,-3.269557348,10000,-99.67344261,173.3881909,0,-14.03629709,0,119.8947838 +135.92,50.32032692,-3.269533039,10000,-99.65603467,173.4011519,0,-14.03629709,0,119.8877579 +135.93,50.32031797,-3.269508728,10000,-99.63862673,173.4132213,0,-14.03629709,0,119.880732 +135.94,50.32030903,-3.269484416,10000,-99.61773724,173.4250679,0,-14.03629709,0,119.8737061 +135.95,50.32030009,-3.269460102,10000,-99.60032931,173.4373602,0,-14.03629709,0,119.8666801 +135.96,50.32029115,-3.269435786,10000,-99.57943983,173.4498754,0,-14.03629709,0,119.8596543 +135.97,50.32028221,-3.269411469,10000,-99.54810569,173.4621677,0,-14.03629709,0,119.8526283 +135.98,50.32027328,-3.269387149,10000,-99.52373465,173.4740143,0,-14.03629709,0,119.8456024 +135.99,50.32026435,-3.269362829,10000,-99.50980827,173.4858608,0,-14.03629709,0,119.8385765 +136,50.32025541,-3.269338506,10000,-99.48891879,173.4981531,0,-14.03629709,0,119.8315506 +136.01,50.32024649,-3.269314182,10000,-99.46802931,173.5106683,0,-14.03629709,0,119.8245246 +136.02,50.32023756,-3.269289856,10000,-99.45410294,173.5229606,0,-14.03629709,0,119.8174987 +136.03,50.32022863,-3.269265528,10000,-99.4297319,173.5348071,0,-14.03629709,0,119.8104728 +136.04,50.32021971,-3.269241199,10000,-99.39839775,173.5468765,0,-14.03629709,0,119.8034469 +136.05,50.32021079,-3.269216868,10000,-99.38098982,173.5598375,0,-14.03629709,0,119.7964209 +136.06,50.32020187,-3.269192535,10000,-99.37402655,173.5725756,0,-14.03629709,0,119.789395 +136.07,50.32019295,-3.2691682,10000,-99.35661862,173.5837534,0,-14.03629709,0,119.7823691 +136.08,50.32018403,-3.269143864,10000,-99.32180292,173.5944854,0,-14.03629709,0,119.7753432 +136.09,50.32017512,-3.269119527,10000,-99.28698722,173.6065548,0,-14.03629709,0,119.7683172 +136.1,50.32016621,-3.269095187,10000,-99.2695793,173.6195158,0,-14.03629709,0,119.7612913 +136.11,50.3201573,-3.269070846,10000,-99.26261602,173.6324768,0,-14.03629709,0,119.7542654 +136.12,50.32014839,-3.269046503,10000,-99.24520809,173.6454378,0,-14.03629709,0,119.7472395 +136.13,50.32013948,-3.269022158,10000,-99.2103924,173.6577301,0,-14.03629709,0,119.7402135 +136.14,50.32013058,-3.268997811,10000,-99.17557669,173.6693536,0,-14.03629709,0,119.7331876 +136.15,50.32012168,-3.268973464,10000,-99.15816876,173.681423,0,-14.03629709,0,119.7261617 +136.16,50.32011278,-3.268949113,10000,-99.1512055,173.6934924,0,-14.03629709,0,119.7191358 +136.17,50.32010388,-3.268924762,10000,-99.13727913,173.7051159,0,-14.03629709,0,119.7121098 +136.18,50.32009498,-3.268900409,10000,-99.11638965,173.7174082,0,-14.03629709,0,119.7050839 +136.19,50.32008609,-3.268876054,10000,-99.09898172,173.7301463,0,-14.03629709,0,119.698058 +136.2,50.32007719,-3.268851697,10000,-99.07809223,173.7422157,0,-14.03629709,0,119.6910321 +136.21,50.3200683,-3.268827339,10000,-99.04327652,173.7540621,0,-14.03629709,0,119.6840062 +136.22,50.32005941,-3.268802979,10000,-99.00846083,173.7661315,0,-14.03629709,0,119.6769802 +136.23,50.32005053,-3.268778617,10000,-98.98757136,173.7779779,0,-14.03629709,0,119.6699543 +136.24,50.32004164,-3.268754254,10000,-98.97016345,173.7898244,0,-14.03629709,0,119.6629284 +136.25,50.32003276,-3.268729889,10000,-98.94927396,173.8018937,0,-14.03629709,0,119.6559025 +136.26,50.32002388,-3.268705522,10000,-98.93534757,173.8137402,0,-14.03629709,0,119.6488765 +136.27,50.320015,-3.268681154,10000,-98.9283843,173.8258095,0,-14.03629709,0,119.6418506 +136.28,50.32000612,-3.268656784,10000,-98.91097637,173.8387705,0,-14.03629709,0,119.6348247 +136.29,50.31999724,-3.268632412,10000,-98.87616069,173.8517314,0,-14.03629709,0,119.6277988 +136.3,50.31998837,-3.268608038,10000,-98.84134499,173.8638008,0,-14.03629709,0,119.6207728 +136.31,50.3199795,-3.268583663,10000,-98.82045551,173.8756472,0,-14.03629709,0,119.613747 +136.32,50.31997063,-3.268559286,10000,-98.80304758,173.8877165,0,-14.03629709,0,119.606721 +136.33,50.31996176,-3.268534907,10000,-98.78215808,173.899563,0,-14.03629709,0,119.5996951 +136.34,50.3199529,-3.268510527,10000,-98.76475015,173.9114094,0,-14.03629709,0,119.5926692 +136.35,50.31994403,-3.268486145,10000,-98.74734223,173.9234787,0,-14.03629709,0,119.5856433 +136.36,50.31993517,-3.268461761,10000,-98.72645277,173.9353251,0,-14.03629709,0,119.5786173 +136.37,50.31992631,-3.268437376,10000,-98.70904485,173.9473944,0,-14.03629709,0,119.5715914 +136.38,50.31991745,-3.268412989,10000,-98.68815537,173.9603554,0,-14.03629709,0,119.5645655 +136.39,50.31990859,-3.2683886,10000,-98.65333966,173.9733163,0,-14.03629709,0,119.5575396 +136.4,50.31989974,-3.268364209,10000,-98.61852394,173.9851627,0,-14.03629709,0,119.5505136 +136.41,50.31989089,-3.268339817,10000,-98.60111601,173.9963404,0,-14.03629709,0,119.5434877 +136.42,50.31988204,-3.268315423,10000,-98.59763432,174.0081868,0,-14.03629709,0,119.5364618 +136.43,50.31987319,-3.268291028,10000,-98.59415262,174.0209248,0,-14.03629709,0,119.5294359 +136.44,50.31986434,-3.26826663,10000,-98.5767447,174.0329942,0,-14.03629709,0,119.5224099 +136.45,50.31985549,-3.268242231,10000,-98.541929,174.043726,0,-14.03629709,0,119.515384 +136.46,50.31984665,-3.268217831,10000,-98.50711329,174.0549037,0,-14.03629709,0,119.5083581 +136.47,50.31983781,-3.268193429,10000,-98.48622382,174.0678646,0,-14.03629709,0,119.5013322 +136.48,50.31982897,-3.268169025,10000,-98.46881591,174.0817172,0,-14.03629709,0,119.4943062 +136.49,50.31982013,-3.268144619,10000,-98.44792642,174.094901,0,-14.03629709,0,119.4872803 +136.5,50.3198113,-3.268120211,10000,-98.43051849,174.1067474,0,-14.03629709,0,119.4802544 +136.51,50.31980246,-3.268095802,10000,-98.409629,174.1177021,0,-14.03629709,0,119.4732285 +136.52,50.31979363,-3.268071391,10000,-98.3748133,174.1286569,0,-14.03629709,0,119.4662025 +136.53,50.3197848,-3.268046979,10000,-98.3399976,174.1402803,0,-14.03629709,0,119.4591766 +136.54,50.31977598,-3.268022565,10000,-98.32258969,174.1525725,0,-14.03629709,0,119.4521507 +136.55,50.31976715,-3.267998149,10000,-98.31910798,174.1650876,0,-14.03629709,0,119.4451248 +136.56,50.31975833,-3.267973732,10000,-98.31214472,174.1773798,0,-14.03629709,0,119.4380988 +136.57,50.3197495,-3.267949312,10000,-98.28429213,174.1892261,0,-14.03629709,0,119.4310729 +136.58,50.31974068,-3.267924892,10000,-98.2459949,174.2010725,0,-14.03629709,0,119.424047 +136.59,50.31973187,-3.267900469,10000,-98.22858697,174.2133647,0,-14.03629709,0,119.4170211 +136.6,50.31972305,-3.267876045,10000,-98.22510526,174.2258797,0,-14.03629709,0,119.4099951 +136.61,50.31971423,-3.267851619,10000,-98.20421577,174.2381719,0,-14.03629709,0,119.4029692 +136.62,50.31970542,-3.267827191,10000,-98.16940007,174.2500183,0,-14.03629709,0,119.3959434 +136.63,50.31969661,-3.267802762,10000,-98.13806593,174.2618646,0,-14.03629709,0,119.3889174 +136.64,50.3196878,-3.267778331,10000,-98.11369491,174.2739339,0,-14.03629709,0,119.3818915 +136.65,50.319679,-3.267753898,10000,-98.09628699,174.2857802,0,-14.03629709,0,119.3748656 +136.66,50.31967019,-3.267729464,10000,-98.07887907,174.2976265,0,-14.03629709,0,119.3678397 +136.67,50.31966139,-3.267705028,10000,-98.05798958,174.3096958,0,-14.03629709,0,119.3608137 +136.68,50.31965259,-3.26768059,10000,-98.04058165,174.3215421,0,-14.03629709,0,119.3537878 +136.69,50.31964379,-3.267656151,10000,-98.02317373,174.3333884,0,-14.03629709,0,119.3467619 +136.7,50.31963499,-3.26763171,10000,-98.00228426,174.3456806,0,-14.03629709,0,119.339736 +136.71,50.3196262,-3.267607267,10000,-97.98487634,174.3581956,0,-14.03629709,0,119.33271 +136.72,50.3196174,-3.267582823,10000,-97.96398685,174.3704878,0,-14.03629709,0,119.3256841 +136.73,50.31960861,-3.267558376,10000,-97.92917116,174.3823341,0,-14.03629709,0,119.3186582 +136.74,50.31959982,-3.267533929,10000,-97.89435547,174.3941804,0,-14.03629709,0,119.3116323 +136.75,50.31959104,-3.267509479,10000,-97.87694755,174.4062496,0,-14.03629709,0,119.3046063 +136.76,50.31958225,-3.267485028,10000,-97.87346584,174.4180959,0,-14.03629709,0,119.2975804 +136.77,50.31957347,-3.267460575,10000,-97.8665026,174.4301652,0,-14.03629709,0,119.2905545 +136.78,50.31956468,-3.267436121,10000,-97.83865001,174.4429031,0,-14.03629709,0,119.2835286 +136.79,50.3195559,-3.267411664,10000,-97.79687119,174.4549723,0,-14.03629709,0,119.2765026 +136.8,50.31954713,-3.267387206,10000,-97.76901859,174.4657041,0,-14.03629709,0,119.2694767 +136.81,50.31953835,-3.267362747,10000,-97.76205534,174.4768816,0,-14.03629709,0,119.2624508 +136.82,50.31952958,-3.267338286,10000,-97.7550921,174.4896196,0,-14.03629709,0,119.2554249 +136.83,50.3195208,-3.267313823,10000,-97.72723952,174.5025804,0,-14.03629709,0,119.2483989 +136.84,50.31951203,-3.267289358,10000,-97.68546071,174.5144267,0,-14.03629709,0,119.241373 +136.85,50.31950327,-3.267264892,10000,-97.65760812,174.5256043,0,-14.03629709,0,119.2343471 +136.86,50.3194945,-3.267240424,10000,-97.65064486,174.5372276,0,-14.03629709,0,119.2273212 +136.87,50.31948574,-3.267215955,10000,-97.64716316,174.5492968,0,-14.03629709,0,119.2202952 +136.88,50.31947697,-3.267191483,10000,-97.62975524,174.5611431,0,-14.03629709,0,119.2132693 +136.89,50.31946821,-3.267167011,10000,-97.59493954,174.5729894,0,-14.03629709,0,119.2062434 +136.9,50.31945945,-3.267142536,10000,-97.56012385,174.5852815,0,-14.03629709,0,119.1992175 +136.91,50.3194507,-3.26711806,10000,-97.53923438,174.5977965,0,-14.03629709,0,119.1921915 +136.92,50.31944194,-3.267093582,10000,-97.52182645,174.6100886,0,-14.03629709,0,119.1851656 +136.93,50.31943319,-3.267069102,10000,-97.50093698,174.6219348,0,-14.03629709,0,119.1781397 +136.94,50.31942444,-3.267044621,10000,-97.48352905,174.6337811,0,-14.03629709,0,119.1711138 +136.95,50.31941569,-3.267020138,10000,-97.46612113,174.6458503,0,-14.03629709,0,119.1640878 +136.96,50.31940694,-3.266995653,10000,-97.44523165,174.6576965,0,-14.03629709,0,119.1570619 +136.97,50.3193982,-3.266971167,10000,-97.42782373,174.6695428,0,-14.03629709,0,119.150036 +136.98,50.31938945,-3.266946679,10000,-97.41041583,174.6816119,0,-14.03629709,0,119.1430101 +136.99,50.31938071,-3.266922189,10000,-97.38604481,174.6934582,0,-14.03629709,0,119.1359841 +137,50.31937197,-3.266897698,10000,-97.35471066,174.7053044,0,-14.03629709,0,119.1289583 +137.01,50.31936323,-3.266873205,10000,-97.31989496,174.7173736,0,-14.03629709,0,119.1219324 +137.02,50.3193545,-3.26684871,10000,-97.29900549,174.7292198,0,-14.03629709,0,119.1149064 +137.03,50.31934577,-3.266824214,10000,-97.29552379,174.7410661,0,-14.03629709,0,119.1078805 +137.04,50.31933703,-3.266799716,10000,-97.27811586,174.7531352,0,-14.03629709,0,119.1008546 +137.05,50.3193283,-3.266775216,10000,-97.23981862,174.7649815,0,-14.03629709,0,119.0938287 +137.06,50.31931958,-3.266750715,10000,-97.21196604,174.7768277,0,-14.03629709,0,119.0868027 +137.07,50.31931085,-3.266726212,10000,-97.20500279,174.7888968,0,-14.03629709,0,119.0797768 +137.08,50.31930213,-3.266701707,10000,-97.19803953,174.800743,0,-14.03629709,0,119.0727509 +137.09,50.3192934,-3.266677201,10000,-97.17018694,174.8125893,0,-14.03629709,0,119.065725 +137.1,50.31928468,-3.266652693,10000,-97.13188969,174.8246584,0,-14.03629709,0,119.058699 +137.11,50.31927597,-3.266628183,10000,-97.11448177,174.8365046,0,-14.03629709,0,119.0516731 +137.12,50.31926725,-3.266603672,10000,-97.11100008,174.8483508,0,-14.03629709,0,119.0446472 +137.13,50.31925853,-3.266579159,10000,-97.09011061,174.86042,0,-14.03629709,0,119.0376213 +137.14,50.31924982,-3.266554644,10000,-97.05529492,174.8722662,0,-14.03629709,0,119.0305953 +137.15,50.31924111,-3.266530128,10000,-97.02396078,174.8841124,0,-14.03629709,0,119.0235694 +137.16,50.3192324,-3.26650561,10000,-96.99958976,174.8961815,0,-14.03629709,0,119.0165435 +137.17,50.3192237,-3.26648109,10000,-96.98218183,174.9080277,0,-14.03629709,0,119.0095176 +137.18,50.31921499,-3.266456569,10000,-96.96477392,174.9198739,0,-14.03629709,0,119.0024916 +137.19,50.31920629,-3.266432046,10000,-96.94388444,174.9317201,0,-14.03629709,0,118.9954657 +137.2,50.31919759,-3.266407521,10000,-96.92647652,174.9426746,0,-14.03629709,0,118.9884398 +137.21,50.31918889,-3.266382995,10000,-96.9090686,174.9536292,0,-14.03629709,0,118.9814139 +137.22,50.31918019,-3.266358468,10000,-96.88817913,174.9665899,0,-14.03629709,0,118.9743879 +137.23,50.3191715,-3.266333938,10000,-96.87077122,174.9804423,0,-14.03629709,0,118.967362 +137.24,50.3191628,-3.266309406,10000,-96.8533633,174.9925114,0,-14.03629709,0,118.9603361 +137.25,50.31915411,-3.266284873,10000,-96.82899228,175.003243,0,-14.03629709,0,118.9533102 +137.26,50.31914542,-3.266260339,10000,-96.8011397,175.0144205,0,-14.03629709,0,118.9462842 +137.27,50.31913673,-3.266235802,10000,-96.77676866,175.0260437,0,-14.03629709,0,118.9392583 +137.28,50.31912805,-3.266211265,10000,-96.75936073,175.0378899,0,-14.03629709,0,118.9322324 +137.29,50.31911936,-3.266186725,10000,-96.73847127,175.049959,0,-14.03629709,0,118.9252065 +137.3,50.31911068,-3.266162184,10000,-96.70365559,175.0615822,0,-14.03629709,0,118.9181805 +137.31,50.319102,-3.266137641,10000,-96.66883991,175.0729826,0,-14.03629709,0,118.9111547 +137.32,50.31909333,-3.266113097,10000,-96.65143199,175.0854975,0,-14.03629709,0,118.9041287 +137.33,50.31908465,-3.266088551,10000,-96.64795028,175.0986811,0,-14.03629709,0,118.8971028 +137.34,50.31907598,-3.266064002,10000,-96.64098702,175.1105272,0,-14.03629709,0,118.8900769 +137.35,50.3190673,-3.266039453,10000,-96.61313444,175.1214818,0,-14.03629709,0,118.883051 +137.36,50.31905863,-3.266014902,10000,-96.5748372,175.1333279,0,-14.03629709,0,118.876025 +137.37,50.31904997,-3.265990349,10000,-96.55742929,175.145397,0,-14.03629709,0,118.8689991 +137.38,50.3190413,-3.265965794,10000,-96.5539476,175.1570202,0,-14.03629709,0,118.8619732 +137.39,50.31903263,-3.265941239,10000,-96.53305813,175.1690892,0,-14.03629709,0,118.8549473 +137.4,50.31902397,-3.26591668,10000,-96.49824245,175.1809354,0,-14.03629709,0,118.8479213 +137.41,50.31901531,-3.265892121,10000,-96.4669083,175.191667,0,-14.03629709,0,118.8408954 +137.42,50.31900665,-3.26586756,10000,-96.44253726,175.2028444,0,-14.03629709,0,118.8338695 +137.43,50.318998,-3.265842998,10000,-96.42512934,175.2155821,0,-14.03629709,0,118.8268436 +137.44,50.31898934,-3.265818433,10000,-96.40772144,175.2285428,0,-14.03629709,0,118.8198177 +137.45,50.31898069,-3.265793867,10000,-96.38683198,175.2403889,0,-14.03629709,0,118.8127917 +137.46,50.31897204,-3.265769299,10000,-96.36942405,175.2515663,0,-14.03629709,0,118.8057658 +137.47,50.31896339,-3.26574473,10000,-96.35201613,175.2631895,0,-14.03629709,0,118.7987399 +137.48,50.31895474,-3.265720159,10000,-96.33112667,175.2752586,0,-14.03629709,0,118.791714 +137.49,50.3189461,-3.265695586,10000,-96.31371876,175.2871047,0,-14.03629709,0,118.784688 +137.5,50.31893745,-3.265671012,10000,-96.29282928,175.2989508,0,-14.03629709,0,118.7776621 +137.51,50.31892881,-3.265646436,10000,-96.2580136,175.3110198,0,-14.03629709,0,118.7706362 +137.52,50.31892017,-3.265621858,10000,-96.22319791,175.322643,0,-14.03629709,0,118.7636103 +137.53,50.31891154,-3.265597279,10000,-96.20230844,175.3338203,0,-14.03629709,0,118.7565843 +137.54,50.3189029,-3.265572698,10000,-96.18490053,175.3454435,0,-14.03629709,0,118.7495584 +137.55,50.31889427,-3.265548116,10000,-96.16401106,175.3575125,0,-14.03629709,0,118.7425325 +137.56,50.31888564,-3.265523531,10000,-96.15008469,175.3693586,0,-14.03629709,0,118.7355066 +137.57,50.31887701,-3.265498946,10000,-96.14312144,175.3812047,0,-14.03629709,0,118.7284806 +137.58,50.31886838,-3.265474358,10000,-96.12571354,175.3934966,0,-14.03629709,0,118.7214547 +137.59,50.31885975,-3.265449769,10000,-96.09089786,175.4060115,0,-14.03629709,0,118.7144288 +137.6,50.31885113,-3.265425178,10000,-96.05608217,175.4180804,0,-14.03629709,0,118.7074029 +137.61,50.31884251,-3.265400585,10000,-96.03867425,175.4290349,0,-14.03629709,0,118.7003769 +137.62,50.31883389,-3.265375991,10000,-96.03171099,175.4397664,0,-14.03629709,0,118.693351 +137.63,50.31882527,-3.265351396,10000,-96.01430307,175.4518354,0,-14.03629709,0,118.6863251 +137.64,50.31881665,-3.265326798,10000,-95.97948739,175.4645731,0,-14.03629709,0,118.6792992 +137.65,50.31880804,-3.265302199,10000,-95.94467172,175.4764192,0,-14.03629709,0,118.6722732 +137.66,50.31879943,-3.265277598,10000,-95.92726381,175.4875965,0,-14.03629709,0,118.6652474 +137.67,50.31879082,-3.265252996,10000,-95.92030055,175.4992196,0,-14.03629709,0,118.6582214 +137.68,50.31878221,-3.265228392,10000,-95.90637418,175.5112886,0,-14.03629709,0,118.6511955 +137.69,50.3187736,-3.265203786,10000,-95.88548471,175.5229117,0,-14.03629709,0,118.6441696 +137.7,50.318765,-3.265179179,10000,-95.86807679,175.5338662,0,-14.03629709,0,118.6371437 +137.71,50.31875639,-3.26515457,10000,-95.84718731,175.5448206,0,-14.03629709,0,118.6301177 +137.72,50.31874779,-3.26512996,10000,-95.81237164,175.5566666,0,-14.03629709,0,118.6230918 +137.73,50.31873919,-3.265105348,10000,-95.77755597,175.5696272,0,-14.03629709,0,118.6160659 +137.74,50.3187306,-3.265080734,10000,-95.75666651,175.5823649,0,-14.03629709,0,118.60904 +137.75,50.318722,-3.265056118,10000,-95.73925859,175.5935422,0,-14.03629709,0,118.602014 +137.76,50.31871341,-3.265031501,10000,-95.71836912,175.6042737,0,-14.03629709,0,118.5949881 +137.77,50.31870482,-3.265006883,10000,-95.70096121,175.6163426,0,-14.03629709,0,118.5879622 +137.78,50.31869623,-3.264982262,10000,-95.6835533,175.6290803,0,-14.03629709,0,118.5809363 +137.79,50.31868764,-3.26495764,10000,-95.66266383,175.6409263,0,-14.03629709,0,118.5739103 +137.8,50.31867906,-3.264933016,10000,-95.64525592,175.6521036,0,-14.03629709,0,118.5668844 +137.81,50.31867047,-3.264908391,10000,-95.62436645,175.6637267,0,-14.03629709,0,118.5598585 +137.82,50.31866189,-3.264883764,10000,-95.58955075,175.6757957,0,-14.03629709,0,118.5528326 +137.83,50.31865331,-3.264859135,10000,-95.55473507,175.6874188,0,-14.03629709,0,118.5458067 +137.84,50.31864474,-3.264834505,10000,-95.53732718,175.6983731,0,-14.03629709,0,118.5387807 +137.85,50.31863616,-3.264809873,10000,-95.53384549,175.7095504,0,-14.03629709,0,118.5317548 +137.86,50.31862759,-3.26478524,10000,-95.52688222,175.7220651,0,-14.03629709,0,118.5247289 +137.87,50.31861901,-3.264760605,10000,-95.49902964,175.7352486,0,-14.03629709,0,118.517703 +137.88,50.31861044,-3.264735967,10000,-95.45725086,175.7470946,0,-14.03629709,0,118.510677 +137.89,50.31860188,-3.264711329,10000,-95.42591674,175.757826,0,-14.03629709,0,118.5036511 +137.9,50.31859331,-3.264686689,10000,-95.40502727,175.7690033,0,-14.03629709,0,118.4966252 +137.91,50.31858475,-3.264662047,10000,-95.38413779,175.7804034,0,-14.03629709,0,118.4895993 +137.92,50.31857619,-3.264637404,10000,-95.37021144,175.7915807,0,-14.03629709,0,118.4825733 +137.93,50.31856763,-3.264612759,10000,-95.3632482,175.8034267,0,-14.03629709,0,118.4755474 +137.94,50.31855907,-3.264588113,10000,-95.34932184,175.8161643,0,-14.03629709,0,118.4685215 +137.95,50.31855051,-3.264563464,10000,-95.32843236,175.8282332,0,-14.03629709,0,118.4614956 +137.96,50.31854196,-3.264538814,10000,-95.30754289,175.8389646,0,-14.03629709,0,118.4544696 +137.97,50.3185334,-3.264514163,10000,-95.27620876,175.849919,0,-14.03629709,0,118.4474437 +137.98,50.31852485,-3.26448951,10000,-95.23791154,175.8617649,0,-14.03629709,0,118.4404178 +137.99,50.31851631,-3.264464855,10000,-95.22050363,175.8736109,0,-14.03629709,0,118.4333919 +138,50.31850776,-3.264440199,10000,-95.21702194,175.8856798,0,-14.03629709,0,118.426366 +138.01,50.31849921,-3.264415541,10000,-95.19613247,175.8986403,0,-14.03629709,0,118.4193401 +138.02,50.31849067,-3.264390881,10000,-95.16131679,175.9113779,0,-14.03629709,0,118.4123141 +138.03,50.31848213,-3.264366219,10000,-95.12998266,175.9223322,0,-14.03629709,0,118.4052882 +138.04,50.31847359,-3.264341556,10000,-95.10561165,175.9321719,0,-14.03629709,0,118.3982623 +138.05,50.31846506,-3.264316892,10000,-95.08820374,175.9429033,0,-14.03629709,0,118.3912364 +138.06,50.31845652,-3.264292226,10000,-95.07079583,175.9547493,0,-14.03629709,0,118.3842104 +138.07,50.31844799,-3.264267558,10000,-95.04990637,175.9665952,0,-14.03629709,0,118.3771845 +138.08,50.31843946,-3.264242889,10000,-95.03249846,175.9786641,0,-14.03629709,0,118.3701586 +138.09,50.31843093,-3.264218218,10000,-95.01509054,175.9914017,0,-14.03629709,0,118.3631327 +138.1,50.3184224,-3.264193545,10000,-94.99420107,176.0034705,0,-14.03629709,0,118.3561067 +138.11,50.31841388,-3.26416887,10000,-94.97679317,176.0142019,0,-14.03629709,0,118.3490808 +138.12,50.31840535,-3.264144195,10000,-94.95938525,176.0251561,0,-14.03629709,0,118.3420549 +138.13,50.31839683,-3.264119517,10000,-94.93501423,176.037225,0,-14.03629709,0,118.335029 +138.14,50.31838831,-3.264094838,10000,-94.90716166,176.0497397,0,-14.03629709,0,118.328003 +138.15,50.31837979,-3.264070157,10000,-94.88279066,176.0618085,0,-14.03629709,0,118.3209771 +138.16,50.31837128,-3.264045474,10000,-94.86538275,176.0727628,0,-14.03629709,0,118.3139512 +138.17,50.31836276,-3.26402079,10000,-94.84449329,176.0834941,0,-14.03629709,0,118.3069253 +138.18,50.31835425,-3.263996105,10000,-94.80967761,176.09534,0,-14.03629709,0,118.2998993 +138.19,50.31834574,-3.263971417,10000,-94.77486192,176.1074088,0,-14.03629709,0,118.2928734 +138.2,50.31833724,-3.263946728,10000,-94.75745401,176.1188089,0,-14.03629709,0,118.2858475 +138.21,50.31832873,-3.263922038,10000,-94.75397232,176.130209,0,-14.03629709,0,118.2788216 +138.22,50.31832023,-3.263897345,10000,-94.75049062,176.141832,0,-14.03629709,0,118.2717957 +138.23,50.31831172,-3.263872652,10000,-94.73308271,176.1536779,0,-14.03629709,0,118.2647697 +138.24,50.31830322,-3.263847956,10000,-94.69478548,176.1657467,0,-14.03629709,0,118.2577438 +138.25,50.31829472,-3.263823259,10000,-94.64952513,176.1773697,0,-14.03629709,0,118.2507179 +138.26,50.31828623,-3.26379856,10000,-94.62515412,176.1883239,0,-14.03629709,0,118.243692 +138.27,50.31827774,-3.26377386,10000,-94.62515399,176.1992781,0,-14.03629709,0,118.236666 +138.28,50.31826924,-3.263749158,10000,-94.61819074,176.211124,0,-14.03629709,0,118.2296401 +138.29,50.31826075,-3.263724455,10000,-94.5868566,176.2238615,0,-14.03629709,0,118.2226142 +138.3,50.31825226,-3.263699749,10000,-94.55204093,176.2359303,0,-14.03629709,0,118.2155883 +138.31,50.31824378,-3.263675042,10000,-94.53115149,176.2466616,0,-14.03629709,0,118.2085623 +138.32,50.31823529,-3.263650334,10000,-94.51374359,176.2576158,0,-14.03629709,0,118.2015365 +138.33,50.31822681,-3.263625624,10000,-94.49285411,176.2694617,0,-14.03629709,0,118.1945105 +138.34,50.31821833,-3.263600912,10000,-94.47544619,176.2810846,0,-14.03629709,0,118.1874846 +138.35,50.31820985,-3.263576199,10000,-94.45455673,176.2922618,0,-14.03629709,0,118.1804587 +138.36,50.31820137,-3.263551484,10000,-94.41974106,176.3041076,0,-14.03629709,0,118.1734328 +138.37,50.3181929,-3.263526768,10000,-94.38492539,176.3168451,0,-14.03629709,0,118.1664068 +138.38,50.31818443,-3.263502049,10000,-94.36751748,176.3289139,0,-14.03629709,0,118.1593809 +138.39,50.31817596,-3.263477329,10000,-94.36403578,176.3396452,0,-14.03629709,0,118.152355 +138.4,50.31816749,-3.263452608,10000,-94.36055408,176.3505993,0,-14.03629709,0,118.1453291 +138.41,50.31815902,-3.263427885,10000,-94.34314617,176.3624452,0,-14.03629709,0,118.1383031 +138.42,50.31815055,-3.26340316,10000,-94.30833051,176.3740681,0,-14.03629709,0,118.1312772 +138.43,50.31814209,-3.263378434,10000,-94.27351484,176.3850223,0,-14.03629709,0,118.1242513 +138.44,50.31813363,-3.263353706,10000,-94.25262538,176.3959765,0,-14.03629709,0,118.1172254 +138.45,50.31812517,-3.263328977,10000,-94.23521747,176.4075994,0,-14.03629709,0,118.1101994 +138.46,50.31811671,-3.263304246,10000,-94.21432801,176.419891,0,-14.03629709,0,118.1031735 +138.47,50.31810826,-3.263279513,10000,-94.1969201,176.4324056,0,-14.03629709,0,118.0961476 +138.48,50.3180998,-3.263254779,10000,-94.17603064,176.4444744,0,-14.03629709,0,118.0891217 +138.49,50.31809135,-3.263230042,10000,-94.14121497,176.4554285,0,-14.03629709,0,118.0820957 +138.5,50.3180829,-3.263205305,10000,-94.10639928,176.4659368,0,-14.03629709,0,118.0750698 +138.51,50.31807446,-3.263180566,10000,-94.08899136,176.4771139,0,-14.03629709,0,118.0680439 +138.52,50.31806601,-3.263155825,10000,-94.08550967,176.4887368,0,-14.03629709,0,118.061018 +138.53,50.31805757,-3.263131083,10000,-94.07854644,176.5005826,0,-14.03629709,0,118.053992 +138.54,50.31804912,-3.263106339,10000,-94.05069388,176.5126513,0,-14.03629709,0,118.0469661 +138.55,50.31804068,-3.263081593,10000,-94.0089151,176.5244971,0,-14.03629709,0,118.0399402 +138.56,50.31803225,-3.263056846,10000,-93.98106255,176.53612,0,-14.03629709,0,118.0329143 +138.57,50.31802381,-3.263032097,10000,-93.97409932,176.5475199,0,-14.03629709,0,118.0258883 +138.58,50.31801538,-3.263007346,10000,-93.96713605,176.5589199,0,-14.03629709,0,118.0188624 +138.59,50.31800694,-3.262982595,10000,-93.93928346,176.5709886,0,-14.03629709,0,118.0118365 +138.6,50.31799851,-3.26295784,10000,-93.89750467,176.5828344,0,-14.03629709,0,118.0048106 +138.61,50.31799009,-3.262933085,10000,-93.86965212,176.5933427,0,-14.03629709,0,117.9977847 +138.62,50.31798166,-3.262908328,10000,-93.86268888,176.603628,0,-14.03629709,0,117.9907587 +138.63,50.31797324,-3.26288357,10000,-93.85920719,176.615028,0,-14.03629709,0,117.9837328 +138.64,50.31796481,-3.26285881,10000,-93.84179928,176.6270967,0,-14.03629709,0,117.9767069 +138.65,50.31795639,-3.262834048,10000,-93.80698361,176.6389425,0,-14.03629709,0,117.969681 +138.66,50.31794797,-3.262809285,10000,-93.77216793,176.6507882,0,-14.03629709,0,117.962655 +138.67,50.31793956,-3.26278452,10000,-93.75127847,176.662634,0,-14.03629709,0,117.9556292 +138.68,50.31793114,-3.262759753,10000,-93.73387057,176.6735881,0,-14.03629709,0,117.9486032 +138.69,50.31792273,-3.262734985,10000,-93.71298112,176.6843192,0,-14.03629709,0,117.9415773 +138.7,50.31791432,-3.262710216,10000,-93.69557322,176.696165,0,-14.03629709,0,117.9345514 +138.71,50.31790591,-3.262685444,10000,-93.67468375,176.7082337,0,-14.03629709,0,117.9275255 +138.72,50.3178975,-3.262660671,10000,-93.63986807,176.7196336,0,-14.03629709,0,117.9204995 +138.73,50.3178891,-3.262635897,10000,-93.6050524,176.7310335,0,-14.03629709,0,117.9134736 +138.74,50.3178807,-3.26261112,10000,-93.58764452,176.7426563,0,-14.03629709,0,117.9064477 +138.75,50.3178723,-3.262586343,10000,-93.58416283,176.7542791,0,-14.03629709,0,117.8994218 +138.76,50.3178639,-3.262561563,10000,-93.58068112,176.765679,0,-14.03629709,0,117.8923958 +138.77,50.3178555,-3.262536782,10000,-93.56327321,176.776856,0,-14.03629709,0,117.8853699 +138.78,50.3178471,-3.262512,10000,-93.52845755,176.7882559,0,-14.03629709,0,117.878344 +138.79,50.31783871,-3.262487215,10000,-93.49364188,176.7998787,0,-14.03629709,0,117.8713181 +138.8,50.31783032,-3.26246243,10000,-93.47275241,176.8115015,0,-14.03629709,0,117.8642921 +138.81,50.31782193,-3.262437642,10000,-93.4553445,176.8229014,0,-14.03629709,0,117.8572662 +138.82,50.31781354,-3.262412853,10000,-93.43445505,176.8340784,0,-14.03629709,0,117.8502403 +138.83,50.31780516,-3.262388063,10000,-93.41704716,176.8454783,0,-14.03629709,0,117.8432144 +138.84,50.31779677,-3.26236327,10000,-93.39615771,176.8571011,0,-14.03629709,0,117.8361884 +138.85,50.31778839,-3.262338477,10000,-93.36134203,176.8689468,0,-14.03629709,0,117.8291625 +138.86,50.31778001,-3.262313681,10000,-93.32652636,176.8810154,0,-14.03629709,0,117.8221366 +138.87,50.31777164,-3.262288884,10000,-93.30911845,176.8926382,0,-14.03629709,0,117.8151107 +138.88,50.31776326,-3.262264085,10000,-93.3021552,176.9035922,0,-14.03629709,0,117.8080847 +138.89,50.31775489,-3.262239285,10000,-93.28474731,176.9143233,0,-14.03629709,0,117.8010588 +138.9,50.31774651,-3.262214483,10000,-93.2534132,176.9252773,0,-14.03629709,0,117.7940329 +138.91,50.31773815,-3.26218968,10000,-93.22904218,176.9369001,0,-14.03629709,0,117.787007 +138.92,50.31772978,-3.262164875,10000,-93.21511583,176.9489687,0,-14.03629709,0,117.779981 +138.93,50.31772141,-3.262140068,10000,-93.19074481,176.9605914,0,-14.03629709,0,117.7729551 +138.94,50.31771305,-3.26211526,10000,-93.1594107,176.9715455,0,-14.03629709,0,117.7659292 +138.95,50.31770469,-3.26209045,10000,-93.1420028,176.9824995,0,-14.03629709,0,117.7589033 +138.96,50.31769633,-3.262065639,10000,-93.13503956,176.9941222,0,-14.03629709,0,117.7518773 +138.97,50.31768797,-3.262040826,10000,-93.12111321,177.0061908,0,-14.03629709,0,117.7448514 +138.98,50.31767961,-3.262016011,10000,-93.10022375,177.0178136,0,-14.03629709,0,117.7378255 +138.99,50.31767126,-3.261991195,10000,-93.07933429,177.0287675,0,-14.03629709,0,117.7307996 +139,50.3176629,-3.261966377,10000,-93.04800017,177.0397215,0,-14.03629709,0,117.7237736 +139.01,50.31765455,-3.261941558,10000,-93.00970296,177.0513443,0,-14.03629709,0,117.7167478 +139.02,50.31764621,-3.261916737,10000,-92.99229506,177.0634128,0,-14.03629709,0,117.7097219 +139.03,50.31763786,-3.261891914,10000,-92.98881336,177.0750356,0,-14.03629709,0,117.7026959 +139.04,50.31762951,-3.26186709,10000,-92.96792391,177.0859896,0,-14.03629709,0,117.69567 +139.05,50.31762117,-3.261842264,10000,-92.93310824,177.0969435,0,-14.03629709,0,117.6886441 +139.06,50.31761283,-3.261817437,10000,-92.90177413,177.1085663,0,-14.03629709,0,117.6816182 +139.07,50.31760449,-3.261792608,10000,-92.87740313,177.1204119,0,-14.03629709,0,117.6745922 +139.08,50.31759616,-3.261767777,10000,-92.85999522,177.1313658,0,-14.03629709,0,117.6675663 +139.09,50.31758782,-3.261742945,10000,-92.84258732,177.1420969,0,-14.03629709,0,117.6605404 +139.1,50.31757949,-3.261718112,10000,-92.82169786,177.1539425,0,-14.03629709,0,117.6535145 +139.11,50.31757116,-3.261693276,10000,-92.80428996,177.1657881,0,-14.03629709,0,117.6464885 +139.12,50.31756283,-3.261668439,10000,-92.78688207,177.1765192,0,-14.03629709,0,117.6394626 +139.13,50.3175545,-3.261643601,10000,-92.76599261,177.1874731,0,-14.03629709,0,117.6324367 +139.14,50.31754618,-3.261618761,10000,-92.74858471,177.1993187,0,-14.03629709,0,117.6254108 +139.15,50.31753785,-3.261593919,10000,-92.72769525,177.2109414,0,-14.03629709,0,117.6183848 +139.16,50.31752953,-3.261569076,10000,-92.69287958,177.2218954,0,-14.03629709,0,117.6113589 +139.17,50.31752121,-3.261544231,10000,-92.65806393,177.2328493,0,-14.03629709,0,117.604333 +139.18,50.3175129,-3.261519385,10000,-92.63717448,177.2446949,0,-14.03629709,0,117.5973071 +139.19,50.31750458,-3.261494537,10000,-92.61976656,177.2574322,0,-14.03629709,0,117.5902811 +139.2,50.31749627,-3.261469687,10000,-92.59887709,177.2695007,0,-14.03629709,0,117.5832552 +139.21,50.31748796,-3.261444835,10000,-92.58495075,177.2802317,0,-14.03629709,0,117.5762293 +139.22,50.31747965,-3.261419983,10000,-92.57798753,177.2909627,0,-14.03629709,0,117.5692034 +139.23,50.31747134,-3.261395128,10000,-92.56057964,177.3019166,0,-14.03629709,0,117.5621774 +139.24,50.31746303,-3.261370272,10000,-92.52576397,177.3124247,0,-14.03629709,0,117.5551515 +139.25,50.31745473,-3.261345415,10000,-92.49094829,177.3233786,0,-14.03629709,0,117.5481256 +139.26,50.31744643,-3.261320556,10000,-92.47005883,177.3352241,0,-14.03629709,0,117.5410997 +139.27,50.31743813,-3.261295695,10000,-92.45265093,177.3470697,0,-14.03629709,0,117.5340737 +139.28,50.31742983,-3.261270833,10000,-92.43176148,177.3589153,0,-14.03629709,0,117.5270478 +139.29,50.31742154,-3.261245969,10000,-92.41435359,177.3707608,0,-14.03629709,0,117.5200219 +139.3,50.31741324,-3.261221103,10000,-92.39694569,177.3817147,0,-14.03629709,0,117.512996 +139.31,50.31740495,-3.261196236,10000,-92.37257468,177.3924457,0,-14.03629709,0,117.50597 +139.32,50.31739666,-3.261171368,10000,-92.34472211,177.4042913,0,-14.03629709,0,117.4989441 +139.33,50.31738837,-3.261146497,10000,-92.32035111,177.4161368,0,-14.03629709,0,117.4919182 +139.34,50.31738009,-3.261121625,10000,-92.30294323,177.4268678,0,-14.03629709,0,117.4848923 +139.35,50.3173718,-3.261096752,10000,-92.28553532,177.4375987,0,-14.03629709,0,117.4778663 +139.36,50.31736352,-3.261071877,10000,-92.2611643,177.4485526,0,-14.03629709,0,117.4708405 +139.37,50.31735524,-3.261047,10000,-92.23331174,177.4592835,0,-14.03629709,0,117.4638145 +139.38,50.31734696,-3.261022123,10000,-92.20894075,177.4709061,0,-14.03629709,0,117.4567886 +139.39,50.31733869,-3.260997243,10000,-92.19153286,177.4831975,0,-14.03629709,0,117.4497627 +139.4,50.31733041,-3.260972361,10000,-92.17412496,177.4945972,0,-14.03629709,0,117.4427368 +139.41,50.31732214,-3.260947479,10000,-92.1532355,177.5055511,0,-14.03629709,0,117.4357108 +139.42,50.31731387,-3.260922594,10000,-92.13582759,177.5167278,0,-14.03629709,0,117.4286849 +139.43,50.3173056,-3.260897708,10000,-92.11493813,177.5281275,0,-14.03629709,0,117.421659 +139.44,50.31729733,-3.260872821,10000,-92.08012248,177.5401959,0,-14.03629709,0,117.4146331 +139.45,50.31728907,-3.260847931,10000,-92.04530683,177.5520415,0,-14.03629709,0,117.4076072 +139.46,50.31728081,-3.26082304,10000,-92.02789894,177.5625494,0,-14.03629709,0,117.4005812 +139.47,50.31727255,-3.260798148,10000,-92.02093569,177.5728345,0,-14.03629709,0,117.3935553 +139.48,50.31726429,-3.260773254,10000,-92.00700933,177.5842342,0,-14.03629709,0,117.3865294 +139.49,50.31725603,-3.260748359,10000,-91.98611988,177.5960797,0,-14.03629709,0,117.3795035 +139.5,50.31724778,-3.260723461,10000,-91.96871198,177.6070335,0,-14.03629709,0,117.3724775 +139.51,50.31723952,-3.260698563,10000,-91.94782253,177.6177644,0,-14.03629709,0,117.3654516 +139.52,50.31723127,-3.260673663,10000,-91.91300686,177.6296099,0,-14.03629709,0,117.3584257 +139.53,50.31722302,-3.260648761,10000,-91.8781912,177.6414554,0,-14.03629709,0,117.3513998 +139.54,50.31721478,-3.260623857,10000,-91.85730176,177.6521863,0,-14.03629709,0,117.3443738 +139.55,50.31720653,-3.260598953,10000,-91.83989386,177.6631401,0,-14.03629709,0,117.3373479 +139.56,50.31719829,-3.260574046,10000,-91.81900441,177.6749855,0,-14.03629709,0,117.330322 +139.57,50.31719005,-3.260549138,10000,-91.80159651,177.6866081,0,-14.03629709,0,117.3232961 +139.58,50.31718181,-3.260524228,10000,-91.78418861,177.6975619,0,-14.03629709,0,117.3162701 +139.59,50.31717357,-3.260499317,10000,-91.76329916,177.7085157,0,-14.03629709,0,117.3092442 +139.6,50.31716534,-3.260474404,10000,-91.74589128,177.7201382,0,-14.03629709,0,117.3022183 +139.61,50.3171571,-3.26044949,10000,-91.72500184,177.7319837,0,-14.03629709,0,117.2951924 +139.62,50.31714887,-3.260424573,10000,-91.69018619,177.7429375,0,-14.03629709,0,117.2881664 +139.63,50.31714064,-3.260399656,10000,-91.65537051,177.7534454,0,-14.03629709,0,117.2811405 +139.64,50.31713242,-3.260374737,10000,-91.63448104,177.7646221,0,-14.03629709,0,117.2741146 +139.65,50.31712419,-3.260349816,10000,-91.61707314,177.7760217,0,-14.03629709,0,117.2670887 +139.66,50.31711597,-3.260324894,10000,-91.5961837,177.7869754,0,-14.03629709,0,117.2600627 +139.67,50.31710775,-3.26029997,10000,-91.58225736,177.7979292,0,-14.03629709,0,117.2530369 +139.68,50.31709953,-3.260275045,10000,-91.57529412,177.8095517,0,-14.03629709,0,117.2460109 +139.69,50.31709131,-3.260250118,10000,-91.55788622,177.8213972,0,-14.03629709,0,117.238985 +139.7,50.31708309,-3.260225189,10000,-91.52307056,177.8323509,0,-14.03629709,0,117.2319591 +139.71,50.31707488,-3.260200259,10000,-91.4882549,177.8428588,0,-14.03629709,0,117.2249332 +139.72,50.31706667,-3.260175328,10000,-91.47084702,177.8540355,0,-14.03629709,0,117.2179072 +139.73,50.31705846,-3.260150394,10000,-91.46388379,177.865658,0,-14.03629709,0,117.2108813 +139.74,50.31705025,-3.26012546,10000,-91.44647588,177.8772805,0,-14.03629709,0,117.2038554 +139.75,50.31704204,-3.260100523,10000,-91.41166021,177.8886801,0,-14.03629709,0,117.1968295 +139.76,50.31703384,-3.260075585,10000,-91.37684454,177.8998567,0,-14.03629709,0,117.1898035 +139.77,50.31702564,-3.260050646,10000,-91.35943665,177.9112563,0,-14.03629709,0,117.1827776 +139.78,50.31701744,-3.260025704,10000,-91.35247343,177.9226558,0,-14.03629709,0,117.1757517 +139.79,50.31700924,-3.260000762,10000,-91.33506553,177.9336096,0,-14.03629709,0,117.1687258 +139.8,50.31700104,-3.259975817,10000,-91.30024986,177.9445633,0,-14.03629709,0,117.1616998 +139.81,50.31699285,-3.259950872,10000,-91.2654342,177.9559628,0,-14.03629709,0,117.1546739 +139.82,50.31698466,-3.259925924,10000,-91.24802631,177.9671394,0,-14.03629709,0,117.147648 +139.83,50.31697647,-3.259900975,10000,-91.24106308,177.9774244,0,-14.03629709,0,117.1406221 +139.84,50.31696828,-3.259876025,10000,-91.22365518,177.9877093,0,-14.03629709,0,117.1335962 +139.85,50.31696009,-3.259851073,10000,-91.18883951,177.9991089,0,-14.03629709,0,117.1265702 +139.86,50.31695191,-3.25982612,10000,-91.15402387,178.0109542,0,-14.03629709,0,117.1195443 +139.87,50.31694373,-3.259801164,10000,-91.13661597,178.0221308,0,-14.03629709,0,117.1125184 +139.88,50.31693555,-3.259776208,10000,-91.12965272,178.0335304,0,-14.03629709,0,117.1054925 +139.89,50.31692737,-3.25975125,10000,-91.11572638,178.0458216,0,-14.03629709,0,117.0984665 +139.9,50.31691919,-3.259726289,10000,-91.09483694,178.0572211,0,-14.03629709,0,117.0914406 +139.91,50.31691102,-3.259701328,10000,-91.0739475,178.0670602,0,-14.03629709,0,117.0844147 +139.92,50.31690284,-3.259676365,10000,-91.04261338,178.0771222,0,-14.03629709,0,117.0773888 +139.93,50.31689467,-3.259651401,10000,-91.00431616,178.0887446,0,-14.03629709,0,117.0703628 +139.94,50.31688651,-3.259626435,10000,-90.98690828,178.1014816,0,-14.03629709,0,117.0633369 +139.95,50.31687834,-3.259601467,10000,-90.9834266,178.1135499,0,-14.03629709,0,117.056311 +139.96,50.31687017,-3.259576497,10000,-90.96253716,178.1242806,0,-14.03629709,0,117.0492851 +139.97,50.31686201,-3.259551527,10000,-90.9277215,178.1350114,0,-14.03629709,0,117.0422591 +139.98,50.31685385,-3.259526554,10000,-90.8963874,178.145965,0,-14.03629709,0,117.0352332 +139.99,50.31684569,-3.25950158,10000,-90.87201639,178.1564728,0,-14.03629709,0,117.0282073 +140,50.31683754,-3.259476605,10000,-90.8546085,178.1672035,0,-14.03629709,0,117.0211814 +140.01,50.31682938,-3.259451628,10000,-90.8372006,178.1781572,0,-14.03629709,0,117.0141554 +140.02,50.31682123,-3.259426649,10000,-90.81631115,178.1888879,0,-14.03629709,0,117.0071296 +140.03,50.31681308,-3.25940167,10000,-90.79890326,178.2005103,0,-14.03629709,0,117.0001036 +140.04,50.31680493,-3.259376688,10000,-90.78149539,178.2128015,0,-14.03629709,0,116.9930777 +140.05,50.31679678,-3.259351704,10000,-90.76060594,178.2242009,0,-14.03629709,0,116.9860518 +140.06,50.31678864,-3.25932672,10000,-90.74319803,178.2351546,0,-14.03629709,0,116.9790259 +140.07,50.31678049,-3.259301733,10000,-90.72230858,178.2461082,0,-14.03629709,0,116.9719999 +140.08,50.31677235,-3.259276745,10000,-90.68749293,178.2566159,0,-14.03629709,0,116.964974 +140.09,50.31676421,-3.259251756,10000,-90.65267728,178.2673466,0,-14.03629709,0,116.9579481 +140.1,50.31675608,-3.259226765,10000,-90.63178783,178.2783002,0,-14.03629709,0,116.9509222 +140.11,50.31674794,-3.259201772,10000,-90.61437993,178.2890309,0,-14.03629709,0,116.9438962 +140.12,50.31673981,-3.259176779,10000,-90.59349049,178.3008762,0,-14.03629709,0,116.9368703 +140.13,50.31673168,-3.259151783,10000,-90.57956415,178.3136132,0,-14.03629709,0,116.9298444 +140.14,50.31672355,-3.259126785,10000,-90.57260091,178.3245668,0,-14.03629709,0,116.9228185 +140.15,50.31671542,-3.259101786,10000,-90.55519303,178.3341828,0,-14.03629709,0,116.9157925 +140.16,50.31670729,-3.259076787,10000,-90.52037737,178.3451364,0,-14.03629709,0,116.9087666 +140.17,50.31669917,-3.259051784,10000,-90.48556171,178.3569817,0,-14.03629709,0,116.9017407 +140.18,50.31669105,-3.259026781,10000,-90.46467226,178.3683811,0,-14.03629709,0,116.8947148 +140.19,50.31668293,-3.259001776,10000,-90.44726437,178.3795576,0,-14.03629709,0,116.8876888 +140.2,50.31667481,-3.258976769,10000,-90.42637493,178.3902883,0,-14.03629709,0,116.8806629 +140.21,50.3166667,-3.258951761,10000,-90.40896704,178.400796,0,-14.03629709,0,116.873637 +140.22,50.31665858,-3.258926752,10000,-90.39155915,178.4117496,0,-14.03629709,0,116.8666111 +140.23,50.31665047,-3.25890174,10000,-90.36718814,178.4224802,0,-14.03629709,0,116.8595852 +140.24,50.31664236,-3.258876728,10000,-90.33933559,178.4332108,0,-14.03629709,0,116.8525592 +140.25,50.31663425,-3.258851714,10000,-90.31496461,178.445279,0,-14.03629709,0,116.8455333 +140.26,50.31662615,-3.258826698,10000,-90.29755672,178.457793,0,-14.03629709,0,116.8385074 +140.27,50.31661804,-3.25880168,10000,-90.28014883,178.4687466,0,-14.03629709,0,116.8314815 +140.28,50.31660994,-3.258776661,10000,-90.25577783,178.4785855,0,-14.03629709,0,116.8244555 +140.29,50.31660184,-3.258751641,10000,-90.22792527,178.4893161,0,-14.03629709,0,116.8174296 +140.3,50.31659374,-3.258726619,10000,-90.20355427,178.5009384,0,-14.03629709,0,116.8104037 +140.31,50.31658565,-3.258701595,10000,-90.18614639,178.511669,0,-14.03629709,0,116.8033778 +140.32,50.31657755,-3.25867657,10000,-90.1687385,178.5217309,0,-14.03629709,0,116.7963518 +140.33,50.31656946,-3.258651544,10000,-90.1443675,178.5331302,0,-14.03629709,0,116.7893259 +140.34,50.31656137,-3.258626516,10000,-90.11651495,178.5454213,0,-14.03629709,0,116.7823 +140.35,50.31655328,-3.258601485,10000,-90.09214395,178.5568206,0,-14.03629709,0,116.7752741 +140.36,50.3165452,-3.258576455,10000,-90.07473607,178.5677742,0,-14.03629709,0,116.7682481 +140.37,50.31653711,-3.258551421,10000,-90.05732819,178.5787277,0,-14.03629709,0,116.7612223 +140.38,50.31652903,-3.258526387,10000,-90.03295719,178.5890124,0,-14.03629709,0,116.7541963 +140.39,50.31652095,-3.258501351,10000,-90.00510463,178.5992971,0,-14.03629709,0,116.7471704 +140.4,50.31651287,-3.258476314,10000,-89.98073362,178.6106965,0,-14.03629709,0,116.7401445 +140.41,50.3165048,-3.258451275,10000,-89.96332574,178.6225417,0,-14.03629709,0,116.7331186 +140.42,50.31649672,-3.258426234,10000,-89.94591787,178.6334952,0,-14.03629709,0,116.7260926 +140.43,50.31648865,-3.258401192,10000,-89.92502843,178.6440028,0,-14.03629709,0,116.7190667 +140.44,50.31648058,-3.258376149,10000,-89.90762053,178.6549563,0,-14.03629709,0,116.7120408 +140.45,50.31647251,-3.258351103,10000,-89.88673107,178.6659098,0,-14.03629709,0,116.7050149 +140.46,50.31646444,-3.258326057,10000,-89.85191541,178.6773091,0,-14.03629709,0,116.6979889 +140.47,50.31645638,-3.258301009,10000,-89.81709976,178.6896001,0,-14.03629709,0,116.690963 +140.48,50.31644832,-3.258275958,10000,-89.79969188,178.7009994,0,-14.03629709,0,116.6839371 +140.49,50.31644026,-3.258250907,10000,-89.79272865,178.7108383,0,-14.03629709,0,116.6769112 +140.5,50.3164322,-3.258225854,10000,-89.77880233,178.7209,0,-14.03629709,0,116.6698852 +140.51,50.31642414,-3.2582008,10000,-89.75791289,178.7322993,0,-14.03629709,0,116.6628593 +140.52,50.31641609,-3.258175744,10000,-89.740505,178.7441445,0,-14.03629709,0,116.6558334 +140.53,50.31640803,-3.258150686,10000,-89.71961555,178.754875,0,-14.03629709,0,116.6488075 +140.54,50.31639998,-3.258125627,10000,-89.68479989,178.7647139,0,-14.03629709,0,116.6417815 +140.55,50.31639193,-3.258100567,10000,-89.64998424,178.7754444,0,-14.03629709,0,116.6347556 +140.56,50.31638389,-3.258075505,10000,-89.6290948,178.7872895,0,-14.03629709,0,116.6277297 +140.57,50.31637584,-3.258050441,10000,-89.6116869,178.7989117,0,-14.03629709,0,116.6207038 +140.58,50.3163678,-3.258025376,10000,-89.59079746,178.8098652,0,-14.03629709,0,116.6136778 +140.59,50.31635976,-3.258000309,10000,-89.57338957,178.8205957,0,-14.03629709,0,116.6066519 +140.6,50.31635172,-3.257975241,10000,-89.55598168,178.8313262,0,-14.03629709,0,116.599626 +140.61,50.31634368,-3.257950171,10000,-89.53509225,178.8420567,0,-14.03629709,0,116.5926001 +140.62,50.31633565,-3.2579251,10000,-89.51768438,178.8530101,0,-14.03629709,0,116.5855742 +140.63,50.31632761,-3.257900027,10000,-89.49679494,178.8646323,0,-14.03629709,0,116.5785482 +140.64,50.31631958,-3.257874953,10000,-89.46197928,178.8764774,0,-14.03629709,0,116.5715223 +140.65,50.31631155,-3.257849876,10000,-89.42716362,178.8872079,0,-14.03629709,0,116.5644964 +140.66,50.31630353,-3.257824799,10000,-89.40627418,178.8968237,0,-14.03629709,0,116.5574705 +140.67,50.3162955,-3.25779972,10000,-89.38886629,178.9068854,0,-14.03629709,0,116.5504445 +140.68,50.31628748,-3.25777464,10000,-89.36797685,178.9182847,0,-14.03629709,0,116.5434187 +140.69,50.31627946,-3.257749558,10000,-89.35056896,178.9303527,0,-14.03629709,0,116.5363927 +140.7,50.31627144,-3.257724474,10000,-89.33316107,178.9419748,0,-14.03629709,0,116.5293668 +140.71,50.31626342,-3.257699389,10000,-89.31227163,178.9529282,0,-14.03629709,0,116.5223409 +140.72,50.31625541,-3.257674302,10000,-89.29486375,178.9636587,0,-14.03629709,0,116.515315 +140.73,50.31624739,-3.257649214,10000,-89.27745587,178.9741662,0,-14.03629709,0,116.508289 +140.74,50.31623938,-3.257624124,10000,-89.25308488,178.9842279,0,-14.03629709,0,116.5012631 +140.75,50.31623137,-3.257599033,10000,-89.22523233,178.9945125,0,-14.03629709,0,116.4942372 +140.76,50.31622336,-3.257573941,10000,-89.20086133,179.0056888,0,-14.03629709,0,116.4872113 +140.77,50.31621536,-3.257548846,10000,-89.18345344,179.0173109,0,-14.03629709,0,116.4801853 +140.78,50.31620735,-3.257523751,10000,-89.16256401,179.0289331,0,-14.03629709,0,116.4731594 +140.79,50.31619935,-3.257498653,10000,-89.12774837,179.0401093,0,-14.03629709,0,116.4661335 +140.8,50.31619135,-3.257473554,10000,-89.09293272,179.0506168,0,-14.03629709,0,116.4591076 +140.81,50.31618336,-3.257448454,10000,-89.07204326,179.0615702,0,-14.03629709,0,116.4520816 +140.82,50.31617536,-3.257423352,10000,-89.05463537,179.0731923,0,-14.03629709,0,116.4450557 +140.83,50.31616737,-3.257398248,10000,-89.03374594,179.0839227,0,-14.03629709,0,116.4380298 +140.84,50.31615938,-3.257373143,10000,-89.01981962,179.0937614,0,-14.03629709,0,116.4310039 +140.85,50.31615139,-3.257348037,10000,-89.01285639,179.1044918,0,-14.03629709,0,116.4239779 +140.86,50.3161434,-3.257322929,10000,-88.9954485,179.1163369,0,-14.03629709,0,116.416952 +140.87,50.31613541,-3.257297819,10000,-88.96063284,179.127959,0,-14.03629709,0,116.4099261 +140.88,50.31612743,-3.257272708,10000,-88.9258172,179.1386893,0,-14.03629709,0,116.4029002 +140.89,50.31611945,-3.257247595,10000,-88.90840932,179.148751,0,-14.03629709,0,116.3958742 +140.9,50.31611147,-3.257222481,10000,-88.90144609,179.1590355,0,-14.03629709,0,116.3888483 +140.91,50.31610349,-3.257197366,10000,-88.88403822,179.1699888,0,-14.03629709,0,116.3818224 +140.92,50.31609551,-3.257172248,10000,-88.84922257,179.1807192,0,-14.03629709,0,116.3747965 +140.93,50.31608754,-3.25714713,10000,-88.81440689,179.1912267,0,-14.03629709,0,116.3677705 +140.94,50.31607957,-3.25712201,10000,-88.796999,179.2024029,0,-14.03629709,0,116.3607446 +140.95,50.3160716,-3.257096888,10000,-88.79003578,179.213802,0,-14.03629709,0,116.3537187 +140.96,50.31606363,-3.257071765,10000,-88.77262791,179.2249782,0,-14.03629709,0,116.3466928 +140.97,50.31605566,-3.25704664,10000,-88.73781227,179.2366003,0,-14.03629709,0,116.3396668 +140.98,50.3160477,-3.257021514,10000,-88.70299661,179.2484453,0,-14.03629709,0,116.3326409 +140.99,50.31603974,-3.256996385,10000,-88.68558872,179.2591756,0,-14.03629709,0,116.325615 +141,50.31603178,-3.256971256,10000,-88.6786255,179.2687914,0,-14.03629709,0,116.3185891 +141.01,50.31602382,-3.256946125,10000,-88.66121762,179.27863,0,-14.03629709,0,116.3115631 +141.02,50.31601586,-3.256920993,10000,-88.62640197,179.2891374,0,-14.03629709,0,116.3045372 +141.03,50.31600791,-3.256895859,10000,-88.59158631,179.3000907,0,-14.03629709,0,116.2975114 +141.04,50.31599996,-3.256870724,10000,-88.57417843,179.3117127,0,-14.03629709,0,116.2904854 +141.05,50.31599201,-3.256845587,10000,-88.56721521,179.3235577,0,-14.03629709,0,116.2834595 +141.06,50.31598406,-3.256820448,10000,-88.55328888,179.334288,0,-14.03629709,0,116.2764336 +141.07,50.31597611,-3.256795308,10000,-88.53239945,179.3441266,0,-14.03629709,0,116.2694077 +141.08,50.31596817,-3.256770167,10000,-88.51151001,179.354857,0,-14.03629709,0,116.2623817 +141.09,50.31596022,-3.256745024,10000,-88.48017591,179.366479,0,-14.03629709,0,116.2553558 +141.1,50.31595228,-3.256719879,10000,-88.43839716,179.3774322,0,-14.03629709,0,116.2483299 +141.11,50.31594435,-3.256694733,10000,-88.41054462,179.3879396,0,-14.03629709,0,116.241304 +141.12,50.31593641,-3.256669586,10000,-88.4035814,179.3991158,0,-14.03629709,0,116.234278 +141.13,50.31592848,-3.256644436,10000,-88.40009972,179.4105148,0,-14.03629709,0,116.2272521 +141.14,50.31592054,-3.256619286,10000,-88.38269182,179.4212451,0,-14.03629709,0,116.2202262 +141.15,50.31591261,-3.256594133,10000,-88.34787618,179.4313067,0,-14.03629709,0,116.2132003 +141.16,50.31590468,-3.25656898,10000,-88.31306054,179.4415911,0,-14.03629709,0,116.2061743 +141.17,50.31589676,-3.256543825,10000,-88.29217112,179.4527672,0,-14.03629709,0,116.1991484 +141.18,50.31588883,-3.256518668,10000,-88.27476324,179.4641663,0,-14.03629709,0,116.1921225 +141.19,50.31588091,-3.25649351,10000,-88.25387378,179.4751195,0,-14.03629709,0,116.1850966 +141.2,50.31587299,-3.25646835,10000,-88.23646589,179.4858498,0,-14.03629709,0,116.1780706 +141.21,50.31586507,-3.256443189,10000,-88.21557647,179.4963571,0,-14.03629709,0,116.1710447 +141.22,50.31585715,-3.256418026,10000,-88.18076083,179.5064186,0,-14.03629709,0,116.1640188 +141.23,50.31584924,-3.256392862,10000,-88.14594519,179.5169259,0,-14.03629709,0,116.1569929 +141.24,50.31584133,-3.256367697,10000,-88.12853729,179.5287708,0,-14.03629709,0,116.1499669 +141.25,50.31583342,-3.256342529,10000,-88.12157405,179.5403928,0,-14.03629709,0,116.142941 +141.26,50.31582551,-3.25631736,10000,-88.10764772,179.5502313,0,-14.03629709,0,116.1359151 +141.27,50.3158176,-3.25629219,10000,-88.0867583,179.5598469,0,-14.03629709,0,116.1288892 +141.28,50.3158097,-3.256267019,10000,-88.06935042,179.5708001,0,-14.03629709,0,116.1218632 +141.29,50.31580179,-3.256241845,10000,-88.04846099,179.5824221,0,-14.03629709,0,116.1148373 +141.3,50.31579389,-3.256216671,10000,-88.01364534,179.594044,0,-14.03629709,0,116.1078114 +141.31,50.31578599,-3.256191494,10000,-87.97882971,179.6052201,0,-14.03629709,0,116.1007855 +141.32,50.3157781,-3.256166316,10000,-87.95794028,179.6155044,0,-14.03629709,0,116.0937595 +141.33,50.3157702,-3.256141137,10000,-87.9405324,179.6255659,0,-14.03629709,0,116.0867336 +141.34,50.31576231,-3.256115956,10000,-87.91964296,179.6360732,0,-14.03629709,0,116.0797077 +141.35,50.31575442,-3.256090774,10000,-87.90223507,179.6470263,0,-14.03629709,0,116.0726818 +141.36,50.31574653,-3.25606559,10000,-87.88482718,179.6586482,0,-14.03629709,0,116.0656558 +141.37,50.31573864,-3.256040405,10000,-87.86393774,179.6702702,0,-14.03629709,0,116.05863 +141.38,50.31573076,-3.256015217,10000,-87.84652986,179.6803316,0,-14.03629709,0,116.051604 +141.39,50.31572287,-3.255990029,10000,-87.82564045,179.6897242,0,-14.03629709,0,116.0445781 +141.4,50.31571499,-3.25596484,10000,-87.7908248,179.7006773,0,-14.03629709,0,116.0375522 +141.41,50.31570711,-3.255939648,10000,-87.75600913,179.7122992,0,-14.03629709,0,116.0305263 +141.42,50.31569924,-3.255914455,10000,-87.7351197,179.7230294,0,-14.03629709,0,116.0235003 +141.43,50.31569136,-3.255889261,10000,-87.71771183,179.7337596,0,-14.03629709,0,116.0164744 +141.44,50.31568349,-3.255864065,10000,-87.69682241,179.7447127,0,-14.03629709,0,116.0094485 +141.45,50.31567562,-3.255838867,10000,-87.68289608,179.75522,0,-14.03629709,0,116.0024226 +141.46,50.31566775,-3.255813669,10000,-87.67593285,179.7659501,0,-14.03629709,0,115.9953967 +141.47,50.31565988,-3.255788468,10000,-87.65852496,179.7769032,0,-14.03629709,0,115.9883707 +141.48,50.31565201,-3.255763266,10000,-87.62370932,179.7871876,0,-14.03629709,0,115.9813448 +141.49,50.31564415,-3.255738063,10000,-87.58889368,179.7972489,0,-14.03629709,0,115.9743189 +141.5,50.31563629,-3.255712858,10000,-87.56800426,179.8079791,0,-14.03629709,0,115.967293 +141.51,50.31562843,-3.255687652,10000,-87.55059638,179.819378,0,-14.03629709,0,115.960267 +141.52,50.31562057,-3.255662444,10000,-87.52970694,179.830554,0,-14.03629709,0,115.9532411 +141.53,50.31561272,-3.255637234,10000,-87.51229906,179.8410612,0,-14.03629709,0,115.9462152 +141.54,50.31560486,-3.255612024,10000,-87.49140962,179.8517914,0,-14.03629709,0,115.9391893 +141.55,50.31559701,-3.255586811,10000,-87.45659398,179.8627445,0,-14.03629709,0,115.9321633 +141.56,50.31558916,-3.255561597,10000,-87.42177834,179.8730287,0,-14.03629709,0,115.9251374 +141.57,50.31558132,-3.255536382,10000,-87.40088891,179.8830901,0,-14.03629709,0,115.9181115 +141.58,50.31557347,-3.255511165,10000,-87.38348103,179.8938202,0,-14.03629709,0,115.9110856 +141.59,50.31556563,-3.255485947,10000,-87.36259159,179.905442,0,-14.03629709,0,115.9040596 +141.6,50.31555779,-3.255460727,10000,-87.34866527,179.9172868,0,-14.03629709,0,115.8970337 +141.61,50.31554995,-3.255435505,10000,-87.34170204,179.9280169,0,-14.03629709,0,115.8900078 +141.62,50.31554211,-3.255410282,10000,-87.32429416,179.9376324,0,-14.03629709,0,115.8829819 +141.63,50.31553427,-3.255385058,10000,-87.28947853,179.9474708,0,-14.03629709,0,115.8759559 +141.64,50.31552644,-3.255359832,10000,-87.25466289,179.9579779,0,-14.03629709,0,115.86893 +141.65,50.31551861,-3.255334605,10000,-87.237255,179.968708,0,-14.03629709,0,115.8619041 +141.66,50.31551078,-3.255309376,10000,-87.23029177,179.9796611,0,-14.03629709,0,115.8548782 +141.67,50.31550295,-3.255284146,10000,-87.21288389,179.9912829,0,-14.03629709,0,115.8478522 +141.68,50.31549512,-3.255258914,10000,-87.17806826,180.0031276,0,-14.03629709,0,115.8408263 +141.69,50.3154873,-3.25523368,10000,-87.14325262,180.0138577,0,-14.03629709,0,115.8338004 +141.7,50.31547948,-3.255208445,10000,-87.12236319,180.0234731,0,-14.03629709,0,115.8267745 +141.71,50.31547166,-3.255183209,10000,-87.10495531,180.0333115,0,-14.03629709,0,115.8197485 +141.72,50.31546384,-3.255157971,10000,-87.08406588,180.0438186,0,-14.03629709,0,115.8127227 +141.73,50.31545603,-3.255132732,10000,-87.066658,180.0545487,0,-14.03629709,0,115.8056967 +141.74,50.31544821,-3.255107491,10000,-87.04925013,180.0655017,0,-14.03629709,0,115.7986708 +141.75,50.3154404,-3.255082249,10000,-87.02487915,180.0769005,0,-14.03629709,0,115.7916449 +141.76,50.31543259,-3.255057005,10000,-86.99702661,180.0878535,0,-14.03629709,0,115.784619 +141.77,50.31542478,-3.255031759,10000,-86.97265562,180.0974689,0,-14.03629709,0,115.777593 +141.78,50.31541698,-3.255006513,10000,-86.95524774,180.1070843,0,-14.03629709,0,115.7705671 +141.79,50.31540917,-3.254981265,10000,-86.93783987,180.1180373,0,-14.03629709,0,115.7635412 +141.8,50.31540137,-3.254956015,10000,-86.91346889,180.129659,0,-14.03629709,0,115.7565153 +141.81,50.31539357,-3.254930764,10000,-86.88561636,180.1412808,0,-14.03629709,0,115.7494893 +141.82,50.31538577,-3.254905511,10000,-86.86124536,180.1522337,0,-14.03629709,0,115.7424634 +141.83,50.31537798,-3.254880256,10000,-86.84383748,180.1618491,0,-14.03629709,0,115.7354375 +141.84,50.31537018,-3.254855001,10000,-86.82642961,180.1714645,0,-14.03629709,0,115.7284116 +141.85,50.31536239,-3.254829744,10000,-86.80205863,180.1824174,0,-14.03629709,0,115.7213857 +141.86,50.3153546,-3.254804485,10000,-86.7742061,180.1938162,0,-14.03629709,0,115.7143597 +141.87,50.31534681,-3.254779225,10000,-86.74983512,180.2047692,0,-14.03629709,0,115.7073338 +141.88,50.31533903,-3.254753963,10000,-86.73242723,180.2154992,0,-14.03629709,0,115.7003079 +141.89,50.31533124,-3.2547287,10000,-86.71501935,180.2262292,0,-14.03629709,0,115.693282 +141.9,50.31532346,-3.254703435,10000,-86.69064838,180.2369592,0,-14.03629709,0,115.686256 +141.91,50.31531568,-3.254678169,10000,-86.66279585,180.2474662,0,-14.03629709,0,115.6792301 +141.92,50.3153079,-3.254652901,10000,-86.63842487,180.2575274,0,-14.03629709,0,115.6722042 +141.93,50.31530013,-3.254627632,10000,-86.62101699,180.2678116,0,-14.03629709,0,115.6651783 +141.94,50.31529235,-3.254602362,10000,-86.60360911,180.2787645,0,-14.03629709,0,115.6581523 +141.95,50.31528458,-3.254577089,10000,-86.57923813,180.2892715,0,-14.03629709,0,115.6511264 +141.96,50.31527681,-3.254551816,10000,-86.55138559,180.2991098,0,-14.03629709,0,115.6441005 +141.97,50.31526904,-3.254526541,10000,-86.52701461,180.3098398,0,-14.03629709,0,115.6370746 +141.98,50.31526128,-3.254501265,10000,-86.50960673,180.3214614,0,-14.03629709,0,115.6300486 +141.99,50.31525351,-3.254475986,10000,-86.49219886,180.3324143,0,-14.03629709,0,115.6230227 +142,50.31524575,-3.254450707,10000,-86.47130944,180.3429214,0,-14.03629709,0,115.6159968 +142.01,50.31523799,-3.254425426,10000,-86.45390157,180.3538742,0,-14.03629709,0,115.6089709 +142.02,50.31523023,-3.254400143,10000,-86.43301213,180.3643813,0,-14.03629709,0,115.6019449 +142.03,50.31522247,-3.254374859,10000,-86.39819648,180.3739966,0,-14.03629709,0,115.5949191 +142.04,50.31521472,-3.254349574,10000,-86.36338086,180.3838348,0,-14.03629709,0,115.5878931 +142.05,50.31520697,-3.254324287,10000,-86.34597299,180.3943418,0,-14.03629709,0,115.5808672 +142.06,50.31519922,-3.254298999,10000,-86.33900976,180.4050717,0,-14.03629709,0,115.5738413 +142.07,50.31519147,-3.254273709,10000,-86.32160188,180.4158016,0,-14.03629709,0,115.5668154 +142.08,50.31518372,-3.254248418,10000,-86.28678625,180.4265316,0,-14.03629709,0,115.5597894 +142.09,50.31517598,-3.254223125,10000,-86.25197062,180.4372615,0,-14.03629709,0,115.5527635 +142.1,50.31516824,-3.254197831,10000,-86.23456274,180.4479914,0,-14.03629709,0,115.5457376 +142.11,50.3151605,-3.254172535,10000,-86.22759951,180.4587213,0,-14.03629709,0,115.5387117 +142.12,50.31515276,-3.254147238,10000,-86.21367317,180.4694512,0,-14.03629709,0,115.5316857 +142.13,50.31514502,-3.254121939,10000,-86.19278374,180.4801811,0,-14.03629709,0,115.5246598 +142.14,50.31513729,-3.254096639,10000,-86.17189433,180.490911,0,-14.03629709,0,115.5176339 +142.15,50.31512955,-3.254071337,10000,-86.14056026,180.5016409,0,-14.03629709,0,115.510608 +142.16,50.31512182,-3.254046034,10000,-86.10226308,180.5121479,0,-14.03629709,0,115.503582 +142.17,50.3151141,-3.254020729,10000,-86.0848552,180.522209,0,-14.03629709,0,115.4965561 +142.18,50.31510637,-3.253995423,10000,-86.08137352,180.532493,0,-14.03629709,0,115.4895302 +142.19,50.31509864,-3.253970116,10000,-86.0604841,180.5434458,0,-14.03629709,0,115.4825043 +142.2,50.31509092,-3.253944806,10000,-86.02566847,180.5539528,0,-14.03629709,0,115.4754783 +142.21,50.3150832,-3.253919496,10000,-85.99433439,180.563568,0,-14.03629709,0,115.4684524 +142.22,50.31507548,-3.253894184,10000,-85.96996341,180.5736291,0,-14.03629709,0,115.4614265 +142.23,50.31506777,-3.253868871,10000,-85.95255552,180.5850277,0,-14.03629709,0,115.4544006 +142.24,50.31506005,-3.253843556,10000,-85.93514765,180.5970952,0,-14.03629709,0,115.4473747 +142.25,50.31505234,-3.253818239,10000,-85.91425823,180.6084938,0,-14.03629709,0,115.4403487 +142.26,50.31504463,-3.253792921,10000,-85.89685036,180.6185549,0,-14.03629709,0,115.4333228 +142.27,50.31503692,-3.253767601,10000,-85.87596093,180.6279471,0,-14.03629709,0,115.4262969 +142.28,50.31502921,-3.253742281,10000,-85.84114528,180.6377853,0,-14.03629709,0,115.419271 +142.29,50.31502151,-3.253716958,10000,-85.80632964,180.6482922,0,-14.03629709,0,115.412245 +142.3,50.31501381,-3.253691635,10000,-85.78892178,180.659022,0,-14.03629709,0,115.4052191 +142.31,50.31500611,-3.253666309,10000,-85.78195859,180.6697518,0,-14.03629709,0,115.3981932 +142.32,50.31499841,-3.253640983,10000,-85.76803226,180.6802587,0,-14.03629709,0,115.3911673 +142.33,50.31499071,-3.253615654,10000,-85.74714282,180.6903198,0,-14.03629709,0,115.3841413 +142.34,50.31498302,-3.253590325,10000,-85.72973494,180.7006037,0,-14.03629709,0,115.3771154 +142.35,50.31497532,-3.253564994,10000,-85.70884552,180.7115565,0,-14.03629709,0,115.3700895 +142.36,50.31496763,-3.253539661,10000,-85.67402988,180.7222863,0,-14.03629709,0,115.3630636 +142.37,50.31495994,-3.253514327,10000,-85.63921425,180.7327932,0,-14.03629709,0,115.3560376 +142.38,50.31495226,-3.253488992,10000,-85.61832483,180.7437459,0,-14.03629709,0,115.3490118 +142.39,50.31494457,-3.253463654,10000,-85.60091696,180.7542528,0,-14.03629709,0,115.3419858 +142.4,50.31493689,-3.253438316,10000,-85.58002752,180.7638679,0,-14.03629709,0,115.3349599 +142.41,50.31492921,-3.253412976,10000,-85.56261965,180.7739289,0,-14.03629709,0,115.327934 +142.42,50.31492153,-3.253387635,10000,-85.54173023,180.7851045,0,-14.03629709,0,115.3209081 +142.43,50.31491385,-3.253362292,10000,-85.50691461,180.7962802,0,-14.03629709,0,115.3138821 +142.44,50.31490618,-3.253336947,10000,-85.47209899,180.8065641,0,-14.03629709,0,115.3068562 +142.45,50.31489851,-3.253311602,10000,-85.45469111,180.8166251,0,-14.03629709,0,115.2998303 +142.46,50.31489084,-3.253286254,10000,-85.44772787,180.8273548,0,-14.03629709,0,115.2928044 +142.47,50.31488317,-3.253260906,10000,-85.43380154,180.8385305,0,-14.03629709,0,115.2857784 +142.48,50.3148755,-3.253235555,10000,-85.41291213,180.8488144,0,-14.03629709,0,115.2787525 +142.49,50.31486784,-3.253210203,10000,-85.39550426,180.8579836,0,-14.03629709,0,115.2717266 +142.5,50.31486017,-3.253184851,10000,-85.37461484,180.8680446,0,-14.03629709,0,115.2647007 +142.51,50.31485251,-3.253159496,10000,-85.33979922,180.879666,0,-14.03629709,0,115.2576747 +142.52,50.31484485,-3.25313414,10000,-85.30498359,180.8910646,0,-14.03629709,0,115.2506488 +142.53,50.3148372,-3.253108782,10000,-85.28409416,180.9011255,0,-14.03629709,0,115.2436229 +142.54,50.31482954,-3.253083423,10000,-85.26668627,180.9107406,0,-14.03629709,0,115.236597 +142.55,50.31482189,-3.253058063,10000,-85.24579683,180.9212474,0,-14.03629709,0,115.229571 +142.56,50.31481424,-3.253032701,10000,-85.22838896,180.9322001,0,-14.03629709,0,115.2225451 +142.57,50.31480659,-3.253007337,10000,-85.2109811,180.9427068,0,-14.03629709,0,115.2155192 +142.58,50.31479894,-3.252981973,10000,-85.19009168,180.9534366,0,-14.03629709,0,115.2084933 +142.59,50.3147913,-3.252956606,10000,-85.17268382,180.9641663,0,-14.03629709,0,115.2014673 +142.6,50.31478365,-3.252931238,10000,-85.1517944,180.9735584,0,-14.03629709,0,115.1944414 +142.61,50.31477601,-3.252905869,10000,-85.11697877,180.9825047,0,-14.03629709,0,115.1874155 +142.62,50.31476837,-3.252880499,10000,-85.08216315,180.9930114,0,-14.03629709,0,115.1803896 +142.63,50.31476074,-3.252855127,10000,-85.06127372,181.0048558,0,-14.03629709,0,115.1733637 +142.64,50.3147531,-3.252829753,10000,-85.04386584,181.0162543,0,-14.03629709,0,115.1663377 +142.65,50.31474547,-3.252804378,10000,-85.02297641,181.0263152,0,-14.03629709,0,115.1593118 +142.66,50.31473784,-3.252779001,10000,-85.00556853,181.0359302,0,-14.03629709,0,115.1522859 +142.67,50.31473021,-3.252753624,10000,-84.98816066,181.0464369,0,-14.03629709,0,115.14526 +142.68,50.31472258,-3.252728244,10000,-84.96727124,181.0573896,0,-14.03629709,0,115.138234 +142.69,50.31471496,-3.252702863,10000,-84.94986338,181.0676734,0,-14.03629709,0,115.1312081 +142.7,50.31470733,-3.252677481,10000,-84.92897396,181.0777342,0,-14.03629709,0,115.1241822 +142.71,50.31469971,-3.252652097,10000,-84.89415834,181.088241,0,-14.03629709,0,115.1171563 +142.72,50.31469209,-3.252626712,10000,-84.85934272,181.0989706,0,-14.03629709,0,115.1101303 +142.73,50.31468448,-3.252601325,10000,-84.83845329,181.1097003,0,-14.03629709,0,115.1031045 +142.74,50.31467686,-3.252575937,10000,-84.82104541,181.120207,0,-14.03629709,0,115.0960785 +142.75,50.31466925,-3.252550547,10000,-84.80015598,181.1300449,0,-14.03629709,0,115.0890526 +142.76,50.31466164,-3.252525156,10000,-84.7827481,181.139437,0,-14.03629709,0,115.0820267 +142.77,50.31465403,-3.252499764,10000,-84.76534023,181.1492749,0,-14.03629709,0,115.0750008 +142.78,50.31464642,-3.25247437,10000,-84.74445082,181.1600045,0,-14.03629709,0,115.0679748 +142.79,50.31463882,-3.252448975,10000,-84.72704296,181.1716259,0,-14.03629709,0,115.0609489 +142.8,50.31463121,-3.252423578,10000,-84.70615354,181.1834702,0,-14.03629709,0,115.053923 +142.81,50.31462361,-3.252398179,10000,-84.6713379,181.1939769,0,-14.03629709,0,115.0468971 +142.82,50.31461601,-3.252372779,10000,-84.63652226,181.202923,0,-14.03629709,0,115.0398711 +142.83,50.31460842,-3.252347378,10000,-84.61563285,181.212315,0,-14.03629709,0,115.0328452 +142.84,50.31460082,-3.252321976,10000,-84.59822499,181.2230447,0,-14.03629709,0,115.0258193 +142.85,50.31459323,-3.252296571,10000,-84.57733557,181.2337743,0,-14.03629709,0,115.0187934 +142.86,50.31458564,-3.252271166,10000,-84.55992769,181.244058,0,-14.03629709,0,115.0117674 +142.87,50.31457805,-3.252245759,10000,-84.54251982,181.2543417,0,-14.03629709,0,115.0047415 +142.88,50.31457046,-3.25222035,10000,-84.52163041,181.2646255,0,-14.03629709,0,114.9977156 +142.89,50.31456288,-3.252194941,10000,-84.50422254,181.275355,0,-14.03629709,0,114.9906897 +142.9,50.31455529,-3.252169529,10000,-84.4833331,181.2863076,0,-14.03629709,0,114.9836637 +142.91,50.31454771,-3.252144116,10000,-84.44851747,181.2965913,0,-14.03629709,0,114.9766378 +142.92,50.31454013,-3.252118702,10000,-84.41370185,181.3064291,0,-14.03629709,0,114.9696119 +142.93,50.31453256,-3.252093286,10000,-84.39281243,181.316267,0,-14.03629709,0,114.962586 +142.94,50.31452498,-3.252067869,10000,-84.37540457,181.3265507,0,-14.03629709,0,114.95556 +142.95,50.31451741,-3.252042451,10000,-84.35451516,181.3375032,0,-14.03629709,0,114.9485341 +142.96,50.31450984,-3.25201703,10000,-84.33710729,181.3480098,0,-14.03629709,0,114.9415082 +142.97,50.31450227,-3.251991609,10000,-84.31969942,181.3578476,0,-14.03629709,0,114.9344823 +142.98,50.3144947,-3.251966186,10000,-84.29880999,181.3685772,0,-14.03629709,0,114.9274563 +142.99,50.31448714,-3.251940762,10000,-84.28140211,181.3799755,0,-14.03629709,0,114.9204304 +143,50.31447957,-3.251915335,10000,-84.26399423,181.3898133,0,-14.03629709,0,114.9134045 +143.01,50.31447201,-3.251889908,10000,-84.23962327,181.3983135,0,-14.03629709,0,114.9063786 +143.02,50.31446445,-3.25186448,10000,-84.20828921,181.4081513,0,-14.03629709,0,114.8993526 +143.03,50.31445689,-3.25183905,10000,-84.16999203,181.4195497,0,-14.03629709,0,114.8923267 +143.04,50.31444934,-3.251813618,10000,-84.13517642,181.4302792,0,-14.03629709,0,114.8853009 +143.05,50.31444179,-3.251788185,10000,-84.11776856,181.440117,0,-14.03629709,0,114.8782749 +143.06,50.31443424,-3.251762751,10000,-84.11428689,181.4508465,0,-14.03629709,0,114.871249 +143.07,50.31442669,-3.251737315,10000,-84.11080522,181.4624677,0,-14.03629709,0,114.8642231 +143.08,50.31441914,-3.251711877,10000,-84.09339734,181.4731972,0,-14.03629709,0,114.8571972 +143.09,50.31441159,-3.251686438,10000,-84.05858171,181.4828121,0,-14.03629709,0,114.8501712 +143.1,50.31440405,-3.251660998,10000,-84.02376609,181.4926498,0,-14.03629709,0,114.8431453 +143.11,50.31439651,-3.251635556,10000,-84.00287668,181.5029335,0,-14.03629709,0,114.8361194 +143.12,50.31438897,-3.251610113,10000,-83.98546882,181.5127712,0,-14.03629709,0,114.8290935 +143.13,50.31438143,-3.251584668,10000,-83.9645794,181.522386,0,-14.03629709,0,114.8220675 +143.14,50.3143739,-3.251559223,10000,-83.94717152,181.5328926,0,-14.03629709,0,114.8150416 +143.15,50.31436636,-3.251533775,10000,-83.9262821,181.543845,0,-14.03629709,0,114.8080157 +143.16,50.31435883,-3.251508326,10000,-83.89146648,181.5541286,0,-14.03629709,0,114.8009898 +143.17,50.3143513,-3.251482876,10000,-83.85665086,181.5641893,0,-14.03629709,0,114.7939638 +143.18,50.31434378,-3.251457424,10000,-83.83576144,181.5746958,0,-14.03629709,0,114.7869379 +143.19,50.31433625,-3.251431971,10000,-83.81835356,181.5852023,0,-14.03629709,0,114.779912 +143.2,50.31432873,-3.251406516,10000,-83.79746414,181.5950401,0,-14.03629709,0,114.7728861 +143.21,50.31432121,-3.25138106,10000,-83.78005628,181.6046548,0,-14.03629709,0,114.7658601 +143.22,50.31431369,-3.251355603,10000,-83.76264842,181.6151613,0,-14.03629709,0,114.7588342 +143.23,50.31430617,-3.251330144,10000,-83.74175901,181.6261137,0,-14.03629709,0,114.7518083 +143.24,50.31429866,-3.251304683,10000,-83.72435114,181.6363973,0,-14.03629709,0,114.7447824 +143.25,50.31429114,-3.251279222,10000,-83.70694326,181.6464579,0,-14.03629709,0,114.7377564 +143.26,50.31428363,-3.251253758,10000,-83.68257229,181.6569644,0,-14.03629709,0,114.7307305 +143.27,50.31427612,-3.251228294,10000,-83.65123823,181.6674709,0,-14.03629709,0,114.7237046 +143.28,50.31426861,-3.251202827,10000,-83.61642261,181.6773086,0,-14.03629709,0,114.7166787 +143.29,50.31426111,-3.25117736,10000,-83.59205164,181.6867004,0,-14.03629709,0,114.7096527 +143.3,50.31425361,-3.251151891,10000,-83.57812532,181.6965381,0,-14.03629709,0,114.7026268 +143.31,50.3142461,-3.251126421,10000,-83.55723591,181.7070446,0,-14.03629709,0,114.6956009 +143.32,50.31423861,-3.251100949,10000,-83.53634648,181.7179969,0,-14.03629709,0,114.688575 +143.33,50.31423111,-3.251075476,10000,-83.52242017,181.7293951,0,-14.03629709,0,114.681549 +143.34,50.31422361,-3.251050001,10000,-83.49804921,181.7403474,0,-14.03629709,0,114.6745231 +143.35,50.31421612,-3.251024524,10000,-83.46671513,181.7497392,0,-14.03629709,0,114.6674972 +143.36,50.31420863,-3.250999047,10000,-83.44582571,181.7586851,0,-14.03629709,0,114.6604713 +143.37,50.31420114,-3.250973568,10000,-83.42841785,181.7691916,0,-14.03629709,0,114.6534453 +143.38,50.31419365,-3.250948088,10000,-83.40752845,181.7808127,0,-14.03629709,0,114.6464194 +143.39,50.31418617,-3.250922605,10000,-83.39012058,181.7913192,0,-14.03629709,0,114.6393935 +143.4,50.31417868,-3.250897122,10000,-83.36923115,181.8000421,0,-14.03629709,0,114.6323676 +143.41,50.3141712,-3.250871637,10000,-83.33441551,181.8087651,0,-14.03629709,0,114.6253416 +143.42,50.31416372,-3.250846152,10000,-83.29959989,181.8190486,0,-14.03629709,0,114.6183158 +143.43,50.31415625,-3.250820664,10000,-83.27871049,181.8300009,0,-14.03629709,0,114.6112898 +143.44,50.31414877,-3.250795175,10000,-83.26130263,181.8405073,0,-14.03629709,0,114.6042639 +143.45,50.3141413,-3.250769685,10000,-83.2404132,181.8514595,0,-14.03629709,0,114.597238 +143.46,50.31413383,-3.250744193,10000,-83.22300534,181.8630806,0,-14.03629709,0,114.5902121 +143.47,50.31412636,-3.250718699,10000,-83.20559749,181.873587,0,-14.03629709,0,114.5831862 +143.48,50.31411889,-3.250693204,10000,-83.18470809,181.88231,0,-14.03629709,0,114.5761602 +143.49,50.31411143,-3.250667708,10000,-83.16730023,181.8910329,0,-14.03629709,0,114.5691343 +143.5,50.31410396,-3.250642211,10000,-83.14989234,181.9015393,0,-14.03629709,0,114.5621084 +143.51,50.3140965,-3.250616712,10000,-83.12552135,181.9131603,0,-14.03629709,0,114.5550825 +143.52,50.31408904,-3.250591211,10000,-83.09418728,181.9236667,0,-14.03629709,0,114.5480565 +143.53,50.31408158,-3.250565709,10000,-83.05589011,181.9326126,0,-14.03629709,0,114.5410306 +143.54,50.31407413,-3.250540206,10000,-83.02107451,181.9420042,0,-14.03629709,0,114.5340047 +143.55,50.31406668,-3.250514702,10000,-83.00366665,181.9527335,0,-14.03629709,0,114.5269788 +143.56,50.31405923,-3.250489195,10000,-83.000185,181.9634628,0,-14.03629709,0,114.5199528 +143.57,50.31405178,-3.250463688,10000,-82.99670333,181.9737463,0,-14.03629709,0,114.5129269 +143.58,50.31404433,-3.250438179,10000,-82.97929546,181.9838068,0,-14.03629709,0,114.505901 +143.59,50.31403688,-3.250412668,10000,-82.94447985,181.9931984,0,-14.03629709,0,114.4988751 +143.6,50.31402944,-3.250387157,10000,-82.90966423,182.003036,0,-14.03629709,0,114.4918491 +143.61,50.314022,-3.250361644,10000,-82.88877482,182.014657,0,-14.03629709,0,114.4848232 +143.62,50.31401456,-3.250336129,10000,-82.87136695,182.026278,0,-14.03629709,0,114.4777973 +143.63,50.31400712,-3.250310612,10000,-82.85047752,182.0358926,0,-14.03629709,0,114.4707714 +143.64,50.31399969,-3.250285095,10000,-82.83306966,182.0446155,0,-14.03629709,0,114.4637454 +143.65,50.31399225,-3.250259576,10000,-82.81218025,182.0542301,0,-14.03629709,0,114.4567195 +143.66,50.31398482,-3.250234056,10000,-82.77736463,182.0645134,0,-14.03629709,0,114.4496936 +143.67,50.31397739,-3.250208534,10000,-82.74254901,182.0745739,0,-14.03629709,0,114.4426677 +143.68,50.31396997,-3.250183011,10000,-82.72165959,182.0848573,0,-14.03629709,0,114.4356417 +143.69,50.31396254,-3.250157487,10000,-82.70425173,182.0955865,0,-14.03629709,0,114.4286158 +143.7,50.31395512,-3.25013196,10000,-82.68336232,182.105424,0,-14.03629709,0,114.4215899 +143.71,50.3139477,-3.250106433,10000,-82.66595446,182.1145927,0,-14.03629709,0,114.414564 +143.72,50.31394028,-3.250080905,10000,-82.64854659,182.124876,0,-14.03629709,0,114.407538 +143.73,50.31393286,-3.250055374,10000,-82.62765717,182.1360511,0,-14.03629709,0,114.4005122 +143.74,50.31392545,-3.250029843,10000,-82.61024932,182.1467803,0,-14.03629709,0,114.3934862 +143.75,50.31391803,-3.250004309,10000,-82.58935992,182.1568408,0,-14.03629709,0,114.3864603 +143.76,50.31391062,-3.249978775,10000,-82.55454431,182.1669012,0,-14.03629709,0,114.3794344 +143.77,50.31390321,-3.249953239,10000,-82.51972868,182.1769616,0,-14.03629709,0,114.3724085 +143.78,50.31389581,-3.249927701,10000,-82.49883924,182.1863532,0,-14.03629709,0,114.3653825 +143.79,50.3138884,-3.249902163,10000,-82.48143138,182.1959677,0,-14.03629709,0,114.3583566 +143.8,50.313881,-3.249876623,10000,-82.46054198,182.2066969,0,-14.03629709,0,114.3513307 +143.81,50.3138736,-3.249851081,10000,-82.44313414,182.2172031,0,-14.03629709,0,114.3443048 +143.82,50.3138662,-3.249825538,10000,-82.42572628,182.2268176,0,-14.03629709,0,114.3372788 +143.83,50.3138588,-3.249799994,10000,-82.40483685,182.2366551,0,-14.03629709,0,114.3302529 +143.84,50.31385141,-3.249774448,10000,-82.38742898,182.2471613,0,-14.03629709,0,114.323227 +143.85,50.31384401,-3.249748901,10000,-82.36653957,182.2578905,0,-14.03629709,0,114.3162011 +143.86,50.31383662,-3.249723352,10000,-82.33172395,182.2683967,0,-14.03629709,0,114.3091752 +143.87,50.31382923,-3.249697802,10000,-82.29690833,182.2782341,0,-14.03629709,0,114.3021492 +143.88,50.31382185,-3.24967225,10000,-82.27601892,182.2878486,0,-14.03629709,0,114.2951233 +143.89,50.31381446,-3.249646698,10000,-82.25861107,182.2981319,0,-14.03629709,0,114.2880974 +143.9,50.31380708,-3.249621143,10000,-82.23772166,182.3081922,0,-14.03629709,0,114.2810715 +143.91,50.3137997,-3.249595587,10000,-82.2203138,182.3173608,0,-14.03629709,0,114.2740455 +143.92,50.31379232,-3.249570031,10000,-82.20290592,182.3271982,0,-14.03629709,0,114.2670196 +143.93,50.31378494,-3.249544472,10000,-82.1820165,182.3379273,0,-14.03629709,0,114.2599937 +143.94,50.31377757,-3.249518912,10000,-82.16460865,182.3482106,0,-14.03629709,0,114.2529678 +143.95,50.31377019,-3.249493351,10000,-82.14371924,182.358048,0,-14.03629709,0,114.2459418 +143.96,50.31376282,-3.249467788,10000,-82.10890363,182.3678854,0,-14.03629709,0,114.2389159 +143.97,50.31375545,-3.249442224,10000,-82.07408802,182.3781686,0,-14.03629709,0,114.23189 +143.98,50.31374809,-3.249416659,10000,-82.05319861,182.3891207,0,-14.03629709,0,114.2248641 +143.99,50.31374072,-3.249391091,10000,-82.03579073,182.3996268,0,-14.03629709,0,114.2178381 +144,50.31373336,-3.249365523,10000,-82.01490132,182.4090183,0,-14.03629709,0,114.2108122 +144.01,50.313726,-3.249339953,10000,-81.99749348,182.4179639,0,-14.03629709,0,114.2037863 +144.02,50.31371864,-3.249314382,10000,-81.98008562,182.4273554,0,-14.03629709,0,114.1967604 +144.03,50.31371128,-3.24928881,10000,-81.95919619,182.4380845,0,-14.03629709,0,114.1897344 +144.04,50.31370393,-3.249263236,10000,-81.94178833,182.4497053,0,-14.03629709,0,114.1827085 +144.05,50.31369657,-3.24923766,10000,-81.92089892,182.4602115,0,-14.03629709,0,114.1756826 +144.06,50.31368922,-3.249212083,10000,-81.88608331,182.4689341,0,-14.03629709,0,114.1686567 +144.07,50.31368187,-3.249186505,10000,-81.85126769,182.4776568,0,-14.03629709,0,114.1616307 +144.08,50.31367453,-3.249160926,10000,-81.83037829,182.48794,0,-14.03629709,0,114.1546049 +144.09,50.31366718,-3.249135345,10000,-81.81297043,182.498892,0,-14.03629709,0,114.1475789 +144.1,50.31365984,-3.249109762,10000,-81.79208102,182.5091752,0,-14.03629709,0,114.140553 +144.11,50.3136525,-3.249084179,10000,-81.77467316,182.5190125,0,-14.03629709,0,114.1335271 +144.12,50.31364516,-3.249058593,10000,-81.75378375,182.5288498,0,-14.03629709,0,114.1265012 +144.13,50.31363782,-3.249033007,10000,-81.72244968,182.5391329,0,-14.03629709,0,114.1194752 +144.14,50.31363049,-3.249007419,10000,-81.69807871,182.5500849,0,-14.03629709,0,114.1124493 +144.15,50.31362316,-3.248981829,10000,-81.6841524,182.560591,0,-14.03629709,0,114.1054234 +144.16,50.31361582,-3.248956238,10000,-81.663263,182.5699824,0,-14.03629709,0,114.0983975 +144.17,50.3136085,-3.248930646,10000,-81.64237359,182.578928,0,-14.03629709,0,114.0913715 +144.18,50.31360117,-3.248905052,10000,-81.62844728,182.5880964,0,-14.03629709,0,114.0843456 +144.19,50.31359384,-3.248879458,10000,-81.60407632,182.5979337,0,-14.03629709,0,114.0773197 +144.2,50.31358652,-3.248853861,10000,-81.56926071,182.6086627,0,-14.03629709,0,114.0702938 +144.21,50.3135792,-3.248828264,10000,-81.53792666,182.6200605,0,-14.03629709,0,114.0632678 +144.22,50.31357188,-3.248802664,10000,-81.51355569,182.6310125,0,-14.03629709,0,114.0562419 +144.23,50.31356457,-3.248777063,10000,-81.49614782,182.6404038,0,-14.03629709,0,114.049216 +144.24,50.31355725,-3.248751461,10000,-81.47873995,182.6491264,0,-14.03629709,0,114.0421901 +144.25,50.31354994,-3.248725858,10000,-81.45785055,182.6587407,0,-14.03629709,0,114.0351642 +144.26,50.31354263,-3.248700253,10000,-81.44044271,182.6690238,0,-14.03629709,0,114.0281382 +144.27,50.31353532,-3.248674647,10000,-81.42303485,182.6788611,0,-14.03629709,0,114.0211123 +144.28,50.31352801,-3.248649039,10000,-81.40214544,182.6882524,0,-14.03629709,0,114.0140864 +144.29,50.31352071,-3.248623431,10000,-81.38125603,182.6978667,0,-14.03629709,0,114.0070605 +144.3,50.3135134,-3.24859782,10000,-81.34992197,182.7077039,0,-14.03629709,0,114.0000345 +144.31,50.3135061,-3.248572209,10000,-81.3116248,182.717987,0,-14.03629709,0,113.9930086 +144.32,50.31349881,-3.248546596,10000,-81.29421694,182.7289389,0,-14.03629709,0,113.9859827 +144.33,50.31349151,-3.248520981,10000,-81.29073528,182.7394449,0,-14.03629709,0,113.9789568 +144.34,50.31348421,-3.248495365,10000,-81.26984587,182.7490592,0,-14.03629709,0,113.9719308 +144.35,50.31347692,-3.248469748,10000,-81.23503025,182.7588964,0,-14.03629709,0,113.9649049 +144.36,50.31346963,-3.248444129,10000,-81.20369619,182.7691795,0,-14.03629709,0,113.957879 +144.37,50.31346234,-3.248418509,10000,-81.17932523,182.7790166,0,-14.03629709,0,113.9508531 +144.38,50.31345506,-3.248392887,10000,-81.16191738,182.7884079,0,-14.03629709,0,113.9438271 +144.39,50.31344777,-3.248367265,10000,-81.14450954,182.7982451,0,-14.03629709,0,113.9368012 +144.4,50.31344049,-3.24834164,10000,-81.12362014,182.8087511,0,-14.03629709,0,113.9297753 +144.41,50.31343321,-3.248316015,10000,-81.10621227,182.8192571,0,-14.03629709,0,113.9227494 +144.42,50.31342593,-3.248290387,10000,-81.08532285,182.8290943,0,-14.03629709,0,113.9157235 +144.43,50.31341865,-3.248264759,10000,-81.05050724,182.8384855,0,-14.03629709,0,113.9086976 +144.44,50.31341138,-3.248239129,10000,-81.01569164,182.8483227,0,-14.03629709,0,113.9016716 +144.45,50.31340411,-3.248213498,10000,-80.99828378,182.8586057,0,-14.03629709,0,113.8946457 +144.46,50.31339684,-3.248187865,10000,-80.99132058,182.8684429,0,-14.03629709,0,113.8876198 +144.47,50.31338957,-3.248162231,10000,-80.97739426,182.8778341,0,-14.03629709,0,113.8805939 +144.48,50.3133823,-3.248136596,10000,-80.95650485,182.8876713,0,-14.03629709,0,113.8735679 +144.49,50.31337504,-3.248110959,10000,-80.93561545,182.8981772,0,-14.03629709,0,113.866542 +144.5,50.31336777,-3.248085321,10000,-80.90428139,182.9086832,0,-14.03629709,0,113.8595161 +144.51,50.31336051,-3.248059681,10000,-80.86598423,182.9185203,0,-14.03629709,0,113.8524902 +144.52,50.31335326,-3.24803404,10000,-80.84857638,182.9279115,0,-14.03629709,0,113.8454642 +144.53,50.313346,-3.248008398,10000,-80.84509473,182.9375257,0,-14.03629709,0,113.8384383 +144.54,50.31333874,-3.247982754,10000,-80.82420532,182.9471399,0,-14.03629709,0,113.8314124 +144.55,50.31333149,-3.247957109,10000,-80.7893897,182.9565311,0,-14.03629709,0,113.8243865 +144.56,50.31332424,-3.247931463,10000,-80.75805563,182.9663682,0,-14.03629709,0,113.8173605 +144.57,50.31331699,-3.247905815,10000,-80.73368467,182.9768741,0,-14.03629709,0,113.8103346 +144.58,50.31330975,-3.247880166,10000,-80.71627682,182.9876029,0,-14.03629709,0,113.8033087 +144.59,50.3133025,-3.247854515,10000,-80.69886898,182.9981088,0,-14.03629709,0,113.7962828 +144.6,50.31329526,-3.247828863,10000,-80.67449802,183.007723,0,-14.03629709,0,113.7892568 +144.61,50.31328802,-3.247803209,10000,-80.64664551,183.0164453,0,-14.03629709,0,113.7822309 +144.62,50.31328078,-3.247777555,10000,-80.62227455,183.0258365,0,-14.03629709,0,113.775205 +144.63,50.31327355,-3.247751899,10000,-80.60486669,183.0365654,0,-14.03629709,0,113.7681791 +144.64,50.31326631,-3.247726241,10000,-80.58745884,183.0470712,0,-14.03629709,0,113.7611532 +144.65,50.31325908,-3.247700582,10000,-80.56656944,183.0566853,0,-14.03629709,0,113.7541272 +144.66,50.31325185,-3.247674922,10000,-80.54916159,183.0665224,0,-14.03629709,0,113.7471013 +144.67,50.31324462,-3.24764926,10000,-80.52827219,183.0768053,0,-14.03629709,0,113.7400754 +144.68,50.31323739,-3.247623597,10000,-80.49345658,183.0866424,0,-14.03629709,0,113.7330495 +144.69,50.31323017,-3.247597932,10000,-80.45864096,183.0960335,0,-14.03629709,0,113.7260235 +144.7,50.31322295,-3.247572267,10000,-80.44123309,183.1056476,0,-14.03629709,0,113.7189976 +144.71,50.31321573,-3.247546599,10000,-80.43426989,183.1154846,0,-14.03629709,0,113.7119717 +144.72,50.31320851,-3.247520931,10000,-80.41686204,183.1255446,0,-14.03629709,0,113.7049458 +144.73,50.31320129,-3.247495261,10000,-80.38204644,183.1358275,0,-14.03629709,0,113.6979198 +144.74,50.31319408,-3.247469589,10000,-80.34723082,183.1458874,0,-14.03629709,0,113.690894 +144.75,50.31318687,-3.247443917,10000,-80.32982296,183.1557244,0,-14.03629709,0,113.683868 +144.76,50.31317966,-3.247418242,10000,-80.32285977,183.1653385,0,-14.03629709,0,113.6768421 +144.77,50.31317245,-3.247392567,10000,-80.30545193,183.1747296,0,-14.03629709,0,113.6698162 +144.78,50.31316524,-3.24736689,10000,-80.27063632,183.1845666,0,-14.03629709,0,113.6627903 +144.79,50.31315804,-3.247341212,10000,-80.23582071,183.1948495,0,-14.03629709,0,113.6557643 +144.8,50.31315084,-3.247315532,10000,-80.21841285,183.2044635,0,-14.03629709,0,113.6487384 +144.81,50.31314364,-3.247289851,10000,-80.21144963,183.2131858,0,-14.03629709,0,113.6417125 +144.82,50.31313644,-3.247264169,10000,-80.19404178,183.2225769,0,-14.03629709,0,113.6346866 +144.83,50.31312924,-3.247238486,10000,-80.15922619,183.2333056,0,-14.03629709,0,113.6276606 +144.84,50.31312205,-3.2472128,10000,-80.12441059,183.2440344,0,-14.03629709,0,113.6206347 +144.85,50.31311486,-3.247187114,10000,-80.10700272,183.2543172,0,-14.03629709,0,113.6136088 +144.86,50.31310767,-3.247161426,10000,-80.10003951,183.2643771,0,-14.03629709,0,113.6065829 +144.87,50.31310048,-3.247135736,10000,-80.08263166,183.2737682,0,-14.03629709,0,113.5995569 +144.88,50.31309329,-3.247110046,10000,-80.04781605,183.2831592,0,-14.03629709,0,113.592531 +144.89,50.31308611,-3.247084354,10000,-80.01300045,183.2929962,0,-14.03629709,0,113.5855051 +144.9,50.31307893,-3.24705866,10000,-79.99211105,183.3023872,0,-14.03629709,0,113.5784792 +144.91,50.31307175,-3.247032966,10000,-79.9747032,183.3117783,0,-14.03629709,0,113.5714532 +144.92,50.31306457,-3.24700727,10000,-79.9538138,183.3216152,0,-14.03629709,0,113.5644273 +144.93,50.3130574,-3.246981572,10000,-79.93640594,183.3310062,0,-14.03629709,0,113.5574014 +144.94,50.31305022,-3.246955874,10000,-79.91899809,183.3406202,0,-14.03629709,0,113.5503755 +144.95,50.31304305,-3.246930174,10000,-79.89462713,183.3515718,0,-14.03629709,0,113.5433495 +144.96,50.31303588,-3.246904472,10000,-79.86677463,183.3627464,0,-14.03629709,0,113.5363236 +144.97,50.31302871,-3.246878769,10000,-79.84240367,183.3725833,0,-14.03629709,0,113.5292977 +144.98,50.31302155,-3.246853064,10000,-79.82499581,183.3810825,0,-14.03629709,0,113.5222718 +144.99,50.31301438,-3.246827359,10000,-79.80758796,183.3895818,0,-14.03629709,0,113.5152458 +145,50.31300722,-3.246801652,10000,-79.78321701,183.3994187,0,-14.03629709,0,113.5082199 +145.01,50.31300006,-3.246775944,10000,-79.75188296,183.4105932,0,-14.03629709,0,113.501194 +145.02,50.3129929,-3.246750234,10000,-79.71706735,183.4215448,0,-14.03629709,0,113.4941681 +145.03,50.31298575,-3.246724522,10000,-79.69617794,183.4309358,0,-14.03629709,0,113.4871421 +145.04,50.3129786,-3.24669881,10000,-79.6926963,183.4396579,0,-14.03629709,0,113.4801162 +145.05,50.31297144,-3.246673096,10000,-79.67528846,183.4490489,0,-14.03629709,0,113.4730903 +145.06,50.31296429,-3.246647381,10000,-79.63699129,183.4586628,0,-14.03629709,0,113.4660644 +145.07,50.31295715,-3.246621664,10000,-79.60565723,183.4682767,0,-14.03629709,0,113.4590385 +145.08,50.31295,-3.246595947,10000,-79.58476784,183.4787824,0,-14.03629709,0,113.4520125 +145.09,50.31294286,-3.246570227,10000,-79.56387844,183.489511,0,-14.03629709,0,113.4449867 +145.1,50.31293572,-3.246544506,10000,-79.54995214,183.498902,0,-14.03629709,0,113.4379607 +145.11,50.31292858,-3.246518784,10000,-79.54298892,183.5076241,0,-14.03629709,0,113.4309348 +145.12,50.31292144,-3.246493061,10000,-79.52558105,183.5170151,0,-14.03629709,0,113.4239089 +145.13,50.3129143,-3.246467336,10000,-79.49076545,183.5268519,0,-14.03629709,0,113.416883 +145.14,50.31290717,-3.24644161,10000,-79.45594986,183.5369116,0,-14.03629709,0,113.409857 +145.15,50.31290004,-3.246415883,10000,-79.43506047,183.5471943,0,-14.03629709,0,113.4028311 +145.16,50.31289291,-3.246390153,10000,-79.41417108,183.5572541,0,-14.03629709,0,113.3958052 +145.17,50.31288578,-3.246364424,10000,-79.38283702,183.5670909,0,-14.03629709,0,113.3887793 +145.18,50.31287866,-3.246338691,10000,-79.36194761,183.5767047,0,-14.03629709,0,113.3817533 +145.19,50.31287154,-3.246312959,10000,-79.35846596,183.5858727,0,-14.03629709,0,113.3747274 +145.2,50.31286441,-3.246287224,10000,-79.34105812,183.5950407,0,-14.03629709,0,113.3677015 +145.21,50.31285729,-3.246261489,10000,-79.30276097,183.6048775,0,-14.03629709,0,113.3606756 +145.22,50.31285018,-3.246235752,10000,-79.27142691,183.6151601,0,-14.03629709,0,113.3536496 +145.23,50.31284306,-3.246210013,10000,-79.2505375,183.6252199,0,-14.03629709,0,113.3466237 +145.24,50.31283595,-3.246184274,10000,-79.22964809,183.6350566,0,-14.03629709,0,113.3395978 +145.25,50.31282884,-3.246158532,10000,-79.21224024,183.6446704,0,-14.03629709,0,113.3325719 +145.26,50.31282173,-3.24613279,10000,-79.1948324,183.6538384,0,-14.03629709,0,113.3255459 +145.27,50.31281462,-3.246107046,10000,-79.173943,183.6630063,0,-14.03629709,0,113.31852 +145.28,50.31280752,-3.246081301,10000,-79.15653514,183.673066,0,-14.03629709,0,113.3114941 +145.29,50.31280041,-3.246055555,10000,-79.13564574,183.6837945,0,-14.03629709,0,113.3044682 +145.3,50.31279331,-3.246029806,10000,-79.10083015,183.6934083,0,-14.03629709,0,113.2974422 +145.31,50.31278621,-3.246004057,10000,-79.06601456,183.7019074,0,-14.03629709,0,113.2904163 +145.32,50.31277912,-3.245978307,10000,-79.04512515,183.7115212,0,-14.03629709,0,113.2833904 +145.33,50.31277202,-3.245952555,10000,-79.02771729,183.7220268,0,-14.03629709,0,113.2763645 +145.34,50.31276493,-3.245926801,10000,-79.00682788,183.7316405,0,-14.03629709,0,113.2693385 +145.35,50.31275784,-3.245901047,10000,-78.98942003,183.7410314,0,-14.03629709,0,113.2623126 +145.36,50.31275075,-3.245875291,10000,-78.97201219,183.7508681,0,-14.03629709,0,113.2552867 +145.37,50.31274366,-3.245849533,10000,-78.95112279,183.7602589,0,-14.03629709,0,113.2482608 +145.38,50.31273658,-3.245823775,10000,-78.93371494,183.7698727,0,-14.03629709,0,113.2412348 +145.39,50.31272949,-3.245798015,10000,-78.91282554,183.7806011,0,-14.03629709,0,113.2342089 +145.4,50.31272241,-3.245772253,10000,-78.87800993,183.7908837,0,-14.03629709,0,113.227183 +145.41,50.31271533,-3.24574649,10000,-78.84319433,183.7996057,0,-14.03629709,0,113.2201571 +145.42,50.31270826,-3.245720726,10000,-78.82230494,183.8083277,0,-14.03629709,0,113.2131311 +145.43,50.31270118,-3.245694961,10000,-78.8048971,183.8186102,0,-14.03629709,0,113.2061053 +145.44,50.31269411,-3.245669194,10000,-78.78400769,183.8293387,0,-14.03629709,0,113.1990794 +145.45,50.31268704,-3.245643425,10000,-78.76659983,183.8387294,0,-14.03629709,0,113.1920534 +145.46,50.31267997,-3.245617656,10000,-78.74571043,183.8474514,0,-14.03629709,0,113.1850275 +145.47,50.3126729,-3.245591885,10000,-78.71089483,183.8570651,0,-14.03629709,0,113.1780016 +145.48,50.31266584,-3.245566113,10000,-78.67607925,183.8673477,0,-14.03629709,0,113.1709757 +145.49,50.31265878,-3.245540339,10000,-78.6586714,183.8769614,0,-14.03629709,0,113.1639497 +145.5,50.31265172,-3.245514564,10000,-78.65170819,183.8854603,0,-14.03629709,0,113.1569238 +145.51,50.31264466,-3.245488788,10000,-78.63778187,183.8941823,0,-14.03629709,0,113.1498979 +145.52,50.3126376,-3.245463011,10000,-78.61689247,183.9044648,0,-14.03629709,0,113.142872 +145.53,50.31263055,-3.245437232,10000,-78.59600309,183.9154161,0,-14.03629709,0,113.135846 +145.54,50.31262349,-3.245411451,10000,-78.56466905,183.9256986,0,-14.03629709,0,113.1288201 +145.55,50.31261644,-3.24538567,10000,-78.52289035,183.9355353,0,-14.03629709,0,113.1217942 +145.56,50.3126094,-3.245359886,10000,-78.49503785,183.944926,0,-14.03629709,0,113.1147683 +145.57,50.31260235,-3.245334102,10000,-78.48807465,183.9534249,0,-14.03629709,0,113.1077423 +145.58,50.31259531,-3.245308316,10000,-78.48459301,183.9621468,0,-14.03629709,0,113.1007164 +145.59,50.31258826,-3.24528253,10000,-78.46718516,183.9724293,0,-14.03629709,0,113.0936905 +145.6,50.31258122,-3.245256741,10000,-78.43236955,183.9833806,0,-14.03629709,0,113.0866646 +145.61,50.31257418,-3.245230951,10000,-78.39755395,183.9934402,0,-14.03629709,0,113.0796386 +145.62,50.31256715,-3.24520516,10000,-78.37666455,184.002385,0,-14.03629709,0,113.0726127 +145.63,50.31256011,-3.245179367,10000,-78.3592567,184.010661,0,-14.03629709,0,113.0655868 +145.64,50.31255308,-3.245153574,10000,-78.33488575,184.0191599,0,-14.03629709,0,113.0585609 +145.65,50.31254605,-3.245127779,10000,-78.30703326,184.0289965,0,-14.03629709,0,113.0515349 +145.66,50.31253902,-3.245101983,10000,-78.28266232,184.0401707,0,-14.03629709,0,113.044509 +145.67,50.312532,-3.245076185,10000,-78.26525447,184.0511219,0,-14.03629709,0,113.0374831 +145.68,50.31252497,-3.245050385,10000,-78.24784661,184.0605126,0,-14.03629709,0,113.0304572 +145.69,50.31251795,-3.245024585,10000,-78.22347566,184.0690115,0,-14.03629709,0,113.0234312 +145.7,50.31251093,-3.244998783,10000,-78.19562317,184.0777333,0,-14.03629709,0,113.0164053 +145.71,50.31250391,-3.24497298,10000,-78.17125222,184.0869011,0,-14.03629709,0,113.0093794 +145.72,50.3124969,-3.244947176,10000,-78.15384438,184.0967376,0,-14.03629709,0,113.0023535 +145.73,50.31248988,-3.24492137,10000,-78.13643654,184.1072429,0,-14.03629709,0,112.9953275 +145.74,50.31248287,-3.244895563,10000,-78.11206559,184.1177483,0,-14.03629709,0,112.9883016 +145.75,50.31247586,-3.244869754,10000,-78.08421308,184.1275848,0,-14.03629709,0,112.9812757 +145.76,50.31246885,-3.244843944,10000,-78.05984212,184.1367525,0,-14.03629709,0,112.9742498 +145.77,50.31246185,-3.244818133,10000,-78.04243428,184.1456972,0,-14.03629709,0,112.9672238 +145.78,50.31245484,-3.24479232,10000,-78.02502644,184.1548649,0,-14.03629709,0,112.960198 +145.79,50.31244784,-3.244766507,10000,-78.00065549,184.1644785,0,-14.03629709,0,112.953172 +145.8,50.31244084,-3.244740691,10000,-77.97280301,184.174315,0,-14.03629709,0,112.9461461 +145.81,50.31243384,-3.244714875,10000,-77.94843206,184.1843744,0,-14.03629709,0,112.9391202 +145.82,50.31242685,-3.244689057,10000,-77.9310242,184.1944338,0,-14.03629709,0,112.9320943 +145.83,50.31241985,-3.244663237,10000,-77.91013479,184.2036015,0,-14.03629709,0,112.9250683 +145.84,50.31241286,-3.244637417,10000,-77.8753192,184.2123233,0,-14.03629709,0,112.9180424 +145.85,50.31240587,-3.244611595,10000,-77.84050362,184.2219368,0,-14.03629709,0,112.9110165 +145.86,50.31239889,-3.244585772,10000,-77.82309577,184.2322191,0,-14.03629709,0,112.9039906 +145.87,50.3123919,-3.244559947,10000,-77.81613256,184.2418326,0,-14.03629709,0,112.8969647 +145.88,50.31238492,-3.244534121,10000,-77.79872472,184.2503314,0,-14.03629709,0,112.8899387 +145.89,50.31237793,-3.244508294,10000,-77.76739068,184.2590532,0,-14.03629709,0,112.8829128 +145.9,50.31237096,-3.244482466,10000,-77.74301973,184.2693355,0,-14.03629709,0,112.8758869 +145.91,50.31236398,-3.244456636,10000,-77.72909344,184.2800637,0,-14.03629709,0,112.868861 +145.92,50.312357,-3.244430804,10000,-77.70472249,184.2894543,0,-14.03629709,0,112.861835 +145.93,50.31235003,-3.244404972,10000,-77.67338843,184.298176,0,-14.03629709,0,112.8548091 +145.94,50.31234306,-3.244379138,10000,-77.65249903,184.3075665,0,-14.03629709,0,112.8477832 +145.95,50.31233609,-3.244353303,10000,-77.63509119,184.316957,0,-14.03629709,0,112.8407573 +145.96,50.31232912,-3.244327466,10000,-77.61420181,184.3256787,0,-14.03629709,0,112.8337313 +145.97,50.31232216,-3.244301629,10000,-77.59679397,184.3350693,0,-14.03629709,0,112.8267054 +145.98,50.31231519,-3.24427579,10000,-77.57938612,184.3457974,0,-14.03629709,0,112.8196795 +145.99,50.31230823,-3.244249949,10000,-77.55501518,184.3563027,0,-14.03629709,0,112.8126536 +146,50.31230127,-3.244224107,10000,-77.52368113,184.3659161,0,-14.03629709,0,112.8056276 +146.01,50.31229431,-3.244198264,10000,-77.48886553,184.3755296,0,-14.03629709,0,112.7986017 +146.02,50.31228736,-3.244172419,10000,-77.46449458,184.3849201,0,-14.03629709,0,112.7915758 +146.03,50.31228041,-3.244146573,10000,-77.45056828,184.3934188,0,-14.03629709,0,112.7845499 +146.04,50.31227345,-3.244120726,10000,-77.42967889,184.4019175,0,-14.03629709,0,112.7775239 +146.05,50.31226651,-3.244094878,10000,-77.40878949,184.4115309,0,-14.03629709,0,112.770498 +146.06,50.31225956,-3.244069028,10000,-77.3948632,184.4220361,0,-14.03629709,0,112.7634721 +146.07,50.31225261,-3.244043177,10000,-77.37049227,184.4325413,0,-14.03629709,0,112.7564462 +146.08,50.31224567,-3.244017324,10000,-77.33915823,184.4421547,0,-14.03629709,0,112.7494202 +146.09,50.31223873,-3.24399147,10000,-77.31826883,184.4506534,0,-14.03629709,0,112.7423944 +146.1,50.31223179,-3.243965615,10000,-77.29737943,184.4591521,0,-14.03629709,0,112.7353684 +146.11,50.31222485,-3.243939759,10000,-77.26256383,184.4685426,0,-14.03629709,0,112.7283425 +146.12,50.31221792,-3.243913901,10000,-77.22774824,184.4783789,0,-14.03629709,0,112.7213166 +146.13,50.31221099,-3.243888042,10000,-77.21034039,184.4884381,0,-14.03629709,0,112.7142907 +146.14,50.31220406,-3.243862182,10000,-77.20337719,184.4984974,0,-14.03629709,0,112.7072647 +146.15,50.31219713,-3.243836319,10000,-77.18945089,184.5076649,0,-14.03629709,0,112.7002388 +146.16,50.3121902,-3.243810457,10000,-77.16856151,184.5163865,0,-14.03629709,0,112.6932129 +146.17,50.31218328,-3.243784592,10000,-77.15115367,184.5259999,0,-14.03629709,0,112.686187 +146.18,50.31217635,-3.243758727,10000,-77.13026428,184.5362821,0,-14.03629709,0,112.679161 +146.19,50.31216943,-3.243732859,10000,-77.09544868,184.5461184,0,-14.03629709,0,112.6721351 +146.2,50.31216251,-3.243706991,10000,-77.06063308,184.5552858,0,-14.03629709,0,112.6651092 +146.21,50.3121556,-3.243681121,10000,-77.03974369,184.5642303,0,-14.03629709,0,112.6580833 +146.22,50.31214868,-3.24365525,10000,-77.02233585,184.5731748,0,-14.03629709,0,112.6510573 +146.23,50.31214177,-3.243629378,10000,-77.00144646,184.5821193,0,-14.03629709,0,112.6440314 +146.24,50.31213486,-3.243603504,10000,-76.98403861,184.5915097,0,-14.03629709,0,112.6370055 +146.25,50.31212795,-3.24357763,10000,-76.96314922,184.6017919,0,-14.03629709,0,112.6299796 +146.26,50.31212104,-3.243551753,10000,-76.92833362,184.6118511,0,-14.03629709,0,112.6229537 +146.27,50.31211414,-3.243525875,10000,-76.89351802,184.6207956,0,-14.03629709,0,112.6159277 +146.28,50.31210724,-3.243499997,10000,-76.87611018,184.62974,0,-14.03629709,0,112.6089018 +146.29,50.31210034,-3.243474116,10000,-76.869147,184.6391304,0,-14.03629709,0,112.6018759 +146.3,50.31209344,-3.243448235,10000,-76.85173915,184.6485208,0,-14.03629709,0,112.59485 +146.31,50.31208654,-3.243422352,10000,-76.81692356,184.658357,0,-14.03629709,0,112.587824 +146.32,50.31207965,-3.243396468,10000,-76.78210797,184.6686391,0,-14.03629709,0,112.5807981 +146.33,50.31207276,-3.243370582,10000,-76.76470012,184.6782524,0,-14.03629709,0,112.5737722 +146.34,50.31206587,-3.243344695,10000,-76.75773692,184.6867509,0,-14.03629709,0,112.5667463 +146.35,50.31205898,-3.243318807,10000,-76.74032909,184.6952495,0,-14.03629709,0,112.5597203 +146.36,50.31205209,-3.243292918,10000,-76.7055135,184.7046398,0,-14.03629709,0,112.5526944 +146.37,50.31204521,-3.243267027,10000,-76.67069791,184.7142531,0,-14.03629709,0,112.5456685 +146.38,50.31203833,-3.243241135,10000,-76.65329006,184.7236434,0,-14.03629709,0,112.5386426 +146.39,50.31203145,-3.243215242,10000,-76.64632688,184.7334796,0,-14.03629709,0,112.5316166 +146.4,50.31202457,-3.243189347,10000,-76.62891904,184.7437617,0,-14.03629709,0,112.5245907 +146.41,50.31201769,-3.243163451,10000,-76.59410343,184.7533749,0,-14.03629709,0,112.5175648 +146.42,50.31201082,-3.243137553,10000,-76.55928784,184.7620964,0,-14.03629709,0,112.5105389 +146.43,50.31200395,-3.243111655,10000,-76.54188,184.7712637,0,-14.03629709,0,112.5035129 +146.44,50.31199708,-3.243085755,10000,-76.53491682,184.7810999,0,-14.03629709,0,112.4964871 +146.45,50.31199021,-3.243059853,10000,-76.51750898,184.7902672,0,-14.03629709,0,112.4894611 +146.46,50.31198334,-3.243033951,10000,-76.48269337,184.7987657,0,-14.03629709,0,112.4824352 +146.47,50.31197648,-3.243008047,10000,-76.44787777,184.8074872,0,-14.03629709,0,112.4754093 +146.48,50.31196962,-3.242982142,10000,-76.43046992,184.8168774,0,-14.03629709,0,112.4683834 +146.49,50.31196276,-3.242956236,10000,-76.42350674,184.8273824,0,-14.03629709,0,112.4613574 +146.5,50.3119559,-3.242930328,10000,-76.40609891,184.8381103,0,-14.03629709,0,112.4543315 +146.51,50.31194904,-3.242904418,10000,-76.37128333,184.8475006,0,-14.03629709,0,112.4473056 +146.52,50.31194219,-3.242878508,10000,-76.33646774,184.855999,0,-14.03629709,0,112.4402797 +146.53,50.31193534,-3.242852596,10000,-76.31557835,184.8647204,0,-14.03629709,0,112.4332537 +146.54,50.31192849,-3.242826683,10000,-76.29817051,184.8738877,0,-14.03629709,0,112.4262278 +146.55,50.31192164,-3.242800769,10000,-76.27728111,184.8835009,0,-14.03629709,0,112.4192019 +146.56,50.3119148,-3.242774853,10000,-76.25987326,184.893114,0,-14.03629709,0,112.412176 +146.57,50.31190795,-3.242748936,10000,-76.2424654,184.9025043,0,-14.03629709,0,112.40515 +146.58,50.31190111,-3.242723018,10000,-76.21809445,184.9121174,0,-14.03629709,0,112.3981241 +146.59,50.31189427,-3.242697098,10000,-76.18676043,184.9215076,0,-14.03629709,0,112.3910982 +146.6,50.31188743,-3.242671177,10000,-76.14846331,184.930006,0,-14.03629709,0,112.3840723 +146.61,50.3118806,-3.242645255,10000,-76.11364772,184.9385044,0,-14.03629709,0,112.3770463 +146.62,50.31187377,-3.242619332,10000,-76.09623987,184.9481176,0,-14.03629709,0,112.3700204 +146.63,50.31186694,-3.242593407,10000,-76.09275823,184.9583995,0,-14.03629709,0,112.3629945 +146.64,50.31186011,-3.242567481,10000,-76.08927659,184.9682356,0,-14.03629709,0,112.3559686 +146.65,50.31185328,-3.242541553,10000,-76.07186875,184.9776258,0,-14.03629709,0,112.3489427 +146.66,50.31184645,-3.242515625,10000,-76.03705317,184.9872389,0,-14.03629709,0,112.3419167 +146.67,50.31183963,-3.242489694,10000,-76.00223759,184.9966291,0,-14.03629709,0,112.3348908 +146.68,50.31183281,-3.242463763,10000,-75.9813482,185.0049045,0,-14.03629709,0,112.3278649 +146.69,50.31182599,-3.24243783,10000,-75.9604588,185.012734,0,-14.03629709,0,112.320839 +146.7,50.31181917,-3.242411897,10000,-75.9256432,185.0219012,0,-14.03629709,0,112.313813 +146.71,50.31181236,-3.242385962,10000,-75.8908276,185.032629,0,-14.03629709,0,112.3067871 +146.72,50.31180555,-3.242360025,10000,-75.87341976,185.0429109,0,-14.03629709,0,112.2997612 +146.73,50.31179874,-3.242334087,10000,-75.86993813,185.0516322,0,-14.03629709,0,112.2927353 +146.74,50.31179193,-3.242308148,10000,-75.86645649,185.0601306,0,-14.03629709,0,112.2857093 +146.75,50.31178512,-3.242282208,10000,-75.84904866,185.0697437,0,-14.03629709,0,112.2786834 +146.76,50.31177831,-3.242256266,10000,-75.81423309,185.0800256,0,-14.03629709,0,112.2716575 +146.77,50.31177151,-3.242230323,10000,-75.77593595,185.0896386,0,-14.03629709,0,112.2646316 +146.78,50.31176471,-3.242204378,10000,-75.7446019,185.0981369,0,-14.03629709,0,112.2576057 +146.79,50.31175791,-3.242178433,10000,-75.72023094,185.1066353,0,-14.03629709,0,112.2505798 +146.8,50.31175112,-3.242152486,10000,-75.70282309,185.1162483,0,-14.03629709,0,112.2435538 +146.81,50.31174432,-3.242126538,10000,-75.68541525,185.1265302,0,-14.03629709,0,112.2365279 +146.82,50.31173753,-3.242100588,10000,-75.66452589,185.1361432,0,-14.03629709,0,112.229502 +146.83,50.31173074,-3.242074637,10000,-75.64711805,185.1446415,0,-14.03629709,0,112.2224761 +146.84,50.31172395,-3.242048685,10000,-75.62622866,185.1531398,0,-14.03629709,0,112.2154501 +146.85,50.31171716,-3.242022732,10000,-75.59141306,185.1625298,0,-14.03629709,0,112.2084242 +146.86,50.31171038,-3.241996777,10000,-75.55659748,185.1721429,0,-14.03629709,0,112.2013983 +146.87,50.3117036,-3.241970821,10000,-75.53918964,185.1815329,0,-14.03629709,0,112.1943724 +146.88,50.31169682,-3.241944864,10000,-75.53222644,185.1911459,0,-14.03629709,0,112.1873464 +146.89,50.31169004,-3.241918905,10000,-75.51481861,185.2007589,0,-14.03629709,0,112.1803205 +146.9,50.31168326,-3.241892945,10000,-75.48000303,185.209926,0,-14.03629709,0,112.1732946 +146.91,50.31167649,-3.241866984,10000,-75.44518745,185.2186472,0,-14.03629709,0,112.1662687 +146.92,50.31166972,-3.241841021,10000,-75.42777961,185.2271454,0,-14.03629709,0,112.1592427 +146.93,50.31166295,-3.241815058,10000,-75.42081641,185.2365355,0,-14.03629709,0,112.1522168 +146.94,50.31165618,-3.241789093,10000,-75.40340857,185.2470402,0,-14.03629709,0,112.1451909 +146.95,50.31164941,-3.241763126,10000,-75.36859298,185.2566532,0,-14.03629709,0,112.138165 +146.96,50.31164265,-3.241737158,10000,-75.3337774,185.2649285,0,-14.03629709,0,112.131139 +146.97,50.31163589,-3.24171119,10000,-75.31636957,185.2736496,0,-14.03629709,0,112.1241131 +146.98,50.31162913,-3.241685219,10000,-75.30940637,185.2830396,0,-14.03629709,0,112.1170872 +146.99,50.31162237,-3.241659248,10000,-75.29199854,185.2924296,0,-14.03629709,0,112.1100613 +147,50.31161561,-3.241633275,10000,-75.25718295,185.3020426,0,-14.03629709,0,112.1030353 +147.01,50.31160886,-3.241607301,10000,-75.22236735,185.3114325,0,-14.03629709,0,112.0960094 +147.02,50.31160211,-3.241581325,10000,-75.20495952,185.3199307,0,-14.03629709,0,112.0889835 +147.03,50.31159536,-3.241555349,10000,-75.19799635,185.3284289,0,-14.03629709,0,112.0819576 +147.04,50.31158861,-3.241529371,10000,-75.18058851,185.3380418,0,-14.03629709,0,112.0749316 +147.05,50.31158186,-3.241503392,10000,-75.14577292,185.3483236,0,-14.03629709,0,112.0679057 +147.06,50.31157512,-3.241477411,10000,-75.11095733,185.3579365,0,-14.03629709,0,112.0608798 +147.07,50.31156838,-3.241451429,10000,-75.09006794,185.3664346,0,-14.03629709,0,112.0538539 +147.08,50.31156164,-3.241425446,10000,-75.0726601,185.3749328,0,-14.03629709,0,112.046828 +147.09,50.3115549,-3.241399462,10000,-75.05177072,185.3843227,0,-14.03629709,0,112.039802 +147.1,50.31154817,-3.241373476,10000,-75.03436288,185.3939356,0,-14.03629709,0,112.0327762 +147.11,50.31154143,-3.241347489,10000,-75.01347349,185.4031026,0,-14.03629709,0,112.0257502 +147.12,50.3115347,-3.241321501,10000,-74.97865791,185.4120466,0,-14.03629709,0,112.0187243 +147.13,50.31152797,-3.241295511,10000,-74.94384232,185.4212136,0,-14.03629709,0,112.0116984 +147.14,50.31152125,-3.241269521,10000,-74.92295293,185.4306035,0,-14.03629709,0,112.0046725 +147.15,50.31151452,-3.241243528,10000,-74.9055451,185.4395475,0,-14.03629709,0,111.9976465 +147.16,50.3115078,-3.241217535,10000,-74.88465572,185.4484915,0,-14.03629709,0,111.9906206 +147.17,50.31150108,-3.241191541,10000,-74.86724788,185.4585503,0,-14.03629709,0,111.9835947 +147.18,50.31149436,-3.241165544,10000,-74.84984003,185.468609,0,-14.03629709,0,111.9765688 +147.19,50.31148764,-3.241139547,10000,-74.82895065,185.4771071,0,-14.03629709,0,111.9695428 +147.2,50.31148093,-3.241113548,10000,-74.81154283,185.4849364,0,-14.03629709,0,111.9625169 +147.21,50.31147421,-3.241087549,10000,-74.79065345,185.4938804,0,-14.03629709,0,111.955491 +147.22,50.3114675,-3.241061548,10000,-74.75583786,185.5037161,0,-14.03629709,0,111.9484651 +147.23,50.31146079,-3.241035545,10000,-74.72102227,185.513106,0,-14.03629709,0,111.9414391 +147.24,50.31145409,-3.241009542,10000,-74.70013289,185.5224959,0,-14.03629709,0,111.9344132 +147.25,50.31144738,-3.240983537,10000,-74.68272505,185.5323316,0,-14.03629709,0,111.9273873 +147.26,50.31144068,-3.24095753,10000,-74.66183566,185.5414985,0,-14.03629709,0,111.9203614 +147.27,50.31143398,-3.240931523,10000,-74.64442783,185.5499966,0,-14.03629709,0,111.9133354 +147.28,50.31142728,-3.240905514,10000,-74.62353844,185.5587176,0,-14.03629709,0,111.9063095 +147.29,50.31142058,-3.240879504,10000,-74.58872285,185.5678844,0,-14.03629709,0,111.8992836 +147.3,50.31141389,-3.240853493,10000,-74.55390726,185.5774972,0,-14.03629709,0,111.8922577 +147.31,50.3114072,-3.24082748,10000,-74.53649942,185.586887,0,-14.03629709,0,111.8852317 +147.32,50.31140051,-3.240801466,10000,-74.52953624,185.5953851,0,-14.03629709,0,111.8782058 +147.33,50.31139382,-3.240775451,10000,-74.51560995,185.6038831,0,-14.03629709,0,111.8711799 +147.34,50.31138713,-3.240749435,10000,-74.49472057,185.6134958,0,-14.03629709,0,111.864154 +147.35,50.31138045,-3.240723417,10000,-74.47383119,185.6237774,0,-14.03629709,0,111.857128 +147.36,50.31137376,-3.240697398,10000,-74.44249717,185.6333902,0,-14.03629709,0,111.8501021 +147.37,50.31136708,-3.240671377,10000,-74.40071849,185.6418882,0,-14.03629709,0,111.8430762 +147.38,50.31136041,-3.240645356,10000,-74.37286598,185.6501632,0,-14.03629709,0,111.8360503 +147.39,50.31135373,-3.240619333,10000,-74.3659028,185.6588842,0,-14.03629709,0,111.8290243 +147.4,50.31134706,-3.240593309,10000,-74.36242118,185.668051,0,-14.03629709,0,111.8219984 +147.41,50.31134038,-3.240567284,10000,-74.34501335,185.6776637,0,-14.03629709,0,111.8149725 +147.42,50.31133371,-3.240541257,10000,-74.31019777,185.6870535,0,-14.03629709,0,111.8079466 +147.43,50.31132704,-3.240515229,10000,-74.27538217,185.6955515,0,-14.03629709,0,111.8009206 +147.44,50.31132038,-3.2404892,10000,-74.25449278,185.7040494,0,-14.03629709,0,111.7938947 +147.45,50.31131371,-3.24046317,10000,-74.23360339,185.7136621,0,-14.03629709,0,111.7868689 +147.46,50.31130705,-3.240437138,10000,-74.19878782,185.7239437,0,-14.03629709,0,111.7798429 +147.47,50.31130039,-3.240411105,10000,-74.16397225,185.7335563,0,-14.03629709,0,111.772817 +147.48,50.31129374,-3.24038507,10000,-74.14656442,185.7420543,0,-14.03629709,0,111.7657911 +147.49,50.31128708,-3.240359035,10000,-74.14308279,185.7505522,0,-14.03629709,0,111.7587652 +147.5,50.31128043,-3.240332998,10000,-74.1361196,185.7599419,0,-14.03629709,0,111.7517392 +147.51,50.31127377,-3.24030696,10000,-74.1082671,185.7693317,0,-14.03629709,0,111.7447133 +147.52,50.31126712,-3.24028092,10000,-74.0664884,185.7778296,0,-14.03629709,0,111.7376874 +147.53,50.31126048,-3.24025488,10000,-74.03515436,185.7863275,0,-14.03629709,0,111.7306615 +147.54,50.31125383,-3.240228838,10000,-74.01426499,185.7957172,0,-14.03629709,0,111.7236355 +147.55,50.31124719,-3.240202795,10000,-73.99337562,185.8051069,0,-14.03629709,0,111.7166096 +147.56,50.31124055,-3.24017675,10000,-73.97596779,185.8136048,0,-14.03629709,0,111.7095837 +147.57,50.31123391,-3.240150705,10000,-73.95855996,185.8221027,0,-14.03629709,0,111.7025578 +147.58,50.31122727,-3.240124658,10000,-73.93767057,185.8317153,0,-14.03629709,0,111.6955318 +147.59,50.31122064,-3.24009861,10000,-73.92026275,185.8419967,0,-14.03629709,0,111.6885059 +147.6,50.311214,-3.24007256,10000,-73.90285492,185.8516094,0,-14.03629709,0,111.68148 +147.61,50.31120737,-3.240046509,10000,-73.87848398,185.8598843,0,-14.03629709,0,111.6744541 +147.62,50.31120074,-3.240020457,10000,-73.84714993,185.8674904,0,-14.03629709,0,111.6674281 +147.63,50.31119411,-3.239994404,10000,-73.8088528,185.8759882,0,-14.03629709,0,111.6604022 +147.64,50.31118749,-3.23996835,10000,-73.77403723,185.8862697,0,-14.03629709,0,111.6533763 +147.65,50.31118087,-3.239942294,10000,-73.7566294,185.896997,0,-14.03629709,0,111.6463504 +147.66,50.31117425,-3.239916236,10000,-73.75314777,185.9063866,0,-14.03629709,0,111.6393244 +147.67,50.31116763,-3.239890178,10000,-73.74966614,185.9148844,0,-14.03629709,0,111.6322985 +147.68,50.31116101,-3.239864118,10000,-73.73225831,185.9233823,0,-14.03629709,0,111.6252726 +147.69,50.31115439,-3.239838057,10000,-73.69744274,185.9316572,0,-14.03629709,0,111.6182467 +147.7,50.31114778,-3.239811995,10000,-73.6591456,185.940155,0,-14.03629709,0,111.6112207 +147.71,50.31114117,-3.239785932,10000,-73.62781156,185.9495446,0,-14.03629709,0,111.6041948 +147.72,50.31113456,-3.239759867,10000,-73.60344061,185.9589342,0,-14.03629709,0,111.5971689 +147.73,50.31112796,-3.239733801,10000,-73.58603278,185.967432,0,-14.03629709,0,111.590143 +147.74,50.31112135,-3.239707734,10000,-73.56862495,185.9759298,0,-14.03629709,0,111.583117 +147.75,50.31111475,-3.239681666,10000,-73.54773558,185.9853194,0,-14.03629709,0,111.5760911 +147.76,50.31110815,-3.239655596,10000,-73.53032777,185.9949319,0,-14.03629709,0,111.5690652 +147.77,50.31110155,-3.239629525,10000,-73.50943839,186.0043215,0,-14.03629709,0,111.5620393 +147.78,50.31109495,-3.239603453,10000,-73.47462278,186.0137111,0,-14.03629709,0,111.5550133 +147.79,50.31108836,-3.239577379,10000,-73.43980719,186.0224318,0,-14.03629709,0,111.5479875 +147.8,50.31108177,-3.239551304,10000,-73.42239937,186.0304836,0,-14.03629709,0,111.5409615 +147.81,50.31107518,-3.239525229,10000,-73.4154362,186.0392043,0,-14.03629709,0,111.5339356 +147.82,50.31106859,-3.239499151,10000,-73.39802837,186.0485939,0,-14.03629709,0,111.5269097 +147.83,50.311062,-3.239473073,10000,-73.36321278,186.0579834,0,-14.03629709,0,111.5198838 +147.84,50.31105542,-3.239446993,10000,-73.32839719,186.0675959,0,-14.03629709,0,111.5128578 +147.85,50.31104884,-3.239420912,10000,-73.31098936,186.0769854,0,-14.03629709,0,111.5058319 +147.86,50.31104226,-3.239394829,10000,-73.30402619,186.0854832,0,-14.03629709,0,111.498806 +147.87,50.31103568,-3.239368746,10000,-73.28661836,186.0937579,0,-14.03629709,0,111.4917801 +147.88,50.3110291,-3.239342661,10000,-73.25180278,186.1024786,0,-14.03629709,0,111.4847542 +147.89,50.31102253,-3.239316575,10000,-73.21698721,186.1116452,0,-14.03629709,0,111.4777282 +147.9,50.31101596,-3.239290488,10000,-73.19957937,186.1212576,0,-14.03629709,0,111.4707023 +147.91,50.31100939,-3.239264399,10000,-73.19261618,186.1306471,0,-14.03629709,0,111.4636764 +147.92,50.31100282,-3.239238309,10000,-73.17520835,186.1391448,0,-14.03629709,0,111.4566505 +147.93,50.31099625,-3.239212218,10000,-73.14039279,186.1476425,0,-14.03629709,0,111.4496245 +147.94,50.31098969,-3.239186126,10000,-73.10557722,186.157032,0,-14.03629709,0,111.4425986 +147.95,50.31098313,-3.239160032,10000,-73.08468783,186.1664215,0,-14.03629709,0,111.4355727 +147.96,50.31097657,-3.239133937,10000,-73.06727998,186.1749191,0,-14.03629709,0,111.4285468 +147.97,50.31097001,-3.239107841,10000,-73.0463906,186.1831939,0,-14.03629709,0,111.4215208 +147.98,50.31096346,-3.239081744,10000,-73.02898278,186.1919145,0,-14.03629709,0,111.4144949 +147.99,50.3109569,-3.239055645,10000,-73.01157496,186.201081,0,-14.03629709,0,111.407469 +148,50.31095035,-3.239029546,10000,-72.98720403,186.2106934,0,-14.03629709,0,111.4004431 +148.01,50.3109438,-3.239003444,10000,-72.95586999,186.2203058,0,-14.03629709,0,111.3934171 +148.02,50.31093725,-3.238977342,10000,-72.9210544,186.2292493,0,-14.03629709,0,111.3863912 +148.03,50.31093071,-3.238951238,10000,-72.89668348,186.2373011,0,-14.03629709,0,111.3793653 +148.04,50.31092417,-3.238925133,10000,-72.88275722,186.2453528,0,-14.03629709,0,111.3723394 +148.05,50.31091762,-3.238899028,10000,-72.86186784,186.2549652,0,-14.03629709,0,111.3653134 +148.06,50.31091109,-3.23887292,10000,-72.84097845,186.2654693,0,-14.03629709,0,111.3582875 +148.07,50.31090455,-3.238846811,10000,-72.82705216,186.2746358,0,-14.03629709,0,111.3512616 +148.08,50.31089801,-3.238820701,10000,-72.80268122,186.2824645,0,-14.03629709,0,111.3442357 +148.09,50.31089148,-3.23879459,10000,-72.7713472,186.2907392,0,-14.03629709,0,111.3372097 +148.1,50.31088495,-3.238768478,10000,-72.75045783,186.3001286,0,-14.03629709,0,111.3301838 +148.11,50.31087842,-3.238742364,10000,-72.72956845,186.309518,0,-14.03629709,0,111.3231579 +148.12,50.31087189,-3.238716249,10000,-72.69475287,186.3180156,0,-14.03629709,0,111.316132 +148.13,50.31086537,-3.238690133,10000,-72.65993729,186.3265131,0,-14.03629709,0,111.309106 +148.14,50.31085885,-3.238664016,10000,-72.64252947,186.3356796,0,-14.03629709,0,111.3020802 +148.15,50.31085233,-3.238637897,10000,-72.6355663,186.3441771,0,-14.03629709,0,111.2950542 +148.16,50.31084581,-3.238611777,10000,-72.62164002,186.3515599,0,-14.03629709,0,111.2880283 +148.17,50.31083929,-3.238585657,10000,-72.60075064,186.3600575,0,-14.03629709,0,111.2810024 +148.18,50.31083278,-3.238559535,10000,-72.57986125,186.3705616,0,-14.03629709,0,111.2739765 +148.19,50.31082626,-3.238533411,10000,-72.54852722,186.3808427,0,-14.03629709,0,111.2669505 +148.2,50.31081975,-3.238507286,10000,-72.50674854,186.3895632,0,-14.03629709,0,111.2599246 +148.21,50.31081325,-3.23848116,10000,-72.47889607,186.3980608,0,-14.03629709,0,111.2528987 +148.22,50.31080674,-3.238455033,10000,-72.4719329,186.4072271,0,-14.03629709,0,111.2458728 +148.23,50.31080024,-3.238428904,10000,-72.46496971,186.4159476,0,-14.03629709,0,111.2388468 +148.24,50.31079373,-3.238402774,10000,-72.43711723,186.4239992,0,-14.03629709,0,111.2318209 +148.25,50.31078723,-3.238376644,10000,-72.39533856,186.4327197,0,-14.03629709,0,111.224795 +148.26,50.31078074,-3.238350511,10000,-72.3674861,186.442109,0,-14.03629709,0,111.2177691 +148.27,50.31077424,-3.238324378,10000,-72.36052291,186.4512753,0,-14.03629709,0,111.2107432 +148.28,50.31076775,-3.238298243,10000,-72.35355973,186.4602187,0,-14.03629709,0,111.2037172 +148.29,50.31076125,-3.238272107,10000,-72.32570725,186.4693851,0,-14.03629709,0,111.1966913 +148.3,50.31075476,-3.23824597,10000,-72.28392858,186.4787744,0,-14.03629709,0,111.1896654 +148.31,50.31074828,-3.238219831,10000,-72.25259455,186.4874948,0,-14.03629709,0,111.1826395 +148.32,50.31074179,-3.238193691,10000,-72.23170517,186.4955464,0,-14.03629709,0,111.1756135 +148.33,50.31073531,-3.238167551,10000,-72.21081579,186.5042668,0,-14.03629709,0,111.1685876 +148.34,50.31072883,-3.238141408,10000,-72.19688951,186.513656,0,-14.03629709,0,111.1615617 +148.35,50.31072235,-3.238115265,10000,-72.18992633,186.5228223,0,-14.03629709,0,111.1545358 +148.36,50.31071587,-3.23808912,10000,-72.17251852,186.5315427,0,-14.03629709,0,111.1475098 +148.37,50.31070939,-3.238062974,10000,-72.13770295,186.5395943,0,-14.03629709,0,111.1404839 +148.38,50.31070292,-3.238036827,10000,-72.10288737,186.5471999,0,-14.03629709,0,111.133458 +148.39,50.31069645,-3.238010679,10000,-72.08199798,186.5554744,0,-14.03629709,0,111.1264321 +148.4,50.31068998,-3.23798453,10000,-72.06459015,186.5650866,0,-14.03629709,0,111.1194061 +148.41,50.31068351,-3.237958379,10000,-72.04370078,186.5753676,0,-14.03629709,0,111.1123802 +148.42,50.31067705,-3.237932227,10000,-72.02629296,186.5849798,0,-14.03629709,0,111.1053543 +148.43,50.31067058,-3.237906073,10000,-72.00540359,186.5934772,0,-14.03629709,0,111.0983284 +148.44,50.31066412,-3.237879919,10000,-71.97058801,186.6017516,0,-14.03629709,0,111.0913024 +148.45,50.31065766,-3.237853763,10000,-71.93577241,186.610472,0,-14.03629709,0,111.0842766 +148.46,50.31065121,-3.237827606,10000,-71.91488303,186.6194153,0,-14.03629709,0,111.0772506 +148.47,50.31064475,-3.237801448,10000,-71.89747522,186.6281356,0,-14.03629709,0,111.0702247 +148.48,50.3106383,-3.237775288,10000,-71.87658586,186.63641,0,-14.03629709,0,111.0631988 +148.49,50.31063185,-3.237749128,10000,-71.85917804,186.6449074,0,-14.03629709,0,111.0561729 +148.5,50.3106254,-3.237722966,10000,-71.83828866,186.6542966,0,-14.03629709,0,111.0491469 +148.51,50.31061895,-3.237696803,10000,-71.80695463,186.6636857,0,-14.03629709,0,111.042121 +148.52,50.31061251,-3.237670638,10000,-71.78258371,186.6721831,0,-14.03629709,0,111.0350951 +148.53,50.31060607,-3.237644473,10000,-71.76865743,186.6806805,0,-14.03629709,0,111.0280692 +148.54,50.31059962,-3.237618306,10000,-71.7442865,186.6900696,0,-14.03629709,0,111.0210432 +148.55,50.31059319,-3.237592138,10000,-71.71295247,186.6994587,0,-14.03629709,0,111.0140173 +148.56,50.31058675,-3.237565968,10000,-71.69554465,186.7079561,0,-14.03629709,0,111.0069914 +148.57,50.31058032,-3.237539798,10000,-71.68858147,186.7162305,0,-14.03629709,0,110.9999655 +148.58,50.31057388,-3.237513626,10000,-71.67117364,186.7249507,0,-14.03629709,0,110.9929395 +148.59,50.31056745,-3.237487453,10000,-71.63635807,186.733894,0,-14.03629709,0,110.9859136 +148.6,50.31056102,-3.237461279,10000,-71.6015425,186.7426142,0,-14.03629709,0,110.9788877 +148.61,50.3105546,-3.237435103,10000,-71.58065313,186.7508886,0,-14.03629709,0,110.9718618 +148.62,50.31054817,-3.237408927,10000,-71.5632453,186.7593859,0,-14.03629709,0,110.9648358 +148.63,50.31054175,-3.237382749,10000,-71.53887437,186.768775,0,-14.03629709,0,110.9578099 +148.64,50.31053533,-3.23735657,10000,-71.51102189,186.7781641,0,-14.03629709,0,110.950784 +148.65,50.31052891,-3.237330389,10000,-71.48665097,186.7866614,0,-14.03629709,0,110.9437581 +148.66,50.3105225,-3.237304208,10000,-71.46924315,186.7949357,0,-14.03629709,0,110.9367322 +148.67,50.31051608,-3.237278025,10000,-71.44835377,186.8036559,0,-14.03629709,0,110.9297062 +148.68,50.31050967,-3.237251841,10000,-71.4135382,186.8125991,0,-14.03629709,0,110.9226803 +148.69,50.31050326,-3.237225656,10000,-71.37872262,186.8213193,0,-14.03629709,0,110.9156544 +148.7,50.31049686,-3.237199469,10000,-71.35783325,186.8295936,0,-14.03629709,0,110.9086285 +148.71,50.31049045,-3.237173282,10000,-71.34042544,186.8380908,0,-14.03629709,0,110.9016025 +148.72,50.31048405,-3.237147093,10000,-71.31953607,186.8477028,0,-14.03629709,0,110.8945766 +148.73,50.31047765,-3.237120903,10000,-71.30560979,186.8577607,0,-14.03629709,0,110.8875507 +148.74,50.31047125,-3.237094711,10000,-71.2986466,186.8664809,0,-14.03629709,0,110.8805248 +148.75,50.31046485,-3.237068518,10000,-71.28123877,186.8736404,0,-14.03629709,0,110.8734988 +148.76,50.31045845,-3.237042325,10000,-71.24642321,186.8812458,0,-14.03629709,0,110.8664729 +148.77,50.31045206,-3.23701613,10000,-71.21160765,186.8906349,0,-14.03629709,0,110.859447 +148.78,50.31044567,-3.236989934,10000,-71.19071828,186.9006927,0,-14.03629709,0,110.8524211 +148.79,50.31043928,-3.236963736,10000,-71.17331044,186.9096358,0,-14.03629709,0,110.8453951 +148.8,50.31043289,-3.236937537,10000,-71.15242105,186.9176871,0,-14.03629709,0,110.8383693 +148.81,50.31042651,-3.236911338,10000,-71.13501323,186.9264073,0,-14.03629709,0,110.8313433 +148.82,50.31042012,-3.236885136,10000,-71.11412387,186.9357963,0,-14.03629709,0,110.8243174 +148.83,50.31041374,-3.236858934,10000,-71.07930831,186.9447394,0,-14.03629709,0,110.8172915 +148.84,50.31040736,-3.23683273,10000,-71.04449273,186.9527906,0,-14.03629709,0,110.8102656 +148.85,50.31040099,-3.236806525,10000,-71.02360334,186.9606189,0,-14.03629709,0,110.8032396 +148.86,50.31039461,-3.23678032,10000,-71.00619553,186.969339,0,-14.03629709,0,110.7962137 +148.87,50.31038824,-3.236754112,10000,-70.98182462,186.9785051,0,-14.03629709,0,110.7891878 +148.88,50.31038187,-3.236727904,10000,-70.95397215,186.9867793,0,-14.03629709,0,110.7821619 +148.89,50.3103755,-3.236701694,10000,-70.92960123,186.9946075,0,-14.03629709,0,110.7751359 +148.9,50.31036914,-3.236675484,10000,-70.9121934,187.0035506,0,-14.03629709,0,110.76811 +148.91,50.31036277,-3.236649272,10000,-70.89478557,187.0133854,0,-14.03629709,0,110.7610841 +148.92,50.31035641,-3.236623058,10000,-70.87389619,187.0225514,0,-14.03629709,0,110.7540582 +148.93,50.31035005,-3.236596844,10000,-70.85648835,187.0310485,0,-14.03629709,0,110.7470322 +148.94,50.31034369,-3.236570628,10000,-70.83559898,187.0397686,0,-14.03629709,0,110.7400063 +148.95,50.31033733,-3.236544411,10000,-70.80078343,187.0487116,0,-14.03629709,0,110.7329804 +148.96,50.31033098,-3.236518193,10000,-70.76596788,187.0574317,0,-14.03629709,0,110.7259545 +148.97,50.31032463,-3.236491973,10000,-70.74856006,187.0654829,0,-14.03629709,0,110.7189285 +148.98,50.31031828,-3.236465753,10000,-70.74159687,187.0730881,0,-14.03629709,0,110.7119026 +148.99,50.31031193,-3.236439531,10000,-70.72418903,187.0813623,0,-14.03629709,0,110.7048767 +149,50.31030558,-3.236413309,10000,-70.68937346,187.0907512,0,-14.03629709,0,110.6978508 +149.01,50.31029924,-3.236387084,10000,-70.65455789,187.100363,0,-14.03629709,0,110.6908248 +149.02,50.3102929,-3.236360859,10000,-70.63715007,187.1095289,0,-14.03629709,0,110.6837989 +149.03,50.31028656,-3.236334632,10000,-70.6301869,187.118249,0,-14.03629709,0,110.676773 +149.04,50.31028022,-3.236308404,10000,-70.61277909,187.1265231,0,-14.03629709,0,110.6697471 +149.05,50.31027388,-3.236282175,10000,-70.57796352,187.1347972,0,-14.03629709,0,110.6627211 +149.06,50.31026755,-3.236255945,10000,-70.54314794,187.1432942,0,-14.03629709,0,110.6556952 +149.07,50.31026122,-3.236229713,10000,-70.52225856,187.1515683,0,-14.03629709,0,110.6486693 +149.08,50.31025489,-3.236203481,10000,-70.50485075,187.1598424,0,-14.03629709,0,110.6416434 +149.09,50.31024856,-3.236177247,10000,-70.48396138,187.1685624,0,-14.03629709,0,110.6346175 +149.1,50.31024224,-3.236151012,10000,-70.46655355,187.1775053,0,-14.03629709,0,110.6275915 +149.11,50.31023591,-3.236124776,10000,-70.44566418,187.1864482,0,-14.03629709,0,110.6205656 +149.12,50.31022959,-3.236098538,10000,-70.41084862,187.1956141,0,-14.03629709,0,110.6135397 +149.13,50.31022327,-3.2360723,10000,-70.37603305,187.2050029,0,-14.03629709,0,110.6065138 +149.14,50.31021696,-3.236046059,10000,-70.35514368,187.2134999,0,-14.03629709,0,110.5994878 +149.15,50.31021064,-3.236019818,10000,-70.33773586,187.2206592,0,-14.03629709,0,110.592462 +149.16,50.31020433,-3.235993576,10000,-70.31684649,187.2282643,0,-14.03629709,0,110.585436 +149.17,50.31019802,-3.235967333,10000,-70.29943866,187.2376531,0,-14.03629709,0,110.5784101 +149.18,50.31019171,-3.235941088,10000,-70.28203083,187.2479337,0,-14.03629709,0,110.5713842 +149.19,50.3101854,-3.235914842,10000,-70.26114147,187.2573225,0,-14.03629709,0,110.5643583 +149.2,50.3101791,-3.235888594,10000,-70.2402521,187.2649277,0,-14.03629709,0,110.5573323 +149.21,50.31017279,-3.235862346,10000,-70.20891808,187.2720869,0,-14.03629709,0,110.5503064 +149.22,50.31016649,-3.235836097,10000,-70.17062097,187.2805839,0,-14.03629709,0,110.5432805 +149.23,50.3101602,-3.235809846,10000,-70.15321314,187.2897497,0,-14.03629709,0,110.5362546 +149.24,50.3101539,-3.235783594,10000,-70.14973152,187.2982466,0,-14.03629709,0,110.5292286 +149.25,50.3101476,-3.235757341,10000,-70.12884215,187.3067436,0,-14.03629709,0,110.5222027 +149.26,50.31014131,-3.235731087,10000,-70.09402659,187.3161323,0,-14.03629709,0,110.5151768 +149.27,50.31013502,-3.235704831,10000,-70.06269255,187.325521,0,-14.03629709,0,110.5081509 +149.28,50.31012873,-3.235678574,10000,-70.03832163,187.333795,0,-14.03629709,0,110.5011249 +149.29,50.31012245,-3.235652316,10000,-70.02091383,187.3414001,0,-14.03629709,0,110.494099 +149.3,50.31011616,-3.235626057,10000,-70.00350602,187.3496741,0,-14.03629709,0,110.4870731 +149.31,50.31010988,-3.235599797,10000,-69.97913509,187.3590628,0,-14.03629709,0,110.4800472 +149.32,50.3101036,-3.235573535,10000,-69.95128262,187.3684515,0,-14.03629709,0,110.4730212 +149.33,50.31009732,-3.235547272,10000,-69.92691169,187.3767254,0,-14.03629709,0,110.4659953 +149.34,50.31009105,-3.235521008,10000,-69.90950386,187.3843305,0,-14.03629709,0,110.4589694 +149.35,50.31008477,-3.235494743,10000,-69.88861448,187.3926044,0,-14.03629709,0,110.4519435 +149.36,50.3100785,-3.235468477,10000,-69.85379893,187.4017701,0,-14.03629709,0,110.4449175 +149.37,50.31007223,-3.235442209,10000,-69.81898339,187.410267,0,-14.03629709,0,110.4378916 +149.38,50.31006597,-3.23541594,10000,-69.79809403,187.4176491,0,-14.03629709,0,110.4308657 +149.39,50.3100597,-3.235389671,10000,-69.7806862,187.425923,0,-14.03629709,0,110.4238398 +149.4,50.31005344,-3.2353634,10000,-69.75979681,187.4355346,0,-14.03629709,0,110.4168138 +149.41,50.31004718,-3.235337127,10000,-69.74587053,187.4447003,0,-14.03629709,0,110.4097879 +149.42,50.31004092,-3.235310854,10000,-69.73890735,187.4534201,0,-14.03629709,0,110.402762 +149.43,50.31003466,-3.235284579,10000,-69.72149954,187.4628087,0,-14.03629709,0,110.3957361 +149.44,50.3100284,-3.235258303,10000,-69.68668398,187.4719744,0,-14.03629709,0,110.3887101 +149.45,50.31002215,-3.235232025,10000,-69.65186843,187.4795794,0,-14.03629709,0,110.3816842 +149.46,50.3100159,-3.235205747,10000,-69.63097907,187.4867385,0,-14.03629709,0,110.3746584 +149.47,50.31000965,-3.235179468,10000,-69.6100897,187.4952353,0,-14.03629709,0,110.3676324 +149.48,50.3100034,-3.235153187,10000,-69.57875567,187.504401,0,-14.03629709,0,110.3606065 +149.49,50.30999716,-3.235126905,10000,-69.55438475,187.5126748,0,-14.03629709,0,110.3535806 +149.5,50.30999092,-3.235100622,10000,-69.54045846,187.5202798,0,-14.03629709,0,110.3465547 +149.51,50.30998467,-3.235074338,10000,-69.51956909,187.5285536,0,-14.03629709,0,110.3395287 +149.52,50.30997844,-3.235048053,10000,-69.49867973,187.5379422,0,-14.03629709,0,110.3325028 +149.53,50.3099722,-3.235021766,10000,-69.48475347,187.5473308,0,-14.03629709,0,110.3254769 +149.54,50.30996596,-3.234995478,10000,-69.46038255,187.5558276,0,-14.03629709,0,110.318451 +149.55,50.30995973,-3.234969189,10000,-69.42556699,187.5641014,0,-14.03629709,0,110.311425 +149.56,50.3099535,-3.234942899,10000,-69.39423297,187.5725981,0,-14.03629709,0,110.3043991 +149.57,50.30994727,-3.234916607,10000,-69.36986206,187.5808719,0,-14.03629709,0,110.2973732 +149.58,50.30994105,-3.234890315,10000,-69.35245424,187.5891457,0,-14.03629709,0,110.2903473 +149.59,50.30993482,-3.234864021,10000,-69.33504642,187.5978654,0,-14.03629709,0,110.2833213 +149.6,50.3099286,-3.234837726,10000,-69.31067551,187.606808,0,-14.03629709,0,110.2762954 +149.61,50.30992238,-3.23481143,10000,-69.28282306,187.6155277,0,-14.03629709,0,110.2692695 +149.62,50.30991616,-3.234785132,10000,-69.25845214,187.6238015,0,-14.03629709,0,110.2622436 +149.63,50.30990995,-3.234758834,10000,-69.24104431,187.6320752,0,-14.03629709,0,110.2552176 +149.64,50.30990373,-3.234732534,10000,-69.22363648,187.6405719,0,-14.03629709,0,110.2481917 +149.65,50.30989752,-3.234706233,10000,-69.19926556,187.6488457,0,-14.03629709,0,110.2411658 +149.66,50.30989131,-3.234679931,10000,-69.17141309,187.6571194,0,-14.03629709,0,110.2341399 +149.67,50.3098851,-3.234653628,10000,-69.14704217,187.6656161,0,-14.03629709,0,110.2271139 +149.68,50.3098789,-3.234627323,10000,-69.12963436,187.6738898,0,-14.03629709,0,110.220088 +149.69,50.30987269,-3.234601018,10000,-69.108745,187.6823865,0,-14.03629709,0,110.2130621 +149.7,50.30986649,-3.234574711,10000,-69.07392943,187.691775,0,-14.03629709,0,110.2060362 +149.71,50.30986029,-3.234548403,10000,-69.03911387,187.7011635,0,-14.03629709,0,110.1990102 +149.72,50.3098541,-3.234522093,10000,-69.01822452,187.7094372,0,-14.03629709,0,110.1919843 +149.73,50.3098479,-3.234495783,10000,-69.00081669,187.7168191,0,-14.03629709,0,110.1849584 +149.74,50.30984171,-3.234469471,10000,-68.97992732,187.7242009,0,-14.03629709,0,110.1779325 +149.75,50.30983552,-3.234443159,10000,-68.96600106,187.7324746,0,-14.03629709,0,110.1709065 +149.76,50.30982933,-3.234416845,10000,-68.9590379,187.7418631,0,-14.03629709,0,110.1638806 +149.77,50.30982314,-3.23439053,10000,-68.94163008,187.7512515,0,-14.03629709,0,110.1568547 +149.78,50.30981695,-3.234364213,10000,-68.9068145,187.7597482,0,-14.03629709,0,110.1498288 +149.79,50.30981077,-3.234337896,10000,-68.86851739,187.7680218,0,-14.03629709,0,110.1428028 +149.8,50.30980459,-3.234311577,10000,-68.83718338,187.7765184,0,-14.03629709,0,110.1357769 +149.81,50.30979841,-3.234285257,10000,-68.81281246,187.7845691,0,-14.03629709,0,110.128751 +149.82,50.30979224,-3.234258936,10000,-68.79540463,187.7921739,0,-14.03629709,0,110.1217251 +149.83,50.30978606,-3.234232614,10000,-68.77799682,187.8004475,0,-14.03629709,0,110.1146991 +149.84,50.30977989,-3.234206291,10000,-68.75710747,187.809613,0,-14.03629709,0,110.1076733 +149.85,50.30977372,-3.234179966,10000,-68.73969966,187.8181096,0,-14.03629709,0,110.1006473 +149.86,50.30976755,-3.23415364,10000,-68.71881029,187.8254914,0,-14.03629709,0,110.0936214 +149.87,50.30976138,-3.234127314,10000,-68.68399472,187.833765,0,-14.03629709,0,110.0865955 +149.88,50.30975522,-3.234100986,10000,-68.64917914,187.8433763,0,-14.03629709,0,110.0795696 +149.89,50.30974906,-3.234074656,10000,-68.63177133,187.8523188,0,-14.03629709,0,110.0725437 +149.9,50.3097429,-3.234048326,10000,-68.62480817,187.8601465,0,-14.03629709,0,110.0655177 +149.91,50.30973674,-3.234021994,10000,-68.60740035,187.8684201,0,-14.03629709,0,110.0584918 +149.92,50.30973058,-3.233995662,10000,-68.57258479,187.8775855,0,-14.03629709,0,110.0514659 +149.93,50.30972443,-3.233969327,10000,-68.53776923,187.886305,0,-14.03629709,0,110.04444 +149.94,50.30971828,-3.233942992,10000,-68.52036143,187.8941326,0,-14.03629709,0,110.037414 +149.95,50.30971213,-3.233916656,10000,-68.51339825,187.9019603,0,-14.03629709,0,110.0303881 +149.96,50.30970598,-3.233890318,10000,-68.49599042,187.9100109,0,-14.03629709,0,110.0233622 +149.97,50.30969983,-3.23386398,10000,-68.46117485,187.9182844,0,-14.03629709,0,110.0163363 +149.98,50.30969369,-3.23383764,10000,-68.42635929,187.9270039,0,-14.03629709,0,110.0093103 +149.99,50.30968755,-3.233811299,10000,-68.40546994,187.9359463,0,-14.03629709,0,110.0022844 +150,50.30968141,-3.233784957,10000,-68.38806214,187.9446657,0,-14.03629709,0,109.9952585 +150.01,50.30967527,-3.233758613,10000,-68.36717277,187.9529393,0,-14.03629709,0,109.9882326 +150.02,50.30966914,-3.233732269,10000,-68.34976495,187.9612128,0,-14.03629709,0,109.9812066 +150.03,50.309663,-3.233705923,10000,-68.33235713,187.9697093,0,-14.03629709,0,109.9741807 +150.04,50.30965687,-3.233679576,10000,-68.30798621,187.9777598,0,-14.03629709,0,109.9671548 +150.05,50.30965074,-3.233653228,10000,-68.2766522,187.9853645,0,-14.03629709,0,109.9601289 +150.06,50.30964461,-3.233626879,10000,-68.23835509,187.993638,0,-14.03629709,0,109.9531029 +150.07,50.30963849,-3.233600529,10000,-68.20353953,188.0030262,0,-14.03629709,0,109.946077 +150.08,50.30963237,-3.233574177,10000,-68.18613171,188.0124145,0,-14.03629709,0,109.9390511 +150.09,50.30962625,-3.233547824,10000,-68.17916855,188.020688,0,-14.03629709,0,109.9320252 +150.1,50.30962013,-3.23352147,10000,-68.16524228,188.0280696,0,-14.03629709,0,109.9249992 +150.11,50.30961401,-3.233495115,10000,-68.14435291,188.0354513,0,-14.03629709,0,109.9179733 +150.12,50.3096079,-3.233468759,10000,-68.1269451,188.0435018,0,-14.03629709,0,109.9109474 +150.13,50.30960178,-3.233442402,10000,-68.10605575,188.0522212,0,-14.03629709,0,109.9039215 +150.14,50.30959567,-3.233416043,10000,-68.07124019,188.0611635,0,-14.03629709,0,109.8968955 +150.15,50.30958956,-3.233389684,10000,-68.03642463,188.0698829,0,-14.03629709,0,109.8898697 +150.16,50.30958346,-3.233363322,10000,-68.01553527,188.0781563,0,-14.03629709,0,109.8828437 +150.17,50.30957735,-3.233336961,10000,-67.99812745,188.0864297,0,-14.03629709,0,109.8758178 +150.18,50.30957125,-3.233310597,10000,-67.97375653,188.0951491,0,-14.03629709,0,109.8687919 +150.19,50.30956515,-3.233284233,10000,-67.94590406,188.1038684,0,-14.03629709,0,109.861766 +150.2,50.30955905,-3.233257867,10000,-67.92153315,188.1116959,0,-14.03629709,0,109.85474 +150.21,50.30955296,-3.2332315,10000,-67.90412534,188.1188545,0,-14.03629709,0,109.8477141 +150.22,50.30954686,-3.233205133,10000,-67.88671752,188.1271279,0,-14.03629709,0,109.8406882 +150.23,50.30954077,-3.233178764,10000,-67.86234661,188.1365161,0,-14.03629709,0,109.8336623 +150.24,50.30953468,-3.233152393,10000,-67.83449416,188.1447895,0,-14.03629709,0,109.8266363 +150.25,50.30952859,-3.233126022,10000,-67.81012324,188.1521711,0,-14.03629709,0,109.8196104 +150.26,50.30952251,-3.23309965,10000,-67.79271542,188.1606674,0,-14.03629709,0,109.8125845 +150.27,50.30951642,-3.233073276,10000,-67.77530761,188.1698326,0,-14.03629709,0,109.8055586 +150.28,50.30951034,-3.233046901,10000,-67.75093672,188.178106,0,-14.03629709,0,109.7985327 +150.29,50.30950426,-3.233020525,10000,-67.7196027,188.1857105,0,-14.03629709,0,109.7915067 +150.3,50.30949818,-3.232994148,10000,-67.68130558,188.1939838,0,-14.03629709,0,109.7844808 +150.31,50.30949211,-3.23296777,10000,-67.64649001,188.2033719,0,-14.03629709,0,109.7774549 +150.32,50.30948604,-3.23294139,10000,-67.62908222,188.2125371,0,-14.03629709,0,109.770429 +150.33,50.30947997,-3.232915009,10000,-67.6256006,188.2201416,0,-14.03629709,0,109.763403 +150.34,50.3094739,-3.232888627,10000,-67.62211897,188.2273001,0,-14.03629709,0,109.7563771 +150.35,50.30946783,-3.232862245,10000,-67.60471116,188.2355735,0,-14.03629709,0,109.7493512 +150.36,50.30946176,-3.23283586,10000,-67.56989561,188.2440697,0,-14.03629709,0,109.7423253 +150.37,50.3094557,-3.232809475,10000,-67.53159852,188.2521201,0,-14.03629709,0,109.7352993 +150.38,50.30944964,-3.232783089,10000,-67.50026451,188.2606164,0,-14.03629709,0,109.7282734 +150.39,50.30944358,-3.232756701,10000,-67.47589359,188.2691126,0,-14.03629709,0,109.7212475 +150.4,50.30943753,-3.232730312,10000,-67.45848577,188.2771629,0,-14.03629709,0,109.7142216 +150.41,50.30943147,-3.232703923,10000,-67.44107794,188.2858821,0,-14.03629709,0,109.7071956 +150.42,50.30942542,-3.232677531,10000,-67.42018858,188.2950472,0,-14.03629709,0,109.7001697 +150.43,50.30941937,-3.232651139,10000,-67.40278077,188.3033205,0,-14.03629709,0,109.6931438 +150.44,50.30941332,-3.232624745,10000,-67.38189142,188.310702,0,-14.03629709,0,109.6861179 +150.45,50.30940727,-3.232598351,10000,-67.34707587,188.3180834,0,-14.03629709,0,109.6790919 +150.46,50.30940123,-3.232571955,10000,-67.31226031,188.3263567,0,-14.03629709,0,109.672066 +150.47,50.30939519,-3.232545559,10000,-67.29485249,188.3355217,0,-14.03629709,0,109.6650401 +150.48,50.30938915,-3.23251916,10000,-67.28788933,188.3440179,0,-14.03629709,0,109.6580142 +150.49,50.30938311,-3.232492761,10000,-67.27048151,188.3511764,0,-14.03629709,0,109.6509882 +150.5,50.30937707,-3.232466361,10000,-67.23566595,188.3587808,0,-14.03629709,0,109.6439624 +150.51,50.30937104,-3.23243996,10000,-67.20085039,188.3679458,0,-14.03629709,0,109.6369364 +150.52,50.30936501,-3.232413557,10000,-67.18344259,188.3773338,0,-14.03629709,0,109.6299105 +150.53,50.30935898,-3.232387153,10000,-67.17647942,188.385607,0,-14.03629709,0,109.6228846 +150.54,50.30935295,-3.232360748,10000,-67.1590716,188.3929884,0,-14.03629709,0,109.6158587 +150.55,50.30934692,-3.232334342,10000,-67.12425604,188.4003698,0,-14.03629709,0,109.6088327 +150.56,50.3093409,-3.232307935,10000,-67.08944049,188.40842,0,-14.03629709,0,109.6018068 +150.57,50.30933488,-3.232281527,10000,-67.06855114,188.4169162,0,-14.03629709,0,109.5947809 +150.58,50.30932886,-3.232255117,10000,-67.05114332,188.4251894,0,-14.03629709,0,109.587755 +150.59,50.30932284,-3.232228707,10000,-67.03025396,188.4334625,0,-14.03629709,0,109.580729 +150.6,50.30931683,-3.232202295,10000,-67.01284615,188.4421816,0,-14.03629709,0,109.5737031 +150.61,50.30931081,-3.232175882,10000,-66.99195678,188.4511237,0,-14.03629709,0,109.5666772 +150.62,50.3093048,-3.232149468,10000,-66.95714123,188.4596198,0,-14.03629709,0,109.5596513 +150.63,50.30929879,-3.232123052,10000,-66.92232567,188.4670011,0,-14.03629709,0,109.5526253 +150.64,50.30929279,-3.232096636,10000,-66.90143632,188.4741595,0,-14.03629709,0,109.5455994 +150.65,50.30928678,-3.232070219,10000,-66.88402852,188.4826556,0,-14.03629709,0,109.5385735 +150.66,50.30928078,-3.2320438,10000,-66.86313916,188.4918205,0,-14.03629709,0,109.5315476 +150.67,50.30927478,-3.23201738,10000,-66.84573135,188.5003166,0,-14.03629709,0,109.5245217 +150.68,50.30926878,-3.231990959,10000,-66.82484198,188.5085897,0,-14.03629709,0,109.5174957 +150.69,50.30926278,-3.231964537,10000,-66.79002641,188.5170858,0,-14.03629709,0,109.5104698 +150.7,50.30925679,-3.231938113,10000,-66.75521085,188.525136,0,-14.03629709,0,109.5034439 +150.71,50.3092508,-3.231911689,10000,-66.73780306,188.5325172,0,-14.03629709,0,109.496418 +150.72,50.30924481,-3.231885263,10000,-66.7308399,188.5398985,0,-14.03629709,0,109.489392 +150.73,50.30923882,-3.231858837,10000,-66.71691362,188.5479487,0,-14.03629709,0,109.4823661 +150.74,50.30923283,-3.231832409,10000,-66.69602425,188.5564447,0,-14.03629709,0,109.4753402 +150.75,50.30922685,-3.23180598,10000,-66.67513489,188.5647178,0,-14.03629709,0,109.4683143 +150.76,50.30922086,-3.23177955,10000,-66.64380091,188.5732138,0,-14.03629709,0,109.4612883 +150.77,50.30921488,-3.231753119,10000,-66.60202226,188.5823787,0,-14.03629709,0,109.4542624 +150.78,50.30920891,-3.231726686,10000,-66.57068824,188.5908747,0,-14.03629709,0,109.4472365 +150.79,50.30920293,-3.231700252,10000,-66.54979888,188.598033,0,-14.03629709,0,109.4402106 +150.8,50.30919696,-3.231673818,10000,-66.52890953,188.6054142,0,-14.03629709,0,109.4331846 +150.81,50.30919099,-3.231647382,10000,-66.51498327,188.6139102,0,-14.03629709,0,109.4261588 +150.82,50.30918502,-3.231620945,10000,-66.5080201,188.6228521,0,-14.03629709,0,109.4191328 +150.83,50.30917905,-3.231594507,10000,-66.49061229,188.6313481,0,-14.03629709,0,109.4121069 +150.84,50.30917308,-3.231568067,10000,-66.45579673,188.6387293,0,-14.03629709,0,109.405081 +150.85,50.30916712,-3.231541627,10000,-66.42098117,188.6458875,0,-14.03629709,0,109.3980551 +150.86,50.30916116,-3.231515186,10000,-66.40009182,188.6543835,0,-14.03629709,0,109.3910291 +150.87,50.3091552,-3.231488743,10000,-66.382684,188.6635484,0,-14.03629709,0,109.3840032 +150.88,50.30914924,-3.231462299,10000,-66.36179465,188.6718214,0,-14.03629709,0,109.3769773 +150.89,50.30914329,-3.231435854,10000,-66.34438685,188.6792025,0,-14.03629709,0,109.3699514 +150.9,50.30913733,-3.231409408,10000,-66.3234975,188.6865837,0,-14.03629709,0,109.3629254 +150.91,50.30913138,-3.231382961,10000,-66.28868193,188.6946337,0,-14.03629709,0,109.3558995 +150.92,50.30912543,-3.231356513,10000,-66.25386637,188.7031296,0,-14.03629709,0,109.3488736 +150.93,50.30911949,-3.231330063,10000,-66.23297702,188.7114026,0,-14.03629709,0,109.3418477 +150.94,50.30911354,-3.231303613,10000,-66.21556921,188.7196756,0,-14.03629709,0,109.3348217 +150.95,50.3091076,-3.231277161,10000,-66.1911983,188.7281715,0,-14.03629709,0,109.3277958 +150.96,50.30910166,-3.231250708,10000,-66.16334584,188.7364444,0,-14.03629709,0,109.3207699 +150.97,50.30909572,-3.231224254,10000,-66.13897494,188.7447174,0,-14.03629709,0,109.313744 +150.98,50.30908979,-3.231197799,10000,-66.12156714,188.7532133,0,-14.03629709,0,109.306718 +150.99,50.30908385,-3.231171342,10000,-66.10415933,188.7614862,0,-14.03629709,0,109.2996921 +151,50.30907792,-3.231144885,10000,-66.07978842,188.7695362,0,-14.03629709,0,109.2926662 +151.01,50.30907199,-3.231118426,10000,-66.05193596,188.7771402,0,-14.03629709,0,109.2856403 +151.02,50.30906606,-3.231091966,10000,-66.02756505,188.7840754,0,-14.03629709,0,109.2786143 +151.03,50.30906014,-3.231065506,10000,-66.01015724,188.7914564,0,-14.03629709,0,109.2715884 +151.04,50.30905421,-3.231039044,10000,-65.99274943,188.7999523,0,-14.03629709,0,109.2645625 +151.05,50.30904829,-3.231012581,10000,-65.96837852,188.809117,0,-14.03629709,0,109.2575366 +151.06,50.30904237,-3.230986117,10000,-65.94052607,188.8185047,0,-14.03629709,0,109.2505106 +151.07,50.30903645,-3.230959651,10000,-65.91615516,188.8270006,0,-14.03629709,0,109.2434847 +151.08,50.30903054,-3.230933184,10000,-65.89874737,188.8341586,0,-14.03629709,0,109.2364588 +151.09,50.30902462,-3.230906717,10000,-65.88133957,188.8413167,0,-14.03629709,0,109.2294329 +151.1,50.30901871,-3.230880248,10000,-65.85696866,188.8489207,0,-14.03629709,0,109.222407 +151.11,50.3090128,-3.230853778,10000,-65.82563464,188.8567477,0,-14.03629709,0,109.215381 +151.12,50.30900689,-3.230827308,10000,-65.78733753,188.8652435,0,-14.03629709,0,109.2083551 +151.13,50.30900099,-3.230800835,10000,-65.75252198,188.8737393,0,-14.03629709,0,109.2013292 +151.14,50.30899509,-3.230774362,10000,-65.73511419,188.8817891,0,-14.03629709,0,109.1943033 +151.15,50.30898919,-3.230747888,10000,-65.72815103,188.8902849,0,-14.03629709,0,109.1872773 +151.16,50.30898329,-3.230721412,10000,-65.71422476,188.8985578,0,-14.03629709,0,109.1802515 +151.17,50.30897739,-3.230694935,10000,-65.69333541,188.9057158,0,-14.03629709,0,109.1732255 +151.18,50.3089715,-3.230668458,10000,-65.67592759,188.9130968,0,-14.03629709,0,109.1661996 +151.19,50.3089656,-3.230641979,10000,-65.65503823,188.9213696,0,-14.03629709,0,109.1591737 +151.2,50.30895971,-3.230615499,10000,-65.62022269,188.9296424,0,-14.03629709,0,109.1521478 +151.21,50.30895382,-3.230589018,10000,-65.58540714,188.9381381,0,-14.03629709,0,109.1451218 +151.22,50.30894794,-3.230562536,10000,-65.56451778,188.9473028,0,-14.03629709,0,109.1380959 +151.23,50.30894205,-3.230536052,10000,-65.54710997,188.9557985,0,-14.03629709,0,109.13107 +151.24,50.30893617,-3.230509567,10000,-65.52273906,188.9629565,0,-14.03629709,0,109.1240441 +151.25,50.30893029,-3.230483082,10000,-65.49488661,188.9703374,0,-14.03629709,0,109.1170181 +151.26,50.30892441,-3.230456595,10000,-65.47051572,188.9786102,0,-14.03629709,0,109.1099922 +151.27,50.30891854,-3.230430107,10000,-65.45310791,188.98666,0,-14.03629709,0,109.1029663 +151.28,50.30891266,-3.230403618,10000,-65.43570009,188.9940409,0,-14.03629709,0,109.0959404 +151.29,50.30890679,-3.230377128,10000,-65.41132919,189.0014218,0,-14.03629709,0,109.0889144 +151.3,50.30890092,-3.230350637,10000,-65.38347674,189.0096945,0,-14.03629709,0,109.0818885 +151.31,50.30889505,-3.230324145,10000,-65.35910584,189.0188591,0,-14.03629709,0,109.0748626 +151.32,50.30888919,-3.230297651,10000,-65.34169804,189.0273548,0,-14.03629709,0,109.0678367 +151.33,50.30888332,-3.230271156,10000,-65.32429022,189.0345127,0,-14.03629709,0,109.0608107 +151.34,50.30887746,-3.230244661,10000,-65.2999193,189.0418936,0,-14.03629709,0,109.0537848 +151.35,50.3088716,-3.230218164,10000,-65.2685853,189.0501663,0,-14.03629709,0,109.0467589 +151.36,50.30886574,-3.230191666,10000,-65.23376977,189.0582161,0,-14.03629709,0,109.039733 +151.37,50.30885989,-3.230165167,10000,-65.20939888,189.0658199,0,-14.03629709,0,109.032707 +151.38,50.30885404,-3.230138667,10000,-65.19547262,189.0738696,0,-14.03629709,0,109.0256811 +151.39,50.30884818,-3.230112166,10000,-65.17458327,189.0823652,0,-14.03629709,0,109.0186552 +151.4,50.30884234,-3.230085663,10000,-65.15369391,189.0906379,0,-14.03629709,0,109.0116293 +151.41,50.30883649,-3.23005916,10000,-65.13976764,189.0989106,0,-14.03629709,0,109.0046033 +151.42,50.30883064,-3.230032655,10000,-65.11539672,189.1074062,0,-14.03629709,0,108.9975774 +151.43,50.3088248,-3.230006149,10000,-65.08058115,189.1154559,0,-14.03629709,0,108.9905515 +151.44,50.30881896,-3.229979642,10000,-65.04924715,189.1228367,0,-14.03629709,0,108.9835256 +151.45,50.30881312,-3.229953134,10000,-65.02487628,189.1299946,0,-14.03629709,0,108.9764996 +151.46,50.30880729,-3.229926625,10000,-65.00746849,189.1373754,0,-14.03629709,0,108.9694737 +151.47,50.30880145,-3.229900115,10000,-64.99006068,189.1454251,0,-14.03629709,0,108.9624478 +151.48,50.30879562,-3.229873604,10000,-64.96917131,189.1539206,0,-14.03629709,0,108.9554219 +151.49,50.30878979,-3.229847091,10000,-64.9517635,189.1621933,0,-14.03629709,0,108.948396 +151.5,50.30878396,-3.229820578,10000,-64.93087414,189.1704659,0,-14.03629709,0,108.94137 +151.51,50.30877813,-3.229794063,10000,-64.8960586,189.1789614,0,-14.03629709,0,108.9343442 +151.52,50.30877231,-3.229767547,10000,-64.86124306,189.1870111,0,-14.03629709,0,108.9273182 +151.53,50.30876649,-3.22974103,10000,-64.84383525,189.1943918,0,-14.03629709,0,108.9202923 +151.54,50.30876067,-3.229714512,10000,-64.83687208,189.2017726,0,-14.03629709,0,108.9132664 +151.55,50.30875485,-3.229687993,10000,-64.81946429,189.2098222,0,-14.03629709,0,108.9062405 +151.56,50.30874903,-3.229661473,10000,-64.78464875,189.2183178,0,-14.03629709,0,108.8992145 +151.57,50.30874322,-3.229634951,10000,-64.74983321,189.2263674,0,-14.03629709,0,108.8921886 +151.58,50.30873741,-3.229608429,10000,-64.72894384,189.2337481,0,-14.03629709,0,108.8851627 +151.59,50.3087316,-3.229581905,10000,-64.71153602,189.2411288,0,-14.03629709,0,108.8781368 +151.6,50.30872579,-3.229555381,10000,-64.69064666,189.2491784,0,-14.03629709,0,108.8711108 +151.61,50.30871999,-3.229528855,10000,-64.67323885,189.2576739,0,-14.03629709,0,108.8640849 +151.62,50.30871418,-3.229502328,10000,-64.6523495,189.2659465,0,-14.03629709,0,108.857059 +151.63,50.30870838,-3.2294758,10000,-64.61753396,189.273996,0,-14.03629709,0,108.8500331 +151.64,50.30870258,-3.229449271,10000,-64.58271842,189.2815997,0,-14.03629709,0,108.8430071 +151.65,50.30869679,-3.22942274,10000,-64.56182908,189.2887574,0,-14.03629709,0,108.8359812 +151.66,50.30869099,-3.22939621,10000,-64.54442127,189.2968069,0,-14.03629709,0,108.8289553 +151.67,50.3086852,-3.229369677,10000,-64.52353191,189.3055254,0,-14.03629709,0,108.8219294 +151.68,50.30867941,-3.229343143,10000,-64.5061241,189.3133519,0,-14.03629709,0,108.8149034 +151.69,50.30867362,-3.229316609,10000,-64.48523475,189.3209556,0,-14.03629709,0,108.8078775 +151.7,50.30866783,-3.229290073,10000,-64.45041921,189.329228,0,-14.03629709,0,108.8008516 +151.71,50.30866205,-3.229263536,10000,-64.41560366,189.3372776,0,-14.03629709,0,108.7938257 +151.72,50.30865627,-3.229236998,10000,-64.39819585,189.3446582,0,-14.03629709,0,108.7867997 +151.73,50.30865049,-3.229210459,10000,-64.39123269,189.3518159,0,-14.03629709,0,108.7797738 +151.74,50.30864471,-3.229183919,10000,-64.37382489,189.3591965,0,-14.03629709,0,108.7727479 +151.75,50.30863893,-3.229157378,10000,-64.33900935,189.3674689,0,-14.03629709,0,108.765722 +151.76,50.30863316,-3.229130836,10000,-64.3041938,189.3768562,0,-14.03629709,0,108.758696 +151.77,50.30862739,-3.229104292,10000,-64.28678599,189.3860205,0,-14.03629709,0,108.7516701 +151.78,50.30862162,-3.229077747,10000,-64.27982283,189.3934011,0,-14.03629709,0,108.7446442 +151.79,50.30861585,-3.229051201,10000,-64.26241502,189.3996669,0,-14.03629709,0,108.7376183 +151.8,50.30861008,-3.229024655,10000,-64.22759948,189.4068245,0,-14.03629709,0,108.7305923 +151.81,50.30860432,-3.228998107,10000,-64.19278394,189.4150969,0,-14.03629709,0,108.7235664 +151.82,50.30859856,-3.228971558,10000,-64.17189459,189.4231464,0,-14.03629709,0,108.7165405 +151.83,50.3085928,-3.228945008,10000,-64.15448678,189.4307499,0,-14.03629709,0,108.7095146 +151.84,50.30858704,-3.228918457,10000,-64.13359743,189.4387993,0,-14.03629709,0,108.7024886 +151.85,50.30858129,-3.228891905,10000,-64.11618963,189.4472947,0,-14.03629709,0,108.6954628 +151.86,50.30857553,-3.228865351,10000,-64.09530027,189.4553441,0,-14.03629709,0,108.6884368 +151.87,50.30856978,-3.228838797,10000,-64.06048472,189.4629476,0,-14.03629709,0,108.6814109 +151.88,50.30856403,-3.228812241,10000,-64.02566918,189.470997,0,-14.03629709,0,108.674385 +151.89,50.30855829,-3.228785685,10000,-64.00477983,189.4792694,0,-14.03629709,0,108.6673591 +151.9,50.30855254,-3.228759126,10000,-63.98737202,189.4866499,0,-14.03629709,0,108.6603332 +151.91,50.3085468,-3.228732568,10000,-63.96648267,189.4935845,0,-14.03629709,0,108.6533072 +151.92,50.30854106,-3.228706008,10000,-63.94907488,189.501188,0,-14.03629709,0,108.6462813 +151.93,50.30853532,-3.228679447,10000,-63.92818553,189.5092373,0,-14.03629709,0,108.6392554 +151.94,50.30852958,-3.228652885,10000,-63.89336998,189.5175097,0,-14.03629709,0,108.6322295 +151.95,50.30852385,-3.228626322,10000,-63.85855443,189.526005,0,-14.03629709,0,108.6252035 +151.96,50.30851812,-3.228599757,10000,-63.84114663,189.5342773,0,-14.03629709,0,108.6181776 +151.97,50.30851239,-3.228573192,10000,-63.83418348,189.5423266,0,-14.03629709,0,108.6111517 +151.98,50.30850666,-3.228546625,10000,-63.81677567,189.5499301,0,-14.03629709,0,108.6041258 +151.99,50.30850093,-3.228520057,10000,-63.78196012,189.5568646,0,-14.03629709,0,108.5970998 +152,50.30849521,-3.228493489,10000,-63.74714458,189.5642451,0,-14.03629709,0,108.5900739 +152.01,50.30848949,-3.228466919,10000,-63.72973677,189.5725174,0,-14.03629709,0,108.583048 +152.02,50.30848377,-3.228440348,10000,-63.72277361,189.5805667,0,-14.03629709,0,108.5760221 +152.03,50.30847805,-3.228413776,10000,-63.70536582,189.5879471,0,-14.03629709,0,108.5689961 +152.04,50.30847233,-3.228387203,10000,-63.67055028,189.5951046,0,-14.03629709,0,108.5619702 +152.05,50.30846662,-3.228360629,10000,-63.63573474,189.602485,0,-14.03629709,0,108.5549443 +152.06,50.30846091,-3.228334054,10000,-63.61832693,189.6107573,0,-14.03629709,0,108.5479184 +152.07,50.3084552,-3.228307478,10000,-63.61136376,189.6199214,0,-14.03629709,0,108.5408924 +152.08,50.30844949,-3.2282809,10000,-63.59395596,189.6284166,0,-14.03629709,0,108.5338665 +152.09,50.30844378,-3.228254321,10000,-63.55914042,189.635574,0,-14.03629709,0,108.5268406 +152.1,50.30843808,-3.228227742,10000,-63.52084334,189.6429544,0,-14.03629709,0,108.5198147 +152.11,50.30843238,-3.228201161,10000,-63.48950934,189.6512266,0,-14.03629709,0,108.5127887 +152.12,50.30842668,-3.228174579,10000,-63.46513844,189.6592759,0,-14.03629709,0,108.5057628 +152.13,50.30842099,-3.228147996,10000,-63.44773064,189.6666563,0,-14.03629709,0,108.4987369 +152.14,50.30841529,-3.228121412,10000,-63.43032283,189.6738137,0,-14.03629709,0,108.491711 +152.15,50.3084096,-3.228094827,10000,-63.40943348,189.6809711,0,-14.03629709,0,108.484685 +152.16,50.30840391,-3.228068241,10000,-63.39202568,189.6883514,0,-14.03629709,0,108.4776591 +152.17,50.30839822,-3.228041654,10000,-63.37113633,189.6966236,0,-14.03629709,0,108.4706332 +152.18,50.30839253,-3.228015066,10000,-63.33632079,189.7057876,0,-14.03629709,0,108.4636073 +152.19,50.30838685,-3.227988476,10000,-63.30150524,189.7140598,0,-14.03629709,0,108.4565813 +152.2,50.30838117,-3.227961885,10000,-63.28409743,189.7203253,0,-14.03629709,0,108.4495555 +152.21,50.30837549,-3.227935294,10000,-63.27713427,189.7265908,0,-14.03629709,0,108.4425295 +152.22,50.30836981,-3.227908702,10000,-63.25972649,189.734863,0,-14.03629709,0,108.4355036 +152.23,50.30836413,-3.227882108,10000,-63.22491096,189.744027,0,-14.03629709,0,108.4284777 +152.24,50.30835846,-3.227855513,10000,-63.19009541,189.7522991,0,-14.03629709,0,108.4214518 +152.25,50.30835279,-3.227828917,10000,-63.1726876,189.7596794,0,-14.03629709,0,108.4144258 +152.26,50.30834712,-3.22780232,10000,-63.16572444,189.7668367,0,-14.03629709,0,108.4073999 +152.27,50.30834145,-3.227775722,10000,-63.14831664,189.774217,0,-14.03629709,0,108.400374 +152.28,50.30833578,-3.227749123,10000,-63.11350111,189.7822662,0,-14.03629709,0,108.3933481 +152.29,50.30833012,-3.227722523,10000,-63.07868555,189.7907613,0,-14.03629709,0,108.3863222 +152.3,50.30832446,-3.227695921,10000,-63.05779619,189.7988104,0,-14.03629709,0,108.3792962 +152.31,50.3083188,-3.227669319,10000,-63.0403884,189.8061907,0,-14.03629709,0,108.3722703 +152.32,50.30831314,-3.227642715,10000,-63.01949907,189.8135709,0,-14.03629709,0,108.3652444 +152.33,50.30830749,-3.227616111,10000,-63.00209128,189.8213971,0,-14.03629709,0,108.3582185 +152.34,50.30830183,-3.227589505,10000,-62.98120192,189.8290003,0,-14.03629709,0,108.3511925 +152.35,50.30829618,-3.227562898,10000,-62.94638637,189.8359346,0,-14.03629709,0,108.3441666 +152.36,50.30829053,-3.227536291,10000,-62.91157083,189.8433148,0,-14.03629709,0,108.3371407 +152.37,50.30828489,-3.227509682,10000,-62.89068148,189.8515869,0,-14.03629709,0,108.3301148 +152.38,50.30827924,-3.227483072,10000,-62.87327367,189.859636,0,-14.03629709,0,108.3230888 +152.39,50.3082736,-3.227456461,10000,-62.85238431,189.8672391,0,-14.03629709,0,108.3160629 +152.4,50.30826796,-3.227429849,10000,-62.83497652,189.8752882,0,-14.03629709,0,108.309037 +152.41,50.30826232,-3.227403236,10000,-62.81408718,189.8837832,0,-14.03629709,0,108.3020111 +152.42,50.30825668,-3.227376621,10000,-62.77927164,189.8918323,0,-14.03629709,0,108.2949851 +152.43,50.30825105,-3.227350006,10000,-62.7444561,189.8989895,0,-14.03629709,0,108.2879592 +152.44,50.30824542,-3.227323389,10000,-62.7270483,189.9054778,0,-14.03629709,0,108.2809333 +152.45,50.30823979,-3.227296772,10000,-62.72008515,189.912412,0,-14.03629709,0,108.2739074 +152.46,50.30823416,-3.227270154,10000,-62.70267735,189.920907,0,-14.03629709,0,108.2668814 +152.47,50.30822853,-3.227243534,10000,-62.6678618,189.9298479,0,-14.03629709,0,108.2598555 +152.48,50.30822291,-3.227216913,10000,-62.63304626,189.937228,0,-14.03629709,0,108.2528296 +152.49,50.30821729,-3.227190291,10000,-62.61215691,189.9434933,0,-14.03629709,0,108.2458037 +152.5,50.30821167,-3.227163669,10000,-62.59474911,189.9506505,0,-14.03629709,0,108.2387777 +152.51,50.30820605,-3.227137045,10000,-62.57385976,189.9591454,0,-14.03629709,0,108.2317519 +152.52,50.30820044,-3.22711042,10000,-62.55645197,189.9680863,0,-14.03629709,0,108.2247259 +152.53,50.30819482,-3.227083794,10000,-62.53556263,189.9765812,0,-14.03629709,0,108.2177 +152.54,50.30818921,-3.227057166,10000,-62.50074709,189.9837384,0,-14.03629709,0,108.2106741 +152.55,50.3081836,-3.227030538,10000,-62.46593155,189.9900036,0,-14.03629709,0,108.2036482 +152.56,50.308178,-3.227003909,10000,-62.44504219,189.9971608,0,-14.03629709,0,108.1966222 +152.57,50.30817239,-3.226977279,10000,-62.42763438,190.0054327,0,-14.03629709,0,108.1895963 +152.58,50.30816679,-3.226950647,10000,-62.40674504,190.0137046,0,-14.03629709,0,108.1825704 +152.59,50.30816119,-3.226924015,10000,-62.38933725,190.0217536,0,-14.03629709,0,108.1755445 +152.6,50.30815559,-3.226897381,10000,-62.36844789,190.0293566,0,-14.03629709,0,108.1685185 +152.61,50.30814999,-3.226870746,10000,-62.33363235,190.0362907,0,-14.03629709,0,108.1614926 +152.62,50.3081444,-3.226844111,10000,-62.29881682,190.0436708,0,-14.03629709,0,108.1544667 +152.63,50.30813881,-3.226817474,10000,-62.28140903,190.0519427,0,-14.03629709,0,108.1474408 +152.64,50.30813322,-3.226790836,10000,-62.27444587,190.0599916,0,-14.03629709,0,108.1404148 +152.65,50.30812763,-3.226764197,10000,-62.25703806,190.0673716,0,-14.03629709,0,108.1333889 +152.66,50.30812204,-3.226737557,10000,-62.22222253,190.0745287,0,-14.03629709,0,108.126363 +152.67,50.30811646,-3.226710916,10000,-62.187407,190.0816857,0,-14.03629709,0,108.1193371 +152.68,50.30811088,-3.226684274,10000,-62.1699992,190.0888428,0,-14.03629709,0,108.1123112 +152.69,50.3081053,-3.226657631,10000,-62.16303603,190.0962228,0,-14.03629709,0,108.1052852 +152.7,50.30809972,-3.226630987,10000,-62.14562823,190.1042717,0,-14.03629709,0,108.0982593 +152.71,50.30809414,-3.226604342,10000,-62.1108127,190.1127665,0,-14.03629709,0,108.0912334 +152.72,50.30808857,-3.226577695,10000,-62.07599717,190.1208154,0,-14.03629709,0,108.0842075 +152.73,50.308083,-3.226551048,10000,-62.05510783,190.1281953,0,-14.03629709,0,108.0771815 +152.74,50.30807743,-3.226524399,10000,-62.03770003,190.1355753,0,-14.03629709,0,108.0701556 +152.75,50.30807186,-3.22649775,10000,-62.01681067,190.1434012,0,-14.03629709,0,108.0631297 +152.76,50.3080663,-3.226471099,10000,-61.99940285,190.1510041,0,-14.03629709,0,108.0561038 +152.77,50.30806073,-3.226444447,10000,-61.97851351,190.1579381,0,-14.03629709,0,108.0490778 +152.78,50.30805517,-3.226417795,10000,-61.94369799,190.1653181,0,-14.03629709,0,108.0420519 +152.79,50.30804961,-3.226391141,10000,-61.90888246,190.1735899,0,-14.03629709,0,108.035026 +152.8,50.30804406,-3.226364486,10000,-61.8879931,190.1816387,0,-14.03629709,0,108.0280001 +152.81,50.3080385,-3.22633783,10000,-61.87058531,190.1890186,0,-14.03629709,0,108.0209741 +152.82,50.30803295,-3.226311173,10000,-61.84969597,190.1961756,0,-14.03629709,0,108.0139482 +152.83,50.3080274,-3.226284515,10000,-61.83228817,190.2033325,0,-14.03629709,0,108.0069223 +152.84,50.30802185,-3.226257856,10000,-61.81139882,190.2107124,0,-14.03629709,0,107.9998964 +152.85,50.3080163,-3.226231196,10000,-61.77658328,190.2187612,0,-14.03629709,0,107.9928704 +152.86,50.30801076,-3.226204535,10000,-61.74176774,190.2272559,0,-14.03629709,0,107.9858446 +152.87,50.30800522,-3.226177872,10000,-61.72435995,190.2353047,0,-14.03629709,0,107.9788186 +152.88,50.30799968,-3.226151209,10000,-61.7173968,190.2426846,0,-14.03629709,0,107.9717927 +152.89,50.30799414,-3.226124544,10000,-61.699989,190.2498415,0,-14.03629709,0,107.9647668 +152.9,50.3079886,-3.226097879,10000,-61.66517346,190.2569984,0,-14.03629709,0,107.9577409 +152.91,50.30798307,-3.226071212,10000,-61.63035792,190.2641553,0,-14.03629709,0,107.9507149 +152.92,50.30797754,-3.226044545,10000,-61.60946858,190.2713122,0,-14.03629709,0,107.943689 +152.93,50.30797201,-3.226017876,10000,-61.59206078,190.278692,0,-14.03629709,0,107.9366631 +152.94,50.30796648,-3.225991207,10000,-61.57117143,190.2865178,0,-14.03629709,0,107.9296372 +152.95,50.30796096,-3.225964536,10000,-61.55376364,190.2941206,0,-14.03629709,0,107.9226112 +152.96,50.30795543,-3.225937864,10000,-61.53635584,190.3012774,0,-14.03629709,0,107.9155853 +152.97,50.30794991,-3.225911192,10000,-61.51198494,190.3093262,0,-14.03629709,0,107.9085594 +152.98,50.30794439,-3.225884518,10000,-61.48065095,190.3178208,0,-14.03629709,0,107.9015335 +152.99,50.30793887,-3.225857842,10000,-61.44235388,190.3247547,0,-14.03629709,0,107.8945075 +153,50.30793336,-3.225831167,10000,-61.40753835,190.3312426,0,-14.03629709,0,107.8874816 +153.01,50.30792785,-3.22580449,10000,-61.39013055,190.3395142,0,-14.03629709,0,107.8804557 +153.02,50.30792234,-3.225777812,10000,-61.38316738,190.3484548,0,-14.03629709,0,107.8734298 +153.03,50.30791683,-3.225751132,10000,-61.36924112,190.3560575,0,-14.03629709,0,107.8664038 +153.04,50.30791132,-3.225724452,10000,-61.34835179,190.3629914,0,-14.03629709,0,107.8593779 +153.05,50.30790582,-3.225697771,10000,-61.32746245,190.3703711,0,-14.03629709,0,107.852352 +153.06,50.30790031,-3.225671088,10000,-61.29612846,190.3775279,0,-14.03629709,0,107.8453261 +153.07,50.30789481,-3.225644405,10000,-61.25434983,190.3844618,0,-14.03629709,0,107.8383001 +153.08,50.30788932,-3.225617721,10000,-61.2264974,190.3920645,0,-14.03629709,0,107.8312742 +153.09,50.30788382,-3.225591035,10000,-61.21953424,190.3998901,0,-14.03629709,0,107.8242483 +153.1,50.30787833,-3.225564349,10000,-61.21257109,190.4072699,0,-14.03629709,0,107.8172224 +153.11,50.30787283,-3.225537661,10000,-61.18471865,190.4146496,0,-14.03629709,0,107.8101965 +153.12,50.30786734,-3.225510973,10000,-61.14294001,190.4224752,0,-14.03629709,0,107.8031705 +153.13,50.30786186,-3.225484283,10000,-61.11160603,190.4300779,0,-14.03629709,0,107.7961446 +153.14,50.30785637,-3.225457592,10000,-61.09071671,190.4370117,0,-14.03629709,0,107.7891187 +153.15,50.30785089,-3.225430901,10000,-61.06982736,190.4443914,0,-14.03629709,0,107.7820928 +153.16,50.30784541,-3.225404208,10000,-61.05590109,190.4526629,0,-14.03629709,0,107.7750668 +153.17,50.30783993,-3.225377514,10000,-61.04893793,190.4607115,0,-14.03629709,0,107.7680409 +153.18,50.30783445,-3.225350819,10000,-61.03153015,190.4680912,0,-14.03629709,0,107.761015 +153.19,50.30782897,-3.225324123,10000,-60.99671462,190.4752479,0,-14.03629709,0,107.7539891 +153.2,50.3078235,-3.225297426,10000,-60.96189908,190.4824046,0,-14.03629709,0,107.7469632 +153.21,50.30781803,-3.225270728,10000,-60.94100973,190.4895613,0,-14.03629709,0,107.7399373 +153.22,50.30781256,-3.225244029,10000,-60.9201204,190.496718,0,-14.03629709,0,107.7329113 +153.23,50.30780709,-3.225217329,10000,-60.88530487,190.5040976,0,-14.03629709,0,107.7258854 +153.24,50.30780163,-3.225190628,10000,-60.85048932,190.5121462,0,-14.03629709,0,107.7188595 +153.25,50.30779617,-3.225163926,10000,-60.83308151,190.5206406,0,-14.03629709,0,107.7118336 +153.26,50.30779071,-3.225137222,10000,-60.82611837,190.5286891,0,-14.03629709,0,107.7048076 +153.27,50.30778525,-3.225110518,10000,-60.80871058,190.5358458,0,-14.03629709,0,107.6977817 +153.28,50.30777979,-3.225083812,10000,-60.77389506,190.5421106,0,-14.03629709,0,107.6907558 +153.29,50.30777434,-3.225057106,10000,-60.73907952,190.5481524,0,-14.03629709,0,107.6837299 +153.3,50.30776889,-3.225030399,10000,-60.72167172,190.555532,0,-14.03629709,0,107.6767039 +153.31,50.30776344,-3.225003691,10000,-60.71470856,190.5644723,0,-14.03629709,0,107.669678 +153.32,50.30775799,-3.224976981,10000,-60.69730075,190.5727438,0,-14.03629709,0,107.6626521 +153.33,50.30775254,-3.22495027,10000,-60.66248522,190.5792315,0,-14.03629709,0,107.6556262 +153.34,50.3077471,-3.224923559,10000,-60.6276697,190.5861652,0,-14.03629709,0,107.6486002 +153.35,50.30774166,-3.224896847,10000,-60.60678037,190.5946595,0,-14.03629709,0,107.6415743 +153.36,50.30773622,-3.224870132,10000,-60.58937257,190.602708,0,-14.03629709,0,107.6345484 +153.37,50.30773078,-3.224843418,10000,-60.56848323,190.6096416,0,-14.03629709,0,107.6275225 +153.38,50.30772535,-3.224816702,10000,-60.55107543,190.6163523,0,-14.03629709,0,107.6204965 +153.39,50.30771991,-3.224789985,10000,-60.53018609,190.6230629,0,-14.03629709,0,107.6134706 +153.4,50.30771448,-3.224763268,10000,-60.49537056,190.6304424,0,-14.03629709,0,107.6064447 +153.41,50.30770905,-3.224736549,10000,-60.46055503,190.6387138,0,-14.03629709,0,107.5994188 +153.42,50.30770363,-3.224709829,10000,-60.43966568,190.6467622,0,-14.03629709,0,107.5923928 +153.43,50.3076982,-3.224683108,10000,-60.42225787,190.6541417,0,-14.03629709,0,107.5853669 +153.44,50.30769278,-3.224656386,10000,-60.40136853,190.6612983,0,-14.03629709,0,107.578341 +153.45,50.30768736,-3.224629663,10000,-60.38396075,190.6684548,0,-14.03629709,0,107.5713151 +153.46,50.30768194,-3.224602939,10000,-60.36307141,190.6756113,0,-14.03629709,0,107.5642891 +153.47,50.30767652,-3.224576214,10000,-60.32825588,190.6827679,0,-14.03629709,0,107.5572632 +153.48,50.30767111,-3.224549488,10000,-60.29344034,190.6899244,0,-14.03629709,0,107.5502373 +153.49,50.3076657,-3.224522761,10000,-60.27603255,190.6970809,0,-14.03629709,0,107.5432114 +153.5,50.30766029,-3.224496033,10000,-60.2690694,190.7044603,0,-14.03629709,0,107.5361855 +153.51,50.30765488,-3.224469304,10000,-60.25166162,190.7125087,0,-14.03629709,0,107.5291595 +153.52,50.30764947,-3.224442574,10000,-60.21684609,190.72078,0,-14.03629709,0,107.5221337 +153.53,50.30764407,-3.224415842,10000,-60.18203055,190.7281595,0,-14.03629709,0,107.5151077 +153.54,50.30763867,-3.22438911,10000,-60.16462276,190.735093,0,-14.03629709,0,107.5080818 +153.55,50.30763327,-3.224362377,10000,-60.1576596,190.7424724,0,-14.03629709,0,107.5010559 +153.56,50.30762787,-3.224335642,10000,-60.1402518,190.7496289,0,-14.03629709,0,107.49403 +153.57,50.30762247,-3.224308907,10000,-60.10543626,190.7565624,0,-14.03629709,0,107.487004 +153.58,50.30761708,-3.224282171,10000,-60.07062074,190.7641647,0,-14.03629709,0,107.4799781 +153.59,50.30761169,-3.224255433,10000,-60.0497314,190.7719901,0,-14.03629709,0,107.4729522 +153.6,50.3076063,-3.224228695,10000,-60.02884206,190.7793695,0,-14.03629709,0,107.4659263 +153.61,50.30760091,-3.224201955,10000,-59.99402652,190.7867489,0,-14.03629709,0,107.4589003 +153.62,50.30759553,-3.224175215,10000,-59.95921099,190.7945742,0,-14.03629709,0,107.4518744 +153.63,50.30759015,-3.224148473,10000,-59.94180321,190.8021765,0,-14.03629709,0,107.4448485 +153.64,50.30758477,-3.22412173,10000,-59.93484006,190.808887,0,-14.03629709,0,107.4378226 +153.65,50.30757939,-3.224094987,10000,-59.9209138,190.8153745,0,-14.03629709,0,107.4307966 +153.66,50.30757401,-3.224068242,10000,-59.90002446,190.8223079,0,-14.03629709,0,107.4237707 +153.67,50.30756864,-3.224041497,10000,-59.87913514,190.8296873,0,-14.03629709,0,107.4167448 +153.68,50.30756326,-3.22401475,10000,-59.84780115,190.8377355,0,-14.03629709,0,107.4097189 +153.69,50.30755789,-3.223988003,10000,-59.80602251,190.8460067,0,-14.03629709,0,107.4026929 +153.7,50.30755253,-3.223961253,10000,-59.77817007,190.8531631,0,-14.03629709,0,107.395667 +153.71,50.30754716,-3.223934504,10000,-59.77120693,190.8594276,0,-14.03629709,0,107.3886411 +153.72,50.3075418,-3.223907753,10000,-59.76424378,190.8665839,0,-14.03629709,0,107.3816152 +153.73,50.30753643,-3.223881002,10000,-59.73639135,190.8746321,0,-14.03629709,0,107.3745892 +153.74,50.30753107,-3.223854248,10000,-59.69461273,190.8820114,0,-14.03629709,0,107.3675633 +153.75,50.30752572,-3.223827495,10000,-59.66327874,190.8889448,0,-14.03629709,0,107.3605374 +153.76,50.30752036,-3.22380074,10000,-59.6423894,190.896547,0,-14.03629709,0,107.3535115 +153.77,50.30751501,-3.223773984,10000,-59.62150006,190.9043722,0,-14.03629709,0,107.3464855 +153.78,50.30750966,-3.223747227,10000,-59.60409228,190.9117515,0,-14.03629709,0,107.3394596 +153.79,50.30750431,-3.223720469,10000,-59.58668449,190.9189078,0,-14.03629709,0,107.3324337 +153.8,50.30749896,-3.22369371,10000,-59.56579513,190.9260641,0,-14.03629709,0,107.3254078 +153.81,50.30749362,-3.22366695,10000,-59.54838733,190.9332204,0,-14.03629709,0,107.3183818 +153.82,50.30748827,-3.223640189,10000,-59.52749801,190.9403767,0,-14.03629709,0,107.3113559 +153.83,50.30748293,-3.223613427,10000,-59.49268249,190.947533,0,-14.03629709,0,107.30433 +153.84,50.30747759,-3.223586664,10000,-59.45786695,190.9546893,0,-14.03629709,0,107.2973041 +153.85,50.30747226,-3.2235599,10000,-59.4369776,190.9618455,0,-14.03629709,0,107.2902781 +153.86,50.30746692,-3.223533135,10000,-59.4195698,190.9690018,0,-14.03629709,0,107.2832522 +153.87,50.30746159,-3.223506369,10000,-59.39519893,190.976381,0,-14.03629709,0,107.2762263 +153.88,50.30745626,-3.223479602,10000,-59.3673465,190.9844291,0,-14.03629709,0,107.2692004 +153.89,50.30745093,-3.223452834,10000,-59.34297561,190.9927001,0,-14.03629709,0,107.2621745 +153.9,50.30744561,-3.223426064,10000,-59.32556782,190.9998564,0,-14.03629709,0,107.2551486 +153.91,50.30744028,-3.223399294,10000,-59.30816002,191.0058978,0,-14.03629709,0,107.2481227 +153.92,50.30743496,-3.223372523,10000,-59.28378914,191.0121621,0,-14.03629709,0,107.2410967 +153.93,50.30742964,-3.223345751,10000,-59.25593671,191.0193183,0,-14.03629709,0,107.2340708 +153.94,50.30742432,-3.223318978,10000,-59.23156583,191.0273664,0,-14.03629709,0,107.2270449 +153.95,50.30741901,-3.223292204,10000,-59.21415804,191.0356374,0,-14.03629709,0,107.220019 +153.96,50.30741369,-3.223265428,10000,-59.19326869,191.0427936,0,-14.03629709,0,107.212993 +153.97,50.30740838,-3.223238652,10000,-59.15845315,191.0490579,0,-14.03629709,0,107.2059671 +153.98,50.30740307,-3.223211875,10000,-59.12363762,191.0562141,0,-14.03629709,0,107.1989412 +153.99,50.30739777,-3.223185097,10000,-59.1027483,191.0642621,0,-14.03629709,0,107.1919153 +154,50.30739246,-3.223158317,10000,-59.08534051,191.0714183,0,-14.03629709,0,107.1848893 +154.01,50.30738716,-3.223131537,10000,-59.06445117,191.0776826,0,-14.03629709,0,107.1778634 +154.02,50.30738186,-3.223104756,10000,-59.04704337,191.0848387,0,-14.03629709,0,107.1708375 +154.03,50.30737656,-3.223077974,10000,-59.02615404,191.0931097,0,-14.03629709,0,107.1638116 +154.04,50.30737126,-3.22305119,10000,-58.99133851,191.1011577,0,-14.03629709,0,107.1567856 +154.05,50.30736597,-3.223024406,10000,-58.95652298,191.1083138,0,-14.03629709,0,107.1497597 +154.06,50.30736068,-3.22299762,10000,-58.93911519,191.114801,0,-14.03629709,0,107.1427338 +154.07,50.30735539,-3.222970834,10000,-58.93215206,191.1215112,0,-14.03629709,0,107.1357079 +154.08,50.3073501,-3.222944047,10000,-58.91822581,191.1291133,0,-14.03629709,0,107.1286819 +154.09,50.30734481,-3.222917258,10000,-58.89733646,191.1369383,0,-14.03629709,0,107.121656 +154.1,50.30733953,-3.222890469,10000,-58.87644711,191.1440944,0,-14.03629709,0,107.1146301 +154.11,50.30733424,-3.222863678,10000,-58.84511314,191.1503586,0,-14.03629709,0,107.1076042 +154.12,50.30732896,-3.222836887,10000,-58.80333452,191.1563998,0,-14.03629709,0,107.1005782 +154.13,50.30732369,-3.222810095,10000,-58.77200054,191.1635559,0,-14.03629709,0,107.0935523 +154.14,50.30731841,-3.222783302,10000,-58.7511112,191.1718268,0,-14.03629709,0,107.0865264 +154.15,50.30731314,-3.222756507,10000,-58.73022186,191.1798747,0,-14.03629709,0,107.0795005 +154.16,50.30730787,-3.222729712,10000,-58.71281407,191.1872537,0,-14.03629709,0,107.0724745 +154.17,50.3073026,-3.222702915,10000,-58.69540628,191.1944098,0,-14.03629709,0,107.0654486 +154.18,50.30729733,-3.222676118,10000,-58.67451695,191.2015658,0,-14.03629709,0,107.0584227 +154.19,50.30729207,-3.222649319,10000,-58.65710917,191.2087218,0,-14.03629709,0,107.0513968 +154.2,50.3072868,-3.22262252,10000,-58.63621982,191.2158779,0,-14.03629709,0,107.0443708 +154.21,50.30728154,-3.222595719,10000,-58.60140428,191.2230339,0,-14.03629709,0,107.037345 +154.22,50.30727628,-3.222568918,10000,-58.56658875,191.2301899,0,-14.03629709,0,107.030319 +154.23,50.30727103,-3.222542115,10000,-58.54569944,191.2373459,0,-14.03629709,0,107.0232931 +154.24,50.30726577,-3.222515312,10000,-58.52829166,191.2445019,0,-14.03629709,0,107.0162672 +154.25,50.30726052,-3.222488507,10000,-58.50740233,191.2516579,0,-14.03629709,0,107.0092413 +154.26,50.30725527,-3.222461702,10000,-58.48999454,191.2588139,0,-14.03629709,0,107.0022153 +154.27,50.30725002,-3.222434895,10000,-58.4691052,191.2659698,0,-14.03629709,0,106.9951894 +154.28,50.30724477,-3.222408088,10000,-58.43428966,191.2731258,0,-14.03629709,0,106.9881635 +154.29,50.30723953,-3.222381279,10000,-58.39947412,191.2802818,0,-14.03629709,0,106.9811376 +154.3,50.30723429,-3.22235447,10000,-58.37858477,191.2874377,0,-14.03629709,0,106.9741117 +154.31,50.30722905,-3.222327659,10000,-58.36117697,191.2945937,0,-14.03629709,0,106.9670857 +154.32,50.30722381,-3.222300848,10000,-58.34028766,191.3017496,0,-14.03629709,0,106.9600598 +154.33,50.30721858,-3.222274035,10000,-58.32287989,191.3089056,0,-14.03629709,0,106.9530339 +154.34,50.30721334,-3.222247222,10000,-58.3054721,191.3160615,0,-14.03629709,0,106.946008 +154.35,50.30720811,-3.222220407,10000,-58.2811012,191.3232174,0,-14.03629709,0,106.938982 +154.36,50.30720288,-3.222193592,10000,-58.24976722,191.3301504,0,-14.03629709,0,106.9319561 +154.37,50.30719765,-3.222166775,10000,-58.21147015,191.3366374,0,-14.03629709,0,106.9249302 +154.38,50.30719243,-3.222139958,10000,-58.17665463,191.3435703,0,-14.03629709,0,106.9179043 +154.39,50.30718721,-3.22211314,10000,-58.15924685,191.351841,0,-14.03629709,0,106.9108783 +154.4,50.30718199,-3.22208632,10000,-58.1522837,191.3598888,0,-14.03629709,0,106.9038524 +154.41,50.30717677,-3.222059499,10000,-58.13835744,191.3661528,0,-14.03629709,0,106.8968265 +154.42,50.30717155,-3.222032678,10000,-58.1174681,191.3721938,0,-14.03629709,0,106.8898006 +154.43,50.30716634,-3.222005856,10000,-58.09657877,191.3795727,0,-14.03629709,0,106.8827746 +154.44,50.30716112,-3.221979032,10000,-58.0652448,191.3873974,0,-14.03629709,0,106.8757487 +154.45,50.30715591,-3.221952208,10000,-58.02694775,191.3945533,0,-14.03629709,0,106.8687228 +154.46,50.30715071,-3.221925382,10000,-58.00953997,191.4010402,0,-14.03629709,0,106.8616969 +154.47,50.3071455,-3.221898556,10000,-58.00605836,191.4079731,0,-14.03629709,0,106.8546709 +154.48,50.30714029,-3.221871729,10000,-57.98168746,191.4162438,0,-14.03629709,0,106.847645 +154.49,50.30713509,-3.2218449,10000,-57.93642728,191.4245144,0,-14.03629709,0,106.8406191 +154.5,50.30712989,-3.22181807,10000,-57.89813021,191.4314473,0,-14.03629709,0,106.8335932 +154.51,50.3071247,-3.22179124,10000,-57.87724088,191.4377112,0,-14.03629709,0,106.8265672 +154.52,50.3071195,-3.221764408,10000,-57.8598331,191.4439751,0,-14.03629709,0,106.8195413 +154.53,50.30711431,-3.221737576,10000,-57.83894378,191.450685,0,-14.03629709,0,106.8125154 +154.54,50.30710912,-3.221710743,10000,-57.82501754,191.4580637,0,-14.03629709,0,106.8054895 +154.55,50.30710393,-3.221683908,10000,-57.81805438,191.4652195,0,-14.03629709,0,106.7984635 +154.56,50.30709874,-3.221657073,10000,-57.80064658,191.4721523,0,-14.03629709,0,106.7914377 +154.57,50.30709355,-3.221630237,10000,-57.76583106,191.4795311,0,-14.03629709,0,106.7844117 +154.58,50.30708837,-3.221603399,10000,-57.73101555,191.4866868,0,-14.03629709,0,106.7773858 +154.59,50.30708319,-3.221576561,10000,-57.71012622,191.4936196,0,-14.03629709,0,106.7703599 +154.6,50.30707801,-3.221549722,10000,-57.68923687,191.5009983,0,-14.03629709,0,106.763334 +154.61,50.30707283,-3.221522881,10000,-57.65442134,191.5079311,0,-14.03629709,0,106.756308 +154.62,50.30706766,-3.22149604,10000,-57.61960584,191.514195,0,-14.03629709,0,106.7492821 +154.63,50.30706249,-3.221469198,10000,-57.60219805,191.5213507,0,-14.03629709,0,106.7422562 +154.64,50.30705732,-3.221442355,10000,-57.59523489,191.5293983,0,-14.03629709,0,106.7352303 +154.65,50.30705215,-3.22141551,10000,-57.57782709,191.536777,0,-14.03629709,0,106.7282043 +154.66,50.30704698,-3.221388665,10000,-57.54301157,191.5437097,0,-14.03629709,0,106.7211784 +154.67,50.30704182,-3.221361819,10000,-57.50819606,191.5510884,0,-14.03629709,0,106.7141525 +154.68,50.30703666,-3.221334971,10000,-57.48730673,191.5580211,0,-14.03629709,0,106.7071266 +154.69,50.3070315,-3.221308123,10000,-57.46989895,191.564062,0,-14.03629709,0,106.7001007 +154.7,50.30702634,-3.221281274,10000,-57.44900961,191.5705487,0,-14.03629709,0,106.6930747 +154.71,50.30702119,-3.221254424,10000,-57.43160182,191.5781503,0,-14.03629709,0,106.6860488 +154.72,50.30701603,-3.221227573,10000,-57.41419403,191.5857519,0,-14.03629709,0,106.6790229 +154.73,50.30701088,-3.22120072,10000,-57.38982315,191.5924617,0,-14.03629709,0,106.671997 +154.74,50.30700573,-3.221173868,10000,-57.35848917,191.5989484,0,-14.03629709,0,106.664971 +154.75,50.30700058,-3.221147013,10000,-57.3201921,191.6061041,0,-14.03629709,0,106.6579451 +154.76,50.30699544,-3.221120159,10000,-57.28537658,191.6139286,0,-14.03629709,0,106.6509192 +154.77,50.3069903,-3.221093302,10000,-57.2679688,191.6215302,0,-14.03629709,0,106.6438933 +154.78,50.30698516,-3.221066445,10000,-57.26100567,191.6282398,0,-14.03629709,0,106.6368673 +154.79,50.30698002,-3.221039587,10000,-57.24707943,191.6347266,0,-14.03629709,0,106.6298414 +154.8,50.30697488,-3.221012728,10000,-57.22619007,191.6416592,0,-14.03629709,0,106.6228155 +154.81,50.30696975,-3.220985868,10000,-57.20530073,191.6488148,0,-14.03629709,0,106.6157896 +154.82,50.30696461,-3.220959007,10000,-57.17396676,191.6557474,0,-14.03629709,0,106.6087636 +154.83,50.30695948,-3.220932145,10000,-57.13218816,191.6620112,0,-14.03629709,0,106.6017377 +154.84,50.30695436,-3.220905282,10000,-57.10433573,191.6680519,0,-14.03629709,0,106.5947118 +154.85,50.30694923,-3.220878419,10000,-57.09737258,191.6752075,0,-14.03629709,0,106.5876859 +154.86,50.30694411,-3.220851554,10000,-57.09040944,191.6834779,0,-14.03629709,0,106.5806599 +154.87,50.30693898,-3.220824688,10000,-57.06255702,191.6915253,0,-14.03629709,0,106.5736341 +154.88,50.30693386,-3.220797821,10000,-57.0207784,191.6989038,0,-14.03629709,0,106.5666081 +154.89,50.30692875,-3.220770953,10000,-56.98944441,191.7060594,0,-14.03629709,0,106.5595822 +154.9,50.30692363,-3.220744084,10000,-56.96855508,191.7129919,0,-14.03629709,0,106.5525563 +154.91,50.30691852,-3.220717214,10000,-56.94766576,191.7192556,0,-14.03629709,0,106.5455304 +154.92,50.30691341,-3.220690343,10000,-56.93025797,191.7252963,0,-14.03629709,0,106.5385044 +154.93,50.3069083,-3.220663472,10000,-56.91285019,191.7322288,0,-14.03629709,0,106.5314785 +154.94,50.30690319,-3.220636599,10000,-56.89196086,191.7396073,0,-14.03629709,0,106.5244526 +154.95,50.30689809,-3.220609725,10000,-56.87455307,191.7465399,0,-14.03629709,0,106.5174267 +154.96,50.30689298,-3.220582851,10000,-56.85366373,191.7536954,0,-14.03629709,0,106.5104007 +154.97,50.30688788,-3.220555975,10000,-56.81884821,191.7610738,0,-14.03629709,0,106.5033748 +154.98,50.30688278,-3.220529098,10000,-56.78403269,191.7677834,0,-14.03629709,0,106.4963489 +154.99,50.30687769,-3.220502221,10000,-56.76314336,191.7742699,0,-14.03629709,0,106.489323 +155,50.30687259,-3.220475342,10000,-56.74573557,191.7812024,0,-14.03629709,0,106.482297 +155.01,50.3068675,-3.220448463,10000,-56.72136469,191.7881349,0,-14.03629709,0,106.4752711 +155.02,50.30686241,-3.220421582,10000,-56.69351227,191.7946215,0,-14.03629709,0,106.4682452 +155.03,50.30685732,-3.220394701,10000,-56.66914139,191.801331,0,-14.03629709,0,106.4612193 +155.04,50.30685224,-3.220367819,10000,-56.65173359,191.8089324,0,-14.03629709,0,106.4541933 +155.05,50.30684715,-3.220340935,10000,-56.63432581,191.8167567,0,-14.03629709,0,106.4471674 +155.06,50.30684207,-3.220314051,10000,-56.60995494,191.8239121,0,-14.03629709,0,106.4401415 +155.07,50.30683699,-3.220287165,10000,-56.57862097,191.8303987,0,-14.03629709,0,106.4331156 +155.08,50.30683191,-3.220260279,10000,-56.54380546,191.8371081,0,-14.03629709,0,106.4260896 +155.09,50.30682684,-3.220233392,10000,-56.51943458,191.8444865,0,-14.03629709,0,106.4190637 +155.1,50.30682177,-3.220206503,10000,-56.50550833,191.8514189,0,-14.03629709,0,106.4120378 +155.11,50.30681669,-3.220179614,10000,-56.48461899,191.8576825,0,-14.03629709,0,106.4050119 +155.12,50.30681163,-3.220152724,10000,-56.46372967,191.8648378,0,-14.03629709,0,106.397986 +155.13,50.30680656,-3.220125833,10000,-56.44980344,191.8728851,0,-14.03629709,0,106.39096 +155.14,50.30680149,-3.22009894,10000,-56.42543255,191.8800405,0,-14.03629709,0,106.3839341 +155.15,50.30679643,-3.220072047,10000,-56.39061702,191.886081,0,-14.03629709,0,106.3769082 +155.16,50.30679137,-3.220045153,10000,-56.35928304,191.8923445,0,-14.03629709,0,106.3698823 +155.17,50.30678631,-3.220018258,10000,-56.33491217,191.8992769,0,-14.03629709,0,106.3628563 +155.18,50.30678126,-3.219991362,10000,-56.3175044,191.9062092,0,-14.03629709,0,106.3558304 +155.19,50.3067762,-3.219964465,10000,-56.30009662,191.9124727,0,-14.03629709,0,106.3488045 +155.2,50.30677115,-3.219937567,10000,-56.27572574,191.9185132,0,-14.03629709,0,106.3417786 +155.21,50.3067661,-3.219910669,10000,-56.2478733,191.9254455,0,-14.03629709,0,106.3347526 +155.22,50.30676105,-3.219883769,10000,-56.22350241,191.9330468,0,-14.03629709,0,106.3277268 +155.23,50.30675601,-3.219856868,10000,-56.20609464,191.940648,0,-14.03629709,0,106.3207008 +155.24,50.30675096,-3.219829967,10000,-56.18868687,191.9482493,0,-14.03629709,0,106.3136749 +155.25,50.30674592,-3.219803063,10000,-56.16431599,191.9551816,0,-14.03629709,0,106.306649 +155.26,50.30674088,-3.21977616,10000,-56.13298202,191.9612221,0,-14.03629709,0,106.2996231 +155.27,50.30673584,-3.219749255,10000,-56.09468495,191.9674855,0,-14.03629709,0,106.2925971 +155.28,50.30673081,-3.21972235,10000,-56.05986944,191.9744178,0,-14.03629709,0,106.2855712 +155.29,50.30672578,-3.219695443,10000,-56.04246165,191.981796,0,-14.03629709,0,106.2785453 +155.3,50.30672075,-3.219668536,10000,-56.0354985,191.9896201,0,-14.03629709,0,106.2715194 +155.31,50.30671572,-3.219641627,10000,-56.02157226,191.9969984,0,-14.03629709,0,106.2644934 +155.32,50.30671069,-3.219614717,10000,-56.00068293,192.0030388,0,-14.03629709,0,106.2574675 +155.33,50.30670567,-3.219587807,10000,-55.98327515,192.0090792,0,-14.03629709,0,106.2504416 +155.34,50.30670064,-3.219560896,10000,-55.96238582,192.0162344,0,-14.03629709,0,106.2434157 +155.35,50.30669562,-3.219533983,10000,-55.9275703,192.0233896,0,-14.03629709,0,106.2363897 +155.36,50.3066906,-3.21950707,10000,-55.89275479,192.0303219,0,-14.03629709,0,106.2293638 +155.37,50.30668559,-3.219480156,10000,-55.87186546,192.0377001,0,-14.03629709,0,106.2223379 +155.38,50.30668057,-3.21945324,10000,-55.85445767,192.0446323,0,-14.03629709,0,106.215312 +155.39,50.30667556,-3.219426324,10000,-55.83008679,192.0506726,0,-14.03629709,0,106.208286 +155.4,50.30667055,-3.219399407,10000,-55.80223437,192.056936,0,-14.03629709,0,106.2012601 +155.41,50.30666554,-3.219372489,10000,-55.77786349,192.0638682,0,-14.03629709,0,106.1942342 +155.42,50.30666054,-3.21934557,10000,-55.76045571,192.0710233,0,-14.03629709,0,106.1872083 +155.43,50.30665553,-3.21931865,10000,-55.73956639,192.0779555,0,-14.03629709,0,106.1801823 +155.44,50.30665053,-3.219291729,10000,-55.70475089,192.0842188,0,-14.03629709,0,106.1731564 +155.45,50.30664553,-3.219264807,10000,-55.66993536,192.0902591,0,-14.03629709,0,106.1661305 +155.46,50.30664054,-3.219237885,10000,-55.64904601,192.0974143,0,-14.03629709,0,106.1591046 +155.47,50.30663554,-3.219210961,10000,-55.63163822,192.1056843,0,-14.03629709,0,106.1520786 +155.48,50.30663055,-3.219184036,10000,-55.61074889,192.1137313,0,-14.03629709,0,106.1450527 +155.49,50.30662556,-3.21915711,10000,-55.59334113,192.1208864,0,-14.03629709,0,106.1380268 +155.5,50.30662057,-3.219130183,10000,-55.57245181,192.1271496,0,-14.03629709,0,106.1310009 +155.51,50.30661558,-3.219103255,10000,-55.53763629,192.1329669,0,-14.03629709,0,106.123975 +155.52,50.3066106,-3.219076327,10000,-55.50282076,192.1392302,0,-14.03629709,0,106.116949 +155.53,50.30660562,-3.219049397,10000,-55.48541297,192.1461623,0,-14.03629709,0,106.1099231 +155.54,50.30660064,-3.219022467,10000,-55.47844983,192.1530944,0,-14.03629709,0,106.1028972 +155.55,50.30659566,-3.218995535,10000,-55.46104206,192.1593576,0,-14.03629709,0,106.0958713 +155.56,50.30659068,-3.218968603,10000,-55.42622654,192.1653978,0,-14.03629709,0,106.0888454 +155.57,50.30658571,-3.21894167,10000,-55.39141101,192.1725529,0,-14.03629709,0,106.0818195 +155.58,50.30658074,-3.218914736,10000,-55.37400323,192.1805998,0,-14.03629709,0,106.0747935 +155.59,50.30657577,-3.2188878,10000,-55.3670401,192.1877549,0,-14.03629709,0,106.0677676 +155.6,50.3065708,-3.218860864,10000,-55.34963233,192.1937951,0,-14.03629709,0,106.0607417 +155.61,50.30656583,-3.218833927,10000,-55.31481681,192.2000583,0,-14.03629709,0,106.0537158 +155.62,50.30656087,-3.218806989,10000,-55.28000128,192.2069903,0,-14.03629709,0,106.0466898 +155.63,50.30655591,-3.21878005,10000,-55.25911195,192.2141454,0,-14.03629709,0,106.0396639 +155.64,50.30655095,-3.21875311,10000,-55.23822263,192.2210774,0,-14.03629709,0,106.032638 +155.65,50.30654599,-3.218726169,10000,-55.20340711,192.2273405,0,-14.03629709,0,106.0256121 +155.66,50.30654104,-3.218699227,10000,-55.16859159,192.2333807,0,-14.03629709,0,106.0185861 +155.67,50.30653609,-3.218672285,10000,-55.15118381,192.2405357,0,-14.03629709,0,106.0115602 +155.68,50.30653114,-3.218645341,10000,-55.14422067,192.2485826,0,-14.03629709,0,106.0045343 +155.69,50.30652619,-3.218618396,10000,-55.13029443,192.2557375,0,-14.03629709,0,105.9975084 +155.7,50.30652124,-3.21859145,10000,-55.1094051,192.2620006,0,-14.03629709,0,105.9904824 +155.71,50.3065163,-3.218564504,10000,-55.08851578,192.2689327,0,-14.03629709,0,105.9834565 +155.72,50.30651135,-3.218537556,10000,-55.05718182,192.2760876,0,-14.03629709,0,105.9764306 +155.73,50.30650641,-3.218510607,10000,-55.01540321,192.2819048,0,-14.03629709,0,105.9694047 +155.74,50.30650148,-3.218483658,10000,-54.98406924,192.2872759,0,-14.03629709,0,105.9623787 +155.75,50.30649654,-3.218456708,10000,-54.9631799,192.2942079,0,-14.03629709,0,105.9553528 +155.76,50.30649161,-3.218429757,10000,-54.94229057,192.3022547,0,-14.03629709,0,105.9483269 +155.77,50.30648668,-3.218402804,10000,-54.92836433,192.3094096,0,-14.03629709,0,105.941301 +155.78,50.30648175,-3.218375851,10000,-54.9214012,192.3154497,0,-14.03629709,0,105.934275 +155.79,50.30647682,-3.218348897,10000,-54.90399343,192.3217127,0,-14.03629709,0,105.9272491 +155.8,50.30647189,-3.218321942,10000,-54.86917791,192.3286447,0,-14.03629709,0,105.9202232 +155.81,50.30646697,-3.218294986,10000,-54.83436239,192.3357996,0,-14.03629709,0,105.9131973 +155.82,50.30646205,-3.218268029,10000,-54.81347306,192.3427315,0,-14.03629709,0,105.9061713 +155.83,50.30645713,-3.218241071,10000,-54.79258373,192.3489945,0,-14.03629709,0,105.8991454 +155.84,50.30645221,-3.218214112,10000,-54.75776822,192.3550345,0,-14.03629709,0,105.8921195 +155.85,50.3064473,-3.218187153,10000,-54.72295272,192.3619664,0,-14.03629709,0,105.8850936 +155.86,50.30644239,-3.218160192,10000,-54.70554494,192.3693443,0,-14.03629709,0,105.8780676 +155.87,50.30643748,-3.21813323,10000,-54.6985818,192.3760532,0,-14.03629709,0,105.8710417 +155.88,50.30643257,-3.218106268,10000,-54.68117401,192.3825391,0,-14.03629709,0,105.8640158 +155.89,50.30642766,-3.218079304,10000,-54.64635849,192.389471,0,-14.03629709,0,105.8569899 +155.9,50.30642276,-3.21805234,10000,-54.61154297,192.3964029,0,-14.03629709,0,105.849964 +155.91,50.30641786,-3.218025374,10000,-54.59413518,192.4028888,0,-14.03629709,0,105.8429381 +155.92,50.30641296,-3.217998408,10000,-54.58717205,192.4095977,0,-14.03629709,0,105.8359122 +155.93,50.30640806,-3.217971441,10000,-54.56976427,192.4167525,0,-14.03629709,0,105.8288862 +155.94,50.30640316,-3.217944472,10000,-54.53494877,192.4230154,0,-14.03629709,0,105.8218603 +155.95,50.30639827,-3.217917503,10000,-54.50013325,192.4288324,0,-14.03629709,0,105.8148344 +155.96,50.30639338,-3.217890534,10000,-54.47924393,192.4359872,0,-14.03629709,0,105.8078085 +155.97,50.30638849,-3.217863562,10000,-54.46183616,192.4431419,0,-14.03629709,0,105.8007825 +155.98,50.3063836,-3.21783659,10000,-54.44094684,192.4489589,0,-14.03629709,0,105.7937566 +155.99,50.30637872,-3.217809618,10000,-54.42353904,192.4552218,0,-14.03629709,0,105.7867307 +156,50.30637383,-3.217782644,10000,-54.40264971,192.4623766,0,-14.03629709,0,105.7797048 +156.01,50.30636895,-3.217755669,10000,-54.3678342,192.4693084,0,-14.03629709,0,105.7726788 +156.02,50.30636407,-3.217728694,10000,-54.33301869,192.4764631,0,-14.03629709,0,105.7656529 +156.03,50.3063592,-3.217701717,10000,-54.31212936,192.4836178,0,-14.03629709,0,105.758627 +156.04,50.30635432,-3.217674739,10000,-54.29472158,192.4896577,0,-14.03629709,0,105.7516011 +156.05,50.30634945,-3.217647761,10000,-54.27035071,192.4956976,0,-14.03629709,0,105.7445751 +156.06,50.30634458,-3.217620782,10000,-54.24249828,192.5028523,0,-14.03629709,0,105.7375492 +156.07,50.30633971,-3.217593801,10000,-54.21812741,192.5097841,0,-14.03629709,0,105.7305233 +156.08,50.30633485,-3.21756682,10000,-54.20071964,192.5158239,0,-14.03629709,0,105.7234974 +156.09,50.30632998,-3.217539838,10000,-54.18331187,192.5220867,0,-14.03629709,0,105.7164714 +156.1,50.30632512,-3.217512855,10000,-54.15894099,192.5290185,0,-14.03629709,0,105.7094455 +156.11,50.30632026,-3.217485871,10000,-54.12760702,192.5361731,0,-14.03629709,0,105.7024196 +156.12,50.3063154,-3.217458886,10000,-54.0927915,192.5433278,0,-14.03629709,0,105.6953937 +156.13,50.30631055,-3.2174319,10000,-54.06842062,192.5502595,0,-14.03629709,0,105.6883677 +156.14,50.3063057,-3.217404913,10000,-54.05449439,192.5565223,0,-14.03629709,0,105.6813418 +156.15,50.30630084,-3.217377925,10000,-54.03360507,192.5623391,0,-14.03629709,0,105.6743159 +156.16,50.306296,-3.217350937,10000,-54.01271576,192.5686019,0,-14.03629709,0,105.66729 +156.17,50.30629115,-3.217323947,10000,-53.99878954,192.5755336,0,-14.03629709,0,105.660264 +156.18,50.3062863,-3.217296957,10000,-53.97441866,192.5826882,0,-14.03629709,0,105.6532381 +156.19,50.30628146,-3.217269965,10000,-53.93960313,192.5898428,0,-14.03629709,0,105.6462122 +156.2,50.30627662,-3.217242973,10000,-53.90826916,192.5967745,0,-14.03629709,0,105.6391863 +156.21,50.30627178,-3.217215979,10000,-53.8838983,192.6030372,0,-14.03629709,0,105.6321603 +156.22,50.30626695,-3.217188985,10000,-53.86649053,192.608854,0,-14.03629709,0,105.6251344 +156.23,50.30626211,-3.21716199,10000,-53.84908274,192.6151167,0,-14.03629709,0,105.6181085 +156.24,50.30625728,-3.217134994,10000,-53.82471184,192.6220483,0,-14.03629709,0,105.6110826 +156.25,50.30625245,-3.217107997,10000,-53.79685942,192.6289799,0,-14.03629709,0,105.6040566 +156.26,50.30624762,-3.217080999,10000,-53.77248857,192.6352426,0,-14.03629709,0,105.5970308 +156.27,50.3062428,-3.217054,10000,-53.75508081,192.6412823,0,-14.03629709,0,105.5900048 +156.28,50.30623797,-3.217027001,10000,-53.73419147,192.6482139,0,-14.03629709,0,105.5829789 +156.29,50.30623315,-3.217,10000,-53.69937595,192.6553685,0,-14.03629709,0,105.575953 +156.3,50.30622833,-3.216972998,10000,-53.66456043,192.6614082,0,-14.03629709,0,105.5689271 +156.31,50.30622352,-3.216945996,10000,-53.64367112,192.6674479,0,-14.03629709,0,105.5619012 +156.32,50.3062187,-3.216918993,10000,-53.62626336,192.6746024,0,-14.03629709,0,105.5548752 +156.33,50.30621389,-3.216891988,10000,-53.60537404,192.6815339,0,-14.03629709,0,105.5478493 +156.34,50.30620908,-3.216864983,10000,-53.58796626,192.6875736,0,-14.03629709,0,105.5408234 +156.35,50.30620427,-3.216837977,10000,-53.56707693,192.6938362,0,-14.03629709,0,105.5337975 +156.36,50.30619946,-3.21681097,10000,-53.53226141,192.7007678,0,-14.03629709,0,105.5267715 +156.37,50.30619466,-3.216783962,10000,-53.4974459,192.7079223,0,-14.03629709,0,105.5197456 +156.38,50.30618986,-3.216756953,10000,-53.48003813,192.7150768,0,-14.03629709,0,105.5127197 +156.39,50.30618506,-3.216729943,10000,-53.47307499,192.7220083,0,-14.03629709,0,105.5056938 +156.4,50.30618026,-3.216702932,10000,-53.4556672,192.7282709,0,-14.03629709,0,105.4986678 +156.41,50.30617546,-3.21667592,10000,-53.42085169,192.7340875,0,-14.03629709,0,105.4916419 +156.42,50.30617067,-3.216648908,10000,-53.38603618,192.7401271,0,-14.03629709,0,105.484616 +156.43,50.30616588,-3.216621894,10000,-53.36862841,192.7463897,0,-14.03629709,0,105.4775901 +156.44,50.30616109,-3.21659488,10000,-53.36166528,192.7530982,0,-14.03629709,0,105.4705641 +156.45,50.3061563,-3.216567865,10000,-53.34425749,192.7604756,0,-14.03629709,0,105.4635382 +156.46,50.30615151,-3.216540848,10000,-53.30944198,192.7674071,0,-14.03629709,0,105.4565123 +156.47,50.30614673,-3.216513831,10000,-53.27462648,192.7734466,0,-14.03629709,0,105.4494864 +156.48,50.30614195,-3.216486813,10000,-53.25373716,192.7794862,0,-14.03629709,0,105.4424604 +156.49,50.30613717,-3.216459794,10000,-53.23284782,192.7855257,0,-14.03629709,0,105.4354345 +156.5,50.30613239,-3.216432774,10000,-53.1980323,192.7915653,0,-14.03629709,0,105.4284086 +156.51,50.30612762,-3.216405754,10000,-53.1632168,192.7984967,0,-14.03629709,0,105.4213827 +156.52,50.30612285,-3.216378732,10000,-53.14580904,192.8058741,0,-14.03629709,0,105.4143567 +156.53,50.30611808,-3.216351709,10000,-53.1388459,192.8125825,0,-14.03629709,0,105.4073308 +156.54,50.30611331,-3.216324686,10000,-53.12491967,192.819068,0,-14.03629709,0,105.4003049 +156.55,50.30610854,-3.216297661,10000,-53.10403034,192.8259994,0,-14.03629709,0,105.393279 +156.56,50.30610378,-3.216270636,10000,-53.08314102,192.8329308,0,-14.03629709,0,105.386253 +156.57,50.30609901,-3.216243609,10000,-53.05180705,192.8389703,0,-14.03629709,0,105.3792272 +156.58,50.30609425,-3.216216582,10000,-53.01002844,192.8438949,0,-14.03629709,0,105.3722012 +156.59,50.3060895,-3.216189554,10000,-52.97869448,192.8490425,0,-14.03629709,0,105.3651753 +156.6,50.30608474,-3.216162526,10000,-52.95780516,192.8559738,0,-14.03629709,0,105.3581494 +156.61,50.30607999,-3.216135496,10000,-52.93691584,192.864243,0,-14.03629709,0,105.3511235 +156.62,50.30607524,-3.216108465,10000,-52.92298961,192.8720663,0,-14.03629709,0,105.3440975 +156.63,50.30607049,-3.216081433,10000,-52.91602647,192.8783287,0,-14.03629709,0,105.3370716 +156.64,50.30606574,-3.2160544,10000,-52.8986187,192.8834762,0,-14.03629709,0,105.3300457 +156.65,50.30606099,-3.216027367,10000,-52.86380319,192.8892927,0,-14.03629709,0,105.3230198 +156.66,50.30605625,-3.216000333,10000,-52.82550612,192.896447,0,-14.03629709,0,105.3159938 +156.67,50.30605151,-3.215973297,10000,-52.79417216,192.9033783,0,-14.03629709,0,105.3089679 +156.68,50.30604677,-3.215946261,10000,-52.7698013,192.9094177,0,-14.03629709,0,105.301942 +156.69,50.30604204,-3.215919224,10000,-52.75239354,192.9156801,0,-14.03629709,0,105.2949161 +156.7,50.3060373,-3.215892186,10000,-52.73498576,192.9226114,0,-14.03629709,0,105.2878902 +156.71,50.30603257,-3.215865147,10000,-52.71061489,192.9297656,0,-14.03629709,0,105.2808642 +156.72,50.30602784,-3.215838107,10000,-52.68276247,192.9366969,0,-14.03629709,0,105.2738383 +156.73,50.30602311,-3.215811066,10000,-52.6583916,192.9429593,0,-14.03629709,0,105.2668124 +156.74,50.30601839,-3.215784024,10000,-52.64098382,192.9487757,0,-14.03629709,0,105.2597865 +156.75,50.30601366,-3.215756982,10000,-52.62357604,192.954815,0,-14.03629709,0,105.2527605 +156.76,50.30600894,-3.215729938,10000,-52.59920517,192.9610773,0,-14.03629709,0,105.2457346 +156.77,50.30600422,-3.215702894,10000,-52.57135276,192.9677856,0,-14.03629709,0,105.2387087 +156.78,50.3059995,-3.215675849,10000,-52.54698188,192.9749398,0,-14.03629709,0,105.2316828 +156.79,50.30599479,-3.215648802,10000,-52.52957411,192.9812021,0,-14.03629709,0,105.2246568 +156.8,50.30599007,-3.215621755,10000,-52.50868478,192.9867955,0,-14.03629709,0,105.2176309 +156.81,50.30598536,-3.215594708,10000,-52.47386928,192.9932808,0,-14.03629709,0,105.210605 +156.82,50.30598065,-3.215567658,10000,-52.43905378,193.000212,0,-14.03629709,0,105.2035791 +156.83,50.30597595,-3.215540609,10000,-52.41816447,193.0069202,0,-14.03629709,0,105.1965531 +156.84,50.30597124,-3.215513558,10000,-52.40075668,193.0134054,0,-14.03629709,0,105.1895272 +156.85,50.30596654,-3.215486506,10000,-52.37638581,193.0192217,0,-14.03629709,0,105.1825013 +156.86,50.30596184,-3.215459454,10000,-52.3485334,193.025261,0,-14.03629709,0,105.1754754 +156.87,50.30595714,-3.215432401,10000,-52.32416254,193.0324152,0,-14.03629709,0,105.1684494 +156.88,50.30595245,-3.215405346,10000,-52.30675475,193.0393463,0,-14.03629709,0,105.1614235 +156.89,50.30594775,-3.215378291,10000,-52.28934697,193.0453856,0,-14.03629709,0,105.1543976 +156.9,50.30594306,-3.215351235,10000,-52.2649761,193.0514248,0,-14.03629709,0,105.1473717 +156.91,50.30593837,-3.215324178,10000,-52.23712369,193.0574641,0,-14.03629709,0,105.1403457 +156.92,50.30593368,-3.21529712,10000,-52.21275283,193.0632803,0,-14.03629709,0,105.1333199 +156.93,50.305929,-3.215270062,10000,-52.19534506,193.0695425,0,-14.03629709,0,105.1262939 +156.94,50.30592431,-3.215243002,10000,-52.17445574,193.0764737,0,-14.03629709,0,105.119268 +156.95,50.30591963,-3.215215942,10000,-52.13964023,193.0834048,0,-14.03629709,0,105.1122421 +156.96,50.30591495,-3.21518888,10000,-52.10482472,193.0896669,0,-14.03629709,0,105.1052162 +156.97,50.30591028,-3.215161818,10000,-52.08393539,193.0954832,0,-14.03629709,0,105.0981902 +156.98,50.3059056,-3.215134755,10000,-52.06652762,193.1017453,0,-14.03629709,0,105.0911643 +156.99,50.30590093,-3.215107691,10000,-52.04563831,193.1086764,0,-14.03629709,0,105.0841384 +157,50.30589626,-3.215080626,10000,-52.02823054,193.1158305,0,-14.03629709,0,105.0771125 +157.01,50.30589159,-3.21505356,10000,-52.0073412,193.1227615,0,-14.03629709,0,105.0700865 +157.02,50.30588692,-3.215026493,10000,-51.9725257,193.1288007,0,-14.03629709,0,105.0630606 +157.03,50.30588226,-3.214999425,10000,-51.93771019,193.1339479,0,-14.03629709,0,105.0560347 +157.04,50.3058776,-3.214972357,10000,-51.92030243,193.1397641,0,-14.03629709,0,105.0490088 +157.05,50.30587294,-3.214945288,10000,-51.91333929,193.1469181,0,-14.03629709,0,105.0419828 +157.06,50.30586828,-3.214918217,10000,-51.89593151,193.1538491,0,-14.03629709,0,105.0349569 +157.07,50.30586362,-3.214891146,10000,-51.86111599,193.1598883,0,-14.03629709,0,105.027931 +157.08,50.30585897,-3.214864074,10000,-51.82630049,193.1661504,0,-14.03629709,0,105.0209051 +157.09,50.30585432,-3.214837001,10000,-51.80541119,193.1728584,0,-14.03629709,0,105.0138791 +157.1,50.30584967,-3.214809927,10000,-51.78800342,193.1791205,0,-14.03629709,0,105.0068532 +157.11,50.30584502,-3.214782852,10000,-51.7671141,193.1851596,0,-14.03629709,0,104.9998273 +157.12,50.30584038,-3.214755777,10000,-51.74970633,193.1920906,0,-14.03629709,0,104.9928014 +157.13,50.30583573,-3.2147287,10000,-51.728817,193.1992445,0,-14.03629709,0,104.9857755 +157.14,50.30583109,-3.214701622,10000,-51.69400148,193.2050606,0,-14.03629709,0,104.9787495 +157.15,50.30582645,-3.214674544,10000,-51.65918596,193.2102078,0,-14.03629709,0,104.9717236 +157.16,50.30582182,-3.214647465,10000,-51.63829664,193.2162468,0,-14.03629709,0,104.9646977 +157.17,50.30581718,-3.214620385,10000,-51.62088888,193.2229548,0,-14.03629709,0,104.9576718 +157.18,50.30581255,-3.214593304,10000,-51.59651802,193.2292168,0,-14.03629709,0,104.9506458 +157.19,50.30580792,-3.214566222,10000,-51.5686656,193.2352559,0,-14.03629709,0,104.9436199 +157.2,50.30580329,-3.21453914,10000,-51.54429473,193.2421868,0,-14.03629709,0,104.936594 +157.21,50.30579867,-3.214512056,10000,-51.52688696,193.2493407,0,-14.03629709,0,104.9295681 +157.22,50.30579404,-3.214484971,10000,-51.5094792,193.2553797,0,-14.03629709,0,104.9225421 +157.23,50.30578942,-3.214457886,10000,-51.48510834,193.2611957,0,-14.03629709,0,104.9155163 +157.24,50.3057848,-3.2144308,10000,-51.45725592,193.2676807,0,-14.03629709,0,104.9084903 +157.25,50.30578018,-3.214403712,10000,-51.43288505,193.2741656,0,-14.03629709,0,104.9014644 +157.26,50.30577557,-3.214376625,10000,-51.41547727,193.2804276,0,-14.03629709,0,104.8944385 +157.27,50.30577095,-3.214349535,10000,-51.39458796,193.2866895,0,-14.03629709,0,104.8874126 +157.28,50.30576634,-3.214322446,10000,-51.35977245,193.2931745,0,-14.03629709,0,104.8803866 +157.29,50.30576173,-3.214295355,10000,-51.32495695,193.2996594,0,-14.03629709,0,104.8733607 +157.3,50.30575713,-3.214268263,10000,-51.30406765,193.3052524,0,-14.03629709,0,104.8663348 +157.31,50.30575252,-3.214241171,10000,-51.28665988,193.3103994,0,-14.03629709,0,104.8593089 +157.32,50.30574792,-3.214214078,10000,-51.26577055,193.3164384,0,-14.03629709,0,104.8522829 +157.33,50.30574332,-3.214186984,10000,-51.24836276,193.3233692,0,-14.03629709,0,104.845257 +157.34,50.30573872,-3.214159889,10000,-51.22747344,193.330523,0,-14.03629709,0,104.8382311 +157.35,50.30573412,-3.214132793,10000,-51.19265793,193.3376768,0,-14.03629709,0,104.8312052 +157.36,50.30572953,-3.214105696,10000,-51.15784243,193.3446076,0,-14.03629709,0,104.8241792 +157.37,50.30572494,-3.214078598,10000,-51.14043466,193.3506465,0,-14.03629709,0,104.8171533 +157.38,50.30572035,-3.214051499,10000,-51.13347154,193.3555705,0,-14.03629709,0,104.8101274 +157.39,50.30571576,-3.2140244,10000,-51.11606377,193.3607175,0,-14.03629709,0,104.8031015 +157.4,50.30571117,-3.2139973,10000,-51.08124825,193.3674253,0,-14.03629709,0,104.7960755 +157.41,50.30570659,-3.213970199,10000,-51.04643274,193.3745791,0,-14.03629709,0,104.7890496 +157.42,50.30570201,-3.213943096,10000,-51.02554343,193.3806179,0,-14.03629709,0,104.7820237 +157.43,50.30569743,-3.213915994,10000,-51.00465412,193.3866568,0,-14.03629709,0,104.7749978 +157.44,50.30569285,-3.21388889,10000,-50.96983862,193.3938105,0,-14.03629709,0,104.7679718 +157.45,50.30568828,-3.213861785,10000,-50.93502311,193.4005183,0,-14.03629709,0,104.7609459 +157.46,50.30568371,-3.213834679,10000,-50.91761532,193.4058882,0,-14.03629709,0,104.75392 +157.47,50.30567914,-3.213807573,10000,-50.9106522,193.411704,0,-14.03629709,0,104.7468941 +157.48,50.30567457,-3.213780466,10000,-50.89672599,193.4186347,0,-14.03629709,0,104.7398681 +157.49,50.30567,-3.213753357,10000,-50.87583667,193.4246735,0,-14.03629709,0,104.7328422 +157.5,50.30566544,-3.213726248,10000,-50.85494734,193.4295975,0,-14.03629709,0,104.7258163 +157.51,50.30566087,-3.213699139,10000,-50.82361337,193.4358593,0,-14.03629709,0,104.7187904 +157.52,50.30565631,-3.213672028,10000,-50.78183476,193.4436819,0,-14.03629709,0,104.7117645 +157.53,50.30565176,-3.213644916,10000,-50.75398236,193.4506125,0,-14.03629709,0,104.7047385 +157.54,50.3056472,-3.213617803,10000,-50.7435377,193.4557594,0,-14.03629709,0,104.6977126 +157.55,50.30564265,-3.21359069,10000,-50.72612993,193.4606833,0,-14.03629709,0,104.6906867 +157.56,50.30563809,-3.213563576,10000,-50.69479597,193.4667221,0,-14.03629709,0,104.6836608 +157.57,50.30563355,-3.213536461,10000,-50.67042511,193.4736527,0,-14.03629709,0,104.6766348 +157.58,50.305629,-3.213509345,10000,-50.65649889,193.4805834,0,-14.03629709,0,104.669609 +157.59,50.30562445,-3.213482228,10000,-50.63212804,193.4868451,0,-14.03629709,0,104.662583 +157.6,50.30561991,-3.21345511,10000,-50.60079407,193.4928838,0,-14.03629709,0,104.6555571 +157.61,50.30561537,-3.213427992,10000,-50.57990474,193.4998144,0,-14.03629709,0,104.6485312 +157.62,50.30561083,-3.213400872,10000,-50.55901542,193.506968,0,-14.03629709,0,104.6415053 +157.63,50.30560629,-3.213373751,10000,-50.52419992,193.5127838,0,-14.03629709,0,104.6344793 +157.64,50.30560176,-3.21334663,10000,-50.48938443,193.5179306,0,-14.03629709,0,104.6274534 +157.65,50.30559723,-3.213319508,10000,-50.47197666,193.5237463,0,-14.03629709,0,104.6204275 +157.66,50.3055927,-3.213292385,10000,-50.46501351,193.529785,0,-14.03629709,0,104.6134016 +157.67,50.30558817,-3.213265261,10000,-50.44760574,193.5356007,0,-14.03629709,0,104.6063756 +157.68,50.30558364,-3.213238137,10000,-50.41279024,193.5418623,0,-14.03629709,0,104.5993497 +157.69,50.30557912,-3.213211011,10000,-50.37797474,193.5485699,0,-14.03629709,0,104.5923238 +157.7,50.3055746,-3.213183885,10000,-50.35708542,193.5546086,0,-14.03629709,0,104.5852979 +157.71,50.30557008,-3.213156757,10000,-50.33967765,193.5597553,0,-14.03629709,0,104.5782719 +157.72,50.30556556,-3.21312963,10000,-50.31878834,193.565571,0,-14.03629709,0,104.571246 +157.73,50.30556105,-3.213102501,10000,-50.30138057,193.5727245,0,-14.03629709,0,104.5642201 +157.74,50.30555653,-3.213075371,10000,-50.2839728,193.579655,0,-14.03629709,0,104.5571942 +157.75,50.30555202,-3.21304824,10000,-50.25960193,193.5856936,0,-14.03629709,0,104.5501682 +157.76,50.30554751,-3.213021109,10000,-50.22826798,193.5919552,0,-14.03629709,0,104.5431423 +157.77,50.305543,-3.212993976,10000,-50.18997093,193.5986628,0,-14.03629709,0,104.5361164 +157.78,50.3055385,-3.212966843,10000,-50.15515542,193.6049243,0,-14.03629709,0,104.5290905 +157.79,50.305534,-3.212939708,10000,-50.13774764,193.6107399,0,-14.03629709,0,104.5220645 +157.8,50.3055295,-3.212912574,10000,-50.13078451,193.6167785,0,-14.03629709,0,104.5150386 +157.81,50.305525,-3.212885437,10000,-50.11337676,193.6228171,0,-14.03629709,0,104.5080127 +157.82,50.3055205,-3.212858301,10000,-50.07856126,193.6286327,0,-14.03629709,0,104.5009868 +157.83,50.30551601,-3.212831163,10000,-50.04374575,193.6348942,0,-14.03629709,0,104.4939608 +157.84,50.30551152,-3.212804025,10000,-50.02633798,193.6416017,0,-14.03629709,0,104.4869349 +157.85,50.30550703,-3.212776885,10000,-50.01937486,193.6478632,0,-14.03629709,0,104.479909 +157.86,50.30550254,-3.212749745,10000,-50.00196709,193.6534558,0,-14.03629709,0,104.4728831 +157.87,50.30549805,-3.212722604,10000,-49.96715157,193.6588254,0,-14.03629709,0,104.4658571 +157.88,50.30549357,-3.212695462,10000,-49.93233607,193.664418,0,-14.03629709,0,104.4588312 +157.89,50.30548909,-3.21266832,10000,-49.91144676,193.6706795,0,-14.03629709,0,104.4518053 +157.9,50.30548461,-3.212641176,10000,-49.89055745,193.6776099,0,-14.03629709,0,104.4447794 +157.91,50.30548013,-3.212614032,10000,-49.85574196,193.6845403,0,-14.03629709,0,104.4377535 +157.92,50.30547566,-3.212586886,10000,-49.82092646,193.6908017,0,-14.03629709,0,104.4307275 +157.93,50.30547119,-3.21255974,10000,-49.80351867,193.6963943,0,-14.03629709,0,104.4237017 +157.94,50.30546672,-3.212532593,10000,-49.79655554,193.7017638,0,-14.03629709,0,104.4166757 +157.95,50.30546225,-3.212505445,10000,-49.78262933,193.7073563,0,-14.03629709,0,104.4096498 +157.96,50.30545778,-3.212478297,10000,-49.76174001,193.7136178,0,-14.03629709,0,104.4026239 +157.97,50.30545332,-3.212451147,10000,-49.74085068,193.7205481,0,-14.03629709,0,104.395598 +157.98,50.30544885,-3.212423997,10000,-49.70951673,193.7274785,0,-14.03629709,0,104.388572 +157.99,50.30544439,-3.212396845,10000,-49.66773814,193.7335169,0,-14.03629709,0,104.3815461 +158,50.30543994,-3.212369693,10000,-49.63640419,193.7384405,0,-14.03629709,0,104.3745202 +158.01,50.30543548,-3.21234254,10000,-49.61551488,193.743364,0,-14.03629709,0,104.3674943 +158.02,50.30543103,-3.212315387,10000,-49.59462556,193.7494024,0,-14.03629709,0,104.3604683 +158.03,50.30542658,-3.212288232,10000,-49.57721779,193.7563328,0,-14.03629709,0,104.3534424 +158.04,50.30542213,-3.212261077,10000,-49.55981002,193.7632631,0,-14.03629709,0,104.3464165 +158.05,50.30541768,-3.21223392,10000,-49.5389207,193.7695244,0,-14.03629709,0,104.3393906 +158.06,50.30541324,-3.212206763,10000,-49.52151293,193.7753398,0,-14.03629709,0,104.3323646 +158.07,50.30540879,-3.212179605,10000,-49.50062362,193.7813782,0,-14.03629709,0,104.3253387 +158.08,50.30540435,-3.212152446,10000,-49.46580813,193.7874166,0,-14.03629709,0,104.3183128 +158.09,50.30539991,-3.212125286,10000,-49.43099263,193.793232,0,-14.03629709,0,104.3112869 +158.1,50.30539548,-3.212098126,10000,-49.41010331,193.7994933,0,-14.03629709,0,104.3042609 +158.11,50.30539104,-3.212070964,10000,-49.39269554,193.8062006,0,-14.03629709,0,104.297235 +158.12,50.30538661,-3.212043802,10000,-49.36832469,193.8124619,0,-14.03629709,0,104.2902091 +158.13,50.30538218,-3.212016638,10000,-49.34047228,193.8182773,0,-14.03629709,0,104.2831832 +158.14,50.30537775,-3.211989475,10000,-49.31610141,193.8240926,0,-14.03629709,0,104.2761572 +158.15,50.30537333,-3.211962309,10000,-49.29869363,193.829462,0,-14.03629709,0,104.2691313 +158.16,50.3053689,-3.211935144,10000,-49.28128586,193.8348314,0,-14.03629709,0,104.2621054 +158.17,50.30536448,-3.211907978,10000,-49.256915,193.8413157,0,-14.03629709,0,104.2550795 +158.18,50.30536006,-3.21188081,10000,-49.22558106,193.8480229,0,-14.03629709,0,104.2480535 +158.19,50.30535564,-3.211853642,10000,-49.18728402,193.8540612,0,-14.03629709,0,104.2410276 +158.2,50.30535123,-3.211826473,10000,-49.15246853,193.8600994,0,-14.03629709,0,104.2340017 +158.21,50.30534682,-3.211799303,10000,-49.13506075,193.8661377,0,-14.03629709,0,104.2269758 +158.22,50.30534241,-3.211772132,10000,-49.12809761,193.871953,0,-14.03629709,0,104.2199498 +158.23,50.305338,-3.211744961,10000,-49.11417139,193.8779912,0,-14.03629709,0,104.2129239 +158.24,50.30533359,-3.211717788,10000,-49.09328207,193.8840295,0,-14.03629709,0,104.205898 +158.25,50.30532919,-3.211690615,10000,-49.07239276,193.8898448,0,-14.03629709,0,104.1988721 +158.26,50.30532478,-3.211663441,10000,-49.04105881,193.895883,0,-14.03629709,0,104.1918461 +158.27,50.30532038,-3.211636266,10000,-48.99928022,193.9019212,0,-14.03629709,0,104.1848203 +158.28,50.30531599,-3.21160909,10000,-48.9714278,193.9077365,0,-14.03629709,0,104.1777943 +158.29,50.30531159,-3.211581914,10000,-48.96446468,193.9137747,0,-14.03629709,0,104.1707684 +158.3,50.3053072,-3.211554736,10000,-48.95750157,193.9198129,0,-14.03629709,0,104.1637425 +158.31,50.3053028,-3.211527558,10000,-48.92964917,193.9256281,0,-14.03629709,0,104.1567166 +158.32,50.30529841,-3.211500379,10000,-48.88787057,193.9318893,0,-14.03629709,0,104.1496907 +158.33,50.30529403,-3.211473199,10000,-48.85653661,193.9385964,0,-14.03629709,0,104.1426647 +158.34,50.30528964,-3.211446018,10000,-48.8356473,193.9448576,0,-14.03629709,0,104.1356388 +158.35,50.30528526,-3.211418836,10000,-48.81475799,193.9506727,0,-14.03629709,0,104.1286129 +158.36,50.30528088,-3.211391654,10000,-48.79735022,193.9567109,0,-14.03629709,0,104.121587 +158.37,50.3052765,-3.21136447,10000,-48.7764609,193.9625261,0,-14.03629709,0,104.114561 +158.38,50.30527212,-3.211337286,10000,-48.74164539,193.9674493,0,-14.03629709,0,104.1075351 +158.39,50.30526775,-3.211310101,10000,-48.70682989,193.9725956,0,-14.03629709,0,104.1005092 +158.4,50.30526338,-3.211282916,10000,-48.68942213,193.9793026,0,-14.03629709,0,104.0934833 +158.41,50.30525901,-3.211255729,10000,-48.68245901,193.9864556,0,-14.03629709,0,104.0864573 +158.42,50.30525464,-3.211228541,10000,-48.66505125,193.9922708,0,-14.03629709,0,104.0794314 +158.43,50.30525027,-3.211201353,10000,-48.63023576,193.997417,0,-14.03629709,0,104.0724055 +158.44,50.30524591,-3.211174164,10000,-48.59542026,194.0034551,0,-14.03629709,0,104.0653796 +158.45,50.30524155,-3.211146974,10000,-48.57801247,194.0101621,0,-14.03629709,0,104.0583536 +158.46,50.30523719,-3.211119783,10000,-48.57104933,194.0164231,0,-14.03629709,0,104.0513277 +158.47,50.30523283,-3.211092591,10000,-48.55364158,194.0222383,0,-14.03629709,0,104.0443018 +158.48,50.30522847,-3.211065399,10000,-48.51882609,194.0282763,0,-14.03629709,0,104.0372759 +158.49,50.30522412,-3.211038205,10000,-48.48401059,194.0340914,0,-14.03629709,0,104.0302499 +158.5,50.30521977,-3.211011011,10000,-48.46312127,194.0390146,0,-14.03629709,0,104.023224 +158.51,50.30521542,-3.210983816,10000,-48.44223196,194.0441607,0,-14.03629709,0,104.0161981 +158.52,50.30521107,-3.210956621,10000,-48.40741647,194.0508677,0,-14.03629709,0,104.0091722 +158.53,50.30520673,-3.210929424,10000,-48.37260097,194.0580206,0,-14.03629709,0,104.0021462 +158.54,50.30520239,-3.210902226,10000,-48.35519321,194.0638356,0,-14.03629709,0,103.9951203 +158.55,50.30519805,-3.210875028,10000,-48.34823008,194.0689817,0,-14.03629709,0,103.9880944 +158.56,50.30519371,-3.210847829,10000,-48.33082232,194.0747968,0,-14.03629709,0,103.9810685 +158.57,50.30518937,-3.210820629,10000,-48.29600681,194.0808348,0,-14.03629709,0,103.9740425 +158.58,50.30518504,-3.210793428,10000,-48.26119131,194.0866498,0,-14.03629709,0,103.9670166 +158.59,50.30518071,-3.210766227,10000,-48.24378353,194.0926878,0,-14.03629709,0,103.9599907 +158.6,50.30517638,-3.210739024,10000,-48.23682041,194.0987258,0,-14.03629709,0,103.9529648 +158.61,50.30517205,-3.210711821,10000,-48.21941266,194.1045408,0,-14.03629709,0,103.9459388 +158.62,50.30516772,-3.210684617,10000,-48.18459716,194.1105787,0,-14.03629709,0,103.938913 +158.63,50.3051634,-3.210657412,10000,-48.14978166,194.1166167,0,-14.03629709,0,103.931887 +158.64,50.30515908,-3.210630206,10000,-48.12889235,194.1224317,0,-14.03629709,0,103.9248611 +158.65,50.30515476,-3.210603,10000,-48.10800304,194.1284696,0,-14.03629709,0,103.9178352 +158.66,50.30515044,-3.210575792,10000,-48.07666909,194.1345075,0,-14.03629709,0,103.9108093 +158.67,50.30514613,-3.210548584,10000,-48.05229822,194.1403225,0,-14.03629709,0,103.9037833 +158.68,50.30514182,-3.210521375,10000,-48.03837201,194.1463604,0,-14.03629709,0,103.8967574 +158.69,50.3051375,-3.210494165,10000,-48.01400116,194.1523983,0,-14.03629709,0,103.8897315 +158.7,50.3051332,-3.210466954,10000,-47.98266721,194.1579902,0,-14.03629709,0,103.8827056 +158.71,50.30512889,-3.210439743,10000,-47.96525944,194.1633592,0,-14.03629709,0,103.8756797 +158.72,50.30512459,-3.21041253,10000,-47.95481477,194.1691741,0,-14.03629709,0,103.8686537 +158.73,50.30512028,-3.210385318,10000,-47.92696237,194.1758809,0,-14.03629709,0,103.8616278 +158.74,50.30511598,-3.210358103,10000,-47.88518377,194.1821418,0,-14.03629709,0,103.8546019 +158.75,50.30511169,-3.210330888,10000,-47.85384981,194.1866188,0,-14.03629709,0,103.847576 +158.76,50.30510739,-3.210303673,10000,-47.8329605,194.1910958,0,-14.03629709,0,103.84055 +158.77,50.3051031,-3.210276457,10000,-47.8120712,194.1978026,0,-14.03629709,0,103.8335241 +158.78,50.30509881,-3.21024924,10000,-47.79466344,194.2056242,0,-14.03629709,0,103.8264982 +158.79,50.30509452,-3.210222021,10000,-47.77725567,194.2118851,0,-14.03629709,0,103.8194723 +158.8,50.30509023,-3.210194802,10000,-47.75636635,194.216585,0,-14.03629709,0,103.8124463 +158.81,50.30508595,-3.210167583,10000,-47.73895858,194.2217309,0,-14.03629709,0,103.8054204 +158.82,50.30508166,-3.210140362,10000,-47.71806927,194.2275458,0,-14.03629709,0,103.7983945 +158.83,50.30507738,-3.210113141,10000,-47.68325377,194.2333606,0,-14.03629709,0,103.7913686 +158.84,50.3050731,-3.210085919,10000,-47.64843828,194.2396214,0,-14.03629709,0,103.7843426 +158.85,50.30506883,-3.210058696,10000,-47.62754899,194.2463281,0,-14.03629709,0,103.7773167 +158.86,50.30506455,-3.210031472,10000,-47.61014122,194.2523659,0,-14.03629709,0,103.7702908 +158.87,50.30506028,-3.210004247,10000,-47.58577035,194.2575117,0,-14.03629709,0,103.7632649 +158.88,50.30505601,-3.209977022,10000,-47.55443639,194.2631035,0,-14.03629709,0,103.7562389 +158.89,50.30505174,-3.209949796,10000,-47.51962092,194.2693643,0,-14.03629709,0,103.749213 +158.9,50.30504748,-3.209922568,10000,-47.49525007,194.275179,0,-14.03629709,0,103.7421871 +158.91,50.30504322,-3.209895341,10000,-47.48132385,194.2809938,0,-14.03629709,0,103.7351612 +158.92,50.30503895,-3.209868112,10000,-47.46043452,194.2872545,0,-14.03629709,0,103.7281352 +158.93,50.3050347,-3.209840882,10000,-47.4395452,194.2928463,0,-14.03629709,0,103.7211094 +158.94,50.30503044,-3.209813652,10000,-47.425619,194.2977691,0,-14.03629709,0,103.7140834 +158.95,50.30502618,-3.209786421,10000,-47.40124815,194.3029149,0,-14.03629709,0,103.7070575 +158.96,50.30502193,-3.209759189,10000,-47.3699142,194.3087296,0,-14.03629709,0,103.7000316 +158.97,50.30501768,-3.209731957,10000,-47.34902488,194.3156593,0,-14.03629709,0,103.6930057 +158.98,50.30501343,-3.209704723,10000,-47.32813556,194.3228118,0,-14.03629709,0,103.6859797 +158.99,50.30500918,-3.209677488,10000,-47.29332006,194.3284036,0,-14.03629709,0,103.6789538 +159,50.30500494,-3.209650253,10000,-47.25850458,194.3326574,0,-14.03629709,0,103.6719279 +159.01,50.3050007,-3.209623017,10000,-47.23761528,194.3375802,0,-14.03629709,0,103.664902 +159.02,50.30499646,-3.209595781,10000,-47.22020752,194.3442868,0,-14.03629709,0,103.657876 +159.03,50.30499222,-3.209568543,10000,-47.1993182,194.3514393,0,-14.03629709,0,103.6508501 +159.04,50.30498799,-3.209541304,10000,-47.18191044,194.357031,0,-14.03629709,0,103.6438242 +159.05,50.30498375,-3.209514065,10000,-47.16450267,194.3612848,0,-14.03629709,0,103.6367983 +159.06,50.30497952,-3.209486825,10000,-47.14013182,194.3662076,0,-14.03629709,0,103.6297723 +159.07,50.30497529,-3.209459585,10000,-47.10879788,194.3729141,0,-14.03629709,0,103.6227464 +159.08,50.30497106,-3.209432343,10000,-47.07050084,194.3800666,0,-14.03629709,0,103.6157205 +159.09,50.30496684,-3.2094051,10000,-47.03568534,194.3858812,0,-14.03629709,0,103.6086946 +159.1,50.30496262,-3.209377857,10000,-47.01827757,194.3908039,0,-14.03629709,0,103.6016687 +159.11,50.3049584,-3.209350613,10000,-47.01131443,194.3959496,0,-14.03629709,0,103.5946427 +159.12,50.30495418,-3.209323368,10000,-46.99738821,194.4015412,0,-14.03629709,0,103.5876168 +159.13,50.30494996,-3.209296123,10000,-46.97649891,194.4078018,0,-14.03629709,0,103.5805909 +159.14,50.30494575,-3.209268876,10000,-46.95560961,194.4145083,0,-14.03629709,0,103.573565 +159.15,50.30494153,-3.209241629,10000,-46.92427566,194.4205458,0,-14.03629709,0,103.566539 +159.16,50.30493732,-3.20921438,10000,-46.88249707,194.4256915,0,-14.03629709,0,103.5595131 +159.17,50.30493312,-3.209187132,10000,-46.85116312,194.4312831,0,-14.03629709,0,103.5524872 +159.18,50.30492891,-3.209159882,10000,-46.83027381,194.4375436,0,-14.03629709,0,103.5454613 +159.19,50.30492471,-3.209132631,10000,-46.8093845,194.4431351,0,-14.03629709,0,103.5384353 +159.2,50.30492051,-3.20910538,10000,-46.79545829,194.4480578,0,-14.03629709,0,103.5314094 +159.21,50.30491631,-3.209078128,10000,-46.78849518,194.4532034,0,-14.03629709,0,103.5243835 +159.22,50.30491211,-3.209050875,10000,-46.77108742,194.4590179,0,-14.03629709,0,103.5173576 +159.23,50.30490791,-3.209023622,10000,-46.73627192,194.4657243,0,-14.03629709,0,103.5103316 +159.24,50.30490372,-3.208996367,10000,-46.69797487,194.4719848,0,-14.03629709,0,103.5033057 +159.25,50.30489953,-3.208969111,10000,-46.66664092,194.4766844,0,-14.03629709,0,103.4962798 +159.26,50.30489534,-3.208941856,10000,-46.64227006,194.481607,0,-14.03629709,0,103.4892539 +159.27,50.30489116,-3.208914599,10000,-46.6248623,194.4878674,0,-14.03629709,0,103.4822279 +159.28,50.30488697,-3.208887341,10000,-46.60745453,194.4943508,0,-14.03629709,0,103.4752021 +159.29,50.30488279,-3.208860083,10000,-46.58308369,194.5006113,0,-14.03629709,0,103.4681761 +159.3,50.30487861,-3.208832823,10000,-46.5552313,194.5066487,0,-14.03629709,0,103.4611502 +159.31,50.30487443,-3.208805563,10000,-46.53086044,194.5122402,0,-14.03629709,0,103.4541243 +159.32,50.30487026,-3.208778302,10000,-46.51345267,194.5173857,0,-14.03629709,0,103.4470984 +159.33,50.30486608,-3.20875104,10000,-46.49604491,194.5220853,0,-14.03629709,0,103.4400724 +159.34,50.30486191,-3.208723778,10000,-46.47167405,194.5270078,0,-14.03629709,0,103.4330465 +159.35,50.30485774,-3.208696515,10000,-46.4403401,194.5330452,0,-14.03629709,0,103.4260206 +159.36,50.30485357,-3.208669251,10000,-46.40204306,194.5399745,0,-14.03629709,0,103.4189947 +159.37,50.30484941,-3.208641986,10000,-46.36722758,194.5469038,0,-14.03629709,0,103.4119687 +159.38,50.30484525,-3.20861472,10000,-46.34981983,194.5529412,0,-14.03629709,0,103.4049428 +159.39,50.30484109,-3.208587453,10000,-46.34285669,194.5578636,0,-14.03629709,0,103.3979169 +159.4,50.30483693,-3.208560186,10000,-46.32893047,194.5625631,0,-14.03629709,0,103.390891 +159.41,50.30483277,-3.208532918,10000,-46.30804116,194.5677086,0,-14.03629709,0,103.383865 +159.42,50.30482862,-3.208505649,10000,-46.28715186,194.5733,0,-14.03629709,0,103.3768391 +159.43,50.30482446,-3.20847838,10000,-46.25581791,194.5793373,0,-14.03629709,0,103.3698132 +159.44,50.30482031,-3.208451109,10000,-46.21403932,194.5853747,0,-14.03629709,0,103.3627873 +159.45,50.30481617,-3.208423838,10000,-46.18270537,194.590966,0,-14.03629709,0,103.3557613 +159.46,50.30481202,-3.208396566,10000,-46.16181608,194.5961114,0,-14.03629709,0,103.3487354 +159.47,50.30480788,-3.208369293,10000,-46.14092677,194.6010338,0,-14.03629709,0,103.3417095 +159.48,50.30480374,-3.20834202,10000,-46.12700054,194.6068482,0,-14.03629709,0,103.3346836 +159.49,50.3047996,-3.208314746,10000,-46.12003742,194.6140004,0,-14.03629709,0,103.3276576 +159.5,50.30479546,-3.20828747,10000,-46.10262967,194.6207066,0,-14.03629709,0,103.3206317 +159.51,50.30479132,-3.208260194,10000,-46.06781419,194.625629,0,-14.03629709,0,103.3136058 +159.52,50.30478719,-3.208232917,10000,-46.02951715,194.6298824,0,-14.03629709,0,103.3065799 +159.53,50.30478306,-3.20820564,10000,-45.9981832,194.6352508,0,-14.03629709,0,103.299554 +159.54,50.30477893,-3.208178362,10000,-45.97381234,194.641511,0,-14.03629709,0,103.292528 +159.55,50.30477481,-3.208151082,10000,-45.95640458,194.6471023,0,-14.03629709,0,103.2855021 +159.56,50.30477068,-3.208123803,10000,-45.93899682,194.6522476,0,-14.03629709,0,103.2784762 +159.57,50.30476656,-3.208096522,10000,-45.91462596,194.6582848,0,-14.03629709,0,103.2714503 +159.58,50.30476244,-3.208069241,10000,-45.88677356,194.664991,0,-14.03629709,0,103.2644243 +159.59,50.30475832,-3.208041958,10000,-45.8624027,194.6712512,0,-14.03629709,0,103.2573985 +159.6,50.30475421,-3.208014675,10000,-45.84499494,194.6768424,0,-14.03629709,0,103.2503725 +159.61,50.30475009,-3.207987391,10000,-45.82758718,194.6819877,0,-14.03629709,0,103.2433466 +159.62,50.30474598,-3.207960106,10000,-45.80321632,194.6866871,0,-14.03629709,0,103.2363207 +159.63,50.30474187,-3.207932821,10000,-45.77188238,194.6916094,0,-14.03629709,0,103.2292948 +159.64,50.30473776,-3.207905535,10000,-45.73358535,194.6974236,0,-14.03629709,0,103.2222688 +159.65,50.30473366,-3.207878248,10000,-45.69876986,194.7032377,0,-14.03629709,0,103.2152429 +159.66,50.30472956,-3.20785096,10000,-45.68136209,194.70816,0,-14.03629709,0,103.208217 +159.67,50.30472546,-3.207823672,10000,-45.67439897,194.7133053,0,-14.03629709,0,103.2011911 +159.68,50.30472136,-3.207796383,10000,-45.66047277,194.7200113,0,-14.03629709,0,103.1941651 +159.69,50.30471726,-3.207769093,10000,-45.63958346,194.7269404,0,-14.03629709,0,103.1871392 +159.7,50.30471317,-3.207741801,10000,-45.61869415,194.7320856,0,-14.03629709,0,103.1801133 +159.71,50.30470907,-3.20771451,10000,-45.58736021,194.7367849,0,-14.03629709,0,103.1730874 +159.72,50.30470498,-3.207687218,10000,-45.54558162,194.742822,0,-14.03629709,0,103.1660614 +159.73,50.3047009,-3.207659924,10000,-45.51424767,194.7486361,0,-14.03629709,0,103.1590355 +159.74,50.30469681,-3.20763263,10000,-45.49335837,194.7533353,0,-14.03629709,0,103.1520096 +159.75,50.30469273,-3.207605336,10000,-45.47246906,194.7587035,0,-14.03629709,0,103.1449837 +159.76,50.30468865,-3.20757804,10000,-45.45854285,194.7654095,0,-14.03629709,0,103.1379577 +159.77,50.30468457,-3.207550744,10000,-45.45157973,194.7721155,0,-14.03629709,0,103.1309318 +159.78,50.30468049,-3.207523446,10000,-45.43417196,194.7774837,0,-14.03629709,0,103.1239059 +159.79,50.30467641,-3.207496148,10000,-45.39935647,194.7819599,0,-14.03629709,0,103.11688 +159.8,50.30467234,-3.20746885,10000,-45.36454099,194.787105,0,-14.03629709,0,103.109854 +159.81,50.30466827,-3.20744155,10000,-45.34365169,194.7929191,0,-14.03629709,0,103.1028281 +159.82,50.3046642,-3.20741425,10000,-45.32276237,194.7985102,0,-14.03629709,0,103.0958022 +159.83,50.30466013,-3.207386949,10000,-45.28794688,194.8036553,0,-14.03629709,0,103.0887763 +159.84,50.30465607,-3.207359647,10000,-45.2531314,194.8085774,0,-14.03629709,0,103.0817503 +159.85,50.30465201,-3.207332345,10000,-45.23572364,194.8143915,0,-14.03629709,0,103.0747244 +159.86,50.30464795,-3.207305042,10000,-45.22876051,194.8213204,0,-14.03629709,0,103.0676985 +159.87,50.30464389,-3.207277737,10000,-45.21135275,194.8273574,0,-14.03629709,0,103.0606726 +159.88,50.30463983,-3.207250432,10000,-45.17653726,194.8320565,0,-14.03629709,0,103.0536466 +159.89,50.30463578,-3.207223127,10000,-45.14172178,194.8372016,0,-14.03629709,0,103.0466207 +159.9,50.30463173,-3.20719582,10000,-45.12083247,194.8430156,0,-14.03629709,0,103.0395948 +159.91,50.30462768,-3.207168513,10000,-45.09994316,194.8486066,0,-14.03629709,0,103.0325689 +159.92,50.30462363,-3.207141205,10000,-45.06512768,194.8539746,0,-14.03629709,0,103.025543 +159.93,50.30461959,-3.207113896,10000,-45.03031218,194.8595656,0,-14.03629709,0,103.018517 +159.94,50.30461555,-3.207086587,10000,-45.01290441,194.8656025,0,-14.03629709,0,103.0114912 +159.95,50.30461151,-3.207059276,10000,-45.00594129,194.8714165,0,-14.03629709,0,103.0044652 +159.96,50.30460747,-3.207031965,10000,-44.99201509,194.8761156,0,-14.03629709,0,102.9974393 +159.97,50.30460343,-3.207004653,10000,-44.97112579,194.8801457,0,-14.03629709,0,102.9904134 +159.98,50.3045994,-3.206977341,10000,-44.95023648,194.8850677,0,-14.03629709,0,102.9833875 +159.99,50.30459536,-3.206950028,10000,-44.91890254,194.8917735,0,-14.03629709,0,102.9763615 +160,50.30459133,-3.206922714,10000,-44.87712395,194.8989253,0,-14.03629709,0,102.9693356 +160.01,50.30458731,-3.206895398,10000,-44.84579002,194.9047392,0,-14.03629709,0,102.9623097 +160.02,50.30458328,-3.206868083,10000,-44.82490072,194.9096612,0,-14.03629709,0,102.9552838 +160.03,50.30457926,-3.206840766,10000,-44.80401141,194.9148062,0,-14.03629709,0,102.9482578 +160.04,50.30457524,-3.206813449,10000,-44.79008519,194.9201741,0,-14.03629709,0,102.9412319 +160.05,50.30457122,-3.206786131,10000,-44.78312206,194.9253191,0,-14.03629709,0,102.934206 +160.06,50.3045672,-3.206758812,10000,-44.7657143,194.930018,0,-14.03629709,0,102.9271801 +160.07,50.30456318,-3.206731493,10000,-44.73089882,194.93494,0,-14.03629709,0,102.9201541 +160.08,50.30455917,-3.206704173,10000,-44.69260179,194.9409768,0,-14.03629709,0,102.9131282 +160.09,50.30455516,-3.206676852,10000,-44.66126784,194.9476826,0,-14.03629709,0,102.9061023 +160.1,50.30455115,-3.20664953,10000,-44.63689699,194.9539424,0,-14.03629709,0,102.8990764 +160.11,50.30454715,-3.206622207,10000,-44.61948923,194.9595332,0,-14.03629709,0,102.8920504 +160.12,50.30454314,-3.206594884,10000,-44.60208146,194.9646781,0,-14.03629709,0,102.8850245 +160.13,50.30453914,-3.206567559,10000,-44.57771062,194.9693771,0,-14.03629709,0,102.8779986 +160.14,50.30453514,-3.206540235,10000,-44.54985823,194.974076,0,-14.03629709,0,102.8709727 +160.15,50.30453114,-3.206512909,10000,-44.52548739,194.9794438,0,-14.03629709,0,102.8639467 +160.16,50.30452715,-3.206485583,10000,-44.50807963,194.9857036,0,-14.03629709,0,102.8569208 +160.17,50.30452315,-3.206458256,10000,-44.49067186,194.9921863,0,-14.03629709,0,102.8498949 +160.18,50.30451916,-3.206430927,10000,-44.466301,194.9977771,0,-14.03629709,0,102.842869 +160.19,50.30451517,-3.206403599,10000,-44.43496705,195.002699,0,-14.03629709,0,102.835843 +160.2,50.30451118,-3.206376269,10000,-44.39667003,195.0078438,0,-14.03629709,0,102.8288171 +160.21,50.3045072,-3.206348939,10000,-44.36185456,195.0132116,0,-14.03629709,0,102.8217912 +160.22,50.30450322,-3.206321608,10000,-44.3444468,195.0183564,0,-14.03629709,0,102.8147653 +160.23,50.30449924,-3.206294276,10000,-44.33748366,195.0230552,0,-14.03629709,0,102.8077393 +160.24,50.30449526,-3.206266944,10000,-44.32355745,195.027977,0,-14.03629709,0,102.8007134 +160.25,50.30449128,-3.206239611,10000,-44.30266815,195.0340137,0,-14.03629709,0,102.7936875 +160.26,50.30448731,-3.206212277,10000,-44.28177886,195.0407194,0,-14.03629709,0,102.7866616 +160.27,50.30448333,-3.206184942,10000,-44.25044491,195.0467561,0,-14.03629709,0,102.7796356 +160.28,50.30447936,-3.206157606,10000,-44.20866631,195.0514549,0,-14.03629709,0,102.7726097 +160.29,50.3044754,-3.20613027,10000,-44.17733238,195.0554847,0,-14.03629709,0,102.7655838 +160.3,50.30447143,-3.206102933,10000,-44.15644309,195.0601835,0,-14.03629709,0,102.7585579 +160.31,50.30446747,-3.206075596,10000,-44.13555379,195.0662202,0,-14.03629709,0,102.751532 +160.32,50.30446351,-3.206048257,10000,-44.11814601,195.0731487,0,-14.03629709,0,102.7445061 +160.33,50.30445955,-3.206020918,10000,-44.10073824,195.0798543,0,-14.03629709,0,102.7374802 +160.34,50.30445559,-3.205993577,10000,-44.07984894,195.084999,0,-14.03629709,0,102.7304542 +160.35,50.30445164,-3.205966236,10000,-44.06244119,195.0888059,0,-14.03629709,0,102.7234283 +160.36,50.30444768,-3.205938895,10000,-44.0415519,195.0937276,0,-14.03629709,0,102.7164024 +160.37,50.30444373,-3.205911553,10000,-44.00673642,195.1004331,0,-14.03629709,0,102.7093765 +160.38,50.30443978,-3.205884209,10000,-43.97192095,195.1064697,0,-14.03629709,0,102.7023505 +160.39,50.30443584,-3.205856865,10000,-43.95103165,195.1111685,0,-14.03629709,0,102.6953246 +160.4,50.30443189,-3.205829521,10000,-43.93362387,195.1160901,0,-14.03629709,0,102.6882987 +160.41,50.30442795,-3.205802175,10000,-43.909253,195.1210118,0,-14.03629709,0,102.6812728 +160.42,50.30442401,-3.205774829,10000,-43.87791906,195.1254875,0,-14.03629709,0,102.6742468 +160.43,50.30442007,-3.205747483,10000,-43.84310358,195.1306322,0,-14.03629709,0,102.6672209 +160.44,50.30441614,-3.205720135,10000,-43.82221428,195.1364457,0,-14.03629709,0,102.660195 +160.45,50.30441221,-3.205692787,10000,-43.81873271,195.1422593,0,-14.03629709,0,102.6531691 +160.46,50.30440827,-3.205665438,10000,-43.80132496,195.1482959,0,-14.03629709,0,102.6461431 +160.47,50.30440434,-3.205638088,10000,-43.76302792,195.1541094,0,-14.03629709,0,102.6391172 +160.48,50.30440042,-3.205610737,10000,-43.73169397,195.159031,0,-14.03629709,0,102.6320913 +160.49,50.30439649,-3.205583386,10000,-43.71080467,195.1639526,0,-14.03629709,0,102.6250654 +160.5,50.30439257,-3.205556034,10000,-43.68643383,195.1697662,0,-14.03629709,0,102.6180394 +160.51,50.30438865,-3.205528681,10000,-43.65858143,195.1755797,0,-14.03629709,0,102.6110135 +160.52,50.30438473,-3.205501327,10000,-43.63421059,195.1805013,0,-14.03629709,0,102.6039876 +160.53,50.30438082,-3.205473973,10000,-43.61680284,195.1851999,0,-14.03629709,0,102.5969617 +160.54,50.3043769,-3.205446618,10000,-43.59939509,195.1903444,0,-14.03629709,0,102.5899357 +160.55,50.30437299,-3.205419262,10000,-43.57502423,195.195935,0,-14.03629709,0,102.5829098 +160.56,50.30436908,-3.205391906,10000,-43.54717183,195.2019714,0,-14.03629709,0,102.5758839 +160.57,50.30436517,-3.205364548,10000,-43.52280098,195.2077849,0,-14.03629709,0,102.568858 +160.58,50.30436127,-3.20533719,10000,-43.50539322,195.2127064,0,-14.03629709,0,102.561832 +160.59,50.30435736,-3.205309831,10000,-43.48450392,195.217628,0,-14.03629709,0,102.5548061 +160.6,50.30435346,-3.205282472,10000,-43.44968844,195.2232184,0,-14.03629709,0,102.5477802 +160.61,50.30434956,-3.205255111,10000,-43.41487296,195.2283629,0,-14.03629709,0,102.5407543 +160.62,50.30434567,-3.20522775,10000,-43.39398365,195.2328385,0,-14.03629709,0,102.5337283 +160.63,50.30434177,-3.205200389,10000,-43.37657588,195.237983,0,-14.03629709,0,102.5267025 +160.64,50.30433788,-3.205173026,10000,-43.35568657,195.2437964,0,-14.03629709,0,102.5196765 +160.65,50.30433399,-3.205145663,10000,-43.33827883,195.2496098,0,-14.03629709,0,102.5126506 +160.66,50.3043301,-3.205118299,10000,-43.31738954,195.2556462,0,-14.03629709,0,102.5056247 +160.67,50.30432621,-3.205090934,10000,-43.28257406,195.2614596,0,-14.03629709,0,102.4985988 +160.68,50.30432233,-3.205063568,10000,-43.24775856,195.266381,0,-14.03629709,0,102.4915728 +160.69,50.30431845,-3.205036202,10000,-43.22686925,195.2710795,0,-14.03629709,0,102.4845469 +160.7,50.30431457,-3.205008835,10000,-43.20946149,195.276001,0,-14.03629709,0,102.477521 +160.71,50.30431069,-3.204981467,10000,-43.1885722,195.2806994,0,-14.03629709,0,102.4704951 +160.72,50.30430682,-3.204954099,10000,-43.17116446,195.2856209,0,-14.03629709,0,102.4634692 +160.73,50.30430294,-3.20492673,10000,-43.15027516,195.2916572,0,-14.03629709,0,102.4564432 +160.74,50.30429907,-3.20489936,10000,-43.11545966,195.2981395,0,-14.03629709,0,102.4494173 +160.75,50.3042952,-3.204871989,10000,-43.08064417,195.3032839,0,-14.03629709,0,102.4423914 +160.76,50.30429134,-3.204844617,10000,-43.05975488,195.3070904,0,-14.03629709,0,102.4353655 +160.77,50.30428747,-3.204817246,10000,-43.04234712,195.3117888,0,-14.03629709,0,102.4283395 +160.78,50.30428361,-3.204789873,10000,-43.02145781,195.318048,0,-14.03629709,0,102.4213136 +160.79,50.30427975,-3.204762499,10000,-43.00405005,195.3245303,0,-14.03629709,0,102.4142877 +160.8,50.30427589,-3.204735125,10000,-42.98316075,195.3305665,0,-14.03629709,0,102.4072618 +160.81,50.30427203,-3.204707749,10000,-42.94834528,195.3357109,0,-14.03629709,0,102.4002358 +160.82,50.30426818,-3.204680373,10000,-42.91352979,195.3399633,0,-14.03629709,0,102.3932099 +160.83,50.30426433,-3.204652997,10000,-42.89264049,195.3442157,0,-14.03629709,0,102.386184 +160.84,50.30426048,-3.204625619,10000,-42.87523273,195.3489141,0,-14.03629709,0,102.3791581 +160.85,50.30425663,-3.204598242,10000,-42.85434343,195.3545043,0,-14.03629709,0,102.3721321 +160.86,50.30425279,-3.204570863,10000,-42.83693567,195.3607635,0,-14.03629709,0,102.3651062 +160.87,50.30424894,-3.204543483,10000,-42.81604638,195.3663538,0,-14.03629709,0,102.3580803 +160.88,50.3042451,-3.204516103,10000,-42.7812309,195.3712751,0,-14.03629709,0,102.3510544 +160.89,50.30424126,-3.204488722,10000,-42.74641542,195.3761964,0,-14.03629709,0,102.3440284 +160.9,50.30423743,-3.20446134,10000,-42.72552611,195.3808947,0,-14.03629709,0,102.3370025 +160.91,50.30423359,-3.204433958,10000,-42.70811836,195.385816,0,-14.03629709,0,102.3299766 +160.92,50.30422976,-3.204406575,10000,-42.68374751,195.3916292,0,-14.03629709,0,102.3229507 +160.93,50.30422593,-3.204379191,10000,-42.65589512,195.3976653,0,-14.03629709,0,102.3159247 +160.94,50.3042221,-3.204351806,10000,-42.63152425,195.4034785,0,-14.03629709,0,102.3088988 +160.95,50.30421828,-3.204324421,10000,-42.61411648,195.4092917,0,-14.03629709,0,102.3018729 +160.96,50.30421445,-3.204297034,10000,-42.59670874,195.4142129,0,-14.03629709,0,102.294847 +160.97,50.30421063,-3.204269647,10000,-42.57233792,195.4180193,0,-14.03629709,0,102.287821 +160.98,50.30420681,-3.20424226,10000,-42.54100399,195.4227175,0,-14.03629709,0,102.2807952 +160.99,50.30420299,-3.204214872,10000,-42.5061885,195.4285307,0,-14.03629709,0,102.2737692 +161,50.30419918,-3.204187482,10000,-42.48181765,195.4334519,0,-14.03629709,0,102.2667433 +161.01,50.30419537,-3.204160093,10000,-42.46789144,195.4381501,0,-14.03629709,0,102.2597174 +161.02,50.30419155,-3.204132703,10000,-42.44700213,195.4441862,0,-14.03629709,0,102.2526915 +161.03,50.30418775,-3.204105311,10000,-42.42611283,195.4497763,0,-14.03629709,0,102.2456655 +161.04,50.30418394,-3.204077919,10000,-42.41218662,195.4538056,0,-14.03629709,0,102.2386396 +161.05,50.30418013,-3.204050527,10000,-42.38781577,195.4587267,0,-14.03629709,0,102.2316137 +161.06,50.30417633,-3.204023134,10000,-42.35300028,195.4656547,0,-14.03629709,0,102.2245878 +161.07,50.30417253,-3.203995739,10000,-42.32166634,195.4723597,0,-14.03629709,0,102.2175618 +161.08,50.30416873,-3.203968344,10000,-42.29729551,195.4772809,0,-14.03629709,0,102.2105359 +161.09,50.30416494,-3.203940948,10000,-42.27988776,195.4810871,0,-14.03629709,0,102.20351 +161.1,50.30416114,-3.203913552,10000,-42.25899845,195.4848933,0,-14.03629709,0,102.1964841 +161.11,50.30415735,-3.203886155,10000,-42.22418296,195.4895915,0,-14.03629709,0,102.1894582 +161.12,50.30415356,-3.203858758,10000,-42.18936749,195.4954045,0,-14.03629709,0,102.1824322 +161.13,50.30414978,-3.203831359,10000,-42.1684782,195.5014405,0,-14.03629709,0,102.1754063 +161.14,50.30414599,-3.20380396,10000,-42.15107044,195.5070305,0,-14.03629709,0,102.1683804 +161.15,50.30414221,-3.20377656,10000,-42.13018113,195.5121746,0,-14.03629709,0,102.1613545 +161.16,50.30413843,-3.203749159,10000,-42.11277338,195.5168727,0,-14.03629709,0,102.1543285 +161.17,50.30413465,-3.203721758,10000,-42.09188409,195.5215708,0,-14.03629709,0,102.1473026 +161.18,50.30413087,-3.203694356,10000,-42.05706861,195.5264919,0,-14.03629709,0,102.1402767 +161.19,50.3041271,-3.203666953,10000,-42.02225312,195.5311899,0,-14.03629709,0,102.1332508 +161.2,50.30412333,-3.20363955,10000,-42.00484538,195.536111,0,-14.03629709,0,102.1262248 +161.21,50.30411956,-3.203612146,10000,-41.99788227,195.541924,0,-14.03629709,0,102.1191989 +161.22,50.30411579,-3.203584741,10000,-41.9804745,195.5479599,0,-14.03629709,0,102.112173 +161.23,50.30411202,-3.203557335,10000,-41.945659,195.5535499,0,-14.03629709,0,102.1051471 +161.24,50.30410826,-3.203529929,10000,-41.91084351,195.5586939,0,-14.03629709,0,102.0981211 +161.25,50.3041045,-3.203502521,10000,-41.88995423,195.5633919,0,-14.03629709,0,102.0910952 +161.26,50.30410074,-3.203475114,10000,-41.87254648,195.5680899,0,-14.03629709,0,102.0840693 +161.27,50.30409698,-3.203447705,10000,-41.85165718,195.5732339,0,-14.03629709,0,102.0770434 +161.28,50.30409323,-3.203420296,10000,-41.83076787,195.5786008,0,-14.03629709,0,102.0700174 +161.29,50.30408947,-3.203392886,10000,-41.79943393,195.5839678,0,-14.03629709,0,102.0629916 +161.3,50.30408572,-3.203365475,10000,-41.76113691,195.5893347,0,-14.03629709,0,102.0559656 +161.31,50.30408198,-3.203338064,10000,-41.74372917,195.5944787,0,-14.03629709,0,102.0489397 +161.32,50.30407823,-3.203310651,10000,-41.74024759,195.5991766,0,-14.03629709,0,102.0419138 +161.33,50.30407448,-3.203283239,10000,-41.71935828,195.6038746,0,-14.03629709,0,102.0348879 +161.34,50.30407074,-3.203255825,10000,-41.6845428,195.6090185,0,-14.03629709,0,102.0278619 +161.35,50.304067,-3.203228411,10000,-41.64972732,195.6143854,0,-14.03629709,0,102.020836 +161.36,50.30406326,-3.203200996,10000,-41.61491184,195.6195293,0,-14.03629709,0,102.0138101 +161.37,50.30405953,-3.20317358,10000,-41.59054101,195.6242272,0,-14.03629709,0,102.0067842 +161.38,50.3040558,-3.203146164,10000,-41.57661481,195.6291481,0,-14.03629709,0,101.9997582 +161.39,50.30405206,-3.203118747,10000,-41.5557255,195.634961,0,-14.03629709,0,101.9927323 +161.4,50.30404834,-3.203091329,10000,-41.5348362,195.6407738,0,-14.03629709,0,101.9857064 +161.41,50.30404461,-3.20306391,10000,-41.52090999,195.6456946,0,-14.03629709,0,101.9786805 +161.42,50.30404088,-3.203036491,10000,-41.49653915,195.6503925,0,-14.03629709,0,101.9716545 +161.43,50.30403716,-3.203009071,10000,-41.46172367,195.6553134,0,-14.03629709,0,101.9646286 +161.44,50.30403344,-3.20298165,10000,-41.43038973,195.6600113,0,-14.03629709,0,101.9576027 +161.45,50.30402972,-3.202954229,10000,-41.40601888,195.6649321,0,-14.03629709,0,101.9505768 +161.46,50.30402601,-3.202926807,10000,-41.38861114,195.6707449,0,-14.03629709,0,101.9435508 +161.47,50.30402229,-3.202899384,10000,-41.37120338,195.6765577,0,-14.03629709,0,101.9365249 +161.48,50.30401858,-3.20287196,10000,-41.34683252,195.6812555,0,-14.03629709,0,101.929499 +161.49,50.30401487,-3.202844536,10000,-41.31898013,195.6850614,0,-14.03629709,0,101.9224731 +161.5,50.30401116,-3.202817111,10000,-41.2946093,195.6890903,0,-14.03629709,0,101.9154471 +161.51,50.30400746,-3.202789686,10000,-41.27720156,195.6944571,0,-14.03629709,0,101.9084212 +161.52,50.30400375,-3.20276226,10000,-41.25631227,195.7007157,0,-14.03629709,0,101.9013953 +161.53,50.30400005,-3.202734832,10000,-41.22149678,195.7063055,0,-14.03629709,0,101.8943694 +161.54,50.30399635,-3.202707405,10000,-41.18668129,195.7112262,0,-14.03629709,0,101.8873435 +161.55,50.30399266,-3.202679976,10000,-41.16579199,195.716147,0,-14.03629709,0,101.8803175 +161.56,50.30398896,-3.202652547,10000,-41.14838424,195.7208448,0,-14.03629709,0,101.8732916 +161.57,50.30398527,-3.202625117,10000,-41.1240134,195.7257655,0,-14.03629709,0,101.8662657 +161.58,50.30398158,-3.202597687,10000,-41.096161,195.7315782,0,-14.03629709,0,101.8592398 +161.59,50.30397789,-3.202570255,10000,-41.07179016,195.7373909,0,-14.03629709,0,101.8522138 +161.6,50.30397421,-3.202542823,10000,-41.05438241,195.7420886,0,-14.03629709,0,101.8451879 +161.61,50.30397052,-3.20251539,10000,-41.03697465,195.7458944,0,-14.03629709,0,101.838162 +161.62,50.30396684,-3.202487957,10000,-41.0126038,195.7497002,0,-14.03629709,0,101.8311361 +161.63,50.30396316,-3.202460523,10000,-40.98126988,195.7546209,0,-14.03629709,0,101.8241101 +161.64,50.30395948,-3.202433089,10000,-40.9464544,195.7611025,0,-14.03629709,0,101.8170843 +161.65,50.30395581,-3.202405653,10000,-40.92208356,195.7673611,0,-14.03629709,0,101.8100583 +161.66,50.30395214,-3.202378216,10000,-40.90815736,195.7718358,0,-14.03629709,0,101.8030324 +161.67,50.30394846,-3.20235078,10000,-40.88726806,195.7758645,0,-14.03629709,0,101.7960065 +161.68,50.3039448,-3.202323342,10000,-40.86637875,195.7807852,0,-14.03629709,0,101.7889806 +161.69,50.30394113,-3.202295904,10000,-40.85245254,195.7861518,0,-14.03629709,0,101.7819546 +161.7,50.30393746,-3.202268465,10000,-40.8280817,195.7912954,0,-14.03629709,0,101.7749287 +161.71,50.3039338,-3.202241025,10000,-40.79326623,195.7959931,0,-14.03629709,0,101.7679028 +161.72,50.30393014,-3.202213585,10000,-40.76193229,195.8006907,0,-14.03629709,0,101.7608769 +161.73,50.30392648,-3.202186144,10000,-40.73756145,195.8058343,0,-14.03629709,0,101.7538509 +161.74,50.30392283,-3.202158702,10000,-40.7201537,195.8114239,0,-14.03629709,0,101.746825 +161.75,50.30391917,-3.20213126,10000,-40.69926441,195.8172364,0,-14.03629709,0,101.7397991 +161.76,50.30391552,-3.202103816,10000,-40.66444893,195.822157,0,-14.03629709,0,101.7327732 +161.77,50.30391187,-3.202076372,10000,-40.62963344,195.8259627,0,-14.03629709,0,101.7257472 +161.78,50.30390823,-3.202048928,10000,-40.60874413,195.8306603,0,-14.03629709,0,101.7187213 +161.79,50.30390458,-3.202021483,10000,-40.59133638,195.8366958,0,-14.03629709,0,101.7116954 +161.8,50.30390094,-3.201994036,10000,-40.57044709,195.8422853,0,-14.03629709,0,101.7046695 +161.81,50.3038973,-3.20196659,10000,-40.55303935,195.8472059,0,-14.03629709,0,101.6976435 +161.82,50.30389366,-3.201939142,10000,-40.53215006,195.8521264,0,-14.03629709,0,101.6906176 +161.83,50.30389002,-3.201911694,10000,-40.49733458,195.856601,0,-14.03629709,0,101.6835917 +161.84,50.30388639,-3.201884245,10000,-40.4625191,195.8606296,0,-14.03629709,0,101.6765658 +161.85,50.30388276,-3.201856796,10000,-40.44511135,195.8651041,0,-14.03629709,0,101.6695398 +161.86,50.30387913,-3.201829346,10000,-40.43814823,195.8700247,0,-14.03629709,0,101.6625139 +161.87,50.3038755,-3.201801895,10000,-40.42074047,195.8749452,0,-14.03629709,0,101.655488 +161.88,50.30387187,-3.201774444,10000,-40.38592499,195.8805346,0,-14.03629709,0,101.6484621 +161.89,50.30386825,-3.201746992,10000,-40.35110952,195.88657,0,-14.03629709,0,101.6414361 +161.9,50.30386463,-3.201719538,10000,-40.33022023,195.8912675,0,-14.03629709,0,101.6344102 +161.91,50.30386101,-3.201692085,10000,-40.31281248,195.8950731,0,-14.03629709,0,101.6273843 +161.92,50.30385739,-3.201664631,10000,-40.29192317,195.9002165,0,-14.03629709,0,101.6203584 +161.93,50.30385378,-3.201637176,10000,-40.27103386,195.9064749,0,-14.03629709,0,101.6133325 +161.94,50.30385016,-3.20160972,10000,-40.23969992,195.9116183,0,-14.03629709,0,101.6063065 +161.95,50.30384655,-3.201582263,10000,-40.19792136,195.9154239,0,-14.03629709,0,101.5992806 +161.96,50.30384295,-3.201554807,10000,-40.17006899,195.9201213,0,-14.03629709,0,101.5922547 +161.97,50.30383934,-3.201527349,10000,-40.16310588,195.9261566,0,-14.03629709,0,101.5852288 +161.98,50.30383574,-3.20149989,10000,-40.15614276,195.931523,0,-14.03629709,0,101.5782029 +161.99,50.30383213,-3.201472431,10000,-40.12829037,195.9355515,0,-14.03629709,0,101.571177 +162,50.30382853,-3.201444971,10000,-40.0865118,195.939357,0,-14.03629709,0,101.564151 +162.01,50.30382494,-3.201417511,10000,-40.05517786,195.9438314,0,-14.03629709,0,101.5571251 +162.02,50.30382134,-3.20139005,10000,-40.03428856,195.9489748,0,-14.03629709,0,101.5500992 +162.03,50.30381775,-3.201362588,10000,-40.01339927,195.9545641,0,-14.03629709,0,101.5430733 +162.04,50.30381416,-3.201335126,10000,-39.99599154,195.9603764,0,-14.03629709,0,101.5360473 +162.05,50.30381057,-3.201307662,10000,-39.9785838,195.9655198,0,-14.03629709,0,101.5290214 +162.06,50.30380698,-3.201280198,10000,-39.95769449,195.9699942,0,-14.03629709,0,101.5219955 +162.07,50.3038034,-3.201252734,10000,-39.94028672,195.9749145,0,-14.03629709,0,101.5149696 +162.08,50.30379981,-3.201225268,10000,-39.91939742,195.9798349,0,-14.03629709,0,101.5079436 +162.09,50.30379623,-3.201197802,10000,-39.88458196,195.9843092,0,-14.03629709,0,101.5009177 +162.1,50.30379265,-3.201170336,10000,-39.8497665,195.9894525,0,-14.03629709,0,101.4938918 +162.11,50.30378908,-3.201142868,10000,-39.8288772,195.9950418,0,-14.03629709,0,101.4868659 +162.12,50.3037855,-3.2011154,10000,-39.80798788,195.9997391,0,-14.03629709,0,101.4798399 +162.13,50.30378193,-3.201087931,10000,-39.7731724,196.0037675,0,-14.03629709,0,101.472814 +162.14,50.30377836,-3.201060462,10000,-39.73835693,196.0082418,0,-14.03629709,0,101.4657881 +162.15,50.3037748,-3.201032992,10000,-39.71746764,196.0131621,0,-14.03629709,0,101.4587622 +162.16,50.30377123,-3.201005521,10000,-39.70005988,196.0178594,0,-14.03629709,0,101.4517362 +162.17,50.30376767,-3.20097805,10000,-39.67917059,196.0225566,0,-14.03629709,0,101.4447103 +162.18,50.30376411,-3.200950578,10000,-39.66176285,196.0276999,0,-14.03629709,0,101.4376844 +162.19,50.30376055,-3.200923105,10000,-39.6443551,196.0330661,0,-14.03629709,0,101.4306585 +162.2,50.30375699,-3.200895632,10000,-39.6234658,196.0382093,0,-14.03629709,0,101.4236325 +162.21,50.30375344,-3.200868157,10000,-39.6025765,196.0429066,0,-14.03629709,0,101.4166066 +162.22,50.30374988,-3.200840683,10000,-39.57124256,196.0476038,0,-14.03629709,0,101.4095807 +162.23,50.30374633,-3.200813207,10000,-39.529464,196.052524,0,-14.03629709,0,101.4025548 +162.24,50.30374279,-3.200785731,10000,-39.50161162,196.0569983,0,-14.03629709,0,101.3955288 +162.25,50.30373924,-3.200758254,10000,-39.49464851,196.0610265,0,-14.03629709,0,101.3885029 +162.26,50.3037357,-3.200730777,10000,-39.48768538,196.0657237,0,-14.03629709,0,101.381477 +162.27,50.30373215,-3.200703299,10000,-39.459833,196.0715359,0,-14.03629709,0,101.3744511 +162.28,50.30372861,-3.20067582,10000,-39.41805445,196.077348,0,-14.03629709,0,101.3674251 +162.29,50.30372508,-3.20064834,10000,-39.38672052,196.0820452,0,-14.03629709,0,101.3603992 +162.3,50.30372154,-3.20062086,10000,-39.36583123,196.0860734,0,-14.03629709,0,101.3533733 +162.31,50.30371801,-3.200593379,10000,-39.34494192,196.0907706,0,-14.03629709,0,101.3463474 +162.32,50.30371448,-3.200565898,10000,-39.32753415,196.0965826,0,-14.03629709,0,101.3393215 +162.33,50.30371095,-3.200538415,10000,-39.30664485,196.1023947,0,-14.03629709,0,101.3322956 +162.34,50.30370742,-3.200510932,10000,-39.27182938,196.1070918,0,-14.03629709,0,101.3252697 +162.35,50.3037039,-3.200483448,10000,-39.23701392,196.11112,0,-14.03629709,0,101.3182437 +162.36,50.30370038,-3.200455964,10000,-39.21960617,196.1153712,0,-14.03629709,0,101.3112178 +162.37,50.30369686,-3.200428479,10000,-39.21264306,196.1196223,0,-14.03629709,0,101.3041919 +162.38,50.30369334,-3.200400993,10000,-39.19523531,196.1238735,0,-14.03629709,0,101.297166 +162.39,50.30368982,-3.200373508,10000,-39.16041984,196.1287936,0,-14.03629709,0,101.29014 +162.4,50.30368631,-3.20034602,10000,-39.12560437,196.1337136,0,-14.03629709,0,101.2831141 +162.41,50.3036828,-3.200318533,10000,-39.10471507,196.1381877,0,-14.03629709,0,101.2760882 +162.42,50.30367929,-3.200291045,10000,-39.08382577,196.1433308,0,-14.03629709,0,101.2690623 +162.43,50.30367578,-3.200263556,10000,-39.04901028,196.1489198,0,-14.03629709,0,101.2620363 +162.44,50.30367228,-3.200236066,10000,-39.01419482,196.1538398,0,-14.03629709,0,101.2550104 +162.45,50.30366878,-3.200208576,10000,-38.99678708,196.1585369,0,-14.03629709,0,101.2479845 +162.46,50.30366528,-3.200181085,10000,-38.98982396,196.1634569,0,-14.03629709,0,101.2409586 +162.47,50.30366178,-3.200153593,10000,-38.97589774,196.1681539,0,-14.03629709,0,101.2339326 +162.48,50.30365828,-3.200126101,10000,-38.95500844,196.172851,0,-14.03629709,0,101.2269067 +162.49,50.30365479,-3.200098608,10000,-38.93411917,196.177771,0,-14.03629709,0,101.2198808 +162.5,50.30365129,-3.200071114,10000,-38.90278525,196.182468,0,-14.03629709,0,101.2128549 +162.51,50.3036478,-3.20004362,10000,-38.86100667,196.187165,0,-14.03629709,0,101.2058289 +162.52,50.30364432,-3.200016125,10000,-38.82967274,196.192085,0,-14.03629709,0,101.198803 +162.53,50.30364083,-3.199988629,10000,-38.80878344,196.196782,0,-14.03629709,0,101.1917771 +162.54,50.30363735,-3.199961133,10000,-38.78789414,196.2014789,0,-14.03629709,0,101.1847512 +162.55,50.30363387,-3.199933636,10000,-38.7704864,196.2063989,0,-14.03629709,0,101.1777252 +162.56,50.30363039,-3.199906138,10000,-38.75307865,196.2110959,0,-14.03629709,0,101.1706993 +162.57,50.30362691,-3.19987864,10000,-38.73218935,196.2157928,0,-14.03629709,0,101.1636734 +162.58,50.30362344,-3.199851141,10000,-38.71130006,196.2207128,0,-14.03629709,0,101.1566475 +162.59,50.30361996,-3.199823641,10000,-38.67996614,196.2251867,0,-14.03629709,0,101.1496215 +162.6,50.30361649,-3.199796141,10000,-38.63818758,196.2292147,0,-14.03629709,0,101.1425956 +162.61,50.30361303,-3.19976864,10000,-38.60685364,196.2336886,0,-14.03629709,0,101.1355697 +162.62,50.30360956,-3.199741139,10000,-38.58596434,196.2386085,0,-14.03629709,0,101.1285438 +162.63,50.3036061,-3.199713636,10000,-38.56507506,196.2433054,0,-14.03629709,0,101.1215178 +162.64,50.30360264,-3.199686134,10000,-38.55114886,196.2480023,0,-14.03629709,0,101.1144919 +162.65,50.30359918,-3.19965863,10000,-38.54418574,196.2531452,0,-14.03629709,0,101.107466 +162.66,50.30359572,-3.199631126,10000,-38.52677798,196.258511,0,-14.03629709,0,101.1004401 +162.67,50.30359226,-3.199603621,10000,-38.49196251,196.2636539,0,-14.03629709,0,101.0934142 +162.68,50.30358881,-3.199576115,10000,-38.45714705,196.2683507,0,-14.03629709,0,101.0863883 +162.69,50.30358536,-3.199548609,10000,-38.43625777,196.2730476,0,-14.03629709,0,101.0793623 +162.7,50.30358191,-3.199521102,10000,-38.41536846,196.2779674,0,-14.03629709,0,101.0723364 +162.71,50.30357846,-3.199493594,10000,-38.38055297,196.2824413,0,-14.03629709,0,101.0653105 +162.72,50.30357502,-3.199466086,10000,-38.34573748,196.2864691,0,-14.03629709,0,101.0582846 +162.73,50.30357158,-3.199438577,10000,-38.32832974,196.290943,0,-14.03629709,0,101.0512587 +162.74,50.30356814,-3.199411068,10000,-38.32136664,196.2958628,0,-14.03629709,0,101.0442327 +162.75,50.3035647,-3.199383557,10000,-38.30395891,196.3005596,0,-14.03629709,0,101.0372068 +162.76,50.30356126,-3.199356047,10000,-38.26914343,196.3052564,0,-14.03629709,0,101.0301809 +162.77,50.30355783,-3.199328535,10000,-38.23432796,196.3103991,0,-14.03629709,0,101.023155 +162.78,50.3035544,-3.199301023,10000,-38.21343867,196.3157649,0,-14.03629709,0,101.016129 +162.79,50.30355097,-3.19927351,10000,-38.19254939,196.3206846,0,-14.03629709,0,101.0091031 +162.8,50.30354754,-3.199245996,10000,-38.16121545,196.3244895,0,-14.03629709,0,101.0020772 +162.81,50.30354412,-3.199218482,10000,-38.1368446,196.3280713,0,-14.03629709,0,100.9950513 +162.82,50.3035407,-3.199190968,10000,-38.12291839,196.3327681,0,-14.03629709,0,100.9880253 +162.83,50.30353727,-3.199163452,10000,-38.09854755,196.3376878,0,-14.03629709,0,100.9809994 +162.84,50.30353386,-3.199135936,10000,-38.06721363,196.3421615,0,-14.03629709,0,100.9739735 +162.85,50.30353044,-3.19910842,10000,-38.04980589,196.3470812,0,-14.03629709,0,100.9669476 +162.86,50.30352703,-3.199080902,10000,-38.03936123,196.3520009,0,-14.03629709,0,100.9599216 +162.87,50.30352361,-3.199053384,10000,-38.01150884,196.3564747,0,-14.03629709,0,100.9528957 +162.88,50.3035202,-3.199025866,10000,-37.96973028,196.3613944,0,-14.03629709,0,100.9458698 +162.89,50.3035168,-3.198998346,10000,-37.93839635,196.366314,0,-14.03629709,0,100.9388439 +162.9,50.30351339,-3.198970826,10000,-37.91750705,196.3707877,0,-14.03629709,0,100.9318179 +162.91,50.30350999,-3.198943306,10000,-37.89661776,196.3757074,0,-14.03629709,0,100.924792 +162.92,50.30350659,-3.198915784,10000,-37.87921002,196.380627,0,-14.03629709,0,100.9177661 +162.93,50.30350319,-3.198888262,10000,-37.86180227,196.3848777,0,-14.03629709,0,100.9107402 +162.94,50.30349979,-3.19886074,10000,-37.84091297,196.3891284,0,-14.03629709,0,100.9037142 +162.95,50.3034964,-3.198833216,10000,-37.82350521,196.3936021,0,-14.03629709,0,100.8966883 +162.96,50.303493,-3.198805693,10000,-37.80261593,196.3982987,0,-14.03629709,0,100.8896624 +162.97,50.30348961,-3.198778168,10000,-37.76780047,196.4032183,0,-14.03629709,0,100.8826365 +162.98,50.30348622,-3.198750643,10000,-37.73298501,196.407692,0,-14.03629709,0,100.8756105 +162.99,50.30348284,-3.198723117,10000,-37.71209572,196.4117196,0,-14.03629709,0,100.8685847 +163,50.30347945,-3.198695591,10000,-37.69120641,196.4161932,0,-14.03629709,0,100.8615587 +163.01,50.30347607,-3.198668064,10000,-37.65639093,196.4211128,0,-14.03629709,0,100.8545328 +163.02,50.30347269,-3.198640536,10000,-37.62157546,196.4258094,0,-14.03629709,0,100.8475069 +163.03,50.30346932,-3.198613008,10000,-37.60068618,196.430506,0,-14.03629709,0,100.840481 +163.04,50.30346594,-3.198585479,10000,-37.58327843,196.4356485,0,-14.03629709,0,100.833455 +163.05,50.30346257,-3.198557949,10000,-37.56238914,196.441014,0,-14.03629709,0,100.8264291 +163.06,50.3034592,-3.198530419,10000,-37.54498138,196.4459335,0,-14.03629709,0,100.8194032 +163.07,50.30345583,-3.198502887,10000,-37.52409208,196.4497381,0,-14.03629709,0,100.8123773 +163.08,50.30345246,-3.198475356,10000,-37.49275816,196.4533198,0,-14.03629709,0,100.8053513 +163.09,50.3034491,-3.198447824,10000,-37.46838734,196.4582393,0,-14.03629709,0,100.7983254 +163.1,50.30344574,-3.198420291,10000,-37.45446114,196.4638277,0,-14.03629709,0,100.7912995 +163.11,50.30344237,-3.198392757,10000,-37.43009031,196.4685242,0,-14.03629709,0,100.7842736 +163.12,50.30343902,-3.198365223,10000,-37.39527483,196.4723288,0,-14.03629709,0,100.7772477 +163.13,50.30343566,-3.198337688,10000,-37.3639409,196.4761334,0,-14.03629709,0,100.7702217 +163.14,50.30343231,-3.198310153,10000,-37.33957006,196.4806069,0,-14.03629709,0,100.7631958 +163.15,50.30342896,-3.198282617,10000,-37.32216231,196.4855263,0,-14.03629709,0,100.7561699 +163.16,50.30342561,-3.19825508,10000,-37.30475456,196.4902228,0,-14.03629709,0,100.749144 +163.17,50.30342226,-3.198227543,10000,-37.28386527,196.4949193,0,-14.03629709,0,100.742118 +163.18,50.30341892,-3.198200005,10000,-37.26645752,196.4998387,0,-14.03629709,0,100.7350921 +163.19,50.30341557,-3.198172466,10000,-37.24556823,196.5045351,0,-14.03629709,0,100.7280662 +163.2,50.30341223,-3.198144927,10000,-37.21075275,196.5092316,0,-14.03629709,0,100.7210403 +163.21,50.30340889,-3.198117387,10000,-37.17593728,196.514151,0,-14.03629709,0,100.7140143 +163.22,50.30340556,-3.198089846,10000,-37.155048,196.5188474,0,-14.03629709,0,100.7069884 +163.23,50.30340222,-3.198062305,10000,-37.13764026,196.5235438,0,-14.03629709,0,100.6999625 +163.24,50.30339889,-3.198034763,10000,-37.11326943,196.5282402,0,-14.03629709,0,100.6929366 +163.25,50.30339556,-3.19800722,10000,-37.08541704,196.5318217,0,-14.03629709,0,100.6859106 +163.26,50.30339223,-3.197979677,10000,-37.0610462,196.5347342,0,-14.03629709,0,100.6788847 +163.27,50.30338891,-3.197952134,10000,-37.04363846,196.5392076,0,-14.03629709,0,100.6718588 +163.28,50.30338558,-3.19792459,10000,-37.02274917,196.5450189,0,-14.03629709,0,100.6648329 +163.29,50.30338226,-3.197897044,10000,-36.98793369,196.5499383,0,-14.03629709,0,100.6578069 +163.3,50.30337894,-3.197869499,10000,-36.95311822,196.5544116,0,-14.03629709,0,100.650781 +163.31,50.30337563,-3.197841953,10000,-36.93222893,196.5595539,0,-14.03629709,0,100.6437551 +163.32,50.30337231,-3.197814405,10000,-36.91482118,196.5640273,0,-14.03629709,0,100.6367292 +163.33,50.303369,-3.197786858,10000,-36.89045034,196.5676087,0,-14.03629709,0,100.6297032 +163.34,50.30336569,-3.19775931,10000,-36.86259797,196.5716361,0,-14.03629709,0,100.6226774 +163.35,50.30336238,-3.197731761,10000,-36.83822713,196.5761094,0,-14.03629709,0,100.6156514 +163.36,50.30335908,-3.197704212,10000,-36.82081939,196.5808057,0,-14.03629709,0,100.6086255 +163.37,50.30335577,-3.197676662,10000,-36.80341165,196.5859479,0,-14.03629709,0,100.6015996 +163.38,50.30335247,-3.197649111,10000,-36.77904082,196.5913132,0,-14.03629709,0,100.5945737 +163.39,50.30334917,-3.19762156,10000,-36.74770689,196.5964554,0,-14.03629709,0,100.5875477 +163.4,50.30334587,-3.197594007,10000,-36.71289141,196.6009287,0,-14.03629709,0,100.5805218 +163.41,50.30334258,-3.197566455,10000,-36.68852057,196.604733,0,-14.03629709,0,100.5734959 +163.42,50.30333929,-3.197538901,10000,-36.67459438,196.6085374,0,-14.03629709,0,100.56647 +163.43,50.30333599,-3.197511348,10000,-36.65370509,196.6127876,0,-14.03629709,0,100.559444 +163.44,50.30333271,-3.197483793,10000,-36.63281579,196.6170379,0,-14.03629709,0,100.5524181 +163.45,50.30332942,-3.197456238,10000,-36.61888959,196.6212882,0,-14.03629709,0,100.5453922 +163.46,50.30332613,-3.197428683,10000,-36.59103721,196.6262074,0,-14.03629709,0,100.5383663 +163.47,50.30332285,-3.197401126,10000,-36.54577711,196.6309036,0,-14.03629709,0,100.5313403 +163.48,50.30331957,-3.197373569,10000,-36.5074801,196.6347079,0,-14.03629709,0,100.5243144 +163.49,50.3033163,-3.197346012,10000,-36.49007236,196.639404,0,-14.03629709,0,100.5172885 +163.5,50.30331302,-3.197318454,10000,-36.48310923,196.6452152,0,-14.03629709,0,100.5102626 +163.51,50.30330975,-3.197290894,10000,-36.46570148,196.6499113,0,-14.03629709,0,100.5032366 +163.52,50.30330647,-3.197263335,10000,-36.43436755,196.6534926,0,-14.03629709,0,100.4962107 +163.53,50.30330321,-3.197235775,10000,-36.40999672,196.6575198,0,-14.03629709,0,100.4891848 +163.54,50.30329994,-3.197208214,10000,-36.39607053,196.661993,0,-14.03629709,0,100.4821589 +163.55,50.30329667,-3.197180653,10000,-36.37169971,196.6666891,0,-14.03629709,0,100.475133 +163.56,50.30329341,-3.197153091,10000,-36.33688424,196.6716082,0,-14.03629709,0,100.468107 +163.57,50.30329015,-3.197125528,10000,-36.30555032,196.6760814,0,-14.03629709,0,100.4610811 +163.58,50.30328689,-3.197097965,10000,-36.28117948,196.6798856,0,-14.03629709,0,100.4540552 +163.59,50.30328364,-3.197070401,10000,-36.26377173,196.6836897,0,-14.03629709,0,100.4470293 +163.6,50.30328038,-3.197042837,10000,-36.24636398,196.6881628,0,-14.03629709,0,100.4400033 +163.61,50.30327713,-3.197015272,10000,-36.22199315,196.6930819,0,-14.03629709,0,100.4329774 +163.62,50.30327388,-3.196987706,10000,-36.19414076,196.697778,0,-14.03629709,0,100.4259515 +163.63,50.30327063,-3.19696014,10000,-36.16976992,196.7024741,0,-14.03629709,0,100.4189256 +163.64,50.30326739,-3.196932573,10000,-36.15236217,196.7073932,0,-14.03629709,0,100.4118996 +163.65,50.30326414,-3.196905005,10000,-36.13147289,196.7118662,0,-14.03629709,0,100.4048738 +163.66,50.3032609,-3.196877437,10000,-36.09665743,196.7158933,0,-14.03629709,0,100.3978478 +163.67,50.30325766,-3.196849868,10000,-36.06184196,196.7203664,0,-14.03629709,0,100.3908219 +163.68,50.30325443,-3.196822299,10000,-36.04095268,196.7250624,0,-14.03629709,0,100.383796 +163.69,50.30325119,-3.196794728,10000,-36.02354493,196.7290895,0,-14.03629709,0,100.3767701 +163.7,50.30324796,-3.196767158,10000,-35.99917409,196.7333396,0,-14.03629709,0,100.3697441 +163.71,50.30324473,-3.196739587,10000,-35.97132171,196.7384815,0,-14.03629709,0,100.3627182 +163.72,50.3032415,-3.196712014,10000,-35.94695088,196.7429546,0,-14.03629709,0,100.3556923 +163.73,50.30323828,-3.196684442,10000,-35.92954314,196.7465356,0,-14.03629709,0,100.3486664 +163.74,50.30323505,-3.196656869,10000,-35.91213539,196.7505627,0,-14.03629709,0,100.3416404 +163.75,50.30323183,-3.196629295,10000,-35.88776456,196.7548127,0,-14.03629709,0,100.3346145 +163.76,50.30322861,-3.196601721,10000,-35.85643063,196.7588397,0,-14.03629709,0,100.3275886 +163.77,50.30322539,-3.196574146,10000,-35.81813361,196.7633127,0,-14.03629709,0,100.3205627 +163.78,50.30322218,-3.196546571,10000,-35.78331814,196.7682316,0,-14.03629709,0,100.3135367 +163.79,50.30321897,-3.196518994,10000,-35.7659104,196.7729275,0,-14.03629709,0,100.3065108 +163.8,50.30321576,-3.196491418,10000,-35.7589473,196.7776235,0,-14.03629709,0,100.2994849 +163.81,50.30321255,-3.19646384,10000,-35.74502109,196.7825424,0,-14.03629709,0,100.292459 +163.82,50.30320934,-3.196436262,10000,-35.7241318,196.7870153,0,-14.03629709,0,100.285433 +163.83,50.30320614,-3.196408683,10000,-35.70324251,196.7910423,0,-14.03629709,0,100.2784071 +163.84,50.30320293,-3.196381104,10000,-35.67190858,196.7955152,0,-14.03629709,0,100.2713812 +163.85,50.30319973,-3.196353524,10000,-35.63013002,196.8002111,0,-14.03629709,0,100.2643553 +163.86,50.30319654,-3.196325943,10000,-35.59879611,196.8037921,0,-14.03629709,0,100.2573293 +163.87,50.30319334,-3.196298362,10000,-35.57790683,196.8064811,0,-14.03629709,0,100.2503034 +163.88,50.30319015,-3.196270781,10000,-35.55701754,196.810285,0,-14.03629709,0,100.2432775 +163.89,50.30318696,-3.196243199,10000,-35.53960978,196.8158728,0,-14.03629709,0,100.2362516 +163.9,50.30318377,-3.196215616,10000,-35.52220204,196.8214606,0,-14.03629709,0,100.2292256 +163.91,50.30318058,-3.196188032,10000,-35.50131276,196.8254875,0,-14.03629709,0,100.2221997 +163.92,50.3031774,-3.196160448,10000,-35.48390502,196.8290684,0,-14.03629709,0,100.2151738 +163.93,50.30317421,-3.196132864,10000,-35.46301573,196.8337643,0,-14.03629709,0,100.2081479 +163.94,50.30317103,-3.196105278,10000,-35.42820025,196.8386831,0,-14.03629709,0,100.201122 +163.95,50.30316785,-3.196077692,10000,-35.39338479,196.8431559,0,-14.03629709,0,100.194096 +163.96,50.30316468,-3.196050106,10000,-35.37249551,196.8480747,0,-14.03629709,0,100.1870701 +163.97,50.3031615,-3.196022518,10000,-35.35508776,196.8527705,0,-14.03629709,0,100.1800442 +163.98,50.30315833,-3.19599493,10000,-35.33071692,196.8561284,0,-14.03629709,0,100.1730183 +163.99,50.30315516,-3.195967342,10000,-35.299383,196.8592632,0,-14.03629709,0,100.1659923 +164,50.30315199,-3.195939753,10000,-35.26108601,196.863513,0,-14.03629709,0,100.1589665 +164.01,50.30314883,-3.195912164,10000,-35.22627054,196.8684318,0,-14.03629709,0,100.1519405 +164.02,50.30314567,-3.195884573,10000,-35.20886277,196.8731275,0,-14.03629709,0,100.1449146 +164.03,50.30314251,-3.195856983,10000,-35.20189966,196.8776003,0,-14.03629709,0,100.1378887 +164.04,50.30313935,-3.195829391,10000,-35.18797348,196.8818501,0,-14.03629709,0,100.1308628 +164.05,50.30313619,-3.195801799,10000,-35.16708419,196.8858768,0,-14.03629709,0,100.1238368 +164.06,50.30313304,-3.195774207,10000,-35.14619489,196.8901266,0,-14.03629709,0,100.1168109 +164.07,50.30312988,-3.195746613,10000,-35.11486097,196.8945993,0,-14.03629709,0,100.109785 +164.08,50.30312673,-3.19571902,10000,-35.07308242,196.899072,0,-14.03629709,0,100.1027591 +164.09,50.30312359,-3.195691425,10000,-35.04523004,196.9033218,0,-14.03629709,0,100.0957331 +164.1,50.30312044,-3.19566383,10000,-35.03478539,196.9073485,0,-14.03629709,0,100.0887072 +164.11,50.3031173,-3.195636235,10000,-35.01737764,196.9115982,0,-14.03629709,0,100.0816813 +164.12,50.30311415,-3.195608638,10000,-34.98604371,196.9160709,0,-14.03629709,0,100.0746554 +164.13,50.30311102,-3.195581042,10000,-34.96167288,196.9207666,0,-14.03629709,0,100.0676294 +164.14,50.30310788,-3.195553444,10000,-34.94774669,196.9256852,0,-14.03629709,0,100.0606035 +164.15,50.30310474,-3.195525846,10000,-34.92337586,196.9299349,0,-14.03629709,0,100.0535776 +164.16,50.30310161,-3.195498247,10000,-34.88856039,196.9330696,0,-14.03629709,0,100.0465517 +164.17,50.30309848,-3.195470648,10000,-34.85722646,196.9364273,0,-14.03629709,0,100.0395257 +164.18,50.30309535,-3.195443049,10000,-34.83285564,196.9413459,0,-14.03629709,0,100.0324998 +164.19,50.30309223,-3.195415448,10000,-34.8154479,196.9469335,0,-14.03629709,0,100.0254739 +164.2,50.3030891,-3.195387847,10000,-34.79804015,196.9516291,0,-14.03629709,0,100.018448 +164.21,50.30308598,-3.195360245,10000,-34.77366931,196.9554327,0,-14.03629709,0,100.011422 +164.22,50.30308286,-3.195332643,10000,-34.74581694,196.9590134,0,-14.03629709,0,100.0043961 +164.23,50.30307974,-3.19530504,10000,-34.72144612,196.962817,0,-14.03629709,0,99.99737018 +164.24,50.30307663,-3.195277437,10000,-34.70403837,196.9672896,0,-14.03629709,0,99.99034429 +164.25,50.30307351,-3.195249833,10000,-34.68314907,196.9719852,0,-14.03629709,0,99.98331833 +164.26,50.3030704,-3.195222228,10000,-34.6483336,196.9757888,0,-14.03629709,0,99.97629244 +164.27,50.30306729,-3.195194623,10000,-34.61351814,196.9791464,0,-14.03629709,0,99.96926649 +164.28,50.30306419,-3.195167018,10000,-34.59262886,196.983173,0,-14.03629709,0,99.96224059 +164.29,50.30306108,-3.195139411,10000,-34.57522112,196.9876456,0,-14.03629709,0,99.95521464 +164.3,50.30305798,-3.195111805,10000,-34.5508503,196.9923411,0,-14.03629709,0,99.94818874 +164.31,50.30305488,-3.195084197,10000,-34.52299792,196.9972596,0,-14.03629709,0,99.94116279 +164.32,50.30305178,-3.195056589,10000,-34.49862707,197.0017321,0,-14.03629709,0,99.9341369 +164.33,50.30304869,-3.19502898,10000,-34.48121932,197.0057586,0,-14.03629709,0,99.927111 +164.34,50.30304559,-3.195001371,10000,-34.46381159,197.0100081,0,-14.03629709,0,99.92008505 +164.35,50.3030425,-3.194973761,10000,-34.43944077,197.0140347,0,-14.03629709,0,99.91305916 +164.36,50.30303941,-3.19494615,10000,-34.40810685,197.0173922,0,-14.03629709,0,99.9060332 +164.37,50.30303632,-3.19491854,10000,-34.36980983,197.0211957,0,-14.03629709,0,99.89900731 +164.38,50.30303324,-3.194890928,10000,-34.33499435,197.0261142,0,-14.03629709,0,99.89198136 +164.39,50.30303016,-3.194863316,10000,-34.31758661,197.0314786,0,-14.03629709,0,99.88495546 +164.4,50.30302708,-3.194835703,10000,-34.3106235,197.03662,0,-14.03629709,0,99.87792951 +164.41,50.303024,-3.194808089,10000,-34.2966973,197.0410924,0,-14.03629709,0,99.87090361 +164.42,50.30302092,-3.194780475,10000,-34.27580803,197.0448959,0,-14.03629709,0,99.86387766 +164.43,50.30301785,-3.19475286,10000,-34.25491875,197.0484764,0,-14.03629709,0,99.85685177 +164.44,50.30301477,-3.194725245,10000,-34.22358483,197.0520569,0,-14.03629709,0,99.84982581 +164.45,50.3030117,-3.194697629,10000,-34.18180627,197.0556373,0,-14.03629709,0,99.84279992 +164.46,50.30300864,-3.194670013,10000,-34.15047234,197.0592178,0,-14.03629709,0,99.83577397 +164.47,50.30300557,-3.194642396,10000,-34.12958306,197.0630212,0,-14.03629709,0,99.82874807 +164.48,50.30300251,-3.194614779,10000,-34.10869378,197.0674936,0,-14.03629709,0,99.82172212 +164.49,50.30299945,-3.194587161,10000,-34.09128604,197.0724119,0,-14.03629709,0,99.81469622 +164.5,50.30299639,-3.194559542,10000,-34.07387829,197.0768843,0,-14.03629709,0,99.80767027 +164.51,50.30299333,-3.194531923,10000,-34.05298899,197.0809107,0,-14.03629709,0,99.80064438 +164.52,50.30299028,-3.194504303,10000,-34.0320997,197.085383,0,-14.03629709,0,99.79361843 +164.53,50.30298722,-3.194476683,10000,-34.0007658,197.0903014,0,-14.03629709,0,99.78659253 +164.54,50.30298417,-3.194449061,10000,-33.95898725,197.0947737,0,-14.03629709,0,99.77956658 +164.55,50.30298113,-3.19442144,10000,-33.93113487,197.0983541,0,-14.03629709,0,99.77254068 +164.56,50.30297808,-3.194393817,10000,-33.92417175,197.1012655,0,-14.03629709,0,99.76551473 +164.57,50.30297504,-3.194366195,10000,-33.91720864,197.1046229,0,-14.03629709,0,99.75848884 +164.58,50.30297199,-3.194338572,10000,-33.88935627,197.1095411,0,-14.03629709,0,99.75146288 +164.59,50.30296895,-3.194310948,10000,-33.84757772,197.1151284,0,-14.03629709,0,99.74443699 +164.6,50.30296592,-3.194283323,10000,-33.81624381,197.1198236,0,-14.03629709,0,99.73741104 +164.61,50.30296288,-3.194255698,10000,-33.79535452,197.1236269,0,-14.03629709,0,99.73038514 +164.62,50.30295985,-3.194228072,10000,-33.77446524,197.1272073,0,-14.03629709,0,99.72335919 +164.63,50.30295682,-3.194200446,10000,-33.7570575,197.1307876,0,-14.03629709,0,99.71633329 +164.64,50.30295379,-3.194172819,10000,-33.7361682,197.1345909,0,-14.03629709,0,99.70930734 +164.65,50.30295076,-3.194145192,10000,-33.70135273,197.1390631,0,-14.03629709,0,99.70228145 +164.66,50.30294774,-3.194117564,10000,-33.66653728,197.1437583,0,-14.03629709,0,99.69525549 +164.67,50.30294472,-3.194089935,10000,-33.64912954,197.1475616,0,-14.03629709,0,99.6882296 +164.68,50.3029417,-3.194062306,10000,-33.64216643,197.1511418,0,-14.03629709,0,99.68120365 +164.69,50.30293868,-3.194034677,10000,-33.62475867,197.155837,0,-14.03629709,0,99.67417775 +164.7,50.30293566,-3.194007046,10000,-33.5899432,197.1605322,0,-14.03629709,0,99.6671518 +164.71,50.30293265,-3.193979415,10000,-33.55512775,197.1641125,0,-14.03629709,0,99.66012591 +164.72,50.30292964,-3.193951784,10000,-33.53423847,197.1679157,0,-14.03629709,0,99.65309995 +164.73,50.30292663,-3.193924152,10000,-33.51683073,197.1726108,0,-14.03629709,0,99.64607406 +164.74,50.30292362,-3.193896519,10000,-33.49594144,197.177083,0,-14.03629709,0,99.63904816 +164.75,50.30292062,-3.193868886,10000,-33.47505215,197.1808862,0,-14.03629709,0,99.63202221 +164.76,50.30291761,-3.193841252,10000,-33.44371823,197.1844664,0,-14.03629709,0,99.62499632 +164.77,50.30291461,-3.193813618,10000,-33.40193968,197.1880466,0,-14.03629709,0,99.61797036 +164.78,50.30291162,-3.193785983,10000,-33.37408732,197.1918498,0,-14.03629709,0,99.61094447 +164.79,50.30290862,-3.193758348,10000,-33.36712421,197.1963219,0,-14.03629709,0,99.60391852 +164.8,50.30290563,-3.193730712,10000,-33.36016109,197.20124,0,-14.03629709,0,99.59689262 +164.81,50.30290263,-3.193703075,10000,-33.33230872,197.2057121,0,-14.03629709,0,99.58986667 +164.82,50.30289964,-3.193675438,10000,-33.29053017,197.2095152,0,-14.03629709,0,99.58284077 +164.83,50.30289666,-3.1936478,10000,-33.25919625,197.2133184,0,-14.03629709,0,99.57581482 +164.84,50.30289367,-3.193620162,10000,-33.23830697,197.2177904,0,-14.03629709,0,99.56878893 +164.85,50.30289069,-3.193592523,10000,-33.21741767,197.2224855,0,-14.03629709,0,99.56176297 +164.86,50.30288771,-3.193564883,10000,-33.20000993,197.2262886,0,-14.03629709,0,99.55473708 +164.87,50.30288473,-3.193537243,10000,-33.17912065,197.2296457,0,-14.03629709,0,99.54771113 +164.88,50.30288175,-3.193509603,10000,-33.1443052,197.2334488,0,-14.03629709,0,99.54068523 +164.89,50.30287878,-3.193481961,10000,-33.10948973,197.2370289,0,-14.03629709,0,99.53365928 +164.9,50.30287581,-3.19345432,10000,-33.09208198,197.240609,0,-14.03629709,0,99.52663339 +164.91,50.30287284,-3.193426678,10000,-33.08511888,197.245527,0,-14.03629709,0,99.51960743 +164.92,50.30286987,-3.193399035,10000,-33.06771115,197.2508909,0,-14.03629709,0,99.51258154 +164.93,50.3028669,-3.193371391,10000,-33.03289568,197.254694,0,-14.03629709,0,99.50555559 +164.94,50.30286394,-3.193343747,10000,-32.99808021,197.2573821,0,-14.03629709,0,99.49852969 +164.95,50.30286098,-3.193316103,10000,-32.97719092,197.2609621,0,-14.03629709,0,99.49150374 +164.96,50.30285802,-3.193288458,10000,-32.95978319,197.2656571,0,-14.03629709,0,99.48447784 +164.97,50.30285506,-3.193260812,10000,-32.9388939,197.270129,0,-14.03629709,0,99.47745189 +164.98,50.30285211,-3.193233166,10000,-32.91800462,197.274155,0,-14.03629709,0,99.470426 +164.99,50.30284915,-3.193205519,10000,-32.88667071,197.278627,0,-14.03629709,0,99.46340004 +165,50.3028462,-3.193177872,10000,-32.84837369,197.2833219,0,-14.03629709,0,99.45637415 +165.01,50.30284326,-3.193150223,10000,-32.83096595,197.2871249,0,-14.03629709,0,99.4493482 +165.02,50.30284031,-3.193122575,10000,-32.82748439,197.2902589,0,-14.03629709,0,99.4423223 +165.03,50.30283736,-3.193094926,10000,-32.80311356,197.2933929,0,-14.03629709,0,99.43529635 +165.04,50.30283442,-3.193067276,10000,-32.75785345,197.2967499,0,-14.03629709,0,99.42827045 +165.05,50.30283148,-3.193039627,10000,-32.71955646,197.3012218,0,-14.03629709,0,99.4212445 +165.06,50.30282855,-3.193011976,10000,-32.69866719,197.3063626,0,-14.03629709,0,99.41421861 +165.07,50.30282561,-3.192984324,10000,-32.68125945,197.3106115,0,-14.03629709,0,99.40719266 +165.08,50.30282268,-3.192956673,10000,-32.66037015,197.3146374,0,-14.03629709,0,99.40016676 +165.09,50.30281975,-3.19292902,10000,-32.6429624,197.3193323,0,-14.03629709,0,99.39314081 +165.1,50.30281682,-3.192901367,10000,-32.62555465,197.3235812,0,-14.03629709,0,99.38611491 +165.11,50.30281389,-3.192873713,10000,-32.60466537,197.3264921,0,-14.03629709,0,99.37908896 +165.12,50.30281097,-3.192846059,10000,-32.5837761,197.3289571,0,-14.03629709,0,99.37206307 +165.13,50.30280804,-3.192818405,10000,-32.55244218,197.332537,0,-14.03629709,0,99.36503717 +165.14,50.30280512,-3.19279075,10000,-32.51066363,197.3374548,0,-14.03629709,0,99.35801122 +165.15,50.30280221,-3.192763094,10000,-32.47932972,197.3428185,0,-14.03629709,0,99.35098532 +165.16,50.30279929,-3.192735438,10000,-32.45844044,197.3477363,0,-14.03629709,0,99.34395937 +165.17,50.30279638,-3.19270778,10000,-32.43755116,197.3515391,0,-14.03629709,0,99.33693348 +165.18,50.30279347,-3.192680123,10000,-32.42362495,197.354896,0,-14.03629709,0,99.32990752 +165.19,50.30279056,-3.192652465,10000,-32.41666184,197.3586988,0,-14.03629709,0,99.32288163 +165.2,50.30278765,-3.192624806,10000,-32.39925409,197.3620557,0,-14.03629709,0,99.31585568 +165.21,50.30278474,-3.192597147,10000,-32.36443863,197.3647435,0,-14.03629709,0,99.30882978 +165.22,50.30278184,-3.192569488,10000,-32.32614163,197.3685463,0,-14.03629709,0,99.30180383 +165.23,50.30277894,-3.192541828,10000,-32.29480772,197.374133,0,-14.03629709,0,99.29477793 +165.24,50.30277604,-3.192514167,10000,-32.2704369,197.3797197,0,-14.03629709,0,99.28775198 +165.25,50.30277315,-3.192486505,10000,-32.25302916,197.3835225,0,-14.03629709,0,99.28072609 +165.26,50.30277025,-3.192458843,10000,-32.23562142,197.3862103,0,-14.03629709,0,99.27370014 +165.27,50.30276736,-3.192431181,10000,-32.21125058,197.3897901,0,-14.03629709,0,99.26667424 +165.28,50.30276447,-3.192403518,10000,-32.17991666,197.3942618,0,-14.03629709,0,99.25964829 +165.29,50.30276158,-3.192375854,10000,-32.1451012,197.3978415,0,-14.03629709,0,99.25262239 +165.3,50.3027587,-3.19234819,10000,-32.12073038,197.4005293,0,-14.03629709,0,99.24559644 +165.31,50.30275582,-3.192320526,10000,-32.10680419,197.404109,0,-14.03629709,0,99.23857055 +165.32,50.30275293,-3.192292861,10000,-32.0859149,197.4088037,0,-14.03629709,0,99.23154459 +165.33,50.30275006,-3.192265195,10000,-32.06502562,197.4132754,0,-14.03629709,0,99.2245187 +165.34,50.30274718,-3.192237529,10000,-32.05109942,197.4170781,0,-14.03629709,0,99.21749275 +165.35,50.3027443,-3.192209862,10000,-32.02672859,197.4208808,0,-14.03629709,0,99.21046685 +165.36,50.30274143,-3.192182195,10000,-31.99191314,197.4253524,0,-14.03629709,0,99.2034409 +165.37,50.30273856,-3.192154527,10000,-31.96057922,197.43027,0,-14.03629709,0,99.196415 +165.38,50.30273569,-3.192126858,10000,-31.93620839,197.4347416,0,-14.03629709,0,99.18938905 +165.39,50.30273283,-3.192099189,10000,-31.91880064,197.4383213,0,-14.03629709,0,99.18236316 +165.4,50.30272996,-3.192071519,10000,-31.89791136,197.441232,0,-14.03629709,0,99.1753372 +165.41,50.3027271,-3.192043849,10000,-31.86309589,197.4443657,0,-14.03629709,0,99.16831131 +165.42,50.30272424,-3.192016179,10000,-31.82828043,197.4481683,0,-14.03629709,0,99.16128536 +165.43,50.30272139,-3.191988507,10000,-31.80739116,197.4519709,0,-14.03629709,0,99.15425946 +165.44,50.30271853,-3.191960836,10000,-31.78998343,197.4562195,0,-14.03629709,0,99.14723351 +165.45,50.30271568,-3.191933164,10000,-31.76909415,197.46136,0,-14.03629709,0,99.14020762 +165.46,50.30271283,-3.19190549,10000,-31.75168639,197.4656086,0,-14.03629709,0,99.13318166 +165.47,50.30270998,-3.191877817,10000,-31.73079709,197.4682962,0,-14.03629709,0,99.12615577 +165.48,50.30270713,-3.191850143,10000,-31.69598164,197.4712068,0,-14.03629709,0,99.11912982 +165.49,50.30270429,-3.191822469,10000,-31.6611662,197.4754554,0,-14.03629709,0,99.11210392 +165.5,50.30270145,-3.191794794,10000,-31.64027692,197.4803729,0,-14.03629709,0,99.10507797 +165.51,50.30269861,-3.191767118,10000,-31.62286918,197.4848444,0,-14.03629709,0,99.09805207 +165.52,50.30269577,-3.191739442,10000,-31.6019799,197.4884239,0,-14.03629709,0,99.09102612 +165.53,50.30269294,-3.191711765,10000,-31.58457216,197.4913345,0,-14.03629709,0,99.08400023 +165.54,50.3026901,-3.191684088,10000,-31.56368287,197.4946911,0,-14.03629709,0,99.07697433 +165.55,50.30268727,-3.191656411,10000,-31.5288674,197.4993855,0,-14.03629709,0,99.06994838 +165.56,50.30268444,-3.191628732,10000,-31.49405192,197.50408,0,-14.03629709,0,99.06292248 +165.57,50.30268162,-3.191601053,10000,-31.47316264,197.5074365,0,-14.03629709,0,99.05589653 +165.58,50.30267879,-3.191573374,10000,-31.45575492,197.5103471,0,-14.03629709,0,99.04887064 +165.59,50.30267597,-3.191545694,10000,-31.43486565,197.5139265,0,-14.03629709,0,99.04184468 +165.6,50.30267315,-3.191518014,10000,-31.41745792,197.518398,0,-14.03629709,0,99.03481879 +165.61,50.30267033,-3.191490333,10000,-31.39656862,197.5230924,0,-14.03629709,0,99.02779284 +165.62,50.30266751,-3.191462651,10000,-31.36175315,197.5266719,0,-14.03629709,0,99.02076694 +165.63,50.3026647,-3.191434969,10000,-31.32693769,197.5293594,0,-14.03629709,0,99.01374099 +165.64,50.30266189,-3.191407287,10000,-31.30604842,197.5329388,0,-14.03629709,0,99.0067151 +165.65,50.30265908,-3.191379604,10000,-31.28515914,197.5376332,0,-14.03629709,0,98.99968914 +165.66,50.30265627,-3.19135192,10000,-31.25382523,197.5421046,0,-14.03629709,0,98.99266325 +165.67,50.30265347,-3.191324236,10000,-31.22945441,197.545907,0,-14.03629709,0,98.9856373 +165.68,50.30265067,-3.191296551,10000,-31.21552822,197.5494864,0,-14.03629709,0,98.9786114 +165.69,50.30264786,-3.191268866,10000,-31.19115738,197.5530658,0,-14.03629709,0,98.97158545 +165.7,50.30264507,-3.19124118,10000,-31.15982345,197.5566452,0,-14.03629709,0,98.96455955 +165.71,50.30264227,-3.191213494,10000,-31.1424157,197.5604476,0,-14.03629709,0,98.9575336 +165.72,50.30263948,-3.191185807,10000,-31.13197106,197.5649189,0,-14.03629709,0,98.95050771 +165.73,50.30263668,-3.19115812,10000,-31.10411869,197.5693903,0,-14.03629709,0,98.94348175 +165.74,50.30263389,-3.191130431,10000,-31.06234015,197.5723007,0,-14.03629709,0,98.93645586 +165.75,50.30263111,-3.191102743,10000,-31.03100624,197.5745421,0,-14.03629709,0,98.92942991 +165.76,50.30262832,-3.191075055,10000,-31.01011696,197.5785674,0,-14.03629709,0,98.92240401 +165.77,50.30262554,-3.191047365,10000,-30.98922768,197.5839307,0,-14.03629709,0,98.91537806 +165.78,50.30262276,-3.191019675,10000,-30.97181994,197.5884019,0,-14.03629709,0,98.90835216 +165.79,50.30261998,-3.190991984,10000,-30.95093065,197.5915353,0,-14.03629709,0,98.90132621 +165.8,50.3026172,-3.190964293,10000,-30.91611519,197.5946686,0,-14.03629709,0,98.89430032 +165.81,50.30261443,-3.190936602,10000,-30.88129974,197.5986939,0,-14.03629709,0,98.88727437 +165.82,50.30261166,-3.190908909,10000,-30.863892,197.6031651,0,-14.03629709,0,98.88024847 +165.83,50.30260889,-3.190881217,10000,-30.85692889,197.6076364,0,-14.03629709,0,98.87322252 +165.84,50.30260612,-3.190853523,10000,-30.83952115,197.6116616,0,-14.03629709,0,98.86619662 +165.85,50.30260335,-3.190825829,10000,-30.80470568,197.6147949,0,-14.03629709,0,98.85917067 +165.86,50.30260059,-3.190798135,10000,-30.76989022,197.6177052,0,-14.03629709,0,98.85214478 +165.87,50.30259783,-3.19077044,10000,-30.74900094,197.6210615,0,-14.03629709,0,98.84511882 +165.88,50.30259507,-3.190742745,10000,-30.73159322,197.6246407,0,-14.03629709,0,98.83809293 +165.89,50.30259231,-3.190715049,10000,-30.71070394,197.62822,0,-14.03629709,0,98.83106698 +165.9,50.30258956,-3.190687353,10000,-30.69329621,197.6317992,0,-14.03629709,0,98.82404108 +165.91,50.3025868,-3.190659656,10000,-30.67240692,197.6356014,0,-14.03629709,0,98.81701513 +165.92,50.30258405,-3.190631959,10000,-30.63759146,197.6400726,0,-14.03629709,0,98.80998923 +165.93,50.3025813,-3.190604261,10000,-30.602776,197.6447667,0,-14.03629709,0,98.80296334 +165.94,50.30257856,-3.190576562,10000,-30.58188671,197.6485689,0,-14.03629709,0,98.79593739 +165.95,50.30257581,-3.190548863,10000,-30.56447897,197.6519251,0,-14.03629709,0,98.78891149 +165.96,50.30257307,-3.190521164,10000,-30.54010815,197.6557273,0,-14.03629709,0,98.78188554 +165.97,50.30257033,-3.190493463,10000,-30.50877425,197.6593064,0,-14.03629709,0,98.77485964 +165.98,50.30256759,-3.190465763,10000,-30.4739588,197.6626626,0,-14.03629709,0,98.76783369 +165.99,50.30256486,-3.190438062,10000,-30.44958796,197.6666877,0,-14.03629709,0,98.7608078 +166,50.30256213,-3.19041036,10000,-30.43566175,197.6709358,0,-14.03629709,0,98.75378185 +166.01,50.30255939,-3.190382658,10000,-30.41129092,197.674515,0,-14.03629709,0,98.74675595 +166.02,50.30255667,-3.190354955,10000,-30.37995702,197.6774251,0,-14.03629709,0,98.73973 +166.03,50.30255394,-3.190327252,10000,-30.36254929,197.6805583,0,-14.03629709,0,98.7327041 +166.04,50.30255122,-3.190299549,10000,-30.35558618,197.6845834,0,-14.03629709,0,98.72567815 +166.05,50.30254849,-3.190271844,10000,-30.33817844,197.6888314,0,-14.03629709,0,98.71865226 +166.06,50.30254577,-3.19024414,10000,-30.29988144,197.6926335,0,-14.03629709,0,98.7116263 +166.07,50.30254305,-3.190216434,10000,-30.25462135,197.6964356,0,-14.03629709,0,98.70460041 +166.08,50.30254034,-3.190188729,10000,-30.22676897,197.7006836,0,-14.03629709,0,98.69757446 +166.09,50.30253763,-3.190161022,10000,-30.21284279,197.7044857,0,-14.03629709,0,98.69054856 +166.1,50.30253491,-3.190133315,10000,-30.19195352,197.7069498,0,-14.03629709,0,98.68352261 +166.11,50.30253221,-3.190105608,10000,-30.17106424,197.7096369,0,-14.03629709,0,98.67649671 +166.12,50.3025295,-3.190077901,10000,-30.15713804,197.7141079,0,-14.03629709,0,98.66947076 +166.13,50.30252679,-3.190050192,10000,-30.13276721,197.7188018,0,-14.03629709,0,98.66244487 +166.14,50.30252409,-3.190022483,10000,-30.09795174,197.7221579,0,-14.03629709,0,98.65541891 +166.15,50.30252139,-3.189994774,10000,-30.06661783,197.7250679,0,-14.03629709,0,98.64839302 +166.16,50.30251869,-3.189967064,10000,-30.04224701,197.7286469,0,-14.03629709,0,98.64136707 +166.17,50.302516,-3.189939354,10000,-30.02483928,197.7331179,0,-14.03629709,0,98.63434117 +166.18,50.3025133,-3.189911643,10000,-30.00743155,197.7380348,0,-14.03629709,0,98.62731522 +166.19,50.30251061,-3.189883931,10000,-29.98306072,197.7422827,0,-14.03629709,0,98.62028933 +166.2,50.30250792,-3.189856219,10000,-29.95520833,197.7451927,0,-14.03629709,0,98.61326337 +166.21,50.30250523,-3.189828506,10000,-29.93083751,197.7476567,0,-14.03629709,0,98.60623748 +166.22,50.30250255,-3.189800794,10000,-29.91342978,197.7510127,0,-14.03629709,0,98.59921153 +166.23,50.30249986,-3.18977308,10000,-29.8925405,197.7548146,0,-14.03629709,0,98.59218563 +166.24,50.30249718,-3.189745366,10000,-29.85772504,197.7581706,0,-14.03629709,0,98.58515968 +166.25,50.3024945,-3.189717652,10000,-29.82290959,197.7619725,0,-14.03629709,0,98.57813378 +166.26,50.30249183,-3.189689937,10000,-29.80202031,197.7666664,0,-14.03629709,0,98.57110783 +166.27,50.30248915,-3.189662221,10000,-29.78461258,197.7711372,0,-14.03629709,0,98.56408194 +166.28,50.30248648,-3.189634505,10000,-29.76024175,197.7749391,0,-14.03629709,0,98.55705598 +166.29,50.30248381,-3.189606788,10000,-29.73238939,197.778295,0,-14.03629709,0,98.55003009 +166.3,50.30248114,-3.189579071,10000,-29.70801856,197.7809819,0,-14.03629709,0,98.54300414 +166.31,50.30247848,-3.189551353,10000,-29.69061081,197.7834459,0,-14.03629709,0,98.53597824 +166.32,50.30247581,-3.189523636,10000,-29.66972153,197.7870247,0,-14.03629709,0,98.52895229 +166.33,50.30247315,-3.189495917,10000,-29.63490608,197.7917185,0,-14.03629709,0,98.52192639 +166.34,50.30247049,-3.189468198,10000,-29.60009062,197.7959664,0,-14.03629709,0,98.5149005 +166.35,50.30246784,-3.189440478,10000,-29.57920133,197.7990992,0,-14.03629709,0,98.50787455 +166.36,50.30246518,-3.189412758,10000,-29.56179359,197.8022321,0,-14.03629709,0,98.50084865 +166.37,50.30246253,-3.189385038,10000,-29.54090432,197.8062569,0,-14.03629709,0,98.4938227 +166.38,50.30245988,-3.189357316,10000,-29.52349659,197.8105046,0,-14.03629709,0,98.48679681 +166.39,50.30245723,-3.189329595,10000,-29.50260732,197.8140835,0,-14.03629709,0,98.47977085 +166.4,50.30245458,-3.189301872,10000,-29.46779186,197.8169933,0,-14.03629709,0,98.47274496 +166.41,50.30245194,-3.18927415,10000,-29.43297639,197.8201261,0,-14.03629709,0,98.46571901 +166.42,50.3024493,-3.189246427,10000,-29.4120871,197.8241509,0,-14.03629709,0,98.45869311 +166.43,50.30244666,-3.189218703,10000,-29.39467937,197.8283986,0,-14.03629709,0,98.45166716 +166.44,50.30244402,-3.189190979,10000,-29.37379011,197.8322003,0,-14.03629709,0,98.44464126 +166.45,50.30244139,-3.189163254,10000,-29.35638237,197.8357791,0,-14.03629709,0,98.43761531 +166.46,50.30243875,-3.189135529,10000,-29.33549309,197.8393578,0,-14.03629709,0,98.43058942 +166.47,50.30243612,-3.189107803,10000,-29.30067763,197.8429366,0,-14.03629709,0,98.42356346 +166.48,50.30243349,-3.189080077,10000,-29.26586218,197.8465153,0,-14.03629709,0,98.41653757 +166.49,50.30243087,-3.18905235,10000,-29.2449729,197.850094,0,-14.03629709,0,98.40951162 +166.5,50.30242824,-3.189024623,10000,-29.22756516,197.8534497,0,-14.03629709,0,98.40248572 +166.51,50.30242562,-3.188996895,10000,-29.20319433,197.8563595,0,-14.03629709,0,98.39545977 +166.52,50.302423,-3.188969167,10000,-29.17534195,197.8594922,0,-14.03629709,0,98.38843388 +166.53,50.30242038,-3.188941439,10000,-29.15097113,197.8632939,0,-14.03629709,0,98.38140792 +166.54,50.30241777,-3.188913709,10000,-29.13356339,197.8668725,0,-14.03629709,0,98.37438203 +166.55,50.30241515,-3.18888598,10000,-29.11267411,197.8702282,0,-14.03629709,0,98.36735608 +166.56,50.30241254,-3.18885825,10000,-29.07785866,197.8742529,0,-14.03629709,0,98.36033018 +166.57,50.30240993,-3.188830519,10000,-29.04304323,197.8785005,0,-14.03629709,0,98.35330423 +166.58,50.30240733,-3.188802788,10000,-29.02215395,197.8823021,0,-14.03629709,0,98.34627833 +166.59,50.30240472,-3.188775056,10000,-29.0047462,197.8858807,0,-14.03629709,0,98.33925238 +166.6,50.30240212,-3.188747324,10000,-28.98037537,197.8894594,0,-14.03629709,0,98.33222649 +166.61,50.30239952,-3.188719591,10000,-28.95252301,197.893038,0,-14.03629709,0,98.32520053 +166.62,50.30239692,-3.188691858,10000,-28.92815219,197.8963936,0,-14.03629709,0,98.31817464 +166.63,50.30239433,-3.188664124,10000,-28.91074444,197.8990802,0,-14.03629709,0,98.31114869 +166.64,50.30239173,-3.18863639,10000,-28.8933367,197.9015439,0,-14.03629709,0,98.30412279 +166.65,50.30238914,-3.188608656,10000,-28.86896587,197.9051225,0,-14.03629709,0,98.29709684 +166.66,50.30238655,-3.188580921,10000,-28.83763197,197.909816,0,-14.03629709,0,98.29007094 +166.67,50.30238396,-3.188553185,10000,-28.80281652,197.9142865,0,-14.03629709,0,98.28304499 +166.68,50.30238138,-3.188525449,10000,-28.77844571,197.918088,0,-14.03629709,0,98.2760191 +166.69,50.3023788,-3.188497712,10000,-28.76451952,197.9216666,0,-14.03629709,0,98.26899315 +166.7,50.30237621,-3.188469975,10000,-28.74014868,197.9250221,0,-14.03629709,0,98.26196725 +166.71,50.30237364,-3.188442237,10000,-28.70881476,197.9279317,0,-14.03629709,0,98.2549413 +166.72,50.30237106,-3.188414499,10000,-28.69140702,197.9310642,0,-14.03629709,0,98.2479154 +166.73,50.30236849,-3.188386761,10000,-28.68096238,197.9348657,0,-14.03629709,0,98.24088945 +166.74,50.30236591,-3.188359021,10000,-28.65311003,197.9382212,0,-14.03629709,0,98.23386356 +166.75,50.30236334,-3.188331282,10000,-28.61133148,197.9409078,0,-14.03629709,0,98.22683766 +166.76,50.30236078,-3.188303542,10000,-28.57999755,197.9444863,0,-14.03629709,0,98.21981171 +166.77,50.30235821,-3.188275802,10000,-28.55910828,197.9489567,0,-14.03629709,0,98.21278581 +166.78,50.30235565,-3.18824806,10000,-28.53821902,197.9527581,0,-14.03629709,0,98.20575986 +166.79,50.30235309,-3.188220319,10000,-28.52081128,197.9561136,0,-14.03629709,0,98.19873397 +166.8,50.30235053,-3.188192577,10000,-28.50340353,197.9599151,0,-14.03629709,0,98.19170801 +166.81,50.30234797,-3.188164834,10000,-28.48251424,197.9632705,0,-14.03629709,0,98.18468212 +166.82,50.30234542,-3.188137091,10000,-28.46510652,197.965734,0,-14.03629709,0,98.17765617 +166.83,50.30234286,-3.188109348,10000,-28.44421725,197.9684205,0,-14.03629709,0,98.17063027 +166.84,50.30234031,-3.188081604,10000,-28.40940179,197.9719989,0,-14.03629709,0,98.16360432 +166.85,50.30233776,-3.18805386,10000,-28.37458633,197.9764693,0,-14.03629709,0,98.15657842 +166.86,50.30233522,-3.188026115,10000,-28.35369706,197.9813856,0,-14.03629709,0,98.14955247 +166.87,50.30233267,-3.187998369,10000,-28.33280778,197.985633,0,-14.03629709,0,98.14252658 +166.88,50.30233013,-3.187970623,10000,-28.29799233,197.9883194,0,-14.03629709,0,98.13550063 +166.89,50.30232759,-3.187942876,10000,-28.26317688,197.9901138,0,-14.03629709,0,98.12847473 +166.9,50.30232506,-3.18791513,10000,-28.2422876,197.9932462,0,-14.03629709,0,98.12144878 +166.91,50.30232252,-3.187887383,10000,-28.22487985,197.9979395,0,-14.03629709,0,98.11442288 +166.92,50.30231999,-3.187859634,10000,-28.20399057,198.0015179,0,-14.03629709,0,98.10739693 +166.93,50.30231746,-3.187831886,10000,-28.18658284,198.0039813,0,-14.03629709,0,98.10037104 +166.94,50.30231493,-3.187804138,10000,-28.16569356,198.0077826,0,-14.03629709,0,98.09334508 +166.95,50.3023124,-3.187776388,10000,-28.13087811,198.0122529,0,-14.03629709,0,98.08631919 +166.96,50.30230988,-3.187748638,10000,-28.09606266,198.0156082,0,-14.03629709,0,98.07929324 +166.97,50.30230736,-3.187720888,10000,-28.07865492,198.0185175,0,-14.03629709,0,98.07226734 +166.98,50.30230484,-3.187693137,10000,-28.07169181,198.0218728,0,-14.03629709,0,98.06524139 +166.99,50.30230232,-3.187665386,10000,-28.05428407,198.0252281,0,-14.03629709,0,98.05821549 +167,50.3022998,-3.187637634,10000,-28.01946863,198.0281374,0,-14.03629709,0,98.05118954 +167.01,50.30229729,-3.187609882,10000,-27.98117163,198.0312697,0,-14.03629709,0,98.04416365 +167.02,50.30229478,-3.18758213,10000,-27.94983771,198.035071,0,-14.03629709,0,98.03713769 +167.03,50.30229227,-3.187554376,10000,-27.92546689,198.0386492,0,-14.03629709,0,98.0301118 +167.04,50.30228977,-3.187526623,10000,-27.90805917,198.0420045,0,-14.03629709,0,98.02308585 +167.05,50.30228726,-3.187498869,10000,-27.89065145,198.0460287,0,-14.03629709,0,98.01605995 +167.06,50.30228476,-3.187471114,10000,-27.86976217,198.0500529,0,-14.03629709,0,98.009034 +167.07,50.30228226,-3.187443359,10000,-27.85235442,198.0529621,0,-14.03629709,0,98.00200811 +167.08,50.30227976,-3.187415603,10000,-27.83146514,198.0554254,0,-14.03629709,0,97.99498215 +167.09,50.30227726,-3.187387848,10000,-27.79664969,198.0590036,0,-14.03629709,0,97.98795626 +167.1,50.30227477,-3.187360091,10000,-27.76183424,198.0634737,0,-14.03629709,0,97.98093031 +167.11,50.30227228,-3.187332334,10000,-27.74094495,198.0670519,0,-14.03629709,0,97.97390441 +167.12,50.30226979,-3.187304576,10000,-27.72005567,198.0697381,0,-14.03629709,0,97.96687846 +167.13,50.3022673,-3.187276819,10000,-27.68524021,198.0730933,0,-14.03629709,0,97.95985256 +167.14,50.30226482,-3.18724906,10000,-27.65042476,198.0768944,0,-14.03629709,0,97.95282667 +167.15,50.30226234,-3.187221301,10000,-27.63301703,198.0800266,0,-14.03629709,0,97.94580072 +167.16,50.30225986,-3.187193542,10000,-27.62605392,198.0829358,0,-14.03629709,0,97.93877482 +167.17,50.30225738,-3.187165782,10000,-27.60864619,198.0862909,0,-14.03629709,0,97.93174887 +167.18,50.3022549,-3.187138022,10000,-27.57383074,198.089869,0,-14.03629709,0,97.92472297 +167.19,50.30225243,-3.187110261,10000,-27.53901529,198.0934471,0,-14.03629709,0,97.91769702 +167.2,50.30224996,-3.1870825,10000,-27.52160756,198.0970253,0,-14.03629709,0,97.91067113 +167.21,50.30224749,-3.187054738,10000,-27.51464445,198.1006033,0,-14.03629709,0,97.90364517 +167.22,50.30224502,-3.187026976,10000,-27.49723671,198.1039584,0,-14.03629709,0,97.89661928 +167.23,50.30224255,-3.186999213,10000,-27.46242127,198.1068676,0,-14.03629709,0,97.88959333 +167.24,50.30224009,-3.18697145,10000,-27.42760582,198.1099997,0,-14.03629709,0,97.88256743 +167.25,50.30223763,-3.186943687,10000,-27.40671655,198.1138007,0,-14.03629709,0,97.87554148 +167.26,50.30223517,-3.186915922,10000,-27.38582726,198.1171558,0,-14.03629709,0,97.86851559 +167.27,50.30223271,-3.186888158,10000,-27.3510118,198.1196189,0,-14.03629709,0,97.86148963 +167.28,50.30223026,-3.186860393,10000,-27.31619635,198.1225279,0,-14.03629709,0,97.85446374 +167.29,50.30222781,-3.186832628,10000,-27.29878862,198.1265519,0,-14.03629709,0,97.84743779 +167.3,50.30222536,-3.186804862,10000,-27.29182553,198.1305759,0,-14.03629709,0,97.84041189 +167.31,50.30222291,-3.186777095,10000,-27.27441779,198.1337079,0,-14.03629709,0,97.83338594 +167.32,50.30222046,-3.186749329,10000,-27.23960232,198.136617,0,-14.03629709,0,97.82636004 +167.33,50.30221802,-3.186721561,10000,-27.20478686,198.140195,0,-14.03629709,0,97.81933409 +167.34,50.30221558,-3.186693794,10000,-27.18389759,198.1444419,0,-14.03629709,0,97.8123082 +167.35,50.30221314,-3.186666025,10000,-27.16300832,198.1482429,0,-14.03629709,0,97.80528224 +167.36,50.3022107,-3.186638256,10000,-27.12819288,198.1504829,0,-14.03629709,0,97.79825635 +167.37,50.30220827,-3.186610487,10000,-27.09337743,198.1522769,0,-14.03629709,0,97.7912304 +167.38,50.30220584,-3.186582718,10000,-27.0759697,198.1556319,0,-14.03629709,0,97.7842045 +167.39,50.30220341,-3.186554948,10000,-27.06900659,198.1603248,0,-14.03629709,0,97.77717855 +167.4,50.30220098,-3.186527177,10000,-27.05159885,198.1647947,0,-14.03629709,0,97.77015265 +167.41,50.30219855,-3.186499406,10000,-27.0167834,198.1683726,0,-14.03629709,0,97.7631267 +167.42,50.30219613,-3.186471634,10000,-26.98196793,198.1710585,0,-14.03629709,0,97.75610081 +167.43,50.30219371,-3.186443862,10000,-26.96456018,198.1732985,0,-14.03629709,0,97.74907486 +167.44,50.30219129,-3.18641609,10000,-26.95759708,198.1759844,0,-14.03629709,0,97.74204896 +167.45,50.30218887,-3.186388317,10000,-26.94018937,198.1793393,0,-14.03629709,0,97.73502301 +167.46,50.30218645,-3.186360544,10000,-26.90537393,198.1829172,0,-14.03629709,0,97.72799711 +167.47,50.30218404,-3.18633277,10000,-26.86707693,198.1864951,0,-14.03629709,0,97.72097116 +167.48,50.30218163,-3.186304996,10000,-26.83574302,198.190073,0,-14.03629709,0,97.71394527 +167.49,50.30217922,-3.186277221,10000,-26.81137219,198.1936508,0,-14.03629709,0,97.70691931 +167.5,50.30217682,-3.186249446,10000,-26.79396446,198.1972286,0,-14.03629709,0,97.69989342 +167.51,50.30217441,-3.18622167,10000,-26.77655674,198.2008065,0,-14.03629709,0,97.69286747 +167.52,50.30217201,-3.186193894,10000,-26.75218592,198.2041613,0,-14.03629709,0,97.68584157 +167.53,50.30216961,-3.186166117,10000,-26.72433356,198.2068472,0,-14.03629709,0,97.67881562 +167.54,50.30216721,-3.18613834,10000,-26.69996272,198.20931,0,-14.03629709,0,97.67178972 +167.55,50.30216482,-3.186110563,10000,-26.68255498,198.2126648,0,-14.03629709,0,97.66476383 +167.56,50.30216242,-3.186082785,10000,-26.66166571,198.2164656,0,-14.03629709,0,97.65773788 +167.57,50.30216003,-3.186055006,10000,-26.62685026,198.2198204,0,-14.03629709,0,97.65071198 +167.58,50.30215764,-3.186027228,10000,-26.59203481,198.2233982,0,-14.03629709,0,97.64368603 +167.59,50.30215526,-3.185999448,10000,-26.57114552,198.2269759,0,-14.03629709,0,97.63666013 +167.6,50.30215287,-3.185971668,10000,-26.5537378,198.2292157,0,-14.03629709,0,97.62963418 +167.61,50.30215049,-3.185943888,10000,-26.52936699,198.2310096,0,-14.03629709,0,97.62260829 +167.62,50.30214811,-3.185916108,10000,-26.50151463,198.2343643,0,-14.03629709,0,97.61558234 +167.63,50.30214573,-3.185888327,10000,-26.47714379,198.239057,0,-14.03629709,0,97.60855644 +167.64,50.30214336,-3.185860545,10000,-26.45973605,198.2435267,0,-14.03629709,0,97.60153049 +167.65,50.30214098,-3.185832763,10000,-26.44232832,198.2471044,0,-14.03629709,0,97.59450459 +167.66,50.30213861,-3.18580498,10000,-26.4179575,198.2497901,0,-14.03629709,0,97.58747864 +167.67,50.30213624,-3.185777197,10000,-26.3866236,198.2520299,0,-14.03629709,0,97.58045275 +167.68,50.30213387,-3.185749414,10000,-26.34832661,198.2547156,0,-14.03629709,0,97.57342679 +167.69,50.30213151,-3.18572163,10000,-26.31351115,198.2580703,0,-14.03629709,0,97.5664009 +167.7,50.30212915,-3.185693846,10000,-26.29610341,198.261648,0,-14.03629709,0,97.55937495 +167.71,50.30212679,-3.185666061,10000,-26.28914032,198.2652256,0,-14.03629709,0,97.55234905 +167.72,50.30212443,-3.185638276,10000,-26.27173259,198.2685803,0,-14.03629709,0,97.5453231 +167.73,50.30212207,-3.18561049,10000,-26.23691714,198.271266,0,-14.03629709,0,97.5382972 +167.74,50.30211972,-3.185582704,10000,-26.20210169,198.2737286,0,-14.03629709,0,97.53127125 +167.75,50.30211737,-3.185554918,10000,-26.18469396,198.2773063,0,-14.03629709,0,97.52424536 +167.76,50.30211502,-3.185527131,10000,-26.17773085,198.2817758,0,-14.03629709,0,97.5172194 +167.77,50.30211267,-3.185499343,10000,-26.16032312,198.2853534,0,-14.03629709,0,97.51019351 +167.78,50.30211032,-3.185471555,10000,-26.12550767,198.2878161,0,-14.03629709,0,97.50316756 +167.79,50.30210798,-3.185443767,10000,-26.08721067,198.2905017,0,-14.03629709,0,97.49614166 +167.8,50.30210564,-3.185415978,10000,-26.05587676,198.2938563,0,-14.03629709,0,97.48911571 +167.81,50.3021033,-3.185388189,10000,-26.03150594,198.2974339,0,-14.03629709,0,97.48208982 +167.82,50.30210097,-3.185360399,10000,-26.0140982,198.3007884,0,-14.03629709,0,97.47506386 +167.83,50.30209863,-3.185332609,10000,-25.99669047,198.303474,0,-14.03629709,0,97.46803797 +167.84,50.3020963,-3.185304818,10000,-25.97231966,198.3059366,0,-14.03629709,0,97.46101202 +167.85,50.30209397,-3.185277028,10000,-25.94446731,198.3092912,0,-14.03629709,0,97.45398612 +167.86,50.30209164,-3.185249236,10000,-25.92009648,198.3130917,0,-14.03629709,0,97.44696017 +167.87,50.30208932,-3.185221444,10000,-25.90268874,198.3162232,0,-14.03629709,0,97.43993427 +167.88,50.30208699,-3.185193652,10000,-25.88528101,198.3191318,0,-14.03629709,0,97.43290832 +167.89,50.30208467,-3.185165859,10000,-25.8609102,198.3224863,0,-14.03629709,0,97.42588243 +167.9,50.30208235,-3.185138066,10000,-25.82957629,198.3260638,0,-14.03629709,0,97.41885647 +167.91,50.30208003,-3.185110272,10000,-25.79127929,198.3294183,0,-14.03629709,0,97.41183058 +167.92,50.30207772,-3.185082478,10000,-25.75646383,198.3321038,0,-14.03629709,0,97.40480463 +167.93,50.30207541,-3.185054683,10000,-25.7390561,198.3345663,0,-14.03629709,0,97.39777873 +167.94,50.3020731,-3.185026889,10000,-25.732093,198.3379208,0,-14.03629709,0,97.39075284 +167.95,50.30207079,-3.184999093,10000,-25.71468528,198.3417212,0,-14.03629709,0,97.38372688 +167.96,50.30206848,-3.184971297,10000,-25.67986983,198.3448527,0,-14.03629709,0,97.37670099 +167.97,50.30206618,-3.184943501,10000,-25.64505438,198.3477611,0,-14.03629709,0,97.36967504 +167.98,50.30206388,-3.184915704,10000,-25.62416509,198.3511156,0,-14.03629709,0,97.36264914 +167.99,50.30206158,-3.184887907,10000,-25.60675736,198.35447,0,-14.03629709,0,97.35562319 +168,50.30205928,-3.184860109,10000,-25.5858681,198.3573784,0,-14.03629709,0,97.3485973 +168.01,50.30205699,-3.184832311,10000,-25.56846037,198.3605098,0,-14.03629709,0,97.34157134 +168.02,50.30205469,-3.184804513,10000,-25.54757108,198.3640872,0,-14.03629709,0,97.33454545 +168.03,50.3020524,-3.184776713,10000,-25.51275563,198.3667726,0,-14.03629709,0,97.3275195 +168.04,50.30205011,-3.184748914,10000,-25.47794018,198.3687891,0,-14.03629709,0,97.3204936 +168.05,50.30204783,-3.184721115,10000,-25.45705091,198.3719205,0,-14.03629709,0,97.31346765 +168.06,50.30204554,-3.184693314,10000,-25.43964317,198.3759438,0,-14.03629709,0,97.30644175 +168.07,50.30204326,-3.184665514,10000,-25.41527235,198.3795211,0,-14.03629709,0,97.2994158 +168.08,50.30204098,-3.184637712,10000,-25.38393845,198.3824295,0,-14.03629709,0,97.29238991 +168.09,50.3020387,-3.184609911,10000,-25.34912301,198.3855608,0,-14.03629709,0,97.28536395 +168.1,50.30203643,-3.184582109,10000,-25.32475219,198.3893611,0,-14.03629709,0,97.27833806 +168.11,50.30203416,-3.184554306,10000,-25.31082599,198.3924925,0,-14.03629709,0,97.27131211 +168.12,50.30203188,-3.184526503,10000,-25.28993671,198.3942858,0,-14.03629709,0,97.26428621 +168.13,50.30202962,-3.1844987,10000,-25.26904744,198.3965252,0,-14.03629709,0,97.25726026 +168.14,50.30202735,-3.184470897,10000,-25.25512125,198.4001025,0,-14.03629709,0,97.25023436 +168.15,50.30202508,-3.184443092,10000,-25.23075044,198.4036797,0,-14.03629709,0,97.24320841 +168.16,50.30202282,-3.184415288,10000,-25.19593499,198.407034,0,-14.03629709,0,97.23618252 +168.17,50.30202056,-3.184387483,10000,-25.16460108,198.4108343,0,-14.03629709,0,97.22915657 +168.18,50.3020183,-3.184359677,10000,-25.14023026,198.4141885,0,-14.03629709,0,97.22213067 +168.19,50.30201605,-3.184331871,10000,-25.12282253,198.4166508,0,-14.03629709,0,97.21510472 +168.2,50.30201379,-3.184304065,10000,-25.10193325,198.4191131,0,-14.03629709,0,97.20807882 +168.21,50.30201154,-3.184276258,10000,-25.0671178,198.4215754,0,-14.03629709,0,97.20105287 +168.22,50.30200929,-3.184248451,10000,-25.03230235,198.4240376,0,-14.03629709,0,97.19402698 +168.23,50.30200705,-3.184220644,10000,-25.01141308,198.4276148,0,-14.03629709,0,97.18700102 +168.24,50.3020048,-3.184192836,10000,-24.99400535,198.432307,0,-14.03629709,0,97.17997513 +168.25,50.30200256,-3.184165027,10000,-24.97311608,198.4365531,0,-14.03629709,0,97.17294918 +168.26,50.30200032,-3.184137218,10000,-24.95570836,198.4392383,0,-14.03629709,0,97.16592328 +168.27,50.30199808,-3.184109408,10000,-24.93481908,198.4408086,0,-14.03629709,0,97.15889733 +168.28,50.30199584,-3.184081599,10000,-24.90000363,198.4430478,0,-14.03629709,0,97.15187143 +168.29,50.30199361,-3.184053789,10000,-24.86518817,198.4466249,0,-14.03629709,0,97.14484548 +168.3,50.30199138,-3.184025978,10000,-24.84429889,198.4499791,0,-14.03629709,0,97.13781959 +168.31,50.30198915,-3.183998167,10000,-24.82689114,198.4524413,0,-14.03629709,0,97.13079363 +168.32,50.30198692,-3.183970356,10000,-24.80600187,198.4551264,0,-14.03629709,0,97.12376774 +168.33,50.3019847,-3.183942544,10000,-24.78859414,198.4587036,0,-14.03629709,0,97.11674179 +168.34,50.30198247,-3.183914732,10000,-24.76770488,198.4629496,0,-14.03629709,0,97.10971589 +168.35,50.30198025,-3.183886919,10000,-24.73288943,198.4667497,0,-14.03629709,0,97.10269 +168.36,50.30197803,-3.183859105,10000,-24.69807398,198.4692119,0,-14.03629709,0,97.09566405 +168.37,50.30197582,-3.183831292,10000,-24.67718472,198.471451,0,-14.03629709,0,97.08863815 +168.38,50.3019736,-3.183803478,10000,-24.65977698,198.4741361,0,-14.03629709,0,97.0816122 +168.39,50.30197139,-3.183775663,10000,-24.63540615,198.4763752,0,-14.03629709,0,97.0745863 +168.4,50.30196918,-3.183747849,10000,-24.60407225,198.4788373,0,-14.03629709,0,97.06756035 +168.41,50.30196697,-3.183720034,10000,-24.5692568,198.4826374,0,-14.03629709,0,97.06053446 +168.42,50.30196477,-3.183692218,10000,-24.54488598,198.4868834,0,-14.03629709,0,97.0535085 +168.43,50.30196257,-3.183664402,10000,-24.53095979,198.4904604,0,-14.03629709,0,97.04648261 +168.44,50.30196036,-3.183636585,10000,-24.51007052,198.4931454,0,-14.03629709,0,97.03945666 +168.45,50.30195817,-3.183608768,10000,-24.48918125,198.4953845,0,-14.03629709,0,97.03243076 +168.46,50.30195597,-3.183580951,10000,-24.47525508,198.4980695,0,-14.03629709,0,97.02540481 +168.47,50.30195377,-3.183553133,10000,-24.45088427,198.5014235,0,-14.03629709,0,97.01837891 +168.48,50.30195158,-3.183525315,10000,-24.41606881,198.5047775,0,-14.03629709,0,97.01135296 +168.49,50.30194939,-3.183497496,10000,-24.38473489,198.5074626,0,-14.03629709,0,97.00432707 +168.5,50.3019472,-3.183469677,10000,-24.36036406,198.5097016,0,-14.03629709,0,96.99730111 +168.51,50.30194502,-3.183441858,10000,-24.34295633,198.5123866,0,-14.03629709,0,96.99027522 +168.52,50.30194283,-3.183414038,10000,-24.32206705,198.5159635,0,-14.03629709,0,96.98324927 +168.53,50.30194065,-3.183386218,10000,-24.2872516,198.5202094,0,-14.03629709,0,96.97622337 +168.54,50.30193847,-3.183358397,10000,-24.25243617,198.5240093,0,-14.03629709,0,96.96919742 +168.55,50.3019363,-3.183330575,10000,-24.23154691,198.5262483,0,-14.03629709,0,96.96217153 +168.56,50.30193412,-3.183302754,10000,-24.21413918,198.5278183,0,-14.03629709,0,96.95514557 +168.57,50.30193195,-3.183274932,10000,-24.19324989,198.5302803,0,-14.03629709,0,96.94811968 +168.58,50.30192978,-3.18324711,10000,-24.17584215,198.5336342,0,-14.03629709,0,96.94109373 +168.59,50.30192761,-3.183219287,10000,-24.15495289,198.537211,0,-14.03629709,0,96.93406783 +168.6,50.30192544,-3.183191464,10000,-24.12013745,198.5405649,0,-14.03629709,0,96.92704188 +168.61,50.30192328,-3.18316364,10000,-24.08532198,198.5432498,0,-14.03629709,0,96.92001598 +168.62,50.30192112,-3.183135816,10000,-24.06791424,198.5454887,0,-14.03629709,0,96.91299003 +168.63,50.30191896,-3.183107992,10000,-24.06095116,198.5481736,0,-14.03629709,0,96.90596414 +168.64,50.3019168,-3.183080167,10000,-24.04354344,198.5515275,0,-14.03629709,0,96.89893818 +168.65,50.30191464,-3.183052342,10000,-24.00872799,198.5551043,0,-14.03629709,0,96.89191229 +168.66,50.30191249,-3.183024516,10000,-23.97043099,198.5586812,0,-14.03629709,0,96.88488634 +168.67,50.30191034,-3.18299669,10000,-23.93909709,198.562035,0,-14.03629709,0,96.87786044 +168.68,50.30190819,-3.182968863,10000,-23.91472627,198.5647198,0,-14.03629709,0,96.87083449 +168.69,50.30190605,-3.182941036,10000,-23.89731853,198.5669587,0,-14.03629709,0,96.86380859 +168.7,50.3019039,-3.182913209,10000,-23.87991081,198.5694205,0,-14.03629709,0,96.85678264 +168.71,50.30190176,-3.182885381,10000,-23.85553999,198.5718823,0,-14.03629709,0,96.84975675 +168.72,50.30189962,-3.182857553,10000,-23.82768762,198.5741212,0,-14.03629709,0,96.8427308 +168.73,50.30189748,-3.182829725,10000,-23.80331681,198.5768059,0,-14.03629709,0,96.8357049 +168.74,50.30189535,-3.182801896,10000,-23.78590909,198.5801597,0,-14.03629709,0,96.82867895 +168.75,50.30189321,-3.182774067,10000,-23.76501983,198.5837365,0,-14.03629709,0,96.82165305 +168.76,50.30189108,-3.182746237,10000,-23.73020437,198.5873132,0,-14.03629709,0,96.81462716 +168.77,50.30188895,-3.182718407,10000,-23.6953889,198.5906669,0,-14.03629709,0,96.80760121 +168.78,50.30188683,-3.182690576,10000,-23.67449963,198.5933517,0,-14.03629709,0,96.80057531 +168.79,50.3018847,-3.182662745,10000,-23.65709191,198.5955904,0,-14.03629709,0,96.79354936 +168.8,50.30188258,-3.182634914,10000,-23.63620264,198.5982752,0,-14.03629709,0,96.78652346 +168.81,50.30188046,-3.182607082,10000,-23.61879491,198.6016289,0,-14.03629709,0,96.77949751 +168.82,50.30187834,-3.18257925,10000,-23.59790563,198.6049826,0,-14.03629709,0,96.77247162 +168.83,50.30187622,-3.182551417,10000,-23.56309018,198.6076673,0,-14.03629709,0,96.76544566 +168.84,50.30187411,-3.182523584,10000,-23.52827472,198.609906,0,-14.03629709,0,96.75841977 +168.85,50.301872,-3.182495751,10000,-23.50738545,198.6125907,0,-14.03629709,0,96.75139382 +168.86,50.30186989,-3.182467917,10000,-23.48997773,198.6159444,0,-14.03629709,0,96.74436792 +168.87,50.30186778,-3.182440083,10000,-23.46908847,198.619298,0,-14.03629709,0,96.73734197 +168.88,50.30186568,-3.182412248,10000,-23.4481992,198.6219827,0,-14.03629709,0,96.73031607 +168.89,50.30186357,-3.182384413,10000,-23.41686529,198.6244443,0,-14.03629709,0,96.72329012 +168.9,50.30186147,-3.182356578,10000,-23.37508674,198.627798,0,-14.03629709,0,96.71626423 +168.91,50.30185938,-3.182328742,10000,-23.34723438,198.6313746,0,-14.03629709,0,96.70923828 +168.92,50.30185728,-3.182300905,10000,-23.34027129,198.6336132,0,-14.03629709,0,96.70221238 +168.93,50.30185519,-3.182273069,10000,-23.33330819,198.6351829,0,-14.03629709,0,96.69518643 +168.94,50.30185309,-3.182245232,10000,-23.30545583,198.6376445,0,-14.03629709,0,96.68816053 +168.95,50.301851,-3.182217395,10000,-23.2636773,198.6409981,0,-14.03629709,0,96.68113458 +168.96,50.30184892,-3.182189557,10000,-23.23234339,198.6445746,0,-14.03629709,0,96.67410869 +168.97,50.30184683,-3.182161719,10000,-23.21145411,198.6481512,0,-14.03629709,0,96.66708273 +168.98,50.30184475,-3.18213388,10000,-23.19056485,198.6515047,0,-14.03629709,0,96.66005684 +168.99,50.30184267,-3.182106041,10000,-23.17315712,198.6541893,0,-14.03629709,0,96.65303089 +169,50.30184059,-3.182078201,10000,-23.15226783,198.6564279,0,-14.03629709,0,96.64600499 +169.01,50.30183851,-3.182050362,10000,-23.11745238,198.6588894,0,-14.03629709,0,96.63897904 +169.02,50.30183644,-3.182022521,10000,-23.08263694,198.661574,0,-14.03629709,0,96.63195314 +169.03,50.30183437,-3.181994681,10000,-23.06522922,198.6644815,0,-14.03629709,0,96.62492719 +169.04,50.3018323,-3.18196684,10000,-23.05826613,198.667612,0,-14.03629709,0,96.6179013 +169.05,50.30183023,-3.181938998,10000,-23.04085839,198.6705195,0,-14.03629709,0,96.61087534 +169.06,50.30182816,-3.181911157,10000,-23.00604294,198.673204,0,-14.03629709,0,96.60384945 +169.07,50.3018261,-3.181883314,10000,-22.9712275,198.6756655,0,-14.03629709,0,96.5968235 +169.08,50.30182404,-3.181855472,10000,-22.95033823,198.677904,0,-14.03629709,0,96.5897976 +169.09,50.30182198,-3.181827629,10000,-22.93293049,198.6805885,0,-14.03629709,0,96.58277165 +169.1,50.30181992,-3.181799786,10000,-22.91204121,198.683942,0,-14.03629709,0,96.57574576 +169.11,50.30181787,-3.181771942,10000,-22.89115195,198.6875184,0,-14.03629709,0,96.5687198 +169.12,50.30181581,-3.181744098,10000,-22.85981804,198.6908718,0,-14.03629709,0,96.56169391 +169.13,50.30181376,-3.181716253,10000,-22.8180395,198.6933333,0,-14.03629709,0,96.55466796 +169.14,50.30181172,-3.181688408,10000,-22.79018715,198.6949027,0,-14.03629709,0,96.54764206 +169.15,50.30180967,-3.181660563,10000,-22.78322406,198.6971412,0,-14.03629709,0,96.54061617 +169.16,50.30180763,-3.181632718,10000,-22.77626097,198.7007176,0,-14.03629709,0,96.53359021 +169.17,50.30180558,-3.181604871,10000,-22.74840861,198.704071,0,-14.03629709,0,96.52656432 +169.18,50.30180354,-3.181577025,10000,-22.70663007,198.7065324,0,-14.03629709,0,96.51953837 +169.19,50.30180151,-3.181549178,10000,-22.67529616,198.7092168,0,-14.03629709,0,96.51251247 +169.2,50.30179947,-3.181521331,10000,-22.65440687,198.7125701,0,-14.03629709,0,96.50548652 +169.21,50.30179744,-3.181493483,10000,-22.6335176,198.7159235,0,-14.03629709,0,96.49846062 +169.22,50.30179541,-3.181465635,10000,-22.61610988,198.7183848,0,-14.03629709,0,96.49143467 +169.23,50.30179338,-3.181437786,10000,-22.59522061,198.7199542,0,-14.03629709,0,96.48440878 +169.24,50.30179135,-3.181409938,10000,-22.56040517,198.7221926,0,-14.03629709,0,96.47738282 +169.25,50.30178933,-3.181382089,10000,-22.52558972,198.7257689,0,-14.03629709,0,96.47035693 +169.26,50.30178731,-3.181354239,10000,-22.50470045,198.7291222,0,-14.03629709,0,96.46333098 +169.27,50.30178529,-3.181326389,10000,-22.48729272,198.7315835,0,-14.03629709,0,96.45630508 +169.28,50.30178327,-3.181298539,10000,-22.46640345,198.7342678,0,-14.03629709,0,96.44927913 +169.29,50.30178126,-3.181270688,10000,-22.44899572,198.7376211,0,-14.03629709,0,96.44225324 +169.3,50.30177924,-3.181242837,10000,-22.42810644,198.7409744,0,-14.03629709,0,96.43522728 +169.31,50.30177723,-3.181214985,10000,-22.39329099,198.7434357,0,-14.03629709,0,96.42820139 +169.32,50.30177522,-3.181187133,10000,-22.35847555,198.744782,0,-14.03629709,0,96.42117544 +169.33,50.30177322,-3.181159281,10000,-22.33758628,198.7463513,0,-14.03629709,0,96.41414954 +169.34,50.30177121,-3.181131429,10000,-22.32017855,198.7494815,0,-14.03629709,0,96.40712359 +169.35,50.30176921,-3.181103576,10000,-22.29580773,198.7532807,0,-14.03629709,0,96.40009769 +169.36,50.30176721,-3.181075722,10000,-22.26795538,198.756411,0,-14.03629709,0,96.39307174 +169.37,50.30176521,-3.181047869,10000,-22.24358456,198.7593182,0,-14.03629709,0,96.38604585 +169.38,50.30176322,-3.181020014,10000,-22.22617682,198.7626714,0,-14.03629709,0,96.37901989 +169.39,50.30176122,-3.18099216,10000,-22.20528755,198.7660246,0,-14.03629709,0,96.371994 +169.4,50.30175923,-3.180964304,10000,-22.17047212,198.7687088,0,-14.03629709,0,96.36496805 +169.41,50.30175724,-3.180936449,10000,-22.13565669,198.770724,0,-14.03629709,0,96.35794215 +169.42,50.30175526,-3.180908593,10000,-22.11476742,198.7725162,0,-14.03629709,0,96.3509162 +169.43,50.30175327,-3.180880737,10000,-22.09735968,198.7745314,0,-14.03629709,0,96.3438903 +169.44,50.30175129,-3.180852881,10000,-22.07647039,198.7769926,0,-14.03629709,0,96.33686435 +169.45,50.30174931,-3.180825024,10000,-22.05906266,198.7796768,0,-14.03629709,0,96.32983846 +169.46,50.30174733,-3.180797167,10000,-22.03817339,198.7828069,0,-14.03629709,0,96.32281251 +169.47,50.30174535,-3.18076931,10000,-22.00335795,198.786383,0,-14.03629709,0,96.31578661 +169.48,50.30174338,-3.180741451,10000,-21.96854251,198.7890671,0,-14.03629709,0,96.30876066 +169.49,50.30174141,-3.180713593,10000,-21.94765323,198.7910823,0,-14.03629709,0,96.30173476 +169.5,50.30173944,-3.180685735,10000,-21.93024549,198.7939894,0,-14.03629709,0,96.29470881 +169.51,50.30173747,-3.180657875,10000,-21.90935621,198.7971195,0,-14.03629709,0,96.28768292 +169.52,50.30173551,-3.180630016,10000,-21.88846695,198.7995806,0,-14.03629709,0,96.28065696 +169.53,50.30173354,-3.180602156,10000,-21.85713306,198.8022647,0,-14.03629709,0,96.27363107 +169.54,50.30173158,-3.180574296,10000,-21.81535454,198.8053947,0,-14.03629709,0,96.26660512 +169.55,50.30172963,-3.180546435,10000,-21.78750217,198.8080788,0,-14.03629709,0,96.25957922 +169.56,50.30172767,-3.180518574,10000,-21.78053907,198.8103169,0,-14.03629709,0,96.25255333 +169.57,50.30172572,-3.180490713,10000,-21.77357597,198.8130009,0,-14.03629709,0,96.24552737 +169.58,50.30172376,-3.180462851,10000,-21.74572361,198.816131,0,-14.03629709,0,96.23850148 +169.59,50.30172181,-3.180434989,10000,-21.70394507,198.818592,0,-14.03629709,0,96.23147553 +169.6,50.30171987,-3.180407126,10000,-21.67261117,198.8201611,0,-14.03629709,0,96.22444963 +169.61,50.30171792,-3.180379264,10000,-21.6517219,198.8223991,0,-14.03629709,0,96.21742368 +169.62,50.30171598,-3.180351401,10000,-21.63083263,198.8259751,0,-14.03629709,0,96.21039778 +169.63,50.30171404,-3.180323537,10000,-21.6134249,198.829328,0,-14.03629709,0,96.20337183 +169.64,50.3017121,-3.180295673,10000,-21.59253563,198.831789,0,-14.03629709,0,96.19634594 +169.65,50.30171016,-3.180267809,10000,-21.55772018,198.83425,0,-14.03629709,0,96.18931999 +169.66,50.30170823,-3.180239944,10000,-21.52290474,198.836711,0,-14.03629709,0,96.18229409 +169.67,50.3017063,-3.180212079,10000,-21.50549702,198.838949,0,-14.03629709,0,96.17526814 +169.68,50.30170437,-3.180184214,10000,-21.49853392,198.8416329,0,-14.03629709,0,96.16824224 +169.69,50.30170244,-3.180156348,10000,-21.4811262,198.8449859,0,-14.03629709,0,96.16121629 +169.7,50.30170051,-3.180128482,10000,-21.44631075,198.8483388,0,-14.03629709,0,96.1541904 +169.71,50.30169859,-3.180100615,10000,-21.4114953,198.8510227,0,-14.03629709,0,96.14716444 +169.72,50.30169667,-3.180072748,10000,-21.39060602,198.8530377,0,-14.03629709,0,96.14013855 +169.73,50.30169475,-3.180044881,10000,-21.3731983,198.8548296,0,-14.03629709,0,96.1331126 +169.74,50.30169283,-3.180017013,10000,-21.35230903,198.8570675,0,-14.03629709,0,96.1260867 +169.75,50.30169092,-3.179989146,10000,-21.33141976,198.8604204,0,-14.03629709,0,96.11906075 +169.76,50.301689,-3.179961277,10000,-21.30008586,198.8639962,0,-14.03629709,0,96.11203485 +169.77,50.30168709,-3.179933408,10000,-21.25830733,198.8662341,0,-14.03629709,0,96.1050089 +169.78,50.30168519,-3.179905539,10000,-21.23045497,198.867803,0,-14.03629709,0,96.09798301 +169.79,50.30168328,-3.17987767,10000,-21.22001033,198.8702639,0,-14.03629709,0,96.09095705 +169.8,50.30168138,-3.1798498,10000,-21.20260259,198.8736167,0,-14.03629709,0,96.08393116 +169.81,50.30167947,-3.17982193,10000,-21.17126869,198.8769695,0,-14.03629709,0,96.07690521 +169.82,50.30167758,-3.179794059,10000,-21.14689789,198.8794304,0,-14.03629709,0,96.06987931 +169.83,50.30167568,-3.179766188,10000,-21.13297171,198.8807762,0,-14.03629709,0,96.06285336 +169.84,50.30167378,-3.179738317,10000,-21.10860089,198.8823451,0,-14.03629709,0,96.05582747 +169.85,50.30167189,-3.179710446,10000,-21.07378543,198.8856979,0,-14.03629709,0,96.04880151 +169.86,50.30167,-3.179682574,10000,-21.04245153,198.8899426,0,-14.03629709,0,96.04177562 +169.87,50.30166811,-3.179654701,10000,-21.01808071,198.8926264,0,-14.03629709,0,96.03474967 +169.88,50.30166623,-3.179626828,10000,-21.00067299,198.8939722,0,-14.03629709,0,96.02772377 +169.89,50.30166434,-3.179598956,10000,-20.98326528,198.896433,0,-14.03629709,0,96.02069782 +169.9,50.30166246,-3.179571082,10000,-20.95889447,198.8997857,0,-14.03629709,0,96.01367192 +169.91,50.30166058,-3.179543208,10000,-20.93104211,198.9020235,0,-14.03629709,0,96.00664597 +169.92,50.3016587,-3.179515334,10000,-20.90667128,198.9035923,0,-14.03629709,0,95.99962008 +169.93,50.30165683,-3.17948746,10000,-20.88926355,198.906053,0,-14.03629709,0,95.99259412 +169.94,50.30165495,-3.179459585,10000,-20.86837428,198.9094057,0,-14.03629709,0,95.98556823 +169.95,50.30165308,-3.17943171,10000,-20.83355884,198.9127584,0,-14.03629709,0,95.97854233 +169.96,50.30165121,-3.179403834,10000,-20.7987434,198.9154421,0,-14.03629709,0,95.97151638 +169.97,50.30164935,-3.179375958,10000,-20.77785413,198.9176798,0,-14.03629709,0,95.96449049 +169.98,50.30164748,-3.179348082,10000,-20.76044639,198.9201405,0,-14.03629709,0,95.95746453 +169.99,50.30164562,-3.179320205,10000,-20.73607558,198.9226012,0,-14.03629709,0,95.95043864 +170,50.30164376,-3.179292328,10000,-20.70474167,198.9248389,0,-14.03629709,0,95.94341269 +170.01,50.3016419,-3.179264451,10000,-20.66992622,198.9272995,0,-14.03629709,0,95.93638679 +170.02,50.30164005,-3.179236573,10000,-20.64903697,198.9297602,0,-14.03629709,0,95.92936084 +170.03,50.3016382,-3.179208695,10000,-20.64555543,198.9319979,0,-14.03629709,0,95.92233495 +170.04,50.30163634,-3.179180817,10000,-20.6281477,198.9346815,0,-14.03629709,0,95.91530899 +170.05,50.30163449,-3.179152938,10000,-20.58985069,198.9378111,0,-14.03629709,0,95.9082831 +170.06,50.30163265,-3.179125059,10000,-20.55851679,198.9402717,0,-14.03629709,0,95.90125715 +170.07,50.3016308,-3.179097179,10000,-20.53762753,198.9418404,0,-14.03629709,0,95.89423125 +170.08,50.30162896,-3.1790693,10000,-20.51325672,198.944078,0,-14.03629709,0,95.8872053 +170.09,50.30162712,-3.17904142,10000,-20.48540436,198.9476535,0,-14.03629709,0,95.8801794 +170.1,50.30162528,-3.179013539,10000,-20.46103355,198.9510061,0,-14.03629709,0,95.87315345 +170.11,50.30162345,-3.178985658,10000,-20.44362582,198.9534667,0,-14.03629709,0,95.86612756 +170.12,50.30162161,-3.178957777,10000,-20.42273653,198.9559273,0,-14.03629709,0,95.8591016 +170.13,50.30161978,-3.178929895,10000,-20.38792109,198.9583878,0,-14.03629709,0,95.85207571 +170.14,50.30161795,-3.178902013,10000,-20.35310566,198.9606254,0,-14.03629709,0,95.84504976 +170.15,50.30161613,-3.178874131,10000,-20.33221639,198.9630859,0,-14.03629709,0,95.83802386 +170.16,50.3016143,-3.178846248,10000,-20.31480866,198.9655464,0,-14.03629709,0,95.83099791 +170.17,50.30161248,-3.178818365,10000,-20.29391939,198.967784,0,-14.03629709,0,95.82397201 +170.18,50.30161066,-3.178790482,10000,-20.27651167,198.9702445,0,-14.03629709,0,95.81694606 +170.19,50.30160884,-3.178762598,10000,-20.25562241,198.972705,0,-14.03629709,0,95.80992017 +170.2,50.30160702,-3.178734714,10000,-20.22080696,198.9749425,0,-14.03629709,0,95.80289422 +170.21,50.30160521,-3.17870683,10000,-20.18599151,198.977403,0,-14.03629709,0,95.79586832 +170.22,50.3016034,-3.178678945,10000,-20.16858378,198.9798635,0,-14.03629709,0,95.78884237 +170.23,50.30160159,-3.17865106,10000,-20.16162068,198.9821009,0,-14.03629709,0,95.78181647 +170.24,50.30159978,-3.178623175,10000,-20.14421294,198.9845614,0,-14.03629709,0,95.77479052 +170.25,50.30159797,-3.178595289,10000,-20.1093975,198.9870219,0,-14.03629709,0,95.76776463 +170.26,50.30159617,-3.178567403,10000,-20.07110053,198.9892593,0,-14.03629709,0,95.76073867 +170.27,50.30159437,-3.178539517,10000,-20.03976663,198.9917197,0,-14.03629709,0,95.75371278 +170.28,50.30159257,-3.17851163,10000,-20.01539581,198.9944032,0,-14.03629709,0,95.74668683 +170.29,50.30159078,-3.178483743,10000,-19.99798807,198.9975326,0,-14.03629709,0,95.73966093 +170.3,50.30158898,-3.178455856,10000,-19.98058034,199.0011079,0,-14.03629709,0,95.73263498 +170.31,50.30158719,-3.178427967,10000,-19.95620953,199.0035683,0,-14.03629709,0,95.72560908 +170.32,50.3015854,-3.178400079,10000,-19.92835717,199.0046908,0,-14.03629709,0,95.71858313 +170.33,50.30158361,-3.178372191,10000,-19.90398637,199.0064822,0,-14.03629709,0,95.71155724 +170.34,50.30158183,-3.178344302,10000,-19.88657867,199.0096115,0,-14.03629709,0,95.70453128 +170.35,50.30158004,-3.178316413,10000,-19.8656894,199.0127409,0,-14.03629709,0,95.69750539 +170.36,50.30157826,-3.178288523,10000,-19.83087394,199.0145322,0,-14.03629709,0,95.6904795 +170.37,50.30157648,-3.178260633,10000,-19.79605848,199.0156546,0,-14.03629709,0,95.68345354 +170.38,50.30157471,-3.178232744,10000,-19.77516921,199.018115,0,-14.03629709,0,95.67642765 +170.39,50.30157293,-3.178204853,10000,-19.75776149,199.0214673,0,-14.03629709,0,95.6694017 +170.4,50.30157116,-3.178176962,10000,-19.73339069,199.0239276,0,-14.03629709,0,95.6623758 +170.41,50.30156939,-3.178149071,10000,-19.70553834,199.0263879,0,-14.03629709,0,95.65534985 +170.42,50.30156762,-3.17812118,10000,-19.68116751,199.0299632,0,-14.03629709,0,95.64832395 +170.43,50.30156586,-3.178093287,10000,-19.66375977,199.0330924,0,-14.03629709,0,95.641298 +170.44,50.30156409,-3.178065395,10000,-19.64635204,199.0346607,0,-14.03629709,0,95.63427211 +170.45,50.30156233,-3.178037502,10000,-19.62198124,199.036006,0,-14.03629709,0,95.62724615 +170.46,50.30156057,-3.17800961,10000,-19.59064735,199.0382433,0,-14.03629709,0,95.62022026 +170.47,50.30155881,-3.177981716,10000,-19.55235036,199.0407036,0,-14.03629709,0,95.61319431 +170.48,50.30155706,-3.177953823,10000,-19.51753492,199.0429408,0,-14.03629709,0,95.60616841 +170.49,50.30155531,-3.177925929,10000,-19.50012719,199.045624,0,-14.03629709,0,95.59914246 +170.5,50.30155356,-3.177898035,10000,-19.49316409,199.0487533,0,-14.03629709,0,95.59211656 +170.51,50.30155181,-3.17787014,10000,-19.47575636,199.0512135,0,-14.03629709,0,95.58509061 +170.52,50.30155006,-3.177842245,10000,-19.44094092,199.0525587,0,-14.03629709,0,95.57806472 +170.53,50.30154832,-3.17781435,10000,-19.40612548,199.053904,0,-14.03629709,0,95.57103876 +170.54,50.30154658,-3.177786455,10000,-19.3852362,199.0563641,0,-14.03629709,0,95.56401287 +170.55,50.30154484,-3.177758559,10000,-19.36782848,199.0597163,0,-14.03629709,0,95.55698692 +170.56,50.3015431,-3.177730663,10000,-19.34693921,199.0630685,0,-14.03629709,0,95.54996102 +170.57,50.30154137,-3.177702766,10000,-19.32953149,199.0657516,0,-14.03629709,0,95.54293507 +170.58,50.30153963,-3.177674869,10000,-19.30864223,199.0679888,0,-14.03629709,0,95.53590918 +170.59,50.3015379,-3.177646972,10000,-19.27382679,199.0704489,0,-14.03629709,0,95.52888322 +170.6,50.30153617,-3.177619074,10000,-19.23901135,199.0726861,0,-14.03629709,0,95.52185733 +170.61,50.30153445,-3.177591176,10000,-19.21812208,199.0740312,0,-14.03629709,0,95.51483138 +170.62,50.30153272,-3.177563278,10000,-19.20071435,199.0753764,0,-14.03629709,0,95.50780548 +170.63,50.301531,-3.17753538,10000,-19.17634353,199.0778365,0,-14.03629709,0,95.50077953 +170.64,50.30152928,-3.177507481,10000,-19.14849116,199.0809656,0,-14.03629709,0,95.49375363 +170.65,50.30152756,-3.177479582,10000,-19.12412035,199.0834257,0,-14.03629709,0,95.48672768 +170.66,50.30152585,-3.177451682,10000,-19.10323109,199.0849938,0,-14.03629709,0,95.47970179 +170.67,50.30152413,-3.177423783,10000,-19.07189719,199.0872309,0,-14.03629709,0,95.47267583 +170.68,50.30152242,-3.177395883,10000,-19.03360019,199.0908059,0,-14.03629709,0,95.46564994 +170.69,50.30152072,-3.177367982,10000,-19.01619247,199.0941579,0,-14.03629709,0,95.45862399 +170.7,50.30151901,-3.177340081,10000,-19.01271092,199.096395,0,-14.03629709,0,95.45159809 +170.71,50.3015173,-3.17731218,10000,-18.99182165,199.0979631,0,-14.03629709,0,95.44457214 +170.72,50.3015156,-3.177284278,10000,-18.95700621,199.0993081,0,-14.03629709,0,95.43754625 +170.73,50.3015139,-3.177256377,10000,-18.92567233,199.1015452,0,-14.03629709,0,95.43052029 +170.74,50.3015122,-3.177228475,10000,-18.90130152,199.1051202,0,-14.03629709,0,95.4234944 +170.75,50.30151051,-3.177200572,10000,-18.88389378,199.1082491,0,-14.03629709,0,95.41646845 +170.76,50.30150881,-3.177172669,10000,-18.86300451,199.1098172,0,-14.03629709,0,95.40944255 +170.77,50.30150712,-3.177144766,10000,-18.82818906,199.1111622,0,-14.03629709,0,95.40241666 +170.78,50.30150543,-3.177116863,10000,-18.79337362,199.1136222,0,-14.03629709,0,95.3953907 +170.79,50.30150375,-3.177088959,10000,-18.77248436,199.1167511,0,-14.03629709,0,95.38836481 +170.8,50.30150206,-3.177061055,10000,-18.75507662,199.1192111,0,-14.03629709,0,95.38133886 +170.81,50.30150038,-3.17703315,10000,-18.7307058,199.120556,0,-14.03629709,0,95.37431296 +170.82,50.3014987,-3.177005246,10000,-18.70285345,199.121901,0,-14.03629709,0,95.36728701 +170.83,50.30149702,-3.176977341,10000,-18.67848264,199.1243609,0,-14.03629709,0,95.36026111 +170.84,50.30149535,-3.176949436,10000,-18.66107492,199.1274899,0,-14.03629709,0,95.35323516 +170.85,50.30149367,-3.17692153,10000,-18.6436672,199.1301728,0,-14.03629709,0,95.34620927 +170.86,50.301492,-3.176893624,10000,-18.61929639,199.1324097,0,-14.03629709,0,95.33918331 +170.87,50.30149033,-3.176865718,10000,-18.5879625,199.1348696,0,-14.03629709,0,95.33215742 +170.88,50.30148866,-3.176837811,10000,-18.54966551,199.1373295,0,-14.03629709,0,95.32513147 +170.89,50.301487,-3.176809904,10000,-18.51485005,199.1395663,0,-14.03629709,0,95.31810557 +170.9,50.30148534,-3.176781997,10000,-18.49744233,199.1420262,0,-14.03629709,0,95.31107962 +170.91,50.30148368,-3.176754089,10000,-18.49047924,199.1444861,0,-14.03629709,0,95.30405373 +170.92,50.30148202,-3.176726181,10000,-18.47307152,199.1464999,0,-14.03629709,0,95.29702777 +170.93,50.30148036,-3.176698273,10000,-18.43825606,199.1480678,0,-14.03629709,0,95.29000188 +170.94,50.30147871,-3.176670364,10000,-18.40344061,199.1491897,0,-14.03629709,0,95.28297593 +170.95,50.30147706,-3.176642456,10000,-18.3860329,199.1505345,0,-14.03629709,0,95.27595003 +170.96,50.30147541,-3.176614547,10000,-18.37906982,199.1529943,0,-14.03629709,0,95.26892408 +170.97,50.30147376,-3.176586638,10000,-18.3616621,199.1563461,0,-14.03629709,0,95.26189818 +170.98,50.30147211,-3.176558728,10000,-18.32684664,199.1599209,0,-14.03629709,0,95.25487223 +170.99,50.30147047,-3.176530818,10000,-18.29203119,199.1632727,0,-14.03629709,0,95.24784634 +171,50.30146883,-3.176502907,10000,-18.27114193,199.1657324,0,-14.03629709,0,95.24082038 +171.01,50.30146719,-3.176474996,10000,-18.25025265,199.1670773,0,-14.03629709,0,95.23379449 +171.02,50.30146555,-3.176447085,10000,-18.21543721,199.168422,0,-14.03629709,0,95.22676854 +171.03,50.30146392,-3.176419174,10000,-18.18062178,199.1706588,0,-14.03629709,0,95.21974264 +171.04,50.30146229,-3.176391262,10000,-18.15973252,199.1728955,0,-14.03629709,0,95.21271669 +171.05,50.30146066,-3.17636335,10000,-18.14232479,199.1744633,0,-14.03629709,0,95.20569079 +171.06,50.30145903,-3.176335438,10000,-18.12143551,199.176477,0,-14.03629709,0,95.19866484 +171.07,50.30145741,-3.176307526,10000,-18.10402778,199.1791598,0,-14.03629709,0,95.19163895 +171.08,50.30145578,-3.176279612,10000,-18.08662006,199.1813965,0,-14.03629709,0,95.184613 +171.09,50.30145416,-3.1762517,10000,-18.06224925,199.1836332,0,-14.03629709,0,95.1775871 +171.1,50.30145254,-3.176223786,10000,-18.03091535,199.1865389,0,-14.03629709,0,95.17056115 +171.11,50.30145092,-3.176195872,10000,-17.99261837,199.1892215,0,-14.03629709,0,95.16353525 +171.12,50.30144931,-3.176167958,10000,-17.95780293,199.1910122,0,-14.03629709,0,95.1565093 +171.13,50.3014477,-3.176140043,10000,-17.94039521,199.1923569,0,-14.03629709,0,95.14948341 +171.14,50.30144609,-3.176112129,10000,-17.93343211,199.1945936,0,-14.03629709,0,95.14245745 +171.15,50.30144448,-3.176084214,10000,-17.91602438,199.1979452,0,-14.03629709,0,95.13543156 +171.16,50.30144287,-3.176056298,10000,-17.88120894,199.2001818,0,-14.03629709,0,95.12840566 +171.17,50.30144127,-3.176028382,10000,-17.8463935,199.2006345,0,-14.03629709,0,95.12137971 +171.18,50.30143967,-3.176000467,10000,-17.82550423,199.2019792,0,-14.03629709,0,95.11435382 +171.19,50.30143807,-3.175972551,10000,-17.80461496,199.2053308,0,-14.03629709,0,95.10732786 +171.2,50.30143647,-3.175944634,10000,-17.77328106,199.2086823,0,-14.03629709,0,95.10030197 +171.21,50.30143488,-3.175916717,10000,-17.74891025,199.2111419,0,-14.03629709,0,95.09327602 +171.22,50.30143329,-3.1758888,10000,-17.73498408,199.2136015,0,-14.03629709,0,95.08625012 +171.23,50.30143169,-3.175860882,10000,-17.71061328,199.2158381,0,-14.03629709,0,95.07922417 +171.24,50.30143011,-3.175832964,10000,-17.67927938,199.2171827,0,-14.03629709,0,95.07219827 +171.25,50.30142852,-3.175805046,10000,-17.6583901,199.2185273,0,-14.03629709,0,95.06517232 +171.26,50.30142694,-3.175777128,10000,-17.63750082,199.2207638,0,-14.03629709,0,95.05814643 +171.27,50.30142535,-3.175749209,10000,-17.60616692,199.2232234,0,-14.03629709,0,95.05112048 +171.28,50.30142378,-3.17572129,10000,-17.58179611,199.2254599,0,-14.03629709,0,95.04409458 +171.29,50.3014222,-3.175693371,10000,-17.56786993,199.2279194,0,-14.03629709,0,95.03706863 +171.3,50.30142062,-3.175665451,10000,-17.54349913,199.2301559,0,-14.03629709,0,95.03004273 +171.31,50.30141905,-3.175637531,10000,-17.51216524,199.2315005,0,-14.03629709,0,95.02301678 +171.32,50.30141748,-3.175609611,10000,-17.49127597,199.232845,0,-14.03629709,0,95.01599089 +171.33,50.30141591,-3.175581691,10000,-17.47038669,199.2353045,0,-14.03629709,0,95.00896493 +171.34,50.30141434,-3.17555377,10000,-17.43557125,199.2384329,0,-14.03629709,0,95.00193904 +171.35,50.30141278,-3.175525849,10000,-17.40075582,199.2408924,0,-14.03629709,0,94.99491309 +171.36,50.30141122,-3.175497927,10000,-17.37986655,199.2424599,0,-14.03629709,0,94.98788719 +171.37,50.30140966,-3.175470006,10000,-17.3624588,199.2444733,0,-14.03629709,0,94.98086124 +171.38,50.3014081,-3.175442084,10000,-17.34156952,199.2471558,0,-14.03629709,0,94.97383534 +171.39,50.30140655,-3.175414161,10000,-17.32416182,199.2491692,0,-14.03629709,0,94.96680939 +171.4,50.30140499,-3.175386239,10000,-17.30327257,199.2507366,0,-14.03629709,0,94.9597835 +171.41,50.30140344,-3.175358316,10000,-17.26845712,199.2531961,0,-14.03629709,0,94.95275754 +171.42,50.30140189,-3.175330393,10000,-17.23364168,199.2561014,0,-14.03629709,0,94.94573165 +171.43,50.30140035,-3.175302469,10000,-17.21275241,199.2578919,0,-14.03629709,0,94.9387057 +171.44,50.3013988,-3.175274545,10000,-17.19534468,199.2587903,0,-14.03629709,0,94.9316798 +171.45,50.30139726,-3.175246622,10000,-17.17097387,199.2605807,0,-14.03629709,0,94.92465385 +171.46,50.30139572,-3.175218697,10000,-17.14312152,199.263709,0,-14.03629709,0,94.91762796 +171.47,50.30139418,-3.175190773,10000,-17.11875072,199.2670604,0,-14.03629709,0,94.910602 +171.48,50.30139265,-3.175162847,10000,-17.10134299,199.2695197,0,-14.03629709,0,94.90357611 +171.49,50.30139111,-3.175134922,10000,-17.08045372,199.2708641,0,-14.03629709,0,94.89655016 +171.5,50.30138958,-3.175106996,10000,-17.04563827,199.2722084,0,-14.03629709,0,94.88952426 +171.51,50.30138805,-3.175079071,10000,-17.01082282,199.2744448,0,-14.03629709,0,94.88249831 +171.52,50.30138653,-3.175051144,10000,-16.98993356,199.2766811,0,-14.03629709,0,94.87547241 +171.53,50.301385,-3.175023218,10000,-16.97252584,199.2780254,0,-14.03629709,0,94.86844646 +171.54,50.30138348,-3.174995291,10000,-16.94815503,199.2795927,0,-14.03629709,0,94.86142057 +171.55,50.30138196,-3.174967365,10000,-16.92030268,199.282498,0,-14.03629709,0,94.85439461 +171.56,50.30138044,-3.174939437,10000,-16.89593187,199.2851803,0,-14.03629709,0,94.84736872 +171.57,50.30137893,-3.174911509,10000,-16.87852415,199.2863016,0,-14.03629709,0,94.84034282 +171.58,50.30137741,-3.174883582,10000,-16.86111643,199.2878688,0,-14.03629709,0,94.83331687 +171.59,50.3013759,-3.174855654,10000,-16.83674561,199.2909971,0,-14.03629709,0,94.82629098 +171.6,50.30137439,-3.174827725,10000,-16.8054117,199.2934563,0,-14.03629709,0,94.81926502 +171.61,50.30137288,-3.174799796,10000,-16.76711472,199.2945776,0,-14.03629709,0,94.81223913 +171.62,50.30137138,-3.174771868,10000,-16.73229928,199.2961448,0,-14.03629709,0,94.80521318 +171.63,50.30136988,-3.174743938,10000,-16.71489156,199.298604,0,-14.03629709,0,94.79818728 +171.64,50.30136838,-3.174716009,10000,-16.70792846,199.3015092,0,-14.03629709,0,94.79116133 +171.65,50.30136688,-3.174688079,10000,-16.69052075,199.3044144,0,-14.03629709,0,94.78413544 +171.66,50.30136538,-3.174660148,10000,-16.65570531,199.3062046,0,-14.03629709,0,94.77710948 +171.67,50.30136389,-3.174632218,10000,-16.62088987,199.3068798,0,-14.03629709,0,94.77008359 +171.68,50.3013624,-3.174604287,10000,-16.60348214,199.308224,0,-14.03629709,0,94.76305764 +171.69,50.30136091,-3.174576357,10000,-16.59651905,199.3111292,0,-14.03629709,0,94.75603174 +171.7,50.30135942,-3.174548425,10000,-16.57911132,199.3140343,0,-14.03629709,0,94.74900579 +171.71,50.30135793,-3.174520493,10000,-16.54429588,199.3158245,0,-14.03629709,0,94.74197989 +171.72,50.30135645,-3.174492562,10000,-16.50599891,199.3176146,0,-14.03629709,0,94.73495394 +171.73,50.30135497,-3.174464629,10000,-16.474665,199.3198508,0,-14.03629709,0,94.72792805 +171.74,50.30135349,-3.174436697,10000,-16.45029417,199.3218639,0,-14.03629709,0,94.72090209 +171.75,50.30135202,-3.174408764,10000,-16.43288645,199.323431,0,-14.03629709,0,94.7138762 +171.76,50.30135054,-3.174380831,10000,-16.41547874,199.3245521,0,-14.03629709,0,94.70685025 +171.77,50.30134907,-3.174352898,10000,-16.39110795,199.3258963,0,-14.03629709,0,94.69982435 +171.78,50.3013476,-3.174324965,10000,-16.36325559,199.3283553,0,-14.03629709,0,94.6927984 +171.79,50.30134613,-3.174297031,10000,-16.33888477,199.3317064,0,-14.03629709,0,94.6857725 +171.8,50.30134467,-3.174269097,10000,-16.32147705,199.3350574,0,-14.03629709,0,94.67874655 +171.81,50.3013432,-3.174241162,10000,-16.30058778,199.3375165,0,-14.03629709,0,94.67172066 +171.82,50.30134174,-3.174213227,10000,-16.26577233,199.3386375,0,-14.03629709,0,94.66469471 +171.83,50.30134028,-3.174185292,10000,-16.23095689,199.3390896,0,-14.03629709,0,94.65766881 +171.84,50.30133883,-3.174157357,10000,-16.21006763,199.3402107,0,-14.03629709,0,94.65064286 +171.85,50.30133737,-3.174129422,10000,-16.19265991,199.3424467,0,-14.03629709,0,94.64361696 +171.86,50.30133592,-3.174101486,10000,-16.16828909,199.3449057,0,-14.03629709,0,94.63659101 +171.87,50.30133447,-3.17407355,10000,-16.14043673,199.3471417,0,-14.03629709,0,94.62956512 +171.88,50.30133302,-3.174045614,10000,-16.11606592,199.3496007,0,-14.03629709,0,94.62253916 +171.89,50.30133158,-3.174017677,10000,-16.09865822,199.3520597,0,-14.03629709,0,94.61551327 +171.9,50.30133013,-3.17398974,10000,-16.07776896,199.3540727,0,-14.03629709,0,94.60848732 +171.91,50.30132869,-3.173961803,10000,-16.0429535,199.3556396,0,-14.03629709,0,94.60146142 +171.92,50.30132725,-3.173933865,10000,-16.00813804,199.3569836,0,-14.03629709,0,94.59443547 +171.93,50.30132582,-3.173905928,10000,-15.98724878,199.3589966,0,-14.03629709,0,94.58740957 +171.94,50.30132438,-3.17387799,10000,-15.96984107,199.3616785,0,-14.03629709,0,94.58038362 +171.95,50.30132295,-3.173850051,10000,-15.94895181,199.3636914,0,-14.03629709,0,94.57335773 +171.96,50.30132152,-3.173822113,10000,-15.93154409,199.3650354,0,-14.03629709,0,94.56633183 +171.97,50.30132009,-3.173794174,10000,-15.91065482,199.3666023,0,-14.03629709,0,94.55930588 +171.98,50.30131866,-3.173766235,10000,-15.87583937,199.3686152,0,-14.03629709,0,94.55227998 +171.99,50.30131724,-3.173738296,10000,-15.84102393,199.3710741,0,-14.03629709,0,94.54525403 +172,50.30131582,-3.173710356,10000,-15.82013467,199.37331,0,-14.03629709,0,94.53822814 +172.01,50.3013144,-3.173682416,10000,-15.80272695,199.3746539,0,-14.03629709,0,94.53120219 +172.02,50.30131298,-3.173654476,10000,-15.78183768,199.3759978,0,-14.03629709,0,94.52417629 +172.03,50.30131157,-3.173626536,10000,-15.7609484,199.3782336,0,-14.03629709,0,94.51715034 +172.04,50.30131015,-3.173598595,10000,-15.7296145,199.3806925,0,-14.03629709,0,94.51012444 +172.05,50.30130874,-3.173570654,10000,-15.68783599,199.3829283,0,-14.03629709,0,94.50309849 +172.06,50.30130734,-3.173542713,10000,-15.65998365,199.3853871,0,-14.03629709,0,94.4960726 +172.07,50.30130593,-3.173514771,10000,-15.65302055,199.3876229,0,-14.03629709,0,94.48904664 +172.08,50.30130453,-3.173486829,10000,-15.64605746,199.3887438,0,-14.03629709,0,94.48202075 +172.09,50.30130312,-3.173458887,10000,-15.61820511,199.3891956,0,-14.03629709,0,94.4749948 +172.1,50.30130172,-3.173430945,10000,-15.57642657,199.3905395,0,-14.03629709,0,94.4679689 +172.11,50.30130033,-3.173403003,10000,-15.54509266,199.3936672,0,-14.03629709,0,94.46094295 +172.12,50.30129893,-3.17337506,10000,-15.5242034,199.397018,0,-14.03629709,0,94.45391705 +172.13,50.30129754,-3.173347116,10000,-15.50331414,199.3985847,0,-14.03629709,0,94.4468911 +172.14,50.30129615,-3.173319173,10000,-15.48590641,199.3994825,0,-14.03629709,0,94.43986521 +172.15,50.30129476,-3.17329123,10000,-15.46501713,199.4012723,0,-14.03629709,0,94.43283925 +172.16,50.30129337,-3.173263285,10000,-15.43020169,199.403285,0,-14.03629709,0,94.42581336 +172.17,50.30129199,-3.173235342,10000,-15.39538626,199.4055208,0,-14.03629709,0,94.41878741 +172.18,50.30129061,-3.173207397,10000,-15.37797855,199.4082025,0,-14.03629709,0,94.41176151 +172.19,50.30128923,-3.173179452,10000,-15.37101547,199.4099922,0,-14.03629709,0,94.40473556 +172.2,50.30128785,-3.173151507,10000,-15.35360775,199.4106669,0,-14.03629709,0,94.39770967 +172.21,50.30128647,-3.173123562,10000,-15.31879229,199.4117877,0,-14.03629709,0,94.39068371 +172.22,50.3012851,-3.173095617,10000,-15.28397684,199.4140234,0,-14.03629709,0,94.38365782 +172.23,50.30128373,-3.173067671,10000,-15.26308757,199.416482,0,-14.03629709,0,94.37663187 +172.24,50.30128236,-3.173039725,10000,-15.24219832,199.4187177,0,-14.03629709,0,94.36960597 +172.25,50.30128099,-3.173011779,10000,-15.20738289,199.4211764,0,-14.03629709,0,94.36258002 +172.26,50.30127963,-3.172983832,10000,-15.17256746,199.423635,0,-14.03629709,0,94.35555412 +172.27,50.30127827,-3.172955885,10000,-15.15515973,199.4256476,0,-14.03629709,0,94.34852817 +172.28,50.30127691,-3.172927938,10000,-15.14819662,199.4269913,0,-14.03629709,0,94.34150228 +172.29,50.30127555,-3.17289999,10000,-15.1307889,199.427443,0,-14.03629709,0,94.33447632 +172.3,50.30127419,-3.172872043,10000,-15.09597346,199.4283406,0,-14.03629709,0,94.32745043 +172.31,50.30127284,-3.172844096,10000,-15.06115802,199.4310222,0,-14.03629709,0,94.32042448 +172.32,50.30127149,-3.172816147,10000,-15.04026876,199.4341498,0,-14.03629709,0,94.31339858 +172.33,50.30127014,-3.172788199,10000,-15.0193795,199.4363853,0,-14.03629709,0,94.30637263 +172.34,50.30126879,-3.17276025,10000,-14.98456406,199.4379519,0,-14.03629709,0,94.29934673 +172.35,50.30126745,-3.172732301,10000,-14.94974861,199.4390725,0,-14.03629709,0,94.29232078 +172.36,50.30126611,-3.172704352,10000,-14.93234089,199.4404161,0,-14.03629709,0,94.28529489 +172.37,50.30126477,-3.172676403,10000,-14.9253778,199.4426517,0,-14.03629709,0,94.27826899 +172.38,50.30126343,-3.172648453,10000,-14.90797008,199.4448872,0,-14.03629709,0,94.27124304 +172.39,50.30126209,-3.172620503,10000,-14.87315464,199.4462307,0,-14.03629709,0,94.26421715 +172.4,50.30126076,-3.172592553,10000,-14.8383392,199.4473513,0,-14.03629709,0,94.25719119 +172.41,50.30125943,-3.172564603,10000,-14.82093148,199.4489178,0,-14.03629709,0,94.2501653 +172.42,50.3012581,-3.172536652,10000,-14.81396838,199.4509303,0,-14.03629709,0,94.24313935 +172.43,50.30125677,-3.172508702,10000,-14.79656065,199.4533888,0,-14.03629709,0,94.23611345 +172.44,50.30125544,-3.17248075,10000,-14.76174522,199.4558473,0,-14.03629709,0,94.2290875 +172.45,50.30125412,-3.172452799,10000,-14.72344824,199.4578598,0,-14.03629709,0,94.2220616 +172.46,50.3012528,-3.172424847,10000,-14.69211435,199.4596493,0,-14.03629709,0,94.21503565 +172.47,50.30125148,-3.172396895,10000,-14.66774353,199.4614387,0,-14.03629709,0,94.20800976 +172.48,50.30125017,-3.172368943,10000,-14.6503358,199.4630052,0,-14.03629709,0,94.2009838 +172.49,50.30124885,-3.17234099,10000,-14.63292809,199.4641257,0,-14.03629709,0,94.19395791 +172.5,50.30124754,-3.172313038,10000,-14.60855729,199.4654691,0,-14.03629709,0,94.18693196 +172.51,50.30124623,-3.172285085,10000,-14.57722338,199.4677046,0,-14.03629709,0,94.17990606 +172.52,50.30124492,-3.172257132,10000,-14.54240794,199.46994,0,-14.03629709,0,94.17288011 +172.53,50.30124362,-3.172229178,10000,-14.51803713,199.4712834,0,-14.03629709,0,94.16585421 +172.54,50.30124232,-3.172201225,10000,-14.50411097,199.4726268,0,-14.03629709,0,94.15882826 +172.55,50.30124101,-3.172173271,10000,-14.47974016,199.4748622,0,-14.03629709,0,94.15180237 +172.56,50.30123972,-3.172145317,10000,-14.44840627,199.4773206,0,-14.03629709,0,94.14477642 +172.57,50.30123842,-3.172117362,10000,-14.43099853,199.4795559,0,-14.03629709,0,94.13775052 +172.58,50.30123713,-3.172089408,10000,-14.42055388,199.4817913,0,-14.03629709,0,94.13072457 +172.59,50.30123583,-3.172061452,10000,-14.39270153,199.4833577,0,-14.03629709,0,94.12369867 +172.6,50.30123454,-3.172033497,10000,-14.35092301,199.484032,0,-14.03629709,0,94.11667272 +172.61,50.30123326,-3.172005542,10000,-14.31958912,199.4849294,0,-14.03629709,0,94.10964683 +172.62,50.30123197,-3.171977586,10000,-14.29869986,199.4867187,0,-14.03629709,0,94.10262087 +172.63,50.30123069,-3.171949631,10000,-14.2778106,199.488954,0,-14.03629709,0,94.09559498 +172.64,50.30122941,-3.171921674,10000,-14.26040287,199.4905204,0,-14.03629709,0,94.08856903 +172.65,50.30122813,-3.171893718,10000,-14.24299514,199.4916407,0,-14.03629709,0,94.08154313 +172.66,50.30122685,-3.171865762,10000,-14.22210587,199.494099,0,-14.03629709,0,94.07451718 +172.67,50.30122558,-3.171837805,10000,-14.20121661,199.4974492,0,-14.03629709,0,94.06749128 +172.68,50.3012243,-3.171809847,10000,-14.16988272,199.4994615,0,-14.03629709,0,94.06046533 +172.69,50.30122303,-3.17178189,10000,-14.1281042,199.4999128,0,-14.03629709,0,94.05343944 +172.7,50.30122177,-3.171753932,10000,-14.0967703,199.5003641,0,-14.03629709,0,94.04641348 +172.71,50.3012205,-3.171725975,10000,-14.07588103,199.5023763,0,-14.03629709,0,94.03938759 +172.72,50.30121924,-3.171698017,10000,-14.05499178,199.5057265,0,-14.03629709,0,94.03236164 +172.73,50.30121798,-3.171670058,10000,-14.03758405,199.5079617,0,-14.03629709,0,94.02533574 +172.74,50.30121672,-3.171642099,10000,-14.02017632,199.508413,0,-14.03629709,0,94.01830979 +172.75,50.30121546,-3.171614141,10000,-13.99928705,199.5095332,0,-14.03629709,0,94.0112839 +172.76,50.30121421,-3.171586182,10000,-13.98187934,199.5119914,0,-14.03629709,0,94.004258 +172.77,50.30121295,-3.171558222,10000,-13.96099007,199.5140036,0,-14.03629709,0,93.99723205 +172.78,50.3012117,-3.171530263,10000,-13.92269308,199.5153468,0,-14.03629709,0,93.99020615 +172.79,50.30121045,-3.171502303,10000,-13.87743301,199.516913,0,-14.03629709,0,93.9831802 +172.8,50.30120921,-3.171474343,10000,-13.85306221,199.5187022,0,-14.03629709,0,93.97615431 +172.81,50.30120797,-3.171446383,10000,-13.84958067,199.5202683,0,-14.03629709,0,93.96912835 +172.82,50.30120672,-3.171418422,10000,-13.83217296,199.5213885,0,-14.03629709,0,93.96210246 +172.83,50.30120548,-3.171390462,10000,-13.79387597,199.5227317,0,-14.03629709,0,93.95507651 +172.84,50.30120425,-3.171362501,10000,-13.76254205,199.5249668,0,-14.03629709,0,93.94805061 +172.85,50.30120301,-3.17133454,10000,-13.74165279,199.5272019,0,-14.03629709,0,93.94102466 +172.86,50.30120178,-3.171306578,10000,-13.72076353,199.528545,0,-14.03629709,0,93.93399876 +172.87,50.30120055,-3.171278617,10000,-13.70335582,199.5296651,0,-14.03629709,0,93.92697281 +172.88,50.30119932,-3.171250655,10000,-13.68246655,199.5312312,0,-14.03629709,0,93.91994692 +172.89,50.30119809,-3.171222693,10000,-13.64765112,199.5332433,0,-14.03629709,0,93.91292096 +172.9,50.30119687,-3.171194731,10000,-13.61283568,199.5357014,0,-14.03629709,0,93.90589507 +172.91,50.30119565,-3.171166768,10000,-13.5919464,199.5379364,0,-14.03629709,0,93.89886912 +172.92,50.30119443,-3.171138805,10000,-13.57453868,199.5392795,0,-14.03629709,0,93.89184322 +172.93,50.30119321,-3.171110842,10000,-13.55364942,199.5406226,0,-14.03629709,0,93.88481727 +172.94,50.301192,-3.171082879,10000,-13.5362417,199.5426346,0,-14.03629709,0,93.87779138 +172.95,50.30119078,-3.171054915,10000,-13.51535242,199.5442007,0,-14.03629709,0,93.87076542 +172.96,50.30118957,-3.171026951,10000,-13.48053699,199.5450977,0,-14.03629709,0,93.86373953 +172.97,50.30118836,-3.170998988,10000,-13.44572156,199.5466637,0,-14.03629709,0,93.85671358 +172.98,50.30118716,-3.170971023,10000,-13.4248323,199.5488987,0,-14.03629709,0,93.84968768 +172.99,50.30118595,-3.170943059,10000,-13.40742458,199.5509107,0,-14.03629709,0,93.84266173 +173,50.30118475,-3.170915094,10000,-13.38305377,199.5524767,0,-14.03629709,0,93.83563583 +173.01,50.30118355,-3.170887129,10000,-13.35171987,199.5535967,0,-14.03629709,0,93.82860988 +173.02,50.30118235,-3.170859164,10000,-13.31342287,199.5547167,0,-14.03629709,0,93.82158399 +173.03,50.30118116,-3.170831199,10000,-13.27860743,199.5560596,0,-14.03629709,0,93.81455803 +173.04,50.30117997,-3.170803233,10000,-13.26119971,199.5574026,0,-14.03629709,0,93.80753214 +173.05,50.30117878,-3.170775268,10000,-13.25423662,199.5594145,0,-14.03629709,0,93.80050619 +173.06,50.30117759,-3.170747302,10000,-13.24031045,199.5620954,0,-14.03629709,0,93.79348029 +173.07,50.3011764,-3.170719335,10000,-13.21942119,199.5641074,0,-14.03629709,0,93.78645434 +173.08,50.30117522,-3.170691369,10000,-13.19853193,199.5654503,0,-14.03629709,0,93.77942844 +173.09,50.30117403,-3.170663402,10000,-13.16719802,199.5667932,0,-14.03629709,0,93.77240249 +173.1,50.30117285,-3.170635435,10000,-13.1254195,199.5679131,0,-14.03629709,0,93.7653766 +173.11,50.30117168,-3.170607468,10000,-13.09756716,199.569256,0,-14.03629709,0,93.75835065 +173.12,50.3011705,-3.170579501,10000,-13.08712253,199.5714909,0,-14.03629709,0,93.75132475 +173.13,50.30116933,-3.170551533,10000,-13.06971479,199.5737257,0,-14.03629709,0,93.7442988 +173.14,50.30116815,-3.170523565,10000,-13.03838089,199.5750686,0,-14.03629709,0,93.7372729 +173.15,50.30116699,-3.170495597,10000,-13.0140101,199.5764115,0,-14.03629709,0,93.73024695 +173.16,50.30116582,-3.170467629,10000,-13.00008393,199.5784233,0,-14.03629709,0,93.72322106 +173.17,50.30116465,-3.17043966,10000,-12.97571312,199.5799892,0,-14.03629709,0,93.71619516 +173.18,50.30116349,-3.170411691,10000,-12.94089767,199.580886,0,-14.03629709,0,93.70916921 +173.19,50.30116233,-3.170383723,10000,-12.90956376,199.5822288,0,-14.03629709,0,93.70214331 +173.2,50.30116117,-3.170355753,10000,-12.88519296,199.5835716,0,-14.03629709,0,93.69511736 +173.21,50.30116002,-3.170327784,10000,-12.86778525,199.5846914,0,-14.03629709,0,93.68809147 +173.22,50.30115886,-3.170299815,10000,-12.84689598,199.5871492,0,-14.03629709,0,93.68106551 +173.23,50.30115771,-3.170271845,10000,-12.81208054,199.590276,0,-14.03629709,0,93.67403962 +173.24,50.30115656,-3.170243874,10000,-12.77726511,199.5916187,0,-14.03629709,0,93.66701367 +173.25,50.30115542,-3.170215904,10000,-12.75637584,199.5918465,0,-14.03629709,0,93.65998777 +173.26,50.30115427,-3.170187934,10000,-12.73896811,199.5931893,0,-14.03629709,0,93.65296182 +173.27,50.30115313,-3.170159963,10000,-12.71807884,199.595424,0,-14.03629709,0,93.64593592 +173.28,50.30115199,-3.170131992,10000,-12.70067114,199.5974358,0,-14.03629709,0,93.63890997 +173.29,50.30115085,-3.170104021,10000,-12.67978187,199.5990015,0,-14.03629709,0,93.63188408 +173.3,50.30114971,-3.170076049,10000,-12.64496642,199.6001212,0,-14.03629709,0,93.62485813 +173.31,50.30114858,-3.170048078,10000,-12.61015098,199.6012409,0,-14.03629709,0,93.61783223 +173.32,50.30114745,-3.170020106,10000,-12.58926173,199.6025836,0,-14.03629709,0,93.61080628 +173.33,50.30114632,-3.169992134,10000,-12.57185402,199.6037033,0,-14.03629709,0,93.60378038 +173.34,50.30114519,-3.169964162,10000,-12.55096475,199.605046,0,-14.03629709,0,93.59675443 +173.35,50.30114407,-3.16993619,10000,-12.53355702,199.6072807,0,-14.03629709,0,93.58972854 +173.36,50.30114294,-3.169908217,10000,-12.51266776,199.6097383,0,-14.03629709,0,93.58270258 +173.37,50.30114182,-3.169880244,10000,-12.47785233,199.61175,0,-14.03629709,0,93.57567669 +173.38,50.3011407,-3.169852271,10000,-12.44303689,199.6133156,0,-14.03629709,0,93.56865074 +173.39,50.30113959,-3.169824297,10000,-12.42214762,199.6144353,0,-14.03629709,0,93.56162484 +173.4,50.30113847,-3.169796324,10000,-12.4047399,199.6155549,0,-14.03629709,0,93.55459889 +173.41,50.30113736,-3.16976835,10000,-12.38036909,199.6168975,0,-14.03629709,0,93.54757299 +173.42,50.30113625,-3.169740376,10000,-12.34903519,199.6180172,0,-14.03629709,0,93.54054704 +173.43,50.30113514,-3.169712402,10000,-12.31073821,199.6191368,0,-14.03629709,0,93.53352115 +173.44,50.30113404,-3.169684428,10000,-12.27592277,199.6204794,0,-14.03629709,0,93.52649519 +173.45,50.30113294,-3.169656453,10000,-12.25851506,199.6218219,0,-14.03629709,0,93.5194693 +173.46,50.30113184,-3.169628479,10000,-12.25155197,199.6238335,0,-14.03629709,0,93.51244335 +173.47,50.30113074,-3.169600504,10000,-12.23762578,199.626514,0,-14.03629709,0,93.50541745 +173.48,50.30112964,-3.169572528,10000,-12.21673651,199.6285256,0,-14.03629709,0,93.4983915 +173.49,50.30112855,-3.169544553,10000,-12.19584725,199.6296451,0,-14.03629709,0,93.49136561 +173.5,50.30112745,-3.169516577,10000,-12.16451337,199.6303187,0,-14.03629709,0,93.48433965 +173.51,50.30112636,-3.169488601,10000,-12.12273485,199.6309923,0,-14.03629709,0,93.47731376 +173.52,50.30112528,-3.169460626,10000,-12.09140094,199.6323348,0,-14.03629709,0,93.47028781 +173.53,50.30112419,-3.169432649,10000,-12.07051167,199.6336773,0,-14.03629709,0,93.46326191 +173.54,50.30112311,-3.169404673,10000,-12.04962241,199.6345738,0,-14.03629709,0,93.45623596 +173.55,50.30112203,-3.169376697,10000,-12.0322147,199.6363623,0,-14.03629709,0,93.44921006 +173.56,50.30112095,-3.16934872,10000,-12.01480698,199.6392657,0,-14.03629709,0,93.44218411 +173.57,50.30111987,-3.169320743,10000,-11.99391772,199.6417232,0,-14.03629709,0,93.43515822 +173.58,50.3011188,-3.169292765,10000,-11.97302845,199.6430657,0,-14.03629709,0,93.42813232 +173.59,50.30111772,-3.169264788,10000,-11.94169455,199.6441851,0,-14.03629709,0,93.42110637 +173.6,50.30111665,-3.16923681,10000,-11.89991602,199.6455276,0,-14.03629709,0,93.41408047 +173.61,50.30111559,-3.169208832,10000,-11.86858212,199.646647,0,-14.03629709,0,93.40705452 +173.62,50.30111452,-3.169180854,10000,-11.84769286,199.6479894,0,-14.03629709,0,93.40002863 +173.63,50.30111346,-3.169152876,10000,-11.8268036,199.6500008,0,-14.03629709,0,93.39300267 +173.64,50.3011124,-3.169124897,10000,-11.81287743,199.6515663,0,-14.03629709,0,93.38597678 +173.65,50.30111134,-3.169096918,10000,-11.80591435,199.6524627,0,-14.03629709,0,93.37895083 +173.66,50.30111028,-3.16906894,10000,-11.78850663,199.6538051,0,-14.03629709,0,93.37192493 +173.67,50.30110922,-3.16904096,10000,-11.75369118,199.6551475,0,-14.03629709,0,93.36489898 +173.68,50.30110817,-3.169012981,10000,-11.7153942,199.6560439,0,-14.03629709,0,93.35787309 +173.69,50.30110712,-3.168985002,10000,-11.6840603,199.6576092,0,-14.03629709,0,93.35084713 +173.7,50.30110607,-3.168957022,10000,-11.6596895,199.6596206,0,-14.03629709,0,93.34382124 +173.71,50.30110503,-3.168929042,10000,-11.64228178,199.6609629,0,-14.03629709,0,93.33679529 +173.72,50.30110398,-3.168901062,10000,-11.62487406,199.6620823,0,-14.03629709,0,93.32976939 +173.73,50.30110294,-3.168873082,10000,-11.60050325,199.6634246,0,-14.03629709,0,93.32274344 +173.74,50.3011019,-3.168845101,10000,-11.56916936,199.6645439,0,-14.03629709,0,93.31571754 +173.75,50.30110086,-3.168817121,10000,-11.53087239,199.6658862,0,-14.03629709,0,93.30869159 +173.76,50.30109983,-3.16878914,10000,-11.49605695,199.6681205,0,-14.03629709,0,93.3016657 +173.77,50.3010988,-3.168761159,10000,-11.47864922,199.6703548,0,-14.03629709,0,93.29463974 +173.78,50.30109777,-3.168733177,10000,-11.47168612,199.6716971,0,-14.03629709,0,93.28761385 +173.79,50.30109674,-3.168705196,10000,-11.45427839,199.6725933,0,-14.03629709,0,93.2805879 +173.8,50.30109571,-3.168677214,10000,-11.41946295,199.6732666,0,-14.03629709,0,93.273562 +173.81,50.30109469,-3.168649232,10000,-11.38464752,199.6739399,0,-14.03629709,0,93.26653605 +173.82,50.30109367,-3.168621251,10000,-11.36723981,199.6755051,0,-14.03629709,0,93.25951015 +173.83,50.30109265,-3.168593268,10000,-11.36027672,199.6777394,0,-14.03629709,0,93.2524842 +173.84,50.30109163,-3.168565286,10000,-11.34286901,199.6797506,0,-14.03629709,0,93.24545831 +173.85,50.30109061,-3.168537303,10000,-11.30805358,199.6813158,0,-14.03629709,0,93.23843236 +173.86,50.3010896,-3.16850932,10000,-11.27323814,199.682212,0,-14.03629709,0,93.23140646 +173.87,50.30108859,-3.168481337,10000,-11.25234886,199.6826623,0,-14.03629709,0,93.22438051 +173.88,50.30108758,-3.168453354,10000,-11.2314596,199.6837815,0,-14.03629709,0,93.21735461 +173.89,50.30108657,-3.168425371,10000,-11.19664416,199.6860156,0,-14.03629709,0,93.21032866 +173.9,50.30108557,-3.168397387,10000,-11.16182872,199.6882498,0,-14.03629709,0,93.20330277 +173.91,50.30108457,-3.168369403,10000,-11.14093946,199.6895919,0,-14.03629709,0,93.19627681 +173.92,50.30108357,-3.168341419,10000,-11.12353174,199.6907111,0,-14.03629709,0,93.18925092 +173.93,50.30108257,-3.168313435,10000,-11.10264248,199.6920532,0,-14.03629709,0,93.18222497 +173.94,50.30108158,-3.16828545,10000,-11.08523476,199.6931724,0,-14.03629709,0,93.17519907 +173.95,50.30108058,-3.168257466,10000,-11.0643455,199.6942915,0,-14.03629709,0,93.16817312 +173.96,50.30107959,-3.168229481,10000,-11.02953005,199.6956337,0,-14.03629709,0,93.16114722 +173.97,50.3010786,-3.168201496,10000,-10.99471461,199.6967528,0,-14.03629709,0,93.15412133 +173.98,50.30107762,-3.168173511,10000,-10.97382536,199.6980949,0,-14.03629709,0,93.14709538 +173.99,50.30107663,-3.168145526,10000,-10.95641765,199.7001059,0,-14.03629709,0,93.14006948 +174,50.30107565,-3.16811754,10000,-10.93204684,199.701448,0,-14.03629709,0,93.13304353 +174.01,50.30107467,-3.168089554,10000,-10.90419448,199.7016751,0,-14.03629709,0,93.12601763 +174.02,50.30107369,-3.168061569,10000,-10.87982366,199.7027942,0,-14.03629709,0,93.11899168 +174.03,50.30107272,-3.168033583,10000,-10.86241595,199.7052512,0,-14.03629709,0,93.11196579 +174.04,50.30107174,-3.168005596,10000,-10.84500822,199.7072623,0,-14.03629709,0,93.10493984 +174.05,50.30107077,-3.16797761,10000,-10.82063743,199.7086043,0,-14.03629709,0,93.09791394 +174.06,50.3010698,-3.167949623,10000,-10.78930355,199.7099463,0,-14.03629709,0,93.09088799 +174.07,50.30106883,-3.167921636,10000,-10.75100656,199.7108424,0,-14.03629709,0,93.08386209 +174.08,50.30106787,-3.167893649,10000,-10.7161911,199.7112924,0,-14.03629709,0,93.07683614 +174.09,50.30106691,-3.167865662,10000,-10.69878337,199.7124114,0,-14.03629709,0,93.06981025 +174.1,50.30106595,-3.167837675,10000,-10.6918203,199.7144224,0,-14.03629709,0,93.06278429 +174.11,50.30106499,-3.167809687,10000,-10.6744126,199.7157644,0,-14.03629709,0,93.0557584 +174.12,50.30106403,-3.167781699,10000,-10.63959716,199.7159914,0,-14.03629709,0,93.04873245 +174.13,50.30106308,-3.167753712,10000,-10.60478172,199.7171103,0,-14.03629709,0,93.04170655 +174.14,50.30106213,-3.167725724,10000,-10.58389246,199.7195673,0,-14.03629709,0,93.0346806 +174.15,50.30106118,-3.167697735,10000,-10.56648473,199.7213552,0,-14.03629709,0,93.0276547 +174.16,50.30106023,-3.167669747,10000,-10.54559546,199.7218052,0,-14.03629709,0,93.02062875 +174.17,50.30105929,-3.167641758,10000,-10.52470619,199.7222551,0,-14.03629709,0,93.01360286 +174.18,50.30105834,-3.16761377,10000,-10.49337231,199.724043,0,-14.03629709,0,93.0065769 +174.19,50.3010574,-3.167585781,10000,-10.45159378,199.7267229,0,-14.03629709,0,92.99955101 +174.2,50.30105647,-3.167557791,10000,-10.42374142,199.7285108,0,-14.03629709,0,92.99252506 +174.21,50.30105553,-3.167529802,10000,-10.41677834,199.7289607,0,-14.03629709,0,92.98549916 +174.22,50.3010546,-3.167501812,10000,-10.40981525,199.7291876,0,-14.03629709,0,92.97847321 +174.23,50.30105366,-3.167473823,10000,-10.3819629,199.7303065,0,-14.03629709,0,92.97144732 +174.24,50.30105273,-3.167445833,10000,-10.34018439,199.7325403,0,-14.03629709,0,92.96442136 +174.25,50.30105181,-3.167417843,10000,-10.3088505,199.7345512,0,-14.03629709,0,92.95739547 +174.26,50.30105088,-3.167389852,10000,-10.28796123,199.735001,0,-14.03629709,0,92.95036952 +174.27,50.30104996,-3.167361862,10000,-10.26707196,199.7350049,0,-14.03629709,0,92.94334362 +174.28,50.30104904,-3.167333872,10000,-10.24966425,199.7365697,0,-14.03629709,0,92.93631767 +174.29,50.30104812,-3.167305881,10000,-10.22877498,199.7394725,0,-14.03629709,0,92.92929177 +174.3,50.3010472,-3.16727789,10000,-10.19395953,199.7417063,0,-14.03629709,0,92.92226582 +174.31,50.30104629,-3.167249898,10000,-10.1591441,199.7421561,0,-14.03629709,0,92.91523993 +174.32,50.30104538,-3.167221907,10000,-10.13825485,199.7421599,0,-14.03629709,0,92.90821397 +174.33,50.30104447,-3.167193916,10000,-10.12084713,199.7435017,0,-14.03629709,0,92.90118808 +174.34,50.30104356,-3.167165924,10000,-10.09995785,199.7455125,0,-14.03629709,0,92.89416213 +174.35,50.30104266,-3.167137932,10000,-10.08255013,199.7466313,0,-14.03629709,0,92.88713623 +174.36,50.30104175,-3.16710994,10000,-10.06166087,199.746858,0,-14.03629709,0,92.88011028 +174.37,50.30104085,-3.167081948,10000,-10.02684544,199.7470848,0,-14.03629709,0,92.87308438 +174.38,50.30103995,-3.167053956,10000,-9.992030007,199.7482036,0,-14.03629709,0,92.86605849 +174.39,50.30103906,-3.167025964,10000,-9.971140753,199.7504373,0,-14.03629709,0,92.85903254 +174.4,50.30103816,-3.166997971,10000,-9.953733034,199.752671,0,-14.03629709,0,92.85200664 +174.41,50.30103727,-3.166969978,10000,-9.92936222,199.7537897,0,-14.03629709,0,92.84498069 +174.42,50.30103638,-3.166941985,10000,-9.901509863,199.7542394,0,-14.03629709,0,92.8379548 +174.43,50.30103549,-3.166913992,10000,-9.877139052,199.7553581,0,-14.03629709,0,92.83092884 +174.44,50.30103461,-3.166885999,10000,-9.859731337,199.7575917,0,-14.03629709,0,92.82390295 +174.45,50.30103372,-3.166858005,10000,-9.838842079,199.7598254,0,-14.03629709,0,92.816877 +174.46,50.30103284,-3.166830011,10000,-9.804026632,199.7609441,0,-14.03629709,0,92.8098511 +174.47,50.30103196,-3.166802017,10000,-9.769211187,199.7611708,0,-14.03629709,0,92.80282515 +174.48,50.30103109,-3.166774023,10000,-9.748321933,199.7613974,0,-14.03629709,0,92.79579925 +174.49,50.30103021,-3.166746029,10000,-9.730914227,199.7625161,0,-14.03629709,0,92.7887733 +174.5,50.30102934,-3.166718035,10000,-9.706543425,199.7645267,0,-14.03629709,0,92.78174741 +174.51,50.30102847,-3.16669004,10000,-9.67869107,199.7660913,0,-14.03629709,0,92.77472145 +174.52,50.3010276,-3.166662045,10000,-9.654320263,199.7667639,0,-14.03629709,0,92.76769556 +174.53,50.30102674,-3.166634051,10000,-9.636912549,199.7674365,0,-14.03629709,0,92.76066961 +174.54,50.30102587,-3.166606055,10000,-9.619504819,199.7683321,0,-14.03629709,0,92.75364371 +174.55,50.30102501,-3.166578061,10000,-9.595133992,199.7694507,0,-14.03629709,0,92.74661776 +174.56,50.30102415,-3.166550065,10000,-9.563800105,199.7710153,0,-14.03629709,0,92.73959187 +174.57,50.30102329,-3.16652207,10000,-9.525503151,199.7728028,0,-14.03629709,0,92.73256591 +174.58,50.30102244,-3.166494074,10000,-9.49068772,199.7743674,0,-14.03629709,0,92.72554002 +174.59,50.30102159,-3.166466078,10000,-9.473279981,199.7752629,0,-14.03629709,0,92.71851407 +174.6,50.30102074,-3.166438082,10000,-9.466316883,199.7757125,0,-14.03629709,0,92.71148817 +174.61,50.30101989,-3.166410086,10000,-9.448909169,199.776831,0,-14.03629709,0,92.70446222 +174.62,50.30101904,-3.16638209,10000,-9.41409373,199.7788415,0,-14.03629709,0,92.69743632 +174.63,50.3010182,-3.166354093,10000,-9.37927829,199.780183,0,-14.03629709,0,92.69041037 +174.64,50.30101736,-3.166326096,10000,-9.358389036,199.7801865,0,-14.03629709,0,92.68338448 +174.65,50.30101652,-3.1662981,10000,-9.340981326,199.780636,0,-14.03629709,0,92.67635852 +174.66,50.30101568,-3.166270103,10000,-9.320092061,199.7826465,0,-14.03629709,0,92.66933263 +174.67,50.30101485,-3.166242106,10000,-9.302684343,199.78488,0,-14.03629709,0,92.66230668 +174.68,50.30101401,-3.166214108,10000,-9.281795089,199.7862214,0,-14.03629709,0,92.65528078 +174.69,50.30101318,-3.166186111,10000,-9.246979655,199.7873399,0,-14.03629709,0,92.64825483 +174.7,50.30101235,-3.166158113,10000,-9.212164206,199.7884583,0,-14.03629709,0,92.64122893 +174.71,50.30101153,-3.166130115,10000,-9.191274924,199.7886848,0,-14.03629709,0,92.63420298 +174.72,50.3010107,-3.166102117,10000,-9.170385654,199.7886883,0,-14.03629709,0,92.62717709 +174.73,50.30100988,-3.16607412,10000,-9.13557023,199.7900297,0,-14.03629709,0,92.62015113 +174.74,50.30100906,-3.166046121,10000,-9.100754805,199.7922631,0,-14.03629709,0,92.61312524 +174.75,50.30100825,-3.166018123,10000,-9.079865544,199.7940504,0,-14.03629709,0,92.60609929 +174.76,50.30100743,-3.165990124,10000,-9.062457824,199.7947228,0,-14.03629709,0,92.59907339 +174.77,50.30100662,-3.165962125,10000,-9.041568559,199.7945032,0,-14.03629709,0,92.5920475 +174.78,50.30100581,-3.165934127,10000,-9.02416084,199.7949526,0,-14.03629709,0,92.58502155 +174.79,50.301005,-3.165906128,10000,-9.003271582,199.796963,0,-14.03629709,0,92.57799565 +174.8,50.30100419,-3.165878129,10000,-8.968456147,199.7991963,0,-14.03629709,0,92.5709697 +174.81,50.30100339,-3.165850129,10000,-8.933640704,199.8005377,0,-14.03629709,0,92.5639438 +174.82,50.30100259,-3.16582213,10000,-8.916232983,199.801656,0,-14.03629709,0,92.55691785 +174.83,50.30100179,-3.16579413,10000,-8.909269897,199.8029973,0,-14.03629709,0,92.54989196 +174.84,50.30100099,-3.16576613,10000,-8.891862174,199.8038926,0,-14.03629709,0,92.542866 +174.85,50.30100019,-3.16573813,10000,-8.857046736,199.804119,0,-14.03629709,0,92.53584011 +174.86,50.3009994,-3.16571013,10000,-8.822231306,199.8043453,0,-14.03629709,0,92.52881416 +174.87,50.30099861,-3.16568213,10000,-8.801342051,199.8052406,0,-14.03629709,0,92.52178826 +174.88,50.30099782,-3.16565413,10000,-8.780452791,199.8065819,0,-14.03629709,0,92.51476231 +174.89,50.30099703,-3.165626129,10000,-8.745637357,199.8077001,0,-14.03629709,0,92.50773641 +174.9,50.30099625,-3.165598129,10000,-8.710821919,199.8088184,0,-14.03629709,0,92.50071046 +174.91,50.30099547,-3.165570128,10000,-8.693414187,199.8101596,0,-14.03629709,0,92.49368457 +174.92,50.30099469,-3.165542127,10000,-8.686451087,199.8112779,0,-14.03629709,0,92.48665862 +174.93,50.30099391,-3.165514126,10000,-8.669043369,199.8126191,0,-14.03629709,0,92.47963272 +174.94,50.30099313,-3.165486125,10000,-8.634227935,199.8146293,0,-14.03629709,0,92.47260677 +174.95,50.30099236,-3.165458123,10000,-8.5994125,199.8159706,0,-14.03629709,0,92.46558087 +174.96,50.30099159,-3.165430121,10000,-8.578523246,199.8161968,0,-14.03629709,0,92.45855492 +174.97,50.30099082,-3.16540212,10000,-8.557634002,199.817315,0,-14.03629709,0,92.45152903 +174.98,50.30099005,-3.165374118,10000,-8.522818573,199.8195482,0,-14.03629709,0,92.44450307 +174.99,50.30098929,-3.165346115,10000,-8.488003122,199.8204433,0,-14.03629709,0,92.43747718 +175,50.30098853,-3.165318113,10000,-8.470595383,199.8197775,0,-14.03629709,0,92.43045123 +175.01,50.30098777,-3.165290111,10000,-8.463632292,199.8200037,0,-14.03629709,0,92.42342533 +175.02,50.30098701,-3.165262109,10000,-8.446224583,199.8217909,0,-14.03629709,0,92.41639938 +175.03,50.30098625,-3.165234106,10000,-8.411409152,199.823355,0,-14.03629709,0,92.40937348 +175.04,50.3009855,-3.165206103,10000,-8.376593714,199.8242501,0,-14.03629709,0,92.40234753 +175.05,50.30098475,-3.165178101,10000,-8.355704452,199.8255913,0,-14.03629709,0,92.39532164 +175.06,50.300984,-3.165150097,10000,-8.338296738,199.8269324,0,-14.03629709,0,92.38829568 +175.07,50.30098325,-3.165122094,10000,-8.317407478,199.8276045,0,-14.03629709,0,92.38126979 +175.08,50.30098251,-3.165094091,10000,-8.296518211,199.8282766,0,-14.03629709,0,92.37424384 +175.09,50.30098176,-3.165066087,10000,-8.265184315,199.8291717,0,-14.03629709,0,92.36721794 +175.1,50.30098102,-3.165038084,10000,-8.223405792,199.8300668,0,-14.03629709,0,92.36019199 +175.11,50.30098029,-3.16501008,10000,-8.195553444,199.8307389,0,-14.03629709,0,92.3531661 +175.12,50.30097955,-3.164982076,10000,-8.185108816,199.8314109,0,-14.03629709,0,92.34614014 +175.13,50.30097882,-3.164954073,10000,-8.167701095,199.832752,0,-14.03629709,0,92.33911425 +175.14,50.30097808,-3.164926068,10000,-8.136367197,199.834093,0,-14.03629709,0,92.3320883 +175.15,50.30097736,-3.164898064,10000,-8.111996393,199.8349881,0,-14.03629709,0,92.3250624 +175.16,50.30097663,-3.16487006,10000,-8.098070223,199.8365521,0,-14.03629709,0,92.31803645 +175.17,50.3009759,-3.164842055,10000,-8.073699415,199.8385621,0,-14.03629709,0,92.31101055 +175.18,50.30097518,-3.16481405,10000,-8.042365513,199.8396801,0,-14.03629709,0,92.30398466 +175.19,50.30097446,-3.164786045,10000,-8.021476246,199.8399061,0,-14.03629709,0,92.29695871 +175.2,50.30097374,-3.16475804,10000,-8.000586995,199.8399091,0,-14.03629709,0,92.28993281 +175.21,50.30097302,-3.164730035,10000,-7.965771573,199.8401351,0,-14.03629709,0,92.28290686 +175.22,50.30097231,-3.16470203,10000,-7.930956135,199.8412531,0,-14.03629709,0,92.27588096 +175.23,50.3009716,-3.164674025,10000,-7.910066862,199.843263,0,-14.03629709,0,92.26885501 +175.24,50.30097089,-3.164646019,10000,-7.892659142,199.844604,0,-14.03629709,0,92.26182912 +175.25,50.30097018,-3.164618013,10000,-7.871769886,199.8446069,0,-14.03629709,0,92.25480316 +175.26,50.30096948,-3.164590008,10000,-7.854362166,199.8448329,0,-14.03629709,0,92.24777727 +175.27,50.30096877,-3.164562002,10000,-7.833472893,199.8461738,0,-14.03629709,0,92.24075132 +175.28,50.30096807,-3.164533996,10000,-7.798657453,199.8479607,0,-14.03629709,0,92.23372542 +175.29,50.30096737,-3.16450599,10000,-7.763842025,199.8495246,0,-14.03629709,0,92.22669947 +175.3,50.30096668,-3.164477983,10000,-7.742952769,199.8506425,0,-14.03629709,0,92.21967358 +175.31,50.30096598,-3.164449977,10000,-7.725545051,199.8515374,0,-14.03629709,0,92.21264762 +175.32,50.30096529,-3.16442197,10000,-7.701174243,199.8522093,0,-14.03629709,0,92.20562173 +175.33,50.3009646,-3.164393963,10000,-7.669840349,199.8528812,0,-14.03629709,0,92.19859578 +175.34,50.30096391,-3.164365957,10000,-7.631543373,199.854222,0,-14.03629709,0,92.19156988 +175.35,50.30096323,-3.164337949,10000,-7.596727937,199.8553399,0,-14.03629709,0,92.18454393 +175.36,50.30096255,-3.164309942,10000,-7.579320215,199.8553427,0,-14.03629709,0,92.17751803 +175.37,50.30096187,-3.164281935,10000,-7.572357128,199.8555686,0,-14.03629709,0,92.17049208 +175.38,50.30096119,-3.164253928,10000,-7.558430963,199.8566864,0,-14.03629709,0,92.16346619 +175.39,50.30096051,-3.16422592,10000,-7.537541708,199.8578042,0,-14.03629709,0,92.15644023 +175.4,50.30095984,-3.164197913,10000,-7.516652444,199.858922,0,-14.03629709,0,92.14941434 +175.41,50.30095916,-3.164169905,10000,-7.485318539,199.8604858,0,-14.03629709,0,92.14238839 +175.42,50.30095849,-3.164141897,10000,-7.443540003,199.8620496,0,-14.03629709,0,92.13536249 +175.43,50.30095783,-3.164113889,10000,-7.412206114,199.8627214,0,-14.03629709,0,92.12833654 +175.44,50.30095716,-3.16408588,10000,-7.391316863,199.8625012,0,-14.03629709,0,92.12131064 +175.45,50.3009565,-3.164057873,10000,-7.370427599,199.8627269,0,-14.03629709,0,92.11428469 +175.46,50.30095584,-3.164029864,10000,-7.353019879,199.8640677,0,-14.03629709,0,92.1072588 +175.47,50.30095518,-3.164001856,10000,-7.33561217,199.8658544,0,-14.03629709,0,92.10023285 +175.48,50.30095452,-3.163973847,10000,-7.314722906,199.8674181,0,-14.03629709,0,92.09320695 +175.49,50.30095387,-3.163945838,10000,-7.297315174,199.8683129,0,-14.03629709,0,92.086181 +175.5,50.30095321,-3.163917829,10000,-7.276425915,199.8687616,0,-14.03629709,0,92.0791551 +175.51,50.30095256,-3.16388982,10000,-7.238128947,199.8696563,0,-14.03629709,0,92.07212915 +175.52,50.30095191,-3.163861811,10000,-7.192868878,199.870774,0,-14.03629709,0,92.06510326 +175.53,50.30095127,-3.163833801,10000,-7.168498061,199.8709997,0,-14.03629709,0,92.0580773 +175.54,50.30095063,-3.163805792,10000,-7.165016516,199.8710024,0,-14.03629709,0,92.05105141 +175.55,50.30094998,-3.163777783,10000,-7.14760881,199.8723431,0,-14.03629709,0,92.04402546 +175.56,50.30094934,-3.163749773,10000,-7.10931184,199.8743527,0,-14.03629709,0,92.03699956 +175.57,50.30094871,-3.163721763,10000,-7.077977942,199.8752474,0,-14.03629709,0,92.02997361 +175.58,50.30094807,-3.163693753,10000,-7.057088664,199.874804,0,-14.03629709,0,92.02294771 +175.59,50.30094744,-3.163665743,10000,-7.032717857,199.8745837,0,-14.03629709,0,92.01592182 +175.6,50.30094681,-3.163637734,10000,-7.004865518,199.8759243,0,-14.03629709,0,92.00889587 +175.61,50.30094618,-3.163609723,10000,-6.980494717,199.8779339,0,-14.03629709,0,92.00186997 +175.62,50.30094556,-3.163581713,10000,-6.963087001,199.8790515,0,-14.03629709,0,91.99484402 +175.63,50.30094493,-3.163553702,10000,-6.94567929,199.8795001,0,-14.03629709,0,91.98781812 +175.64,50.30094431,-3.163525692,10000,-6.921308482,199.8803947,0,-14.03629709,0,91.98079217 +175.65,50.30094369,-3.163497681,10000,-6.889974578,199.8817353,0,-14.03629709,0,91.97376628 +175.66,50.30094307,-3.16346967,10000,-6.855159139,199.8826298,0,-14.03629709,0,91.96674033 +175.67,50.30094246,-3.163441659,10000,-6.830788342,199.8830784,0,-14.03629709,0,91.95971443 +175.68,50.30094185,-3.163413648,10000,-6.816862175,199.8839729,0,-14.03629709,0,91.95268848 +175.69,50.30094123,-3.163385637,10000,-6.792491369,199.8850905,0,-14.03629709,0,91.94566258 +175.7,50.30094063,-3.163357625,10000,-6.761157473,199.885316,0,-14.03629709,0,91.93863663 +175.71,50.30094002,-3.163329614,10000,-6.74026821,199.8853186,0,-14.03629709,0,91.93161074 +175.72,50.30093942,-3.163301603,10000,-6.719378946,199.8866591,0,-14.03629709,0,91.92458478 +175.73,50.30093881,-3.163273591,10000,-6.68804505,199.8886686,0,-14.03629709,0,91.91755889 +175.74,50.30093822,-3.163245579,10000,-6.663674243,199.8897861,0,-14.03629709,0,91.91053294 +175.75,50.30093762,-3.163217567,10000,-6.649748066,199.8900115,0,-14.03629709,0,91.90350704 +175.76,50.30093702,-3.163189555,10000,-6.625377259,199.890237,0,-14.03629709,0,91.89648109 +175.77,50.30093643,-3.163161543,10000,-6.594043363,199.8911315,0,-14.03629709,0,91.88945519 +175.78,50.30093584,-3.163133531,10000,-6.573154102,199.892472,0,-14.03629709,0,91.88242924 +175.79,50.30093525,-3.163105518,10000,-6.552264847,199.8933664,0,-14.03629709,0,91.87540335 +175.8,50.30093466,-3.163077506,10000,-6.517449418,199.8935919,0,-14.03629709,0,91.86837739 +175.81,50.30093408,-3.163049493,10000,-6.482633979,199.8938173,0,-14.03629709,0,91.8613515 +175.82,50.3009335,-3.163021481,10000,-6.465226253,199.8947117,0,-14.03629709,0,91.85432555 +175.83,50.30093292,-3.162993468,10000,-6.458263173,199.8960521,0,-14.03629709,0,91.84729965 +175.84,50.30093234,-3.162965455,10000,-6.440855473,199.8971695,0,-14.03629709,0,91.8402737 +175.85,50.30093176,-3.162937442,10000,-6.406040036,199.8982869,0,-14.03629709,0,91.83324781 +175.86,50.30093119,-3.162909429,10000,-6.36774304,199.8994043,0,-14.03629709,0,91.82622185 +175.87,50.30093062,-3.162881415,10000,-6.33640914,199.8996297,0,-14.03629709,0,91.81919596 +175.88,50.30093005,-3.162853402,10000,-6.312038339,199.8994091,0,-14.03629709,0,91.81217001 +175.89,50.30092949,-3.162825389,10000,-6.29463063,199.8998575,0,-14.03629709,0,91.80514411 +175.9,50.30092892,-3.162797375,10000,-6.277222921,199.9007518,0,-14.03629709,0,91.79811816 +175.91,50.30092836,-3.162769362,10000,-6.252852114,199.9018691,0,-14.03629709,0,91.79109226 +175.92,50.3009278,-3.162741348,10000,-6.224999751,199.9032095,0,-14.03629709,0,91.78406631 +175.93,50.30092724,-3.162713334,10000,-6.200628937,199.9041038,0,-14.03629709,0,91.77704042 +175.94,50.30092669,-3.16268532,10000,-6.183221224,199.9045521,0,-14.03629709,0,91.77001446 +175.95,50.30092613,-3.162657306,10000,-6.165813515,199.9054464,0,-14.03629709,0,91.76298857 +175.96,50.30092558,-3.162629292,10000,-6.141442712,199.9065637,0,-14.03629709,0,91.75596262 +175.97,50.30092503,-3.162601277,10000,-6.110108821,199.906789,0,-14.03629709,0,91.74893672 +175.98,50.30092448,-3.162573263,10000,-6.071811845,199.9067913,0,-14.03629709,0,91.74191083 +175.99,50.30092394,-3.162545249,10000,-6.036996403,199.9081316,0,-14.03629709,0,91.73488487 +176,50.3009234,-3.162517234,10000,-6.019588681,199.9101408,0,-14.03629709,0,91.72785898 +176.01,50.30092286,-3.162489219,10000,-6.012625598,199.911035,0,-14.03629709,0,91.72083303 +176.02,50.30092232,-3.162461204,10000,-5.995217875,199.9105913,0,-14.03629709,0,91.71380713 +176.03,50.30092178,-3.162433189,10000,-5.960402436,199.9103706,0,-14.03629709,0,91.70678118 +176.04,50.30092125,-3.162405175,10000,-5.925587011,199.9114878,0,-14.03629709,0,91.69975529 +176.05,50.30092072,-3.162377159,10000,-5.904697756,199.912828,0,-14.03629709,0,91.69272933 +176.06,50.30092019,-3.162349144,10000,-5.883808492,199.9134992,0,-14.03629709,0,91.68570344 +176.07,50.30091966,-3.162321129,10000,-5.852474597,199.9141704,0,-14.03629709,0,91.67867749 +176.08,50.30091914,-3.162293113,10000,-5.828103783,199.9148416,0,-14.03629709,0,91.67165159 +176.09,50.30091862,-3.162265098,10000,-5.8141776,199.9150667,0,-14.03629709,0,91.66462564 +176.1,50.30091809,-3.162237082,10000,-5.789806802,199.9152919,0,-14.03629709,0,91.65759974 +176.11,50.30091758,-3.162209067,10000,-5.754991378,199.9161861,0,-14.03629709,0,91.65057379 +176.12,50.30091706,-3.162181051,10000,-5.723657494,199.9177492,0,-14.03629709,0,91.6435479 +176.13,50.30091655,-3.162153035,10000,-5.699286691,199.9193123,0,-14.03629709,0,91.63652194 +176.14,50.30091604,-3.162125019,10000,-5.685360511,199.9199835,0,-14.03629709,0,91.62949605 +176.15,50.30091553,-3.162097002,10000,-5.678397416,199.9197626,0,-14.03629709,0,91.6224701 +176.16,50.30091502,-3.162068987,10000,-5.660989694,199.9199877,0,-14.03629709,0,91.6154442 +176.17,50.30091451,-3.16204097,10000,-5.626174255,199.9211048,0,-14.03629709,0,91.60841825 +176.18,50.30091401,-3.162012954,10000,-5.587877274,199.9219989,0,-14.03629709,0,91.60139235 +176.19,50.30091351,-3.161984937,10000,-5.556543388,199.922447,0,-14.03629709,0,91.5943664 +176.2,50.30091301,-3.161956921,10000,-5.532172592,199.9231181,0,-14.03629709,0,91.58734051 +176.21,50.30091252,-3.161928904,10000,-5.514764872,199.9237892,0,-14.03629709,0,91.58031456 +176.22,50.30091202,-3.161900887,10000,-5.497357144,199.9244602,0,-14.03629709,0,91.57328866 +176.23,50.30091153,-3.161872871,10000,-5.472986338,199.9258003,0,-14.03629709,0,91.56626271 +176.24,50.30091104,-3.161844853,10000,-5.441652459,199.9269173,0,-14.03629709,0,91.55923681 +176.25,50.30091055,-3.161816836,10000,-5.406837027,199.9266963,0,-14.03629709,0,91.55221086 +176.26,50.30091007,-3.161788819,10000,-5.382466213,199.9262524,0,-14.03629709,0,91.54518497 +176.27,50.30090959,-3.161760802,10000,-5.368540034,199.9271464,0,-14.03629709,0,91.53815901 +176.28,50.3009091,-3.161732785,10000,-5.344169234,199.9291554,0,-14.03629709,0,91.53113312 +176.29,50.30090863,-3.161704767,10000,-5.312835348,199.9304953,0,-14.03629709,0,91.52410717 +176.3,50.30090815,-3.161676749,10000,-5.295427632,199.9304973,0,-14.03629709,0,91.51708127 +176.31,50.30090768,-3.161648732,10000,-5.284982998,199.9307223,0,-14.03629709,0,91.51005532 +176.32,50.3009072,-3.161620714,10000,-5.257130647,199.9316163,0,-14.03629709,0,91.50302942 +176.33,50.30090673,-3.161592696,10000,-5.215352123,199.9318413,0,-14.03629709,0,91.49600347 +176.34,50.30090627,-3.161564678,10000,-5.184018228,199.9318432,0,-14.03629709,0,91.48897758 +176.35,50.3009058,-3.161536661,10000,-5.163128971,199.9329601,0,-14.03629709,0,91.48195162 +176.36,50.30090534,-3.161508642,10000,-5.142239714,199.9340771,0,-14.03629709,0,91.47492573 +176.37,50.30090488,-3.161480624,10000,-5.12483199,199.933856,0,-14.03629709,0,91.46789978 +176.38,50.30090442,-3.161452606,10000,-5.107424273,199.9334119,0,-14.03629709,0,91.46087388 +176.39,50.30090396,-3.161424588,10000,-5.08653502,199.9343058,0,-14.03629709,0,91.45384799 +176.4,50.30090351,-3.16139657,10000,-5.065645755,199.9363147,0,-14.03629709,0,91.44682204 +176.41,50.30090305,-3.161368551,10000,-5.034311853,199.9376546,0,-14.03629709,0,91.43979614 +176.42,50.3009026,-3.161340532,10000,-4.992533338,199.9376565,0,-14.03629709,0,91.43277019 +176.43,50.30090216,-3.161312514,10000,-4.96119946,199.9378813,0,-14.03629709,0,91.42574429 +176.44,50.30090171,-3.161284495,10000,-4.940310197,199.9389982,0,-14.03629709,0,91.41871834 +176.45,50.30090127,-3.161256476,10000,-4.919420916,199.939892,0,-14.03629709,0,91.41169245 +176.46,50.30090083,-3.161228457,10000,-4.902013185,199.9401169,0,-14.03629709,0,91.40466649 +176.47,50.30090039,-3.161200438,10000,-4.884605477,199.9401187,0,-14.03629709,0,91.3976406 +176.48,50.30089995,-3.161172419,10000,-4.863716233,199.9403435,0,-14.03629709,0,91.39061465 +176.49,50.30089952,-3.1611444,10000,-4.842826981,199.9412373,0,-14.03629709,0,91.38358875 +176.5,50.30089908,-3.161116381,10000,-4.811493086,199.9425771,0,-14.03629709,0,91.3765628 +176.51,50.30089865,-3.161088361,10000,-4.769714551,199.9434709,0,-14.03629709,0,91.3695369 +176.52,50.30089823,-3.161060342,10000,-4.738380645,199.9436957,0,-14.03629709,0,91.36251095 +176.53,50.3008978,-3.161032322,10000,-4.717491384,199.9439205,0,-14.03629709,0,91.35548506 +176.54,50.30089738,-3.161004303,10000,-4.69660214,199.9448142,0,-14.03629709,0,91.3484591 +176.55,50.30089696,-3.160976283,10000,-4.682675984,199.946154,0,-14.03629709,0,91.34143321 +176.56,50.30089654,-3.160948263,10000,-4.675712899,199.9468247,0,-14.03629709,0,91.33440726 +176.57,50.30089612,-3.160920243,10000,-4.658305168,199.9461575,0,-14.03629709,0,91.32738136 +176.58,50.3008957,-3.160892223,10000,-4.62348972,199.9452673,0,-14.03629709,0,91.32035541 +176.59,50.30089529,-3.160864204,10000,-4.585192738,199.946161,0,-14.03629709,0,91.31332952 +176.6,50.30089488,-3.160836184,10000,-4.553858852,199.9483927,0,-14.03629709,0,91.30630356 +176.61,50.30089447,-3.160808163,10000,-4.529488056,199.9495093,0,-14.03629709,0,91.29927767 +176.62,50.30089407,-3.160780143,10000,-4.512080339,199.9495111,0,-14.03629709,0,91.29225172 +176.63,50.30089366,-3.160752123,10000,-4.491191073,199.9499587,0,-14.03629709,0,91.28522582 +176.64,50.30089326,-3.160724102,10000,-4.456375637,199.9506294,0,-14.03629709,0,91.27819987 +176.65,50.30089286,-3.160696082,10000,-4.421560198,199.9508541,0,-14.03629709,0,91.27117397 +176.66,50.30089247,-3.160668061,10000,-4.400670932,199.9510787,0,-14.03629709,0,91.26414802 +176.67,50.30089207,-3.160640041,10000,-4.383263217,199.9517494,0,-14.03629709,0,91.25712213 +176.68,50.30089168,-3.16061202,10000,-4.362373961,199.952197,0,-14.03629709,0,91.25009617 +176.69,50.30089129,-3.160583999,10000,-4.344966243,199.9521986,0,-14.03629709,0,91.24307028 +176.7,50.3008909,-3.160555979,10000,-4.32407698,199.9533153,0,-14.03629709,0,91.23604433 +176.71,50.30089051,-3.160527958,10000,-4.289261544,199.9555468,0,-14.03629709,0,91.22901843 +176.72,50.30089013,-3.160499936,10000,-4.254446116,199.9564404,0,-14.03629709,0,91.22199248 +176.73,50.30088975,-3.160471915,10000,-4.237038414,199.95555,0,-14.03629709,0,91.21496658 +176.74,50.30088937,-3.160443894,10000,-4.230075331,199.9546597,0,-14.03629709,0,91.20794063 +176.75,50.30088899,-3.160415873,10000,-4.212667598,199.9546612,0,-14.03629709,0,91.20091474 +176.76,50.30088861,-3.160387852,10000,-4.177852151,199.9555548,0,-14.03629709,0,91.19388879 +176.77,50.30088824,-3.160359831,10000,-4.139555168,199.9568944,0,-14.03629709,0,91.18686289 +176.78,50.30088787,-3.160331809,10000,-4.108221274,199.9580109,0,-14.03629709,0,91.179837 +176.79,50.3008875,-3.160303788,10000,-4.083850478,199.9589044,0,-14.03629709,0,91.17281104 +176.8,50.30088714,-3.160275766,10000,-4.066442778,199.9593519,0,-14.03629709,0,91.16578515 +176.81,50.30088677,-3.160247744,10000,-4.049035059,199.9589075,0,-14.03629709,0,91.1587592 +176.82,50.30088641,-3.160219723,10000,-4.024664232,199.958463,0,-14.03629709,0,91.1517333 +176.83,50.30088605,-3.160191701,10000,-3.996811874,199.9591335,0,-14.03629709,0,91.14470735 +176.84,50.30088569,-3.16016368,10000,-3.972441085,199.960473,0,-14.03629709,0,91.13768145 +176.85,50.30088534,-3.160135657,10000,-3.951551842,199.9615894,0,-14.03629709,0,91.1306555 +176.86,50.30088498,-3.160107636,10000,-3.920217951,199.9624829,0,-14.03629709,0,91.12362961 +176.87,50.30088463,-3.160079613,10000,-3.881920967,199.9629304,0,-14.03629709,0,91.11660365 +176.88,50.30088429,-3.160051591,10000,-3.86451325,199.9624858,0,-14.03629709,0,91.10957776 +176.89,50.30088394,-3.160023569,10000,-3.861031703,199.9620413,0,-14.03629709,0,91.10255181 +176.9,50.30088359,-3.159995547,10000,-3.840142431,199.9627117,0,-14.03629709,0,91.09552591 +176.91,50.30088325,-3.159967525,10000,-3.805326993,199.9640511,0,-14.03629709,0,91.08849996 +176.92,50.30088291,-3.159939502,10000,-3.770511563,199.9649446,0,-14.03629709,0,91.08147406 +176.93,50.30088257,-3.15991148,10000,-3.735696127,199.965169,0,-14.03629709,0,91.07444811 +176.94,50.30088224,-3.159883457,10000,-3.711325317,199.9651704,0,-14.03629709,0,91.06742222 +176.95,50.30088191,-3.159855435,10000,-3.697399149,199.9651718,0,-14.03629709,0,91.06039627 +176.96,50.30088157,-3.159827412,10000,-3.676509901,199.9653961,0,-14.03629709,0,91.05337037 +176.97,50.30088125,-3.15979939,10000,-3.655620649,199.9662895,0,-14.03629709,0,91.04634442 +176.98,50.30088092,-3.159771367,10000,-3.641694467,199.9676289,0,-14.03629709,0,91.03931852 +176.99,50.30088059,-3.159743344,10000,-3.617323646,199.9682992,0,-14.03629709,0,91.03229257 +177,50.30088027,-3.159715321,10000,-3.582508212,199.9678546,0,-14.03629709,0,91.02526668 +177.01,50.30087995,-3.159687298,10000,-3.551174333,199.9676329,0,-14.03629709,0,91.01824072 +177.02,50.30087963,-3.159659276,10000,-3.526803528,199.9687492,0,-14.03629709,0,91.01121483 +177.03,50.30087932,-3.159631252,10000,-3.5093958,199.9698655,0,-14.03629709,0,91.00418888 +177.04,50.300879,-3.159603229,10000,-3.488506537,199.9698669,0,-14.03629709,0,90.99716298 +177.05,50.30087869,-3.159575206,10000,-3.45369111,199.9700912,0,-14.03629709,0,90.99013703 +177.06,50.30087838,-3.159547183,10000,-3.418875678,199.9709844,0,-14.03629709,0,90.98311113 +177.07,50.30087808,-3.159519159,10000,-3.39798641,199.9712087,0,-14.03629709,0,90.97608518 +177.08,50.30087777,-3.159491136,10000,-3.380578687,199.970987,0,-14.03629709,0,90.96905929 +177.09,50.30087747,-3.159463113,10000,-3.356207884,199.9714343,0,-14.03629709,0,90.96203333 +177.1,50.30087717,-3.159435089,10000,-3.328355542,199.9721045,0,-14.03629709,0,90.95500744 +177.11,50.30087687,-3.159407066,10000,-3.303984744,199.9723287,0,-14.03629709,0,90.94798149 +177.12,50.30087658,-3.159379042,10000,-3.286577031,199.972553,0,-14.03629709,0,90.94095559 +177.13,50.30087628,-3.159351019,10000,-3.269169314,199.9734462,0,-14.03629709,0,90.93392964 +177.14,50.30087599,-3.159322995,10000,-3.244798505,199.9747854,0,-14.03629709,0,90.92690375 +177.15,50.3008757,-3.159294971,10000,-3.213464606,199.9756786,0,-14.03629709,0,90.91987779 +177.16,50.30087541,-3.159266947,10000,-3.175167626,199.9759028,0,-14.03629709,0,90.9128519 +177.17,50.30087513,-3.159238923,10000,-3.140352197,199.975681,0,-14.03629709,0,90.90582595 +177.18,50.30087485,-3.159210899,10000,-3.122944477,199.9747902,0,-14.03629709,0,90.89880005 +177.19,50.30087457,-3.159182875,10000,-3.115981383,199.9736764,0,-14.03629709,0,90.89177416 +177.2,50.30087429,-3.159154852,10000,-3.09857367,199.9739005,0,-14.03629709,0,90.8847482 +177.21,50.30087401,-3.159126828,10000,-3.063758248,199.9759087,0,-14.03629709,0,90.87772231 +177.22,50.30087374,-3.159098804,10000,-3.028942816,199.9779168,0,-14.03629709,0,90.87069636 +177.23,50.30087347,-3.159070779,10000,-3.011535097,199.9781409,0,-14.03629709,0,90.86367046 +177.24,50.3008732,-3.159042755,10000,-3.004572002,199.9772501,0,-14.03629709,0,90.85664451 +177.25,50.30087293,-3.159014731,10000,-2.98716427,199.9772512,0,-14.03629709,0,90.84961861 +177.26,50.30087266,-3.158986707,10000,-2.952348831,199.9783673,0,-14.03629709,0,90.84259266 +177.27,50.3008724,-3.158958682,10000,-2.914051862,199.9792604,0,-14.03629709,0,90.83556677 +177.28,50.30087214,-3.158930658,10000,-2.882717974,199.9794845,0,-14.03629709,0,90.82854081 +177.29,50.30087188,-3.158902633,10000,-2.858347174,199.9794855,0,-14.03629709,0,90.82151492 +177.3,50.30087163,-3.158874609,10000,-2.840939475,199.9794866,0,-14.03629709,0,90.81448897 +177.31,50.30087137,-3.158846584,10000,-2.823531773,199.9797107,0,-14.03629709,0,90.80746307 +177.32,50.30087112,-3.15881856,10000,-2.79916096,199.9803807,0,-14.03629709,0,90.80043712 +177.33,50.30087087,-3.158790535,10000,-2.771308587,199.9808278,0,-14.03629709,0,90.79341123 +177.34,50.30087062,-3.15876251,10000,-2.746937771,199.9806058,0,-14.03629709,0,90.78638527 +177.35,50.30087038,-3.158734486,10000,-2.726048519,199.9808298,0,-14.03629709,0,90.77935938 +177.36,50.30087013,-3.158706461,10000,-2.69471464,199.9819458,0,-14.03629709,0,90.77233343 +177.37,50.30086989,-3.158678436,10000,-2.656417663,199.9828388,0,-14.03629709,0,90.76530753 +177.38,50.30086966,-3.158650411,10000,-2.639009932,199.9830628,0,-14.03629709,0,90.75828158 +177.39,50.30086942,-3.158622386,10000,-2.63552838,199.9830638,0,-14.03629709,0,90.75125568 +177.4,50.30086918,-3.158594361,10000,-2.614639128,199.9832878,0,-14.03629709,0,90.74422973 +177.41,50.30086895,-3.158566336,10000,-2.579823707,199.9841808,0,-14.03629709,0,90.73720384 +177.42,50.30086872,-3.158538311,10000,-2.545008271,199.9852967,0,-14.03629709,0,90.73017788 +177.43,50.30086849,-3.158510285,10000,-2.510192822,199.9852977,0,-14.03629709,0,90.72315199 +177.44,50.30086827,-3.15848226,10000,-2.485822008,199.9841836,0,-14.03629709,0,90.71612604 +177.45,50.30086805,-3.158454235,10000,-2.471895839,199.9835156,0,-14.03629709,0,90.70910014 +177.46,50.30086782,-3.15842621,10000,-2.45100659,199.9841855,0,-14.03629709,0,90.70207419 +177.47,50.30086761,-3.158398185,10000,-2.430117335,199.9853014,0,-14.03629709,0,90.69504829 +177.48,50.30086739,-3.158370159,10000,-2.416191162,199.9855253,0,-14.03629709,0,90.68802234 +177.49,50.30086717,-3.158342134,10000,-2.391820356,199.9853032,0,-14.03629709,0,90.68099645 +177.5,50.30086696,-3.158314109,10000,-2.357004917,199.9857501,0,-14.03629709,0,90.6739705 +177.51,50.30086675,-3.158286083,10000,-2.322189481,199.98642,0,-14.03629709,0,90.6669446 +177.52,50.30086654,-3.158258058,10000,-2.28737405,199.9866438,0,-14.03629709,0,90.65991865 +177.53,50.30086634,-3.158230032,10000,-2.263003247,199.9868677,0,-14.03629709,0,90.65289275 +177.54,50.30086614,-3.158202007,10000,-2.24907707,199.9875375,0,-14.03629709,0,90.6458668 +177.55,50.30086593,-3.158173981,10000,-2.228187807,199.9879843,0,-14.03629709,0,90.63884091 +177.56,50.30086574,-3.158145955,10000,-2.207298546,199.9877622,0,-14.03629709,0,90.63181495 +177.57,50.30086554,-3.15811793,10000,-2.193372368,199.987986,0,-14.03629709,0,90.62478906 +177.58,50.30086534,-3.158089904,10000,-2.169001564,199.9888788,0,-14.03629709,0,90.61776311 +177.59,50.30086515,-3.158061878,10000,-2.134186134,199.9888796,0,-14.03629709,0,90.61073721 +177.6,50.30086496,-3.158033852,10000,-2.10285224,199.9879884,0,-14.03629709,0,90.60371132 +177.61,50.30086477,-3.158005827,10000,-2.078481424,199.9879892,0,-14.03629709,0,90.59668536 +177.62,50.30086459,-3.157977801,10000,-2.061073705,199.989105,0,-14.03629709,0,90.58965947 +177.63,50.3008644,-3.157949775,10000,-2.040184455,199.9899977,0,-14.03629709,0,90.58263352 +177.64,50.30086422,-3.157921749,10000,-2.005369035,199.9902215,0,-14.03629709,0,90.57560762 +177.65,50.30086404,-3.157893723,10000,-1.97055361,199.9902222,0,-14.03629709,0,90.56858167 +177.66,50.30086387,-3.157865697,10000,-1.949664347,199.990223,0,-14.03629709,0,90.56155577 +177.67,50.30086369,-3.157837671,10000,-1.932256617,199.9902237,0,-14.03629709,0,90.55452982 +177.68,50.30086352,-3.157809645,10000,-1.911367345,199.9902244,0,-14.03629709,0,90.54750393 +177.69,50.30086335,-3.157781619,10000,-1.893959626,199.9904481,0,-14.03629709,0,90.54047798 +177.7,50.30086318,-3.157753593,10000,-1.873070372,199.9913408,0,-14.03629709,0,90.53345208 +177.71,50.30086301,-3.157725567,10000,-1.838254945,199.9924565,0,-14.03629709,0,90.52642613 +177.72,50.30086285,-3.15769754,10000,-1.803439509,199.9924572,0,-14.03629709,0,90.51940023 +177.73,50.30086269,-3.157669514,10000,-1.782550243,199.9915659,0,-14.03629709,0,90.51237428 +177.74,50.30086253,-3.157641488,10000,-1.765142529,199.9915666,0,-14.03629709,0,90.50534839 +177.75,50.30086237,-3.157613462,10000,-1.744253272,199.9926822,0,-14.03629709,0,90.49832243 +177.76,50.30086222,-3.157585435,10000,-1.726845555,199.9935748,0,-14.03629709,0,90.49129654 +177.77,50.30086206,-3.157557409,10000,-1.705956293,199.9937985,0,-14.03629709,0,90.48427059 +177.78,50.30086191,-3.157529382,10000,-1.671140854,199.9937991,0,-14.03629709,0,90.47724469 +177.79,50.30086176,-3.157501356,10000,-1.636325418,199.9937997,0,-14.03629709,0,90.47021874 +177.8,50.30086162,-3.157473329,10000,-1.615436162,199.9938004,0,-14.03629709,0,90.46319284 +177.81,50.30086147,-3.157445303,10000,-1.594546904,199.993801,0,-14.03629709,0,90.45616689 +177.82,50.30086133,-3.157417276,10000,-1.559731463,199.9938016,0,-14.03629709,0,90.449141 +177.83,50.30086119,-3.15738925,10000,-1.524916025,199.9938021,0,-14.03629709,0,90.44211504 +177.84,50.30086106,-3.157361223,10000,-1.504026766,199.9940257,0,-14.03629709,0,90.43508915 +177.85,50.30086092,-3.157333197,10000,-1.486619052,199.9946953,0,-14.03629709,0,90.4280632 +177.86,50.30086079,-3.15730517,10000,-1.465729793,199.9951418,0,-14.03629709,0,90.4210373 +177.87,50.30086066,-3.157277143,10000,-1.448322074,199.9946964,0,-14.03629709,0,90.41401135 +177.88,50.30086053,-3.157249117,10000,-1.427432809,199.9940279,0,-14.03629709,0,90.40698546 +177.89,50.3008604,-3.15722109,10000,-1.392617375,199.9940284,0,-14.03629709,0,90.3999595 +177.9,50.30086028,-3.157193064,10000,-1.357801944,199.9949209,0,-14.03629709,0,90.39293361 +177.91,50.30086016,-3.157165037,10000,-1.340394227,199.9962594,0,-14.03629709,0,90.38590766 +177.92,50.30086004,-3.15713701,10000,-1.333431139,199.9969289,0,-14.03629709,0,90.37888176 +177.93,50.30085992,-3.157108983,10000,-1.31602342,199.9962604,0,-14.03629709,0,90.37185581 +177.94,50.3008598,-3.157080956,10000,-1.281207984,199.9951459,0,-14.03629709,0,90.36482991 +177.95,50.30085969,-3.15705293,10000,-1.246392555,199.9951464,0,-14.03629709,0,90.35780396 +177.96,50.30085958,-3.157024903,10000,-1.225503303,199.9962619,0,-14.03629709,0,90.35077807 +177.97,50.30085947,-3.156996876,10000,-1.20461404,199.9969313,0,-14.03629709,0,90.34375211 +177.98,50.30085936,-3.156968849,10000,-1.169798593,199.9962628,0,-14.03629709,0,90.33672622 +177.99,50.30085926,-3.156940822,10000,-1.134983155,199.9953712,0,-14.03629709,0,90.32970032 +178,50.30085916,-3.156912796,10000,-1.117575447,199.9960406,0,-14.03629709,0,90.32267437 +178.01,50.30085906,-3.156884769,10000,-1.110612368,199.997379,0,-14.03629709,0,90.31564848 +178.02,50.30085896,-3.156856741,10000,-1.093204651,199.9973794,0,-14.03629709,0,90.30862252 +178.03,50.30085886,-3.156828715,10000,-1.058389213,199.9971568,0,-14.03629709,0,90.30159663 +178.04,50.30085877,-3.156800688,10000,-1.023573775,199.9976032,0,-14.03629709,0,90.29457068 +178.05,50.30085868,-3.15677266,10000,-1.002684514,199.9973806,0,-14.03629709,0,90.28754478 +178.06,50.30085859,-3.156744634,10000,-0.981795258,199.997158,0,-14.03629709,0,90.28051883 +178.07,50.3008585,-3.156716607,10000,-0.946979824,199.9978273,0,-14.03629709,0,90.27349294 +178.08,50.30085842,-3.156688579,10000,-0.912164382,199.9982737,0,-14.03629709,0,90.26646698 +178.09,50.30085834,-3.156660553,10000,-0.894756656,199.998497,0,-14.03629709,0,90.25944109 +178.1,50.30085826,-3.156632525,10000,-0.887793568,199.9987204,0,-14.03629709,0,90.25241514 +178.11,50.30085818,-3.156604498,10000,-0.870385856,199.9982747,0,-14.03629709,0,90.24538924 +178.12,50.3008581,-3.156576471,10000,-0.835570422,199.997829,0,-14.03629709,0,90.23836329 +178.13,50.30085803,-3.156548444,10000,-0.800754984,199.9982753,0,-14.03629709,0,90.23133739 +178.14,50.30085796,-3.156520417,10000,-0.77986573,199.9987216,0,-14.03629709,0,90.22431144 +178.15,50.30085789,-3.156492389,10000,-0.762458024,199.9984989,0,-14.03629709,0,90.21728555 +178.16,50.30085782,-3.156464363,10000,-0.741568759,199.9984992,0,-14.03629709,0,90.21025959 +178.17,50.30085776,-3.156436335,10000,-0.724161031,199.9987225,0,-14.03629709,0,90.2032337 +178.18,50.30085769,-3.156408308,10000,-0.703271771,199.9984997,0,-14.03629709,0,90.19620775 +178.19,50.30085763,-3.156380281,10000,-0.668456339,199.998723,0,-14.03629709,0,90.18918185 +178.2,50.30085757,-3.156352254,10000,-0.633640905,199.9996152,0,-14.03629709,0,90.1821559 +178.21,50.30085752,-3.156324226,10000,-0.612751649,199.9996155,0,-14.03629709,0,90.17513 +178.22,50.30085746,-3.156296199,10000,-0.591862391,199.9987237,0,-14.03629709,0,90.16810405 +178.23,50.30085741,-3.156268172,10000,-0.55704695,199.9987239,0,-14.03629709,0,90.16107816 +178.24,50.30085736,-3.156240145,10000,-0.522231514,199.9996161,0,-14.03629709,0,90.15405221 +178.25,50.30085732,-3.156212117,10000,-0.50134226,199.9996163,0,-14.03629709,0,90.14702631 +178.26,50.30085727,-3.15618409,10000,-0.483934541,199.9987245,0,-14.03629709,0,90.14000036 +178.27,50.30085723,-3.156156063,10000,-0.46304527,199.9987247,0,-14.03629709,0,90.13297446 +178.28,50.30085719,-3.156128036,10000,-0.44563755,199.9996168,0,-14.03629709,0,90.12594851 +178.29,50.30085715,-3.156100008,10000,-0.424748301,199.99984,0,-14.03629709,0,90.11892262 +178.3,50.30085711,-3.156071981,10000,-0.389932878,199.9996171,0,-14.03629709,0,90.11189666 +178.31,50.30085708,-3.156043954,10000,-0.355117445,199.9998403,0,-14.03629709,0,90.10487077 +178.32,50.30085705,-3.156015926,10000,-0.334228171,199.9998404,0,-14.03629709,0,90.09784482 +178.33,50.30085702,-3.155987899,10000,-0.31682044,199.9996175,0,-14.03629709,0,90.09081892 +178.34,50.30085699,-3.155959872,10000,-0.29593118,200.0000636,0,-14.03629709,0,90.08379297 +178.35,50.30085697,-3.155931844,10000,-0.27852347,200.0007327,0,-14.03088184,0,90.07676776 +178.36,50.30085694,-3.155903817,10000,-0.257634218,200.0007328,0,-13.99297518,0,90.06975241 +178.37,50.30085692,-3.155875789,10000,-0.222818793,200.0000639,0,-13.89008565,0,90.06277235 +178.38,50.3008569,-3.155847762,10000,-0.188003361,199.999618,0,-13.68972185,0,90.05586976 +178.39,50.30085689,-3.155819735,10000,-0.167114092,199.9998411,0,-13.35939232,0,90.04910364 +178.4,50.30085687,-3.155791707,10000,-0.149706362,199.9998411,0,-12.86660564,0,90.04254923 +178.41,50.30085686,-3.15576368,10000,-0.128817099,199.9996182,0,-12.18970087,0,90.0362966 +178.42,50.30085685,-3.155735653,10000,-0.111409391,199.9998412,0,-11.35033901,0,90.03043444 +178.43,50.30085684,-3.155707625,10000,-0.094001681,199.9996183,0,-10.38101136,0,90.02503506 +178.44,50.30085683,-3.155679598,10000,-0.07311242,199.9987263,0,-9.3142095,0,90.02015311 +178.45,50.30085683,-3.155651571,10000,-0.055704701,199.9987264,0,-8.182424711,0,90.01582619 +178.46,50.30085682,-3.155623544,10000,-0.038296982,199.9996184,0,-7.018148516,0,90.01207544 +178.47,50.30085682,-3.155595516,10000,-0.017407719,199.9998414,0,-5.853872379,0,90.00890578 +178.48,50.30085682,-3.155567489,10000,-0.003481544,199.9996184,0,-4.722087589,0,90.00630656 +178.49,50.30085682,-3.155539462,10000,-0.003481544,200.0000644,0,-3.655285668,0,90.00425165 +178.5,50.30085682,-3.155511434,10000,-0.017407719,200.0007334,0,-2.685958076,0,90.0026995 +178.51,50.30085682,-3.155483407,10000,-0.034815438,200.0007334,0,-1.846596163,0,90.00159324 +178.52,50.30085681,-3.155455379,10000,-0.034815438,200.0000644,0,-1.169691448,0,90.00086065 +178.53,50.30085681,-3.155427352,10000,-0.017407719,199.9996184,0,-0.676904772,0,90.00041506 +178.54,50.30085681,-3.155399325,10000,-0.003481544,199.9998414,0,-0.346575237,0,90.00017001 +178.55,50.30085681,-3.155371297,10000,0,199.9998414,0,-0.146211438,0,90.00005381 +178.56,50.30085681,-3.15534327,10000,0,199.9996184,0,-0.043321912,0,90.00001061 +178.57,50.30085681,-3.155315243,10000,0,200.0000644,0,-0.005415253,0,90.00000064 +178.58,50.30085681,-3.155287215,10000,0,200.0007334,0,0,0,90.00000001 +178.59,50.30085681,-3.155259188,10000,0,200.0007334,0,0,0,90.00000001 +178.6,50.30085681,-3.15523116,10000,0,200.0000644,0,0,0,90.00000001 +178.61,50.30085681,-3.155203133,10000,0,199.9996184,0,0,0,90.00000001 +178.62,50.30085681,-3.155175106,10000,0,200.0000644,0,0,0,90.00000001 +178.63,50.30085681,-3.155147078,10000,0,200.0007334,0,0,0,90.00000001 +178.64,50.30085681,-3.155119051,10000,0,200.0007334,0,0,0,90.00000001 +178.65,50.30085681,-3.155091023,10000,0,200.0000644,0,0,0,90.00000001 +178.66,50.30085681,-3.155062996,10000,0,199.9996184,0,0,0,90.00000001 +178.67,50.30085681,-3.155034969,10000,0,199.9998414,0,0,0,90.00000001 +178.68,50.30085681,-3.155006941,10000,0,199.9998414,0,0,0,90.00000001 +178.69,50.30085681,-3.154978914,10000,0,199.9996184,0,0,0,90.00000001 +178.7,50.30085681,-3.154950887,10000,0,200.0000644,0,0,0,90.00000001 +178.71,50.30085681,-3.154922859,10000,0,200.0007334,0,0,0,90.00000001 +178.72,50.30085681,-3.154894832,10000,0,200.0007334,0,0,0,90.00000001 +178.73,50.30085681,-3.154866804,10000,0,200.0000644,0,0,0,90.00000001 +178.74,50.30085681,-3.154838777,10000,0,199.9996184,0,0,0,90.00000001 +178.75,50.30085681,-3.15481075,10000,0,199.9998414,0,0,0,90.00000001 +178.76,50.30085681,-3.154782722,10000,0,199.9998414,0,0,0,90.00000001 +178.77,50.30085681,-3.154754695,10000,0,199.9996184,0,0,0,90.00000001 +178.78,50.30085681,-3.154726668,10000,0,200.0000644,0,0,0,90.00000001 +178.79,50.30085681,-3.15469864,10000,0,200.0007334,0,0,0,90.00000001 +178.8,50.30085681,-3.154670613,10000,0,200.0007334,0,0,0,90.00000001 +178.81,50.30085681,-3.154642585,10000,0,200.0000644,0,0,0,90.00000001 +178.82,50.30085681,-3.154614558,10000,0,199.9996184,0,0,0,90.00000001 +178.83,50.30085681,-3.154586531,10000,0,199.9998414,0,0,0,90.00000001 +178.84,50.30085681,-3.154558503,10000,0,199.9998414,0,0,0,90.00000001 +178.85,50.30085681,-3.154530476,10000,0,199.9996184,0,0,0,90.00000001 +178.86,50.30085681,-3.154502449,10000,0,200.0000644,0,0,0,90.00000001 +178.87,50.30085681,-3.154474421,10000,0,200.0007334,0,0,0,90.00000001 +178.88,50.30085681,-3.154446394,10000,0,200.0007334,0,0,0,90.00000001 +178.89,50.30085681,-3.154418366,10000,0,200.0000644,0,0,0,90.00000001 +178.9,50.30085681,-3.154390339,10000,0,199.9996184,0,0,0,90.00000001 +178.91,50.30085681,-3.154362312,10000,0,199.9998414,0,0,0,90.00000001 +178.92,50.30085681,-3.154334284,10000,0,199.9998414,0,0,0,90.00000001 +178.93,50.30085681,-3.154306257,10000,0,199.9996184,0,0,0,90.00000001 +178.94,50.30085681,-3.15427823,10000,0,200.0000644,0,0,0,90.00000001 +178.95,50.30085681,-3.154250202,10000,0,200.0005104,0,0,0,90.00000001 +178.96,50.30085681,-3.154222175,10000,0,199.9998414,0,0,0,90.00000001 +178.97,50.30085681,-3.154194147,10000,0,199.9987264,0,0,0,90.00000001 +178.98,50.30085681,-3.154166121,10000,0,199.9985034,0,0,0,90.00000001 +178.99,50.30085681,-3.154138093,10000,0,199.9989494,0,0,0,90.00000001 +179,50.30085681,-3.154110066,10000,0,199.9993954,0,0,0,90.00000001 +179.01,50.30085681,-3.154082039,10000,0,200.0000644,0,0,0,90.00000001 +179.02,50.30085681,-3.154054011,10000,0,200.0007334,0,0,0,90.00000001 +179.03,50.30085681,-3.154025984,10000,0,200.0007334,0,0,0,90.00000001 +179.04,50.30085681,-3.153997956,10000,0,200.0000644,0,0,0,90.00000001 +179.05,50.30085681,-3.153969929,10000,0,199.9996184,0,0,0,90.00000001 +179.06,50.30085681,-3.153941902,10000,0,200.0000644,0,0,0,90.00000001 +179.07,50.30085681,-3.153913874,10000,0,200.0007334,0,0,0,90.00000001 +179.08,50.30085681,-3.153885847,10000,0,200.0007334,0,0,0,90.00000001 +179.09,50.30085681,-3.153857819,10000,0,200.0000644,0,0,0,90.00000001 +179.1,50.30085681,-3.153829792,10000,0,199.9996184,0,0,0,90.00000001 +179.11,50.30085681,-3.153801765,10000,0,199.9998414,0,0,0,90.00000001 +179.12,50.30085681,-3.153773737,10000,0,199.9998414,0,0,0,90.00000001 +179.13,50.30085681,-3.15374571,10000,0,199.9996184,0,0,0,90.00000001 +179.14,50.30085681,-3.153717683,10000,0,200.0000644,0,0,0,90.00000001 +179.15,50.30085681,-3.153689655,10000,0,200.0007334,0,0,0,90.00000001 +179.16,50.30085681,-3.153661628,10000,0,200.0007334,0,0,0,90.00000001 +179.17,50.30085681,-3.1536336,10000,0,200.0000644,0,0,0,90.00000001 +179.18,50.30085681,-3.153605573,10000,0,199.9996184,0,0,0,90.00000001 +179.19,50.30085681,-3.153577546,10000,0,199.9998414,0,0,0,90.00000001 +179.2,50.30085681,-3.153549518,10000,0,199.9998414,0,0,0,90.00000001 +179.21,50.30085681,-3.153521491,10000,0,199.9996184,0,0,0,90.00000001 +179.22,50.30085681,-3.153493464,10000,0,200.0000644,0,0,0,90.00000001 +179.23,50.30085681,-3.153465436,10000,0,200.0007334,0,0,0,90.00000001 +179.24,50.30085681,-3.153437409,10000,0,200.0007334,0,0,0,90.00000001 +179.25,50.30085681,-3.153409381,10000,0,200.0000644,0,0,0,90.00000001 +179.26,50.30085681,-3.153381354,10000,0,199.9996184,0,0,0,90.00000001 +179.27,50.30085681,-3.153353327,10000,0,199.9998414,0,0,0,90.00000001 +179.28,50.30085681,-3.153325299,10000,0,199.9998414,0,0,0,90.00000001 +179.29,50.30085681,-3.153297272,10000,0,199.9996184,0,0,0,90.00000001 +179.3,50.30085681,-3.153269245,10000,0,200.0000644,0,0,0,90.00000001 +179.31,50.30085681,-3.153241217,10000,0,200.0007334,0,0,0,90.00000001 +179.32,50.30085681,-3.15321319,10000,0,200.0007334,0,0,0,90.00000001 +179.33,50.30085681,-3.153185162,10000,0,200.0000644,0,0,0,90.00000001 +179.34,50.30085681,-3.153157135,10000,0,199.9996184,0,0,0,90.00000001 +179.35,50.30085681,-3.153129108,10000,0,199.9998414,0,0,0,90.00000001 +179.36,50.30085681,-3.15310108,10000,0,199.9998414,0,0,0,90.00000001 +179.37,50.30085681,-3.153073053,10000,0,199.9996184,0,0,0,90.00000001 +179.38,50.30085681,-3.153045026,10000,0,200.0000644,0,0,0,90.00000001 +179.39,50.30085681,-3.153016998,10000,0,200.0007334,0,0,0,90.00000001 +179.4,50.30085681,-3.152988971,10000,0,200.0007334,0,0,0,90.00000001 +179.41,50.30085681,-3.152960943,10000,0,200.0000644,0,0,0,90.00000001 +179.42,50.30085681,-3.152932916,10000,0,199.9996184,0,0,0,90.00000001 +179.43,50.30085681,-3.152904889,10000,0,199.9998414,0,0,0,90.00000001 +179.44,50.30085681,-3.152876861,10000,0,199.9998414,0,0,0,90.00000001 +179.45,50.30085681,-3.152848834,10000,0,199.9996184,0,0,0,90.00000001 +179.46,50.30085681,-3.152820807,10000,0,200.0000644,0,0,0,90.00000001 +179.47,50.30085681,-3.152792779,10000,0,200.0007334,0,0,0,90.00000001 +179.48,50.30085681,-3.152764752,10000,0,200.0007334,0,0,0,90.00000001 +179.49,50.30085681,-3.152736724,10000,0,199.9998414,0,0,0,90.00000001 +179.5,50.30085681,-3.152708697,10000,0,199.9985034,0,0,0,90.00000001 +179.51,50.30085681,-3.15268067,10000,0,199.9978344,0,0,0,90.00000001 +179.52,50.30085681,-3.152652643,10000,0,199.9985034,0,0,0,90.00000001 +179.53,50.30085681,-3.152624616,10000,0,199.9998414,0,0,0,90.00000001 +179.54,50.30085681,-3.152596588,10000,0,200.0007334,0,0,0,90.00000001 +179.55,50.30085681,-3.152568561,10000,0,200.0007334,0,0,0,90.00000001 +179.56,50.30085681,-3.152540533,10000,0,200.0000644,0,0,0,90.00000001 +179.57,50.30085681,-3.152512506,10000,0,199.9996184,0,0,0,90.00000001 +179.58,50.30085681,-3.152484479,10000,0,200.0000644,0,0,0,90.00000001 +179.59,50.30085681,-3.152456451,10000,0,200.0007334,0,0,0,90.00000001 +179.6,50.30085681,-3.152428424,10000,0,200.0007334,0,0,0,90.00000001 +179.61,50.30085681,-3.152400396,10000,0,200.0000644,0,0,0,90.00000001 +179.62,50.30085681,-3.152372369,10000,0,199.9996184,0,0,0,90.00000001 +179.63,50.30085681,-3.152344342,10000,0,199.9998414,0,0,0,90.00000001 +179.64,50.30085681,-3.152316314,10000,0,199.9998414,0,0,0,90.00000001 +179.65,50.30085681,-3.152288287,10000,0,199.9996184,0,0,0,90.00000001 +179.66,50.30085681,-3.15226026,10000,0,200.0000644,0,0,0,90.00000001 +179.67,50.30085681,-3.152232232,10000,0,200.0007334,0,0,0,90.00000001 +179.68,50.30085681,-3.152204205,10000,0,200.0007334,0,0,0,90.00000001 +179.69,50.30085681,-3.152176177,10000,0,200.0000644,0,0,0,90.00000001 +179.7,50.30085681,-3.15214815,10000,0,199.9996184,0,0,0,90.00000001 +179.71,50.30085681,-3.152120123,10000,0,199.9998414,0,0,0,90.00000001 +179.72,50.30085681,-3.152092095,10000,0,199.9998414,0,0,0,90.00000001 +179.73,50.30085681,-3.152064068,10000,0,199.9996184,0,0,0,90.00000001 +179.74,50.30085681,-3.152036041,10000,0,200.0000644,0,0,0,90.00000001 +179.75,50.30085681,-3.152008013,10000,0,200.0007334,0,0,0,90.00000001 +179.76,50.30085681,-3.151979986,10000,0,200.0007334,0,0,0,90.00000001 +179.77,50.30085681,-3.151951958,10000,0,200.0000644,0,0,0,90.00000001 +179.78,50.30085681,-3.151923931,10000,0,199.9996184,0,0,0,90.00000001 +179.79,50.30085681,-3.151895904,10000,0,199.9998414,0,0,0,90.00000001 +179.8,50.30085681,-3.151867876,10000,0,199.9998414,0,0,0,90.00000001 +179.81,50.30085681,-3.151839849,10000,0,199.9996184,0,0,0,90.00000001 +179.82,50.30085681,-3.151811822,10000,0,200.0000644,0,0,0,90.00000001 +179.83,50.30085681,-3.151783794,10000,0,200.0007334,0,0,0,90.00000001 +179.84,50.30085681,-3.151755767,10000,0,200.0007334,0,0,0,90.00000001 +179.85,50.30085681,-3.151727739,10000,0,200.0000644,0,0,0,90.00000001 +179.86,50.30085681,-3.151699712,10000,0,199.9996184,0,0,0,90.00000001 +179.87,50.30085681,-3.151671685,10000,0,199.9998414,0,0,0,90.00000001 +179.88,50.30085681,-3.151643657,10000,0,199.9998414,0,0,0,90.00000001 +179.89,50.30085681,-3.15161563,10000,0,199.9996184,0,0,0,90.00000001 +179.9,50.30085681,-3.151587603,10000,0,200.0000644,0,0,0,90.00000001 +179.91,50.30085681,-3.151559575,10000,0,200.0007334,0,0,0,90.00000001 +179.92,50.30085681,-3.151531548,10000,0,200.0007334,0,0,0,90.00000001 +179.93,50.30085681,-3.15150352,10000,0,200.0000644,0,0,0,90.00000001 +179.94,50.30085681,-3.151475493,10000,0,199.9996184,0,0,0,90.00000001 +179.95,50.30085681,-3.151447466,10000,0,199.9998414,0,0,0,90.00000001 +179.96,50.30085681,-3.151419438,10000,0,199.9998414,0,0,0,90.00000001 +179.97,50.30085681,-3.151391411,10000,0,199.9996184,0,0,0,90.00000001 +179.98,50.30085681,-3.151363384,10000,0,200.0000644,0,0,0,90.00000001 +179.99,50.30085681,-3.151335356,10000,0,200.0007334,0,0,0,90.00000001 +180,50.30085681,-3.151307329,10000,0,200.0007334,0,0,0,90.00000001 +180.01,50.30085681,-3.151279301,10000,0,200.0000644,0,0,0,90.00000001 +180.02,50.30085681,-3.151251274,10000,0,199.9996184,0,0,0,90.00000001 +180.03,50.30085681,-3.151223247,10000,0,199.9998414,0,0,0,90.00000001 +180.04,50.30085681,-3.151195219,10000,0,199.9996184,0,0,0,90.00000001 +180.05,50.30085681,-3.151167192,10000,0,199.9987264,0,0,0,90.00000001 +180.06,50.30085681,-3.151139165,10000,0,199.9987264,0,0,0,90.00000001 +180.07,50.30085681,-3.151111138,10000,0,199.9996184,0,0,0,90.00000001 +180.08,50.30085681,-3.15108311,10000,0,199.9998414,0,0,0,90.00000001 +180.09,50.30085681,-3.151055083,10000,0,199.9996184,0,0,0,90.00000001 +180.1,50.30085681,-3.151027056,10000,0,200.0000644,0,0,0,90.00000001 +180.11,50.30085681,-3.150999028,10000,0,200.0007334,0,0,0,90.00000001 +180.12,50.30085681,-3.150971001,10000,0,200.0007334,0,0,0,90.00000001 +180.13,50.30085681,-3.150942973,10000,0,200.0000644,0,0,0,90.00000001 +180.14,50.30085681,-3.150914946,10000,0,199.9996184,0,0,0,90.00000001 +180.15,50.30085681,-3.150886919,10000,0,199.9998414,0,0,0,90.00000001 +180.16,50.30085681,-3.150858891,10000,0,199.9998414,0,0,0,90.00000001 +180.17,50.30085681,-3.150830864,10000,0,199.9996184,0,0,0,90.00000001 +180.18,50.30085681,-3.150802837,10000,0,200.0000644,0,0,0,90.00000001 +180.19,50.30085681,-3.150774809,10000,0,200.0007334,0,0,0,90.00000001 +180.2,50.30085681,-3.150746782,10000,0,200.0007334,0,0,0,90.00000001 +180.21,50.30085681,-3.150718754,10000,0,200.0000644,0,0,0,90.00000001 +180.22,50.30085681,-3.150690727,10000,0,199.9996184,0,0,0,90.00000001 +180.23,50.30085681,-3.1506627,10000,0,199.9998414,0,0,0,90.00000001 +180.24,50.30085681,-3.150634672,10000,0,199.9998414,0,0,0,90.00000001 +180.25,50.30085681,-3.150606645,10000,0,199.9996184,0,0,0,90.00000001 +180.26,50.30085681,-3.150578618,10000,0,200.0000644,0,0,0,90.00000001 +180.27,50.30085681,-3.15055059,10000,0,200.0007334,0,0,0,90.00000001 +180.28,50.30085681,-3.150522563,10000,0,200.0007334,0,0,0,90.00000001 +180.29,50.30085681,-3.150494535,10000,0,200.0000644,0,0,0,90.00000001 +180.3,50.30085681,-3.150466508,10000,0,199.9996184,0,0,0,90.00000001 +180.31,50.30085681,-3.150438481,10000,0,199.9998414,0,0,0,90.00000001 +180.32,50.30085681,-3.150410453,10000,0,199.9998414,0,0,0,90.00000001 +180.33,50.30085681,-3.150382426,10000,0,199.9996184,0,0,0,90.00000001 +180.34,50.30085681,-3.150354399,10000,0,200.0000644,0,0,0,90.00000001 +180.35,50.30085681,-3.150326371,10000,0,200.0007334,0,0,0,90.00000001 +180.36,50.30085681,-3.150298344,10000,0,200.0007334,0,0,0,90.00000001 +180.37,50.30085681,-3.150270316,10000,0,200.0000644,0,0,0,90.00000001 +180.38,50.30085681,-3.150242289,10000,0,199.9996184,0,0,0,90.00000001 +180.39,50.30085681,-3.150214262,10000,0,199.9998414,0,0,0,90.00000001 +180.4,50.30085681,-3.150186234,10000,0,199.9998414,0,0,0,90.00000001 +180.41,50.30085681,-3.150158207,10000,0,199.9996184,0,0,0,90.00000001 +180.42,50.30085681,-3.15013018,10000,0,200.0000644,0,0,0,90.00000001 +180.43,50.30085681,-3.150102152,10000,0,200.0007334,0,0,0,90.00000001 +180.44,50.30085681,-3.150074125,10000,0,200.0007334,0,0,0,90.00000001 +180.45,50.30085681,-3.150046097,10000,0,200.0000644,0,0,0,90.00000001 +180.46,50.30085681,-3.15001807,10000,0,199.9996184,0,0,0,90.00000001 +180.47,50.30085681,-3.149990043,10000,0,199.9998414,0,0,0,90.00000001 +180.48,50.30085681,-3.149962015,10000,0,199.9998414,0,0,0,90.00000001 +180.49,50.30085681,-3.149933988,10000,0,199.9996184,0,0,0,90.00000001 +180.5,50.30085681,-3.149905961,10000,0,200.0000644,0,0,0,90.00000001 +180.51,50.30085681,-3.149877933,10000,0,200.0007334,0,0,0,90.00000001 +180.52,50.30085681,-3.149849906,10000,0,200.0007334,0,0,0,90.00000001 +180.53,50.30085681,-3.149821878,10000,0,200.0000644,0,0,0,90.00000001 +180.54,50.30085681,-3.149793851,10000,0,199.9996184,0,0,0,90.00000001 +180.55,50.30085681,-3.149765824,10000,0,199.9998414,0,0,0,90.00000001 +180.56,50.30085681,-3.149737796,10000,0,199.9998414,0,0,0,90.00000001 +180.57,50.30085681,-3.149709769,10000,0,199.9996184,0,0,0,90.00000001 +180.58,50.30085681,-3.149681742,10000,0,200.0000644,0,0,0,90.00000001 +180.59,50.30085681,-3.149653714,10000,0,200.0005104,0,0,0,90.00000001 +180.6,50.30085681,-3.149625687,10000,0,199.9998414,0,0,0,90.00000001 +180.61,50.30085681,-3.149597659,10000,0,199.9987264,0,0,0,90.00000001 +180.62,50.30085681,-3.149569633,10000,0,199.9987264,0,0,0,90.00000001 +180.63,50.30085681,-3.149541605,10000,0,199.9998414,0,0,0,90.00000001 +180.64,50.30085681,-3.149513578,10000,0,200.0005104,0,0,0,90.00000001 +180.65,50.30085681,-3.14948555,10000,0,200.0000644,0,0,0,90.00000001 +180.66,50.30085681,-3.149457523,10000,0,199.9996184,0,0,0,90.00000001 +180.67,50.30085681,-3.149429496,10000,0,199.9998414,0,0,0,90.00000001 +180.68,50.30085681,-3.149401468,10000,0,199.9998414,0,0,0,90.00000001 +180.69,50.30085681,-3.149373441,10000,0,199.9996184,0,0,0,90.00000001 +180.7,50.30085681,-3.149345414,10000,0,200.0000644,0,0,0,90.00000001 +180.71,50.30085681,-3.149317386,10000,0,200.0007334,0,0,0,90.00000001 +180.72,50.30085681,-3.149289359,10000,0,200.0007334,0,0,0,90.00000001 +180.73,50.30085681,-3.149261331,10000,0,200.0000644,0,0,0,90.00000001 +180.74,50.30085681,-3.149233304,10000,0,199.9996184,0,0,0,90.00000001 +180.75,50.30085681,-3.149205277,10000,0,199.9998414,0,0,0,90.00000001 +180.76,50.30085681,-3.149177249,10000,0,199.9998414,0,0,0,90.00000001 +180.77,50.30085681,-3.149149222,10000,0,199.9996184,0,0,0,90.00000001 +180.78,50.30085681,-3.149121195,10000,0,200.0000644,0,0,0,90.00000001 +180.79,50.30085681,-3.149093167,10000,0,200.0007334,0,0,0,90.00000001 +180.8,50.30085681,-3.14906514,10000,0,200.0007334,0,0,0,90.00000001 +180.81,50.30085681,-3.149037112,10000,0,200.0000644,0,0,0,90.00000001 +180.82,50.30085681,-3.149009085,10000,0,199.9996184,0,0,0,90.00000001 +180.83,50.30085681,-3.148981058,10000,0,199.9998414,0,0,0,90.00000001 +180.84,50.30085681,-3.14895303,10000,0,199.9998414,0,0,0,90.00000001 +180.85,50.30085681,-3.148925003,10000,0,199.9996184,0,0,0,90.00000001 +180.86,50.30085681,-3.148896976,10000,0,200.0000644,0,0,0,90.00000001 +180.87,50.30085681,-3.148868948,10000,0,200.0007334,0,0,0,90.00000001 +180.88,50.30085681,-3.148840921,10000,0,200.0007334,0,0,0,90.00000001 +180.89,50.30085681,-3.148812893,10000,0,200.0000644,0,0,0,90.00000001 +180.9,50.30085681,-3.148784866,10000,0,199.9996184,0,0,0,90.00000001 +180.91,50.30085681,-3.148756839,10000,0,199.9998414,0,0,0,90.00000001 +180.92,50.30085681,-3.148728811,10000,0,199.9998414,0,0,0,90.00000001 +180.93,50.30085681,-3.148700784,10000,0,199.9996184,0,0,0,90.00000001 +180.94,50.30085681,-3.148672757,10000,0,200.0000644,0,0,0,90.00000001 +180.95,50.30085681,-3.148644729,10000,0,200.0007334,0,0,0,90.00000001 +180.96,50.30085681,-3.148616702,10000,0,200.0007334,0,0,0,90.00000001 +180.97,50.30085681,-3.148588674,10000,0,200.0000644,0,0,0,90.00000001 +180.98,50.30085681,-3.148560647,10000,0,199.9996184,0,0,0,90.00000001 +180.99,50.30085681,-3.14853262,10000,0,199.9998414,0,0,0,90.00000001 +181,50.30085681,-3.148504592,10000,0,199.9998414,0,0,0,90.00000001 +181.01,50.30085681,-3.148476565,10000,0,199.9996184,0,0,0,90.00000001 +181.02,50.30085681,-3.148448538,10000,0,200.0000644,0,0,0,90.00000001 +181.03,50.30085681,-3.14842051,10000,0,200.0007334,0,0,0,90.00000001 +181.04,50.30085681,-3.148392483,10000,0,200.0007334,0,0,0,90.00000001 +181.05,50.30085681,-3.148364455,10000,0,200.0000644,0,0,0,90.00000001 +181.06,50.30085681,-3.148336428,10000,0,199.9996184,0,0,0,90.00000001 +181.07,50.30085681,-3.148308401,10000,0,199.9998414,0,0,0,90.00000001 +181.08,50.30085681,-3.148280373,10000,0,199.9998414,0,0,0,90.00000001 +181.09,50.30085681,-3.148252346,10000,0,199.9996184,0,0,0,90.00000001 +181.1,50.30085681,-3.148224319,10000,0,200.0000644,0,0,0,90.00000001 +181.11,50.30085681,-3.148196291,10000,0,200.0007334,0,0,0,90.00000001 +181.12,50.30085681,-3.148168264,10000,0,200.0007334,0,0,0,90.00000001 +181.13,50.30085681,-3.148140236,10000,0,199.9998414,0,0,0,90.00000001 +181.14,50.30085681,-3.148112209,10000,0,199.9987264,0,0,0,90.00000001 +181.15,50.30085681,-3.148084182,10000,0,199.9987264,0,0,0,90.00000001 +181.16,50.30085681,-3.148056155,10000,0,199.9996184,0,0,0,90.00000001 +181.17,50.30085681,-3.148028127,10000,0,199.9998414,0,0,0,90.00000001 +181.18,50.30085681,-3.1480001,10000,0,199.9996184,0,0,0,90.00000001 +181.19,50.30085681,-3.147972073,10000,0,199.9998414,0,0,0,90.00000001 +181.2,50.30085681,-3.147944045,10000,0,199.9998414,0,0,0,90.00000001 +181.21,50.30085681,-3.147916018,10000,0,199.9996184,0,0,0,90.00000001 +181.22,50.30085681,-3.147887991,10000,0,200.0000644,0,0,0,90.00000001 +181.23,50.30085681,-3.147859963,10000,0,200.0007334,0,0,0,90.00000001 +181.24,50.30085681,-3.147831936,10000,0,200.0007334,0,0,0,90.00000001 +181.25,50.30085681,-3.147803908,10000,0,200.0000644,0,0,0,90.00000001 +181.26,50.30085681,-3.147775881,10000,0,199.9996184,0,0,0,90.00000001 +181.27,50.30085681,-3.147747854,10000,0,199.9998414,0,0,0,90.00000001 +181.28,50.30085681,-3.147719826,10000,0,199.9998414,0,0,0,90.00000001 +181.29,50.30085681,-3.147691799,10000,0,199.9996184,0,0,0,90.00000001 +181.3,50.30085681,-3.147663772,10000,0,200.0000644,0,0,0,90.00000001 +181.31,50.30085681,-3.147635744,10000,0,200.0007334,0,0,0,90.00000001 +181.32,50.30085681,-3.147607717,10000,0,200.0007334,0,0,0,90.00000001 +181.33,50.30085681,-3.147579689,10000,0,200.0000644,0,0,0,90.00000001 +181.34,50.30085681,-3.147551662,10000,0,199.9996184,0,0,0,90.00000001 +181.35,50.30085681,-3.147523635,10000,0,199.9998414,0,0,0,90.00000001 +181.36,50.30085681,-3.147495607,10000,0,199.9998414,0,0,0,90.00000001 +181.37,50.30085681,-3.14746758,10000,0,199.9996184,0,0,0,90.00000001 +181.38,50.30085681,-3.147439553,10000,0,200.0000644,0,0,0,90.00000001 +181.39,50.30085681,-3.147411525,10000,0,200.0007334,0,0,0,90.00000001 +181.4,50.30085681,-3.147383498,10000,0,200.0007334,0,0,0,90.00000001 +181.41,50.30085681,-3.14735547,10000,0,200.0000644,0,0,0,90.00000001 +181.42,50.30085681,-3.147327443,10000,0,199.9996184,0,0,0,90.00000001 +181.43,50.30085681,-3.147299416,10000,0,199.9998414,0,0,0,90.00000001 +181.44,50.30085681,-3.147271388,10000,0,199.9998414,0,0,0,90.00000001 +181.45,50.30085681,-3.147243361,10000,0,199.9996184,0,0,0,90.00000001 +181.46,50.30085681,-3.147215334,10000,0,200.0000644,0,0,0,90.00000001 +181.47,50.30085681,-3.147187306,10000,0,200.0007334,0,0,0,90.00000001 +181.48,50.30085681,-3.147159279,10000,0,200.0007334,0,0,0,90.00000001 +181.49,50.30085681,-3.147131251,10000,0,200.0000644,0,0,0,90.00000001 +181.5,50.30085681,-3.147103224,10000,0,199.9996184,0,0,0,90.00000001 +181.51,50.30085681,-3.147075197,10000,0,199.9998414,0,0,0,90.00000001 +181.52,50.30085681,-3.147047169,10000,0,199.9998414,0,0,0,90.00000001 +181.53,50.30085681,-3.147019142,10000,0,199.9996184,0,0,0,90.00000001 +181.54,50.30085681,-3.146991115,10000,0,200.0000644,0,0,0,90.00000001 +181.55,50.30085681,-3.146963087,10000,0,200.0007334,0,0,0,90.00000001 +181.56,50.30085681,-3.14693506,10000,0,200.0007334,0,0,0,90.00000001 +181.57,50.30085681,-3.146907032,10000,0,200.0000644,0,0,0,90.00000001 +181.58,50.30085681,-3.146879005,10000,0,199.9996184,0,0,0,90.00000001 +181.59,50.30085681,-3.146850978,10000,0,199.9998414,0,0,0,90.00000001 +181.6,50.30085681,-3.14682295,10000,0,199.9998414,0,0,0,90.00000001 +181.61,50.30085681,-3.146794923,10000,0,199.9996184,0,0,0,90.00000001 +181.62,50.30085681,-3.146766896,10000,0,200.0000644,0,0,0,90.00000001 +181.63,50.30085681,-3.146738868,10000,0,200.0007334,0,0,0,90.00000001 +181.64,50.30085681,-3.146710841,10000,0,200.0007334,0,0,0,90.00000001 +181.65,50.30085681,-3.146682813,10000,0,200.0000644,0,0,0,90.00000001 +181.66,50.30085681,-3.146654786,10000,0,199.9996184,0,0,0,90.00000001 +181.67,50.30085681,-3.146626759,10000,0,199.9998414,0,0,0,90.00000001 +181.68,50.30085681,-3.146598731,10000,0,199.9996184,0,0,0,90.00000001 +181.69,50.30085681,-3.146570704,10000,0,199.9987264,0,0,0,90.00000001 +181.7,50.30085681,-3.146542677,10000,0,199.9987264,0,0,0,90.00000001 +181.71,50.30085681,-3.14651465,10000,0,199.9996184,0,0,0,90.00000001 +181.72,50.30085681,-3.146486622,10000,0,199.9998414,0,0,0,90.00000001 +181.73,50.30085681,-3.146458595,10000,0,199.9996184,0,0,0,90.00000001 +181.74,50.30085681,-3.146430568,10000,0,200.0000644,0,0,0,90.00000001 +181.75,50.30085681,-3.14640254,10000,0,200.0007334,0,0,0,90.00000001 +181.76,50.30085681,-3.146374513,10000,0,200.0007334,0,0,0,90.00000001 +181.77,50.30085681,-3.146346485,10000,0,200.0000644,0,0,0,90.00000001 +181.78,50.30085681,-3.146318458,10000,0,199.9996184,0,0,0,90.00000001 +181.79,50.30085681,-3.146290431,10000,0,199.9998414,0,0,0,90.00000001 +181.8,50.30085681,-3.146262403,10000,0,199.9998414,0,0,0,90.00000001 +181.81,50.30085681,-3.146234376,10000,0,199.9996184,0,0,0,90.00000001 +181.82,50.30085681,-3.146206349,10000,0,200.0000644,0,0,0,90.00000001 +181.83,50.30085681,-3.146178321,10000,0,200.0007334,0,0,0,90.00000001 +181.84,50.30085681,-3.146150294,10000,0,200.0007334,0,0,0,90.00000001 +181.85,50.30085681,-3.146122266,10000,0,200.0000644,0,0,0,90.00000001 +181.86,50.30085681,-3.146094239,10000,0,199.9996184,0,0,0,90.00000001 +181.87,50.30085681,-3.146066212,10000,0,199.9998414,0,0,0,90.00000001 +181.88,50.30085681,-3.146038184,10000,0,199.9998414,0,0,0,90.00000001 +181.89,50.30085681,-3.146010157,10000,0,199.9996184,0,0,0,90.00000001 +181.9,50.30085681,-3.14598213,10000,0,200.0000644,0,0,0,90.00000001 +181.91,50.30085681,-3.145954102,10000,0,200.0007334,0,0,0,90.00000001 +181.92,50.30085681,-3.145926075,10000,0,200.0007334,0,0,0,90.00000001 +181.93,50.30085681,-3.145898047,10000,0,200.0000644,0,0,0,90.00000001 +181.94,50.30085681,-3.14587002,10000,0,199.9996184,0,0,0,90.00000001 +181.95,50.30085681,-3.145841993,10000,0,199.9998414,0,0,0,90.00000001 +181.96,50.30085681,-3.145813965,10000,0,199.9998414,0,0,0,90.00000001 +181.97,50.30085681,-3.145785938,10000,0,199.9996184,0,0,0,90.00000001 +181.98,50.30085681,-3.145757911,10000,0,200.0000644,0,0,0,90.00000001 +181.99,50.30085681,-3.145729883,10000,0,200.0007334,0,0,0,90.00000001 +182,50.30085681,-3.145701856,10000,0,200.0007334,0,0,0,90.00000001 +182.01,50.30085681,-3.145673828,10000,0,200.0000644,0,0,0,90.00000001 +182.02,50.30085681,-3.145645801,10000,0,199.9996184,0,0,0,90.00000001 +182.03,50.30085681,-3.145617774,10000,0,199.9998414,0,0,0,90.00000001 +182.04,50.30085681,-3.145589746,10000,0,199.9998414,0,0,0,90.00000001 +182.05,50.30085681,-3.145561719,10000,0,199.9996184,0,0,0,90.00000001 +182.06,50.30085681,-3.145533692,10000,0,200.0000644,0,0,0,90.00000001 +182.07,50.30085681,-3.145505664,10000,0,200.0007334,0,0,0,90.00000001 +182.08,50.30085681,-3.145477637,10000,0,200.0007334,0,0,0,90.00000001 +182.09,50.30085681,-3.145449609,10000,0,200.0000644,0,0,0,90.00000001 +182.1,50.30085681,-3.145421582,10000,0,199.9996184,0,0,0,90.00000001 +182.11,50.30085681,-3.145393555,10000,0,199.9998414,0,0,0,90.00000001 +182.12,50.30085681,-3.145365527,10000,0,199.9998414,0,0,0,90.00000001 +182.13,50.30085681,-3.1453375,10000,0,199.9996184,0,0,0,90.00000001 +182.14,50.30085681,-3.145309473,10000,0,200.0000644,0,0,0,90.00000001 +182.15,50.30085681,-3.145281445,10000,0,200.0007334,0,0,0,90.00000001 +182.16,50.30085681,-3.145253418,10000,0,200.0007334,0,0,0,90.00000001 +182.17,50.30085681,-3.14522539,10000,0,200.0000644,0,0,0,90.00000001 +182.18,50.30085681,-3.145197363,10000,0,199.9996184,0,0,0,90.00000001 +182.19,50.30085681,-3.145169336,10000,0,199.9998414,0,0,0,90.00000001 +182.2,50.30085681,-3.145141308,10000,0,199.9998414,0,0,0,90.00000001 +182.21,50.30085681,-3.145113281,10000,0,199.9996184,0,0,0,90.00000001 +182.22,50.30085681,-3.145085254,10000,0,200.0000644,0,0,0,90.00000001 +182.23,50.30085681,-3.145057226,10000,0,200.0005104,0,0,0,90.00000001 +182.24,50.30085681,-3.145029199,10000,0,199.9998414,0,0,0,90.00000001 +182.25,50.30085681,-3.145001171,10000,0,199.9987264,0,0,0,90.00000001 +182.26,50.30085681,-3.144973145,10000,0,199.9987264,0,0,0,90.00000001 +182.27,50.30085681,-3.144945117,10000,0,199.9998414,0,0,0,90.00000001 +182.28,50.30085681,-3.14491709,10000,0,200.0005104,0,0,0,90.00000001 +182.29,50.30085681,-3.144889062,10000,0,200.0000644,0,0,0,90.00000001 +182.3,50.30085681,-3.144861035,10000,0,199.9996184,0,0,0,90.00000001 +182.31,50.30085681,-3.144833008,10000,0,199.9998414,0,0,0,90.00000001 +182.32,50.30085681,-3.14480498,10000,0,199.9998414,0,0,0,90.00000001 +182.33,50.30085681,-3.144776953,10000,0,199.9996184,0,0,0,90.00000001 +182.34,50.30085681,-3.144748926,10000,0,200.0000644,0,0,0,90.00000001 +182.35,50.30085681,-3.144720898,10000,0,200.0007334,0,0,0,90.00000001 +182.36,50.30085681,-3.144692871,10000,0,200.0007334,0,0,0,90.00000001 +182.37,50.30085681,-3.144664843,10000,0,200.0000644,0,0,0,90.00000001 +182.38,50.30085681,-3.144636816,10000,0,199.9996184,0,0,0,90.00000001 +182.39,50.30085681,-3.144608789,10000,0,199.9998414,0,0,0,90.00000001 +182.4,50.30085681,-3.144580761,10000,0,199.9998414,0,0,0,90.00000001 +182.41,50.30085681,-3.144552734,10000,0,199.9996184,0,0,0,90.00000001 +182.42,50.30085681,-3.144524707,10000,0,200.0000644,0,0,0,90.00000001 +182.43,50.30085681,-3.144496679,10000,0,200.0007334,0,0,0,90.00000001 +182.44,50.30085681,-3.144468652,10000,0,200.0007334,0,0,0,90.00000001 +182.45,50.30085681,-3.144440624,10000,0,200.0000644,0,0,0,90.00000001 +182.46,50.30085681,-3.144412597,10000,0,199.9996184,0,0,0,90.00000001 +182.47,50.30085681,-3.14438457,10000,0,199.9998414,0,0,0,90.00000001 +182.48,50.30085681,-3.144356542,10000,0,199.9998414,0,0,0,90.00000001 +182.49,50.30085681,-3.144328515,10000,0,199.9996184,0,0,0,90.00000001 +182.5,50.30085681,-3.144300488,10000,0,200.0000644,0,0,0,90.00000001 +182.51,50.30085681,-3.14427246,10000,0,200.0007334,0,0,0,90.00000001 +182.52,50.30085681,-3.144244433,10000,0,200.0007334,0,0,0,90.00000001 +182.53,50.30085681,-3.144216405,10000,0,200.0000644,0,0,0,90.00000001 +182.54,50.30085681,-3.144188378,10000,0,199.9996184,0,0,0,90.00000001 +182.55,50.30085681,-3.144160351,10000,0,199.9998414,0,0,0,90.00000001 +182.56,50.30085681,-3.144132323,10000,0,199.9998414,0,0,0,90.00000001 +182.57,50.30085681,-3.144104296,10000,0,199.9996184,0,0,0,90.00000001 +182.58,50.30085681,-3.144076269,10000,0,200.0000644,0,0,0,90.00000001 +182.59,50.30085681,-3.144048241,10000,0,200.0007334,0,0,0,90.00000001 +182.6,50.30085681,-3.144020214,10000,0,200.0007334,0,0,0,90.00000001 +182.61,50.30085681,-3.143992186,10000,0,200.0000644,0,0,0,90.00000001 +182.62,50.30085681,-3.143964159,10000,0,199.9996184,0,0,0,90.00000001 +182.63,50.30085681,-3.143936132,10000,0,199.9998414,0,0,0,90.00000001 +182.64,50.30085681,-3.143908104,10000,0,199.9998414,0,0,0,90.00000001 +182.65,50.30085681,-3.143880077,10000,0,199.9996184,0,0,0,90.00000001 +182.66,50.30085681,-3.14385205,10000,0,200.0000644,0,0,0,90.00000001 +182.67,50.30085681,-3.143824022,10000,0,200.0007334,0,0,0,90.00000001 +182.68,50.30085681,-3.143795995,10000,0,200.0007334,0,0,0,90.00000001 +182.69,50.30085681,-3.143767967,10000,0,200.0000644,0,0,0,90.00000001 +182.7,50.30085681,-3.14373994,10000,0,199.9996184,0,0,0,90.00000001 +182.71,50.30085681,-3.143711913,10000,0,199.9998414,0,0,0,90.00000001 +182.72,50.30085681,-3.143683885,10000,0,199.9998414,0,0,0,90.00000001 +182.73,50.30085681,-3.143655858,10000,0,199.9996184,0,0,0,90.00000001 +182.74,50.30085681,-3.143627831,10000,0,200.0000644,0,0,0,90.00000001 +182.75,50.30085681,-3.143599803,10000,0,200.0007334,0,0,0,90.00000001 +182.76,50.30085681,-3.143571776,10000,0,200.0007334,0,0,0,90.00000001 +182.77,50.30085681,-3.143543748,10000,0,199.9998414,0,0,0,90.00000001 +182.78,50.30085681,-3.143515721,10000,0,199.9987264,0,0,0,90.00000001 +182.79,50.30085681,-3.143487694,10000,0,199.9987264,0,0,0,90.00000001 +182.8,50.30085681,-3.143459667,10000,0,199.9996184,0,0,0,90.00000001 +182.81,50.30085681,-3.143431639,10000,0,199.9998414,0,0,0,90.00000001 +182.82,50.30085681,-3.143403612,10000,0,199.9996184,0,0,0,90.00000001 +182.83,50.30085681,-3.143375585,10000,0,199.9998414,0,0,0,90.00000001 +182.84,50.30085681,-3.143347557,10000,0,199.9998414,0,0,0,90.00000001 +182.85,50.30085681,-3.14331953,10000,0,199.9996184,0,0,0,90.00000001 +182.86,50.30085681,-3.143291503,10000,0,200.0000644,0,0,0,90.00000001 +182.87,50.30085681,-3.143263475,10000,0,200.0007334,0,0,0,90.00000001 +182.88,50.30085681,-3.143235448,10000,0,200.0007334,0,0,0,90.00000001 +182.89,50.30085681,-3.14320742,10000,0,200.0000644,0,0,0,90.00000001 +182.9,50.30085681,-3.143179393,10000,0,199.9996184,0,0,0,90.00000001 +182.91,50.30085681,-3.143151366,10000,0,199.9998414,0,0,0,90.00000001 +182.92,50.30085681,-3.143123338,10000,0,199.9998414,0,0,0,90.00000001 +182.93,50.30085681,-3.143095311,10000,0,199.9996184,0,0,0,90.00000001 +182.94,50.30085681,-3.143067284,10000,0,200.0000644,0,0,0,90.00000001 +182.95,50.30085681,-3.143039256,10000,0,200.0007334,0,0,0,90.00000001 +182.96,50.30085681,-3.143011229,10000,0,200.0007334,0,0,0,90.00000001 +182.97,50.30085681,-3.142983201,10000,0,200.0000644,0,0,0,90.00000001 +182.98,50.30085681,-3.142955174,10000,0,199.9996184,0,0,0,90.00000001 +182.99,50.30085681,-3.142927147,10000,0,199.9998414,0,0,0,90.00000001 +183,50.30085681,-3.142899119,10000,0,199.9998414,0,0,0,90.00000001 +183.01,50.30085681,-3.142871092,10000,0,199.9996184,0,0,0,90.00000001 +183.02,50.30085681,-3.142843065,10000,0,200.0000644,0,0,0,90.00000001 +183.03,50.30085681,-3.142815037,10000,0,200.0007334,0,0,0,90.00000001 +183.04,50.30085681,-3.14278701,10000,0,200.0007334,0,0,0,90.00000001 +183.05,50.30085681,-3.142758982,10000,0,200.0000644,0,0,0,90.00000001 +183.06,50.30085681,-3.142730955,10000,0,199.9996184,0,0,0,90.00000001 +183.07,50.30085681,-3.142702928,10000,0,199.9998414,0,0,0,90.00000001 +183.08,50.30085681,-3.1426749,10000,0,199.9998414,0,0,0,90.00000001 +183.09,50.30085681,-3.142646873,10000,0,199.9996184,0,0,0,90.00000001 +183.1,50.30085681,-3.142618846,10000,0,200.0000644,0,0,0,90.00000001 +183.11,50.30085681,-3.142590818,10000,0,200.0007334,0,0,0,90.00000001 +183.12,50.30085681,-3.142562791,10000,0,200.0007334,0,0,0,90.00000001 +183.13,50.30085681,-3.142534763,10000,0,200.0000644,0,0,0,90.00000001 +183.14,50.30085681,-3.142506736,10000,0,199.9996184,0,0,0,90.00000001 +183.15,50.30085681,-3.142478709,10000,0,199.9998414,0,0,0,90.00000001 +183.16,50.30085681,-3.142450681,10000,0,199.9998414,0,0,0,90.00000001 +183.17,50.30085681,-3.142422654,10000,0,199.9996184,0,0,0,90.00000001 +183.18,50.30085681,-3.142394627,10000,0,200.0000644,0,0,0,90.00000001 +183.19,50.30085681,-3.142366599,10000,0,200.0007334,0,0,0,90.00000001 +183.2,50.30085681,-3.142338572,10000,0,200.0007334,0,0,0,90.00000001 +183.21,50.30085681,-3.142310544,10000,0,200.0000644,0,0,0,90.00000001 +183.22,50.30085681,-3.142282517,10000,0,199.9996184,0,0,0,90.00000001 +183.23,50.30085681,-3.14225449,10000,0,199.9998414,0,0,0,90.00000001 +183.24,50.30085681,-3.142226462,10000,0,199.9998414,0,0,0,90.00000001 +183.25,50.30085681,-3.142198435,10000,0,199.9996184,0,0,0,90.00000001 +183.26,50.30085681,-3.142170408,10000,0,200.0000644,0,0,0,90.00000001 +183.27,50.30085681,-3.14214238,10000,0,200.0007334,0,0,0,90.00000001 +183.28,50.30085681,-3.142114353,10000,0,200.0007334,0,0,0,90.00000001 +183.29,50.30085681,-3.142086325,10000,0,200.0000644,0,0,0,90.00000001 +183.3,50.30085681,-3.142058298,10000,0,199.9996184,0,0,0,90.00000001 +183.31,50.30085681,-3.142030271,10000,0,199.9998414,0,0,0,90.00000001 +183.32,50.30085681,-3.142002243,10000,0,199.9996184,0,0,0,90.00000001 +183.33,50.30085681,-3.141974216,10000,0,199.9987264,0,0,0,90.00000001 +183.34,50.30085681,-3.141946189,10000,0,199.9987264,0,0,0,90.00000001 +183.35,50.30085681,-3.141918162,10000,0,199.9996184,0,0,0,90.00000001 +183.36,50.30085681,-3.141890134,10000,0,199.9998414,0,0,0,90.00000001 +183.37,50.30085681,-3.141862107,10000,0,199.9996184,0,0,0,90.00000001 +183.38,50.30085681,-3.14183408,10000,0,200.0000644,0,0,0,90.00000001 +183.39,50.30085681,-3.141806052,10000,0,200.0007334,0,0,0,90.00000001 +183.4,50.30085681,-3.141778025,10000,0,200.0007334,0,0,0,90.00000001 +183.41,50.30085681,-3.141749997,10000,0,200.0000644,0,0,0,90.00000001 +183.42,50.30085681,-3.14172197,10000,0,199.9996184,0,0,0,90.00000001 +183.43,50.30085681,-3.141693943,10000,0,199.9998414,0,0,0,90.00000001 +183.44,50.30085681,-3.141665915,10000,0,199.9998414,0,0,0,90.00000001 +183.45,50.30085681,-3.141637888,10000,0,199.9996184,0,0,0,90.00000001 +183.46,50.30085681,-3.141609861,10000,0,200.0000644,0,0,0,90.00000001 +183.47,50.30085681,-3.141581833,10000,0,200.0007334,0,0,0,90.00000001 +183.48,50.30085681,-3.141553806,10000,0,200.0007334,0,0,0,90.00000001 +183.49,50.30085681,-3.141525778,10000,0,200.0000644,0,0,0,90.00000001 +183.5,50.30085681,-3.141497751,10000,0,199.9996184,0,0,0,90.00000001 +183.51,50.30085681,-3.141469724,10000,0,199.9998414,0,0,0,90.00000001 +183.52,50.30085681,-3.141441696,10000,0,199.9998414,0,0,0,90.00000001 +183.53,50.30085681,-3.141413669,10000,0,199.9996184,0,0,0,90.00000001 +183.54,50.30085681,-3.141385642,10000,0,200.0000644,0,0,0,90.00000001 +183.55,50.30085681,-3.141357614,10000,0,200.0007334,0,0,0,90.00000001 +183.56,50.30085681,-3.141329587,10000,0,200.0007334,0,0,0,90.00000001 +183.57,50.30085681,-3.141301559,10000,0,200.0000644,0,0,0,90.00000001 +183.58,50.30085681,-3.141273532,10000,0,199.9996184,0,0,0,90.00000001 +183.59,50.30085681,-3.141245505,10000,0,199.9998414,0,0,0,90.00000001 +183.6,50.30085681,-3.141217477,10000,0,199.9998414,0,0,0,90.00000001 +183.61,50.30085681,-3.14118945,10000,0,199.9996184,0,0,0,90.00000001 +183.62,50.30085681,-3.141161423,10000,0,200.0000644,0,0,0,90.00000001 +183.63,50.30085681,-3.141133395,10000,0,200.0007334,0,0,0,90.00000001 +183.64,50.30085681,-3.141105368,10000,0,200.0007334,0,0,0,90.00000001 +183.65,50.30085681,-3.14107734,10000,0,200.0000644,0,0,0,90.00000001 +183.66,50.30085681,-3.141049313,10000,0,199.9996184,0,0,0,90.00000001 +183.67,50.30085681,-3.141021286,10000,0,199.9998414,0,0,0,90.00000001 +183.68,50.30085681,-3.140993258,10000,0,199.9998414,0,0,0,90.00000001 +183.69,50.30085681,-3.140965231,10000,0,199.9996184,0,0,0,90.00000001 +183.7,50.30085681,-3.140937204,10000,0,200.0000644,0,0,0,90.00000001 +183.71,50.30085681,-3.140909176,10000,0,200.0007334,0,0,0,90.00000001 +183.72,50.30085681,-3.140881149,10000,0,200.0007334,0,0,0,90.00000001 +183.73,50.30085681,-3.140853121,10000,0,200.0000644,0,0,0,90.00000001 +183.74,50.30085681,-3.140825094,10000,0,199.9996184,0,0,0,90.00000001 +183.75,50.30085681,-3.140797067,10000,0,199.9998414,0,0,0,90.00000001 +183.76,50.30085681,-3.140769039,10000,0,199.9998414,0,0,0,90.00000001 +183.77,50.30085681,-3.140741012,10000,0,199.9996184,0,0,0,90.00000001 +183.78,50.30085681,-3.140712985,10000,0,200.0000644,0,0,0,90.00000001 +183.79,50.30085681,-3.140684957,10000,0,200.0007334,0,0,0,90.00000001 +183.8,50.30085681,-3.14065693,10000,0,200.0007334,0,0,0,90.00000001 +183.81,50.30085681,-3.140628902,10000,0,200.0000644,0,0,0,90.00000001 +183.82,50.30085681,-3.140600875,10000,0,199.9996184,0,0,0,90.00000001 +183.83,50.30085681,-3.140572848,10000,0,199.9998414,0,0,0,90.00000001 +183.84,50.30085681,-3.14054482,10000,0,199.9998414,0,0,0,90.00000001 +183.85,50.30085681,-3.140516793,10000,0,199.9996184,0,0,0,90.00000001 +183.86,50.30085681,-3.140488766,10000,0,199.9998414,0,0,0,90.00000001 +183.87,50.30085681,-3.140460738,10000,0,199.9996184,0,0,0,90.00000001 +183.88,50.30085681,-3.140432711,10000,0,199.9987264,0,0,0,90.00000001 +183.89,50.30085681,-3.140404684,10000,0,199.9987264,0,0,0,90.00000001 +183.9,50.30085681,-3.140376657,10000,0,199.9998414,0,0,0,90.00000001 +183.91,50.30085681,-3.140348629,10000,0,200.0007334,0,0,0,90.00000001 +183.92,50.30085681,-3.140320602,10000,0,200.0007334,0,0,0,90.00000001 +183.93,50.30085681,-3.140292574,10000,0,200.0000644,0,0,0,90.00000001 +183.94,50.30085681,-3.140264547,10000,0,199.9996184,0,0,0,90.00000001 +183.95,50.30085681,-3.14023652,10000,0,199.9998414,0,0,0,90.00000001 +183.96,50.30085681,-3.140208492,10000,0,199.9998414,0,0,0,90.00000001 +183.97,50.30085681,-3.140180465,10000,0,199.9996184,0,0,0,90.00000001 +183.98,50.30085681,-3.140152438,10000,0,200.0000644,0,0,0,90.00000001 +183.99,50.30085681,-3.14012441,10000,0,200.0007334,0,0,0,90.00000001 +184,50.30085681,-3.140096383,10000,0,200.0007334,0,0,0,90.00000001 +184.01,50.30085681,-3.140068355,10000,0,200.0000644,0,0,0,90.00000001 +184.02,50.30085681,-3.140040328,10000,0,199.9996184,0,0,0,90.00000001 +184.03,50.30085681,-3.140012301,10000,0,199.9998414,0,0,0,90.00000001 +184.04,50.30085681,-3.139984273,10000,0,199.9998414,0,0,0,90.00000001 +184.05,50.30085681,-3.139956246,10000,0,199.9996184,0,0,0,90.00000001 +184.06,50.30085681,-3.139928219,10000,0,200.0000644,0,0,0,90.00000001 +184.07,50.30085681,-3.139900191,10000,0,200.0007334,0,0,0,90.00000001 +184.08,50.30085681,-3.139872164,10000,0,200.0007334,0,0,0,90.00000001 +184.09,50.30085681,-3.139844136,10000,0,200.0000644,0,0,0,90.00000001 +184.1,50.30085681,-3.139816109,10000,0,199.9996184,0,0,0,90.00000001 +184.11,50.30085681,-3.139788082,10000,0,199.9998414,0,0,0,90.00000001 +184.12,50.30085681,-3.139760054,10000,0,199.9998414,0,0,0,90.00000001 +184.13,50.30085681,-3.139732027,10000,0,199.9996184,0,0,0,90.00000001 +184.14,50.30085681,-3.139704,10000,0,200.0000644,0,0,0,90.00000001 +184.15,50.30085681,-3.139675972,10000,0,200.0007334,0,0,0,90.00000001 +184.16,50.30085681,-3.139647945,10000,0,200.0007334,0,0,0,90.00000001 +184.17,50.30085681,-3.139619917,10000,0,200.0000644,0,0,0,90.00000001 +184.18,50.30085681,-3.13959189,10000,0,199.9996184,0,0,0,90.00000001 +184.19,50.30085681,-3.139563863,10000,0,199.9998414,0,0,0,90.00000001 +184.2,50.30085681,-3.139535835,10000,0,199.9998414,0,0,0,90.00000001 +184.21,50.30085681,-3.139507808,10000,0,199.9996184,0,0,0,90.00000001 +184.22,50.30085681,-3.139479781,10000,0,200.0000644,0,0,0,90.00000001 +184.23,50.30085681,-3.139451753,10000,0,200.0007334,0,0,0,90.00000001 +184.24,50.30085681,-3.139423726,10000,0,200.0007334,0,0,0,90.00000001 +184.25,50.30085681,-3.139395698,10000,0,200.0000644,0,0,0,90.00000001 +184.26,50.30085681,-3.139367671,10000,0,199.9996184,0,0,0,90.00000001 +184.27,50.30085681,-3.139339644,10000,0,199.9998414,0,0,0,90.00000001 +184.28,50.30085681,-3.139311616,10000,0,199.9998414,0,0,0,90.00000001 +184.29,50.30085681,-3.139283589,10000,0,199.9996184,0,0,0,90.00000001 +184.3,50.30085681,-3.139255562,10000,0,200.0000644,0,0,0,90.00000001 +184.31,50.30085681,-3.139227534,10000,0,200.0007334,0,0,0,90.00000001 +184.32,50.30085681,-3.139199507,10000,0,200.0007334,0,0,0,90.00000001 +184.33,50.30085681,-3.139171479,10000,0,200.0000644,0,0,0,90.00000001 +184.34,50.30085681,-3.139143452,10000,0,199.9996184,0,0,0,90.00000001 +184.35,50.30085681,-3.139115425,10000,0,199.9998414,0,0,0,90.00000001 +184.36,50.30085681,-3.139087397,10000,0,199.9998414,0,0,0,90.00000001 +184.37,50.30085681,-3.13905937,10000,0,199.9996184,0,0,0,90.00000001 +184.38,50.30085681,-3.139031343,10000,0,200.0000644,0,0,0,90.00000001 +184.39,50.30085681,-3.139003315,10000,0,200.0007334,0,0,0,90.00000001 +184.4,50.30085681,-3.138975288,10000,0,200.0007334,0,0,0,90.00000001 +184.41,50.30085681,-3.13894726,10000,0,199.9998414,0,0,0,90.00000001 +184.42,50.30085681,-3.138919233,10000,0,199.9987264,0,0,0,90.00000001 +184.43,50.30085681,-3.138891206,10000,0,199.9987264,0,0,0,90.00000001 +184.44,50.30085681,-3.138863179,10000,0,199.9996184,0,0,0,90.00000001 +184.45,50.30085681,-3.138835151,10000,0,199.9998414,0,0,0,90.00000001 +184.46,50.30085681,-3.138807124,10000,0,199.9996184,0,0,0,90.00000001 +184.47,50.30085681,-3.138779097,10000,0,199.9998414,0,0,0,90.00000001 +184.48,50.30085681,-3.138751069,10000,0,199.9998414,0,0,0,90.00000001 +184.49,50.30085681,-3.138723042,10000,0,199.9996184,0,0,0,90.00000001 +184.5,50.30085681,-3.138695015,10000,0,200.0000644,0,0,0,90.00000001 +184.51,50.30085681,-3.138666987,10000,0,200.0007334,0,0,0,90.00000001 +184.52,50.30085681,-3.13863896,10000,0,200.0007334,0,0,0,90.00000001 +184.53,50.30085681,-3.138610932,10000,0,200.0000644,0,0,0,90.00000001 +184.54,50.30085681,-3.138582905,10000,0,199.9996184,0,0,0,90.00000001 +184.55,50.30085681,-3.138554878,10000,0,199.9998414,0,0,0,90.00000001 +184.56,50.30085681,-3.13852685,10000,0,199.9998414,0,0,0,90.00000001 +184.57,50.30085681,-3.138498823,10000,0,199.9996184,0,0,0,90.00000001 +184.58,50.30085681,-3.138470796,10000,0,200.0000644,0,0,0,90.00000001 +184.59,50.30085681,-3.138442768,10000,0,200.0007334,0,0,0,90.00000001 +184.6,50.30085681,-3.138414741,10000,0,200.0007334,0,0,0,90.00000001 +184.61,50.30085681,-3.138386713,10000,0,200.0000644,0,0,0,90.00000001 +184.62,50.30085681,-3.138358686,10000,0,199.9996184,0,0,0,90.00000001 +184.63,50.30085681,-3.138330659,10000,0,199.9998414,0,0,0,90.00000001 +184.64,50.30085681,-3.138302631,10000,0,199.9998414,0,0,0,90.00000001 +184.65,50.30085681,-3.138274604,10000,0,199.9996184,0,0,0,90.00000001 +184.66,50.30085681,-3.138246577,10000,0,200.0000644,0,0,0,90.00000001 +184.67,50.30085681,-3.138218549,10000,0,200.0007334,0,0,0,90.00000001 +184.68,50.30085681,-3.138190522,10000,0,200.0007334,0,0,0,90.00000001 +184.69,50.30085681,-3.138162494,10000,0,200.0000644,0,0,0,90.00000001 +184.7,50.30085681,-3.138134467,10000,0,199.9996184,0,0,0,90.00000001 +184.71,50.30085681,-3.13810644,10000,0,199.9998414,0,0,0,90.00000001 +184.72,50.30085681,-3.138078412,10000,0,199.9998414,0,0,0,90.00000001 +184.73,50.30085681,-3.138050385,10000,0,199.9996184,0,0,0,90.00000001 +184.74,50.30085681,-3.138022358,10000,0,200.0000644,0,0,0,90.00000001 +184.75,50.30085681,-3.13799433,10000,0,200.0007334,0,0,0,90.00000001 +184.76,50.30085681,-3.137966303,10000,0,200.0007334,0,0,0,90.00000001 +184.77,50.30085681,-3.137938275,10000,0,200.0000644,0,0,0,90.00000001 +184.78,50.30085681,-3.137910248,10000,0,199.9996184,0,0,0,90.00000001 +184.79,50.30085681,-3.137882221,10000,0,199.9998414,0,0,0,90.00000001 +184.8,50.30085681,-3.137854193,10000,0,199.9998414,0,0,0,90.00000001 +184.81,50.30085681,-3.137826166,10000,0,199.9996184,0,0,0,90.00000001 +184.82,50.30085681,-3.137798139,10000,0,200.0000644,0,0,0,90.00000001 +184.83,50.30085681,-3.137770111,10000,0,200.0007334,0,0,0,90.00000001 +184.84,50.30085681,-3.137742084,10000,0,200.0007334,0,0,0,90.00000001 +184.85,50.30085681,-3.137714056,10000,0,200.0000644,0,0,0,90.00000001 +184.86,50.30085681,-3.137686029,10000,0,199.9996184,0,0,0,90.00000001 +184.87,50.30085681,-3.137658002,10000,0,199.9998414,0,0,0,90.00000001 +184.88,50.30085681,-3.137629974,10000,0,199.9998414,0,0,0,90.00000001 +184.89,50.30085681,-3.137601947,10000,0,199.9996184,0,0,0,90.00000001 +184.9,50.30085681,-3.13757392,10000,0,200.0000644,0,0,0,90.00000001 +184.91,50.30085681,-3.137545892,10000,0,200.0007334,0,0,0,90.00000001 +184.92,50.30085681,-3.137517865,10000,0,200.0007334,0,0,0,90.00000001 +184.93,50.30085681,-3.137489837,10000,0,200.0000644,0,0,0,90.00000001 +184.94,50.30085681,-3.13746181,10000,0,199.9996184,0,0,0,90.00000001 +184.95,50.30085681,-3.137433783,10000,0,200.0000644,0,0,0,90.00000001 +184.96,50.30085681,-3.137405755,10000,0,200.0005104,0,0,0,90.00000001 +184.97,50.30085681,-3.137377728,10000,0,199.9998414,0,0,0,90.00000001 +184.98,50.30085681,-3.1373497,10000,0,199.9987264,0,0,0,90.00000001 +184.99,50.30085681,-3.137321674,10000,0,199.9985034,0,0,0,90.00000001 +185,50.30085681,-3.137293646,10000,0,199.9989494,0,0,0,90.00000001 +185.01,50.30085681,-3.137265619,10000,0,199.9993954,0,0,0,90.00000001 +185.02,50.30085681,-3.137237592,10000,0,200.0000644,0,0,0,90.00000001 +185.03,50.30085681,-3.137209564,10000,0,200.0007334,0,0,0,90.00000001 +185.04,50.30085681,-3.137181537,10000,0,200.0007334,0,0,0,90.00000001 +185.05,50.30085681,-3.137153509,10000,0,200.0000644,0,0,0,90.00000001 +185.06,50.30085681,-3.137125482,10000,0,199.9996184,0,0,0,90.00000001 +185.07,50.30085681,-3.137097455,10000,0,199.9998414,0,0,0,90.00000001 +185.08,50.30085681,-3.137069427,10000,0,199.9998414,0,0,0,90.00000001 +185.09,50.30085681,-3.1370414,10000,0,199.9996184,0,0,0,90.00000001 +185.1,50.30085681,-3.137013373,10000,0,200.0000644,0,0,0,90.00000001 +185.11,50.30085681,-3.136985345,10000,0,200.0007334,0,0,0,90.00000001 +185.12,50.30085681,-3.136957318,10000,0,200.0007334,0,0,0,90.00000001 +185.13,50.30085681,-3.13692929,10000,0,200.0000644,0,0,0,90.00000001 +185.14,50.30085681,-3.136901263,10000,0,199.9996184,0,0,0,90.00000001 +185.15,50.30085681,-3.136873236,10000,0,199.9998414,0,0,0,90.00000001 +185.16,50.30085681,-3.136845208,10000,0,199.9998414,0,0,0,90.00000001 +185.17,50.30085681,-3.136817181,10000,0,199.9996184,0,0,0,90.00000001 +185.18,50.30085681,-3.136789154,10000,0,200.0000644,0,0,0,90.00000001 +185.19,50.30085681,-3.136761126,10000,0,200.0007334,0,0,0,90.00000001 +185.2,50.30085681,-3.136733099,10000,0,200.0007334,0,0,0,90.00000001 +185.21,50.30085681,-3.136705071,10000,0,200.0000644,0,0,0,90.00000001 +185.22,50.30085681,-3.136677044,10000,0,199.9996184,0,0,0,90.00000001 +185.23,50.30085681,-3.136649017,10000,0,199.9998414,0,0,0,90.00000001 +185.24,50.30085681,-3.136620989,10000,0,199.9998414,0,0,0,90.00000001 +185.25,50.30085681,-3.136592962,10000,0,199.9996184,0,0,0,90.00000001 +185.26,50.30085681,-3.136564935,10000,0,200.0000644,0,0,0,90.00000001 +185.27,50.30085681,-3.136536907,10000,0,200.0007334,0,0,0,90.00000001 +185.28,50.30085681,-3.13650888,10000,0,200.0007334,0,0,0,90.00000001 +185.29,50.30085681,-3.136480852,10000,0,200.0000644,0,0,0,90.00000001 +185.3,50.30085681,-3.136452825,10000,0,199.9996184,0,0,0,90.00000001 +185.31,50.30085681,-3.136424798,10000,0,199.9998414,0,0,0,90.00000001 +185.32,50.30085681,-3.13639677,10000,0,199.9998414,0,0,0,90.00000001 +185.33,50.30085681,-3.136368743,10000,0,199.9996184,0,0,0,90.00000001 +185.34,50.30085681,-3.136340716,10000,0,200.0000644,0,0,0,90.00000001 +185.35,50.30085681,-3.136312688,10000,0,200.0007334,0,0,0,90.00000001 +185.36,50.30085681,-3.136284661,10000,0,200.0007334,0,0,0,90.00000001 +185.37,50.30085681,-3.136256633,10000,0,200.0000644,0,0,0,90.00000001 +185.38,50.30085681,-3.136228606,10000,0,199.9996184,0,0,0,90.00000001 +185.39,50.30085681,-3.136200579,10000,0,200.0000644,0,0,0,90.00000001 +185.4,50.30085681,-3.136172551,10000,0,200.0007334,0,0,0,90.00000001 +185.41,50.30085681,-3.136144524,10000,0,200.0007334,0,0,0,90.00000001 +185.42,50.30085681,-3.136116496,10000,0,200.0000644,0,0,0,90.00000001 +185.43,50.30085681,-3.136088469,10000,0,199.9996184,0,0,0,90.00000001 +185.44,50.30085681,-3.136060442,10000,0,199.9998414,0,0,0,90.00000001 +185.45,50.30085681,-3.136032414,10000,0,199.9998414,0,0,0,90.00000001 +185.46,50.30085681,-3.136004387,10000,0,199.9996184,0,0,0,90.00000001 +185.47,50.30085681,-3.13597636,10000,0,200.0000644,0,0,0,90.00000001 +185.48,50.30085681,-3.135948332,10000,0,200.0007334,0,0,0,90.00000001 +185.49,50.30085681,-3.135920305,10000,0,200.0007334,0,0,0,90.00000001 +185.5,50.30085681,-3.135892277,10000,0,199.9998414,0,0,0,90.00000001 +185.51,50.30085681,-3.13586425,10000,0,199.9985034,0,0,0,90.00000001 +185.52,50.30085681,-3.135836223,10000,0,199.9978344,0,0,0,90.00000001 +185.53,50.30085681,-3.135808196,10000,0,199.9985034,0,0,0,90.00000001 +185.54,50.30085681,-3.135780169,10000,0,199.9998414,0,0,0,90.00000001 +185.55,50.30085681,-3.135752141,10000,0,200.0007334,0,0,0,90.00000001 +185.56,50.30085681,-3.135724114,10000,0,200.0007334,0,0,0,90.00000001 +185.57,50.30085681,-3.135696086,10000,0,200.0000644,0,0,0,90.00000001 +185.58,50.30085681,-3.135668059,10000,0,199.9996184,0,0,0,90.00000001 +185.59,50.30085681,-3.135640032,10000,0,199.9998414,0,0,0,90.00000001 +185.6,50.30085681,-3.135612004,10000,0,199.9998414,0,0,0,90.00000001 +185.61,50.30085681,-3.135583977,10000,0,199.9996184,0,0,0,90.00000001 +185.62,50.30085681,-3.13555595,10000,0,200.0000644,0,0,0,90.00000001 +185.63,50.30085681,-3.135527922,10000,0,200.0007334,0,0,0,90.00000001 +185.64,50.30085681,-3.135499895,10000,0,200.0007334,0,0,0,90.00000001 +185.65,50.30085681,-3.135471867,10000,0,200.0000644,0,0,0,90.00000001 +185.66,50.30085681,-3.13544384,10000,0,199.9996184,0,0,0,90.00000001 +185.67,50.30085681,-3.135415813,10000,0,199.9998414,0,0,0,90.00000001 +185.68,50.30085681,-3.135387785,10000,0,199.9998414,0,0,0,90.00000001 +185.69,50.30085681,-3.135359758,10000,0,199.9996184,0,0,0,90.00000001 +185.7,50.30085681,-3.135331731,10000,0,200.0000644,0,0,0,90.00000001 +185.71,50.30085681,-3.135303703,10000,0,200.0007334,0,0,0,90.00000001 +185.72,50.30085681,-3.135275676,10000,0,200.0007334,0,0,0,90.00000001 +185.73,50.30085681,-3.135247648,10000,0,200.0000644,0,0,0,90.00000001 +185.74,50.30085681,-3.135219621,10000,0,199.9996184,0,0,0,90.00000001 +185.75,50.30085681,-3.135191594,10000,0,199.9998414,0,0,0,90.00000001 +185.76,50.30085681,-3.135163566,10000,0,199.9998414,0,0,0,90.00000001 +185.77,50.30085681,-3.135135539,10000,0,199.9996184,0,0,0,90.00000001 +185.78,50.30085681,-3.135107512,10000,0,200.0000644,0,0,0,90.00000001 +185.79,50.30085681,-3.135079484,10000,0,200.0007334,0,0,0,90.00000001 +185.8,50.30085681,-3.135051457,10000,0,200.0007334,0,0,0,90.00000001 +185.81,50.30085681,-3.135023429,10000,0,200.0000644,0,0,0,90.00000001 +185.82,50.30085681,-3.134995402,10000,0,199.9996184,0,0,0,90.00000001 +185.83,50.30085681,-3.134967375,10000,0,199.9998414,0,0,0,90.00000001 +185.84,50.30085681,-3.134939347,10000,0,199.9998414,0,0,0,90.00000001 +185.85,50.30085681,-3.13491132,10000,0,199.9996184,0,0,0,90.00000001 +185.86,50.30085681,-3.134883293,10000,0,200.0000644,0,0,0,90.00000001 +185.87,50.30085681,-3.134855265,10000,0,200.0007334,0,0,0,90.00000001 +185.88,50.30085681,-3.134827238,10000,0,200.0007334,0,0,0,90.00000001 +185.89,50.30085681,-3.13479921,10000,0,200.0000644,0,0,0,90.00000001 +185.9,50.30085681,-3.134771183,10000,0,199.9996184,0,0,0,90.00000001 +185.91,50.30085681,-3.134743156,10000,0,200.0000644,0,0,0,90.00000001 +185.92,50.30085681,-3.134715128,10000,0,200.0007334,0,0,0,90.00000001 +185.93,50.30085681,-3.134687101,10000,0,200.0007334,0,0,0,90.00000001 +185.94,50.30085681,-3.134659073,10000,0,200.0000644,0,0,0,90.00000001 +185.95,50.30085681,-3.134631046,10000,0,199.9996184,0,0,0,90.00000001 +185.96,50.30085681,-3.134603019,10000,0,199.9998414,0,0,0,90.00000001 +185.97,50.30085681,-3.134574991,10000,0,199.9998414,0,0,0,90.00000001 +185.98,50.30085681,-3.134546964,10000,0,199.9996184,0,0,0,90.00000001 +185.99,50.30085681,-3.134518937,10000,0,200.0000644,0,0,0,90.00000001 +186,50.30085681,-3.134490909,10000,0,200.0007334,0,0,0,90.00000001 +186.01,50.30085681,-3.134462882,10000,0,200.0007334,0,0,0,90.00000001 +186.02,50.30085681,-3.134434854,10000,0,200.0000644,0,0,0,90.00000001 +186.03,50.30085681,-3.134406827,10000,0,199.9996184,0,0,0,90.00000001 +186.04,50.30085681,-3.1343788,10000,0,199.9998414,0,0,0,90.00000001 +186.05,50.30085681,-3.134350772,10000,0,199.9996184,0,0,0,90.00000001 +186.06,50.30085681,-3.134322745,10000,0,199.9987264,0,0,0,90.00000001 +186.07,50.30085681,-3.134294718,10000,0,199.9987264,0,0,0,90.00000001 +186.08,50.30085681,-3.134266691,10000,0,199.9996184,0,0,0,90.00000001 +186.09,50.30085681,-3.134238663,10000,0,199.9998414,0,0,0,90.00000001 +186.1,50.30085681,-3.134210636,10000,0,199.9996184,0,0,0,90.00000001 +186.11,50.30085681,-3.134182609,10000,0,199.9998414,0,0,0,90.00000001 +186.12,50.30085681,-3.134154581,10000,0,199.9998414,0,0,0,90.00000001 +186.13,50.30085681,-3.134126554,10000,0,199.9996184,0,0,0,90.00000001 +186.14,50.30085681,-3.134098527,10000,0,200.0000644,0,0,0,90.00000001 +186.15,50.30085681,-3.134070499,10000,0,200.0007334,0,0,0,90.00000001 +186.16,50.30085681,-3.134042472,10000,0,200.0007334,0,0,0,90.00000001 +186.17,50.30085681,-3.134014444,10000,0,200.0000644,0,0,0,90.00000001 +186.18,50.30085681,-3.133986417,10000,0,199.9996184,0,0,0,90.00000001 +186.19,50.30085681,-3.13395839,10000,0,199.9998414,0,0,0,90.00000001 +186.2,50.30085681,-3.133930362,10000,0,199.9998414,0,0,0,90.00000001 +186.21,50.30085681,-3.133902335,10000,0,199.9996184,0,0,0,90.00000001 +186.22,50.30085681,-3.133874308,10000,0,200.0000644,0,0,0,90.00000001 +186.23,50.30085681,-3.13384628,10000,0,200.0007334,0,0,0,90.00000001 +186.24,50.30085681,-3.133818253,10000,0,200.0007334,0,0,0,90.00000001 +186.25,50.30085681,-3.133790225,10000,0,200.0000644,0,0,0,90.00000001 +186.26,50.30085681,-3.133762198,10000,0,199.9996184,0,0,0,90.00000001 +186.27,50.30085681,-3.133734171,10000,0,199.9998414,0,0,0,90.00000001 +186.28,50.30085681,-3.133706143,10000,0,199.9998414,0,0,0,90.00000001 +186.29,50.30085681,-3.133678116,10000,0,199.9996184,0,0,0,90.00000001 +186.3,50.30085681,-3.133650089,10000,0,200.0000644,0,0,0,90.00000001 +186.31,50.30085681,-3.133622061,10000,0,200.0007334,0,0,0,90.00000001 +186.32,50.30085681,-3.133594034,10000,0,200.0007334,0,0,0,90.00000001 +186.33,50.30085681,-3.133566006,10000,0,200.0000644,0,0,0,90.00000001 +186.34,50.30085681,-3.133537979,10000,0,199.9996184,0,0,0,90.00000001 +186.35,50.30085681,-3.133509952,10000,0,199.9998414,0,0,0,90.00000001 +186.36,50.30085681,-3.133481924,10000,0,199.9998414,0,0,0,90.00000001 +186.37,50.30085681,-3.133453897,10000,0,199.9996184,0,0,0,90.00000001 +186.38,50.30085681,-3.13342587,10000,0,200.0000644,0,0,0,90.00000001 +186.39,50.30085681,-3.133397842,10000,0,200.0007334,0,0,0,90.00000001 +186.4,50.30085681,-3.133369815,10000,0,200.0007334,0,0,0,90.00000001 +186.41,50.30085681,-3.133341787,10000,0,200.0000644,0,0,0,90.00000001 +186.42,50.30085681,-3.13331376,10000,0,199.9996184,0,0,0,90.00000001 +186.43,50.30085681,-3.133285733,10000,0,200.0000644,0,0,0,90.00000001 +186.44,50.30085681,-3.133257705,10000,0,200.0007334,0,0,0,90.00000001 +186.45,50.30085681,-3.133229678,10000,0,200.0007334,0,0,0,90.00000001 +186.46,50.30085681,-3.13320165,10000,0,200.0000644,0,0,0,90.00000001 +186.47,50.30085681,-3.133173623,10000,0,199.9996184,0,0,0,90.00000001 +186.48,50.30085681,-3.133145596,10000,0,199.9998414,0,0,0,90.00000001 +186.49,50.30085681,-3.133117568,10000,0,199.9998414,0,0,0,90.00000001 +186.5,50.30085681,-3.133089541,10000,0,199.9996184,0,0,0,90.00000001 +186.51,50.30085681,-3.133061514,10000,0,200.0000644,0,0,0,90.00000001 +186.52,50.30085681,-3.133033486,10000,0,200.0007334,0,0,0,90.00000001 +186.53,50.30085681,-3.133005459,10000,0,200.0007334,0,0,0,90.00000001 +186.54,50.30085681,-3.132977431,10000,0,200.0000644,0,0,0,90.00000001 +186.55,50.30085681,-3.132949404,10000,0,199.9996184,0,0,0,90.00000001 +186.56,50.30085681,-3.132921377,10000,0,199.9998414,0,0,0,90.00000001 +186.57,50.30085681,-3.132893349,10000,0,199.9998414,0,0,0,90.00000001 +186.58,50.30085681,-3.132865322,10000,0,199.9996184,0,0,0,90.00000001 +186.59,50.30085681,-3.132837295,10000,0,200.0000644,0,0,0,90.00000001 +186.6,50.30085681,-3.132809267,10000,0,200.0005104,0,0,0,90.00000001 +186.61,50.30085681,-3.13278124,10000,0,199.9998414,0,0,0,90.00000001 +186.62,50.30085681,-3.132753212,10000,0,199.9987264,0,0,0,90.00000001 +186.63,50.30085681,-3.132725186,10000,0,199.9985034,0,0,0,90.00000001 +186.64,50.30085681,-3.132697158,10000,0,199.9989494,0,0,0,90.00000001 +186.65,50.30085681,-3.132669131,10000,0,199.9993954,0,0,0,90.00000001 +186.66,50.30085681,-3.132641104,10000,0,200.0000644,0,0,0,90.00000001 +186.67,50.30085681,-3.132613076,10000,0,200.0007334,0,0,0,90.00000001 +186.68,50.30085681,-3.132585049,10000,0,200.0007334,0,0,0,90.00000001 +186.69,50.30085681,-3.132557021,10000,0,200.0000644,0,0,0,90.00000001 +186.7,50.30085681,-3.132528994,10000,0,199.9996184,0,0,0,90.00000001 +186.71,50.30085681,-3.132500967,10000,0,199.9998414,0,0,0,90.00000001 +186.72,50.30085681,-3.132472939,10000,0,199.9998414,0,0,0,90.00000001 +186.73,50.30085681,-3.132444912,10000,0,199.9996184,0,0,0,90.00000001 +186.74,50.30085681,-3.132416885,10000,0,200.0000644,0,0,0,90.00000001 +186.75,50.30085681,-3.132388857,10000,0,200.0007334,0,0,0,90.00000001 +186.76,50.30085681,-3.13236083,10000,0,200.0007334,0,0,0,90.00000001 +186.77,50.30085681,-3.132332802,10000,0,200.0000644,0,0,0,90.00000001 +186.78,50.30085681,-3.132304775,10000,0,199.9996184,0,0,0,90.00000001 +186.79,50.30085681,-3.132276748,10000,0,199.9998414,0,0,0,90.00000001 +186.8,50.30085681,-3.13224872,10000,0,199.9998414,0,0,0,90.00000001 +186.81,50.30085681,-3.132220693,10000,0,199.9996184,0,0,0,90.00000001 +186.82,50.30085681,-3.132192666,10000,0,200.0000644,0,0,0,90.00000001 +186.83,50.30085681,-3.132164638,10000,0,200.0007334,0,0,0,90.00000001 +186.84,50.30085681,-3.132136611,10000,0,200.0007334,0,0,0,90.00000001 +186.85,50.30085681,-3.132108583,10000,0,200.0000644,0,0,0,90.00000001 +186.86,50.30085681,-3.132080556,10000,0,199.9996184,0,0,0,90.00000001 +186.87,50.30085681,-3.132052529,10000,0,199.9998414,0,0,0,90.00000001 +186.88,50.30085681,-3.132024501,10000,0,199.9998414,0,0,0,90.00000001 +186.89,50.30085681,-3.131996474,10000,0,199.9996184,0,0,0,90.00000001 +186.9,50.30085681,-3.131968447,10000,0,200.0000644,0,0,0,90.00000001 +186.91,50.30085681,-3.131940419,10000,0,200.0007334,0,0,0,90.00000001 +186.92,50.30085681,-3.131912392,10000,0,200.0007334,0,0,0,90.00000001 +186.93,50.30085681,-3.131884364,10000,0,200.0000644,0,0,0,90.00000001 +186.94,50.30085681,-3.131856337,10000,0,199.9996184,0,0,0,90.00000001 +186.95,50.30085681,-3.13182831,10000,0,200.0000644,0,0,0,90.00000001 +186.96,50.30085681,-3.131800282,10000,0,200.0007334,0,0,0,90.00000001 +186.97,50.30085681,-3.131772255,10000,0,200.0007334,0,0,0,90.00000001 +186.98,50.30085681,-3.131744227,10000,0,200.0000644,0,0,0,90.00000001 +186.99,50.30085681,-3.1317162,10000,0,199.9996184,0,0,0,90.00000001 +187,50.30085681,-3.131688173,10000,0,199.9998414,0,0,0,90.00000001 +187.01,50.30085681,-3.131660145,10000,0,199.9998414,0,0,0,90.00000001 +187.02,50.30085681,-3.131632118,10000,0,199.9996184,0,0,0,90.00000001 +187.03,50.30085681,-3.131604091,10000,0,200.0000644,0,0,0,90.00000001 +187.04,50.30085681,-3.131576063,10000,0,200.0007334,0,0,0,90.00000001 +187.05,50.30085681,-3.131548036,10000,0,200.0007334,0,0,0,90.00000001 +187.06,50.30085681,-3.131520008,10000,0,200.0000644,0,0,0,90.00000001 +187.07,50.30085681,-3.131491981,10000,0,199.9996184,0,0,0,90.00000001 +187.08,50.30085681,-3.131463954,10000,0,199.9998414,0,0,0,90.00000001 +187.09,50.30085681,-3.131435926,10000,0,199.9998414,0,0,0,90.00000001 +187.1,50.30085681,-3.131407899,10000,0,199.9996184,0,0,0,90.00000001 +187.11,50.30085681,-3.131379872,10000,0,200.0000644,0,0,0,90.00000001 +187.12,50.30085681,-3.131351844,10000,0,200.0007334,0,0,0,90.00000001 +187.13,50.30085681,-3.131323817,10000,0,200.0007334,0,0,0,90.00000001 +187.14,50.30085681,-3.131295789,10000,0,199.9998414,0,0,0,90.00000001 +187.15,50.30085681,-3.131267762,10000,0,199.9985034,0,0,0,90.00000001 +187.16,50.30085681,-3.131239735,10000,0,199.9978344,0,0,0,90.00000001 +187.17,50.30085681,-3.131211708,10000,0,199.9985034,0,0,0,90.00000001 +187.18,50.30085681,-3.131183681,10000,0,199.9998414,0,0,0,90.00000001 +187.19,50.30085681,-3.131155653,10000,0,200.0007334,0,0,0,90.00000001 +187.2,50.30085681,-3.131127626,10000,0,200.0007334,0,0,0,90.00000001 +187.21,50.30085681,-3.131099598,10000,0,200.0000644,0,0,0,90.00000001 +187.22,50.30085681,-3.131071571,10000,0,199.9996184,0,0,0,90.00000001 +187.23,50.30085681,-3.131043544,10000,0,199.9998414,0,0,0,90.00000001 +187.24,50.30085681,-3.131015516,10000,0,199.9998414,0,0,0,90.00000001 +187.25,50.30085681,-3.130987489,10000,0,199.9996184,0,0,0,90.00000001 +187.26,50.30085681,-3.130959462,10000,0,200.0000644,0,0,0,90.00000001 +187.27,50.30085681,-3.130931434,10000,0,200.0007334,0,0,0,90.00000001 +187.28,50.30085681,-3.130903407,10000,0,200.0007334,0,0,0,90.00000001 +187.29,50.30085681,-3.130875379,10000,0,200.0000644,0,0,0,90.00000001 +187.3,50.30085681,-3.130847352,10000,0,199.9996184,0,0,0,90.00000001 +187.31,50.30085681,-3.130819325,10000,0,199.9998414,0,0,0,90.00000001 +187.32,50.30085681,-3.130791297,10000,0,199.9998414,0,0,0,90.00000001 +187.33,50.30085681,-3.13076327,10000,0,199.9996184,0,0,0,90.00000001 +187.34,50.30085681,-3.130735243,10000,0,200.0000644,0,0,0,90.00000001 +187.35,50.30085681,-3.130707215,10000,0,200.0007334,0,0,0,90.00000001 +187.36,50.30085681,-3.130679188,10000,0,200.0007334,0,0,0,90.00000001 +187.37,50.30085681,-3.13065116,10000,0,200.0000644,0,0,0,90.00000001 +187.38,50.30085681,-3.130623133,10000,0,199.9996184,0,0,0,90.00000001 +187.39,50.30085681,-3.130595106,10000,0,200.0000644,0,0,0,90.00000001 +187.4,50.30085681,-3.130567078,10000,0,200.0007334,0,0,0,90.00000001 +187.41,50.30085681,-3.130539051,10000,0,200.0007334,0,0,0,90.00000001 +187.42,50.30085681,-3.130511023,10000,0,200.0000644,0,0,0,90.00000001 +187.43,50.30085681,-3.130482996,10000,0,199.9996184,0,0,0,90.00000001 +187.44,50.30085681,-3.130454969,10000,0,199.9998414,0,0,0,90.00000001 +187.45,50.30085681,-3.130426941,10000,0,199.9998414,0,0,0,90.00000001 +187.46,50.30085681,-3.130398914,10000,0,199.9996184,0,0,0,90.00000001 +187.47,50.30085681,-3.130370887,10000,0,200.0000644,0,0,0,90.00000001 +187.48,50.30085681,-3.130342859,10000,0,200.0007334,0,0,0,90.00000001 +187.49,50.30085681,-3.130314832,10000,0,200.0007334,0,0,0,90.00000001 +187.5,50.30085681,-3.130286804,10000,0,200.0000644,0,0,0,90.00000001 +187.51,50.30085681,-3.130258777,10000,0,199.9996184,0,0,0,90.00000001 +187.52,50.30085681,-3.13023075,10000,0,199.9998414,0,0,0,90.00000001 +187.53,50.30085681,-3.130202722,10000,0,199.9998414,0,0,0,90.00000001 +187.54,50.30085681,-3.130174695,10000,0,199.9996184,0,0,0,90.00000001 +187.55,50.30085681,-3.130146668,10000,0,200.0000644,0,0,0,90.00000001 +187.56,50.30085681,-3.13011864,10000,0,200.0007334,0,0,0,90.00000001 +187.57,50.30085681,-3.130090613,10000,0,200.0007334,0,0,0,90.00000001 +187.58,50.30085681,-3.130062585,10000,0,200.0000644,0,0,0,90.00000001 +187.59,50.30085681,-3.130034558,10000,0,199.9996184,0,0,0,90.00000001 +187.6,50.30085681,-3.130006531,10000,0,199.9998414,0,0,0,90.00000001 +187.61,50.30085681,-3.129978503,10000,0,199.9998414,0,0,0,90.00000001 +187.62,50.30085681,-3.129950476,10000,0,199.9996184,0,0,0,90.00000001 +187.63,50.30085681,-3.129922449,10000,0,200.0000644,0,0,0,90.00000001 +187.64,50.30085681,-3.129894421,10000,0,200.0007334,0,0,0,90.00000001 +187.65,50.30085681,-3.129866394,10000,0,200.0007334,0,0,0,90.00000001 +187.66,50.30085681,-3.129838366,10000,0,200.0000644,0,0,0,90.00000001 +187.67,50.30085681,-3.129810339,10000,0,199.9996184,0,0,0,90.00000001 +187.68,50.30085681,-3.129782312,10000,0,199.9998414,0,0,0,90.00000001 +187.69,50.30085681,-3.129754284,10000,0,199.9996184,0,0,0,90.00000001 +187.7,50.30085681,-3.129726257,10000,0,199.9987264,0,0,0,90.00000001 +187.71,50.30085681,-3.12969823,10000,0,199.9987264,0,0,0,90.00000001 +187.72,50.30085681,-3.129670203,10000,0,199.9996184,0,0,0,90.00000001 +187.73,50.30085681,-3.129642175,10000,0,199.9998414,0,0,0,90.00000001 +187.74,50.30085681,-3.129614148,10000,0,199.9996184,0,0,0,90.00000001 +187.75,50.30085681,-3.129586121,10000,0,199.9998414,0,0,0,90.00000001 +187.76,50.30085681,-3.129558093,10000,0,199.9998414,0,0,0,90.00000001 +187.77,50.30085681,-3.129530066,10000,0,199.9996184,0,0,0,90.00000001 +187.78,50.30085681,-3.129502039,10000,0,200.0000644,0,0,0,90.00000001 +187.79,50.30085681,-3.129474011,10000,0,200.0007334,0,0,0,90.00000001 +187.8,50.30085681,-3.129445984,10000,0,200.0007334,0,0,0,90.00000001 +187.81,50.30085681,-3.129417956,10000,0,200.0000644,0,0,0,90.00000001 +187.82,50.30085681,-3.129389929,10000,0,199.9996184,0,0,0,90.00000001 +187.83,50.30085681,-3.129361902,10000,0,199.9998414,0,0,0,90.00000001 +187.84,50.30085681,-3.129333874,10000,0,199.9998414,0,0,0,90.00000001 +187.85,50.30085681,-3.129305847,10000,0,199.9996184,0,0,0,90.00000001 +187.86,50.30085681,-3.12927782,10000,0,200.0000644,0,0,0,90.00000001 +187.87,50.30085681,-3.129249792,10000,0,200.0007334,0,0,0,90.00000001 +187.88,50.30085681,-3.129221765,10000,0,200.0007334,0,0,0,90.00000001 +187.89,50.30085681,-3.129193737,10000,0,200.0000644,0,0,0,90.00000001 +187.9,50.30085681,-3.12916571,10000,0,199.9996184,0,0,0,90.00000001 +187.91,50.30085681,-3.129137683,10000,0,200.0000644,0,0,0,90.00000001 +187.92,50.30085681,-3.129109655,10000,0,200.0007334,0,0,0,90.00000001 +187.93,50.30085681,-3.129081628,10000,0,200.0007334,0,0,0,90.00000001 +187.94,50.30085681,-3.1290536,10000,0,200.0000644,0,0,0,90.00000001 +187.95,50.30085681,-3.129025573,10000,0,199.9996184,0,0,0,90.00000001 +187.96,50.30085681,-3.128997546,10000,0,199.9998414,0,0,0,90.00000001 +187.97,50.30085681,-3.128969518,10000,0,199.9998414,0,0,0,90.00000001 +187.98,50.30085681,-3.128941491,10000,0,199.9996184,0,0,0,90.00000001 +187.99,50.30085681,-3.128913464,10000,0,200.0000644,0,0,0,90.00000001 +188,50.30085681,-3.128885436,10000,0,200.0007334,0,0,0,90.00000001 +188.01,50.30085681,-3.128857409,10000,0,200.0007334,0,0,0,90.00000001 +188.02,50.30085681,-3.128829381,10000,0,200.0000644,0,0,0,90.00000001 +188.03,50.30085681,-3.128801354,10000,0,199.9996184,0,0,0,90.00000001 +188.04,50.30085681,-3.128773327,10000,0,199.9998414,0,0,0,90.00000001 +188.05,50.30085681,-3.128745299,10000,0,199.9998414,0,0,0,90.00000001 +188.06,50.30085681,-3.128717272,10000,0,199.9996184,0,0,0,90.00000001 +188.07,50.30085681,-3.128689245,10000,0,200.0000644,0,0,0,90.00000001 +188.08,50.30085681,-3.128661217,10000,0,200.0007334,0,0,0,90.00000001 +188.09,50.30085681,-3.12863319,10000,0,200.0007334,0,0,0,90.00000001 +188.1,50.30085681,-3.128605162,10000,0,200.0000644,0,0,0,90.00000001 +188.11,50.30085681,-3.128577135,10000,0,199.9996184,0,0,0,90.00000001 +188.12,50.30085681,-3.128549108,10000,0,199.9998414,0,0,0,90.00000001 +188.13,50.30085681,-3.12852108,10000,0,199.9998414,0,0,0,90.00000001 +188.14,50.30085681,-3.128493053,10000,0,199.9996184,0,0,0,90.00000001 +188.15,50.30085681,-3.128465026,10000,0,200.0000644,0,0,0,90.00000001 +188.16,50.30085681,-3.128436998,10000,0,200.0007334,0,0,0,90.00000001 +188.17,50.30085681,-3.128408971,10000,0,200.0007334,0,0,0,90.00000001 +188.18,50.30085681,-3.128380943,10000,0,200.0000644,0,0,0,90.00000001 +188.19,50.30085681,-3.128352916,10000,0,199.9996184,0,0,0,90.00000001 +188.2,50.30085681,-3.128324889,10000,0,199.9998414,0,0,0,90.00000001 +188.21,50.30085681,-3.128296861,10000,0,199.9998414,0,0,0,90.00000001 +188.22,50.30085681,-3.128268834,10000,0,199.9996184,0,0,0,90.00000001 +188.23,50.30085681,-3.128240807,10000,0,199.9998414,0,0,0,90.00000001 +188.24,50.30085681,-3.128212779,10000,0,199.9996184,0,0,0,90.00000001 +188.25,50.30085681,-3.128184752,10000,0,199.9987264,0,0,0,90.00000001 +188.26,50.30085681,-3.128156725,10000,0,199.9987264,0,0,0,90.00000001 +188.27,50.30085681,-3.128128698,10000,0,199.9996184,0,0,0,90.00000001 +188.28,50.30085681,-3.12810067,10000,0,199.9998414,0,0,0,90.00000001 +188.29,50.30085681,-3.128072643,10000,0,199.9996184,0,0,0,90.00000001 +188.3,50.30085681,-3.128044616,10000,0,200.0000644,0,0,0,90.00000001 +188.31,50.30085681,-3.128016588,10000,0,200.0007334,0,0,0,90.00000001 +188.32,50.30085681,-3.127988561,10000,0,200.0007334,0,0,0,90.00000001 +188.33,50.30085681,-3.127960533,10000,0,200.0000644,0,0,0,90.00000001 +188.34,50.30085681,-3.127932506,10000,0,199.9996184,0,0,0,90.00000001 +188.35,50.30085681,-3.127904479,10000,0,199.9998414,0,0,0,90.00000001 +188.36,50.30085681,-3.127876451,10000,0,199.9998414,0,0,0,90.00000001 +188.37,50.30085681,-3.127848424,10000,0,199.9996184,0,0,0,90.00000001 +188.38,50.30085681,-3.127820397,10000,0,200.0000644,0,0,0,90.00000001 +188.39,50.30085681,-3.127792369,10000,0,200.0007334,0,0,0,90.00000001 +188.4,50.30085681,-3.127764342,10000,0,200.0007334,0,0,0,90.00000001 +188.41,50.30085681,-3.127736314,10000,0,200.0000644,0,0,0,90.00000001 +188.42,50.30085681,-3.127708287,10000,0,199.9996184,0,0,0,90.00000001 +188.43,50.30085681,-3.12768026,10000,0,200.0000644,0,0,0,90.00000001 +188.44,50.30085681,-3.127652232,10000,0,200.0007334,0,0,0,90.00000001 +188.45,50.30085681,-3.127624205,10000,0,200.0007334,0,0,0,90.00000001 +188.46,50.30085681,-3.127596177,10000,0,200.0000644,0,0,0,90.00000001 +188.47,50.30085681,-3.12756815,10000,0,199.9996184,0,0,0,90.00000001 +188.48,50.30085681,-3.127540123,10000,0,199.9998414,0,0,0,90.00000001 +188.49,50.30085681,-3.127512095,10000,0,199.9998414,0,0,0,90.00000001 +188.5,50.30085681,-3.127484068,10000,0,199.9996184,0,0,0,90.00000001 +188.51,50.30085681,-3.127456041,10000,0,200.0000644,0,0,0,90.00000001 +188.52,50.30085681,-3.127428013,10000,0,200.0007334,0,0,0,90.00000001 +188.53,50.30085681,-3.127399986,10000,0,200.0007334,0,0,0,90.00000001 +188.54,50.30085681,-3.127371958,10000,0,200.0000644,0,0,0,90.00000001 +188.55,50.30085681,-3.127343931,10000,0,199.9996184,0,0,0,90.00000001 +188.56,50.30085681,-3.127315904,10000,0,199.9998414,0,0,0,90.00000001 +188.57,50.30085681,-3.127287876,10000,0,199.9998414,0,0,0,90.00000001 +188.58,50.30085681,-3.127259849,10000,0,199.9996184,0,0,0,90.00000001 +188.59,50.30085681,-3.127231822,10000,0,200.0000644,0,0,0,90.00000001 +188.6,50.30085681,-3.127203794,10000,0,200.0007334,0,0,0,90.00000001 +188.61,50.30085681,-3.127175767,10000,0,200.0007334,0,0,0,90.00000001 +188.62,50.30085681,-3.127147739,10000,0,200.0000644,0,0,0,90.00000001 +188.63,50.30085681,-3.127119712,10000,0,199.9996184,0,0,0,90.00000001 +188.64,50.30085681,-3.127091685,10000,0,199.9998414,0,0,0,90.00000001 +188.65,50.30085681,-3.127063657,10000,0,199.9998414,0,0,0,90.00000001 +188.66,50.30085681,-3.12703563,10000,0,199.9996184,0,0,0,90.00000001 +188.67,50.30085681,-3.127007603,10000,0,200.0000644,0,0,0,90.00000001 +188.68,50.30085681,-3.126979575,10000,0,200.0007334,0,0,0,90.00000001 +188.69,50.30085681,-3.126951548,10000,0,200.0007334,0,0,0,90.00000001 +188.7,50.30085681,-3.12692352,10000,0,200.0000644,0,0,0,90.00000001 +188.71,50.30085681,-3.126895493,10000,0,199.9996184,0,0,0,90.00000001 +188.72,50.30085681,-3.126867466,10000,0,199.9998414,0,0,0,90.00000001 +188.73,50.30085681,-3.126839438,10000,0,199.9998414,0,0,0,90.00000001 +188.74,50.30085681,-3.126811411,10000,0,199.9996184,0,0,0,90.00000001 +188.75,50.30085681,-3.126783384,10000,0,200.0000644,0,0,0,90.00000001 +188.76,50.30085681,-3.126755356,10000,0,200.0007334,0,0,0,90.00000001 +188.77,50.30085681,-3.126727329,10000,0,200.0007334,0,0,0,90.00000001 +188.78,50.30085681,-3.126699301,10000,0,199.9998414,0,0,0,90.00000001 +188.79,50.30085681,-3.126671274,10000,0,199.9985034,0,0,0,90.00000001 +188.8,50.30085681,-3.126643247,10000,0,199.9978344,0,0,0,90.00000001 +188.81,50.30085681,-3.12661522,10000,0,199.9985034,0,0,0,90.00000001 +188.82,50.30085681,-3.126587193,10000,0,199.9998414,0,0,0,90.00000001 +188.83,50.30085681,-3.126559165,10000,0,200.0007334,0,0,0,90.00000001 +188.84,50.30085681,-3.126531138,10000,0,200.0007334,0,0,0,90.00000001 +188.85,50.30085681,-3.12650311,10000,0,200.0000644,0,0,0,90.00000001 +188.86,50.30085681,-3.126475083,10000,0,199.9996184,0,0,0,90.00000001 +188.87,50.30085681,-3.126447056,10000,0,200.0000644,0,0,0,90.00000001 +188.88,50.30085681,-3.126419028,10000,0,200.0007334,0,0,0,90.00000001 +188.89,50.30085681,-3.126391001,10000,0,200.0007334,0,0,0,90.00000001 +188.9,50.30085681,-3.126362973,10000,0,200.0000644,0,0,0,90.00000001 +188.91,50.30085681,-3.126334946,10000,0,199.9996184,0,0,0,90.00000001 +188.92,50.30085681,-3.126306919,10000,0,199.9998414,0,0,0,90.00000001 +188.93,50.30085681,-3.126278891,10000,0,199.9998414,0,0,0,90.00000001 +188.94,50.30085681,-3.126250864,10000,0,199.9996184,0,0,0,90.00000001 +188.95,50.30085681,-3.126222837,10000,0,200.0000644,0,0,0,90.00000001 +188.96,50.30085681,-3.126194809,10000,0,200.0007334,0,0,0,90.00000001 +188.97,50.30085681,-3.126166782,10000,0,200.0007334,0,0,0,90.00000001 +188.98,50.30085681,-3.126138754,10000,0,200.0000644,0,0,0,90.00000001 +188.99,50.30085681,-3.126110727,10000,0,199.9996184,0,0,0,90.00000001 +189,50.30085681,-3.1260827,10000,0,199.9998414,0,0,0,90.00000001 +189.01,50.30085681,-3.126054672,10000,0,199.9998414,0,0,0,90.00000001 +189.02,50.30085681,-3.126026645,10000,0,199.9996184,0,0,0,90.00000001 +189.03,50.30085681,-3.125998618,10000,0,200.0000644,0,0,0,90.00000001 +189.04,50.30085681,-3.12597059,10000,0,200.0007334,0,0,0,90.00000001 +189.05,50.30085681,-3.125942563,10000,0,200.0007334,0,0,0,90.00000001 +189.06,50.30085681,-3.125914535,10000,0,200.0000644,0,0,0,90.00000001 +189.07,50.30085681,-3.125886508,10000,0,199.9996184,0,0,0,90.00000001 +189.08,50.30085681,-3.125858481,10000,0,199.9998414,0,0,0,90.00000001 +189.09,50.30085681,-3.125830453,10000,0,199.9998414,0,0,0,90.00000001 +189.1,50.30085681,-3.125802426,10000,0,199.9996184,0,0,0,90.00000001 +189.11,50.30085681,-3.125774399,10000,0,200.0000644,0,0,0,90.00000001 +189.12,50.30085681,-3.125746371,10000,0,200.0007334,0,0,0,90.00000001 +189.13,50.30085681,-3.125718344,10000,0,200.0007334,0,0,0,90.00000001 +189.14,50.30085681,-3.125690316,10000,0,200.0000644,0,0,0,90.00000001 +189.15,50.30085681,-3.125662289,10000,0,199.9996184,0,0,0,90.00000001 +189.16,50.30085681,-3.125634262,10000,0,199.9998414,0,0,0,90.00000001 +189.17,50.30085681,-3.125606234,10000,0,199.9998414,0,0,0,90.00000001 +189.18,50.30085681,-3.125578207,10000,0,199.9996184,0,0,0,90.00000001 +189.19,50.30085681,-3.12555018,10000,0,200.0000644,0,0,0,90.00000001 +189.2,50.30085681,-3.125522152,10000,0,200.0007334,0,0,0,90.00000001 +189.21,50.30085681,-3.125494125,10000,0,200.0007334,0,0,0,90.00000001 +189.22,50.30085681,-3.125466097,10000,0,200.0000644,0,0,0,90.00000001 +189.23,50.30085681,-3.12543807,10000,0,199.9996184,0,0,0,90.00000001 +189.24,50.30085681,-3.125410043,10000,0,199.9998414,0,0,0,90.00000001 +189.25,50.30085681,-3.125382015,10000,0,199.9998414,0,0,0,90.00000001 +189.26,50.30085681,-3.125353988,10000,0,199.9996184,0,0,0,90.00000001 +189.27,50.30085681,-3.125325961,10000,0,200.0000644,0,0,0,90.00000001 +189.28,50.30085681,-3.125297933,10000,0,200.0007334,0,0,0,90.00000001 +189.29,50.30085681,-3.125269906,10000,0,200.0007334,0,0,0,90.00000001 +189.3,50.30085681,-3.125241878,10000,0,200.0000644,0,0,0,90.00000001 +189.31,50.30085681,-3.125213851,10000,0,199.9996184,0,0,0,90.00000001 +189.32,50.30085681,-3.125185824,10000,0,199.9998414,0,0,0,90.00000001 +189.33,50.30085681,-3.125157796,10000,0,199.9996184,0,0,0,90.00000001 +189.34,50.30085681,-3.125129769,10000,0,199.9987264,0,0,0,90.00000001 +189.35,50.30085681,-3.125101742,10000,0,199.9987264,0,0,0,90.00000001 +189.36,50.30085681,-3.125073715,10000,0,199.9996184,0,0,0,90.00000001 +189.37,50.30085681,-3.125045687,10000,0,199.9998414,0,0,0,90.00000001 +189.38,50.30085681,-3.12501766,10000,0,199.9996184,0,0,0,90.00000001 +189.39,50.30085681,-3.124989633,10000,0,200.0000644,0,0,0,90.00000001 +189.4,50.30085681,-3.124961605,10000,0,200.0007334,0,0,0,90.00000001 +189.41,50.30085681,-3.124933578,10000,0,200.0007334,0,0,0,90.00000001 +189.42,50.30085681,-3.12490555,10000,0,200.0000644,0,0,0,90.00000001 +189.43,50.30085681,-3.124877523,10000,0,199.9996184,0,0,0,90.00000001 +189.44,50.30085681,-3.124849496,10000,0,199.9998414,0,0,0,90.00000001 +189.45,50.30085681,-3.124821468,10000,0,199.9998414,0,0,0,90.00000001 +189.46,50.30085681,-3.124793441,10000,0,199.9996184,0,0,0,90.00000001 +189.47,50.30085681,-3.124765414,10000,0,200.0000644,0,0,0,90.00000001 +189.48,50.30085681,-3.124737386,10000,0,200.0007334,0,0,0,90.00000001 +189.49,50.30085681,-3.124709359,10000,0,200.0007334,0,0,0,90.00000001 +189.5,50.30085681,-3.124681331,10000,0,200.0000644,0,0,0,90.00000001 +189.51,50.30085681,-3.124653304,10000,0,199.9996184,0,0,0,90.00000001 +189.52,50.30085681,-3.124625277,10000,0,199.9998414,0,0,0,90.00000001 +189.53,50.30085681,-3.124597249,10000,0,199.9998414,0,0,0,90.00000001 +189.54,50.30085681,-3.124569222,10000,0,199.9996184,0,0,0,90.00000001 +189.55,50.30085681,-3.124541195,10000,0,200.0000644,0,0,0,90.00000001 +189.56,50.30085681,-3.124513167,10000,0,200.0007334,0,0,0,90.00000001 +189.57,50.30085681,-3.12448514,10000,0,200.0007334,0,0,0,90.00000001 +189.58,50.30085681,-3.124457112,10000,0,200.0000644,0,0,0,90.00000001 +189.59,50.30085681,-3.124429085,10000,0,199.9996184,0,0,0,90.00000001 +189.6,50.30085681,-3.124401058,10000,0,199.9998414,0,0,0,90.00000001 +189.61,50.30085681,-3.12437303,10000,0,199.9998414,0,0,0,90.00000001 +189.62,50.30085681,-3.124345003,10000,0,199.9996184,0,0,0,90.00000001 +189.63,50.30085681,-3.124316976,10000,0,200.0000644,0,0,0,90.00000001 +189.64,50.30085681,-3.124288948,10000,0,200.0007334,0,0,0,90.00000001 +189.65,50.30085681,-3.124260921,10000,0,200.0007334,0,0,0,90.00000001 +189.66,50.30085681,-3.124232893,10000,0,200.0000644,0,0,0,90.00000001 +189.67,50.30085681,-3.124204866,10000,0,199.9996184,0,0,0,90.00000001 +189.68,50.30085681,-3.124176839,10000,0,199.9998414,0,0,0,90.00000001 +189.69,50.30085681,-3.124148811,10000,0,199.9998414,0,0,0,90.00000001 +189.7,50.30085681,-3.124120784,10000,0,199.9996184,0,0,0,90.00000001 +189.71,50.30085681,-3.124092757,10000,0,200.0000644,0,0,0,90.00000001 +189.72,50.30085681,-3.124064729,10000,0,200.0007334,0,0,0,90.00000001 +189.73,50.30085681,-3.124036702,10000,0,200.0007334,0,0,0,90.00000001 +189.74,50.30085681,-3.124008674,10000,0,200.0000644,0,0,0,90.00000001 +189.75,50.30085681,-3.123980647,10000,0,199.9996184,0,0,0,90.00000001 +189.76,50.30085681,-3.12395262,10000,0,199.9998414,0,0,0,90.00000001 +189.77,50.30085681,-3.123924592,10000,0,199.9998414,0,0,0,90.00000001 +189.78,50.30085681,-3.123896565,10000,0,199.9996184,0,0,0,90.00000001 +189.79,50.30085681,-3.123868538,10000,0,200.0000644,0,0,0,90.00000001 +189.8,50.30085681,-3.12384051,10000,0,200.0007334,0,0,0,90.00000001 +189.81,50.30085681,-3.123812483,10000,0,200.0007334,0,0,0,90.00000001 +189.82,50.30085681,-3.123784455,10000,0,200.0000644,0,0,0,90.00000001 +189.83,50.30085681,-3.123756428,10000,0,199.9996184,0,0,0,90.00000001 +189.84,50.30085681,-3.123728401,10000,0,199.9998414,0,0,0,90.00000001 +189.85,50.30085681,-3.123700373,10000,0,199.9998414,0,0,0,90.00000001 +189.86,50.30085681,-3.123672346,10000,0,199.9996184,0,0,0,90.00000001 +189.87,50.30085681,-3.123644319,10000,0,199.9998414,0,0,0,90.00000001 +189.88,50.30085681,-3.123616291,10000,0,199.9996184,0,0,0,90.00000001 +189.89,50.30085681,-3.123588264,10000,0,199.9987264,0,0,0,90.00000001 +189.9,50.30085681,-3.123560237,10000,0,199.9987264,0,0,0,90.00000001 +189.91,50.30085681,-3.12353221,10000,0,199.9998414,0,0,0,90.00000001 +189.92,50.30085681,-3.123504182,10000,0,200.0007334,0,0,0,90.00000001 +189.93,50.30085681,-3.123476155,10000,0,200.0007334,0,0,0,90.00000001 +189.94,50.30085681,-3.123448127,10000,0,200.0000644,0,0,0,90.00000001 +189.95,50.30085681,-3.1234201,10000,0,199.9996184,0,0,0,90.00000001 +189.96,50.30085681,-3.123392073,10000,0,199.9998414,0,0,0,90.00000001 +189.97,50.30085681,-3.123364045,10000,0,199.9998414,0,0,0,90.00000001 +189.98,50.30085681,-3.123336018,10000,0,199.9996184,0,0,0,90.00000001 +189.99,50.30085681,-3.123307991,10000,0,200.0000644,0,0,0,90.00000001 +190,50.30085681,-3.123279963,10000,0,200.0007334,0,0,0,90.00000001 +190.01,50.30085681,-3.123251936,10000,0,200.0007334,0,0,0,90.00000001 +190.02,50.30085681,-3.123223908,10000,0,200.0000644,0,0,0,90.00000001 +190.03,50.30085681,-3.123195881,10000,0,199.9996184,0,0,0,90.00000001 +190.04,50.30085681,-3.123167854,10000,0,199.9998414,0,0,0,90.00000001 +190.05,50.30085681,-3.123139826,10000,0,199.9998414,0,0,0,90.00000001 +190.06,50.30085681,-3.123111799,10000,0,199.9996184,0,0,0,90.00000001 +190.07,50.30085681,-3.123083772,10000,0,200.0000644,0,0,0,90.00000001 +190.08,50.30085681,-3.123055744,10000,0,200.0007334,0,0,0,90.00000001 +190.09,50.30085681,-3.123027717,10000,0,200.0007334,0,0,0,90.00000001 +190.1,50.30085681,-3.122999689,10000,0,200.0000644,0,0,0,90.00000001 +190.11,50.30085681,-3.122971662,10000,0,199.9996184,0,0,0,90.00000001 +190.12,50.30085681,-3.122943635,10000,0,199.9998414,0,0,0,90.00000001 +190.13,50.30085681,-3.122915607,10000,0,199.9998414,0,0,0,90.00000001 +190.14,50.30085681,-3.12288758,10000,0,199.9996184,0,0,0,90.00000001 +190.15,50.30085681,-3.122859553,10000,0,200.0000644,0,0,0,90.00000001 +190.16,50.30085681,-3.122831525,10000,0,200.0007334,0,0,0,90.00000001 +190.17,50.30085681,-3.122803498,10000,0,200.0007334,0,0,0,90.00000001 +190.18,50.30085681,-3.12277547,10000,0,200.0000644,0,0,0,90.00000001 +190.19,50.30085681,-3.122747443,10000,0,199.9996184,0,0,0,90.00000001 +190.2,50.30085681,-3.122719416,10000,0,199.9998414,0,0,0,90.00000001 +190.21,50.30085681,-3.122691388,10000,0,199.9998414,0,0,0,90.00000001 +190.22,50.30085681,-3.122663361,10000,0,199.9996184,0,0,0,90.00000001 +190.23,50.30085681,-3.122635334,10000,0,200.0000644,0,0,0,90.00000001 +190.24,50.30085681,-3.122607306,10000,0,200.0007334,0,0,0,90.00000001 +190.25,50.30085681,-3.122579279,10000,0,200.0007334,0,0,0,90.00000001 +190.26,50.30085681,-3.122551251,10000,0,200.0000644,0,0,0,90.00000001 +190.27,50.30085681,-3.122523224,10000,0,199.9996184,0,0,0,90.00000001 +190.28,50.30085681,-3.122495197,10000,0,199.9998414,0,0,0,90.00000001 +190.29,50.30085681,-3.122467169,10000,0,199.9998414,0,0,0,90.00000001 +190.3,50.30085681,-3.122439142,10000,0,199.9996184,0,0,0,90.00000001 +190.31,50.30085681,-3.122411115,10000,0,200.0000644,0,0,0,90.00000001 +190.32,50.30085681,-3.122383087,10000,0,200.0007334,0,0,0,90.00000001 +190.33,50.30085681,-3.12235506,10000,0,200.0007334,0,0,0,90.00000001 +190.34,50.30085681,-3.122327032,10000,0,200.0000644,0,0,0,90.00000001 +190.35,50.30085681,-3.122299005,10000,0,199.9996184,0,0,0,90.00000001 +190.36,50.30085681,-3.122270978,10000,0,199.9998414,0,0,0,90.00000001 +190.37,50.30085681,-3.12224295,10000,0,199.9998414,0,0,0,90.00000001 +190.38,50.30085681,-3.122214923,10000,0,199.9996184,0,0,0,90.00000001 +190.39,50.30085681,-3.122186896,10000,0,200.0000644,0,0,0,90.00000001 +190.4,50.30085681,-3.122158868,10000,0,200.0007334,0,0,0,90.00000001 +190.41,50.30085681,-3.122130841,10000,0,200.0007334,0,0,0,90.00000001 +190.42,50.30085681,-3.122102813,10000,0,199.9998414,0,0,0,90.00000001 +190.43,50.30085681,-3.122074786,10000,0,199.9987264,0,0,0,90.00000001 +190.44,50.30085681,-3.122046759,10000,0,199.9987264,0,0,0,90.00000001 +190.45,50.30085681,-3.122018732,10000,0,199.9996184,0,0,0,90.00000001 +190.46,50.30085681,-3.121990704,10000,0,199.9998414,0,0,0,90.00000001 +190.47,50.30085681,-3.121962677,10000,0,199.9996184,0,0,0,90.00000001 +190.48,50.30085681,-3.12193465,10000,0,199.9998414,0,0,0,90.00000001 +190.49,50.30085681,-3.121906622,10000,0,199.9998414,0,0,0,90.00000001 +190.5,50.30085681,-3.121878595,10000,0,199.9996184,0,0,0,90.00000001 +190.51,50.30085681,-3.121850568,10000,0,200.0000644,0,0,0,90.00000001 +190.52,50.30085681,-3.12182254,10000,0,200.0007334,0,0,0,90.00000001 +190.53,50.30085681,-3.121794513,10000,0,200.0007334,0,0,0,90.00000001 +190.54,50.30085681,-3.121766485,10000,0,200.0000644,0,0,0,90.00000001 +190.55,50.30085681,-3.121738458,10000,0,199.9996184,0,0,0,90.00000001 +190.56,50.30085681,-3.121710431,10000,0,199.9998414,0,0,0,90.00000001 +190.57,50.30085681,-3.121682403,10000,0,199.9998414,0,0,0,90.00000001 +190.58,50.30085681,-3.121654376,10000,0,199.9996184,0,0,0,90.00000001 +190.59,50.30085681,-3.121626349,10000,0,200.0000644,0,0,0,90.00000001 +190.6,50.30085681,-3.121598321,10000,0,200.0007334,0,0,0,90.00000001 +190.61,50.30085681,-3.121570294,10000,0,200.0007334,0,0,0,90.00000001 +190.62,50.30085681,-3.121542266,10000,0,200.0000644,0,0,0,90.00000001 +190.63,50.30085681,-3.121514239,10000,0,199.9996184,0,0,0,90.00000001 +190.64,50.30085681,-3.121486212,10000,0,199.9998414,0,0,0,90.00000001 +190.65,50.30085681,-3.121458184,10000,0,199.9998414,0,0,0,90.00000001 +190.66,50.30085681,-3.121430157,10000,0,199.9996184,0,0,0,90.00000001 +190.67,50.30085681,-3.12140213,10000,0,200.0000644,0,0,0,90.00000001 +190.68,50.30085681,-3.121374102,10000,0,200.0007334,0,0,0,90.00000001 +190.69,50.30085681,-3.121346075,10000,0,200.0007334,0,0,0,90.00000001 +190.7,50.30085681,-3.121318047,10000,0,200.0000644,0,0,0,90.00000001 +190.71,50.30085681,-3.12129002,10000,0,199.9996184,0,0,0,90.00000001 +190.72,50.30085681,-3.121261993,10000,0,199.9998414,0,0,0,90.00000001 +190.73,50.30085681,-3.121233965,10000,0,199.9998414,0,0,0,90.00000001 +190.74,50.30085681,-3.121205938,10000,0,199.9996184,0,0,0,90.00000001 +190.75,50.30085681,-3.121177911,10000,0,200.0000644,0,0,0,90.00000001 +190.76,50.30085681,-3.121149883,10000,0,200.0007334,0,0,0,90.00000001 +190.77,50.30085681,-3.121121856,10000,0,200.0007334,0,0,0,90.00000001 +190.78,50.30085681,-3.121093828,10000,0,200.0000644,0,0,0,90.00000001 +190.79,50.30085681,-3.121065801,10000,0,199.9996184,0,0,0,90.00000001 +190.8,50.30085681,-3.121037774,10000,0,199.9998414,0,0,0,90.00000001 +190.81,50.30085681,-3.121009746,10000,0,199.9998414,0,0,0,90.00000001 +190.82,50.30085681,-3.120981719,10000,0,199.9996184,0,0,0,90.00000001 +190.83,50.30085681,-3.120953692,10000,0,200.0000644,0,0,0,90.00000001 +190.84,50.30085681,-3.120925664,10000,0,200.0007334,0,0,0,90.00000001 +190.85,50.30085681,-3.120897637,10000,0,200.0007334,0,0,0,90.00000001 +190.86,50.30085681,-3.120869609,10000,0,200.0000644,0,0,0,90.00000001 +190.87,50.30085681,-3.120841582,10000,0,199.9996184,0,0,0,90.00000001 +190.88,50.30085681,-3.120813555,10000,0,199.9998414,0,0,0,90.00000001 +190.89,50.30085681,-3.120785527,10000,0,199.9998414,0,0,0,90.00000001 +190.9,50.30085681,-3.1207575,10000,0,199.9996184,0,0,0,90.00000001 +190.91,50.30085681,-3.120729473,10000,0,200.0000644,0,0,0,90.00000001 +190.92,50.30085681,-3.120701445,10000,0,200.0007334,0,0,0,90.00000001 +190.93,50.30085681,-3.120673418,10000,0,200.0007334,0,0,0,90.00000001 +190.94,50.30085681,-3.12064539,10000,0,200.0000644,0,0,0,90.00000001 +190.95,50.30085681,-3.120617363,10000,0,199.9996184,0,0,0,90.00000001 +190.96,50.30085681,-3.120589336,10000,0,199.9998414,0,0,0,90.00000001 +190.97,50.30085681,-3.120561308,10000,0,199.9996184,0,0,0,90.00000001 +190.98,50.30085681,-3.120533281,10000,0,199.9987264,0,0,0,90.00000001 +190.99,50.30085681,-3.120505254,10000,0,199.9987264,0,0,0,90.00000001 +191,50.30085681,-3.120477227,10000,0,199.9996184,0,0,0,90.00000001 +191.01,50.30085681,-3.120449199,10000,0,199.9998414,0,0,0,90.00000001 +191.02,50.30085681,-3.120421172,10000,0,199.9996184,0,0,0,90.00000001 +191.03,50.30085681,-3.120393145,10000,0,200.0000644,0,0,0,90.00000001 +191.04,50.30085681,-3.120365117,10000,0,200.0007334,0,0,0,90.00000001 +191.05,50.30085681,-3.12033709,10000,0,200.0007334,0,0,0,90.00000001 +191.06,50.30085681,-3.120309062,10000,0,200.0000644,0,0,0,90.00000001 +191.07,50.30085681,-3.120281035,10000,0,199.9996184,0,0,0,90.00000001 +191.08,50.30085681,-3.120253008,10000,0,199.9998414,0,0,0,90.00000001 +191.09,50.30085681,-3.12022498,10000,0,199.9998414,0,0,0,90.00000001 +191.1,50.30085681,-3.120196953,10000,0,199.9996184,0,0,0,90.00000001 +191.11,50.30085681,-3.120168926,10000,0,200.0000644,0,0,0,90.00000001 +191.12,50.30085681,-3.120140898,10000,0,200.0007334,0,0,0,90.00000001 +191.13,50.30085681,-3.120112871,10000,0,200.0007334,0,0,0,90.00000001 +191.14,50.30085681,-3.120084843,10000,0,200.0000644,0,0,0,90.00000001 +191.15,50.30085681,-3.120056816,10000,0,199.9996184,0,0,0,90.00000001 +191.16,50.30085681,-3.120028789,10000,0,199.9998414,0,0,0,90.00000001 +191.17,50.30085681,-3.120000761,10000,0,199.9998414,0,0,0,90.00000001 +191.18,50.30085681,-3.119972734,10000,0,199.9996184,0,0,0,90.00000001 +191.19,50.30085681,-3.119944707,10000,0,200.0000644,0,0,0,90.00000001 +191.2,50.30085681,-3.119916679,10000,0,200.0007334,0,0,0,90.00000001 +191.21,50.30085681,-3.119888652,10000,0,200.0007334,0,0,0,90.00000001 +191.22,50.30085681,-3.119860624,10000,0,200.0000644,0,0,0,90.00000001 +191.23,50.30085681,-3.119832597,10000,0,199.9996184,0,0,0,90.00000001 +191.24,50.30085681,-3.11980457,10000,0,199.9998414,0,0,0,90.00000001 +191.25,50.30085681,-3.119776542,10000,0,199.9998414,0,0,0,90.00000001 +191.26,50.30085681,-3.119748515,10000,0,199.9996184,0,0,0,90.00000001 +191.27,50.30085681,-3.119720488,10000,0,200.0000644,0,0,0,90.00000001 +191.28,50.30085681,-3.11969246,10000,0,200.0007334,0,0,0,90.00000001 +191.29,50.30085681,-3.119664433,10000,0,200.0007334,0,0,0,90.00000001 +191.3,50.30085681,-3.119636405,10000,0,200.0000644,0,0,0,90.00000001 +191.31,50.30085681,-3.119608378,10000,0,199.9996184,0,0,0,90.00000001 +191.32,50.30085681,-3.119580351,10000,0,199.9998414,0,0,0,90.00000001 +191.33,50.30085681,-3.119552323,10000,0,199.9998414,0,0,0,90.00000001 +191.34,50.30085681,-3.119524296,10000,0,199.9996184,0,0,0,90.00000001 +191.35,50.30085681,-3.119496269,10000,0,200.0000644,0,0,0,90.00000001 +191.36,50.30085681,-3.119468241,10000,0,200.0007334,0,0,0,90.00000001 +191.37,50.30085681,-3.119440214,10000,0,200.0007334,0,0,0,90.00000001 +191.38,50.30085681,-3.119412186,10000,0,200.0000644,0,0,0,90.00000001 +191.39,50.30085681,-3.119384159,10000,0,199.9996184,0,0,0,90.00000001 +191.4,50.30085681,-3.119356132,10000,0,199.9998414,0,0,0,90.00000001 +191.41,50.30085681,-3.119328104,10000,0,199.9998414,0,0,0,90.00000001 +191.42,50.30085681,-3.119300077,10000,0,199.9996184,0,0,0,90.00000001 +191.43,50.30085681,-3.11927205,10000,0,200.0000644,0,0,0,90.00000001 +191.44,50.30085681,-3.119244022,10000,0,200.0007334,0,0,0,90.00000001 +191.45,50.30085681,-3.119215995,10000,0,200.0007334,0,0,0,90.00000001 +191.46,50.30085681,-3.119187967,10000,0,200.0000644,0,0,0,90.00000001 +191.47,50.30085681,-3.11915994,10000,0,199.9996184,0,0,0,90.00000001 +191.48,50.30085681,-3.119131913,10000,0,199.9998414,0,0,0,90.00000001 +191.49,50.30085681,-3.119103885,10000,0,199.9998414,0,0,0,90.00000001 +191.5,50.30085681,-3.119075858,10000,0,199.9996184,0,0,0,90.00000001 +191.51,50.30085681,-3.119047831,10000,0,199.9998414,0,0,0,90.00000001 +191.52,50.30085681,-3.119019803,10000,0,199.9996184,0,0,0,90.00000001 +191.53,50.30085681,-3.118991776,10000,0,199.9987264,0,0,0,90.00000001 +191.54,50.30085681,-3.118963749,10000,0,199.9987264,0,0,0,90.00000001 +191.55,50.30085681,-3.118935722,10000,0,199.9998414,0,0,0,90.00000001 +191.56,50.30085681,-3.118907694,10000,0,200.0007334,0,0,0,90.00000001 +191.57,50.30085681,-3.118879667,10000,0,200.0007334,0,0,0,90.00000001 +191.58,50.30085681,-3.118851639,10000,0,200.0000644,0,0,0,90.00000001 +191.59,50.30085681,-3.118823612,10000,0,199.9996184,0,0,0,90.00000001 +191.6,50.30085681,-3.118795585,10000,0,199.9998414,0,0,0,90.00000001 +191.61,50.30085681,-3.118767557,10000,0,199.9998414,0,0,0,90.00000001 +191.62,50.30085681,-3.11873953,10000,0,199.9996184,0,0,0,90.00000001 +191.63,50.30085681,-3.118711503,10000,0,200.0000644,0,0,0,90.00000001 +191.64,50.30085681,-3.118683475,10000,0,200.0007334,0,0,0,90.00000001 +191.65,50.30085681,-3.118655448,10000,0,200.0007334,0,0,0,90.00000001 +191.66,50.30085681,-3.11862742,10000,0,200.0000644,0,0,0,90.00000001 +191.67,50.30085681,-3.118599393,10000,0,199.9996184,0,0,0,90.00000001 +191.68,50.30085681,-3.118571366,10000,0,199.9998414,0,0,0,90.00000001 +191.69,50.30085681,-3.118543338,10000,0,199.9998414,0,0,0,90.00000001 +191.7,50.30085681,-3.118515311,10000,0,199.9996184,0,0,0,90.00000001 +191.71,50.30085681,-3.118487284,10000,0,200.0000644,0,0,0,90.00000001 +191.72,50.30085681,-3.118459256,10000,0,200.0007334,0,0,0,90.00000001 +191.73,50.30085681,-3.118431229,10000,0,200.0007334,0,0,0,90.00000001 +191.74,50.30085681,-3.118403201,10000,0,200.0000644,0,0,0,90.00000001 +191.75,50.30085681,-3.118375174,10000,0,199.9996184,0,0,0,90.00000001 +191.76,50.30085681,-3.118347147,10000,0,199.9998414,0,0,0,90.00000001 +191.77,50.30085681,-3.118319119,10000,0,199.9998414,0,0,0,90.00000001 +191.78,50.30085681,-3.118291092,10000,0,199.9996184,0,0,0,90.00000001 +191.79,50.30085681,-3.118263065,10000,0,200.0000644,0,0,0,90.00000001 +191.8,50.30085681,-3.118235037,10000,0,200.0007334,0,0,0,90.00000001 +191.81,50.30085681,-3.11820701,10000,0,200.0007334,0,0,0,90.00000001 +191.82,50.30085681,-3.118178982,10000,0,200.0000644,0,0,0,90.00000001 +191.83,50.30085681,-3.118150955,10000,0,199.9996184,0,0,0,90.00000001 +191.84,50.30085681,-3.118122928,10000,0,199.9998414,0,0,0,90.00000001 +191.85,50.30085681,-3.1180949,10000,0,199.9998414,0,0,0,90.00000001 +191.86,50.30085681,-3.118066873,10000,0,199.9996184,0,0,0,90.00000001 +191.87,50.30085681,-3.118038846,10000,0,200.0000644,0,0,0,90.00000001 +191.88,50.30085681,-3.118010818,10000,0,200.0007334,0,0,0,90.00000001 +191.89,50.30085681,-3.117982791,10000,0,200.0007334,0,0,0,90.00000001 +191.9,50.30085681,-3.117954763,10000,0,200.0000644,0,0,0,90.00000001 +191.91,50.30085681,-3.117926736,10000,0,199.9996184,0,0,0,90.00000001 +191.92,50.30085681,-3.117898709,10000,0,199.9998414,0,0,0,90.00000001 +191.93,50.30085681,-3.117870681,10000,0,199.9998414,0,0,0,90.00000001 +191.94,50.30085681,-3.117842654,10000,0,199.9996184,0,0,0,90.00000001 +191.95,50.30085681,-3.117814627,10000,0,200.0000644,0,0,0,90.00000001 +191.96,50.30085681,-3.117786599,10000,0,200.0007334,0,0,0,90.00000001 +191.97,50.30085681,-3.117758572,10000,0,200.0007334,0,0,0,90.00000001 +191.98,50.30085681,-3.117730544,10000,0,200.0000644,0,0,0,90.00000001 +191.99,50.30085681,-3.117702517,10000,0,199.9996184,0,0,0,90.00000001 +192,50.30085681,-3.11767449,10000,0,199.9998414,0,0,0,90.00000001 +192.01,50.30085681,-3.117646462,10000,0,199.9998414,0,0,0,90.00000001 +192.02,50.30085681,-3.117618435,10000,0,199.9996184,0,0,0,90.00000001 +192.03,50.30085681,-3.117590408,10000,0,200.0000644,0,0,0,90.00000001 +192.04,50.30085681,-3.11756238,10000,0,200.0007334,0,0,0,90.00000001 +192.05,50.30085681,-3.117534353,10000,0,200.0007334,0,0,0,90.00000001 +192.06,50.30085681,-3.117506325,10000,0,199.9998414,0,0,0,90.00000001 +192.07,50.30085681,-3.117478298,10000,0,199.9987264,0,0,0,90.00000001 +192.08,50.30085681,-3.117450271,10000,0,199.9987264,0,0,0,90.00000001 +192.09,50.30085681,-3.117422244,10000,0,199.9996184,0,0,0,90.00000001 +192.1,50.30085681,-3.117394216,10000,0,199.9998414,0,0,0,90.00000001 +192.11,50.30085681,-3.117366189,10000,0,199.9996184,0,0,0,90.00000001 +192.12,50.30085681,-3.117338162,10000,0,199.9998414,0,0,0,90.00000001 +192.13,50.30085681,-3.117310134,10000,0,199.9998414,0,0,0,90.00000001 +192.14,50.30085681,-3.117282107,10000,0,199.9996184,0,0,0,90.00000001 +192.15,50.30085681,-3.11725408,10000,0,200.0000644,0,0,0,90.00000001 +192.16,50.30085681,-3.117226052,10000,0,200.0007334,0,0,0,90.00000001 +192.17,50.30085681,-3.117198025,10000,0,200.0007334,0,0,0,90.00000001 +192.18,50.30085681,-3.117169997,10000,0,200.0000644,0,0,0,90.00000001 +192.19,50.30085681,-3.11714197,10000,0,199.9996184,0,0,0,90.00000001 +192.2,50.30085681,-3.117113943,10000,0,199.9998414,0,0,0,90.00000001 +192.21,50.30085681,-3.117085915,10000,0,199.9998414,0,0,0,90.00000001 +192.22,50.30085681,-3.117057888,10000,0,199.9996184,0,0,0,90.00000001 +192.23,50.30085681,-3.117029861,10000,0,200.0000644,0,0,0,90.00000001 +192.24,50.30085681,-3.117001833,10000,0,200.0007334,0,0,0,90.00000001 +192.25,50.30085681,-3.116973806,10000,0,200.0007334,0,0,0,90.00000001 +192.26,50.30085681,-3.116945778,10000,0,200.0000644,0,0,0,90.00000001 +192.27,50.30085681,-3.116917751,10000,0,199.9996184,0,0,0,90.00000001 +192.28,50.30085681,-3.116889724,10000,0,199.9998414,0,0,0,90.00000001 +192.29,50.30085681,-3.116861696,10000,0,199.9998414,0,0,0,90.00000001 +192.3,50.30085681,-3.116833669,10000,0,199.9996184,0,0,0,90.00000001 +192.31,50.30085681,-3.116805642,10000,0,200.0000644,0,0,0,90.00000001 +192.32,50.30085681,-3.116777614,10000,0,200.0007334,0,0,0,90.00000001 +192.33,50.30085681,-3.116749587,10000,0,200.0007334,0,0,0,90.00000001 +192.34,50.30085681,-3.116721559,10000,0,200.0000644,0,0,0,90.00000001 +192.35,50.30085681,-3.116693532,10000,0,199.9996184,0,0,0,90.00000001 +192.36,50.30085681,-3.116665505,10000,0,199.9998414,0,0,0,90.00000001 +192.37,50.30085681,-3.116637477,10000,0,199.9998414,0,0,0,90.00000001 +192.38,50.30085681,-3.11660945,10000,0,199.9996184,0,0,0,90.00000001 +192.39,50.30085681,-3.116581423,10000,0,200.0000644,0,0,0,90.00000001 +192.4,50.30085681,-3.116553395,10000,0,200.0007334,0,0,0,90.00000001 +192.41,50.30085681,-3.116525368,10000,0,200.0007334,0,0,0,90.00000001 +192.42,50.30085681,-3.11649734,10000,0,200.0000644,0,0,0,90.00000001 +192.43,50.30085681,-3.116469313,10000,0,199.9996184,0,0,0,90.00000001 +192.44,50.30085681,-3.116441286,10000,0,199.9998414,0,0,0,90.00000001 +192.45,50.30085681,-3.116413258,10000,0,199.9998414,0,0,0,90.00000001 +192.46,50.30085681,-3.116385231,10000,0,199.9996184,0,0,0,90.00000001 +192.47,50.30085681,-3.116357204,10000,0,200.0000644,0,0,0,90.00000001 +192.48,50.30085681,-3.116329176,10000,0,200.0007334,0,0,0,90.00000001 +192.49,50.30085681,-3.116301149,10000,0,200.0007334,0,0,0,90.00000001 +192.5,50.30085681,-3.116273121,10000,0,200.0000644,0,0,0,90.00000001 +192.51,50.30085681,-3.116245094,10000,0,199.9996184,0,0,0,90.00000001 +192.52,50.30085681,-3.116217067,10000,0,199.9998414,0,0,0,90.00000001 +192.53,50.30085681,-3.116189039,10000,0,199.9998414,0,0,0,90.00000001 +192.54,50.30085681,-3.116161012,10000,0,199.9996184,0,0,0,90.00000001 +192.55,50.30085681,-3.116132985,10000,0,200.0000644,0,0,0,90.00000001 +192.56,50.30085681,-3.116104957,10000,0,200.0007334,0,0,0,90.00000001 +192.57,50.30085681,-3.11607693,10000,0,200.0007334,0,0,0,90.00000001 +192.58,50.30085681,-3.116048902,10000,0,200.0000644,0,0,0,90.00000001 +192.59,50.30085681,-3.116020875,10000,0,199.9996184,0,0,0,90.00000001 +192.6,50.30085681,-3.115992848,10000,0,199.9998414,0,0,0,90.00000001 +192.61,50.30085681,-3.11596482,10000,0,199.9996184,0,0,0,90.00000001 +192.62,50.30085681,-3.115936793,10000,0,199.9987264,0,0,0,90.00000001 +192.63,50.30085681,-3.115908766,10000,0,199.9987264,0,0,0,90.00000001 +192.64,50.30085681,-3.115880739,10000,0,199.9996184,0,0,0,90.00000001 +192.65,50.30085681,-3.115852711,10000,0,199.9998414,0,0,0,90.00000001 +192.66,50.30085681,-3.115824684,10000,0,199.9996184,0,0,0,90.00000001 +192.67,50.30085681,-3.115796657,10000,0,200.0000644,0,0,0,90.00000001 +192.68,50.30085681,-3.115768629,10000,0,200.0007334,0,0,0,90.00000001 +192.69,50.30085681,-3.115740602,10000,0,200.0007334,0,0,0,90.00000001 +192.7,50.30085681,-3.115712574,10000,0,200.0000644,0,0,0,90.00000001 +192.71,50.30085681,-3.115684547,10000,0,199.9996184,0,0,0,90.00000001 +192.72,50.30085681,-3.11565652,10000,0,199.9998414,0,0,0,90.00000001 +192.73,50.30085681,-3.115628492,10000,0,199.9998414,0,0,0,90.00000001 +192.74,50.30085681,-3.115600465,10000,0,199.9996184,0,0,0,90.00000001 +192.75,50.30085681,-3.115572438,10000,0,200.0000644,0,0,0,90.00000001 +192.76,50.30085681,-3.11554441,10000,0,200.0007334,0,0,0,90.00000001 +192.77,50.30085681,-3.115516383,10000,0,200.0007334,0,0,0,90.00000001 +192.78,50.30085681,-3.115488355,10000,0,200.0000644,0,0,0,90.00000001 +192.79,50.30085681,-3.115460328,10000,0,199.9996184,0,0,0,90.00000001 +192.8,50.30085681,-3.115432301,10000,0,199.9998414,0,0,0,90.00000001 +192.81,50.30085681,-3.115404273,10000,0,199.9998414,0,0,0,90.00000001 +192.82,50.30085681,-3.115376246,10000,0,199.9996184,0,0,0,90.00000001 +192.83,50.30085681,-3.115348219,10000,0,200.0000644,0,0,0,90.00000001 +192.84,50.30085681,-3.115320191,10000,0,200.0007334,0,0,0,90.00000001 +192.85,50.30085681,-3.115292164,10000,0,200.0007334,0,0,0,90.00000001 +192.86,50.30085681,-3.115264136,10000,0,200.0000644,0,0,0,90.00000001 +192.87,50.30085681,-3.115236109,10000,0,199.9996184,0,0,0,90.00000001 +192.88,50.30085681,-3.115208082,10000,0,199.9998414,0,0,0,90.00000001 +192.89,50.30085681,-3.115180054,10000,0,199.9998414,0,0,0,90.00000001 +192.9,50.30085681,-3.115152027,10000,0,199.9996184,0,0,0,90.00000001 +192.91,50.30085681,-3.115124,10000,0,200.0000644,0,0,0,90.00000001 +192.92,50.30085681,-3.115095972,10000,0,200.0007334,0,0,0,90.00000001 +192.93,50.30085681,-3.115067945,10000,0,200.0007334,0,0,0,90.00000001 +192.94,50.30085681,-3.115039917,10000,0,200.0000644,0,0,0,90.00000001 +192.95,50.30085681,-3.11501189,10000,0,199.9996184,0,0,0,90.00000001 +192.96,50.30085681,-3.114983863,10000,0,199.9998414,0,0,0,90.00000001 +192.97,50.30085681,-3.114955835,10000,0,199.9998414,0,0,0,90.00000001 +192.98,50.30085681,-3.114927808,10000,0,199.9996184,0,0,0,90.00000001 +192.99,50.30085681,-3.114899781,10000,0,200.0000644,0,0,0,90.00000001 +193,50.30085681,-3.114871753,10000,0,200.0007334,0,0,0,90.00000001 +193.01,50.30085681,-3.114843726,10000,0,200.0007334,0,0,0,90.00000001 +193.02,50.30085681,-3.114815698,10000,0,200.0000644,0,0,0,90.00000001 +193.03,50.30085681,-3.114787671,10000,0,199.9996184,0,0,0,90.00000001 +193.04,50.30085681,-3.114759644,10000,0,199.9998414,0,0,0,90.00000001 +193.05,50.30085681,-3.114731616,10000,0,199.9998414,0,0,0,90.00000001 +193.06,50.30085681,-3.114703589,10000,0,199.9996184,0,0,0,90.00000001 +193.07,50.30085681,-3.114675562,10000,0,200.0000644,0,0,0,90.00000001 +193.08,50.30085681,-3.114647534,10000,0,200.0007334,0,0,0,90.00000001 +193.09,50.30085681,-3.114619507,10000,0,200.0007334,0,0,0,90.00000001 +193.1,50.30085681,-3.114591479,10000,0,200.0000644,0,0,0,90.00000001 +193.11,50.30085681,-3.114563452,10000,0,199.9996184,0,0,0,90.00000001 +193.12,50.30085681,-3.114535425,10000,0,199.9998414,0,0,0,90.00000001 +193.13,50.30085681,-3.114507397,10000,0,199.9998414,0,0,0,90.00000001 +193.14,50.30085681,-3.11447937,10000,0,199.9996184,0,0,0,90.00000001 +193.15,50.30085681,-3.114451343,10000,0,199.9998414,0,0,0,90.00000001 +193.16,50.30085681,-3.114423315,10000,0,199.9996184,0,0,0,90.00000001 +193.17,50.30085681,-3.114395288,10000,0,199.9987264,0,0,0,90.00000001 +193.18,50.30085681,-3.114367261,10000,0,199.9987264,0,0,0,90.00000001 +193.19,50.30085681,-3.114339234,10000,0,199.9998414,0,0,0,90.00000001 +193.2,50.30085681,-3.114311206,10000,0,200.0007334,0,0,0,90.00000001 +193.21,50.30085681,-3.114283179,10000,0,200.0007334,0,0,0,90.00000001 +193.22,50.30085681,-3.114255151,10000,0,200.0000644,0,0,0,90.00000001 +193.23,50.30085681,-3.114227124,10000,0,199.9996184,0,0,0,90.00000001 +193.24,50.30085681,-3.114199097,10000,0,199.9998414,0,0,0,90.00000001 +193.25,50.30085681,-3.114171069,10000,0,199.9998414,0,0,0,90.00000001 +193.26,50.30085681,-3.114143042,10000,0,199.9996184,0,0,0,90.00000001 +193.27,50.30085681,-3.114115015,10000,0,200.0000644,0,0,0,90.00000001 +193.28,50.30085681,-3.114086987,10000,0,200.0007334,0,0,0,90.00000001 +193.29,50.30085681,-3.11405896,10000,0,200.0007334,0,0,0,90.00000001 +193.3,50.30085681,-3.114030932,10000,0,200.0000644,0,0,0,90.00000001 +193.31,50.30085681,-3.114002905,10000,0,199.9996184,0,0,0,90.00000001 +193.32,50.30085681,-3.113974878,10000,0,199.9998414,0,0,0,90.00000001 +193.33,50.30085681,-3.11394685,10000,0,199.9998414,0,0,0,90.00000001 +193.34,50.30085681,-3.113918823,10000,0,199.9996184,0,0,0,90.00000001 +193.35,50.30085681,-3.113890796,10000,0,200.0000644,0,0,0,90.00000001 +193.36,50.30085681,-3.113862768,10000,0,200.0007334,0,0,0,90.00000001 +193.37,50.30085681,-3.113834741,10000,0,200.0007334,0,0,0,90.00000001 +193.38,50.30085681,-3.113806713,10000,0,200.0000644,0,0,0,90.00000001 +193.39,50.30085681,-3.113778686,10000,0,199.9996184,0,0,0,90.00000001 +193.4,50.30085681,-3.113750659,10000,0,199.9998414,0,0,0,90.00000001 +193.41,50.30085681,-3.113722631,10000,0,199.9998414,0,0,0,90.00000001 +193.42,50.30085681,-3.113694604,10000,0,199.9996184,0,0,0,90.00000001 +193.43,50.30085681,-3.113666577,10000,0,200.0000644,0,0,0,90.00000001 +193.44,50.30085681,-3.113638549,10000,0,200.0007334,0,0,0,90.00000001 +193.45,50.30085681,-3.113610522,10000,0,200.0007334,0,0,0,90.00000001 +193.46,50.30085681,-3.113582494,10000,0,200.0000644,0,0,0,90.00000001 +193.47,50.30085681,-3.113554467,10000,0,199.9996184,0,0,0,90.00000001 +193.48,50.30085681,-3.11352644,10000,0,199.9998414,0,0,0,90.00000001 +193.49,50.30085681,-3.113498412,10000,0,199.9998414,0,0,0,90.00000001 +193.5,50.30085681,-3.113470385,10000,0,199.9996184,0,0,0,90.00000001 +193.51,50.30085681,-3.113442358,10000,0,200.0000644,0,0,0,90.00000001 +193.52,50.30085681,-3.11341433,10000,0,200.0007334,0,0,0,90.00000001 +193.53,50.30085681,-3.113386303,10000,0,200.0007334,0,0,0,90.00000001 +193.54,50.30085681,-3.113358275,10000,0,200.0000644,0,0,0,90.00000001 +193.55,50.30085681,-3.113330248,10000,0,199.9996184,0,0,0,90.00000001 +193.56,50.30085681,-3.113302221,10000,0,199.9998414,0,0,0,90.00000001 +193.57,50.30085681,-3.113274193,10000,0,199.9998414,0,0,0,90.00000001 +193.58,50.30085681,-3.113246166,10000,0,199.9996184,0,0,0,90.00000001 +193.59,50.30085681,-3.113218139,10000,0,200.0000644,0,0,0,90.00000001 +193.6,50.30085681,-3.113190111,10000,0,200.0007334,0,0,0,90.00000001 +193.61,50.30085681,-3.113162084,10000,0,200.0007334,0,0,0,90.00000001 +193.62,50.30085681,-3.113134056,10000,0,200.0000644,0,0,0,90.00000001 +193.63,50.30085681,-3.113106029,10000,0,199.9996184,0,0,0,90.00000001 +193.64,50.30085681,-3.113078002,10000,0,199.9998414,0,0,0,90.00000001 +193.65,50.30085681,-3.113049974,10000,0,199.9998414,0,0,0,90.00000001 +193.66,50.30085681,-3.113021947,10000,0,199.9996184,0,0,0,90.00000001 +193.67,50.30085681,-3.11299392,10000,0,200.0000644,0,0,0,90.00000001 +193.68,50.30085681,-3.112965892,10000,0,200.0007334,0,0,0,90.00000001 +193.69,50.30085681,-3.112937865,10000,0,200.0007334,0,0,0,90.00000001 +193.7,50.30085681,-3.112909837,10000,0,199.9998414,0,0,0,90.00000001 +193.71,50.30085681,-3.11288181,10000,0,199.9987264,0,0,0,90.00000001 +193.72,50.30085681,-3.112853783,10000,0,199.9987264,0,0,0,90.00000001 +193.73,50.30085681,-3.112825756,10000,0,199.9996184,0,0,0,90.00000001 +193.74,50.30085681,-3.112797728,10000,0,199.9998414,0,0,0,90.00000001 +193.75,50.30085681,-3.112769701,10000,0,199.9996184,0,0,0,90.00000001 +193.76,50.30085681,-3.112741674,10000,0,199.9998414,0,0,0,90.00000001 +193.77,50.30085681,-3.112713646,10000,0,199.9998414,0,0,0,90.00000001 +193.78,50.30085681,-3.112685619,10000,0,199.9996184,0,0,0,90.00000001 +193.79,50.30085681,-3.112657592,10000,0,200.0000644,0,0,0,90.00000001 +193.8,50.30085681,-3.112629564,10000,0,200.0007334,0,0,0,90.00000001 +193.81,50.30085681,-3.112601537,10000,0,200.0007334,0,0,0,90.00000001 +193.82,50.30085681,-3.112573509,10000,0,200.0000644,0,0,0,90.00000001 +193.83,50.30085681,-3.112545482,10000,0,199.9996184,0,0,0,90.00000001 +193.84,50.30085681,-3.112517455,10000,0,199.9998414,0,0,0,90.00000001 +193.85,50.30085681,-3.112489427,10000,0,199.9998414,0,0,0,90.00000001 +193.86,50.30085681,-3.1124614,10000,0,199.9996184,0,0,0,90.00000001 +193.87,50.30085681,-3.112433373,10000,0,200.0000644,0,0,0,90.00000001 +193.88,50.30085681,-3.112405345,10000,0,200.0007334,0,0,0,90.00000001 +193.89,50.30085681,-3.112377318,10000,0,200.0007334,0,0,0,90.00000001 +193.9,50.30085681,-3.11234929,10000,0,200.0000644,0,0,0,90.00000001 +193.91,50.30085681,-3.112321263,10000,0,199.9996184,0,0,0,90.00000001 +193.92,50.30085681,-3.112293236,10000,0,199.9998414,0,0,0,90.00000001 +193.93,50.30085681,-3.112265208,10000,0,199.9998414,0,0,0,90.00000001 +193.94,50.30085681,-3.112237181,10000,0,199.9996184,0,0,0,90.00000001 +193.95,50.30085681,-3.112209154,10000,0,200.0000644,0,0,0,90.00000001 +193.96,50.30085681,-3.112181126,10000,0,200.0007334,0,0,0,90.00000001 +193.97,50.30085681,-3.112153099,10000,0,200.0007334,0,0,0,90.00000001 +193.98,50.30085681,-3.112125071,10000,0,200.0000644,0,0,0,90.00000001 +193.99,50.30085681,-3.112097044,10000,0,199.9996184,0,0,0,90.00000001 +194,50.30085681,-3.112069017,10000,0,199.9998414,0,0,0,90.00000001 +194.01,50.30085681,-3.112040989,10000,0,199.9998414,0,0,0,90.00000001 +194.02,50.30085681,-3.112012962,10000,0,199.9996184,0,0,0,90.00000001 +194.03,50.30085681,-3.111984935,10000,0,200.0000644,0,0,0,90.00000001 +194.04,50.30085681,-3.111956907,10000,0,200.0007334,0,0,0,90.00000001 +194.05,50.30085681,-3.11192888,10000,0,200.0007334,0,0,0,90.00000001 +194.06,50.30085681,-3.111900852,10000,0,200.0000644,0,0,0,90.00000001 +194.07,50.30085681,-3.111872825,10000,0,199.9996184,0,0,0,90.00000001 +194.08,50.30085681,-3.111844798,10000,0,199.9998414,0,0,0,90.00000001 +194.09,50.30085681,-3.11181677,10000,0,199.9998414,0,0,0,90.00000001 +194.1,50.30085681,-3.111788743,10000,0,199.9996184,0,0,0,90.00000001 +194.11,50.30085681,-3.111760716,10000,0,200.0000644,0,0,0,90.00000001 +194.12,50.30085681,-3.111732688,10000,0,200.0007334,0,0,0,90.00000001 +194.13,50.30085681,-3.111704661,10000,0,200.0007334,0,0,0,90.00000001 +194.14,50.30085681,-3.111676633,10000,0,200.0000644,0,0,0,90.00000001 +194.15,50.30085681,-3.111648606,10000,0,199.9996184,0,0,0,90.00000001 +194.16,50.30085681,-3.111620579,10000,0,199.9998414,0,0,0,90.00000001 +194.17,50.30085681,-3.111592551,10000,0,199.9998414,0,0,0,90.00000001 +194.18,50.30085681,-3.111564524,10000,0,199.9996184,0,0,0,90.00000001 +194.19,50.30085681,-3.111536497,10000,0,200.0000644,0,0,0,90.00000001 +194.2,50.30085681,-3.111508469,10000,0,200.0007334,0,0,0,90.00000001 +194.21,50.30085681,-3.111480442,10000,0,200.0007334,0,0,0,90.00000001 +194.22,50.30085681,-3.111452414,10000,0,200.0000644,0,0,0,90.00000001 +194.23,50.30085681,-3.111424387,10000,0,199.9996184,0,0,0,90.00000001 +194.24,50.30085681,-3.11139636,10000,0,199.9998414,0,0,0,90.00000001 +194.25,50.30085681,-3.111368332,10000,0,199.9996184,0,0,0,90.00000001 +194.26,50.30085681,-3.111340305,10000,0,199.9987264,0,0,0,90.00000001 +194.27,50.30085681,-3.111312278,10000,0,199.9987264,0,0,0,90.00000001 +194.28,50.30085681,-3.111284251,10000,0,199.9996184,0,0,0,90.00000001 +194.29,50.30085681,-3.111256223,10000,0,199.9998414,0,0,0,90.00000001 +194.3,50.30085681,-3.111228196,10000,0,199.9996184,0,0,0,90.00000001 +194.31,50.30085681,-3.111200169,10000,0,200.0000644,0,0,0,90.00000001 +194.32,50.30085681,-3.111172141,10000,0,200.0007334,0,0,0,90.00000001 +194.33,50.30085681,-3.111144114,10000,0,200.0007334,0,0,0,90.00000001 +194.34,50.30085681,-3.111116086,10000,0,200.0000644,0,0,0,90.00000001 +194.35,50.30085681,-3.111088059,10000,0,199.9996184,0,0,0,90.00000001 +194.36,50.30085681,-3.111060032,10000,0,199.9998414,0,0,0,90.00000001 +194.37,50.30085681,-3.111032004,10000,0,199.9998414,0,0,0,90.00000001 +194.38,50.30085681,-3.111003977,10000,0,199.9996184,0,0,0,90.00000001 +194.39,50.30085681,-3.11097595,10000,0,200.0000644,0,0,0,90.00000001 +194.4,50.30085681,-3.110947922,10000,0,200.0007334,0,0,0,90.00000001 +194.41,50.30085681,-3.110919895,10000,0,200.0007334,0,0,0,90.00000001 +194.42,50.30085681,-3.110891867,10000,0,200.0000644,0,0,0,90.00000001 +194.43,50.30085681,-3.11086384,10000,0,199.9996184,0,0,0,90.00000001 +194.44,50.30085681,-3.110835813,10000,0,199.9998414,0,0,0,90.00000001 +194.45,50.30085681,-3.110807785,10000,0,199.9998414,0,0,0,90.00000001 +194.46,50.30085681,-3.110779758,10000,0,199.9996184,0,0,0,90.00000001 +194.47,50.30085681,-3.110751731,10000,0,200.0000644,0,0,0,90.00000001 +194.48,50.30085681,-3.110723703,10000,0,200.0007334,0,0,0,90.00000001 +194.49,50.30085681,-3.110695676,10000,0,200.0007334,0,0,0,90.00000001 +194.5,50.30085681,-3.110667648,10000,0,200.0000644,0,0,0,90.00000001 +194.51,50.30085681,-3.110639621,10000,0,199.9996184,0,0,0,90.00000001 +194.52,50.30085681,-3.110611594,10000,0,199.9998414,0,0,0,90.00000001 +194.53,50.30085681,-3.110583566,10000,0,199.9998414,0,0,0,90.00000001 +194.54,50.30085681,-3.110555539,10000,0,199.9996184,0,0,0,90.00000001 +194.55,50.30085681,-3.110527512,10000,0,200.0000644,0,0,0,90.00000001 +194.56,50.30085681,-3.110499484,10000,0,200.0007334,0,0,0,90.00000001 +194.57,50.30085681,-3.110471457,10000,0,200.0007334,0,0,0,90.00000001 +194.58,50.30085681,-3.110443429,10000,0,200.0000644,0,0,0,90.00000001 +194.59,50.30085681,-3.110415402,10000,0,199.9996184,0,0,0,90.00000001 +194.6,50.30085681,-3.110387375,10000,0,199.9998414,0,0,0,90.00000001 +194.61,50.30085681,-3.110359347,10000,0,199.9998414,0,0,0,90.00000001 +194.62,50.30085681,-3.11033132,10000,0,199.9996184,0,0,0,90.00000001 +194.63,50.30085681,-3.110303293,10000,0,200.0000644,0,0,0,90.00000001 +194.64,50.30085681,-3.110275265,10000,0,200.0007334,0,0,0,90.00000001 +194.65,50.30085681,-3.110247238,10000,0,200.0007334,0,0,0,90.00000001 +194.66,50.30085681,-3.11021921,10000,0,200.0000644,0,0,0,90.00000001 +194.67,50.30085681,-3.110191183,10000,0,199.9996184,0,0,0,90.00000001 +194.68,50.30085681,-3.110163156,10000,0,199.9998414,0,0,0,90.00000001 +194.69,50.30085681,-3.110135128,10000,0,199.9998414,0,0,0,90.00000001 +194.7,50.30085681,-3.110107101,10000,0,199.9996184,0,0,0,90.00000001 +194.71,50.30085681,-3.110079074,10000,0,200.0000644,0,0,0,90.00000001 +194.72,50.30085681,-3.110051046,10000,0,200.0007334,0,0,0,90.00000001 +194.73,50.30085681,-3.110023019,10000,0,200.0007334,0,0,0,90.00000001 +194.74,50.30085681,-3.109994991,10000,0,200.0000644,0,0,0,90.00000001 +194.75,50.30085681,-3.109966964,10000,0,199.9996184,0,0,0,90.00000001 +194.76,50.30085681,-3.109938937,10000,0,200.0000644,0,0,0,90.00000001 +194.77,50.30085681,-3.109910909,10000,0,200.0007334,0,0,0,90.00000001 +194.78,50.30085681,-3.109882882,10000,0,200.0007334,0,0,0,90.00000001 +194.79,50.30085681,-3.109854854,10000,0,199.9998414,0,0,0,90.00000001 +194.8,50.30085681,-3.109826827,10000,0,199.9985034,0,0,0,90.00000001 +194.81,50.30085681,-3.1097988,10000,0,199.9978344,0,0,0,90.00000001 +194.82,50.30085681,-3.109770773,10000,0,199.9985034,0,0,0,90.00000001 +194.83,50.30085681,-3.109742746,10000,0,199.9998414,0,0,0,90.00000001 +194.84,50.30085681,-3.109714718,10000,0,200.0007334,0,0,0,90.00000001 +194.85,50.30085681,-3.109686691,10000,0,200.0007334,0,0,0,90.00000001 +194.86,50.30085681,-3.109658663,10000,0,200.0000644,0,0,0,90.00000001 +194.87,50.30085681,-3.109630636,10000,0,199.9996184,0,0,0,90.00000001 +194.88,50.30085681,-3.109602609,10000,0,199.9998414,0,0,0,90.00000001 +194.89,50.30085681,-3.109574581,10000,0,199.9998414,0,0,0,90.00000001 +194.9,50.30085681,-3.109546554,10000,0,199.9996184,0,0,0,90.00000001 +194.91,50.30085681,-3.109518527,10000,0,200.0000644,0,0,0,90.00000001 +194.92,50.30085681,-3.109490499,10000,0,200.0007334,0,0,0,90.00000001 +194.93,50.30085681,-3.109462472,10000,0,200.0007334,0,0,0,90.00000001 +194.94,50.30085681,-3.109434444,10000,0,200.0000644,0,0,0,90.00000001 +194.95,50.30085681,-3.109406417,10000,0,199.9996184,0,0,0,90.00000001 +194.96,50.30085681,-3.10937839,10000,0,199.9998414,0,0,0,90.00000001 +194.97,50.30085681,-3.109350362,10000,0,199.9998414,0,0,0,90.00000001 +194.98,50.30085681,-3.109322335,10000,0,199.9996184,0,0,0,90.00000001 +194.99,50.30085681,-3.109294308,10000,0,200.0000644,0,0,0,90.00000001 +195,50.30085681,-3.10926628,10000,0,200.0007334,0,0,0,90.00000001 +195.01,50.30085681,-3.109238253,10000,0,200.0007334,0,0,0,90.00000001 +195.02,50.30085681,-3.109210225,10000,0,200.0000644,0,0,0,90.00000001 +195.03,50.30085681,-3.109182198,10000,0,199.9996184,0,0,0,90.00000001 +195.04,50.30085681,-3.109154171,10000,0,199.9998414,0,0,0,90.00000001 +195.05,50.30085681,-3.109126143,10000,0,199.9998414,0,0,0,90.00000001 +195.06,50.30085681,-3.109098116,10000,0,199.9996184,0,0,0,90.00000001 +195.07,50.30085681,-3.109070089,10000,0,200.0000644,0,0,0,90.00000001 +195.08,50.30085681,-3.109042061,10000,0,200.0007334,0,0,0,90.00000001 +195.09,50.30085681,-3.109014034,10000,0,200.0007334,0,0,0,90.00000001 +195.1,50.30085681,-3.108986006,10000,0,200.0000644,0,0,0,90.00000001 +195.11,50.30085681,-3.108957979,10000,0,199.9996184,0,0,0,90.00000001 +195.12,50.30085681,-3.108929952,10000,0,199.9998414,0,0,0,90.00000001 +195.13,50.30085681,-3.108901924,10000,0,199.9998414,0,0,0,90.00000001 +195.14,50.30085681,-3.108873897,10000,0,199.9996184,0,0,0,90.00000001 +195.15,50.30085681,-3.10884587,10000,0,200.0000644,0,0,0,90.00000001 +195.16,50.30085681,-3.108817842,10000,0,200.0007334,0,0,0,90.00000001 +195.17,50.30085681,-3.108789815,10000,0,200.0007334,0,0,0,90.00000001 +195.18,50.30085681,-3.108761787,10000,0,200.0000644,0,0,0,90.00000001 +195.19,50.30085681,-3.10873376,10000,0,199.9996184,0,0,0,90.00000001 +195.2,50.30085681,-3.108705733,10000,0,200.0000644,0,0,0,90.00000001 +195.21,50.30085681,-3.108677705,10000,0,200.0007334,0,0,0,90.00000001 +195.22,50.30085681,-3.108649678,10000,0,200.0007334,0,0,0,90.00000001 +195.23,50.30085681,-3.10862165,10000,0,200.0000644,0,0,0,90.00000001 +195.24,50.30085681,-3.108593623,10000,0,199.9996184,0,0,0,90.00000001 +195.25,50.30085681,-3.108565596,10000,0,199.9998414,0,0,0,90.00000001 +195.26,50.30085681,-3.108537568,10000,0,199.9998414,0,0,0,90.00000001 +195.27,50.30085681,-3.108509541,10000,0,199.9996184,0,0,0,90.00000001 +195.28,50.30085681,-3.108481514,10000,0,200.0000644,0,0,0,90.00000001 +195.29,50.30085681,-3.108453486,10000,0,200.0007334,0,0,0,90.00000001 +195.3,50.30085681,-3.108425459,10000,0,200.0007334,0,0,0,90.00000001 +195.31,50.30085681,-3.108397431,10000,0,200.0000644,0,0,0,90.00000001 +195.32,50.30085681,-3.108369404,10000,0,199.9996184,0,0,0,90.00000001 +195.33,50.30085681,-3.108341377,10000,0,199.9998414,0,0,0,90.00000001 +195.34,50.30085681,-3.108313349,10000,0,199.9996184,0,0,0,90.00000001 +195.35,50.30085681,-3.108285322,10000,0,199.9987264,0,0,0,90.00000001 +195.36,50.30085681,-3.108257295,10000,0,199.9987264,0,0,0,90.00000001 +195.37,50.30085681,-3.108229268,10000,0,199.9996184,0,0,0,90.00000001 +195.38,50.30085681,-3.10820124,10000,0,199.9998414,0,0,0,90.00000001 +195.39,50.30085681,-3.108173213,10000,0,199.9996184,0,0,0,90.00000001 +195.4,50.30085681,-3.108145186,10000,0,199.9998414,0,0,0,90.00000001 +195.41,50.30085681,-3.108117158,10000,0,199.9998414,0,0,0,90.00000001 +195.42,50.30085681,-3.108089131,10000,0,199.9996184,0,0,0,90.00000001 +195.43,50.30085681,-3.108061104,10000,0,200.0000644,0,0,0,90.00000001 +195.44,50.30085681,-3.108033076,10000,0,200.0007334,0,0,0,90.00000001 +195.45,50.30085681,-3.108005049,10000,0,200.0007334,0,0,0,90.00000001 +195.46,50.30085681,-3.107977021,10000,0,200.0000644,0,0,0,90.00000001 +195.47,50.30085681,-3.107948994,10000,0,199.9996184,0,0,0,90.00000001 +195.48,50.30085681,-3.107920967,10000,0,199.9998414,0,0,0,90.00000001 +195.49,50.30085681,-3.107892939,10000,0,199.9998414,0,0,0,90.00000001 +195.5,50.30085681,-3.107864912,10000,0,199.9996184,0,0,0,90.00000001 +195.51,50.30085681,-3.107836885,10000,0,200.0000644,0,0,0,90.00000001 +195.52,50.30085681,-3.107808857,10000,0,200.0007334,0,0,0,90.00000001 +195.53,50.30085681,-3.10778083,10000,0,200.0007334,0,0,0,90.00000001 +195.54,50.30085681,-3.107752802,10000,0,200.0000644,0,0,0,90.00000001 +195.55,50.30085681,-3.107724775,10000,0,199.9996184,0,0,0,90.00000001 +195.56,50.30085681,-3.107696748,10000,0,199.9998414,0,0,0,90.00000001 +195.57,50.30085681,-3.10766872,10000,0,199.9998414,0,0,0,90.00000001 +195.58,50.30085681,-3.107640693,10000,0,199.9996184,0,0,0,90.00000001 +195.59,50.30085681,-3.107612666,10000,0,200.0000644,0,0,0,90.00000001 +195.6,50.30085681,-3.107584638,10000,0,200.0007334,0,0,0,90.00000001 +195.61,50.30085681,-3.107556611,10000,0,200.0007334,0,0,0,90.00000001 +195.62,50.30085681,-3.107528583,10000,0,200.0000644,0,0,0,90.00000001 +195.63,50.30085681,-3.107500556,10000,0,199.9996184,0,0,0,90.00000001 +195.64,50.30085681,-3.107472529,10000,0,199.9998414,0,0,0,90.00000001 +195.65,50.30085681,-3.107444501,10000,0,199.9998414,0,0,0,90.00000001 +195.66,50.30085681,-3.107416474,10000,0,199.9996184,0,0,0,90.00000001 +195.67,50.30085681,-3.107388447,10000,0,200.0000644,0,0,0,90.00000001 +195.68,50.30085681,-3.107360419,10000,0,200.0007334,0,0,0,90.00000001 +195.69,50.30085681,-3.107332392,10000,0,200.0007334,0,0,0,90.00000001 +195.7,50.30085681,-3.107304364,10000,0,200.0000644,0,0,0,90.00000001 +195.71,50.30085681,-3.107276337,10000,0,199.9996184,0,0,0,90.00000001 +195.72,50.30085681,-3.10724831,10000,0,200.0000644,0,0,0,90.00000001 +195.73,50.30085681,-3.107220282,10000,0,200.0007334,0,0,0,90.00000001 +195.74,50.30085681,-3.107192255,10000,0,200.0007334,0,0,0,90.00000001 +195.75,50.30085681,-3.107164227,10000,0,200.0000644,0,0,0,90.00000001 +195.76,50.30085681,-3.1071362,10000,0,199.9996184,0,0,0,90.00000001 +195.77,50.30085681,-3.107108173,10000,0,199.9998414,0,0,0,90.00000001 +195.78,50.30085681,-3.107080145,10000,0,199.9998414,0,0,0,90.00000001 +195.79,50.30085681,-3.107052118,10000,0,199.9996184,0,0,0,90.00000001 +195.8,50.30085681,-3.107024091,10000,0,200.0000644,0,0,0,90.00000001 +195.81,50.30085681,-3.106996063,10000,0,200.0007334,0,0,0,90.00000001 +195.82,50.30085681,-3.106968036,10000,0,200.0007334,0,0,0,90.00000001 +195.83,50.30085681,-3.106940008,10000,0,200.0000644,0,0,0,90.00000001 +195.84,50.30085681,-3.106911981,10000,0,199.9996184,0,0,0,90.00000001 +195.85,50.30085681,-3.106883954,10000,0,199.9998414,0,0,0,90.00000001 +195.86,50.30085681,-3.106855926,10000,0,199.9998414,0,0,0,90.00000001 +195.87,50.30085681,-3.106827899,10000,0,199.9996184,0,0,0,90.00000001 +195.88,50.30085681,-3.106799872,10000,0,199.9998414,0,0,0,90.00000001 +195.89,50.30085681,-3.106771844,10000,0,199.9996184,0,0,0,90.00000001 +195.9,50.30085681,-3.106743817,10000,0,199.9987264,0,0,0,90.00000001 +195.91,50.30085681,-3.10671579,10000,0,199.9987264,0,0,0,90.00000001 +195.92,50.30085681,-3.106687763,10000,0,199.9996184,0,0,0,90.00000001 +195.93,50.30085681,-3.106659735,10000,0,199.9998414,0,0,0,90.00000001 +195.94,50.30085681,-3.106631708,10000,0,199.9996184,0,0,0,90.00000001 +195.95,50.30085681,-3.106603681,10000,0,200.0000644,0,0,0,90.00000001 +195.96,50.30085681,-3.106575653,10000,0,200.0007334,0,0,0,90.00000001 +195.97,50.30085681,-3.106547626,10000,0,200.0007334,0,0,0,90.00000001 +195.98,50.30085681,-3.106519598,10000,0,200.0000644,0,0,0,90.00000001 +195.99,50.30085681,-3.106491571,10000,0,199.9996184,0,0,0,90.00000001 +196,50.30085681,-3.106463544,10000,0,199.9998414,0,0,0,90.00000001 +196.01,50.30085681,-3.106435516,10000,0,199.9998414,0,0,0,90.00000001 +196.02,50.30085681,-3.106407489,10000,0,199.9996184,0,0,0,90.00000001 +196.03,50.30085681,-3.106379462,10000,0,200.0000644,0,0,0,90.00000001 +196.04,50.30085681,-3.106351434,10000,0,200.0007334,0,0,0,90.00000001 +196.05,50.30085681,-3.106323407,10000,0,200.0007334,0,0,0,90.00000001 +196.06,50.30085681,-3.106295379,10000,0,200.0000644,0,0,0,90.00000001 +196.07,50.30085681,-3.106267352,10000,0,199.9996184,0,0,0,90.00000001 +196.08,50.30085681,-3.106239325,10000,0,199.9998414,0,0,0,90.00000001 +196.09,50.30085681,-3.106211297,10000,0,199.9998414,0,0,0,90.00000001 +196.1,50.30085681,-3.10618327,10000,0,199.9996184,0,0,0,90.00000001 +196.11,50.30085681,-3.106155243,10000,0,200.0000644,0,0,0,90.00000001 +196.12,50.30085681,-3.106127215,10000,0,200.0007334,0,0,0,90.00000001 +196.13,50.30085681,-3.106099188,10000,0,200.0007334,0,0,0,90.00000001 +196.14,50.30085681,-3.10607116,10000,0,200.0000644,0,0,0,90.00000001 +196.15,50.30085681,-3.106043133,10000,0,199.9996184,0,0,0,90.00000001 +196.16,50.30085681,-3.106015106,10000,0,199.9998414,0,0,0,90.00000001 +196.17,50.30085681,-3.105987078,10000,0,199.9998414,0,0,0,90.00000001 +196.18,50.30085681,-3.105959051,10000,0,199.9996184,0,0,0,90.00000001 +196.19,50.30085681,-3.105931024,10000,0,200.0000644,0,0,0,90.00000001 +196.2,50.30085681,-3.105902996,10000,0,200.0007334,0,0,0,90.00000001 +196.21,50.30085681,-3.105874969,10000,0,200.0007334,0,0,0,90.00000001 +196.22,50.30085681,-3.105846941,10000,0,200.0000644,0,0,0,90.00000001 +196.23,50.30085681,-3.105818914,10000,0,199.9996184,0,0,0,90.00000001 +196.24,50.30085681,-3.105790887,10000,0,200.0000644,0,0,0,90.00000001 +196.25,50.30085681,-3.105762859,10000,0,200.0007334,0,0,0,90.00000001 +196.26,50.30085681,-3.105734832,10000,0,200.0007334,0,0,0,90.00000001 +196.27,50.30085681,-3.105706804,10000,0,200.0000644,0,0,0,90.00000001 +196.28,50.30085681,-3.105678777,10000,0,199.9996184,0,0,0,90.00000001 +196.29,50.30085681,-3.10565075,10000,0,199.9998414,0,0,0,90.00000001 +196.3,50.30085681,-3.105622722,10000,0,199.9998414,0,0,0,90.00000001 +196.31,50.30085681,-3.105594695,10000,0,199.9996184,0,0,0,90.00000001 +196.32,50.30085681,-3.105566668,10000,0,200.0000644,0,0,0,90.00000001 +196.33,50.30085681,-3.10553864,10000,0,200.0007334,0,0,0,90.00000001 +196.34,50.30085681,-3.105510613,10000,0,200.0007334,0,0,0,90.00000001 +196.35,50.30085681,-3.105482585,10000,0,200.0000644,0,0,0,90.00000001 +196.36,50.30085681,-3.105454558,10000,0,199.9996184,0,0,0,90.00000001 +196.37,50.30085681,-3.105426531,10000,0,199.9998414,0,0,0,90.00000001 +196.38,50.30085681,-3.105398503,10000,0,199.9998414,0,0,0,90.00000001 +196.39,50.30085681,-3.105370476,10000,0,199.9996184,0,0,0,90.00000001 +196.4,50.30085681,-3.105342449,10000,0,200.0000644,0,0,0,90.00000001 +196.41,50.30085681,-3.105314421,10000,0,200.0007334,0,0,0,90.00000001 +196.42,50.30085681,-3.105286394,10000,0,200.0007334,0,0,0,90.00000001 +196.43,50.30085681,-3.105258366,10000,0,199.9998414,0,0,0,90.00000001 +196.44,50.30085681,-3.105230339,10000,0,199.9985034,0,0,0,90.00000001 +196.45,50.30085681,-3.105202312,10000,0,199.9978344,0,0,0,90.00000001 +196.46,50.30085681,-3.105174285,10000,0,199.9985034,0,0,0,90.00000001 +196.47,50.30085681,-3.105146258,10000,0,199.9998414,0,0,0,90.00000001 +196.48,50.30085681,-3.10511823,10000,0,200.0007334,0,0,0,90.00000001 +196.49,50.30085681,-3.105090203,10000,0,200.0007334,0,0,0,90.00000001 +196.5,50.30085681,-3.105062175,10000,0,200.0000644,0,0,0,90.00000001 +196.51,50.30085681,-3.105034148,10000,0,199.9996184,0,0,0,90.00000001 +196.52,50.30085681,-3.105006121,10000,0,199.9998414,0,0,0,90.00000001 +196.53,50.30085681,-3.104978093,10000,0,199.9998414,0,0,0,90.00000001 +196.54,50.30085681,-3.104950066,10000,0,199.9996184,0,0,0,90.00000001 +196.55,50.30085681,-3.104922039,10000,0,200.0000644,0,0,0,90.00000001 +196.56,50.30085681,-3.104894011,10000,0,200.0007334,0,0,0,90.00000001 +196.57,50.30085681,-3.104865984,10000,0,200.0007334,0,0,0,90.00000001 +196.58,50.30085681,-3.104837956,10000,0,200.0000644,0,0,0,90.00000001 +196.59,50.30085681,-3.104809929,10000,0,199.9996184,0,0,0,90.00000001 +196.6,50.30085681,-3.104781902,10000,0,199.9998414,0,0,0,90.00000001 +196.61,50.30085681,-3.104753874,10000,0,199.9998414,0,0,0,90.00000001 +196.62,50.30085681,-3.104725847,10000,0,199.9996184,0,0,0,90.00000001 +196.63,50.30085681,-3.10469782,10000,0,200.0000644,0,0,0,90.00000001 +196.64,50.30085681,-3.104669792,10000,0,200.0007334,0,0,0,90.00000001 +196.65,50.30085681,-3.104641765,10000,0,200.0007334,0,0,0,90.00000001 +196.66,50.30085681,-3.104613737,10000,0,200.0000644,0,0,0,90.00000001 +196.67,50.30085681,-3.10458571,10000,0,199.9996184,0,0,0,90.00000001 +196.68,50.30085681,-3.104557683,10000,0,199.9998414,0,0,0,90.00000001 +196.69,50.30085681,-3.104529655,10000,0,199.9998414,0,0,0,90.00000001 +196.7,50.30085681,-3.104501628,10000,0,199.9996184,0,0,0,90.00000001 +196.71,50.30085681,-3.104473601,10000,0,200.0000644,0,0,0,90.00000001 +196.72,50.30085681,-3.104445573,10000,0,200.0007334,0,0,0,90.00000001 +196.73,50.30085681,-3.104417546,10000,0,200.0007334,0,0,0,90.00000001 +196.74,50.30085681,-3.104389518,10000,0,200.0000644,0,0,0,90.00000001 +196.75,50.30085681,-3.104361491,10000,0,199.9996184,0,0,0,90.00000001 +196.76,50.30085681,-3.104333464,10000,0,200.0000644,0,0,0,90.00000001 +196.77,50.30085681,-3.104305436,10000,0,200.0007334,0,0,0,90.00000001 +196.78,50.30085681,-3.104277409,10000,0,200.0007334,0,0,0,90.00000001 +196.79,50.30085681,-3.104249381,10000,0,200.0000644,0,0,0,90.00000001 +196.8,50.30085681,-3.104221354,10000,0,199.9996184,0,0,0,90.00000001 +196.81,50.30085681,-3.104193327,10000,0,199.9998414,0,0,0,90.00000001 +196.82,50.30085681,-3.104165299,10000,0,199.9998414,0,0,0,90.00000001 +196.83,50.30085681,-3.104137272,10000,0,199.9996184,0,0,0,90.00000001 +196.84,50.30085681,-3.104109245,10000,0,200.0000644,0,0,0,90.00000001 +196.85,50.30085681,-3.104081217,10000,0,200.0007334,0,0,0,90.00000001 +196.86,50.30085681,-3.10405319,10000,0,200.0007334,0,0,0,90.00000001 +196.87,50.30085681,-3.104025162,10000,0,200.0000644,0,0,0,90.00000001 +196.88,50.30085681,-3.103997135,10000,0,199.9996184,0,0,0,90.00000001 +196.89,50.30085681,-3.103969108,10000,0,199.9998414,0,0,0,90.00000001 +196.9,50.30085681,-3.10394108,10000,0,199.9998414,0,0,0,90.00000001 +196.91,50.30085681,-3.103913053,10000,0,199.9996184,0,0,0,90.00000001 +196.92,50.30085681,-3.103885026,10000,0,200.0000644,0,0,0,90.00000001 +196.93,50.30085681,-3.103856998,10000,0,200.0007334,0,0,0,90.00000001 +196.94,50.30085681,-3.103828971,10000,0,200.0007334,0,0,0,90.00000001 +196.95,50.30085681,-3.103800943,10000,0,200.0000644,0,0,0,90.00000001 +196.96,50.30085681,-3.103772916,10000,0,199.9996184,0,0,0,90.00000001 +196.97,50.30085681,-3.103744889,10000,0,199.9998414,0,0,0,90.00000001 +196.98,50.30085681,-3.103716861,10000,0,199.9996184,0,0,0,90.00000001 +196.99,50.30085681,-3.103688834,10000,0,199.9987264,0,0,0,90.00000001 +197,50.30085681,-3.103660807,10000,0,199.9987264,0,0,0,90.00000001 +197.01,50.30085681,-3.10363278,10000,0,199.9996184,0,0,0,90.00000001 +197.02,50.30085681,-3.103604752,10000,0,199.9998414,0,0,0,90.00000001 +197.03,50.30085681,-3.103576725,10000,0,199.9996184,0,0,0,90.00000001 +197.04,50.30085681,-3.103548698,10000,0,199.9998414,0,0,0,90.00000001 +197.05,50.30085681,-3.10352067,10000,0,199.9998414,0,0,0,90.00000001 +197.06,50.30085681,-3.103492643,10000,0,199.9996184,0,0,0,90.00000001 +197.07,50.30085681,-3.103464616,10000,0,200.0000644,0,0,0,90.00000001 +197.08,50.30085681,-3.103436588,10000,0,200.0007334,0,0,0,90.00000001 +197.09,50.30085681,-3.103408561,10000,0,200.0007334,0,0,0,90.00000001 +197.1,50.30085681,-3.103380533,10000,0,200.0000644,0,0,0,90.00000001 +197.11,50.30085681,-3.103352506,10000,0,199.9996184,0,0,0,90.00000001 +197.12,50.30085681,-3.103324479,10000,0,199.9998414,0,0,0,90.00000001 +197.13,50.30085681,-3.103296451,10000,0,199.9998414,0,0,0,90.00000001 +197.14,50.30085681,-3.103268424,10000,0,199.9996184,0,0,0,90.00000001 +197.15,50.30085681,-3.103240397,10000,0,200.0000644,0,0,0,90.00000001 +197.16,50.30085681,-3.103212369,10000,0,200.0007334,0,0,0,90.00000001 +197.17,50.30085681,-3.103184342,10000,0,200.0007334,0,0,0,90.00000001 +197.18,50.30085681,-3.103156314,10000,0,200.0000644,0,0,0,90.00000001 +197.19,50.30085681,-3.103128287,10000,0,199.9996184,0,0,0,90.00000001 +197.2,50.30085681,-3.10310026,10000,0,200.0000644,0,0,0,90.00000001 +197.21,50.30085681,-3.103072232,10000,0,200.0007334,0,0,0,90.00000001 +197.22,50.30085681,-3.103044205,10000,0,200.0007334,0,0,0,90.00000001 +197.23,50.30085681,-3.103016177,10000,0,200.0000644,0,0,0,90.00000001 +197.24,50.30085681,-3.10298815,10000,0,199.9996184,0,0,0,90.00000001 +197.25,50.30085681,-3.102960123,10000,0,199.9998414,0,0,0,90.00000001 +197.26,50.30085681,-3.102932095,10000,0,199.9998414,0,0,0,90.00000001 +197.27,50.30085681,-3.102904068,10000,0,199.9996184,0,0,0,90.00000001 +197.28,50.30085681,-3.102876041,10000,0,200.0000644,0,0,0,90.00000001 +197.29,50.30085681,-3.102848013,10000,0,200.0007334,0,0,0,90.00000001 +197.3,50.30085681,-3.102819986,10000,0,200.0007334,0,0,0,90.00000001 +197.31,50.30085681,-3.102791958,10000,0,200.0000644,0,0,0,90.00000001 +197.32,50.30085681,-3.102763931,10000,0,199.9996184,0,0,0,90.00000001 +197.33,50.30085681,-3.102735904,10000,0,199.9998414,0,0,0,90.00000001 +197.34,50.30085681,-3.102707876,10000,0,199.9998414,0,0,0,90.00000001 +197.35,50.30085681,-3.102679849,10000,0,199.9996184,0,0,0,90.00000001 +197.36,50.30085681,-3.102651822,10000,0,200.0000644,0,0,0,90.00000001 +197.37,50.30085681,-3.102623794,10000,0,200.0007334,0,0,0,90.00000001 +197.38,50.30085681,-3.102595767,10000,0,200.0007334,0,0,0,90.00000001 +197.39,50.30085681,-3.102567739,10000,0,200.0000644,0,0,0,90.00000001 +197.4,50.30085681,-3.102539712,10000,0,199.9996184,0,0,0,90.00000001 +197.41,50.30085681,-3.102511685,10000,0,199.9998414,0,0,0,90.00000001 +197.42,50.30085681,-3.102483657,10000,0,199.9998414,0,0,0,90.00000001 +197.43,50.30085681,-3.10245563,10000,0,199.9996184,0,0,0,90.00000001 +197.44,50.30085681,-3.102427603,10000,0,200.0000644,0,0,0,90.00000001 +197.45,50.30085681,-3.102399575,10000,0,200.0007334,0,0,0,90.00000001 +197.46,50.30085681,-3.102371548,10000,0,200.0007334,0,0,0,90.00000001 +197.47,50.30085681,-3.10234352,10000,0,200.0000644,0,0,0,90.00000001 +197.48,50.30085681,-3.102315493,10000,0,199.9996184,0,0,0,90.00000001 +197.49,50.30085681,-3.102287466,10000,0,199.9998414,0,0,0,90.00000001 +197.5,50.30085681,-3.102259438,10000,0,199.9998414,0,0,0,90.00000001 +197.51,50.30085681,-3.102231411,10000,0,199.9996184,0,0,0,90.00000001 +197.52,50.30085681,-3.102203384,10000,0,199.9998414,0,0,0,90.00000001 +197.53,50.30085681,-3.102175356,10000,0,199.9996184,0,0,0,90.00000001 +197.54,50.30085681,-3.102147329,10000,0,199.9987264,0,0,0,90.00000001 +197.55,50.30085681,-3.102119302,10000,0,199.9987264,0,0,0,90.00000001 +197.56,50.30085681,-3.102091275,10000,0,199.9996184,0,0,0,90.00000001 +197.57,50.30085681,-3.102063247,10000,0,199.9998414,0,0,0,90.00000001 +197.58,50.30085681,-3.10203522,10000,0,199.9996184,0,0,0,90.00000001 +197.59,50.30085681,-3.102007193,10000,0,200.0000644,0,0,0,90.00000001 +197.6,50.30085681,-3.101979165,10000,0,200.0007334,0,0,0,90.00000001 +197.61,50.30085681,-3.101951138,10000,0,200.0007334,0,0,0,90.00000001 +197.62,50.30085681,-3.10192311,10000,0,200.0000644,0,0,0,90.00000001 +197.63,50.30085681,-3.101895083,10000,0,199.9996184,0,0,0,90.00000001 +197.64,50.30085681,-3.101867056,10000,0,199.9998414,0,0,0,90.00000001 +197.65,50.30085681,-3.101839028,10000,0,199.9998414,0,0,0,90.00000001 +197.66,50.30085681,-3.101811001,10000,0,199.9996184,0,0,0,90.00000001 +197.67,50.30085681,-3.101782974,10000,0,200.0000644,0,0,0,90.00000001 +197.68,50.30085681,-3.101754946,10000,0,200.0007334,0,0,0,90.00000001 +197.69,50.30085681,-3.101726919,10000,0,200.0007334,0,0,0,90.00000001 +197.7,50.30085681,-3.101698891,10000,0,200.0000644,0,0,0,90.00000001 +197.71,50.30085681,-3.101670864,10000,0,199.9996184,0,0,0,90.00000001 +197.72,50.30085681,-3.101642837,10000,0,200.0000644,0,0,0,90.00000001 +197.73,50.30085681,-3.101614809,10000,0,200.0007334,0,0,0,90.00000001 +197.74,50.30085681,-3.101586782,10000,0,200.0007334,0,0,0,90.00000001 +197.75,50.30085681,-3.101558754,10000,0,200.0000644,0,0,0,90.00000001 +197.76,50.30085681,-3.101530727,10000,0,199.9996184,0,0,0,90.00000001 +197.77,50.30085681,-3.1015027,10000,0,199.9998414,0,0,0,90.00000001 +197.78,50.30085681,-3.101474672,10000,0,199.9998414,0,0,0,90.00000001 +197.79,50.30085681,-3.101446645,10000,0,199.9996184,0,0,0,90.00000001 +197.8,50.30085681,-3.101418618,10000,0,200.0000644,0,0,0,90.00000001 +197.81,50.30085681,-3.10139059,10000,0,200.0007334,0,0,0,90.00000001 +197.82,50.30085681,-3.101362563,10000,0,200.0007334,0,0,0,90.00000001 +197.83,50.30085681,-3.101334535,10000,0,200.0000644,0,0,0,90.00000001 +197.84,50.30085681,-3.101306508,10000,0,199.9996184,0,0,0,90.00000001 +197.85,50.30085681,-3.101278481,10000,0,199.9998414,0,0,0,90.00000001 +197.86,50.30085681,-3.101250453,10000,0,199.9998414,0,0,0,90.00000001 +197.87,50.30085681,-3.101222426,10000,0,199.9996184,0,0,0,90.00000001 +197.88,50.30085681,-3.101194399,10000,0,200.0000644,0,0,0,90.00000001 +197.89,50.30085681,-3.101166371,10000,0,200.0007334,0,0,0,90.00000001 +197.9,50.30085681,-3.101138344,10000,0,200.0007334,0,0,0,90.00000001 +197.91,50.30085681,-3.101110316,10000,0,200.0000644,0,0,0,90.00000001 +197.92,50.30085681,-3.101082289,10000,0,199.9996184,0,0,0,90.00000001 +197.93,50.30085681,-3.101054262,10000,0,199.9998414,0,0,0,90.00000001 +197.94,50.30085681,-3.101026234,10000,0,199.9998414,0,0,0,90.00000001 +197.95,50.30085681,-3.100998207,10000,0,199.9996184,0,0,0,90.00000001 +197.96,50.30085681,-3.10097018,10000,0,200.0000644,0,0,0,90.00000001 +197.97,50.30085681,-3.100942152,10000,0,200.0007334,0,0,0,90.00000001 +197.98,50.30085681,-3.100914125,10000,0,200.0007334,0,0,0,90.00000001 +197.99,50.30085681,-3.100886097,10000,0,200.0000644,0,0,0,90.00000001 +198,50.30085681,-3.10085807,10000,0,199.9996184,0,0,0,90.00000001 +198.01,50.30085681,-3.100830043,10000,0,199.9998414,0,0,0,90.00000001 +198.02,50.30085681,-3.100802015,10000,0,199.9998414,0,0,0,90.00000001 +198.03,50.30085681,-3.100773988,10000,0,199.9996184,0,0,0,90.00000001 +198.04,50.30085681,-3.100745961,10000,0,200.0000644,0,0,0,90.00000001 +198.05,50.30085681,-3.100717933,10000,0,200.0007334,0,0,0,90.00000001 +198.06,50.30085681,-3.100689906,10000,0,200.0007334,0,0,0,90.00000001 +198.07,50.30085681,-3.100661878,10000,0,199.9998414,0,0,0,90.00000001 +198.08,50.30085681,-3.100633851,10000,0,199.9985034,0,0,0,90.00000001 +198.09,50.30085681,-3.100605824,10000,0,199.9978344,0,0,0,90.00000001 +198.1,50.30085681,-3.100577797,10000,0,199.9985034,0,0,0,90.00000001 +198.11,50.30085681,-3.10054977,10000,0,199.9998414,0,0,0,90.00000001 +198.12,50.30085681,-3.100521742,10000,0,200.0007334,0,0,0,90.00000001 +198.13,50.30085681,-3.100493715,10000,0,200.0007334,0,0,0,90.00000001 +198.14,50.30085681,-3.100465687,10000,0,200.0000644,0,0,0,90.00000001 +198.15,50.30085681,-3.10043766,10000,0,199.9996184,0,0,0,90.00000001 +198.16,50.30085681,-3.100409633,10000,0,199.9998414,0,0,0,90.00000001 +198.17,50.30085681,-3.100381605,10000,0,199.9998414,0,0,0,90.00000001 +198.18,50.30085681,-3.100353578,10000,0,199.9996184,0,0,0,90.00000001 +198.19,50.30085681,-3.100325551,10000,0,200.0000644,0,0,0,90.00000001 +198.2,50.30085681,-3.100297523,10000,0,200.0007334,0,0,0,90.00000001 +198.21,50.30085681,-3.100269496,10000,0,200.0007334,0,0,0,90.00000001 +198.22,50.30085681,-3.100241468,10000,0,200.0000644,0,0,0,90.00000001 +198.23,50.30085681,-3.100213441,10000,0,199.9996184,0,0,0,90.00000001 +198.24,50.30085681,-3.100185414,10000,0,200.0000644,0,0,0,90.00000001 +198.25,50.30085681,-3.100157386,10000,0,200.0007334,0,0,0,90.00000001 +198.26,50.30085681,-3.100129359,10000,0,200.0007334,0,0,0,90.00000001 +198.27,50.30085681,-3.100101331,10000,0,200.0000644,0,0,0,90.00000001 +198.28,50.30085681,-3.100073304,10000,0,199.9996184,0,0,0,90.00000001 +198.29,50.30085681,-3.100045277,10000,0,199.9998414,0,0,0,90.00000001 +198.3,50.30085681,-3.100017249,10000,0,199.9998414,0,0,0,90.00000001 +198.31,50.30085681,-3.099989222,10000,0,199.9996184,0,0,0,90.00000001 +198.32,50.30085681,-3.099961195,10000,0,200.0000644,0,0,0,90.00000001 +198.33,50.30085681,-3.099933167,10000,0,200.0007334,0,0,0,90.00000001 +198.34,50.30085681,-3.09990514,10000,0,200.0007334,0,0,0,90.00000001 +198.35,50.30085681,-3.099877112,10000,0,200.0000644,0,0,0,90.00000001 +198.36,50.30085681,-3.099849085,10000,0,199.9996184,0,0,0,90.00000001 +198.37,50.30085681,-3.099821058,10000,0,199.9998414,0,0,0,90.00000001 +198.38,50.30085681,-3.09979303,10000,0,199.9998414,0,0,0,90.00000001 +198.39,50.30085681,-3.099765003,10000,0,199.9996184,0,0,0,90.00000001 +198.4,50.30085681,-3.099736976,10000,0,200.0000644,0,0,0,90.00000001 +198.41,50.30085681,-3.099708948,10000,0,200.0007334,0,0,0,90.00000001 +198.42,50.30085681,-3.099680921,10000,0,200.0007334,0,0,0,90.00000001 +198.43,50.30085681,-3.099652893,10000,0,200.0000644,0,0,0,90.00000001 +198.44,50.30085681,-3.099624866,10000,0,199.9996184,0,0,0,90.00000001 +198.45,50.30085681,-3.099596839,10000,0,199.9998414,0,0,0,90.00000001 +198.46,50.30085681,-3.099568811,10000,0,199.9998414,0,0,0,90.00000001 +198.47,50.30085681,-3.099540784,10000,0,199.9996184,0,0,0,90.00000001 +198.48,50.30085681,-3.099512757,10000,0,200.0000644,0,0,0,90.00000001 +198.49,50.30085681,-3.099484729,10000,0,200.0007334,0,0,0,90.00000001 +198.5,50.30085681,-3.099456702,10000,0,200.0007334,0,0,0,90.00000001 +198.51,50.30085681,-3.099428674,10000,0,200.0000644,0,0,0,90.00000001 +198.52,50.30085681,-3.099400647,10000,0,199.9996184,0,0,0,90.00000001 +198.53,50.30085681,-3.09937262,10000,0,199.9998414,0,0,0,90.00000001 +198.54,50.30085681,-3.099344592,10000,0,199.9998414,0,0,0,90.00000001 +198.55,50.30085681,-3.099316565,10000,0,199.9996184,0,0,0,90.00000001 +198.56,50.30085681,-3.099288538,10000,0,200.0000644,0,0,0,90.00000001 +198.57,50.30085681,-3.09926051,10000,0,200.0007334,0,0,0,90.00000001 +198.58,50.30085681,-3.099232483,10000,0,200.0007334,0,0,0,90.00000001 +198.59,50.30085681,-3.099204455,10000,0,200.0000644,0,0,0,90.00000001 +198.6,50.30085681,-3.099176428,10000,0,199.9996184,0,0,0,90.00000001 +198.61,50.30085681,-3.099148401,10000,0,199.9998414,0,0,0,90.00000001 +198.62,50.30085681,-3.099120373,10000,0,199.9996184,0,0,0,90.00000001 +198.63,50.30085681,-3.099092346,10000,0,199.9987264,0,0,0,90.00000001 +198.64,50.30085681,-3.099064319,10000,0,199.9987264,0,0,0,90.00000001 +198.65,50.30085681,-3.099036292,10000,0,199.9996184,0,0,0,90.00000001 +198.66,50.30085681,-3.099008264,10000,0,199.9998414,0,0,0,90.00000001 +198.67,50.30085681,-3.098980237,10000,0,199.9996184,0,0,0,90.00000001 +198.68,50.30085681,-3.09895221,10000,0,199.9998414,0,0,0,90.00000001 +198.69,50.30085681,-3.098924182,10000,0,199.9998414,0,0,0,90.00000001 +198.7,50.30085681,-3.098896155,10000,0,199.9996184,0,0,0,90.00000001 +198.71,50.30085681,-3.098868128,10000,0,200.0000644,0,0,0,90.00000001 +198.72,50.30085681,-3.0988401,10000,0,200.0007334,0,0,0,90.00000001 +198.73,50.30085681,-3.098812073,10000,0,200.0007334,0,0,0,90.00000001 +198.74,50.30085681,-3.098784045,10000,0,200.0000644,0,0,0,90.00000001 +198.75,50.30085681,-3.098756018,10000,0,199.9996184,0,0,0,90.00000001 +198.76,50.30085681,-3.098727991,10000,0,200.0000644,0,0,0,90.00000001 +198.77,50.30085681,-3.098699963,10000,0,200.0007334,0,0,0,90.00000001 +198.78,50.30085681,-3.098671936,10000,0,200.0007334,0,0,0,90.00000001 +198.79,50.30085681,-3.098643908,10000,0,200.0000644,0,0,0,90.00000001 +198.8,50.30085681,-3.098615881,10000,0,199.9996184,0,0,0,90.00000001 +198.81,50.30085681,-3.098587854,10000,0,199.9998414,0,0,0,90.00000001 +198.82,50.30085681,-3.098559826,10000,0,199.9998414,0,0,0,90.00000001 +198.83,50.30085681,-3.098531799,10000,0,199.9996184,0,0,0,90.00000001 +198.84,50.30085681,-3.098503772,10000,0,200.0000644,0,0,0,90.00000001 +198.85,50.30085681,-3.098475744,10000,0,200.0007334,0,0,0,90.00000001 +198.86,50.30085681,-3.098447717,10000,0,200.0007334,0,0,0,90.00000001 +198.87,50.30085681,-3.098419689,10000,0,200.0000644,0,0,0,90.00000001 +198.88,50.30085681,-3.098391662,10000,0,199.9996184,0,0,0,90.00000001 +198.89,50.30085681,-3.098363635,10000,0,199.9998414,0,0,0,90.00000001 +198.9,50.30085681,-3.098335607,10000,0,199.9998414,0,0,0,90.00000001 +198.91,50.30085681,-3.09830758,10000,0,199.9996184,0,0,0,90.00000001 +198.92,50.30085681,-3.098279553,10000,0,200.0000644,0,0,0,90.00000001 +198.93,50.30085681,-3.098251525,10000,0,200.0007334,0,0,0,90.00000001 +198.94,50.30085681,-3.098223498,10000,0,200.0007334,0,0,0,90.00000001 +198.95,50.30085681,-3.09819547,10000,0,200.0000644,0,0,0,90.00000001 +198.96,50.30085681,-3.098167443,10000,0,199.9996184,0,0,0,90.00000001 +198.97,50.30085681,-3.098139416,10000,0,199.9998414,0,0,0,90.00000001 +198.98,50.30085681,-3.098111388,10000,0,199.9998414,0,0,0,90.00000001 +198.99,50.30085681,-3.098083361,10000,0,199.9996184,0,0,0,90.00000001 +199,50.30085681,-3.098055334,10000,0,200.0000644,0,0,0,90.00000001 +199.01,50.30085681,-3.098027306,10000,0,200.0007334,0,0,0,90.00000001 +199.02,50.30085681,-3.097999279,10000,0,200.0007334,0,0,0,90.00000001 +199.03,50.30085681,-3.097971251,10000,0,200.0000644,0,0,0,90.00000001 +199.04,50.30085681,-3.097943224,10000,0,199.9996184,0,0,0,90.00000001 +199.05,50.30085681,-3.097915197,10000,0,199.9998414,0,0,0,90.00000001 +199.06,50.30085681,-3.097887169,10000,0,199.9998414,0,0,0,90.00000001 +199.07,50.30085681,-3.097859142,10000,0,199.9996184,0,0,0,90.00000001 +199.08,50.30085681,-3.097831115,10000,0,200.0000644,0,0,0,90.00000001 +199.09,50.30085681,-3.097803087,10000,0,200.0007334,0,0,0,90.00000001 +199.1,50.30085681,-3.09777506,10000,0,200.0007334,0,0,0,90.00000001 +199.11,50.30085681,-3.097747032,10000,0,200.0000644,0,0,0,90.00000001 +199.12,50.30085681,-3.097719005,10000,0,199.9996184,0,0,0,90.00000001 +199.13,50.30085681,-3.097690978,10000,0,199.9998414,0,0,0,90.00000001 +199.14,50.30085681,-3.09766295,10000,0,199.9998414,0,0,0,90.00000001 +199.15,50.30085681,-3.097634923,10000,0,199.9996184,0,0,0,90.00000001 +199.16,50.30085681,-3.097606896,10000,0,199.9998414,0,0,0,90.00000001 +199.17,50.30085681,-3.097578868,10000,0,199.9996184,0,0,0,90.00000001 +199.18,50.30085681,-3.097550841,10000,0,199.9987264,0,0,0,90.00000001 +199.19,50.30085681,-3.097522814,10000,0,199.9987264,0,0,0,90.00000001 +199.2,50.30085681,-3.097494787,10000,0,199.9998414,0,0,0,90.00000001 +199.21,50.30085681,-3.097466759,10000,0,200.0007334,0,0,0,90.00000001 +199.22,50.30085681,-3.097438732,10000,0,200.0007334,0,0,0,90.00000001 +199.23,50.30085681,-3.097410704,10000,0,200.0000644,0,0,0,90.00000001 +199.24,50.30085681,-3.097382677,10000,0,199.9996184,0,0,0,90.00000001 +199.25,50.30085681,-3.09735465,10000,0,199.9998414,0,0,0,90.00000001 +199.26,50.30085681,-3.097326622,10000,0,199.9998414,0,0,0,90.00000001 +199.27,50.30085681,-3.097298595,10000,0,199.9996184,0,0,0,90.00000001 +199.28,50.30085681,-3.097270568,10000,0,200.0000644,0,0,0,90.00000001 +199.29,50.30085681,-3.09724254,10000,0,200.0007334,0,0,0,90.00000001 +199.3,50.30085681,-3.097214513,10000,0,200.0007334,0,0,0,90.00000001 +199.31,50.30085681,-3.097186485,10000,0,200.0000644,0,0,0,90.00000001 +199.32,50.30085681,-3.097158458,10000,0,199.9996184,0,0,0,90.00000001 +199.33,50.30085681,-3.097130431,10000,0,199.9998414,0,0,0,90.00000001 +199.34,50.30085681,-3.097102403,10000,0,199.9998414,0,0,0,90.00000001 +199.35,50.30085681,-3.097074376,10000,0,199.9996184,0,0,0,90.00000001 +199.36,50.30085681,-3.097046349,10000,0,200.0000644,0,0,0,90.00000001 +199.37,50.30085681,-3.097018321,10000,0,200.0007334,0,0,0,90.00000001 +199.38,50.30085681,-3.096990294,10000,0,200.0007334,0,0,0,90.00000001 +199.39,50.30085681,-3.096962266,10000,0,200.0000644,0,0,0,90.00000001 +199.4,50.30085681,-3.096934239,10000,0,199.9996184,0,0,0,90.00000001 +199.41,50.30085681,-3.096906212,10000,0,199.9998414,0,0,0,90.00000001 +199.42,50.30085681,-3.096878184,10000,0,199.9998414,0,0,0,90.00000001 +199.43,50.30085681,-3.096850157,10000,0,199.9996184,0,0,0,90.00000001 +199.44,50.30085681,-3.09682213,10000,0,200.0000644,0,0,0,90.00000001 +199.45,50.30085681,-3.096794102,10000,0,200.0007334,0,0,0,90.00000001 +199.46,50.30085681,-3.096766075,10000,0,200.0007334,0,0,0,90.00000001 +199.47,50.30085681,-3.096738047,10000,0,200.0000644,0,0,0,90.00000001 +199.48,50.30085681,-3.09671002,10000,0,199.9996184,0,0,0,90.00000001 +199.49,50.30085681,-3.096681993,10000,0,199.9998414,0,0,0,90.00000001 +199.5,50.30085681,-3.096653965,10000,0,199.9998414,0,0,0,90.00000001 +199.51,50.30085681,-3.096625938,10000,0,199.9996184,0,0,0,90.00000001 +199.52,50.30085681,-3.096597911,10000,0,200.0000644,0,0,0,90.00000001 +199.53,50.30085681,-3.096569883,10000,0,200.0007334,0,0,0,90.00000001 +199.54,50.30085681,-3.096541856,10000,0,200.0007334,0,0,0,90.00000001 +199.55,50.30085681,-3.096513828,10000,0,200.0000644,0,0,0,90.00000001 +199.56,50.30085681,-3.096485801,10000,0,199.9996184,0,0,0,90.00000001 +199.57,50.30085681,-3.096457774,10000,0,199.9998414,0,0,0,90.00000001 +199.58,50.30085681,-3.096429746,10000,0,199.9998414,0,0,0,90.00000001 +199.59,50.30085681,-3.096401719,10000,0,199.9996184,0,0,0,90.00000001 +199.6,50.30085681,-3.096373692,10000,0,200.0000644,0,0,0,90.00000001 +199.61,50.30085681,-3.096345664,10000,0,200.0007334,0,0,0,90.00000001 +199.62,50.30085681,-3.096317637,10000,0,200.0007334,0,0,0,90.00000001 +199.63,50.30085681,-3.096289609,10000,0,200.0000644,0,0,0,90.00000001 +199.64,50.30085681,-3.096261582,10000,0,199.9996184,0,0,0,90.00000001 +199.65,50.30085681,-3.096233555,10000,0,199.9998414,0,0,0,90.00000001 +199.66,50.30085681,-3.096205527,10000,0,199.9998414,0,0,0,90.00000001 +199.67,50.30085681,-3.0961775,10000,0,199.9996184,0,0,0,90.00000001 +199.68,50.30085681,-3.096149473,10000,0,200.0000644,0,0,0,90.00000001 +199.69,50.30085681,-3.096121445,10000,0,200.0007334,0,0,0,90.00000001 +199.7,50.30085681,-3.096093418,10000,0,200.0007334,0,0,0,90.00000001 +199.71,50.30085681,-3.09606539,10000,0,199.9998414,0,0,0,90.00000001 +199.72,50.30085681,-3.096037363,10000,0,199.9987264,0,0,0,90.00000001 +199.73,50.30085681,-3.096009336,10000,0,199.9987264,0,0,0,90.00000001 +199.74,50.30085681,-3.095981309,10000,0,199.9996184,0,0,0,90.00000001 +199.75,50.30085681,-3.095953281,10000,0,199.9998414,0,0,0,90.00000001 +199.76,50.30085681,-3.095925254,10000,0,199.9996184,0,0,0,90.00000001 +199.77,50.30085681,-3.095897227,10000,0,199.9998414,0,0,0,90.00000001 +199.78,50.30085681,-3.095869199,10000,0,199.9998414,0,0,0,90.00000001 +199.79,50.30085681,-3.095841172,10000,0,199.9996184,0,0,0,90.00000001 +199.8,50.30085681,-3.095813145,10000,0,200.0000644,0,0,0,90.00000001 +199.81,50.30085681,-3.095785117,10000,0,200.0007334,0,0,0,90.00000001 +199.82,50.30085681,-3.09575709,10000,0,200.0007334,0,0,0,90.00000001 +199.83,50.30085681,-3.095729062,10000,0,200.0000644,0,0,0,90.00000001 +199.84,50.30085681,-3.095701035,10000,0,199.9996184,0,0,0,90.00000001 +199.85,50.30085681,-3.095673008,10000,0,199.9998414,0,0,0,90.00000001 +199.86,50.30085681,-3.09564498,10000,0,199.9998414,0,0,0,90.00000001 +199.87,50.30085681,-3.095616953,10000,0,199.9996184,0,0,0,90.00000001 +199.88,50.30085681,-3.095588926,10000,0,200.0000644,0,0,0,90.00000001 +199.89,50.30085681,-3.095560898,10000,0,200.0007334,0,0,0,90.00000001 +199.9,50.30085681,-3.095532871,10000,0,200.0007334,0,0,0,90.00000001 +199.91,50.30085681,-3.095504843,10000,0,200.0000644,0,0,0,90.00000001 +199.92,50.30085681,-3.095476816,10000,0,199.9996184,0,0,0,90.00000001 +199.93,50.30085681,-3.095448789,10000,0,199.9998414,0,0,0,90.00000001 +199.94,50.30085681,-3.095420761,10000,0,199.9998414,0,0,0,90.00000001 +199.95,50.30085681,-3.095392734,10000,0,199.9996184,0,0,0,90.00000001 +199.96,50.30085681,-3.095364707,10000,0,200.0000644,0,0,0,90.00000001 +199.97,50.30085681,-3.095336679,10000,0,200.0007334,0,0,0,90.00000001 +199.98,50.30085681,-3.095308652,10000,0,200.0007334,0,0,0,90.00000001 +199.99,50.30085681,-3.095280624,10000,0,200.0000644,0,0,0,90.00000001 +200,50.30085681,-3.095252597,10000,0,199.9996184,0,0,0,90.00000001 +200.01,50.30085681,-3.09522457,10000,0,199.9998414,0,0,0,90.00000001 +200.02,50.30085681,-3.095196542,10000,0,199.9998414,0,0,0,90.00000001 +200.03,50.30085681,-3.095168515,10000,0,199.9996184,0,0,0,90.00000001 +200.04,50.30085681,-3.095140488,10000,0,200.0000644,0,0,0,90.00000001 +200.05,50.30085681,-3.09511246,10000,0,200.0007334,0,0,0,90.00000001 +200.06,50.30085681,-3.095084433,10000,0,200.0007334,0,0,0,90.00000001 +200.07,50.30085681,-3.095056405,10000,0,200.0000644,0,0,0,90.00000001 +200.08,50.30085681,-3.095028378,10000,0,199.9996184,0,0,0,90.00000001 +200.09,50.30085681,-3.095000351,10000,0,199.9998414,0,0,0,90.00000001 +200.1,50.30085681,-3.094972323,10000,0,199.9998414,0,0,0,90.00000001 +200.11,50.30085681,-3.094944296,10000,0,199.9996184,0,0,0,90.00000001 +200.12,50.30085681,-3.094916269,10000,0,200.0000644,0,0,0,90.00000001 +200.13,50.30085681,-3.094888241,10000,0,200.0007334,0,0,0,90.00000001 +200.14,50.30085681,-3.094860214,10000,0,200.0007334,0,0,0,90.00000001 +200.15,50.30085681,-3.094832186,10000,0,200.0000644,0,0,0,90.00000001 +200.16,50.30085681,-3.094804159,10000,0,199.9996184,0,0,0,90.00000001 +200.17,50.30085681,-3.094776132,10000,0,199.9998414,0,0,0,90.00000001 +200.18,50.30085681,-3.094748104,10000,0,199.9998414,0,0,0,90.00000001 +200.19,50.30085681,-3.094720077,10000,0,199.9996184,0,0,0,90.00000001 +200.2,50.30085681,-3.09469205,10000,0,200.0000644,0,0,0,90.00000001 +200.21,50.30085681,-3.094664022,10000,0,200.0007334,0,0,0,90.00000001 +200.22,50.30085681,-3.094635995,10000,0,200.0007334,0,0,0,90.00000001 +200.23,50.30085681,-3.094607967,10000,0,200.0000644,0,0,0,90.00000001 +200.24,50.30085681,-3.09457994,10000,0,199.9996184,0,0,0,90.00000001 +200.25,50.30085681,-3.094551913,10000,0,199.9998414,0,0,0,90.00000001 +200.26,50.30085681,-3.094523885,10000,0,199.9996184,0,0,0,90.00000001 +200.27,50.30085681,-3.094495858,10000,0,199.9987264,0,0,0,90.00000001 +200.28,50.30085681,-3.094467831,10000,0,199.9987264,0,0,0,90.00000001 +200.29,50.30085681,-3.094439804,10000,0,199.9996184,0,0,0,90.00000001 +200.3,50.30085681,-3.094411776,10000,0,199.9998414,0,0,0,90.00000001 +200.31,50.30085681,-3.094383749,10000,0,199.9996184,0,0,0,90.00000001 +200.32,50.30085681,-3.094355722,10000,0,200.0000644,0,0,0,90.00000001 +200.33,50.30085681,-3.094327694,10000,0,200.0007334,0,0,0,90.00000001 +200.34,50.30085681,-3.094299667,10000,0,200.0007334,0,0,0,90.00000001 +200.35,50.30085681,-3.094271639,10000,0,200.0000644,0,0,0,90.00000001 +200.36,50.30085681,-3.094243612,10000,0,199.9996184,0,0,0,90.00000001 +200.37,50.30085681,-3.094215585,10000,0,199.9998414,0,0,0,90.00000001 +200.38,50.30085681,-3.094187557,10000,0,199.9998414,0,0,0,90.00000001 +200.39,50.30085681,-3.09415953,10000,0,199.9996184,0,0,0,90.00000001 +200.4,50.30085681,-3.094131503,10000,0,200.0000644,0,0,0,90.00000001 +200.41,50.30085681,-3.094103475,10000,0,200.0007334,0,0,0,90.00000001 +200.42,50.30085681,-3.094075448,10000,0,200.0007334,0,0,0,90.00000001 +200.43,50.30085681,-3.09404742,10000,0,200.0000644,0,0,0,90.00000001 +200.44,50.30085681,-3.094019393,10000,0,199.9996184,0,0,0,90.00000001 +200.45,50.30085681,-3.093991366,10000,0,199.9998414,0,0,0,90.00000001 +200.46,50.30085681,-3.093963338,10000,0,199.9998414,0,0,0,90.00000001 +200.47,50.30085681,-3.093935311,10000,0,199.9996184,0,0,0,90.00000001 +200.48,50.30085681,-3.093907284,10000,0,200.0000644,0,0,0,90.00000001 +200.49,50.30085681,-3.093879256,10000,0,200.0007334,0,0,0,90.00000001 +200.5,50.30085681,-3.093851229,10000,0,200.0007334,0,0,0,90.00000001 +200.51,50.30085681,-3.093823201,10000,0,200.0000644,0,0,0,90.00000001 +200.52,50.30085681,-3.093795174,10000,0,199.9996184,0,0,0,90.00000001 +200.53,50.30085681,-3.093767147,10000,0,199.9998414,0,0,0,90.00000001 +200.54,50.30085681,-3.093739119,10000,0,199.9998414,0,0,0,90.00000001 +200.55,50.30085681,-3.093711092,10000,0,199.9996184,0,0,0,90.00000001 +200.56,50.30085681,-3.093683065,10000,0,200.0000644,0,0,0,90.00000001 +200.57,50.30085681,-3.093655037,10000,0,200.0007334,0,0,0,90.00000001 +200.58,50.30085681,-3.09362701,10000,0,200.0007334,0,0,0,90.00000001 +200.59,50.30085681,-3.093598982,10000,0,200.0000644,0,0,0,90.00000001 +200.6,50.30085681,-3.093570955,10000,0,199.9996184,0,0,0,90.00000001 +200.61,50.30085681,-3.093542928,10000,0,199.9998414,0,0,0,90.00000001 +200.62,50.30085681,-3.0935149,10000,0,199.9998414,0,0,0,90.00000001 +200.63,50.30085681,-3.093486873,10000,0,199.9996184,0,0,0,90.00000001 +200.64,50.30085681,-3.093458846,10000,0,200.0000644,0,0,0,90.00000001 +200.65,50.30085681,-3.093430818,10000,0,200.0007334,0,0,0,90.00000001 +200.66,50.30085681,-3.093402791,10000,0,200.0007334,0,0,0,90.00000001 +200.67,50.30085681,-3.093374763,10000,0,200.0000644,0,0,0,90.00000001 +200.68,50.30085681,-3.093346736,10000,0,199.9996184,0,0,0,90.00000001 +200.69,50.30085681,-3.093318709,10000,0,199.9998414,0,0,0,90.00000001 +200.7,50.30085681,-3.093290681,10000,0,199.9998414,0,0,0,90.00000001 +200.71,50.30085681,-3.093262654,10000,0,199.9996184,0,0,0,90.00000001 +200.72,50.30085681,-3.093234627,10000,0,200.0000644,0,0,0,90.00000001 +200.73,50.30085681,-3.093206599,10000,0,200.0007334,0,0,0,90.00000001 +200.74,50.30085681,-3.093178572,10000,0,200.0007334,0,0,0,90.00000001 +200.75,50.30085681,-3.093150544,10000,0,200.0000644,0,0,0,90.00000001 +200.76,50.30085681,-3.093122517,10000,0,199.9996184,0,0,0,90.00000001 +200.77,50.30085681,-3.09309449,10000,0,199.9998414,0,0,0,90.00000001 +200.78,50.30085681,-3.093066462,10000,0,199.9998414,0,0,0,90.00000001 +200.79,50.30085681,-3.093038435,10000,0,199.9996184,0,0,0,90.00000001 +200.8,50.30085681,-3.093010408,10000,0,199.9998414,0,0,0,90.00000001 +200.81,50.30085681,-3.09298238,10000,0,199.9996184,0,0,0,90.00000001 +200.82,50.30085681,-3.092954353,10000,0,199.9987264,0,0,0,90.00000001 +200.83,50.30085681,-3.092926326,10000,0,199.9987264,0,0,0,90.00000001 +200.84,50.30085681,-3.092898299,10000,0,199.9998414,0,0,0,90.00000001 +200.85,50.30085681,-3.092870271,10000,0,200.0007334,0,0,0,90.00000001 +200.86,50.30085681,-3.092842244,10000,0,200.0007334,0,0,0,90.00000001 +200.87,50.30085681,-3.092814216,10000,0,200.0000644,0,0,0,90.00000001 +200.88,50.30085681,-3.092786189,10000,0,199.9996184,0,0,0,90.00000001 +200.89,50.30085681,-3.092758162,10000,0,199.9998414,0,0,0,90.00000001 +200.9,50.30085681,-3.092730134,10000,0,199.9998414,0,0,0,90.00000001 +200.91,50.30085681,-3.092702107,10000,0,199.9996184,0,0,0,90.00000001 +200.92,50.30085681,-3.09267408,10000,0,200.0000644,0,0,0,90.00000001 +200.93,50.30085681,-3.092646052,10000,0,200.0007334,0,0,0,90.00000001 +200.94,50.30085681,-3.092618025,10000,0,200.0007334,0,0,0,90.00000001 +200.95,50.30085681,-3.092589997,10000,0,200.0000644,0,0,0,90.00000001 +200.96,50.30085681,-3.09256197,10000,0,199.9996184,0,0,0,90.00000001 +200.97,50.30085681,-3.092533943,10000,0,199.9998414,0,0,0,90.00000001 +200.98,50.30085681,-3.092505915,10000,0,199.9998414,0,0,0,90.00000001 +200.99,50.30085681,-3.092477888,10000,0,199.9996184,0,0,0,90.00000001 +201,50.30085681,-3.092449861,10000,0,200.0000644,0,0,0,90.00000001 +201.01,50.30085681,-3.092421833,10000,0,200.0007334,0,0,0,90.00000001 +201.02,50.30085681,-3.092393806,10000,0,200.0007334,0,0,0,90.00000001 +201.03,50.30085681,-3.092365778,10000,0,200.0000644,0,0,0,90.00000001 +201.04,50.30085681,-3.092337751,10000,0,199.9996184,0,0,0,90.00000001 +201.05,50.30085681,-3.092309724,10000,0,199.9998414,0,0,0,90.00000001 +201.06,50.30085681,-3.092281696,10000,0,199.9998414,0,0,0,90.00000001 +201.07,50.30085681,-3.092253669,10000,0,199.9996184,0,0,0,90.00000001 +201.08,50.30085681,-3.092225642,10000,0,200.0000644,0,0,0,90.00000001 +201.09,50.30085681,-3.092197614,10000,0,200.0007334,0,0,0,90.00000001 +201.1,50.30085681,-3.092169587,10000,0,200.0007334,0,0,0,90.00000001 +201.11,50.30085681,-3.092141559,10000,0,200.0000644,0,0,0,90.00000001 +201.12,50.30085681,-3.092113532,10000,0,199.9996184,0,0,0,90.00000001 +201.13,50.30085681,-3.092085505,10000,0,199.9998414,0,0,0,90.00000001 +201.14,50.30085681,-3.092057477,10000,0,199.9998414,0,0,0,90.00000001 +201.15,50.30085681,-3.09202945,10000,0,199.9996184,0,0,0,90.00000001 +201.16,50.30085681,-3.092001423,10000,0,200.0000644,0,0,0,90.00000001 +201.17,50.30085681,-3.091973395,10000,0,200.0007334,0,0,0,90.00000001 +201.18,50.30085681,-3.091945368,10000,0,200.0007334,0,0,0,90.00000001 +201.19,50.30085681,-3.09191734,10000,0,200.0000644,0,0,0,90.00000001 +201.2,50.30085681,-3.091889313,10000,0,199.9996184,0,0,0,90.00000001 +201.21,50.30085681,-3.091861286,10000,0,199.9998414,0,0,0,90.00000001 +201.22,50.30085681,-3.091833258,10000,0,199.9998414,0,0,0,90.00000001 +201.23,50.30085681,-3.091805231,10000,0,199.9996184,0,0,0,90.00000001 +201.24,50.30085681,-3.091777204,10000,0,200.0000644,0,0,0,90.00000001 +201.25,50.30085681,-3.091749176,10000,0,200.0007334,0,0,0,90.00000001 +201.26,50.30085681,-3.091721149,10000,0,200.0007334,0,0,0,90.00000001 +201.27,50.30085681,-3.091693121,10000,0,200.0000644,0,0,0,90.00000001 +201.28,50.30085681,-3.091665094,10000,0,199.9996184,0,0,0,90.00000001 +201.29,50.30085681,-3.091637067,10000,0,199.9998414,0,0,0,90.00000001 +201.3,50.30085681,-3.091609039,10000,0,199.9998414,0,0,0,90.00000001 +201.31,50.30085681,-3.091581012,10000,0,199.9996184,0,0,0,90.00000001 +201.32,50.30085681,-3.091552985,10000,0,200.0000644,0,0,0,90.00000001 +201.33,50.30085681,-3.091524957,10000,0,200.0007334,0,0,0,90.00000001 +201.34,50.30085681,-3.09149693,10000,0,200.0007334,0,0,0,90.00000001 +201.35,50.30085681,-3.091468902,10000,0,199.9998414,0,0,0,90.00000001 +201.36,50.30085681,-3.091440875,10000,0,199.9987264,0,0,0,90.00000001 +201.37,50.30085681,-3.091412848,10000,0,199.9987264,0,0,0,90.00000001 +201.38,50.30085681,-3.091384821,10000,0,199.9996184,0,0,0,90.00000001 +201.39,50.30085681,-3.091356793,10000,0,199.9998414,0,0,0,90.00000001 +201.4,50.30085681,-3.091328766,10000,0,199.9996184,0,0,0,90.00000001 +201.41,50.30085681,-3.091300739,10000,0,199.9998414,0,0,0,90.00000001 +201.42,50.30085681,-3.091272711,10000,0,199.9998414,0,0,0,90.00000001 +201.43,50.30085681,-3.091244684,10000,0,199.9996184,0,0,0,90.00000001 +201.44,50.30085681,-3.091216657,10000,0,200.0000644,0,0,0,90.00000001 +201.45,50.30085681,-3.091188629,10000,0,200.0007334,0,0,0,90.00000001 +201.46,50.30085681,-3.091160602,10000,0,200.0007334,0,0,0,90.00000001 +201.47,50.30085681,-3.091132574,10000,0,200.0000644,0,0,0,90.00000001 +201.48,50.30085681,-3.091104547,10000,0,199.9996184,0,0,0,90.00000001 +201.49,50.30085681,-3.09107652,10000,0,199.9998414,0,0,0,90.00000001 +201.5,50.30085681,-3.091048492,10000,0,199.9998414,0,0,0,90.00000001 +201.51,50.30085681,-3.091020465,10000,0,199.9996184,0,0,0,90.00000001 +201.52,50.30085681,-3.090992438,10000,0,200.0000644,0,0,0,90.00000001 +201.53,50.30085681,-3.09096441,10000,0,200.0007334,0,0,0,90.00000001 +201.54,50.30085681,-3.090936383,10000,0,200.0007334,0,0,0,90.00000001 +201.55,50.30085681,-3.090908355,10000,0,200.0000644,0,0,0,90.00000001 +201.56,50.30085681,-3.090880328,10000,0,199.9996184,0,0,0,90.00000001 +201.57,50.30085681,-3.090852301,10000,0,199.9998414,0,0,0,90.00000001 +201.58,50.30085681,-3.090824273,10000,0,199.9998414,0,0,0,90.00000001 +201.59,50.30085681,-3.090796246,10000,0,199.9996184,0,0,0,90.00000001 +201.6,50.30085681,-3.090768219,10000,0,200.0000644,0,0,0,90.00000001 +201.61,50.30085681,-3.090740191,10000,0,200.0007334,0,0,0,90.00000001 +201.62,50.30085681,-3.090712164,10000,0,200.0007334,0,0,0,90.00000001 +201.63,50.30085681,-3.090684136,10000,0,200.0000644,0,0,0,90.00000001 +201.64,50.30085681,-3.090656109,10000,0,199.9996184,0,0,0,90.00000001 +201.65,50.30085681,-3.090628082,10000,0,199.9998414,0,0,0,90.00000001 +201.66,50.30085681,-3.090600054,10000,0,199.9998414,0,0,0,90.00000001 +201.67,50.30085681,-3.090572027,10000,0,199.9996184,0,0,0,90.00000001 +201.68,50.30085681,-3.090544,10000,0,200.0000644,0,0,0,90.00000001 +201.69,50.30085681,-3.090515972,10000,0,200.0007334,0,0,0,90.00000001 +201.7,50.30085681,-3.090487945,10000,0,200.0007334,0,0,0,90.00000001 +201.71,50.30085681,-3.090459917,10000,0,200.0000644,0,0,0,90.00000001 +201.72,50.30085681,-3.09043189,10000,0,199.9996184,0,0,0,90.00000001 +201.73,50.30085681,-3.090403863,10000,0,199.9998414,0,0,0,90.00000001 +201.74,50.30085681,-3.090375835,10000,0,199.9998414,0,0,0,90.00000001 +201.75,50.30085681,-3.090347808,10000,0,199.9996184,0,0,0,90.00000001 +201.76,50.30085681,-3.090319781,10000,0,200.0000644,0,0,0,90.00000001 +201.77,50.30085681,-3.090291753,10000,0,200.0007334,0,0,0,90.00000001 +201.78,50.30085681,-3.090263726,10000,0,200.0007334,0,0,0,90.00000001 +201.79,50.30085681,-3.090235698,10000,0,200.0000644,0,0,0,90.00000001 +201.8,50.30085681,-3.090207671,10000,0,199.9996184,0,0,0,90.00000001 +201.81,50.30085681,-3.090179644,10000,0,199.9998414,0,0,0,90.00000001 +201.82,50.30085681,-3.090151616,10000,0,199.9998414,0,0,0,90.00000001 +201.83,50.30085681,-3.090123589,10000,0,199.9996184,0,0,0,90.00000001 +201.84,50.30085681,-3.090095562,10000,0,200.0000644,0,0,0,90.00000001 +201.85,50.30085681,-3.090067534,10000,0,200.0007334,0,0,0,90.00000001 +201.86,50.30085681,-3.090039507,10000,0,200.0007334,0,0,0,90.00000001 +201.87,50.30085681,-3.090011479,10000,0,200.0000644,0,0,0,90.00000001 +201.88,50.30085681,-3.089983452,10000,0,199.9996184,0,0,0,90.00000001 +201.89,50.30085681,-3.089955425,10000,0,199.9998414,0,0,0,90.00000001 +201.9,50.30085681,-3.089927397,10000,0,199.9996184,0,0,0,90.00000001 +201.91,50.30085681,-3.08989937,10000,0,199.9987264,0,0,0,90.00000001 +201.92,50.30085681,-3.089871343,10000,0,199.9987264,0,0,0,90.00000001 +201.93,50.30085681,-3.089843316,10000,0,199.9996184,0,0,0,90.00000001 +201.94,50.30085681,-3.089815288,10000,0,199.9998414,0,0,0,90.00000001 +201.95,50.30085681,-3.089787261,10000,0,199.9996184,0,0,0,90.00000001 +201.96,50.30085681,-3.089759234,10000,0,200.0000644,0,0,0,90.00000001 +201.97,50.30085681,-3.089731206,10000,0,200.0007334,0,0,0,90.00000001 +201.98,50.30085681,-3.089703179,10000,0,200.0007334,0,0,0,90.00000001 +201.99,50.30085681,-3.089675151,10000,0,200.0000644,0,0,0,90.00000001 +202,50.30085681,-3.089647124,10000,0,199.9996184,0,0,0,90.00000001 +202.01,50.30085681,-3.089619097,10000,0,199.9998414,0,0,0,90.00000001 +202.02,50.30085681,-3.089591069,10000,0,199.9998414,0,0,0,90.00000001 +202.03,50.30085681,-3.089563042,10000,0,199.9996184,0,0,0,90.00000001 +202.04,50.30085681,-3.089535015,10000,0,200.0000644,0,0,0,90.00000001 +202.05,50.30085681,-3.089506987,10000,0,200.0007334,0,0,0,90.00000001 +202.06,50.30085681,-3.08947896,10000,0,200.0007334,0,0,0,90.00000001 +202.07,50.30085681,-3.089450932,10000,0,200.0000644,0,0,0,90.00000001 +202.08,50.30085681,-3.089422905,10000,0,199.9996184,0,0,0,90.00000001 +202.09,50.30085681,-3.089394878,10000,0,199.9998414,0,0,0,90.00000001 +202.1,50.30085681,-3.08936685,10000,0,199.9998414,0,0,0,90.00000001 +202.11,50.30085681,-3.089338823,10000,0,199.9996184,0,0,0,90.00000001 +202.12,50.30085681,-3.089310796,10000,0,200.0000644,0,0,0,90.00000001 +202.13,50.30085681,-3.089282768,10000,0,200.0007334,0,0,0,90.00000001 +202.14,50.30085681,-3.089254741,10000,0,200.0007334,0,0,0,90.00000001 +202.15,50.30085681,-3.089226713,10000,0,200.0000644,0,0,0,90.00000001 +202.16,50.30085681,-3.089198686,10000,0,199.9996184,0,0,0,90.00000001 +202.17,50.30085681,-3.089170659,10000,0,199.9998414,0,0,0,90.00000001 +202.18,50.30085681,-3.089142631,10000,0,199.9998414,0,0,0,90.00000001 +202.19,50.30085681,-3.089114604,10000,0,199.9996184,0,0,0,90.00000001 +202.2,50.30085681,-3.089086577,10000,0,200.0000644,0,0,0,90.00000001 +202.21,50.30085681,-3.089058549,10000,0,200.0007334,0,0,0,90.00000001 +202.22,50.30085681,-3.089030522,10000,0,200.0007334,0,0,0,90.00000001 +202.23,50.30085681,-3.089002494,10000,0,200.0000644,0,0,0,90.00000001 +202.24,50.30085681,-3.088974467,10000,0,199.9996184,0,0,0,90.00000001 +202.25,50.30085681,-3.08894644,10000,0,199.9998414,0,0,0,90.00000001 +202.26,50.30085681,-3.088918412,10000,0,199.9998414,0,0,0,90.00000001 +202.27,50.30085681,-3.088890385,10000,0,199.9996184,0,0,0,90.00000001 +202.28,50.30085681,-3.088862358,10000,0,200.0000644,0,0,0,90.00000001 +202.29,50.30085681,-3.08883433,10000,0,200.0007334,0,0,0,90.00000001 +202.3,50.30085681,-3.088806303,10000,0,200.0007334,0,0,0,90.00000001 +202.31,50.30085681,-3.088778275,10000,0,200.0000644,0,0,0,90.00000001 +202.32,50.30085681,-3.088750248,10000,0,199.9996184,0,0,0,90.00000001 +202.33,50.30085681,-3.088722221,10000,0,199.9998414,0,0,0,90.00000001 +202.34,50.30085681,-3.088694193,10000,0,199.9998414,0,0,0,90.00000001 +202.35,50.30085681,-3.088666166,10000,0,199.9996184,0,0,0,90.00000001 +202.36,50.30085681,-3.088638139,10000,0,200.0000644,0,0,0,90.00000001 +202.37,50.30085681,-3.088610111,10000,0,200.0007334,0,0,0,90.00000001 +202.38,50.30085681,-3.088582084,10000,0,200.0007334,0,0,0,90.00000001 +202.39,50.30085681,-3.088554056,10000,0,200.0000644,0,0,0,90.00000001 +202.4,50.30085681,-3.088526029,10000,0,199.9996184,0,0,0,90.00000001 +202.41,50.30085681,-3.088498002,10000,0,199.9998414,0,0,0,90.00000001 +202.42,50.30085681,-3.088469974,10000,0,199.9998414,0,0,0,90.00000001 +202.43,50.30085681,-3.088441947,10000,0,199.9996184,0,0,0,90.00000001 +202.44,50.30085681,-3.08841392,10000,0,199.9998414,0,0,0,90.00000001 +202.45,50.30085681,-3.088385892,10000,0,199.9996184,0,0,0,90.00000001 +202.46,50.30085681,-3.088357865,10000,0,199.9987264,0,0,0,90.00000001 +202.47,50.30085681,-3.088329838,10000,0,199.9987264,0,0,0,90.00000001 +202.48,50.30085681,-3.088301811,10000,0,199.9998414,0,0,0,90.00000001 +202.49,50.30085681,-3.088273783,10000,0,200.0007334,0,0,0,90.00000001 +202.5,50.30085681,-3.088245756,10000,0,200.0007334,0,0,0,90.00000001 +202.51,50.30085681,-3.088217728,10000,0,200.0000644,0,0,0,90.00000001 +202.52,50.30085681,-3.088189701,10000,0,199.9996184,0,0,0,90.00000001 +202.53,50.30085681,-3.088161674,10000,0,199.9998414,0,0,0,90.00000001 +202.54,50.30085681,-3.088133646,10000,0,199.9998414,0,0,0,90.00000001 +202.55,50.30085681,-3.088105619,10000,0,199.9996184,0,0,0,90.00000001 +202.56,50.30085681,-3.088077592,10000,0,200.0000644,0,0,0,90.00000001 +202.57,50.30085681,-3.088049564,10000,0,200.0007334,0,0,0,90.00000001 +202.58,50.30085681,-3.088021537,10000,0,200.0007334,0,0,0,90.00000001 +202.59,50.30085681,-3.087993509,10000,0,200.0000644,0,0,0,90.00000001 +202.6,50.30085681,-3.087965482,10000,0,199.9996184,0,0,0,90.00000001 +202.61,50.30085681,-3.087937455,10000,0,199.9998414,0,0,0,90.00000001 +202.62,50.30085681,-3.087909427,10000,0,199.9998414,0,0,0,90.00000001 +202.63,50.30085681,-3.0878814,10000,0,199.9996184,0,0,0,90.00000001 +202.64,50.30085681,-3.087853373,10000,0,200.0000644,0,0,0,90.00000001 +202.65,50.30085681,-3.087825345,10000,0,200.0007334,0,0,0,90.00000001 +202.66,50.30085681,-3.087797318,10000,0,200.0007334,0,0,0,90.00000001 +202.67,50.30085681,-3.08776929,10000,0,200.0000644,0,0,0,90.00000001 +202.68,50.30085681,-3.087741263,10000,0,199.9996184,0,0,0,90.00000001 +202.69,50.30085681,-3.087713236,10000,0,199.9998414,0,0,0,90.00000001 +202.7,50.30085681,-3.087685208,10000,0,199.9998414,0,0,0,90.00000001 +202.71,50.30085681,-3.087657181,10000,0,199.9996184,0,0,0,90.00000001 +202.72,50.30085681,-3.087629154,10000,0,200.0000644,0,0,0,90.00000001 +202.73,50.30085681,-3.087601126,10000,0,200.0007334,0,0,0,90.00000001 +202.74,50.30085681,-3.087573099,10000,0,200.0007334,0,0,0,90.00000001 +202.75,50.30085681,-3.087545071,10000,0,200.0000644,0,0,0,90.00000001 +202.76,50.30085681,-3.087517044,10000,0,199.9996184,0,0,0,90.00000001 +202.77,50.30085681,-3.087489017,10000,0,199.9998414,0,0,0,90.00000001 +202.78,50.30085681,-3.087460989,10000,0,199.9998414,0,0,0,90.00000001 +202.79,50.30085681,-3.087432962,10000,0,199.9996184,0,0,0,90.00000001 +202.8,50.30085681,-3.087404935,10000,0,200.0000644,0,0,0,90.00000001 +202.81,50.30085681,-3.087376907,10000,0,200.0007334,0,0,0,90.00000001 +202.82,50.30085681,-3.08734888,10000,0,200.0007334,0,0,0,90.00000001 +202.83,50.30085681,-3.087320852,10000,0,200.0000644,0,0,0,90.00000001 +202.84,50.30085681,-3.087292825,10000,0,199.9996184,0,0,0,90.00000001 +202.85,50.30085681,-3.087264798,10000,0,199.9998414,0,0,0,90.00000001 +202.86,50.30085681,-3.08723677,10000,0,199.9998414,0,0,0,90.00000001 +202.87,50.30085681,-3.087208743,10000,0,199.9996184,0,0,0,90.00000001 +202.88,50.30085681,-3.087180716,10000,0,200.0000644,0,0,0,90.00000001 +202.89,50.30085681,-3.087152688,10000,0,200.0007334,0,0,0,90.00000001 +202.9,50.30085681,-3.087124661,10000,0,200.0007334,0,0,0,90.00000001 +202.91,50.30085681,-3.087096633,10000,0,200.0000644,0,0,0,90.00000001 +202.92,50.30085681,-3.087068606,10000,0,199.9996184,0,0,0,90.00000001 +202.93,50.30085681,-3.087040579,10000,0,199.9998414,0,0,0,90.00000001 +202.94,50.30085681,-3.087012551,10000,0,199.9998414,0,0,0,90.00000001 +202.95,50.30085681,-3.086984524,10000,0,199.9996184,0,0,0,90.00000001 +202.96,50.30085681,-3.086956497,10000,0,200.0000644,0,0,0,90.00000001 +202.97,50.30085681,-3.086928469,10000,0,200.0007334,0,0,0,90.00000001 +202.98,50.30085681,-3.086900442,10000,0,200.0007334,0,0,0,90.00000001 +202.99,50.30085681,-3.086872414,10000,0,199.9998414,0,0,0,90.00000001 +203,50.30085681,-3.086844387,10000,0,199.9987264,0,0,0,90.00000001 +203.01,50.30085681,-3.08681636,10000,0,199.9987264,0,0,0,90.00000001 +203.02,50.30085681,-3.086788333,10000,0,199.9996184,0,0,0,90.00000001 +203.03,50.30085681,-3.086760305,10000,0,199.9998414,0,0,0,90.00000001 +203.04,50.30085681,-3.086732278,10000,0,199.9996184,0,0,0,90.00000001 +203.05,50.30085681,-3.086704251,10000,0,199.9998414,0,0,0,90.00000001 +203.06,50.30085681,-3.086676223,10000,0,199.9998414,0,0,0,90.00000001 +203.07,50.30085681,-3.086648196,10000,0,199.9996184,0,0,0,90.00000001 +203.08,50.30085681,-3.086620169,10000,0,200.0000644,0,0,0,90.00000001 +203.09,50.30085681,-3.086592141,10000,0,200.0007334,0,0,0,90.00000001 +203.1,50.30085681,-3.086564114,10000,0,200.0007334,0,0,0,90.00000001 +203.11,50.30085681,-3.086536086,10000,0,200.0000644,0,0,0,90.00000001 +203.12,50.30085681,-3.086508059,10000,0,199.9996184,0,0,0,90.00000001 +203.13,50.30085681,-3.086480032,10000,0,199.9998414,0,0,0,90.00000001 +203.14,50.30085681,-3.086452004,10000,0,199.9998414,0,0,0,90.00000001 +203.15,50.30085681,-3.086423977,10000,0,199.9996184,0,0,0,90.00000001 +203.16,50.30085681,-3.08639595,10000,0,200.0000644,0,0,0,90.00000001 +203.17,50.30085681,-3.086367922,10000,0,200.0007334,0,0,0,90.00000001 +203.18,50.30085681,-3.086339895,10000,0,200.0007334,0,0,0,90.00000001 +203.19,50.30085681,-3.086311867,10000,0,200.0000644,0,0,0,90.00000001 +203.2,50.30085681,-3.08628384,10000,0,199.9996184,0,0,0,90.00000001 +203.21,50.30085681,-3.086255813,10000,0,199.9998414,0,0,0,90.00000001 +203.22,50.30085681,-3.086227785,10000,0,199.9998414,0,0,0,90.00000001 +203.23,50.30085681,-3.086199758,10000,0,199.9996184,0,0,0,90.00000001 +203.24,50.30085681,-3.086171731,10000,0,200.0000644,0,0,0,90.00000001 +203.25,50.30085681,-3.086143703,10000,0,200.0007334,0,0,0,90.00000001 +203.26,50.30085681,-3.086115676,10000,0,200.0007334,0,0,0,90.00000001 +203.27,50.30085681,-3.086087648,10000,0,200.0000644,0,0,0,90.00000001 +203.28,50.30085681,-3.086059621,10000,0,199.9996184,0,0,0,90.00000001 +203.29,50.30085681,-3.086031594,10000,0,199.9998414,0,0,0,90.00000001 +203.3,50.30085681,-3.086003566,10000,0,199.9998414,0,0,0,90.00000001 +203.31,50.30085681,-3.085975539,10000,0,199.9996184,0,0,0,90.00000001 +203.32,50.30085681,-3.085947512,10000,0,200.0000644,0,0,0,90.00000001 +203.33,50.30085681,-3.085919484,10000,0,200.0007334,0,0,0,90.00000001 +203.34,50.30085681,-3.085891457,10000,0,200.0007334,0,0,0,90.00000001 +203.35,50.30085681,-3.085863429,10000,0,200.0000644,0,0,0,90.00000001 +203.36,50.30085681,-3.085835402,10000,0,199.9996184,0,0,0,90.00000001 +203.37,50.30085681,-3.085807375,10000,0,199.9998414,0,0,0,90.00000001 +203.38,50.30085681,-3.085779347,10000,0,199.9998414,0,0,0,90.00000001 +203.39,50.30085681,-3.08575132,10000,0,199.9996184,0,0,0,90.00000001 +203.4,50.30085681,-3.085723293,10000,0,200.0000644,0,0,0,90.00000001 +203.41,50.30085681,-3.085695265,10000,0,200.0007334,0,0,0,90.00000001 +203.42,50.30085681,-3.085667238,10000,0,200.0007334,0,0,0,90.00000001 +203.43,50.30085681,-3.08563921,10000,0,200.0000644,0,0,0,90.00000001 +203.44,50.30085681,-3.085611183,10000,0,199.9996184,0,0,0,90.00000001 +203.45,50.30085681,-3.085583156,10000,0,199.9998414,0,0,0,90.00000001 +203.46,50.30085681,-3.085555128,10000,0,199.9998414,0,0,0,90.00000001 +203.47,50.30085681,-3.085527101,10000,0,199.9996184,0,0,0,90.00000001 +203.48,50.30085681,-3.085499074,10000,0,200.0000644,0,0,0,90.00000001 +203.49,50.30085681,-3.085471046,10000,0,200.0007334,0,0,0,90.00000001 +203.5,50.30085681,-3.085443019,10000,0,200.0007334,0,0,0,90.00000001 +203.51,50.30085681,-3.085414991,10000,0,200.0000644,0,0,0,90.00000001 +203.52,50.30085681,-3.085386964,10000,0,199.9996184,0,0,0,90.00000001 +203.53,50.30085681,-3.085358937,10000,0,199.9998414,0,0,0,90.00000001 +203.54,50.30085681,-3.085330909,10000,0,199.9996184,0,0,0,90.00000001 +203.55,50.30085681,-3.085302882,10000,0,199.9987264,0,0,0,90.00000001 +203.56,50.30085681,-3.085274855,10000,0,199.9987264,0,0,0,90.00000001 +203.57,50.30085681,-3.085246828,10000,0,199.9996184,0,0,0,90.00000001 +203.58,50.30085681,-3.0852188,10000,0,199.9998414,0,0,0,90.00000001 +203.59,50.30085681,-3.085190773,10000,0,199.9996184,0,0,0,90.00000001 +203.6,50.30085681,-3.085162746,10000,0,200.0000644,0,0,0,90.00000001 +203.61,50.30085681,-3.085134718,10000,0,200.0007334,0,0,0,90.00000001 +203.62,50.30085681,-3.085106691,10000,0,200.0007334,0,0,0,90.00000001 +203.63,50.30085681,-3.085078663,10000,0,200.0000644,0,0,0,90.00000001 +203.64,50.30085681,-3.085050636,10000,0,199.9996184,0,0,0,90.00000001 +203.65,50.30085681,-3.085022609,10000,0,199.9998414,0,0,0,90.00000001 +203.66,50.30085681,-3.084994581,10000,0,199.9998414,0,0,0,90.00000001 +203.67,50.30085681,-3.084966554,10000,0,199.9996184,0,0,0,90.00000001 +203.68,50.30085681,-3.084938527,10000,0,200.0000644,0,0,0,90.00000001 +203.69,50.30085681,-3.084910499,10000,0,200.0007334,0,0,0,90.00000001 +203.7,50.30085681,-3.084882472,10000,0,200.0007334,0,0,0,90.00000001 +203.71,50.30085681,-3.084854444,10000,0,200.0000644,0,0,0,90.00000001 +203.72,50.30085681,-3.084826417,10000,0,199.9996184,0,0,0,90.00000001 +203.73,50.30085681,-3.08479839,10000,0,199.9998414,0,0,0,90.00000001 +203.74,50.30085681,-3.084770362,10000,0,199.9998414,0,0,0,90.00000001 +203.75,50.30085681,-3.084742335,10000,0,199.9996184,0,0,0,90.00000001 +203.76,50.30085681,-3.084714308,10000,0,200.0000644,0,0,0,90.00000001 +203.77,50.30085681,-3.08468628,10000,0,200.0007334,0,0,0,90.00000001 +203.78,50.30085681,-3.084658253,10000,0,200.0007334,0,0,0,90.00000001 +203.79,50.30085681,-3.084630225,10000,0,200.0000644,0,0,0,90.00000001 +203.8,50.30085681,-3.084602198,10000,0,199.9996184,0,0,0,90.00000001 +203.81,50.30085681,-3.084574171,10000,0,199.9998414,0,0,0,90.00000001 +203.82,50.30085681,-3.084546143,10000,0,199.9998414,0,0,0,90.00000001 +203.83,50.30085681,-3.084518116,10000,0,199.9996184,0,0,0,90.00000001 +203.84,50.30085681,-3.084490089,10000,0,200.0000644,0,0,0,90.00000001 +203.85,50.30085681,-3.084462061,10000,0,200.0007334,0,0,0,90.00000001 +203.86,50.30085681,-3.084434034,10000,0,200.0007334,0,0,0,90.00000001 +203.87,50.30085681,-3.084406006,10000,0,200.0000644,0,0,0,90.00000001 +203.88,50.30085681,-3.084377979,10000,0,199.9996184,0,0,0,90.00000001 +203.89,50.30085681,-3.084349952,10000,0,199.9998414,0,0,0,90.00000001 +203.9,50.30085681,-3.084321924,10000,0,199.9998414,0,0,0,90.00000001 +203.91,50.30085681,-3.084293897,10000,0,199.9996184,0,0,0,90.00000001 +203.92,50.30085681,-3.08426587,10000,0,200.0000644,0,0,0,90.00000001 +203.93,50.30085681,-3.084237842,10000,0,200.0007334,0,0,0,90.00000001 +203.94,50.30085681,-3.084209815,10000,0,200.0007334,0,0,0,90.00000001 +203.95,50.30085681,-3.084181787,10000,0,200.0000644,0,0,0,90.00000001 +203.96,50.30085681,-3.08415376,10000,0,199.9996184,0,0,0,90.00000001 +203.97,50.30085681,-3.084125733,10000,0,199.9998414,0,0,0,90.00000001 +203.98,50.30085681,-3.084097705,10000,0,199.9998414,0,0,0,90.00000001 +203.99,50.30085681,-3.084069678,10000,0,199.9996184,0,0,0,90.00000001 +204,50.30085681,-3.084041651,10000,0,200.0000644,0,0,0,90.00000001 +204.01,50.30085681,-3.084013623,10000,0,200.0007334,0,0,0,90.00000001 +204.02,50.30085681,-3.083985596,10000,0,200.0007334,0,0,0,90.00000001 +204.03,50.30085681,-3.083957568,10000,0,200.0000644,0,0,0,90.00000001 +204.04,50.30085681,-3.083929541,10000,0,199.9996184,0,0,0,90.00000001 +204.05,50.30085681,-3.083901514,10000,0,200.0000644,0,0,0,90.00000001 +204.06,50.30085681,-3.083873486,10000,0,200.0007334,0,0,0,90.00000001 +204.07,50.30085681,-3.083845459,10000,0,200.0007334,0,0,0,90.00000001 +204.08,50.30085681,-3.083817431,10000,0,199.9998414,0,0,0,90.00000001 +204.09,50.30085681,-3.083789404,10000,0,199.9985034,0,0,0,90.00000001 +204.1,50.30085681,-3.083761377,10000,0,199.9978344,0,0,0,90.00000001 +204.11,50.30085681,-3.08373335,10000,0,199.9985034,0,0,0,90.00000001 +204.12,50.30085681,-3.083705323,10000,0,199.9998414,0,0,0,90.00000001 +204.13,50.30085681,-3.083677295,10000,0,200.0007334,0,0,0,90.00000001 +204.14,50.30085681,-3.083649268,10000,0,200.0007334,0,0,0,90.00000001 +204.15,50.30085681,-3.08362124,10000,0,200.0000644,0,0,0,90.00000001 +204.16,50.30085681,-3.083593213,10000,0,199.9996184,0,0,0,90.00000001 +204.17,50.30085681,-3.083565186,10000,0,199.9998414,0,0,0,90.00000001 +204.18,50.30085681,-3.083537158,10000,0,199.9998414,0,0,0,90.00000001 +204.19,50.30085681,-3.083509131,10000,0,199.9996184,0,0,0,90.00000001 +204.2,50.30085681,-3.083481104,10000,0,200.0000644,0,0,0,90.00000001 +204.21,50.30085681,-3.083453076,10000,0,200.0007334,0,0,0,90.00000001 +204.22,50.30085681,-3.083425049,10000,0,200.0007334,0,0,0,90.00000001 +204.23,50.30085681,-3.083397021,10000,0,200.0000644,0,0,0,90.00000001 +204.24,50.30085681,-3.083368994,10000,0,199.9996184,0,0,0,90.00000001 +204.25,50.30085681,-3.083340967,10000,0,199.9998414,0,0,0,90.00000001 +204.26,50.30085681,-3.083312939,10000,0,199.9998414,0,0,0,90.00000001 +204.27,50.30085681,-3.083284912,10000,0,199.9996184,0,0,0,90.00000001 +204.28,50.30085681,-3.083256885,10000,0,200.0000644,0,0,0,90.00000001 +204.29,50.30085681,-3.083228857,10000,0,200.0007334,0,0,0,90.00000001 +204.3,50.30085681,-3.08320083,10000,0,200.0007334,0,0,0,90.00000001 +204.31,50.30085681,-3.083172802,10000,0,200.0000644,0,0,0,90.00000001 +204.32,50.30085681,-3.083144775,10000,0,199.9996184,0,0,0,90.00000001 +204.33,50.30085681,-3.083116748,10000,0,199.9998414,0,0,0,90.00000001 +204.34,50.30085681,-3.08308872,10000,0,199.9998414,0,0,0,90.00000001 +204.35,50.30085681,-3.083060693,10000,0,199.9996184,0,0,0,90.00000001 +204.36,50.30085681,-3.083032666,10000,0,200.0000644,0,0,0,90.00000001 +204.37,50.30085681,-3.083004638,10000,0,200.0007334,0,0,0,90.00000001 +204.38,50.30085681,-3.082976611,10000,0,200.0007334,0,0,0,90.00000001 +204.39,50.30085681,-3.082948583,10000,0,200.0000644,0,0,0,90.00000001 +204.4,50.30085681,-3.082920556,10000,0,199.9996184,0,0,0,90.00000001 +204.41,50.30085681,-3.082892529,10000,0,199.9998414,0,0,0,90.00000001 +204.42,50.30085681,-3.082864501,10000,0,199.9998414,0,0,0,90.00000001 +204.43,50.30085681,-3.082836474,10000,0,199.9996184,0,0,0,90.00000001 +204.44,50.30085681,-3.082808447,10000,0,200.0000644,0,0,0,90.00000001 +204.45,50.30085681,-3.082780419,10000,0,200.0007334,0,0,0,90.00000001 +204.46,50.30085681,-3.082752392,10000,0,200.0007334,0,0,0,90.00000001 +204.47,50.30085681,-3.082724364,10000,0,200.0000644,0,0,0,90.00000001 +204.48,50.30085681,-3.082696337,10000,0,199.9996184,0,0,0,90.00000001 +204.49,50.30085681,-3.08266831,10000,0,199.9998414,0,0,0,90.00000001 +204.5,50.30085681,-3.082640282,10000,0,199.9998414,0,0,0,90.00000001 +204.51,50.30085681,-3.082612255,10000,0,199.9996184,0,0,0,90.00000001 +204.52,50.30085681,-3.082584228,10000,0,200.0000644,0,0,0,90.00000001 +204.53,50.30085681,-3.0825562,10000,0,200.0007334,0,0,0,90.00000001 +204.54,50.30085681,-3.082528173,10000,0,200.0007334,0,0,0,90.00000001 +204.55,50.30085681,-3.082500145,10000,0,200.0000644,0,0,0,90.00000001 +204.56,50.30085681,-3.082472118,10000,0,199.9996184,0,0,0,90.00000001 +204.57,50.30085681,-3.082444091,10000,0,200.0000644,0,0,0,90.00000001 +204.58,50.30085681,-3.082416063,10000,0,200.0007334,0,0,0,90.00000001 +204.59,50.30085681,-3.082388036,10000,0,200.0007334,0,0,0,90.00000001 +204.6,50.30085681,-3.082360008,10000,0,200.0000644,0,0,0,90.00000001 +204.61,50.30085681,-3.082331981,10000,0,199.9996184,0,0,0,90.00000001 +204.62,50.30085681,-3.082303954,10000,0,199.9998414,0,0,0,90.00000001 +204.63,50.30085681,-3.082275926,10000,0,199.9996184,0,0,0,90.00000001 +204.64,50.30085681,-3.082247899,10000,0,199.9987264,0,0,0,90.00000001 +204.65,50.30085681,-3.082219872,10000,0,199.9987264,0,0,0,90.00000001 +204.66,50.30085681,-3.082191845,10000,0,199.9996184,0,0,0,90.00000001 +204.67,50.30085681,-3.082163817,10000,0,199.9998414,0,0,0,90.00000001 +204.68,50.30085681,-3.08213579,10000,0,199.9996184,0,0,0,90.00000001 +204.69,50.30085681,-3.082107763,10000,0,199.9998414,0,0,0,90.00000001 +204.7,50.30085681,-3.082079735,10000,0,199.9998414,0,0,0,90.00000001 +204.71,50.30085681,-3.082051708,10000,0,199.9996184,0,0,0,90.00000001 +204.72,50.30085681,-3.082023681,10000,0,200.0000644,0,0,0,90.00000001 +204.73,50.30085681,-3.081995653,10000,0,200.0007334,0,0,0,90.00000001 +204.74,50.30085681,-3.081967626,10000,0,200.0007334,0,0,0,90.00000001 +204.75,50.30085681,-3.081939598,10000,0,200.0000644,0,0,0,90.00000001 +204.76,50.30085681,-3.081911571,10000,0,199.9996184,0,0,0,90.00000001 +204.77,50.30085681,-3.081883544,10000,0,199.9998414,0,0,0,90.00000001 +204.78,50.30085681,-3.081855516,10000,0,199.9998414,0,0,0,90.00000001 +204.79,50.30085681,-3.081827489,10000,0,199.9996184,0,0,0,90.00000001 +204.8,50.30085681,-3.081799462,10000,0,200.0000644,0,0,0,90.00000001 +204.81,50.30085681,-3.081771434,10000,0,200.0007334,0,0,0,90.00000001 +204.82,50.30085681,-3.081743407,10000,0,200.0007334,0,0,0,90.00000001 +204.83,50.30085681,-3.081715379,10000,0,200.0000644,0,0,0,90.00000001 +204.84,50.30085681,-3.081687352,10000,0,199.9996184,0,0,0,90.00000001 +204.85,50.30085681,-3.081659325,10000,0,199.9998414,0,0,0,90.00000001 +204.86,50.30085681,-3.081631297,10000,0,199.9998414,0,0,0,90.00000001 +204.87,50.30085681,-3.08160327,10000,0,199.9996184,0,0,0,90.00000001 +204.88,50.30085681,-3.081575243,10000,0,200.0000644,0,0,0,90.00000001 +204.89,50.30085681,-3.081547215,10000,0,200.0007334,0,0,0,90.00000001 +204.9,50.30085681,-3.081519188,10000,0,200.0007334,0,0,0,90.00000001 +204.91,50.30085681,-3.08149116,10000,0,200.0000644,0,0,0,90.00000001 +204.92,50.30085681,-3.081463133,10000,0,199.9996184,0,0,0,90.00000001 +204.93,50.30085681,-3.081435106,10000,0,199.9998414,0,0,0,90.00000001 +204.94,50.30085681,-3.081407078,10000,0,199.9998414,0,0,0,90.00000001 +204.95,50.30085681,-3.081379051,10000,0,199.9996184,0,0,0,90.00000001 +204.96,50.30085681,-3.081351024,10000,0,200.0000644,0,0,0,90.00000001 +204.97,50.30085681,-3.081322996,10000,0,200.0007334,0,0,0,90.00000001 +204.98,50.30085681,-3.081294969,10000,0,200.0007334,0,0,0,90.00000001 +204.99,50.30085681,-3.081266941,10000,0,200.0000644,0,0,0,90.00000001 +205,50.30085681,-3.081238914,10000,0,199.9996184,0,0,0,90.00000001 +205.01,50.30085681,-3.081210887,10000,0,199.9998414,0,0,0,90.00000001 +205.02,50.30085681,-3.081182859,10000,0,199.9998414,0,0,0,90.00000001 +205.03,50.30085681,-3.081154832,10000,0,199.9996184,0,0,0,90.00000001 +205.04,50.30085681,-3.081126805,10000,0,200.0000644,0,0,0,90.00000001 +205.05,50.30085681,-3.081098777,10000,0,200.0007334,0,0,0,90.00000001 +205.06,50.30085681,-3.08107075,10000,0,200.0007334,0,0,0,90.00000001 +205.07,50.30085681,-3.081042722,10000,0,200.0000644,0,0,0,90.00000001 +205.08,50.30085681,-3.081014695,10000,0,199.9996184,0,0,0,90.00000001 +205.09,50.30085681,-3.080986668,10000,0,200.0000644,0,0,0,90.00000001 +205.1,50.30085681,-3.08095864,10000,0,200.0007334,0,0,0,90.00000001 +205.11,50.30085681,-3.080930613,10000,0,200.0007334,0,0,0,90.00000001 +205.12,50.30085681,-3.080902585,10000,0,200.0000644,0,0,0,90.00000001 +205.13,50.30085681,-3.080874558,10000,0,199.9996184,0,0,0,90.00000001 +205.14,50.30085681,-3.080846531,10000,0,199.9998414,0,0,0,90.00000001 +205.15,50.30085681,-3.080818503,10000,0,199.9998414,0,0,0,90.00000001 +205.16,50.30085681,-3.080790476,10000,0,199.9996184,0,0,0,90.00000001 +205.17,50.30085681,-3.080762449,10000,0,199.9998414,0,0,0,90.00000001 +205.18,50.30085681,-3.080734421,10000,0,199.9996184,0,0,0,90.00000001 +205.19,50.30085681,-3.080706394,10000,0,199.9987264,0,0,0,90.00000001 +205.2,50.30085681,-3.080678367,10000,0,199.9987264,0,0,0,90.00000001 +205.21,50.30085681,-3.08065034,10000,0,199.9996184,0,0,0,90.00000001 +205.22,50.30085681,-3.080622312,10000,0,199.9998414,0,0,0,90.00000001 +205.23,50.30085681,-3.080594285,10000,0,199.9996184,0,0,0,90.00000001 +205.24,50.30085681,-3.080566258,10000,0,200.0000644,0,0,0,90.00000001 +205.25,50.30085681,-3.08053823,10000,0,200.0007334,0,0,0,90.00000001 +205.26,50.30085681,-3.080510203,10000,0,200.0007334,0,0,0,90.00000001 +205.27,50.30085681,-3.080482175,10000,0,200.0000644,0,0,0,90.00000001 +205.28,50.30085681,-3.080454148,10000,0,199.9996184,0,0,0,90.00000001 +205.29,50.30085681,-3.080426121,10000,0,199.9998414,0,0,0,90.00000001 +205.3,50.30085681,-3.080398093,10000,0,199.9998414,0,0,0,90.00000001 +205.31,50.30085681,-3.080370066,10000,0,199.9996184,0,0,0,90.00000001 +205.32,50.30085681,-3.080342039,10000,0,200.0000644,0,0,0,90.00000001 +205.33,50.30085681,-3.080314011,10000,0,200.0007334,0,0,0,90.00000001 +205.34,50.30085681,-3.080285984,10000,0,200.0007334,0,0,0,90.00000001 +205.35,50.30085681,-3.080257956,10000,0,200.0000644,0,0,0,90.00000001 +205.36,50.30085681,-3.080229929,10000,0,199.9996184,0,0,0,90.00000001 +205.37,50.30085681,-3.080201902,10000,0,199.9998414,0,0,0,90.00000001 +205.38,50.30085681,-3.080173874,10000,0,199.9998414,0,0,0,90.00000001 +205.39,50.30085681,-3.080145847,10000,0,199.9996184,0,0,0,90.00000001 +205.4,50.30085681,-3.08011782,10000,0,200.0000644,0,0,0,90.00000001 +205.41,50.30085681,-3.080089792,10000,0,200.0007334,0,0,0,90.00000001 +205.42,50.30085681,-3.080061765,10000,0,200.0007334,0,0,0,90.00000001 +205.43,50.30085681,-3.080033737,10000,0,200.0000644,0,0,0,90.00000001 +205.44,50.30085681,-3.08000571,10000,0,199.9996184,0,0,0,90.00000001 +205.45,50.30085681,-3.079977683,10000,0,199.9998414,0,0,0,90.00000001 +205.46,50.30085681,-3.079949655,10000,0,199.9998414,0,0,0,90.00000001 +205.47,50.30085681,-3.079921628,10000,0,199.9996184,0,0,0,90.00000001 +205.48,50.30085681,-3.079893601,10000,0,200.0000644,0,0,0,90.00000001 +205.49,50.30085681,-3.079865573,10000,0,200.0007334,0,0,0,90.00000001 +205.5,50.30085681,-3.079837546,10000,0,200.0007334,0,0,0,90.00000001 +205.51,50.30085681,-3.079809518,10000,0,200.0000644,0,0,0,90.00000001 +205.52,50.30085681,-3.079781491,10000,0,199.9996184,0,0,0,90.00000001 +205.53,50.30085681,-3.079753464,10000,0,200.0000644,0,0,0,90.00000001 +205.54,50.30085681,-3.079725436,10000,0,200.0007334,0,0,0,90.00000001 +205.55,50.30085681,-3.079697409,10000,0,200.0007334,0,0,0,90.00000001 +205.56,50.30085681,-3.079669381,10000,0,200.0000644,0,0,0,90.00000001 +205.57,50.30085681,-3.079641354,10000,0,199.9996184,0,0,0,90.00000001 +205.58,50.30085681,-3.079613327,10000,0,199.9998414,0,0,0,90.00000001 +205.59,50.30085681,-3.079585299,10000,0,199.9998414,0,0,0,90.00000001 +205.6,50.30085681,-3.079557272,10000,0,199.9996184,0,0,0,90.00000001 +205.61,50.30085681,-3.079529245,10000,0,200.0000644,0,0,0,90.00000001 +205.62,50.30085681,-3.079501217,10000,0,200.0007334,0,0,0,90.00000001 +205.63,50.30085681,-3.07947319,10000,0,200.0007334,0,0,0,90.00000001 +205.64,50.30085681,-3.079445162,10000,0,200.0000644,0,0,0,90.00000001 +205.65,50.30085681,-3.079417135,10000,0,199.9996184,0,0,0,90.00000001 +205.66,50.30085681,-3.079389108,10000,0,199.9998414,0,0,0,90.00000001 +205.67,50.30085681,-3.07936108,10000,0,199.9998414,0,0,0,90.00000001 +205.68,50.30085681,-3.079333053,10000,0,199.9996184,0,0,0,90.00000001 +205.69,50.30085681,-3.079305026,10000,0,200.0000644,0,0,0,90.00000001 +205.7,50.30085681,-3.079276998,10000,0,200.0007334,0,0,0,90.00000001 +205.71,50.30085681,-3.079248971,10000,0,200.0007334,0,0,0,90.00000001 +205.72,50.30085681,-3.079220943,10000,0,199.9998414,0,0,0,90.00000001 +205.73,50.30085681,-3.079192916,10000,0,199.9985034,0,0,0,90.00000001 +205.74,50.30085681,-3.079164889,10000,0,199.9978344,0,0,0,90.00000001 +205.75,50.30085681,-3.079136862,10000,0,199.9985034,0,0,0,90.00000001 +205.76,50.30085681,-3.079108835,10000,0,199.9998414,0,0,0,90.00000001 +205.77,50.30085681,-3.079080807,10000,0,200.0007334,0,0,0,90.00000001 +205.78,50.30085681,-3.07905278,10000,0,200.0007334,0,0,0,90.00000001 +205.79,50.30085681,-3.079024752,10000,0,200.0000644,0,0,0,90.00000001 +205.8,50.30085681,-3.078996725,10000,0,199.9996184,0,0,0,90.00000001 +205.81,50.30085681,-3.078968698,10000,0,199.9998414,0,0,0,90.00000001 +205.82,50.30085681,-3.07894067,10000,0,199.9998414,0,0,0,90.00000001 +205.83,50.30085681,-3.078912643,10000,0,199.9996184,0,0,0,90.00000001 +205.84,50.30085681,-3.078884616,10000,0,200.0000644,0,0,0,90.00000001 +205.85,50.30085681,-3.078856588,10000,0,200.0007334,0,0,0,90.00000001 +205.86,50.30085681,-3.078828561,10000,0,200.0007334,0,0,0,90.00000001 +205.87,50.30085681,-3.078800533,10000,0,200.0000644,0,0,0,90.00000001 +205.88,50.30085681,-3.078772506,10000,0,199.9996184,0,0,0,90.00000001 +205.89,50.30085681,-3.078744479,10000,0,199.9998414,0,0,0,90.00000001 +205.9,50.30085681,-3.078716451,10000,0,199.9998414,0,0,0,90.00000001 +205.91,50.30085681,-3.078688424,10000,0,199.9996184,0,0,0,90.00000001 +205.92,50.30085681,-3.078660397,10000,0,200.0000644,0,0,0,90.00000001 +205.93,50.30085681,-3.078632369,10000,0,200.0007334,0,0,0,90.00000001 +205.94,50.30085681,-3.078604342,10000,0,200.0007334,0,0,0,90.00000001 +205.95,50.30085681,-3.078576314,10000,0,200.0000644,0,0,0,90.00000001 +205.96,50.30085681,-3.078548287,10000,0,199.9996184,0,0,0,90.00000001 +205.97,50.30085681,-3.07852026,10000,0,199.9998414,0,0,0,90.00000001 +205.98,50.30085681,-3.078492232,10000,0,199.9998414,0,0,0,90.00000001 +205.99,50.30085681,-3.078464205,10000,0,199.9996184,0,0,0,90.00000001 +206,50.30085681,-3.078436178,10000,0,200.0000644,0,0,0,90.00000001 +206.01,50.30085681,-3.07840815,10000,0,200.0007334,0,0,0,90.00000001 +206.02,50.30085681,-3.078380123,10000,0,200.0007334,0,0,0,90.00000001 +206.03,50.30085681,-3.078352095,10000,0,200.0000644,0,0,0,90.00000001 +206.04,50.30085681,-3.078324068,10000,0,199.9996184,0,0,0,90.00000001 +206.05,50.30085681,-3.078296041,10000,0,200.0000644,0,0,0,90.00000001 +206.06,50.30085681,-3.078268013,10000,0,200.0007334,0,0,0,90.00000001 +206.07,50.30085681,-3.078239986,10000,0,200.0007334,0,0,0,90.00000001 +206.08,50.30085681,-3.078211958,10000,0,200.0000644,0,0,0,90.00000001 +206.09,50.30085681,-3.078183931,10000,0,199.9996184,0,0,0,90.00000001 +206.1,50.30085681,-3.078155904,10000,0,199.9998414,0,0,0,90.00000001 +206.11,50.30085681,-3.078127876,10000,0,199.9998414,0,0,0,90.00000001 +206.12,50.30085681,-3.078099849,10000,0,199.9996184,0,0,0,90.00000001 +206.13,50.30085681,-3.078071822,10000,0,200.0000644,0,0,0,90.00000001 +206.14,50.30085681,-3.078043794,10000,0,200.0007334,0,0,0,90.00000001 +206.15,50.30085681,-3.078015767,10000,0,200.0007334,0,0,0,90.00000001 +206.16,50.30085681,-3.077987739,10000,0,200.0000644,0,0,0,90.00000001 +206.17,50.30085681,-3.077959712,10000,0,199.9996184,0,0,0,90.00000001 +206.18,50.30085681,-3.077931685,10000,0,199.9998414,0,0,0,90.00000001 +206.19,50.30085681,-3.077903657,10000,0,199.9998414,0,0,0,90.00000001 +206.2,50.30085681,-3.07787563,10000,0,199.9996184,0,0,0,90.00000001 +206.21,50.30085681,-3.077847603,10000,0,200.0000644,0,0,0,90.00000001 +206.22,50.30085681,-3.077819575,10000,0,200.0007334,0,0,0,90.00000001 +206.23,50.30085681,-3.077791548,10000,0,200.0007334,0,0,0,90.00000001 +206.24,50.30085681,-3.07776352,10000,0,200.0000644,0,0,0,90.00000001 +206.25,50.30085681,-3.077735493,10000,0,199.9996184,0,0,0,90.00000001 +206.26,50.30085681,-3.077707466,10000,0,199.9998414,0,0,0,90.00000001 +206.27,50.30085681,-3.077679438,10000,0,199.9996184,0,0,0,90.00000001 +206.28,50.30085681,-3.077651411,10000,0,199.9987264,0,0,0,90.00000001 +206.29,50.30085681,-3.077623384,10000,0,199.9987264,0,0,0,90.00000001 +206.3,50.30085681,-3.077595357,10000,0,199.9996184,0,0,0,90.00000001 +206.31,50.30085681,-3.077567329,10000,0,199.9998414,0,0,0,90.00000001 +206.32,50.30085681,-3.077539302,10000,0,199.9996184,0,0,0,90.00000001 +206.33,50.30085681,-3.077511275,10000,0,199.9998414,0,0,0,90.00000001 +206.34,50.30085681,-3.077483247,10000,0,199.9998414,0,0,0,90.00000001 +206.35,50.30085681,-3.07745522,10000,0,199.9996184,0,0,0,90.00000001 +206.36,50.30085681,-3.077427193,10000,0,200.0000644,0,0,0,90.00000001 +206.37,50.30085681,-3.077399165,10000,0,200.0007334,0,0,0,90.00000001 +206.38,50.30085681,-3.077371138,10000,0,200.0007334,0,0,0,90.00000001 +206.39,50.30085681,-3.07734311,10000,0,200.0000644,0,0,0,90.00000001 +206.4,50.30085681,-3.077315083,10000,0,199.9996184,0,0,0,90.00000001 +206.41,50.30085681,-3.077287056,10000,0,199.9998414,0,0,0,90.00000001 +206.42,50.30085681,-3.077259028,10000,0,199.9998414,0,0,0,90.00000001 +206.43,50.30085681,-3.077231001,10000,0,199.9996184,0,0,0,90.00000001 +206.44,50.30085681,-3.077202974,10000,0,200.0000644,0,0,0,90.00000001 +206.45,50.30085681,-3.077174946,10000,0,200.0007334,0,0,0,90.00000001 +206.46,50.30085681,-3.077146919,10000,0,200.0007334,0,0,0,90.00000001 +206.47,50.30085681,-3.077118891,10000,0,200.0000644,0,0,0,90.00000001 +206.48,50.30085681,-3.077090864,10000,0,199.9996184,0,0,0,90.00000001 +206.49,50.30085681,-3.077062837,10000,0,199.9998414,0,0,0,90.00000001 +206.5,50.30085681,-3.077034809,10000,0,199.9998414,0,0,0,90.00000001 +206.51,50.30085681,-3.077006782,10000,0,199.9996184,0,0,0,90.00000001 +206.52,50.30085681,-3.076978755,10000,0,200.0000644,0,0,0,90.00000001 +206.53,50.30085681,-3.076950727,10000,0,200.0007334,0,0,0,90.00000001 +206.54,50.30085681,-3.0769227,10000,0,200.0007334,0,0,0,90.00000001 +206.55,50.30085681,-3.076894672,10000,0,200.0000644,0,0,0,90.00000001 +206.56,50.30085681,-3.076866645,10000,0,199.9996184,0,0,0,90.00000001 +206.57,50.30085681,-3.076838618,10000,0,200.0000644,0,0,0,90.00000001 +206.58,50.30085681,-3.07681059,10000,0,200.0007334,0,0,0,90.00000001 +206.59,50.30085681,-3.076782563,10000,0,200.0007334,0,0,0,90.00000001 +206.6,50.30085681,-3.076754535,10000,0,200.0000644,0,0,0,90.00000001 +206.61,50.30085681,-3.076726508,10000,0,199.9996184,0,0,0,90.00000001 +206.62,50.30085681,-3.076698481,10000,0,199.9998414,0,0,0,90.00000001 +206.63,50.30085681,-3.076670453,10000,0,199.9998414,0,0,0,90.00000001 +206.64,50.30085681,-3.076642426,10000,0,199.9996184,0,0,0,90.00000001 +206.65,50.30085681,-3.076614399,10000,0,200.0000644,0,0,0,90.00000001 +206.66,50.30085681,-3.076586371,10000,0,200.0007334,0,0,0,90.00000001 +206.67,50.30085681,-3.076558344,10000,0,200.0007334,0,0,0,90.00000001 +206.68,50.30085681,-3.076530316,10000,0,200.0000644,0,0,0,90.00000001 +206.69,50.30085681,-3.076502289,10000,0,199.9996184,0,0,0,90.00000001 +206.7,50.30085681,-3.076474262,10000,0,199.9998414,0,0,0,90.00000001 +206.71,50.30085681,-3.076446234,10000,0,199.9998414,0,0,0,90.00000001 +206.72,50.30085681,-3.076418207,10000,0,199.9996184,0,0,0,90.00000001 +206.73,50.30085681,-3.07639018,10000,0,200.0000644,0,0,0,90.00000001 +206.74,50.30085681,-3.076362152,10000,0,200.0007334,0,0,0,90.00000001 +206.75,50.30085681,-3.076334125,10000,0,200.0007334,0,0,0,90.00000001 +206.76,50.30085681,-3.076306097,10000,0,200.0000644,0,0,0,90.00000001 +206.77,50.30085681,-3.07627807,10000,0,199.9996184,0,0,0,90.00000001 +206.78,50.30085681,-3.076250043,10000,0,199.9998414,0,0,0,90.00000001 +206.79,50.30085681,-3.076222015,10000,0,199.9998414,0,0,0,90.00000001 +206.8,50.30085681,-3.076193988,10000,0,199.9996184,0,0,0,90.00000001 +206.81,50.30085681,-3.076165961,10000,0,199.9998414,0,0,0,90.00000001 +206.82,50.30085681,-3.076137933,10000,0,199.9996184,0,0,0,90.00000001 +206.83,50.30085681,-3.076109906,10000,0,199.9987264,0,0,0,90.00000001 +206.84,50.30085681,-3.076081879,10000,0,199.9987264,0,0,0,90.00000001 +206.85,50.30085681,-3.076053852,10000,0,199.9996184,0,0,0,90.00000001 +206.86,50.30085681,-3.076025824,10000,0,199.9998414,0,0,0,90.00000001 +206.87,50.30085681,-3.075997797,10000,0,199.9996184,0,0,0,90.00000001 +206.88,50.30085681,-3.07596977,10000,0,200.0000644,0,0,0,90.00000001 +206.89,50.30085681,-3.075941742,10000,0,200.0007334,0,0,0,90.00000001 +206.9,50.30085681,-3.075913715,10000,0,200.0007334,0,0,0,90.00000001 +206.91,50.30085681,-3.075885687,10000,0,200.0000644,0,0,0,90.00000001 +206.92,50.30085681,-3.07585766,10000,0,199.9996184,0,0,0,90.00000001 +206.93,50.30085681,-3.075829633,10000,0,199.9998414,0,0,0,90.00000001 +206.94,50.30085681,-3.075801605,10000,0,199.9998414,0,0,0,90.00000001 +206.95,50.30085681,-3.075773578,10000,0,199.9996184,0,0,0,90.00000001 +206.96,50.30085681,-3.075745551,10000,0,200.0000644,0,0,0,90.00000001 +206.97,50.30085681,-3.075717523,10000,0,200.0007334,0,0,0,90.00000001 +206.98,50.30085681,-3.075689496,10000,0,200.0007334,0,0,0,90.00000001 +206.99,50.30085681,-3.075661468,10000,0,200.0000644,0,0,0,90.00000001 +207,50.30085681,-3.075633441,10000,0,199.9996184,0,0,0,90.00000001 +207.01,50.30085681,-3.075605414,10000,0,199.9998414,0,0,0,90.00000001 +207.02,50.30085681,-3.075577386,10000,0,199.9998414,0,0,0,90.00000001 +207.03,50.30085681,-3.075549359,10000,0,199.9996184,0,0,0,90.00000001 +207.04,50.30085681,-3.075521332,10000,0,200.0000644,0,0,0,90.00000001 +207.05,50.30085681,-3.075493304,10000,0,200.0007334,0,0,0,90.00000001 +207.06,50.30085681,-3.075465277,10000,0,200.0007334,0,0,0,90.00000001 +207.07,50.30085681,-3.075437249,10000,0,200.0000644,0,0,0,90.00000001 +207.08,50.30085681,-3.075409222,10000,0,199.9996184,0,0,0,90.00000001 +207.09,50.30085681,-3.075381195,10000,0,200.0000644,0,0,0,90.00000001 +207.1,50.30085681,-3.075353167,10000,0,200.0007334,0,0,0,90.00000001 +207.11,50.30085681,-3.07532514,10000,0,200.0007334,0,0,0,90.00000001 +207.12,50.30085681,-3.075297112,10000,0,200.0000644,0,0,0,90.00000001 +207.13,50.30085681,-3.075269085,10000,0,199.9996184,0,0,0,90.00000001 +207.14,50.30085681,-3.075241058,10000,0,199.9998414,0,0,0,90.00000001 +207.15,50.30085681,-3.07521303,10000,0,199.9998414,0,0,0,90.00000001 +207.16,50.30085681,-3.075185003,10000,0,199.9996184,0,0,0,90.00000001 +207.17,50.30085681,-3.075156976,10000,0,200.0000644,0,0,0,90.00000001 +207.18,50.30085681,-3.075128948,10000,0,200.0007334,0,0,0,90.00000001 +207.19,50.30085681,-3.075100921,10000,0,200.0007334,0,0,0,90.00000001 +207.2,50.30085681,-3.075072893,10000,0,200.0000644,0,0,0,90.00000001 +207.21,50.30085681,-3.075044866,10000,0,199.9996184,0,0,0,90.00000001 +207.22,50.30085681,-3.075016839,10000,0,199.9998414,0,0,0,90.00000001 +207.23,50.30085681,-3.074988811,10000,0,199.9998414,0,0,0,90.00000001 +207.24,50.30085681,-3.074960784,10000,0,199.9996184,0,0,0,90.00000001 +207.25,50.30085681,-3.074932757,10000,0,200.0000644,0,0,0,90.00000001 +207.26,50.30085681,-3.074904729,10000,0,200.0007334,0,0,0,90.00000001 +207.27,50.30085681,-3.074876702,10000,0,200.0007334,0,0,0,90.00000001 +207.28,50.30085681,-3.074848674,10000,0,200.0000644,0,0,0,90.00000001 +207.29,50.30085681,-3.074820647,10000,0,199.9996184,0,0,0,90.00000001 +207.3,50.30085681,-3.07479262,10000,0,199.9998414,0,0,0,90.00000001 +207.31,50.30085681,-3.074764592,10000,0,199.9998414,0,0,0,90.00000001 +207.32,50.30085681,-3.074736565,10000,0,199.9996184,0,0,0,90.00000001 +207.33,50.30085681,-3.074708538,10000,0,200.0000644,0,0,0,90.00000001 +207.34,50.30085681,-3.07468051,10000,0,200.0007334,0,0,0,90.00000001 +207.35,50.30085681,-3.074652483,10000,0,200.0007334,0,0,0,90.00000001 +207.36,50.30085681,-3.074624455,10000,0,199.9998414,0,0,0,90.00000001 +207.37,50.30085681,-3.074596428,10000,0,199.9985034,0,0,0,90.00000001 +207.38,50.30085681,-3.074568401,10000,0,199.9978344,0,0,0,90.00000001 +207.39,50.30085681,-3.074540374,10000,0,199.9985034,0,0,0,90.00000001 +207.4,50.30085681,-3.074512347,10000,0,199.9998414,0,0,0,90.00000001 +207.41,50.30085681,-3.074484319,10000,0,200.0007334,0,0,0,90.00000001 +207.42,50.30085681,-3.074456292,10000,0,200.0007334,0,0,0,90.00000001 +207.43,50.30085681,-3.074428264,10000,0,200.0000644,0,0,0,90.00000001 +207.44,50.30085681,-3.074400237,10000,0,199.9996184,0,0,0,90.00000001 +207.45,50.30085681,-3.07437221,10000,0,199.9998414,0,0,0,90.00000001 +207.46,50.30085681,-3.074344182,10000,0,199.9998414,0,0,0,90.00000001 +207.47,50.30085681,-3.074316155,10000,0,199.9996184,0,0,0,90.00000001 +207.48,50.30085681,-3.074288128,10000,0,200.0000644,0,0,0,90.00000001 +207.49,50.30085681,-3.0742601,10000,0,200.0007334,0,0,0,90.00000001 +207.5,50.30085681,-3.074232073,10000,0,200.0007334,0,0,0,90.00000001 +207.51,50.30085681,-3.074204045,10000,0,200.0000644,0,0,0,90.00000001 +207.52,50.30085681,-3.074176018,10000,0,199.9996184,0,0,0,90.00000001 +207.53,50.30085681,-3.074147991,10000,0,200.0000644,0,0,0,90.00000001 +207.54,50.30085681,-3.074119963,10000,0,200.0007334,0,0,0,90.00000001 +207.55,50.30085681,-3.074091936,10000,0,200.0007334,0,0,0,90.00000001 +207.56,50.30085681,-3.074063908,10000,0,200.0000644,0,0,0,90.00000001 +207.57,50.30085681,-3.074035881,10000,0,199.9996184,0,0,0,90.00000001 +207.58,50.30085681,-3.074007854,10000,0,199.9998414,0,0,0,90.00000001 +207.59,50.30085681,-3.073979826,10000,0,199.9998414,0,0,0,90.00000001 +207.6,50.30085681,-3.073951799,10000,0,199.9996184,0,0,0,90.00000001 +207.61,50.30085681,-3.073923772,10000,0,200.0000644,0,0,0,90.00000001 +207.62,50.30085681,-3.073895744,10000,0,200.0007334,0,0,0,90.00000001 +207.63,50.30085681,-3.073867717,10000,0,200.0007334,0,0,0,90.00000001 +207.64,50.30085681,-3.073839689,10000,0,200.0000644,0,0,0,90.00000001 +207.65,50.30085681,-3.073811662,10000,0,199.9996184,0,0,0,90.00000001 +207.66,50.30085681,-3.073783635,10000,0,199.9998414,0,0,0,90.00000001 +207.67,50.30085681,-3.073755607,10000,0,199.9998414,0,0,0,90.00000001 +207.68,50.30085681,-3.07372758,10000,0,199.9996184,0,0,0,90.00000001 +207.69,50.30085681,-3.073699553,10000,0,200.0000644,0,0,0,90.00000001 +207.7,50.30085681,-3.073671525,10000,0,200.0007334,0,0,0,90.00000001 +207.71,50.30085681,-3.073643498,10000,0,200.0007334,0,0,0,90.00000001 +207.72,50.30085681,-3.07361547,10000,0,200.0000644,0,0,0,90.00000001 +207.73,50.30085681,-3.073587443,10000,0,199.9996184,0,0,0,90.00000001 +207.74,50.30085681,-3.073559416,10000,0,199.9998414,0,0,0,90.00000001 +207.75,50.30085681,-3.073531388,10000,0,199.9998414,0,0,0,90.00000001 +207.76,50.30085681,-3.073503361,10000,0,199.9996184,0,0,0,90.00000001 +207.77,50.30085681,-3.073475334,10000,0,200.0000644,0,0,0,90.00000001 +207.78,50.30085681,-3.073447306,10000,0,200.0007334,0,0,0,90.00000001 +207.79,50.30085681,-3.073419279,10000,0,200.0007334,0,0,0,90.00000001 +207.8,50.30085681,-3.073391251,10000,0,200.0000644,0,0,0,90.00000001 +207.81,50.30085681,-3.073363224,10000,0,199.9996184,0,0,0,90.00000001 +207.82,50.30085681,-3.073335197,10000,0,199.9998414,0,0,0,90.00000001 +207.83,50.30085681,-3.073307169,10000,0,199.9998414,0,0,0,90.00000001 +207.84,50.30085681,-3.073279142,10000,0,199.9996184,0,0,0,90.00000001 +207.85,50.30085681,-3.073251115,10000,0,200.0000644,0,0,0,90.00000001 +207.86,50.30085681,-3.073223087,10000,0,200.0007334,0,0,0,90.00000001 +207.87,50.30085681,-3.07319506,10000,0,200.0007334,0,0,0,90.00000001 +207.88,50.30085681,-3.073167032,10000,0,200.0000644,0,0,0,90.00000001 +207.89,50.30085681,-3.073139005,10000,0,199.9996184,0,0,0,90.00000001 +207.9,50.30085681,-3.073110978,10000,0,199.9998414,0,0,0,90.00000001 +207.91,50.30085681,-3.07308295,10000,0,199.9996184,0,0,0,90.00000001 +207.92,50.30085681,-3.073054923,10000,0,199.9987264,0,0,0,90.00000001 +207.93,50.30085681,-3.073026896,10000,0,199.9987264,0,0,0,90.00000001 +207.94,50.30085681,-3.072998869,10000,0,199.9996184,0,0,0,90.00000001 +207.95,50.30085681,-3.072970841,10000,0,199.9998414,0,0,0,90.00000001 +207.96,50.30085681,-3.072942814,10000,0,199.9996184,0,0,0,90.00000001 +207.97,50.30085681,-3.072914787,10000,0,199.9998414,0,0,0,90.00000001 +207.98,50.30085681,-3.072886759,10000,0,199.9998414,0,0,0,90.00000001 +207.99,50.30085681,-3.072858732,10000,0,199.9996184,0,0,0,90.00000001 +208,50.30085681,-3.072830705,10000,0,200.0000644,0,0,0,90.00000001 +208.01,50.30085681,-3.072802677,10000,0,200.0007334,0,0,0,90.00000001 +208.02,50.30085681,-3.07277465,10000,0,200.0007334,0,0,0,90.00000001 +208.03,50.30085681,-3.072746622,10000,0,200.0000644,0,0,0,90.00000001 +208.04,50.30085681,-3.072718595,10000,0,199.9996184,0,0,0,90.00000001 +208.05,50.30085681,-3.072690568,10000,0,200.0000644,0,0,0,90.00000001 +208.06,50.30085681,-3.07266254,10000,0,200.0007334,0,0,0,90.00000001 +208.07,50.30085681,-3.072634513,10000,0,200.0007334,0,0,0,90.00000001 +208.08,50.30085681,-3.072606485,10000,0,200.0000644,0,0,0,90.00000001 +208.09,50.30085681,-3.072578458,10000,0,199.9996184,0,0,0,90.00000001 +208.1,50.30085681,-3.072550431,10000,0,199.9998414,0,0,0,90.00000001 +208.11,50.30085681,-3.072522403,10000,0,199.9998414,0,0,0,90.00000001 +208.12,50.30085681,-3.072494376,10000,0,199.9996184,0,0,0,90.00000001 +208.13,50.30085681,-3.072466349,10000,0,200.0000644,0,0,0,90.00000001 +208.14,50.30085681,-3.072438321,10000,0,200.0007334,0,0,0,90.00000001 +208.15,50.30085681,-3.072410294,10000,0,200.0007334,0,0,0,90.00000001 +208.16,50.30085681,-3.072382266,10000,0,200.0000644,0,0,0,90.00000001 +208.17,50.30085681,-3.072354239,10000,0,199.9996184,0,0,0,90.00000001 +208.18,50.30085681,-3.072326212,10000,0,199.9998414,0,0,0,90.00000001 +208.19,50.30085681,-3.072298184,10000,0,199.9998414,0,0,0,90.00000001 +208.2,50.30085681,-3.072270157,10000,0,199.9996184,0,0,0,90.00000001 +208.21,50.30085681,-3.07224213,10000,0,200.0000644,0,0,0,90.00000001 +208.22,50.30085681,-3.072214102,10000,0,200.0007334,0,0,0,90.00000001 +208.23,50.30085681,-3.072186075,10000,0,200.0007334,0,0,0,90.00000001 +208.24,50.30085681,-3.072158047,10000,0,200.0000644,0,0,0,90.00000001 +208.25,50.30085681,-3.07213002,10000,0,199.9996184,0,0,0,90.00000001 +208.26,50.30085681,-3.072101993,10000,0,199.9998414,0,0,0,90.00000001 +208.27,50.30085681,-3.072073965,10000,0,199.9998414,0,0,0,90.00000001 +208.28,50.30085681,-3.072045938,10000,0,199.9996184,0,0,0,90.00000001 +208.29,50.30085681,-3.072017911,10000,0,200.0000644,0,0,0,90.00000001 +208.3,50.30085681,-3.071989883,10000,0,200.0007334,0,0,0,90.00000001 +208.31,50.30085681,-3.071961856,10000,0,200.0007334,0,0,0,90.00000001 +208.32,50.30085681,-3.071933828,10000,0,200.0000644,0,0,0,90.00000001 +208.33,50.30085681,-3.071905801,10000,0,199.9996184,0,0,0,90.00000001 +208.34,50.30085681,-3.071877774,10000,0,199.9998414,0,0,0,90.00000001 +208.35,50.30085681,-3.071849746,10000,0,199.9998414,0,0,0,90.00000001 +208.36,50.30085681,-3.071821719,10000,0,199.9996184,0,0,0,90.00000001 +208.37,50.30085681,-3.071793692,10000,0,200.0000644,0,0,0,90.00000001 +208.38,50.30085681,-3.071765664,10000,0,200.0007334,0,0,0,90.00000001 +208.39,50.30085681,-3.071737637,10000,0,200.0007334,0,0,0,90.00000001 +208.4,50.30085681,-3.071709609,10000,0,200.0000644,0,0,0,90.00000001 +208.41,50.30085681,-3.071681582,10000,0,199.9996184,0,0,0,90.00000001 +208.42,50.30085681,-3.071653555,10000,0,199.9998414,0,0,0,90.00000001 +208.43,50.30085681,-3.071625527,10000,0,199.9998414,0,0,0,90.00000001 +208.44,50.30085681,-3.0715975,10000,0,199.9996184,0,0,0,90.00000001 +208.45,50.30085681,-3.071569473,10000,0,199.9998414,0,0,0,90.00000001 +208.46,50.30085681,-3.071541445,10000,0,199.9996184,0,0,0,90.00000001 +208.47,50.30085681,-3.071513418,10000,0,199.9987264,0,0,0,90.00000001 +208.48,50.30085681,-3.071485391,10000,0,199.9987264,0,0,0,90.00000001 +208.49,50.30085681,-3.071457364,10000,0,199.9996184,0,0,0,90.00000001 +208.5,50.30085681,-3.071429336,10000,0,199.9998414,0,0,0,90.00000001 +208.51,50.30085681,-3.071401309,10000,0,199.9996184,0,0,0,90.00000001 +208.52,50.30085681,-3.071373282,10000,0,200.0000644,0,0,0,90.00000001 +208.53,50.30085681,-3.071345254,10000,0,200.0007334,0,0,0,90.00000001 +208.54,50.30085681,-3.071317227,10000,0,200.0007334,0,0,0,90.00000001 +208.55,50.30085681,-3.071289199,10000,0,200.0000644,0,0,0,90.00000001 +208.56,50.30085681,-3.071261172,10000,0,199.9996184,0,0,0,90.00000001 +208.57,50.30085681,-3.071233145,10000,9.37E-12,200.0000644,-0.0003125,0,0,90.00000001 +208.58,50.30085681,-3.071205117,10000,9.37E-12,200.0007334,-0.0028125,0,0,90.00000001 +208.59,50.30085681,-3.07117709,10000,-3.75E-11,200.0007334,-0.01125,0,0.001170954,90.00000001 +208.6,50.30085681,-3.071149062,10000.0001,-8.59E-11,200.0000644,-0.0278125,0,0.007025551,90.00000001 +208.61,50.30085681,-3.071121035,10000.0005,-9.22E-11,199.9996184,-0.0503125,0,0.01405116,90.00000001 +208.62,50.30085681,-3.071093008,10000.0011,-8.28E-11,199.9998415,-0.0746875,0,0.021076711,90.00000001 +208.63,50.30085681,-3.07106498,10000.002,-5.16E-11,199.9998415,-0.0984375,0,0.028102319,90.00000001 +208.64,50.30085681,-3.071036953,10000.0031,-6.25E-12,199.9996185,-0.121875,0,0.035127871,90.00000001 +208.65,50.30085681,-3.071008926,10000.0044,-4.69E-12,200.0000646,-0.146875,0,0.042153479,90.00000001 +208.66,50.30085681,-3.070980898,10000.006,-3.59E-11,200.0007336,-0.173125,0,0.04917903,90.00000001 +208.67,50.30085681,-3.070952871,10000.0079,-2.66E-11,200.0007337,-0.198125,0,0.056204639,90.00000001 +208.68,50.30085681,-3.070924843,10000.01,2.66E-11,200.0000647,-0.2215625,0,0.06323019,90.00000001 +208.69,50.30085681,-3.070896816,10000.0123,5.63E-11,199.9996188,-0.245,0,0.070255798,90.00000001 +208.7,50.30085681,-3.070868789,10000.0149,1.88E-11,199.9998419,-0.26875,0,0.07728135,90.00000001 +208.71,50.30085681,-3.070840761,10000.0177,-7.34E-11,199.999842,-0.293125,0,0.084306958,90.00000001 +208.72,50.30085681,-3.070812734,10000.0207,-1.52E-10,199.9996191,-0.3184375,0,0.091332509,90.00000001 +208.73,50.30085681,-3.070784707,10000.0241,-1.42E-10,199.9998422,-0.3434375,0,0.098358118,90.00000001 +208.74,50.30085681,-3.070756679,10000.0276,-4.22E-11,199.9996193,-0.3678125,0,0.105383669,90.00000001 +208.75,50.30085681,-3.070728652,10000.0314,9.06E-11,199.9987274,-0.3921875,0,0.112409277,90.00000001 +208.76,50.30085681,-3.070700625,10000.0355,1.83E-10,199.9987275,-0.4165625,0,0.119434829,90.00000001 +208.77,50.30085681,-3.070672598,10000.0397,1.77E-10,199.9996197,-0.4415625,0,0.126460437,90.00000001 +208.78,50.30085681,-3.07064457,10000.0443,8.28E-11,199.9998428,-0.466875,0,0.133485988,90.00000001 +208.79,50.30085681,-3.070616543,10000.0491,-1.72E-11,199.99962,-0.49125,0,0.140511597,90.00000001 +208.8,50.30085681,-3.070588516,10000.0541,-5.63E-11,199.9998431,-0.515,0,0.147537148,90.00000001 +208.81,50.30085681,-3.070560488,10000.0594,-1.72E-11,199.9996203,-0.53875,0,0.154562756,90.00000001 +208.82,50.30085681,-3.070532461,10000.0649,8.28E-11,199.9987285,-0.563125,0,0.161588308,90.00000001 +208.83,50.30085681,-3.070504434,10000.0706,1.77E-10,199.9987286,-0.5884375,0,0.168613916,90.00000001 +208.84,50.30085681,-3.070476407,10000.0767,1.83E-10,199.9996208,-0.6134375,0,0.175639467,90.00000001 +208.85,50.30085681,-3.070448379,10000.0829,9.06E-11,199.999621,-0.6378125,0,0.182665076,90.00000001 +208.86,50.30085681,-3.070420352,10000.0894,-4.22E-11,199.9985062,-0.6621875,0,0.189690627,90.00000001 +208.87,50.30085681,-3.070392325,10000.0962,-1.42E-10,199.9978375,-0.6865625,0,0.196716235,90.00000001 +208.88,50.30085681,-3.070364298,10000.1031,-1.52E-10,199.9985067,-0.7115625,0,0.203741787,90.00000001 +208.89,50.30085681,-3.070336271,10000.1104,-7.34E-11,199.9996219,-0.736875,0,0.210767395,90.00000001 +208.9,50.30085681,-3.070308243,10000.1179,1.88E-11,199.9996221,-0.76125,0,0.217792946,90.00000001 +208.91,50.30085681,-3.070280216,10000.1256,5.63E-11,199.9985074,-0.785,0,0.224818555,90.00000001 +208.92,50.30085681,-3.070252189,10000.1336,2.66E-11,199.9976156,-0.8084375,0,0.231844106,90.00000001 +208.93,50.30085681,-3.070224162,10000.1418,-2.66E-11,199.9973929,-0.831875,0,0.238869714,90.00000001 +208.94,50.30085681,-3.070196135,10000.1502,-3.59E-11,199.9973932,-0.856875,0,0.245895266,90.00000001 +208.95,50.30085681,-3.070168108,10000.1589,-3.12E-12,199.9973934,-0.883125,0,0.252920874,90.00000001 +208.96,50.30085681,-3.070140081,10000.1679,3.13E-12,199.9976167,-0.908125,0,0.259946425,90.00000001 +208.97,50.30085681,-3.070112054,10000.1771,-2.81E-11,199.998286,-0.9315625,0,0.266972034,90.00000001 +208.98,50.30085681,-3.070084027,10000.1865,-5.16E-11,199.9985093,-0.9553125,0,0.273997585,90.00000001 +208.99,50.30085681,-3.070055999,10000.1962,-5.94E-11,199.9976176,-0.98,0,0.281023193,90.00000001 +209,50.30085681,-3.070027973,10000.2061,-6.72E-11,199.9971719,-1.005,0,0.288048745,90.00000001 +209.01,50.30085681,-3.069999946,10000.2163,-7.19E-11,199.9976182,-1.03,0,0.295074353,90.00000001 +209.02,50.30085681,-3.069971918,10000.2267,-6.72E-11,199.9971725,-1.055,0,0.302099904,90.00000001 +209.03,50.30085681,-3.069943892,10000.2374,-5.94E-11,199.9962809,-1.08,0,0.309125513,90.00000001 +209.04,50.30085681,-3.069915865,10000.2483,-5.16E-11,199.9965042,-1.1046875,0,0.316151064,90.00000001 +209.05,50.30085681,-3.069887838,10000.2595,-2.66E-11,199.9971736,-1.1284375,0,0.323176672,90.00000001 +209.06,50.30085681,-3.069859811,10000.2709,1.25E-11,199.9973969,-1.151875,0,0.330202224,90.00000001 +209.07,50.30085681,-3.069831784,10000.2825,2.03E-11,199.9973973,-1.176875,0,0.337227832,90.00000001 +209.08,50.30085681,-3.069803757,10000.2944,-4.69E-12,199.9971747,-1.203125,0,0.344253383,90.00000001 +209.09,50.30085681,-3.06977573,10000.3066,-3.13E-12,199.9962831,-1.228125,0,0.351278992,90.00000001 +209.1,50.30085681,-3.069747703,10000.319,3.59E-11,199.9951685,-1.2515625,0,0.358304543,90.00000001 +209.11,50.30085681,-3.069719677,10000.3316,5.78E-11,199.9951689,-1.275,0,0.365330151,90.00000001 +209.12,50.30085681,-3.06969165,10000.3445,1.72E-11,199.9962842,-1.29875,0,0.372355703,90.00000001 +209.13,50.30085681,-3.069663623,10000.3576,-8.28E-11,199.9969536,-1.323125,0,0.379381311,90.00000001 +209.14,50.30085681,-3.069635596,10000.3709,-1.77E-10,199.9962851,-1.3484375,0,0.386406862,90.00000001 +209.15,50.30085681,-3.069607569,10000.3846,-1.83E-10,199.9949475,-1.3734375,0,0.393432471,90.00000001 +209.16,50.30085681,-3.069579543,10000.3984,-9.06E-11,199.994056,-1.3978125,0,0.400458022,90.00000001 +209.17,50.30085681,-3.069551516,10000.4125,4.22E-11,199.9938334,-1.4221875,0,0.40748363,90.00000001 +209.18,50.30085681,-3.06952349,10000.4269,1.42E-10,199.9938339,-1.4465625,0,0.414509182,90.00000001 +209.19,50.30085681,-3.069495463,10000.4414,1.50E-10,199.9940573,-1.4715625,0,0.42153479,90.00000001 +209.2,50.30085681,-3.069467437,10000.4563,6.41E-11,199.9947268,-1.496875,0,0.428560341,90.00000001 +209.21,50.30085681,-3.06943941,10000.4714,-4.22E-11,199.9951732,-1.52125,0,0.43558595,90.00000001 +209.22,50.30085681,-3.069411383,10000.4867,-8.75E-11,199.9947277,-1.545,0,0.442611501,90.00000001 +209.23,50.30085681,-3.069383357,10000.5023,-4.22E-11,199.9940592,-1.56875,0,0.44963711,90.00000001 +209.24,50.30085681,-3.06935533,10000.5181,6.41E-11,199.9938367,-1.593125,0,0.456662661,90.00000001 +209.25,50.30085681,-3.069327304,10000.5341,1.50E-10,199.9938372,-1.6184375,0,0.463688269,90.00000001 +209.26,50.30085681,-3.069299277,10000.5505,1.42E-10,199.9938377,-1.6434375,0,0.47071382,90.00000001 +209.27,50.30085681,-3.069271251,10000.567,4.38E-11,199.9936152,-1.6678125,0,0.477739429,90.00000001 +209.28,50.30085681,-3.069243224,10000.5838,-8.28E-11,199.9927238,-1.6921875,0,0.48476498,90.00000001 +209.29,50.30085681,-3.069215198,10000.6009,-1.69E-10,199.9916093,-1.7165625,0,0.491790589,90.00000001 +209.3,50.30085681,-3.069187172,10000.6181,-1.69E-10,199.9916099,-1.7415625,0,0.49881614,90.00000001 +209.31,50.30085681,-3.069159146,10000.6357,-8.91E-11,199.9925024,-1.766875,0,0.505841748,90.00000001 +209.32,50.30085681,-3.069131119,10000.6535,1.09E-11,199.992503,-1.79125,0,0.512867299,90.00000001 +209.33,50.30085681,-3.069103093,10000.6715,6.41E-11,199.9913885,-1.815,0,0.519892908,90.00000001 +209.34,50.30085681,-3.069075067,10000.6898,4.22E-11,199.9907201,-1.8384375,0,0.526918459,90.00000001 +209.35,50.30085681,-3.069047041,10000.7083,-9.37E-12,199.9911667,-1.861875,0,0.533944068,90.00000001 +209.36,50.30085681,-3.069019015,10000.727,-1.09E-11,199.9916133,-1.886875,0,0.540969619,90.00000001 +209.37,50.30085681,-3.068990988,10000.746,2.66E-11,199.9911679,-1.913125,0,0.547995227,90.00000001 +209.38,50.30085681,-3.068962963,10000.7653,1.72E-11,199.9902765,-1.938125,0,0.555020778,90.00000001 +209.39,50.30085681,-3.068934936,10000.7848,-4.22E-11,199.9893851,-1.9615625,0,0.562046387,90.00000001 +209.4,50.30085681,-3.068906911,10000.8045,-8.13E-11,199.9889397,-1.9853125,0,0.569071938,90.00000001 +209.41,50.30085681,-3.068878885,10000.8245,-8.28E-11,199.9893864,-2.01,0,0.576097547,90.00000001 +209.42,50.30085681,-3.068850859,10000.8447,-7.66E-11,199.990056,-2.035,0,0.583123098,90.00000001 +209.43,50.30085681,-3.068822833,10000.8652,-7.50E-11,199.9902796,-2.06,0,0.590148706,90.00000001 +209.44,50.30085681,-3.068794807,10000.8859,-7.66E-11,199.9902803,-2.085,0,0.597174257,90.00000001 +209.45,50.30085681,-3.068766781,10000.9069,-8.28E-11,199.9900579,-2.11,0,0.604199866,90.00000001 +209.46,50.30085681,-3.068738755,10000.9281,-8.28E-11,199.9891666,-2.1346875,0,0.611225417,90.00000001 +209.47,50.30085681,-3.068710729,10000.9496,-5.16E-11,199.9880523,-2.1584375,0,0.618251026,90.00000001 +209.48,50.30085681,-3.068682704,10000.9713,-6.25E-12,199.98783,-2.181875,0,0.625276577,90.00000001 +209.49,50.30085681,-3.068654678,10000.9932,-1.41E-11,199.9880536,-2.2065625,0,0.632302185,90.00000001 +209.5,50.30085681,-3.068626652,10001.0154,-9.22E-11,199.9876083,-2.231875,0,0.639327736,90.00000001 +209.51,50.30085681,-3.068598627,10001.0379,-1.77E-10,199.9869401,-2.25625,0,0.646353345,90.00000001 +209.52,50.30085681,-3.068570601,10001.0605,-2.17E-10,199.9867178,-2.2803125,0,0.653378896,90.00000001 +209.53,50.30085681,-3.068542576,10001.0835,-2.25E-10,199.9864955,-2.305,0,0.660404505,90.00000001 +209.54,50.30085681,-3.06851455,10001.1066,-2.17E-10,199.9858272,-2.3296875,0,0.667430056,90.00000001 +209.55,50.30085681,-3.068486525,10001.1301,-1.77E-10,199.985382,-2.35375,0,0.674455664,90.00000001 +209.56,50.30085681,-3.0684585,10001.1537,-9.06E-11,199.9858287,-2.378125,0,0.681481215,90.00000001 +209.57,50.30085681,-3.068430474,10001.1776,-4.69E-12,199.9864984,-2.4034375,0,0.688506824,90.00000001 +209.58,50.30085681,-3.068402449,10001.2018,1.72E-11,199.9864992,-2.428125,0,0.695532375,90.00000001 +209.59,50.30085681,-3.068374423,10001.2262,-1.09E-11,199.985608,-2.451875,0,0.702557984,90.00000001 +209.6,50.30085681,-3.068346398,10001.2508,-1.09E-11,199.9842708,-2.476875,0,0.709583535,90.00000001 +209.61,50.30085681,-3.068318373,10001.2757,2.81E-11,199.9833796,-2.503125,0,0.716609086,90.00000001 +209.62,50.30085681,-3.068290348,10001.3009,3.44E-11,199.9831573,-2.528125,0,0.723634694,90.00000001 +209.63,50.30085681,-3.068262323,10001.3263,-1.09E-11,199.9831581,-2.5515625,0,0.730660246,90.00000001 +209.64,50.30085681,-3.068234298,10001.3519,-4.06E-11,199.9831589,-2.575,0,0.737685854,90.00000001 +209.65,50.30085681,-3.068206273,10001.3778,-1.09E-11,199.9831597,-2.5984375,0,0.744711405,90.00000001 +209.66,50.30085681,-3.068178248,10001.4039,3.28E-11,199.9831606,-2.621875,0,0.751737014,90.00000001 +209.67,50.30085681,-3.068150223,10001.4302,1.87E-11,199.9831614,-2.646875,0,0.758762565,90.00000001 +209.68,50.30085681,-3.068122198,10001.4568,-3.44E-11,199.9831622,-2.673125,0,0.765788173,90.00000001 +209.69,50.30085681,-3.068094173,10001.4837,-4.06E-11,199.9829401,-2.698125,0,0.772813725,90.00000001 +209.7,50.30085681,-3.068066148,10001.5108,1.56E-12,199.9820489,-2.721875,0,0.779839333,90.00000001 +209.71,50.30085681,-3.068038123,10001.5381,-6.66E-16,199.9807118,-2.7465625,0,0.786864884,90.00000001 +209.72,50.30085681,-3.068010099,10001.5657,-8.44E-11,199.9798207,-2.771875,0,0.793890493,90.00000001 +209.73,50.30085681,-3.067982074,10001.5936,-1.83E-10,199.9795985,-2.79625,0,0.800916044,90.00000001 +209.74,50.30085681,-3.06795405,10001.6216,-2.14E-10,199.9795994,-2.82,0,0.807941652,90.00000001 +209.75,50.30085681,-3.067926025,10001.65,-1.61E-10,199.9796003,-2.84375,0,0.814967204,90.00000001 +209.76,50.30085681,-3.067898001,10001.6785,-6.25E-11,199.9796012,-2.868125,0,0.821992812,90.00000001 +209.77,50.30085681,-3.067869976,10001.7073,1.87E-11,199.9796021,-2.89375,0,0.829018363,90.00000001 +209.78,50.30085681,-3.067841952,10001.7364,5.00E-11,199.97938,-2.9196875,0,0.836043972,90.00000001 +209.79,50.30085681,-3.067813927,10001.7657,4.22E-11,199.9784889,-2.9446875,0,0.843069523,90.00000001 +209.8,50.30085681,-3.067785903,10001.7953,3.12E-12,199.9773749,-2.9684375,0,0.850095132,90.00000001 +209.81,50.30085681,-3.067757879,10001.8251,-5.16E-11,199.9773758,-2.9915625,0,0.857120683,90.00000001 +209.82,50.30085681,-3.067729855,10001.8551,-8.28E-11,199.9780457,-3.0153125,0,0.864146291,90.00000001 +209.83,50.30085681,-3.06770183,10001.8854,-8.28E-11,199.9771547,-3.04,0,0.871171842,90.00000001 +209.84,50.30085681,-3.067673806,10001.9159,-7.66E-11,199.9749257,-3.065,0,0.878197451,90.00000001 +209.85,50.30085681,-3.067645783,10001.9467,-7.34E-11,199.9740347,-3.09,0,0.885223002,90.00000001 +209.86,50.30085681,-3.067617759,10001.9777,-5.78E-11,199.9749276,-3.1146875,0,0.892248611,90.00000001 +209.87,50.30085681,-3.067589735,10002.009,-1.25E-11,199.9758206,-3.1384375,0,0.899274162,90.00000001 +209.88,50.30085681,-3.067561711,10002.0405,3.28E-11,199.9760446,-3.161875,0,0.90629977,90.00000001 +209.89,50.30085681,-3.067533687,10002.0722,2.03E-11,199.9758226,-3.186875,0,0.913325321,90.00000001 +209.9,50.30085681,-3.067505663,10002.1042,-2.50E-11,199.9749316,-3.213125,0,0.92035093,90.00000001 +209.91,50.30085681,-3.067477639,10002.1365,-1.72E-11,199.9735946,-3.238125,0,0.927376481,90.00000001 +209.92,50.30085681,-3.067449616,10002.169,4.22E-11,199.9727036,-3.2615625,0,0.93440209,90.00000001 +209.93,50.30085681,-3.067421592,10002.2017,8.12E-11,199.9727047,-3.2853125,0,0.941427641,90.00000001 +209.94,50.30085681,-3.067393569,10002.2347,8.28E-11,199.9733747,-3.31,0,0.948453249,90.00000001 +209.95,50.30085681,-3.067365545,10002.2679,7.81E-11,199.9735987,-3.335,0,0.9554788,90.00000001 +209.96,50.30085681,-3.067337521,10002.3014,8.28E-11,199.9724848,-3.36,0,0.962504409,90.00000001 +209.97,50.30085681,-3.067309498,10002.3351,9.06E-11,199.9711478,-3.385,0,0.96952996,90.00000001 +209.98,50.30085681,-3.067281475,10002.3691,8.91E-11,199.9704799,-3.41,0,0.976555569,90.00000001 +209.99,50.30085681,-3.067253451,10002.4033,6.56E-11,199.970035,-3.4346875,0,0.98358112,90.00000001 +210,50.30085681,-3.067225429,10002.4378,1.25E-11,199.9700361,-3.4584375,0,0.990606728,90.00000001 +210.01,50.30085681,-3.067197405,10002.4725,-5.00E-11,199.9702602,-3.4815625,0,0.997632279,90.00000001 +210.02,50.30085681,-3.067169382,10002.5074,-8.28E-11,199.9698153,-3.5053125,0,1.004657888,90.00000001 +210.03,50.30085681,-3.067141359,10002.5426,-8.28E-11,199.9689244,-3.53,0,1.011683439,90.00000001 +210.04,50.30085681,-3.067113336,10002.578,-7.66E-11,199.9678105,-3.555,0,1.018709048,90.00000001 +210.05,50.30085681,-3.067085313,10002.6137,-7.50E-11,199.9666966,-3.58,0,1.025734599,90.00000001 +210.06,50.30085681,-3.067057291,10002.6496,-7.50E-11,199.9666977,-3.605,0,1.032760207,90.00000001 +210.07,50.30085681,-3.067029268,10002.6858,-7.34E-11,199.9675909,-3.63,0,1.039785758,90.00000001 +210.08,50.30085681,-3.067001245,10002.7222,-5.78E-11,199.967592,-3.6546875,0,1.046811367,90.00000001 +210.09,50.30085681,-3.066973222,10002.7589,-1.09E-11,199.9664782,-3.6784375,0,1.053836918,90.00000001 +210.1,50.30085681,-3.0669452,10002.7958,4.22E-11,199.9655873,-3.701875,0,1.060862527,90.00000001 +210.11,50.30085681,-3.066917177,10002.8329,4.38E-11,199.9653655,-3.726875,0,1.067888078,90.00000001 +210.12,50.30085681,-3.066889155,10002.8703,4.69E-12,199.9651437,-3.753125,0,1.074913686,90.00000001 +210.13,50.30085681,-3.066861132,10002.908,-1.56E-12,199.9642529,-3.778125,0,1.081939237,90.00000001 +210.14,50.30085681,-3.06683311,10002.9459,3.59E-11,199.9631391,-3.8015625,0,1.088964846,90.00000001 +210.15,50.30085681,-3.066805088,10002.984,6.72E-11,199.9629172,-3.8253125,0,1.095990397,90.00000001 +210.16,50.30085681,-3.066777066,10003.0224,7.50E-11,199.9629184,-3.85,0,1.103016006,90.00000001 +210.17,50.30085681,-3.066749043,10003.061,6.72E-11,199.9618047,-3.8746875,0,1.110041557,90.00000001 +210.18,50.30085681,-3.066721022,10003.0999,3.59E-11,199.9606909,-3.8984375,0,1.117067165,90.00000001 +210.19,50.30085681,-3.066693,10003.139,-1.56E-12,199.9609151,-3.921875,0,1.124092716,90.00000001 +210.2,50.30085681,-3.066664978,10003.1783,4.69E-12,199.9615853,-3.946875,0,1.131118325,90.00000001 +210.21,50.30085681,-3.066636956,10003.2179,4.37E-11,199.9615866,-3.973125,0,1.138143876,90.00000001 +210.22,50.30085681,-3.066608934,10003.2578,4.22E-11,199.9606958,-3.998125,0,1.145169485,90.00000001 +210.23,50.30085681,-3.066580912,10003.2979,-1.09E-11,199.9595821,-4.0215625,0,1.152195036,90.00000001 +210.24,50.30085681,-3.066552891,10003.3382,-5.78E-11,199.9593604,-4.0453125,0,1.159220644,90.00000001 +210.25,50.30085681,-3.066524869,10003.3788,-7.34E-11,199.9593616,-4.07,0,1.166246195,90.00000001 +210.26,50.30085681,-3.066496847,10003.4196,-7.50E-11,199.9580249,-4.095,0,1.173271804,90.00000001 +210.27,50.30085681,-3.066468826,10003.4607,-7.50E-11,199.9562422,-4.12,0,1.180297355,90.00000001 +210.28,50.30085681,-3.066440805,10003.502,-7.66E-11,199.9560205,-4.145,0,1.187322964,90.00000001 +210.29,50.30085681,-3.066412784,10003.5436,-8.28E-11,199.9569138,-4.17,0,1.194348515,90.00000001 +210.3,50.30085681,-3.066384762,10003.5854,-8.28E-11,199.9569151,-4.1946875,0,1.201374123,90.00000001 +210.31,50.30085681,-3.066356741,10003.6275,-5.16E-11,199.9558015,-4.2184375,0,1.208399674,90.00000001 +210.32,50.30085681,-3.06632872,10003.6698,3.12E-12,199.9549108,-4.2415625,0,1.215425283,90.00000001 +210.33,50.30085681,-3.066300699,10003.7123,4.22E-11,199.9546891,-4.2653125,0,1.222450834,90.00000001 +210.34,50.30085681,-3.066272678,10003.7551,5.78E-11,199.9544675,-4.29,0,1.229476443,90.00000001 +210.35,50.30085681,-3.066244657,10003.7981,6.72E-11,199.9535768,-4.315,0,1.236501994,90.00000001 +210.36,50.30085681,-3.066216636,10003.8414,7.34E-11,199.9522402,-4.34,0,1.243527602,90.00000001 +210.37,50.30085681,-3.066188616,10003.8849,7.50E-11,199.9513496,-4.365,0,1.250553154,90.00000001 +210.38,50.30085681,-3.066160595,10003.9287,7.34E-11,199.9511279,-4.39,0,1.257578762,90.00000001 +210.39,50.30085681,-3.066132575,10003.9727,6.72E-11,199.9511293,-4.415,0,1.264604313,90.00000001 +210.4,50.30085681,-3.066104554,10004.017,6.87E-11,199.9511307,-4.4396875,0,1.271629922,90.00000001 +210.41,50.30085681,-3.066076534,10004.0615,1.08E-10,199.9509091,-4.4634375,0,1.278655473,90.00000001 +210.42,50.30085681,-3.066048513,10004.1063,1.67E-10,199.9500185,-4.486875,0,1.285681081,90.00000001 +210.43,50.30085681,-3.066020493,10004.1512,1.67E-10,199.9486819,-4.5115625,0,1.292706633,90.00000001 +210.44,50.30085681,-3.065992473,10004.1965,8.12E-11,199.9477914,-4.536875,0,1.299732241,90.00000001 +210.45,50.30085681,-3.065964453,10004.242,-1.72E-11,199.9475698,-4.56125,0,1.306757792,90.00000001 +210.46,50.30085681,-3.065936433,10004.2877,-6.56E-11,199.9475712,-4.5853125,0,1.313783401,90.00000001 +210.47,50.30085681,-3.065908413,10004.3337,-7.50E-11,199.9473497,-4.61,0,1.320808952,90.00000001 +210.48,50.30085681,-3.065880393,10004.3799,-7.50E-11,199.9464591,-4.635,0,1.32783456,90.00000001 +210.49,50.30085681,-3.065852373,10004.4264,-7.34E-11,199.9453456,-4.66,0,1.334860112,90.00000001 +210.5,50.30085681,-3.065824354,10004.4731,-5.78E-11,199.945124,-4.6846875,0,1.34188572,90.00000001 +210.51,50.30085681,-3.065796334,10004.5201,-1.09E-11,199.9451255,-4.7084375,0,1.348911271,90.00000001 +210.52,50.30085681,-3.065768314,10004.5673,5.16E-11,199.944012,-4.7315625,0,1.35593688,90.00000001 +210.53,50.30085681,-3.065740295,10004.6147,9.06E-11,199.9428985,-4.7553125,0,1.362962431,90.00000001 +210.54,50.30085681,-3.065712276,10004.6624,8.91E-11,199.9429,-4.7803125,0,1.369988039,90.00000001 +210.55,50.30085681,-3.065684256,10004.7103,3.59E-11,199.9426785,-4.80625,0,1.377013591,90.00000001 +210.56,50.30085681,-3.065656237,10004.7585,-6.72E-11,199.941565,-4.831875,0,1.384039199,90.00000001 +210.57,50.30085681,-3.065628218,10004.807,-1.67E-10,199.9406745,-4.85625,0,1.39106475,90.00000001 +210.58,50.30085681,-3.065600199,10004.8556,-2.06E-10,199.9404531,-4.88,0,1.398090359,90.00000001 +210.59,50.30085681,-3.06557218,10004.9046,-1.67E-10,199.9404546,-4.90375,0,1.40511591,90.00000001 +210.6,50.30085681,-3.065544161,10004.9537,-6.72E-11,199.9402331,-4.928125,0,1.412141461,90.00000001 +210.61,50.30085681,-3.065516142,10005.0031,2.66E-11,199.9393427,-4.9534375,0,1.41916707,90.00000001 +210.62,50.30085681,-3.065488123,10005.0528,4.22E-11,199.9380063,-4.978125,0,1.426192621,90.00000001 +210.63,50.30085681,-3.065460105,10005.1027,6.25E-12,199.9368928,-5.001875,0,1.433218229,90.00000001 +210.64,50.30085681,-3.065432086,10005.1528,1.41E-11,199.9360024,-5.0265625,0,1.44024378,90.00000001 +210.65,50.30085681,-3.065404068,10005.2032,9.22E-11,199.935558,-5.051875,0,1.447269389,90.00000001 +210.66,50.30085681,-3.06537605,10005.2539,1.77E-10,199.9357826,-5.07625,0,1.45429494,90.00000001 +210.67,50.30085681,-3.065348031,10005.3047,2.17E-10,199.9355612,-5.1003125,0,1.461320549,90.00000001 +210.68,50.30085681,-3.065320013,10005.3559,2.25E-10,199.9344478,-5.125,0,1.4683461,90.00000001 +210.69,50.30085681,-3.065291995,10005.4072,2.16E-10,199.9335574,-5.1496875,0,1.475371708,90.00000001 +210.7,50.30085681,-3.065263977,10005.4589,1.67E-10,199.933336,-5.17375,0,1.482397259,90.00000001 +210.71,50.30085681,-3.065235959,10005.5107,6.72E-11,199.9331146,-5.198125,0,1.489422868,90.00000001 +210.72,50.30085681,-3.065207941,10005.5628,-2.66E-11,199.9322243,-5.2234375,0,1.496448419,90.00000001 +210.73,50.30085681,-3.065179923,10005.6152,-4.22E-11,199.9308879,-5.248125,0,1.503474028,90.00000001 +210.74,50.30085681,-3.065151906,10005.6678,3.12E-12,199.9299976,-5.2715625,0,1.510499579,90.00000001 +210.75,50.30085681,-3.065123888,10005.7206,4.22E-11,199.9297763,-5.2953125,0,1.517525187,90.00000001 +210.76,50.30085681,-3.065095871,10005.7737,5.78E-11,199.9295549,-5.32,0,1.524550738,90.00000001 +210.77,50.30085681,-3.065067853,10005.827,6.72E-11,199.9286646,-5.345,0,1.531576347,90.00000001 +210.78,50.30085681,-3.065039836,10005.8806,7.34E-11,199.9273283,-5.37,0,1.538601898,90.00000001 +210.79,50.30085681,-3.065011819,10005.9344,7.50E-11,199.926438,-5.395,0,1.545627507,90.00000001 +210.8,50.30085681,-3.064983802,10005.9885,7.34E-11,199.9262167,-5.42,0,1.552653058,90.00000001 +210.81,50.30085681,-3.064955785,10006.0428,5.78E-11,199.9259954,-5.4446875,0,1.559678666,90.00000001 +210.82,50.30085681,-3.064927768,10006.0974,1.09E-11,199.9251051,-5.4684375,0,1.566704217,90.00000001 +210.83,50.30085681,-3.064899751,10006.1522,-4.22E-11,199.9239918,-5.491875,0,1.573729826,90.00000001 +210.84,50.30085681,-3.064871735,10006.2072,-4.37E-11,199.9237706,-5.516875,0,1.580755377,90.00000001 +210.85,50.30085681,-3.064843718,10006.2625,-4.69E-12,199.9237723,-5.543125,0,1.587780986,90.00000001 +210.86,50.30085681,-3.064815701,10006.3181,1.56E-12,199.922659,-5.568125,0,1.594806537,90.00000001 +210.87,50.30085681,-3.064787685,10006.3739,-3.59E-11,199.9215458,-5.5915625,0,1.601832145,90.00000001 +210.88,50.30085681,-3.064759669,10006.4299,-5.78E-11,199.9215475,-5.615,0,1.608857697,90.00000001 +210.89,50.30085681,-3.064731652,10006.4862,-1.87E-11,199.9213263,-5.63875,0,1.615883305,90.00000001 +210.9,50.30085681,-3.064703636,10006.5427,7.50E-11,199.9202131,-5.663125,0,1.622908856,90.00000001 +210.91,50.30085681,-3.06467562,10006.5994,1.61E-10,199.9190999,-5.6884375,0,1.629934465,90.00000001 +210.92,50.30085681,-3.064647604,10006.6565,1.67E-10,199.9179867,-5.7134375,0,1.636960016,90.00000001 +210.93,50.30085681,-3.064619588,10006.7137,9.22E-11,199.9168735,-5.738125,0,1.643985624,90.00000001 +210.94,50.30085681,-3.064591573,10006.7712,1.25E-11,199.9166523,-5.7634375,0,1.651011176,90.00000001 +210.95,50.30085681,-3.064563557,10006.829,-3.13E-12,199.9166541,-5.788125,0,1.658036784,90.00000001 +210.96,50.30085681,-3.064535541,10006.887,2.81E-11,199.9155409,-5.8115625,0,1.665062335,90.00000001 +210.97,50.30085681,-3.064507526,10006.9452,5.16E-11,199.9144277,-5.8353125,0,1.672087944,90.00000001 +210.98,50.30085681,-3.064479511,10007.0037,5.94E-11,199.9144296,-5.86,0,1.679113495,90.00000001 +210.99,50.30085681,-3.064451495,10007.0624,5.78E-11,199.9142084,-5.8846875,0,1.686139103,90.00000001 +211,50.30085681,-3.06442348,10007.1214,1.56E-11,199.9130953,-5.90875,0,1.693164655,90.00000001 +211.01,50.30085681,-3.064395465,10007.1806,-8.28E-11,199.9122051,-5.933125,0,1.700190263,90.00000001 +211.02,50.30085681,-3.06436745,10007.24,-1.75E-10,199.911761,-5.9584375,0,1.707215814,90.00000001 +211.03,50.30085681,-3.064339435,10007.2998,-1.83E-10,199.9108709,-5.983125,0,1.714241423,90.00000001 +211.04,50.30085681,-3.06431142,10007.3597,-1.23E-10,199.9095348,-6.0065625,0,1.721266974,90.00000001 +211.05,50.30085681,-3.064283406,10007.4199,-6.87E-11,199.9086447,-6.030625,0,1.728292582,90.00000001 +211.06,50.30085681,-3.064255391,10007.4803,-2.03E-11,199.9084235,-6.05625,0,1.735318134,90.00000001 +211.07,50.30085681,-3.064227377,10007.541,6.09E-11,199.9082024,-6.081875,0,1.742343742,90.00000001 +211.08,50.30085681,-3.064199362,10007.602,1.53E-10,199.9073124,-6.10625,0,1.749369293,90.00000001 +211.09,50.30085681,-3.064171348,10007.6631,1.98E-10,199.9059763,-6.13,0,1.756394902,90.00000001 +211.1,50.30085681,-3.064143334,10007.7246,1.67E-10,199.9050862,-6.15375,0,1.763420453,90.00000001 +211.11,50.30085681,-3.06411532,10007.7862,7.66E-11,199.9046422,-6.178125,0,1.770446061,90.00000001 +211.12,50.30085681,-3.064087306,10007.8481,-1.09E-11,199.9037521,-6.20375,0,1.777471613,90.00000001 +211.13,50.30085681,-3.064059292,10007.9103,-5.78E-11,199.9024161,-6.229375,0,1.784497221,90.00000001 +211.14,50.30085681,-3.064031279,10007.9727,-9.84E-11,199.901303,-6.2534375,0,1.791522772,90.00000001 +211.15,50.30085681,-3.064003265,10008.0354,-1.44E-10,199.900413,-6.276875,0,1.798548381,90.00000001 +211.16,50.30085681,-3.063975252,10008.0982,-1.36E-10,199.899969,-6.3015625,0,1.805573932,90.00000001 +211.17,50.30085681,-3.063947239,10008.1614,-5.94E-11,199.9001939,-6.326875,0,1.81259954,90.00000001 +211.18,50.30085681,-3.063919225,10008.2248,1.87E-11,199.8999729,-6.35125,0,1.819625092,90.00000001 +211.19,50.30085681,-3.063891212,10008.2884,5.31E-11,199.8988599,-6.3753125,0,1.8266507,90.00000001 +211.2,50.30085681,-3.063863199,10008.3523,6.72E-11,199.8977469,-6.4,0,1.833676251,90.00000001 +211.21,50.30085681,-3.063835186,10008.4164,7.34E-11,199.896634,-6.4246875,0,1.84070186,90.00000001 +211.22,50.30085681,-3.063807173,10008.4808,4.22E-11,199.895521,-6.4484375,0,1.847727411,90.00000001 +211.23,50.30085681,-3.063779161,10008.5454,-9.38E-12,199.8953,-6.471875,0,1.854753019,90.00000001 +211.24,50.30085681,-3.063751148,10008.6102,-9.37E-12,199.895302,-6.496875,0,1.861778571,90.00000001 +211.25,50.30085681,-3.063723135,10008.6753,3.59E-11,199.8939661,-6.523125,0,1.868804179,90.00000001 +211.26,50.30085681,-3.063695123,10008.7407,4.06E-11,199.8921842,-6.548125,0,1.87582973,90.00000001 +211.27,50.30085681,-3.063667111,10008.8063,-1.25E-11,199.8917402,-6.5715625,0,1.882855339,90.00000001 +211.28,50.30085681,-3.063639099,10008.8721,-6.56E-11,199.8917423,-6.5953125,0,1.88988089,90.00000001 +211.29,50.30085681,-3.063611086,10008.9382,-8.91E-11,199.8906293,-6.62,0,1.896906498,90.00000001 +211.3,50.30085681,-3.063583075,10009.0045,-8.13E-11,199.8892934,-6.6446875,0,1.90393205,90.00000001 +211.31,50.30085681,-3.063555063,10009.0711,-3.44E-11,199.8886265,-6.6684375,0,1.910957658,90.00000001 +211.32,50.30085681,-3.063527051,10009.1379,2.50E-11,199.8879596,-6.691875,0,1.917983209,90.00000001 +211.33,50.30085681,-3.06349904,10009.2049,3.44E-11,199.8870697,-6.716875,0,1.925008818,90.00000001 +211.34,50.30085681,-3.063471028,10009.2722,-4.69E-12,199.8859568,-6.743125,0,1.932034369,90.00000001 +211.35,50.30085681,-3.063443017,10009.3398,-1.72E-11,199.884621,-6.768125,0,1.939059977,90.00000001 +211.36,50.30085681,-3.063415006,10009.4076,2.19E-11,199.8837311,-6.7915625,0,1.946085529,90.00000001 +211.37,50.30085681,-3.063386995,10009.4756,6.72E-11,199.8835102,-6.8153125,0,1.953111137,90.00000001 +211.38,50.30085681,-3.063358984,10009.5439,8.91E-11,199.8832894,-6.84,0,1.960136688,90.00000001 +211.39,50.30085681,-3.063330973,10009.6124,9.06E-11,199.8823995,-6.865,0,1.967162297,90.00000001 +211.4,50.30085681,-3.063302962,10009.6812,8.28E-11,199.8810637,-6.89,0,1.974187848,90.00000001 +211.41,50.30085681,-3.063274952,10009.7502,7.66E-11,199.8799509,-6.915,0,1.981213456,90.00000001 +211.42,50.30085681,-3.063246941,10009.8195,7.50E-11,199.879061,-6.94,0,1.988239008,90.00000001 +211.43,50.30085681,-3.063218931,10009.889,6.72E-11,199.8786172,-6.9646875,0,1.995264616,90.00000001 +211.44,50.30085681,-3.063190921,10009.9588,3.59E-11,199.8788424,-6.9884375,0,2.002290167,90.00000001 +211.45,50.30085681,-3.06316291,10010.0288,-1.56E-12,199.8786216,-7.011875,0,2.009315776,90.00000001 +211.46,50.30085681,-3.0631349,10010.099,1.41E-11,199.8772858,-7.0365625,0,2.016341327,90.00000001 +211.47,50.30085681,-3.06310689,10010.1695,1.00E-10,199.875504,-7.061875,0,2.023366935,90.00000001 +211.48,50.30085681,-3.06307888,10010.2403,1.92E-10,199.8739453,-7.08625,0,2.030392487,90.00000001 +211.49,50.30085681,-3.063050871,10010.3112,2.23E-10,199.8730555,-7.11,0,2.037418095,90.00000001 +211.5,50.30085681,-3.063022861,10010.3825,1.77E-10,199.8728347,-7.13375,0,2.044443646,90.00000001 +211.51,50.30085681,-3.062994852,10010.4539,7.66E-11,199.872614,-7.158125,0,2.051469255,90.00000001 +211.52,50.30085681,-3.062966842,10010.5256,-1.88E-11,199.8717242,-7.18375,0,2.058494806,90.00000001 +211.53,50.30085681,-3.062938833,10010.5976,-6.56E-11,199.8701655,-7.2096875,0,2.065520414,90.00000001 +211.54,50.30085681,-3.062910824,10010.6698,-6.72E-11,199.8683838,-7.2346875,0,2.072545966,90.00000001 +211.55,50.30085681,-3.062882815,10010.7423,-3.59E-11,199.867048,-7.2584375,0,2.079571574,90.00000001 +211.56,50.30085681,-3.062854807,10010.815,1.09E-11,199.8668273,-7.2815625,0,2.086597125,90.00000001 +211.57,50.30085681,-3.062826798,10010.8879,4.37E-11,199.8670526,-7.3053125,0,2.093622734,90.00000001 +211.58,50.30085681,-3.062798789,10010.9611,5.94E-11,199.8663859,-7.33,0,2.100648285,90.00000001 +211.59,50.30085681,-3.062770781,10011.0345,7.50E-11,199.8646042,-7.355,0,2.107673894,90.00000001 +211.6,50.30085681,-3.062742772,10011.1082,8.91E-11,199.8623765,-7.38,0,2.114699445,90.00000001 +211.61,50.30085681,-3.062714765,10011.1821,9.06E-11,199.8610409,-7.405,0,2.121724996,90.00000001 +211.62,50.30085681,-3.062686757,10011.2563,8.13E-11,199.8612662,-7.43,0,2.128750604,90.00000001 +211.63,50.30085681,-3.062658749,10011.3307,5.94E-11,199.8617145,-7.4546875,0,2.135776156,90.00000001 +211.64,50.30085681,-3.062630741,10011.4054,1.25E-11,199.8610478,-7.4784375,0,2.142801764,90.00000001 +211.65,50.30085681,-3.062602733,10011.4803,-3.28E-11,199.8597122,-7.501875,0,2.149827315,90.00000001 +211.66,50.30085681,-3.062574726,10011.5554,-9.37E-12,199.8585996,-7.5265625,0,2.156852924,90.00000001 +211.67,50.30085681,-3.062546718,10011.6308,9.06E-11,199.8574869,-7.551875,0,2.163878475,90.00000001 +211.68,50.30085681,-3.062518711,10011.7065,1.91E-10,199.8561513,-7.57625,0,2.170904083,90.00000001 +211.69,50.30085681,-3.062490704,10011.7823,2.31E-10,199.8552617,-7.6003125,0,2.177929635,90.00000001 +211.7,50.30085681,-3.062462697,10011.8585,2.25E-10,199.8548181,-7.625,0,2.184955243,90.00000001 +211.71,50.30085681,-3.06243469,10011.9348,2.02E-10,199.8539285,-7.6496875,0,2.191980794,90.00000001 +211.72,50.30085681,-3.062406683,10012.0115,1.52E-10,199.8525929,-7.67375,0,2.199006403,90.00000001 +211.73,50.30085681,-3.062378677,10012.0883,5.94E-11,199.8514803,-7.698125,0,2.206031954,90.00000001 +211.74,50.30085681,-3.06235067,10012.1654,-2.66E-11,199.8505907,-7.7234375,0,2.213057562,90.00000001 +211.75,50.30085681,-3.062322664,10012.2428,-3.44E-11,199.8499241,-7.748125,0,2.220083114,90.00000001 +211.76,50.30085681,-3.062294658,10012.3204,1.87E-11,199.8492576,-7.7715625,0,2.227108722,90.00000001 +211.77,50.30085681,-3.062266651,10012.3982,5.78E-11,199.847922,-7.7953125,0,2.234134273,90.00000001 +211.78,50.30085681,-3.062238646,10012.4763,6.72E-11,199.8468095,-7.82,0,2.241159882,90.00000001 +211.79,50.30085681,-3.06221064,10012.5546,7.66E-11,199.8468119,-7.845,0,2.248185433,90.00000001 +211.8,50.30085681,-3.062182634,10012.6332,8.91E-11,199.8463684,-7.87,0,2.255211041,90.00000001 +211.81,50.30085681,-3.062154628,10012.712,9.06E-11,199.8443639,-7.895,0,2.262236593,90.00000001 +211.82,50.30085681,-3.062126623,10012.7911,8.28E-11,199.8421364,-7.92,0,2.269262201,90.00000001 +211.83,50.30085681,-3.062098618,10012.8704,6.72E-11,199.8410239,-7.9446875,0,2.276287752,90.00000001 +211.84,50.30085681,-3.062070613,10012.95,2.81E-11,199.8408034,-7.9684375,0,2.283313361,90.00000001 +211.85,50.30085681,-3.062042608,10013.0298,-1.72E-11,199.8405828,-7.991875,0,2.290338912,90.00000001 +211.86,50.30085681,-3.062014603,10013.1098,-1.09E-11,199.8396934,-8.016875,0,2.29736452,90.00000001 +211.87,50.30085681,-3.061986598,10013.1901,3.59E-11,199.8383579,-8.043125,0,2.304390072,90.00000001 +211.88,50.30085681,-3.061958594,10013.2707,4.22E-11,199.8372454,-8.068125,0,2.31141568,90.00000001 +211.89,50.30085681,-3.061930589,10013.3515,-3.12E-12,199.836356,-8.0915625,0,2.318441231,90.00000001 +211.9,50.30085681,-3.061902585,10013.4325,-3.28E-11,199.8356895,-8.115,0,2.32546684,90.00000001 +211.91,50.30085681,-3.061874581,10013.5138,-1.56E-12,199.835023,-8.13875,0,2.332492391,90.00000001 +211.92,50.30085681,-3.061846576,10013.5953,8.28E-11,199.8336876,-8.163125,0,2.339517999,90.00000001 +211.93,50.30085681,-3.061818573,10013.677,1.61E-10,199.8323522,-8.1884375,0,2.346543551,90.00000001 +211.94,50.30085681,-3.061790569,10013.7591,1.59E-10,199.8314627,-8.2134375,0,2.353569159,90.00000001 +211.95,50.30085681,-3.061762565,10013.8413,6.72E-11,199.8301273,-8.2378125,0,2.36059471,90.00000001 +211.96,50.30085681,-3.061734562,10013.9238,-5.78E-11,199.8287919,-8.2621875,0,2.367620319,90.00000001 +211.97,50.30085681,-3.061706559,10014.0066,-1.42E-10,199.8279025,-8.2865625,0,2.37464587,90.00000001 +211.98,50.30085681,-3.061678555,10014.0895,-1.36E-10,199.8265671,-8.3115625,0,2.381671478,90.00000001 +211.99,50.30085681,-3.061650553,10014.1728,-5.00E-11,199.8254547,-8.336875,0,2.38869703,90.00000001 +212,50.30085681,-3.06162255,10014.2563,4.22E-11,199.8254574,-8.36125,0,2.395722638,90.00000001 +212.01,50.30085681,-3.061594547,10014.34,7.34E-11,199.825014,-8.385,0,2.402748189,90.00000001 +212.02,50.30085681,-3.061566544,10014.424,3.59E-11,199.8232326,-8.4084375,0,2.409773798,90.00000001 +212.03,50.30085681,-3.061538542,10014.5082,-1.72E-11,199.8218973,-8.431875,0,2.416799349,90.00000001 +212.04,50.30085681,-3.06151054,10014.5926,-1.87E-11,199.8216769,-8.456875,0,2.423824957,90.00000001 +212.05,50.30085681,-3.061482537,10014.6773,1.88E-11,199.8205646,-8.483125,0,2.430850509,90.00000001 +212.06,50.30085681,-3.061454535,10014.7623,1.88E-11,199.8183373,-8.508125,0,2.437876117,90.00000001 +212.07,50.30085681,-3.061426534,10014.8475,-2.66E-11,199.8172249,-8.5315625,0,2.444901668,90.00000001 +212.08,50.30085681,-3.061398532,10014.9329,-5.78E-11,199.8170046,-8.5553125,0,2.451927277,90.00000001 +212.09,50.30085681,-3.06137053,10015.0186,-5.78E-11,199.8158923,-8.58,0,2.458952828,90.00000001 +212.1,50.30085681,-3.061342529,10015.1045,-5.31E-11,199.814557,-8.605,0,2.465978436,90.00000001 +212.11,50.30085681,-3.061314528,10015.1907,-5.78E-11,199.8136677,-8.63,0,2.473003988,90.00000001 +212.12,50.30085681,-3.061286526,10015.2771,-6.72E-11,199.8123324,-8.655,0,2.480029596,90.00000001 +212.13,50.30085681,-3.061258526,10015.3638,-7.34E-11,199.8112201,-8.68,0,2.487055147,90.00000001 +212.14,50.30085681,-3.061230525,10015.4507,-6.56E-11,199.8112228,-8.7046875,0,2.494080756,90.00000001 +212.15,50.30085681,-3.061202524,10015.5379,-2.81E-11,199.8107796,-8.7284375,0,2.501106307,90.00000001 +212.16,50.30085681,-3.061174523,10015.6253,2.81E-11,199.8087753,-8.7515625,0,2.508131916,90.00000001 +212.17,50.30085681,-3.061146523,10015.7129,6.72E-11,199.8065481,-8.7753125,0,2.515157467,90.00000001 +212.18,50.30085681,-3.061118523,10015.8008,8.28E-11,199.8054359,-8.8,0,2.522183075,90.00000001 +212.19,50.30085681,-3.061090523,10015.8889,9.22E-11,199.8052156,-8.825,0,2.529208626,90.00000001 +212.2,50.30085681,-3.061062523,10015.9773,9.69E-11,199.8049954,-8.85,0,2.536234235,90.00000001 +212.21,50.30085681,-3.061034523,10016.0659,9.06E-11,199.8038831,-8.875,0,2.543259786,90.00000001 +212.22,50.30085681,-3.061006523,10016.1548,7.50E-11,199.801656,-8.9,0,2.550285395,90.00000001 +212.23,50.30085681,-3.060978524,10016.2439,5.16E-11,199.7994288,-8.9246875,0,2.557310946,90.00000001 +212.24,50.30085681,-3.060950525,10016.3333,1.25E-11,199.7983166,-8.9484375,0,2.564336554,90.00000001 +212.25,50.30085681,-3.060922526,10016.4229,-2.50E-11,199.7980964,-8.971875,0,2.571362105,90.00000001 +212.26,50.30085681,-3.060894527,10016.5127,-1.25E-11,199.7978762,-8.996875,0,2.578387714,90.00000001 +212.27,50.30085681,-3.060866528,10016.6028,3.44E-11,199.796987,-9.023125,0,2.585413265,90.00000001 +212.28,50.30085681,-3.060838529,10016.6932,3.28E-11,199.7956518,-9.048125,0,2.592438874,90.00000001 +212.29,50.30085681,-3.060810531,10016.7838,-2.81E-11,199.7945397,-9.0715625,0,2.599464425,90.00000001 +212.3,50.30085681,-3.060782532,10016.8746,-7.19E-11,199.7934275,-9.095,0,2.606490033,90.00000001 +212.31,50.30085681,-3.060754534,10016.9657,-5.00E-11,199.7920924,-9.1184375,0,2.613515584,90.00000001 +212.32,50.30085681,-3.060726536,10017.057,3.13E-12,199.7909803,-9.141875,0,2.620541193,90.00000001 +212.33,50.30085681,-3.060698538,10017.1485,1.88E-11,199.7898681,-9.166875,0,2.627566744,90.00000001 +212.34,50.30085681,-3.06067054,10017.2403,-4.69E-12,199.788533,-9.193125,0,2.634592353,90.00000001 +212.35,50.30085681,-3.060642543,10017.3324,-1.56E-12,199.7874209,-9.218125,0,2.641617904,90.00000001 +212.36,50.30085681,-3.060614545,10017.4247,3.44E-11,199.7863088,-9.241875,0,2.648643512,90.00000001 +212.37,50.30085681,-3.060586548,10017.5172,3.59E-11,199.7849737,-9.266875,0,2.655669063,90.00000001 +212.38,50.30085681,-3.060558551,10017.61,-4.69E-12,199.7840846,-9.293125,0,2.662694672,90.00000001 +212.39,50.30085681,-3.060530554,10017.7031,-2.81E-11,199.7836415,-9.3178125,0,2.669720223,90.00000001 +212.4,50.30085681,-3.060502557,10017.7964,-4.37E-11,199.7825295,-9.3403125,0,2.676745832,90.00000001 +212.41,50.30085681,-3.06047456,10017.8899,-1.08E-10,199.7803024,-9.3634375,0,2.683771383,90.00000001 +212.42,50.30085681,-3.060446564,10017.9836,-1.84E-10,199.7780754,-9.3884375,0,2.690796991,90.00000001 +212.43,50.30085681,-3.060418568,10018.0777,-1.83E-10,199.7769633,-9.4134375,0,2.697822542,90.00000001 +212.44,50.30085681,-3.060390572,10018.1719,-9.22E-11,199.7767433,-9.438125,0,2.704848151,90.00000001 +212.45,50.30085681,-3.060362576,10018.2664,1.56E-12,199.7765232,-9.4634375,0,2.711873702,90.00000001 +212.46,50.30085681,-3.06033458,10018.3612,1.72E-11,199.7756342,-9.488125,0,2.718899311,90.00000001 +212.47,50.30085681,-3.060306584,10018.4562,-2.66E-11,199.7742992,-9.5115625,0,2.725924862,90.00000001 +212.48,50.30085681,-3.060278589,10018.5514,-5.78E-11,199.7731872,-9.5353125,0,2.73295047,90.00000001 +212.49,50.30085681,-3.060250593,10018.6469,-5.94E-11,199.7718521,-9.56,0,2.739976021,90.00000001 +212.5,50.30085681,-3.060222598,10018.7426,-6.09E-11,199.7696252,-9.585,0,2.74700163,90.00000001 +212.51,50.30085681,-3.060194603,10018.8386,-7.34E-11,199.7676212,-9.61,0,2.754027181,90.00000001 +212.52,50.30085681,-3.060166609,10018.9348,-7.19E-11,199.7671782,-9.6346875,0,2.76105279,90.00000001 +212.53,50.30085681,-3.060138614,10019.0313,-2.66E-11,199.7671812,-9.6584375,0,2.768078341,90.00000001 +212.54,50.30085681,-3.060110619,10019.128,3.28E-11,199.7658462,-9.681875,0,2.775103949,90.00000001 +212.55,50.30085681,-3.060082625,10019.2249,3.44E-11,199.7638423,-9.706875,0,2.7821295,90.00000001 +212.56,50.30085681,-3.060054631,10019.3221,-1.09E-11,199.7627303,-9.733125,0,2.789155109,90.00000001 +212.57,50.30085681,-3.060026637,10019.4196,-1.56E-11,199.7625104,-9.758125,0,2.79618066,90.00000001 +212.58,50.30085681,-3.059998643,10019.5173,3.59E-11,199.7622904,-9.7815625,0,2.803206269,90.00000001 +212.59,50.30085681,-3.059970649,10019.6152,8.13E-11,199.7611785,-9.8053125,0,2.81023182,90.00000001 +212.6,50.30085681,-3.059942655,10019.7134,8.91E-11,199.7589516,-9.83,0,2.817257428,90.00000001 +212.61,50.30085681,-3.059914662,10019.8118,6.72E-11,199.7567247,-9.8546875,0,2.824282979,90.00000001 +212.62,50.30085681,-3.059886669,10019.9105,1.25E-11,199.7553898,-9.87875,0,2.831308531,90.00000001 +212.63,50.30085681,-3.059858676,10020.0094,-7.34E-11,199.7540549,-9.903125,0,2.838334139,90.00000001 +212.64,50.30085681,-3.059830683,10020.1085,-1.45E-10,199.752051,-9.9284375,0,2.84535969,90.00000001 +212.65,50.30085681,-3.059802691,10020.208,-1.53E-10,199.7507162,-9.953125,0,2.852385299,90.00000001 +212.66,50.30085681,-3.059774699,10020.3076,-1.14E-10,199.7507193,-9.9765625,0,2.85941085,90.00000001 +212.67,50.30085681,-3.059746706,10020.4075,-8.28E-11,199.7504994,-10.0003125,0,2.866436458,90.00000001 +212.68,50.30085681,-3.059718714,10020.5076,-7.66E-11,199.7491645,-10.025,0,2.87346201,90.00000001 +212.69,50.30085681,-3.059690722,10020.608,-8.28E-11,199.7473837,-10.05,0,2.880487618,90.00000001 +212.7,50.30085681,-3.05966273,10020.7086,-9.06E-11,199.7458258,-10.075,0,2.887513169,90.00000001 +212.71,50.30085681,-3.059634739,10020.8095,-8.91E-11,199.744714,-10.1,0,2.894538778,90.00000001 +212.72,50.30085681,-3.059606747,10020.9106,-7.66E-11,199.7436022,-10.125,0,2.901564329,90.00000001 +212.73,50.30085681,-3.059578756,10021.012,-6.88E-11,199.7422674,-10.15,0,2.908589938,90.00000001 +212.74,50.30085681,-3.059550765,10021.1136,-6.72E-11,199.7411555,-10.1746875,0,2.915615489,90.00000001 +212.75,50.30085681,-3.059522774,10021.2155,-4.22E-11,199.7400437,-10.1984375,0,2.922641097,90.00000001 +212.76,50.30085681,-3.059494783,10021.3176,1.25E-11,199.7387089,-10.2215625,0,2.929666648,90.00000001 +212.77,50.30085681,-3.059466793,10021.4199,5.78E-11,199.7375971,-10.2453125,0,2.936692257,90.00000001 +212.78,50.30085681,-3.059438802,10021.5225,7.19E-11,199.7364854,-10.27,0,2.943717808,90.00000001 +212.79,50.30085681,-3.059410812,10021.6253,6.72E-11,199.7349276,-10.295,0,2.950743417,90.00000001 +212.8,50.30085681,-3.059382822,10021.7284,5.94E-11,199.7331468,-10.32,0,2.957768968,90.00000001 +212.81,50.30085681,-3.059354832,10021.8317,6.09E-11,199.7315891,-10.345,0,2.964794576,90.00000001 +212.82,50.30085681,-3.059326843,10021.9353,7.50E-11,199.7304773,-10.37,0,2.971820127,90.00000001 +212.83,50.30085681,-3.059298853,10022.0391,8.13E-11,199.7293656,-10.3946875,0,2.978845736,90.00000001 +212.84,50.30085681,-3.059270864,10022.1432,5.00E-11,199.7280308,-10.4184375,0,2.985871287,90.00000001 +212.85,50.30085681,-3.059242875,10022.2475,-1.09E-11,199.7271421,-10.4415625,0,2.992896896,90.00000001 +212.86,50.30085681,-3.059214886,10022.352,-5.78E-11,199.7266994,-10.4653125,0,2.999922447,90.00000001 +212.87,50.30085681,-3.059186897,10022.4568,-7.34E-11,199.7255877,-10.49,0,3.006948055,90.00000001 +212.88,50.30085681,-3.059158908,10022.5618,-7.50E-11,199.723361,-10.515,0,3.013973606,90.00000001 +212.89,50.30085681,-3.05913092,10022.6671,-7.50E-11,199.7211343,-10.54,0,3.020999215,90.00000001 +212.9,50.30085681,-3.059102932,10022.7726,-7.66E-11,199.7200226,-10.565,0,3.028024766,90.00000001 +212.91,50.30085681,-3.059074944,10022.8784,-8.28E-11,199.7195799,-10.59,0,3.035050375,90.00000001 +212.92,50.30085681,-3.059046956,10022.9844,-8.28E-11,199.7186912,-10.6146875,0,3.042075926,90.00000001 +212.93,50.30085681,-3.059018968,10023.0907,-5.00E-11,199.7173565,-10.6384375,0,3.049101534,90.00000001 +212.94,50.30085681,-3.058990981,10023.1972,3.13E-12,199.7162449,-10.661875,0,3.056127085,90.00000001 +212.95,50.30085681,-3.058962993,10023.3039,1.88E-11,199.7149102,-10.686875,0,3.063152694,90.00000001 +212.96,50.30085681,-3.058935006,10023.4109,-4.69E-12,199.7126836,-10.713125,0,3.070178245,90.00000001 +212.97,50.30085681,-3.058907019,10023.5182,-3.12E-12,199.71068,-10.738125,0,3.077203854,90.00000001 +212.98,50.30085681,-3.058879033,10023.6257,3.59E-11,199.7102373,-10.7615625,0,3.084229405,90.00000001 +212.99,50.30085681,-3.058851046,10023.7334,6.88E-11,199.7102407,-10.7853125,0,3.091255013,90.00000001 +213,50.30085681,-3.058823059,10023.8414,8.28E-11,199.7089061,-10.81,0,3.098280564,90.00000001 +213.01,50.30085681,-3.058795073,10023.9496,8.13E-11,199.7066795,-10.8346875,0,3.105306173,90.00000001 +213.02,50.30085681,-3.058767087,10024.0581,4.22E-11,199.7046759,-10.8584375,0,3.112331724,90.00000001 +213.03,50.30085681,-3.058739101,10024.1668,-1.87E-11,199.7031183,-10.881875,0,3.119357333,90.00000001 +213.04,50.30085681,-3.058711116,10024.2757,-3.44E-11,199.7020067,-10.906875,0,3.126382884,90.00000001 +213.05,50.30085681,-3.05868313,10024.3849,-3.12E-12,199.7008951,-10.933125,0,3.133408492,90.00000001 +213.06,50.30085681,-3.058655145,10024.4944,1.56E-12,199.6995606,-10.958125,0,3.140434043,90.00000001 +213.07,50.30085681,-3.05862716,10024.6041,-3.59E-11,199.698449,-10.9815625,0,3.147459652,90.00000001 +213.08,50.30085681,-3.058599175,10024.714,-6.72E-11,199.6971144,-11.0053125,0,3.154485203,90.00000001 +213.09,50.30085681,-3.05857119,10024.8242,-7.50E-11,199.6951109,-11.03,0,3.161510812,90.00000001 +213.1,50.30085681,-3.058543206,10024.9346,-6.56E-11,199.6937764,-11.0546875,0,3.168536363,90.00000001 +213.11,50.30085681,-3.058515222,10025.0453,-2.66E-11,199.6935568,-11.0784375,0,3.175561971,90.00000001 +213.12,50.30085681,-3.058487237,10025.1562,2.66E-11,199.6924453,-11.101875,0,3.182587522,90.00000001 +213.13,50.30085681,-3.058459253,10025.2673,3.59E-11,199.6899958,-11.126875,0,3.189613131,90.00000001 +213.14,50.30085681,-3.05843127,10025.3787,3.13E-12,199.6879923,-11.153125,0,3.196638682,90.00000001 +213.15,50.30085681,-3.058403286,10025.4904,-3.13E-12,199.6866578,-11.178125,0,3.203664291,90.00000001 +213.16,50.30085681,-3.058375303,10025.6023,2.81E-11,199.6853233,-11.2015625,0,3.210689842,90.00000001 +213.17,50.30085681,-3.05834732,10025.7144,5.16E-11,199.6844348,-11.2253125,0,3.21771545,90.00000001 +213.18,50.30085681,-3.058319337,10025.8268,5.94E-11,199.6839923,-11.25,0,3.224741001,90.00000001 +213.19,50.30085681,-3.058291354,10025.9394,6.72E-11,199.6828809,-11.275,0,3.23176661,90.00000001 +213.2,50.30085681,-3.058263371,10026.0523,7.19E-11,199.6806544,-11.3,0,3.238792161,90.00000001 +213.21,50.30085681,-3.058235389,10026.1654,5.78E-11,199.678428,-11.3246875,0,3.24581777,90.00000001 +213.22,50.30085681,-3.058207407,10026.2788,1.25E-11,199.6773165,-11.3484375,0,3.252843321,90.00000001 +213.23,50.30085681,-3.058179425,10026.3924,-3.28E-11,199.6768741,-11.371875,0,3.259868929,90.00000001 +213.24,50.30085681,-3.058151443,10026.5062,-2.03E-11,199.6757626,-11.396875,0,3.266894481,90.00000001 +213.25,50.30085681,-3.058123461,10026.6203,2.50E-11,199.6735362,-11.423125,0,3.273920089,90.00000001 +213.26,50.30085681,-3.05809548,10026.7347,1.72E-11,199.6713098,-11.448125,0,3.28094564,90.00000001 +213.27,50.30085681,-3.058067499,10026.8493,-4.22E-11,199.6701984,-11.4715625,0,3.287971249,90.00000001 +213.28,50.30085681,-3.058039518,10026.9641,-8.13E-11,199.669756,-11.4953125,0,3.2949968,90.00000001 +213.29,50.30085681,-3.058011537,10027.0792,-8.28E-11,199.6686446,-11.52,0,3.302022408,90.00000001 +213.3,50.30085681,-3.057983556,10027.1945,-6.72E-11,199.6664182,-11.5446875,0,3.30904796,90.00000001 +213.31,50.30085681,-3.057955576,10027.3101,-2.66E-11,199.6641918,-11.5684375,0,3.316073568,90.00000001 +213.32,50.30085681,-3.057927596,10027.4259,2.66E-11,199.6630805,-11.591875,0,3.323099119,90.00000001 +213.33,50.30085681,-3.057899616,10027.5419,3.44E-11,199.6626381,-11.616875,0,3.330124728,90.00000001 +213.34,50.30085681,-3.057871636,10027.6582,-4.69E-12,199.6615267,-11.643125,0,3.337150279,90.00000001 +213.35,50.30085681,-3.057843656,10027.7748,-1.72E-11,199.6593004,-11.668125,0,3.344175887,90.00000001 +213.36,50.30085681,-3.057815677,10027.8916,2.19E-11,199.6570741,-11.6915625,0,3.351201439,90.00000001 +213.37,50.30085681,-3.057787698,10028.0086,6.72E-11,199.6559627,-11.7153125,0,3.358227047,90.00000001 +213.38,50.30085681,-3.057759719,10028.1259,8.91E-11,199.6555204,-11.74,0,3.365252598,90.00000001 +213.39,50.30085681,-3.05773174,10028.2434,8.13E-11,199.6544091,-11.7646875,0,3.372278207,90.00000001 +213.4,50.30085681,-3.057703761,10028.3612,3.59E-11,199.6521828,-11.7884375,0,3.379303758,90.00000001 +213.41,50.30085681,-3.057675783,10028.4792,-1.56E-11,199.6499565,-11.811875,0,3.386329366,90.00000001 +213.42,50.30085681,-3.057647805,10028.5974,-1.09E-11,199.6488452,-11.836875,0,3.393354918,90.00000001 +213.43,50.30085681,-3.057619827,10028.7159,3.44E-11,199.6484029,-11.863125,0,3.400380526,90.00000001 +213.44,50.30085681,-3.057591849,10028.8347,3.28E-11,199.6472916,-11.888125,0,3.407406077,90.00000001 +213.45,50.30085681,-3.057563871,10028.9537,-2.66E-11,199.6450653,-11.9115625,0,3.414431686,90.00000001 +213.46,50.30085681,-3.057535894,10029.0729,-7.19E-11,199.6428391,-11.9353125,0,3.421457237,90.00000001 +213.47,50.30085681,-3.057507917,10029.1924,-7.34E-11,199.6417278,-11.96,0,3.428482845,90.00000001 +213.48,50.30085681,-3.05747994,10029.3121,-6.09E-11,199.6412856,-11.985,0,3.435508397,90.00000001 +213.49,50.30085681,-3.057451963,10029.4321,-5.94E-11,199.6401743,-12.01,0,3.442534005,90.00000001 +213.5,50.30085681,-3.057423986,10029.5523,-5.78E-11,199.6379481,-12.0346875,0,3.449559556,90.00000001 +213.51,50.30085681,-3.05739601,10029.6728,-2.66E-11,199.6357219,-12.0584375,0,3.456585165,90.00000001 +213.52,50.30085681,-3.057368034,10029.7935,1.72E-11,199.6343877,-12.081875,0,3.463610716,90.00000001 +213.53,50.30085681,-3.057340058,10029.9144,1.09E-11,199.6332764,-12.106875,0,3.470636324,90.00000001 +213.54,50.30085681,-3.057312082,10030.0356,-3.44E-11,199.6319422,-12.133125,0,3.477661876,90.00000001 +213.55,50.30085681,-3.057284107,10030.1571,-3.28E-11,199.630608,-12.158125,0,3.484687484,90.00000001 +213.56,50.30085681,-3.057256131,10030.2788,2.66E-11,199.6286049,-12.1815625,0,3.491713035,90.00000001 +213.57,50.30085681,-3.057228156,10030.4007,7.34E-11,199.6261557,-12.2053125,0,3.498738644,90.00000001 +213.58,50.30085681,-3.057200182,10030.5229,8.28E-11,199.6250445,-12.23,0,3.505764195,90.00000001 +213.59,50.30085681,-3.057172207,10030.6453,7.50E-11,199.6248253,-12.2546875,0,3.512789803,90.00000001 +213.6,50.30085681,-3.057144232,10030.768,4.37E-11,199.6234912,-12.2784375,0,3.519815355,90.00000001 +213.61,50.30085681,-3.057116258,10030.8909,-1.57E-12,199.621488,-12.301875,0,3.526840906,90.00000001 +213.62,50.30085681,-3.057088284,10031.014,-3.13E-12,199.6201539,-12.326875,0,3.533866514,90.00000001 +213.63,50.30085681,-3.05706031,10031.1374,3.59E-11,199.6188198,-12.353125,0,3.540892065,90.00000001 +213.64,50.30085681,-3.057032336,10031.2611,3.28E-11,199.6165936,-12.378125,0,3.547917674,90.00000001 +213.65,50.30085681,-3.057004363,10031.385,-2.81E-11,199.6143675,-12.4015625,0,3.554943225,90.00000001 +213.66,50.30085681,-3.05697639,10031.5091,-8.13E-11,199.6130334,-12.4253125,0,3.561968834,90.00000001 +213.67,50.30085681,-3.056948417,10031.6335,-9.84E-11,199.6119223,-12.45,0,3.568994385,90.00000001 +213.68,50.30085681,-3.056920444,10031.7581,-9.06E-11,199.6105882,-12.4746875,0,3.576019993,90.00000001 +213.69,50.30085681,-3.056892472,10031.883,-5.16E-11,199.6094771,-12.4984375,0,3.583045544,90.00000001 +213.7,50.30085681,-3.056864499,10032.0081,1.56E-12,199.608366,-12.521875,0,3.590071153,90.00000001 +213.71,50.30085681,-3.056836527,10032.1334,1.09E-11,199.606809,-12.546875,0,3.597096704,90.00000001 +213.72,50.30085681,-3.056808555,10032.259,-2.03E-11,199.6048059,-12.573125,0,3.604122313,90.00000001 +213.73,50.30085681,-3.056780583,10032.3849,-1.72E-11,199.6023568,-12.598125,0,3.611147864,90.00000001 +213.74,50.30085681,-3.056752612,10032.511,3.59E-11,199.6001308,-12.6215625,0,3.618173472,90.00000001 +213.75,50.30085681,-3.056724641,10032.6373,8.28E-11,199.5990198,-12.6453125,0,3.625199023,90.00000001 +213.76,50.30085681,-3.05669667,10032.7639,9.84E-11,199.5985777,-12.67,0,3.632224632,90.00000001 +213.77,50.30085681,-3.056668699,10032.8907,1.00E-10,199.5974667,-12.695,0,3.639250183,90.00000001 +213.78,50.30085681,-3.056640728,10033.0178,9.84E-11,199.5952407,-12.72,0,3.646275792,90.00000001 +213.79,50.30085681,-3.056612758,10033.1451,8.28E-11,199.5930147,-12.7446875,0,3.653301343,90.00000001 +213.8,50.30085681,-3.056584788,10033.2727,3.75E-11,199.5916807,-12.7684375,0,3.660326951,90.00000001 +213.81,50.30085681,-3.056556818,10033.4005,-1.72E-11,199.5903466,-12.7915625,0,3.667352503,90.00000001 +213.82,50.30085681,-3.056528848,10033.5285,-4.22E-11,199.5881207,-12.8153125,0,3.674378111,90.00000001 +213.83,50.30085681,-3.056500879,10033.6568,-3.44E-11,199.5858947,-12.8403125,0,3.681403662,90.00000001 +213.84,50.30085681,-3.05647291,10033.7853,4.69E-12,199.5847837,-12.86625,0,3.688429271,90.00000001 +213.85,50.30085681,-3.056444941,10033.9141,8.59E-11,199.5845647,-12.891875,0,3.695454822,90.00000001 +213.86,50.30085681,-3.056416972,10034.0432,1.78E-10,199.5841228,-12.91625,0,3.70248043,90.00000001 +213.87,50.30085681,-3.056389003,10034.1724,2.23E-10,199.5823428,-12.94,0,3.709505982,90.00000001 +213.88,50.30085681,-3.056361034,10034.302,1.91E-10,199.5796709,-12.96375,0,3.71653159,90.00000001 +213.89,50.30085681,-3.056333067,10034.4317,9.06E-11,199.5776679,-12.988125,0,3.723557141,90.00000001 +213.9,50.30085681,-3.056305098,10034.5617,-9.37E-12,199.576334,-13.0134375,0,3.73058275,90.00000001 +213.91,50.30085681,-3.056277131,10034.692,-3.28E-11,199.5747771,-13.038125,0,3.737608301,90.00000001 +213.92,50.30085681,-3.056249163,10034.8225,1.25E-11,199.5729972,-13.0615625,0,3.744633909,90.00000001 +213.93,50.30085681,-3.056221196,10034.9532,5.94E-11,199.5712173,-13.0853125,0,3.751659461,90.00000001 +213.94,50.30085681,-3.056193229,10035.0842,8.12E-11,199.5694374,-13.11,0,3.758685069,90.00000001 +213.95,50.30085681,-3.056165262,10035.2154,9.06E-11,199.5678805,-13.135,0,3.76571062,90.00000001 +213.96,50.30085681,-3.056137296,10035.3469,8.91E-11,199.5667696,-13.16,0,3.772736229,90.00000001 +213.97,50.30085681,-3.056109329,10035.4786,7.50E-11,199.5656587,-13.185,0,3.77976178,90.00000001 +213.98,50.30085681,-3.056081363,10035.6106,5.94E-11,199.5641019,-13.21,0,3.786787388,90.00000001 +213.99,50.30085681,-3.056053397,10035.7428,4.38E-11,199.562099,-13.2346875,0,3.79381294,90.00000001 +214,50.30085681,-3.056025431,10035.8753,1.09E-11,199.5596502,-13.2584375,0,3.800838548,90.00000001 +214.01,50.30085681,-3.055997466,10036.008,-3.59E-11,199.5574243,-13.2815625,0,3.807864099,90.00000001 +214.02,50.30085681,-3.055969501,10036.1409,-6.72E-11,199.5560905,-13.3053125,0,3.814889708,90.00000001 +214.03,50.30085681,-3.055941536,10036.2741,-7.50E-11,199.5549796,-13.33,0,3.821915259,90.00000001 +214.04,50.30085681,-3.055913571,10036.4075,-7.50E-11,199.5536458,-13.355,0,3.828940867,90.00000001 +214.05,50.30085681,-3.055885607,10036.5412,-7.50E-11,199.552535,-13.38,0,3.835966419,90.00000001 +214.06,50.30085681,-3.055857642,10036.6751,-7.66E-11,199.5512012,-13.405,0,3.842992027,90.00000001 +214.07,50.30085681,-3.055829678,10036.8093,-8.28E-11,199.5489754,-13.43,0,3.850017578,90.00000001 +214.08,50.30085681,-3.055801714,10036.9437,-8.28E-11,199.5467496,-13.4546875,0,3.857043187,90.00000001 +214.09,50.30085681,-3.055773751,10037.0784,-5.00E-11,199.5454158,-13.4784375,0,3.864068738,90.00000001 +214.1,50.30085681,-3.055745787,10037.2133,1.09E-11,199.544082,-13.5015625,0,3.871094346,90.00000001 +214.11,50.30085681,-3.055717824,10037.3484,5.62E-11,199.5418563,-13.5253125,0,3.878119898,90.00000001 +214.12,50.30085681,-3.055689861,10037.4838,6.56E-11,199.5396305,-13.55,0,3.885145506,90.00000001 +214.13,50.30085681,-3.055661899,10037.6194,6.09E-11,199.5382968,-13.575,0,3.892171057,90.00000001 +214.14,50.30085681,-3.055633936,10037.7553,6.72E-11,199.537186,-13.6,0,3.899196666,90.00000001 +214.15,50.30085681,-3.055605974,10037.8914,8.28E-11,199.5356293,-13.625,0,3.906222217,90.00000001 +214.16,50.30085681,-3.055578012,10038.0278,8.91E-11,199.5338495,-13.65,0,3.913247825,90.00000001 +214.17,50.30085681,-3.05555005,10038.1644,7.50E-11,199.5320698,-13.6746875,0,3.920273377,90.00000001 +214.18,50.30085681,-3.055522089,10038.3013,3.59E-11,199.5300671,-13.6984375,0,3.927298985,90.00000001 +214.19,50.30085681,-3.055494127,10038.4384,-1.09E-11,199.5278414,-13.721875,0,3.934324536,90.00000001 +214.2,50.30085681,-3.055466167,10038.5757,-1.09E-11,199.5262847,-13.7465625,0,3.941350145,90.00000001 +214.21,50.30085681,-3.055438206,10038.7133,6.09E-11,199.525397,-13.771875,0,3.948375696,90.00000001 +214.22,50.30085681,-3.055410245,10038.8512,1.53E-10,199.5238403,-13.79625,0,3.955401304,90.00000001 +214.23,50.30085681,-3.055382285,10038.9892,2.08E-10,199.5218376,-13.8203125,0,3.962426856,90.00000001 +214.24,50.30085681,-3.055354325,10039.1276,2.23E-10,199.520504,-13.845,0,3.969452464,90.00000001 +214.25,50.30085681,-3.055326365,10039.2661,2.16E-10,199.5191703,-13.8696875,0,3.976478015,90.00000001 +214.26,50.30085681,-3.055298405,10039.405,1.67E-10,199.5169446,-13.89375,0,3.983503624,90.00000001 +214.27,50.30085681,-3.055270446,10039.544,6.72E-11,199.514719,-13.918125,0,3.990529175,90.00000001 +214.28,50.30085681,-3.055242487,10039.6833,-2.66E-11,199.5133853,-13.9434375,0,3.997554783,90.00000001 +214.29,50.30085681,-3.055214528,10039.8229,-4.22E-11,199.5120517,-13.968125,0,4.004580335,90.00000001 +214.3,50.30085681,-3.055186569,10039.9627,3.12E-12,199.5098261,-13.9915625,0,4.011605943,90.00000001 +214.31,50.30085681,-3.055158611,10040.1027,4.22E-11,199.5076005,-14.0153125,0,4.018631494,90.00000001 +214.32,50.30085681,-3.055130653,10040.243,5.78E-11,199.5062669,-14.04,0,4.025657103,90.00000001 +214.33,50.30085681,-3.055102695,10040.3835,6.72E-11,199.5051563,-14.065,0,4.032682654,90.00000001 +214.34,50.30085681,-3.055074737,10040.5243,7.34E-11,199.5038227,-14.09,0,4.039708262,90.00000001 +214.35,50.30085681,-3.05504678,10040.6653,6.56E-11,199.5024891,-14.1146875,0,4.046733814,90.00000001 +214.36,50.30085681,-3.055018822,10040.8066,2.81E-11,199.5004865,-14.1384375,0,4.053759422,90.00000001 +214.37,50.30085681,-3.054990865,10040.9481,-1.72E-11,199.4978149,-14.161875,0,4.060784973,90.00000001 +214.38,50.30085681,-3.054962909,10041.0898,-1.09E-11,199.4958124,-14.186875,0,4.067810582,90.00000001 +214.39,50.30085681,-3.054934952,10041.2318,3.59E-11,199.4944788,-14.213125,0,4.074836133,90.00000001 +214.4,50.30085681,-3.054906996,10041.3741,4.22E-11,199.4929223,-14.238125,0,4.081861741,90.00000001 +214.41,50.30085681,-3.05487904,10041.5166,-3.12E-12,199.4909197,-14.2615625,0,4.088887293,90.00000001 +214.42,50.30085681,-3.054851084,10041.6593,-4.22E-11,199.4884712,-14.2853125,0,4.095912901,90.00000001 +214.43,50.30085681,-3.054823129,10041.8023,-5.78E-11,199.4862457,-14.31,0,4.102938452,90.00000001 +214.44,50.30085681,-3.054795174,10041.9455,-5.78E-11,199.4849121,-14.3346875,0,4.109964061,90.00000001 +214.45,50.30085681,-3.054767219,10042.089,-2.66E-11,199.4835786,-14.3584375,0,4.116989612,90.00000001 +214.46,50.30085681,-3.054739264,10042.2327,1.72E-11,199.4815761,-14.381875,0,4.12401522,90.00000001 +214.47,50.30085681,-3.05471131,10042.3766,1.56E-12,199.4802426,-14.4065625,0,4.131040772,90.00000001 +214.48,50.30085681,-3.054683356,10042.5208,-9.06E-11,199.4800241,-14.431875,0,4.13806638,90.00000001 +214.49,50.30085681,-3.054655401,10042.6653,-1.83E-10,199.4786906,-14.45625,0,4.145091931,90.00000001 +214.5,50.30085681,-3.054627447,10042.8099,-2.16E-10,199.4753502,-14.4803125,0,4.15211754,90.00000001 +214.51,50.30085681,-3.054599494,10042.9549,-2.09E-10,199.4722327,-14.505,0,4.159143091,90.00000001 +214.52,50.30085681,-3.054571541,10043.1,-1.94E-10,199.4708993,-14.5296875,0,4.1661687,90.00000001 +214.53,50.30085681,-3.054543588,10043.2455,-1.52E-10,199.4702348,-14.55375,0,4.173194251,90.00000001 +214.54,50.30085681,-3.054515635,10043.3911,-6.72E-11,199.4684554,-14.578125,0,4.180219859,90.00000001 +214.55,50.30085681,-3.054487682,10043.537,1.09E-11,199.4657839,-14.6034375,0,4.18724541,90.00000001 +214.56,50.30085681,-3.054459731,10043.6832,1.88E-11,199.4637815,-14.628125,0,4.194271019,90.00000001 +214.57,50.30085681,-3.054431778,10043.8296,-1.72E-11,199.4624481,-14.651875,0,4.20129657,90.00000001 +214.58,50.30085681,-3.054403827,10043.9762,-1.56E-12,199.4608917,-14.6765625,0,4.208322179,90.00000001 +214.59,50.30085681,-3.054375875,10044.1231,9.06E-11,199.4591123,-14.701875,0,4.21534773,90.00000001 +214.6,50.30085681,-3.054347924,10044.2703,1.83E-10,199.4573329,-14.72625,0,4.222373338,90.00000001 +214.61,50.30085681,-3.054319973,10044.4176,2.08E-10,199.4553305,-14.75,0,4.229398889,90.00000001 +214.62,50.30085681,-3.054292022,10044.5653,1.62E-10,199.4528821,-14.77375,0,4.236424441,90.00000001 +214.63,50.30085681,-3.054264072,10044.7131,7.66E-11,199.4506567,-14.798125,0,4.243450049,90.00000001 +214.64,50.30085681,-3.054236122,10044.8612,4.69E-12,199.4495463,-14.8234375,0,4.2504756,90.00000001 +214.65,50.30085681,-3.054208172,10045.0096,-3.13E-12,199.449105,-14.848125,0,4.257501209,90.00000001 +214.66,50.30085681,-3.054180222,10045.1582,2.66E-11,199.4477716,-14.871875,0,4.26452676,90.00000001 +214.67,50.30085681,-3.054152272,10045.307,1.25E-11,199.4446543,-14.8965625,0,4.271552368,90.00000001 +214.68,50.30085681,-3.054124323,10045.4561,-6.72E-11,199.441314,-14.921875,0,4.27857792,90.00000001 +214.69,50.30085681,-3.054096375,10045.6055,-1.53E-10,199.4399806,-14.94625,0,4.285603528,90.00000001 +214.7,50.30085681,-3.054068426,10045.755,-1.92E-10,199.4397623,-14.97,0,4.292629079,90.00000001 +214.71,50.30085681,-3.054040477,10045.9049,-1.67E-10,199.438206,-14.99375,0,4.299654688,90.00000001 +214.72,50.30085681,-3.054012529,10046.0549,-8.12E-11,199.4353117,-15.018125,0,4.306680239,90.00000001 +214.73,50.30085681,-3.053984581,10046.2052,2.03E-11,199.4328634,-15.04375,0,4.313705847,90.00000001 +214.74,50.30085681,-3.053956634,10046.3558,8.91E-11,199.4315301,-15.069375,0,4.320731399,90.00000001 +214.75,50.30085681,-3.053928686,10046.5066,1.38E-10,199.4301968,-15.0934375,0,4.327757007,90.00000001 +214.76,50.30085681,-3.053900739,10046.6577,1.77E-10,199.4277485,-15.116875,0,4.334782558,90.00000001 +214.77,50.30085681,-3.053872792,10046.8089,1.61E-10,199.4246313,-15.1415625,0,4.341808167,90.00000001 +214.78,50.30085681,-3.053844846,10046.9605,8.28E-11,199.422183,-15.1665625,0,4.348833718,90.00000001 +214.79,50.30085681,-3.0538169,10047.1123,2.97E-11,199.4210727,-15.19,0,4.355859326,90.00000001 +214.8,50.30085681,-3.053788954,10047.2643,6.72E-11,199.4206315,-15.2134375,0,4.362884878,90.00000001 +214.81,50.30085681,-3.053761008,10047.4165,1.36E-10,199.4195212,-15.2384375,0,4.369910486,90.00000001 +214.82,50.30085681,-3.053733062,10047.5691,1.34E-10,199.417296,-15.2634375,0,4.376936037,90.00000001 +214.83,50.30085681,-3.053705117,10047.7218,5.16E-11,199.4148478,-15.288125,0,4.383961646,90.00000001 +214.84,50.30085681,-3.053677172,10047.8748,-2.66E-11,199.4128456,-15.3134375,0,4.390987197,90.00000001 +214.85,50.30085681,-3.053649227,10048.0281,-2.81E-11,199.4112894,-15.338125,0,4.398012805,90.00000001 +214.86,50.30085681,-3.053621283,10048.1816,1.72E-11,199.4101792,-15.3615625,0,4.405038357,90.00000001 +214.87,50.30085681,-3.053593338,10048.3353,4.22E-11,199.408846,-15.3853125,0,4.412063965,90.00000001 +214.88,50.30085681,-3.053565394,10048.4893,4.38E-11,199.4063978,-15.41,0,4.419089516,90.00000001 +214.89,50.30085681,-3.05353745,10048.6435,4.22E-11,199.4032806,-15.4346875,0,4.426115125,90.00000001 +214.9,50.30085681,-3.053509507,10048.798,1.72E-11,199.4008324,-15.4584375,0,4.433140676,90.00000001 +214.91,50.30085681,-3.053481564,10048.9527,-2.81E-11,199.3994993,-15.481875,0,4.440166284,90.00000001 +214.92,50.30085681,-3.053453621,10049.1076,-3.59E-11,199.3981661,-15.506875,0,4.447191836,90.00000001 +214.93,50.30085681,-3.053425678,10049.2628,-3.12E-12,199.395941,-15.533125,0,4.454217444,90.00000001 +214.94,50.30085681,-3.053397736,10049.4183,3.13E-12,199.3937158,-15.558125,0,4.461242995,90.00000001 +214.95,50.30085681,-3.053369794,10049.574,-2.81E-11,199.3923827,-15.5815625,0,4.468268604,90.00000001 +214.96,50.30085681,-3.053341852,10049.7299,-5.16E-11,199.3910496,-15.6053125,0,4.475294155,90.00000001 +214.97,50.30085681,-3.05331391,10049.8861,-5.94E-11,199.3886014,-15.63,0,4.482319763,90.00000001 +214.98,50.30085681,-3.053285969,10050.0425,-6.87E-11,199.3854843,-15.655,0,4.489345315,90.00000001 +214.99,50.30085681,-3.053258028,10050.1992,-8.12E-11,199.3832592,-15.68,0,4.496370923,90.00000001 +215,50.30085681,-3.053230088,10050.3561,-8.12E-11,199.3825951,-15.7046875,0,4.503396474,90.00000001 +215.01,50.30085681,-3.053202147,10050.5133,-4.22E-11,199.381708,-15.7284375,0,4.510422083,90.00000001 +215.02,50.30085681,-3.053174206,10050.6707,2.81E-11,199.379037,-15.7515625,0,4.517447634,90.00000001 +215.03,50.30085681,-3.053146267,10050.8283,8.13E-11,199.3759199,-15.7753125,0,4.524473242,90.00000001 +215.04,50.30085681,-3.053118327,10050.9862,8.75E-11,199.3736948,-15.8003125,0,4.531498794,90.00000001 +215.05,50.30085681,-3.053090388,10051.1443,3.59E-11,199.3721388,-15.82625,0,4.538524402,90.00000001 +215.06,50.30085681,-3.053062449,10051.3027,-5.78E-11,199.3710287,-15.8515625,0,4.545549953,90.00000001 +215.07,50.30085681,-3.05303451,10051.4614,-1.11E-10,199.3696957,-15.875,0,4.552575562,90.00000001 +215.08,50.30085681,-3.053006571,10051.6202,-6.56E-11,199.3674706,-15.8984375,0,4.559601113,90.00000001 +215.09,50.30085681,-3.052978633,10051.7793,9.37E-12,199.3650226,-15.9234375,0,4.566626722,90.00000001 +215.1,50.30085681,-3.052950695,10051.9387,1.88E-11,199.3630206,-15.948125,0,4.573652273,90.00000001 +215.11,50.30085681,-3.052922757,10052.0983,-1.72E-11,199.3614646,-15.971875,0,4.580677881,90.00000001 +215.12,50.30085681,-3.05289482,10052.2581,-1.09E-11,199.3601316,-15.996875,0,4.587703432,90.00000001 +215.13,50.30085681,-3.052866882,10052.4182,3.59E-11,199.3581296,-16.023125,0,4.594729041,90.00000001 +215.14,50.30085681,-3.052838945,10052.5786,4.06E-11,199.3552356,-16.048125,0,4.601754592,90.00000001 +215.15,50.30085681,-3.052811009,10052.7392,-1.09E-11,199.3525646,-16.0715625,0,4.608780201,90.00000001 +215.16,50.30085681,-3.052783072,10052.9,-4.84E-11,199.3507856,-16.095,0,4.615805752,90.00000001 +215.17,50.30085681,-3.052755137,10053.0611,-2.66E-11,199.3494527,-16.1184375,0,4.62283136,90.00000001 +215.18,50.30085681,-3.0527272,10053.2224,1.87E-11,199.3474507,-16.141875,0,4.629856911,90.00000001 +215.19,50.30085681,-3.052699265,10053.3839,1.87E-11,199.3447798,-16.166875,0,4.63688252,90.00000001 +215.2,50.30085681,-3.05267133,10053.5457,-1.88E-11,199.3427778,-16.193125,0,4.643908071,90.00000001 +215.21,50.30085681,-3.052643395,10053.7078,-1.72E-11,199.3414449,-16.218125,0,4.65093368,90.00000001 +215.22,50.30085681,-3.05261546,10053.8701,3.59E-11,199.3398889,-16.2415625,0,4.657959231,90.00000001 +215.23,50.30085681,-3.052587526,10054.0326,8.28E-11,199.337887,-16.2653125,0,4.664984839,90.00000001 +215.24,50.30085681,-3.052559591,10054.1954,9.84E-11,199.3354391,-16.29,0,4.67201039,90.00000001 +215.25,50.30085681,-3.052531658,10054.3584,1.00E-10,199.3329912,-16.315,0,4.679035999,90.00000001 +215.26,50.30085681,-3.052503724,10054.5217,9.84E-11,199.3309893,-16.34,0,4.68606155,90.00000001 +215.27,50.30085681,-3.052475791,10054.6852,8.28E-11,199.3294334,-16.3646875,0,4.693087159,90.00000001 +215.28,50.30085681,-3.052447858,10054.849,3.59E-11,199.3283235,-16.3884375,0,4.70011271,90.00000001 +215.29,50.30085681,-3.052419925,10055.013,-2.66E-11,199.3267676,-16.4115625,0,4.707138318,90.00000001 +215.3,50.30085681,-3.052391992,10055.1772,-6.56E-11,199.3236508,-16.4353125,0,4.714163869,90.00000001 +215.31,50.30085681,-3.05236406,10055.3417,-7.34E-11,199.3200879,-16.46,0,4.721189478,90.00000001 +215.32,50.30085681,-3.052336129,10055.5064,-6.72E-11,199.3178631,-16.485,0,4.728215029,90.00000001 +215.33,50.30085681,-3.052308197,10055.6714,-5.78E-11,199.3165302,-16.51,0,4.735240638,90.00000001 +215.34,50.30085681,-3.052280266,10055.8366,-5.16E-11,199.3151974,-16.535,0,4.742266189,90.00000001 +215.35,50.30085681,-3.052252335,10056.0021,-5.00E-11,199.3140875,-16.56,0,4.749291797,90.00000001 +215.36,50.30085681,-3.052224404,10056.1678,-4.22E-11,199.3125317,-16.5846875,0,4.756317348,90.00000001 +215.37,50.30085681,-3.052196473,10056.3338,-1.09E-11,199.3094149,-16.6084375,0,4.763342957,90.00000001 +215.38,50.30085681,-3.052168543,10056.5,2.66E-11,199.3060751,-16.631875,0,4.770368508,90.00000001 +215.39,50.30085681,-3.052140614,10056.6664,1.09E-11,199.3047423,-16.6565625,0,4.777394117,90.00000001 +215.4,50.30085681,-3.052112684,10056.8331,-7.50E-11,199.3043015,-16.681875,0,4.784419668,90.00000001 +215.41,50.30085681,-3.052084754,10057.0001,-1.69E-10,199.3020767,-16.70625,0,4.791445276,90.00000001 +215.42,50.30085681,-3.052056825,10057.1672,-2.08E-10,199.2987369,-16.73,0,4.798470827,90.00000001 +215.43,50.30085681,-3.052028897,10057.3347,-1.77E-10,199.2965122,-16.75375,0,4.805496436,90.00000001 +215.44,50.30085681,-3.052000968,10057.5023,-9.22E-11,199.2949564,-16.778125,0,4.812521987,90.00000001 +215.45,50.30085681,-3.05197304,10057.6702,-4.69E-12,199.2927316,-16.80375,0,4.819547596,90.00000001 +215.46,50.30085681,-3.051945112,10057.8384,5.00E-11,199.2905069,-16.829375,0,4.826573147,90.00000001 +215.47,50.30085681,-3.051917185,10058.0068,9.84E-11,199.2891741,-16.8534375,0,4.833598755,90.00000001 +215.48,50.30085681,-3.051889257,10058.1755,1.52E-10,199.2878414,-16.876875,0,4.840624306,90.00000001 +215.49,50.30085681,-3.05186133,10058.3443,1.52E-10,199.2853937,-16.9015625,0,4.847649915,90.00000001 +215.5,50.30085681,-3.051833403,10058.5135,7.34E-11,199.282277,-16.926875,0,4.854675466,90.00000001 +215.51,50.30085681,-3.051805477,10058.6829,-1.87E-11,199.2798293,-16.95125,0,4.861701075,90.00000001 +215.52,50.30085681,-3.051777551,10058.8525,-5.78E-11,199.2784966,-16.975,0,4.868726626,90.00000001 +215.53,50.30085681,-3.051749625,10059.0224,-3.59E-11,199.2771638,-16.9984375,0,4.875752234,90.00000001 +215.54,50.30085681,-3.051721699,10059.1925,1.56E-12,199.2747162,-17.021875,0,4.882777785,90.00000001 +215.55,50.30085681,-3.051693774,10059.3628,-4.69E-12,199.2715995,-17.046875,0,4.889803394,90.00000001 +215.56,50.30085681,-3.051665849,10059.5334,-4.38E-11,199.2689288,-17.073125,0,4.896828945,90.00000001 +215.57,50.30085681,-3.051637925,10059.7043,-4.22E-11,199.2669272,-17.098125,0,4.903854554,90.00000001 +215.58,50.30085681,-3.05161,10059.8754,1.09E-11,199.2653715,-17.1215625,0,4.910880105,90.00000001 +215.59,50.30085681,-3.051582077,10060.0467,5.78E-11,199.2640388,-17.1453125,0,4.917905713,90.00000001 +215.6,50.30085681,-3.051554152,10060.2183,7.34E-11,199.2620372,-17.17,0,4.924931265,90.00000001 +215.61,50.30085681,-3.051526229,10060.3901,6.56E-11,199.2593666,-17.1946875,0,4.931956873,90.00000001 +215.62,50.30085681,-3.051498306,10060.5622,2.81E-11,199.2573649,-17.2184375,0,4.938982424,90.00000001 +215.63,50.30085681,-3.051470383,10060.7345,-1.72E-11,199.2558093,-17.241875,0,4.946007975,90.00000001 +215.64,50.30085681,-3.05144246,10060.907,-1.09E-11,199.2533617,-17.266875,0,4.953033584,90.00000001 +215.65,50.30085681,-3.051414538,10061.0798,3.59E-11,199.2502451,-17.293125,0,4.960059135,90.00000001 +215.66,50.30085681,-3.051386616,10061.2529,4.06E-11,199.2477975,-17.318125,0,4.967084744,90.00000001 +215.67,50.30085681,-3.051358695,10061.4262,-1.25E-11,199.2464649,-17.3415625,0,4.974110295,90.00000001 +215.68,50.30085681,-3.051330773,10061.5997,-6.56E-11,199.2451323,-17.3653125,0,4.981135903,90.00000001 +215.69,50.30085681,-3.051302852,10061.7735,-8.91E-11,199.2426847,-17.39,0,4.988161454,90.00000001 +215.7,50.30085681,-3.051274931,10061.9475,-8.12E-11,199.2397912,-17.4146875,0,4.995187063,90.00000001 +215.71,50.30085681,-3.051247011,10062.1218,-3.59E-11,199.2380126,-17.4384375,0,5.002212614,90.00000001 +215.72,50.30085681,-3.051219091,10062.2963,1.56E-11,199.236903,-17.461875,0,5.009238223,90.00000001 +215.73,50.30085681,-3.05119117,10062.471,1.09E-11,199.2346785,-17.486875,0,5.016263774,90.00000001 +215.74,50.30085681,-3.051163251,10062.646,-3.44E-11,199.232008,-17.513125,0,5.023289382,90.00000001 +215.75,50.30085681,-3.051135332,10062.8213,-3.28E-11,199.2302294,-17.538125,0,5.030314933,90.00000001 +215.76,50.30085681,-3.051107412,10062.9968,2.66E-11,199.2282279,-17.5615625,0,5.037340542,90.00000001 +215.77,50.30085681,-3.051079494,10063.1725,7.19E-11,199.2251114,-17.5853125,0,5.044366093,90.00000001 +215.78,50.30085681,-3.051051575,10063.3485,7.34E-11,199.2219949,-17.61,0,5.051391702,90.00000001 +215.79,50.30085681,-3.051023658,10063.5247,5.16E-11,199.2202164,-17.6346875,0,5.058417253,90.00000001 +215.8,50.30085681,-3.05099574,10063.7012,1.25E-11,199.2193299,-17.6584375,0,5.065442861,90.00000001 +215.81,50.30085681,-3.050967822,10063.8779,-2.66E-11,199.2175514,-17.681875,0,5.072468412,90.00000001 +215.82,50.30085681,-3.050939905,10064.0548,-1.09E-11,199.2144349,-17.7065625,0,5.079494021,90.00000001 +215.83,50.30085681,-3.050911988,10064.232,7.66E-11,199.2113185,-17.731875,0,5.086519572,90.00000001 +215.84,50.30085681,-3.050884072,10064.4095,1.77E-10,199.20954,-17.75625,0,5.093545181,90.00000001 +215.85,50.30085681,-3.050856156,10064.5871,2.31E-10,199.2084305,-17.7803125,0,5.100570732,90.00000001 +215.86,50.30085681,-3.050828239,10064.7651,2.39E-10,199.2059831,-17.805,0,5.10759634,90.00000001 +215.87,50.30085681,-3.050800324,10064.9432,2.17E-10,199.2028666,-17.8296875,0,5.114621891,90.00000001 +215.88,50.30085681,-3.050772409,10065.1217,1.62E-10,199.2013112,-17.85375,0,5.1216475,90.00000001 +215.89,50.30085681,-3.050744494,10065.3003,7.66E-11,199.2002018,-17.878125,0,5.128673051,90.00000001 +215.9,50.30085681,-3.050716578,10065.4792,4.69E-12,199.1977544,-17.9034375,0,5.13569866,90.00000001 +215.91,50.30085681,-3.050688665,10065.6584,-3.13E-12,199.195307,-17.928125,0,5.142724211,90.00000001 +215.92,50.30085681,-3.05066075,10065.8378,3.59E-11,199.1933055,-17.9515625,0,5.149749819,90.00000001 +215.93,50.30085681,-3.050632836,10066.0174,6.87E-11,199.1904122,-17.9753125,0,5.15677537,90.00000001 +215.94,50.30085681,-3.050604923,10066.1973,8.28E-11,199.1875188,-18,0,5.163800979,90.00000001 +215.95,50.30085681,-3.05057701,10066.3774,9.06E-11,199.1859634,-18.025,0,5.17082653,90.00000001 +215.96,50.30085681,-3.050549097,10066.5578,8.91E-11,199.184631,-18.05,0,5.177852139,90.00000001 +215.97,50.30085681,-3.050521184,10066.7384,6.72E-11,199.1824066,-18.0746875,0,5.18487769,90.00000001 +215.98,50.30085681,-3.050493272,10066.9193,2.19E-11,199.1799593,-18.0984375,0,5.191903298,90.00000001 +215.99,50.30085681,-3.05046536,10067.1004,-1.72E-11,199.1777349,-18.121875,0,5.198928849,90.00000001 +216,50.30085681,-3.050437448,10067.2817,-4.69E-12,199.1750646,-18.146875,0,5.205954458,90.00000001 +216.01,50.30085681,-3.050409537,10067.4633,3.44E-11,199.1719483,-18.173125,0,5.212980009,90.00000001 +216.02,50.30085681,-3.050381626,10067.6452,2.66E-11,199.1695009,-18.198125,0,5.220005618,90.00000001 +216.03,50.30085681,-3.050353716,10067.8273,-2.66E-11,199.1681686,-18.2215625,0,5.227031169,90.00000001 +216.04,50.30085681,-3.050325805,10068.0096,-5.78E-11,199.1668363,-18.245,0,5.234056777,90.00000001 +216.05,50.30085681,-3.050297895,10068.1922,-3.59E-11,199.164389,-18.2684375,0,5.241082328,90.00000001 +216.06,50.30085681,-3.050269985,10068.375,3.13E-12,199.1612727,-18.291875,0,5.248107937,90.00000001 +216.07,50.30085681,-3.050242076,10068.558,4.69E-12,199.1586024,-18.316875,0,5.255133488,90.00000001 +216.08,50.30085681,-3.050214167,10068.7413,-2.03E-11,199.1563781,-18.343125,0,5.262159097,90.00000001 +216.09,50.30085681,-3.050186258,10068.9249,-1.25E-11,199.1539308,-18.368125,0,5.269184648,90.00000001 +216.1,50.30085681,-3.05015835,10069.1087,2.66E-11,199.1517066,-18.3915625,0,5.276210256,90.00000001 +216.11,50.30085681,-3.050130442,10069.2927,5.16E-11,199.1503743,-18.4153125,0,5.283235807,90.00000001 +216.12,50.30085681,-3.050102534,10069.477,5.94E-11,199.149042,-18.44,0,5.290261416,90.00000001 +216.13,50.30085681,-3.050074626,10069.6615,6.72E-11,199.1465948,-18.465,0,5.297286967,90.00000001 +216.14,50.30085681,-3.050046719,10069.8463,7.19E-11,199.1434786,-18.49,0,5.304312576,90.00000001 +216.15,50.30085681,-3.050018812,10070.0313,5.78E-11,199.1410313,-18.5146875,0,5.311338127,90.00000001 +216.16,50.30085681,-3.049990906,10070.2166,1.25E-11,199.1394761,-18.5384375,0,5.318363735,90.00000001 +216.17,50.30085681,-3.049962999,10070.4021,-4.22E-11,199.1372519,-18.5615625,0,5.325389287,90.00000001 +216.18,50.30085681,-3.049935093,10070.5878,-6.72E-11,199.1339127,-18.5853125,0,5.332414895,90.00000001 +216.19,50.30085681,-3.049907188,10070.7738,-6.88E-11,199.1314655,-18.61,0,5.339440446,90.00000001 +216.2,50.30085681,-3.049879283,10070.96,-7.66E-11,199.1303563,-18.635,0,5.346466055,90.00000001 +216.21,50.30085681,-3.049851377,10071.1465,-8.91E-11,199.1285781,-18.66,0,5.353491606,90.00000001 +216.22,50.30085681,-3.049823473,10071.3332,-9.06E-11,199.1254619,-18.685,0,5.360517214,90.00000001 +216.23,50.30085681,-3.049795568,10071.5202,-8.28E-11,199.1223458,-18.71,0,5.367542766,90.00000001 +216.24,50.30085681,-3.049767665,10071.7074,-6.72E-11,199.1205676,-18.7346875,0,5.374568374,90.00000001 +216.25,50.30085681,-3.049739761,10071.8949,-2.66E-11,199.1194584,-18.7584375,0,5.381593925,90.00000001 +216.26,50.30085681,-3.049711857,10072.0826,3.59E-11,199.1170113,-18.7815625,0,5.388619534,90.00000001 +216.27,50.30085681,-3.049683954,10072.2705,8.12E-11,199.1134491,-18.8053125,0,5.395645085,90.00000001 +216.28,50.30085681,-3.049656052,10072.4587,8.91E-11,199.110333,-18.83,0,5.402670693,90.00000001 +216.29,50.30085681,-3.049628149,10072.6471,7.66E-11,199.1078859,-18.855,0,5.409696245,90.00000001 +216.3,50.30085681,-3.049600248,10072.8358,6.87E-11,199.1063308,-18.88,0,5.416721853,90.00000001 +216.31,50.30085681,-3.049572346,10073.0247,6.72E-11,199.1054446,-18.9046875,0,5.423747404,90.00000001 +216.32,50.30085681,-3.049544444,10073.2139,4.22E-11,199.1036665,-18.9284375,0,5.430773013,90.00000001 +216.33,50.30085681,-3.049516543,10073.4033,-3.13E-12,199.1005504,-18.951875,0,5.437798564,90.00000001 +216.34,50.30085681,-3.049488642,10073.5929,-1.09E-11,199.0972114,-18.976875,0,5.444824172,90.00000001 +216.35,50.30085681,-3.049460742,10073.7828,2.19E-11,199.0945413,-19.003125,0,5.451849724,90.00000001 +216.36,50.30085681,-3.049432842,10073.973,2.66E-11,199.0923172,-19.028125,0,5.458875332,90.00000001 +216.37,50.30085681,-3.049404942,10074.1634,-1.25E-11,199.0898701,-19.0515625,0,5.465900883,90.00000001 +216.38,50.30085681,-3.049377043,10074.354,-4.22E-11,199.0876461,-19.075,0,5.472926492,90.00000001 +216.39,50.30085681,-3.049349144,10074.5449,-1.72E-11,199.086314,-19.09875,0,5.479952043,90.00000001 +216.4,50.30085681,-3.049321245,10074.736,6.87E-11,199.084982,-19.123125,0,5.486977651,90.00000001 +216.41,50.30085681,-3.049293346,10074.9273,1.61E-10,199.0825349,-19.1484375,0,5.494003203,90.00000001 +216.42,50.30085681,-3.049265448,10075.119,1.83E-10,199.0791959,-19.173125,0,5.501028811,90.00000001 +216.43,50.30085681,-3.04923755,10075.3108,1.37E-10,199.0758569,-19.1965625,0,5.508054362,90.00000001 +216.44,50.30085681,-3.049209653,10075.5029,9.22E-11,199.0734099,-19.2203125,0,5.515079971,90.00000001 +216.45,50.30085681,-3.049181756,10075.6952,7.66E-11,199.0720779,-19.245,0,5.522105522,90.00000001 +216.46,50.30085681,-3.049153859,10075.8878,7.50E-11,199.0705229,-19.27,0,5.52913113,90.00000001 +216.47,50.30085681,-3.049125962,10076.0806,7.66E-11,199.0674069,-19.295,0,5.536156682,90.00000001 +216.48,50.30085681,-3.049098066,10076.2737,8.28E-11,199.0638449,-19.32,0,5.54318229,90.00000001 +216.49,50.30085681,-3.049070171,10076.467,8.28E-11,199.0616209,-19.3446875,0,5.550207841,90.00000001 +216.5,50.30085681,-3.049042275,10076.6606,5.00E-11,199.0600659,-19.3684375,0,5.55723345,90.00000001 +216.51,50.30085681,-3.04901438,10076.8544,-3.13E-12,199.057619,-19.391875,0,5.564259001,90.00000001 +216.52,50.30085681,-3.048986485,10077.0484,-9.38E-12,199.054503,-19.4165625,0,5.571284609,90.00000001 +216.53,50.30085681,-3.048958591,10077.2427,6.09E-11,199.0520561,-19.441875,0,5.578310161,90.00000001 +216.54,50.30085681,-3.048930697,10077.4373,1.53E-10,199.0507241,-19.46625,0,5.585335769,90.00000001 +216.55,50.30085681,-3.048902803,10077.632,1.98E-10,199.0493922,-19.49,0,5.59236132,90.00000001 +216.56,50.30085681,-3.048874909,10077.8271,1.67E-10,199.0469453,-19.51375,0,5.599386929,90.00000001 +216.57,50.30085681,-3.048847016,10078.0223,7.66E-11,199.0436064,-19.538125,0,5.60641248,90.00000001 +216.58,50.30085681,-3.048819123,10078.2178,-1.56E-12,199.0402675,-19.5634375,0,5.613438088,90.00000001 +216.59,50.30085681,-3.048791231,10078.4136,-1.56E-12,199.0375976,-19.588125,0,5.62046364,90.00000001 +216.6,50.30085681,-3.048763339,10078.6096,5.16E-11,199.0353737,-19.6115625,0,5.627489248,90.00000001 +216.61,50.30085681,-3.048735447,10078.8058,9.06E-11,199.0329268,-19.6353125,0,5.634514799,90.00000001 +216.62,50.30085681,-3.048707556,10079.0023,9.84E-11,199.0307029,-19.66,0,5.64154035,90.00000001 +216.63,50.30085681,-3.048679665,10079.199,9.22E-11,199.029148,-19.685,0,5.648565959,90.00000001 +216.64,50.30085681,-3.048651774,10079.396,8.28E-11,199.0269241,-19.71,0,5.65559151,90.00000001 +216.65,50.30085681,-3.048623883,10079.5932,7.66E-11,199.0235853,-19.735,0,5.662617119,90.00000001 +216.66,50.30085681,-3.048595994,10079.7907,7.50E-11,199.0211384,-19.76,0,5.66964267,90.00000001 +216.67,50.30085681,-3.048568104,10079.9884,6.56E-11,199.0200296,-19.7846875,0,5.676668278,90.00000001 +216.68,50.30085681,-3.048540214,10080.1864,2.66E-11,199.0182518,-19.8084375,0,5.683693829,90.00000001 +216.69,50.30085681,-3.048512325,10080.3846,-3.59E-11,199.0151359,-19.8315625,0,5.690719438,90.00000001 +216.7,50.30085681,-3.048484436,10080.583,-8.28E-11,199.0117971,-19.8553125,0,5.697744989,90.00000001 +216.71,50.30085681,-3.048456548,10080.7817,-9.84E-11,199.0091273,-19.88,0,5.704770598,90.00000001 +216.72,50.30085681,-3.04842866,10080.9806,-1.00E-10,199.0069035,-19.905,0,5.711796149,90.00000001 +216.73,50.30085681,-3.048400772,10081.1798,-1.08E-10,199.0044567,-19.9296875,0,5.718821757,90.00000001 +216.74,50.30085681,-3.048372885,10081.3792,-1.30E-10,199.0020099,-19.953125,0,5.725847309,90.00000001 +216.75,50.30085681,-3.048344998,10081.5789,-1.67E-10,199.0000091,-19.9740625,0,5.732872917,90.00000001 +216.76,50.30085681,-3.048317111,10081.7787,-1.98E-10,198.9984543,-19.9903125,0,5.738727572,90.00000001 +216.77,50.30085681,-3.048289225,10081.9788,-1.61E-10,198.9975686,-19.9990625,0,5.739898468,90.00000001 +216.78,50.30085681,-3.048261338,10082.1788,-8.28E-11,198.9973518,-20.00125,0,5.739898468,90.00000001 +216.79,50.30085681,-3.048233452,10082.3788,-7.19E-11,198.997358,-20.001875,0,5.739898468,90.00000001 +216.8,50.30085681,-3.048205565,10082.5788,-1.09E-10,198.9973642,-20.003125,0,5.739898468,90.00000001 +216.81,50.30085681,-3.048177679,10082.7789,-1.02E-10,198.9973704,-20.003125,0,5.739898468,90.00000001 +216.82,50.30085681,-3.048149792,10082.9789,-5.78E-11,198.9973766,-20.001875,0,5.739898468,90.00000001 +216.83,50.30085681,-3.048121906,10083.1789,-5.62E-11,198.9971599,-20.001875,0,5.739898468,90.00000001 +216.84,50.30085681,-3.048094019,10083.3789,-9.37E-11,198.9964971,-20.003125,0,5.739898468,90.00000001 +216.85,50.30085681,-3.048066133,10083.579,-9.37E-11,198.9960573,-20.003125,0,5.739898468,90.00000001 +216.86,50.30085681,-3.048038247,10083.779,-5.62E-11,198.9965095,-20.001875,0,5.739898468,90.00000001 +216.87,50.30085681,-3.04801036,10083.979,-5.78E-11,198.9974077,-20.001875,0,5.739898468,90.00000001 +216.88,50.30085681,-3.047982474,10084.179,-1.02E-10,198.998306,-20.003125,0,5.739898468,90.00000001 +216.89,50.30085681,-3.047954587,10084.3791,-1.09E-10,198.9987582,-20.003125,0,5.739898468,90.00000001 +216.9,50.30085681,-3.0479267,10084.5791,-7.19E-11,198.9983184,-20.001875,0,5.739898468,90.00000001 +216.91,50.30085681,-3.047898814,10084.7791,-6.41E-11,198.9974326,-20.001875,0,5.739898468,90.00000001 +216.92,50.30085681,-3.047870927,10084.9791,-9.53E-11,198.9965468,-20.003125,0,5.739898468,90.00000001 +216.93,50.30085681,-3.047843041,10085.1792,-9.37E-11,198.9961071,-20.003125,0,5.739898468,90.00000001 +216.94,50.30085681,-3.047815155,10085.3792,-5.62E-11,198.9965593,-20.001875,0,5.739898468,90.00000001 +216.95,50.30085681,-3.047787268,10085.5792,-5.62E-11,198.9972345,-20.001875,0,5.739898468,90.00000001 +216.96,50.30085681,-3.047759382,10085.7792,-9.22E-11,198.9974637,-20.003125,0,5.739898468,90.00000001 +216.97,50.30085681,-3.047731495,10085.9793,-8.59E-11,198.9974699,-20.003125,0,5.739898468,90.00000001 +216.98,50.30085681,-3.047703609,10086.1793,-4.06E-11,198.9972531,-20.001875,0,5.739898468,90.00000001 +216.99,50.30085681,-3.047675722,10086.3793,-4.06E-11,198.9965904,-20.001875,0,5.739898468,90.00000001 +217,50.30085681,-3.047647836,10086.5793,-8.59E-11,198.9961506,-20.003125,0,5.739898468,90.00000001 +217.01,50.30085681,-3.04761995,10086.7794,-9.22E-11,198.9966028,-20.003125,0,5.739898468,90.00000001 +217.02,50.30085681,-3.047592063,10086.9794,-5.63E-11,198.997501,-20.001875,0,5.739898468,90.00000001 +217.03,50.30085681,-3.047564177,10087.1794,-5.63E-11,198.9983992,-20.001875,0,5.739898468,90.00000001 +217.04,50.30085681,-3.04753629,10087.3794,-9.38E-11,198.9988514,-20.003125,0,5.739898468,90.00000001 +217.05,50.30085681,-3.047508403,10087.5795,-9.53E-11,198.9984117,-20.003125,0,5.739898468,90.00000001 +217.06,50.30085681,-3.047480517,10087.7795,-6.41E-11,198.9975259,-20.001875,0,5.739898468,90.00000001 +217.07,50.30085681,-3.04745263,10087.9795,-7.19E-11,198.9966401,-20.001875,0,5.739898468,90.00000001 +217.08,50.30085681,-3.047424744,10088.1795,-1.09E-10,198.9962003,-20.003125,0,5.739898468,90.00000001 +217.09,50.30085681,-3.047396858,10088.3796,-1.02E-10,198.9966526,-20.003125,0,5.739898468,90.00000001 +217.1,50.30085681,-3.047368971,10088.5796,-5.78E-11,198.9973278,-20.001875,0,5.739898468,90.00000001 +217.11,50.30085681,-3.047341085,10088.7796,-5.62E-11,198.997557,-20.001875,0,5.739898468,90.00000001 +217.12,50.30085681,-3.047313198,10088.9796,-9.37E-11,198.9975632,-20.003125,0,5.739898468,90.00000001 +217.13,50.30085681,-3.047285312,10089.1797,-9.38E-11,198.9973464,-20.003125,0,5.739898468,90.00000001 +217.14,50.30085681,-3.047257425,10089.3797,-5.63E-11,198.9966836,-20.001875,0,5.739898468,90.00000001 +217.15,50.30085681,-3.047229539,10089.5797,-5.78E-11,198.9962439,-20.001875,0,5.739898468,90.00000001 +217.16,50.30085681,-3.047201653,10089.7797,-1.02E-10,198.9966961,-20.003125,0,5.739898468,90.00000001 +217.17,50.30085681,-3.047173766,10089.9798,-1.09E-10,198.9973713,-20.003125,0,5.739898468,90.00000001 +217.18,50.30085681,-3.04714588,10090.1798,-7.19E-11,198.9976005,-20.001875,0,5.739898468,90.00000001 +217.19,50.30085681,-3.047117993,10090.3798,-6.41E-11,198.9976067,-20.001875,0,5.739898468,90.00000001 +217.2,50.30085681,-3.047090107,10090.5798,-9.53E-11,198.99739,-20.003125,0,5.739898468,90.00000001 +217.21,50.30085681,-3.04706222,10090.7799,-9.37E-11,198.9967272,-20.003125,0,5.739898468,90.00000001 +217.22,50.30085681,-3.047034334,10090.9799,-5.62E-11,198.9962874,-20.001875,0,5.739898468,90.00000001 +217.23,50.30085681,-3.047006448,10091.1799,-5.62E-11,198.9967396,-20.001875,0,5.739898468,90.00000001 +217.24,50.30085681,-3.046978561,10091.3799,-9.22E-11,198.9974148,-20.003125,0,5.739898468,90.00000001 +217.25,50.30085681,-3.046950675,10091.58,-8.59E-11,198.997644,-20.003125,0,5.739898468,90.00000001 +217.26,50.30085681,-3.046922788,10091.78,-4.06E-11,198.9976503,-20.001875,0,5.739898468,90.00000001 +217.27,50.30085681,-3.046894902,10091.98,-4.06E-11,198.9974335,-20.001875,0,5.739898468,90.00000001 +217.28,50.30085681,-3.046867015,10092.18,-8.59E-11,198.9967707,-20.003125,0,5.739898468,90.00000001 +217.29,50.30085681,-3.046839129,10092.3801,-8.28E-11,198.9963309,-20.0034375,0,5.739898468,90.00000001 +217.3,50.30085681,-3.046811243,10092.5801,1.11E-15,198.9967831,-20.003125,0,5.739898468,90.00000001 +217.31,50.30085681,-3.046783356,10092.7801,8.44E-11,198.9976814,-20.0034375,0,5.739898468,90.00000001 +217.32,50.30085681,-3.04675547,10092.9802,9.38E-11,198.9985796,-20.003125,0,5.739898468,90.00000001 +217.33,50.30085681,-3.046727583,10093.1802,5.63E-11,198.9990318,-20.001875,0,5.739898468,90.00000001 +217.34,50.30085681,-3.046699696,10093.3802,5.78E-11,198.998592,-20.001875,0,5.739898468,90.00000001 +217.35,50.30085681,-3.04667181,10093.5802,1.02E-10,198.9977062,-20.003125,0,5.739898468,90.00000001 +217.36,50.30085681,-3.046643923,10093.7803,1.09E-10,198.9968205,-20.003125,0,5.739898468,90.00000001 +217.37,50.30085681,-3.046616037,10093.9803,7.19E-11,198.9963807,-20.001875,0,5.739898468,90.00000001 +217.38,50.30085681,-3.046588151,10094.1803,6.41E-11,198.9968329,-20.001875,0,5.739898468,90.00000001 +217.39,50.30085681,-3.046560264,10094.3803,9.53E-11,198.9975081,-20.003125,0,5.739898468,90.00000001 +217.4,50.30085681,-3.046532378,10094.5804,9.38E-11,198.9977373,-20.003125,0,5.739898468,90.00000001 +217.41,50.30085681,-3.046504491,10094.7804,5.63E-11,198.9977435,-20.001875,0,5.739898468,90.00000001 +217.42,50.30085681,-3.046476605,10094.9804,5.63E-11,198.9975268,-20.001875,0,5.739898468,90.00000001 +217.43,50.30085681,-3.046448718,10095.1804,9.22E-11,198.996864,-20.003125,0,5.739898468,90.00000001 +217.44,50.30085681,-3.046420832,10095.3805,8.59E-11,198.9964242,-20.003125,0,5.739898468,90.00000001 +217.45,50.30085681,-3.046392946,10095.5805,4.06E-11,198.9968764,-20.001875,0,5.739898468,90.00000001 +217.46,50.30085681,-3.046365059,10095.7805,4.06E-11,198.9975516,-20.001875,0,5.739898468,90.00000001 +217.47,50.30085681,-3.046337173,10095.9805,8.59E-11,198.9975579,-20.003125,0,5.739898468,90.00000001 +217.48,50.30085681,-3.046309286,10096.1806,9.22E-11,198.9966721,-20.003125,0,5.739898468,90.00000001 +217.49,50.30085681,-3.0462814,10096.3806,5.62E-11,198.9955633,-20.001875,0,5.739898468,90.00000001 +217.5,50.30085681,-3.046253514,10096.5806,5.62E-11,198.9955695,-20.001875,0,5.739898468,90.00000001 +217.51,50.30085681,-3.046225628,10096.7806,9.37E-11,198.9966907,-20.003125,0,5.739898468,90.00000001 +217.52,50.30085681,-3.046197741,10096.9807,9.53E-11,198.9975889,-20.003125,0,5.739898468,90.00000001 +217.53,50.30085681,-3.046169855,10097.1807,6.41E-11,198.9978182,-20.001875,0,5.739898468,90.00000001 +217.54,50.30085681,-3.046141968,10097.3807,7.19E-11,198.9978244,-20.001875,0,5.739898468,90.00000001 +217.55,50.30085681,-3.046114082,10097.5807,1.09E-10,198.9976076,-20.003125,0,5.739898468,90.00000001 +217.56,50.30085681,-3.046086195,10097.7808,1.02E-10,198.9969448,-20.003125,0,5.739898468,90.00000001 +217.57,50.30085681,-3.046058309,10097.9808,5.78E-11,198.996505,-20.001875,0,5.739898468,90.00000001 +217.58,50.30085681,-3.046030423,10098.1808,5.62E-11,198.9969573,-20.001875,0,5.739898468,90.00000001 +217.59,50.30085681,-3.046002536,10098.3808,9.37E-11,198.9976325,-20.003125,0,5.739898468,90.00000001 +217.6,50.30085681,-3.04597465,10098.5809,9.37E-11,198.9978617,-20.003125,0,5.739898468,90.00000001 +217.61,50.30085681,-3.045946763,10098.7809,5.62E-11,198.9978679,-20.001875,0,5.739898468,90.00000001 +217.62,50.30085681,-3.045918877,10098.9809,5.78E-11,198.9976511,-20.001875,0,5.739898468,90.00000001 +217.63,50.30085681,-3.04589099,10099.1809,1.02E-10,198.9969884,-20.003125,0,5.739898468,90.00000001 +217.64,50.30085681,-3.045863104,10099.381,1.09E-10,198.9965486,-20.003125,0,5.739898468,90.00000001 +217.65,50.30085681,-3.045835218,10099.581,7.19E-11,198.9970008,-20.001875,0,5.739898468,90.00000001 +217.66,50.30085681,-3.045807331,10099.781,6.41E-11,198.997676,-20.001875,0,5.739898468,90.00000001 +217.67,50.30085681,-3.045779445,10099.981,9.53E-11,198.9979052,-20.003125,0,5.739898468,90.00000001 +217.68,50.30085681,-3.045751558,10100.1811,9.37E-11,198.9979114,-20.003125,0,5.739898468,90.00000001 +217.69,50.30085681,-3.045723672,10100.3811,5.62E-11,198.9976947,-20.001875,0,5.739898468,90.00000001 +217.7,50.30085681,-3.045695785,10100.5811,5.62E-11,198.9970319,-20.001875,0,5.739898468,90.00000001 +217.71,50.30085681,-3.045667899,10100.7811,9.22E-11,198.9965921,-20.003125,0,5.739898468,90.00000001 +217.72,50.30085681,-3.045640013,10100.9812,8.59E-11,198.9970443,-20.003125,0,5.739898468,90.00000001 +217.73,50.30085681,-3.045612126,10101.1812,4.06E-11,198.9977195,-20.001875,0,5.739898468,90.00000001 +217.74,50.30085681,-3.04558424,10101.3812,4.06E-11,198.9979488,-20.001875,0,5.739898468,90.00000001 +217.75,50.30085681,-3.045556353,10101.5812,8.59E-11,198.997732,-20.003125,0,5.739898468,90.00000001 +217.76,50.30085681,-3.045528467,10101.7813,9.22E-11,198.9968462,-20.003125,0,5.739898468,90.00000001 +217.77,50.30085681,-3.04550058,10101.9813,5.63E-11,198.9957374,-20.001875,0,5.739898468,90.00000001 +217.78,50.30085681,-3.045472695,10102.1813,5.63E-11,198.9957436,-20.001875,0,5.739898468,90.00000001 +217.79,50.30085681,-3.045444808,10102.3813,9.38E-11,198.9968648,-20.003125,0,5.739898468,90.00000001 +217.8,50.30085681,-3.045416922,10102.5814,9.53E-11,198.9977631,-20.003125,0,5.739898468,90.00000001 +217.81,50.30085681,-3.045389035,10102.7814,6.41E-11,198.9979923,-20.001875,0,5.739898468,90.00000001 +217.82,50.30085681,-3.045361149,10102.9814,7.19E-11,198.9977755,-20.001875,0,5.739898468,90.00000001 +217.83,50.30085681,-3.045333262,10103.1814,1.09E-10,198.9971127,-20.003125,0,5.739898468,90.00000001 +217.84,50.30085681,-3.045305376,10103.3815,1.02E-10,198.9966729,-20.003125,0,5.739898468,90.00000001 +217.85,50.30085681,-3.04527749,10103.5815,5.78E-11,198.9971252,-20.001875,0,5.739898468,90.00000001 +217.86,50.30085681,-3.045249603,10103.7815,5.62E-11,198.9978004,-20.001875,0,5.739898468,90.00000001 +217.87,50.30085681,-3.045221717,10103.9815,9.37E-11,198.9980296,-20.003125,0,5.739898468,90.00000001 +217.88,50.30085681,-3.04519383,10104.1816,9.38E-11,198.9980358,-20.003125,0,5.739898468,90.00000001 +217.89,50.30085681,-3.045165944,10104.3816,5.63E-11,198.997819,-20.001875,0,5.739898468,90.00000001 +217.9,50.30085681,-3.045138057,10104.5816,5.78E-11,198.9969333,-20.001875,0,5.739898468,90.00000001 +217.91,50.30085681,-3.045110171,10104.7816,1.02E-10,198.9958245,-20.003125,0,5.739898468,90.00000001 +217.92,50.30085681,-3.045082285,10104.9817,1.09E-10,198.9958307,-20.003125,0,5.739898468,90.00000001 +217.93,50.30085681,-3.045054399,10105.1817,7.19E-11,198.9969519,-20.001875,0,5.739898468,90.00000001 +217.94,50.30085681,-3.045026512,10105.3817,6.41E-11,198.9978501,-20.001875,0,5.739898468,90.00000001 +217.95,50.30085681,-3.044998626,10105.5817,9.53E-11,198.9978563,-20.003125,0,5.739898468,90.00000001 +217.96,50.30085681,-3.044970739,10105.7818,9.37E-11,198.9971936,-20.003125,0,5.739898468,90.00000001 +217.97,50.30085681,-3.044942853,10105.9818,5.62E-11,198.9967538,-20.001875,0,5.739898468,90.00000001 +217.98,50.30085681,-3.044914967,10106.1818,5.62E-11,198.997206,-20.001875,0,5.739898468,90.00000001 +217.99,50.30085681,-3.04488708,10106.3818,9.22E-11,198.9978812,-20.003125,0,5.739898468,90.00000001 +218,50.30085681,-3.044859194,10106.5819,8.59E-11,198.9981104,-20.003125,0,5.739898468,90.00000001 +218.01,50.30085681,-3.044831307,10106.7819,4.06E-11,198.9978937,-20.001875,0,5.739898468,90.00000001 +218.02,50.30085681,-3.044803421,10106.9819,4.06E-11,198.9970079,-20.001875,0,5.739898468,90.00000001 +218.03,50.30085681,-3.044775534,10107.1819,8.59E-11,198.9958991,-20.003125,0,5.739898468,90.00000001 +218.04,50.30085681,-3.044747649,10107.382,9.22E-11,198.9959053,-20.003125,0,5.739898468,90.00000001 +218.05,50.30085681,-3.044719762,10107.582,5.62E-11,198.9970265,-20.001875,0,5.739898468,90.00000001 +218.06,50.30085681,-3.044691876,10107.782,5.62E-11,198.9979248,-20.001875,0,5.739898468,90.00000001 +218.07,50.30085681,-3.044663989,10107.982,9.37E-11,198.998154,-20.003125,0,5.739898468,90.00000001 +218.08,50.30085681,-3.044636103,10108.1821,9.53E-11,198.9979372,-20.003125,0,5.739898468,90.00000001 +218.09,50.30085681,-3.044608216,10108.3821,6.41E-11,198.9972744,-20.001875,0,5.739898468,90.00000001 +218.1,50.30085681,-3.04458033,10108.5821,7.19E-11,198.9968346,-20.001875,0,5.739898468,90.00000001 +218.11,50.30085681,-3.044552444,10108.7821,1.09E-10,198.9970638,-20.003125,0,5.739898468,90.00000001 +218.12,50.30085681,-3.044524557,10108.9822,1.02E-10,198.9970701,-20.003125,0,5.739898468,90.00000001 +218.13,50.30085681,-3.044496671,10109.1822,5.78E-11,198.9968533,-20.001875,0,5.739898468,90.00000001 +218.14,50.30085681,-3.044468785,10109.3822,5.63E-11,198.9970825,-20.001875,0,5.739898468,90.00000001 +218.15,50.30085681,-3.044440898,10109.5822,9.38E-11,198.9970887,-20.003125,0,5.739898468,90.00000001 +218.16,50.30085681,-3.044413012,10109.7823,8.44E-11,198.9968719,-20.0034375,0,5.739898468,90.00000001 +218.17,50.30085681,-3.044385126,10109.9823,-1.11E-15,198.9973242,-20.003125,0,5.739898468,90.00000001 +218.18,50.30085681,-3.044357239,10110.1823,-8.28E-11,198.9979994,-20.0034375,0,5.739898468,90.00000001 +218.19,50.30085681,-3.044329353,10110.3824,-8.59E-11,198.9982286,-20.003125,0,5.739898468,90.00000001 +218.2,50.30085681,-3.044301466,10110.5824,-4.06E-11,198.9980118,-20.001875,0,5.739898468,90.00000001 +218.21,50.30085681,-3.04427358,10110.7824,-4.06E-11,198.997126,-20.001875,0,5.739898468,90.00000001 +218.22,50.30085681,-3.044245693,10110.9824,-8.59E-11,198.9960172,-20.003125,0,5.739898468,90.00000001 +218.23,50.30085681,-3.044217808,10111.1825,-9.22E-11,198.9960235,-20.003125,0,5.739898468,90.00000001 +218.24,50.30085681,-3.044189921,10111.3825,-5.62E-11,198.9971447,-20.001875,0,5.739898468,90.00000001 +218.25,50.30085681,-3.044162035,10111.5825,-5.62E-11,198.9980429,-20.001875,0,5.739898468,90.00000001 +218.26,50.30085681,-3.044134148,10111.7825,-9.37E-11,198.9982721,-20.003125,0,5.739898468,90.00000001 +218.27,50.30085681,-3.044106262,10111.9826,-9.53E-11,198.9980553,-20.003125,0,5.739898468,90.00000001 +218.28,50.30085681,-3.044078375,10112.1826,-6.41E-11,198.9971696,-20.001875,0,5.739898468,90.00000001 +218.29,50.30085681,-3.044050489,10112.3826,-7.19E-11,198.9960608,-20.001875,0,5.739898468,90.00000001 +218.3,50.30085681,-3.044022603,10112.5826,-1.09E-10,198.996067,-20.003125,0,5.739898468,90.00000001 +218.31,50.30085681,-3.043994717,10112.7827,-1.02E-10,198.9971882,-20.003125,0,5.739898468,90.00000001 +218.32,50.30085681,-3.04396683,10112.9827,-5.78E-11,198.9980864,-20.001875,0,5.739898468,90.00000001 +218.33,50.30085681,-3.043938944,10113.1827,-5.62E-11,198.9980927,-20.001875,0,5.739898468,90.00000001 +218.34,50.30085681,-3.043911057,10113.3827,-9.37E-11,198.9972069,-20.003125,0,5.739898468,90.00000001 +218.35,50.30085681,-3.043883171,10113.5828,-9.37E-11,198.9960981,-20.003125,0,5.739898468,90.00000001 +218.36,50.30085681,-3.043855285,10113.7828,-5.62E-11,198.9961043,-20.001875,0,5.739898468,90.00000001 +218.37,50.30085681,-3.043827399,10113.9828,-5.78E-11,198.9972255,-20.001875,0,5.739898468,90.00000001 +218.38,50.30085681,-3.043799512,10114.1828,-1.02E-10,198.9981237,-20.003125,0,5.739898468,90.00000001 +218.39,50.30085681,-3.043771626,10114.3829,-1.09E-10,198.99813,-20.003125,0,5.739898468,90.00000001 +218.4,50.30085681,-3.043743739,10114.5829,-7.19E-11,198.9974672,-20.001875,0,5.739898468,90.00000001 +218.41,50.30085681,-3.043715853,10114.7829,-6.41E-11,198.9970274,-20.001875,0,5.739898468,90.00000001 +218.42,50.30085681,-3.043687967,10114.9829,-9.53E-11,198.9972566,-20.003125,0,5.739898468,90.00000001 +218.43,50.30085681,-3.04366008,10115.183,-9.37E-11,198.9972628,-20.003125,0,5.739898468,90.00000001 +218.44,50.30085681,-3.043632194,10115.383,-5.62E-11,198.9970461,-20.001875,0,5.739898468,90.00000001 +218.45,50.30085681,-3.043604308,10115.583,-5.62E-11,198.9972753,-20.001875,0,5.739898468,90.00000001 +218.46,50.30085681,-3.043576421,10115.783,-9.22E-11,198.9972815,-20.003125,0,5.739898468,90.00000001 +218.47,50.30085681,-3.043548535,10115.9831,-8.59E-11,198.9970647,-20.003125,0,5.739898468,90.00000001 +218.48,50.30085681,-3.043520649,10116.1831,-4.06E-11,198.9972939,-20.001875,0,5.739898468,90.00000001 +218.49,50.30085681,-3.043492762,10116.3831,-4.06E-11,198.9973001,-20.001875,0,5.739898468,90.00000001 +218.5,50.30085681,-3.043464876,10116.5831,-8.59E-11,198.9970834,-20.003125,0,5.739898468,90.00000001 +218.51,50.30085681,-3.04343699,10116.7832,-9.22E-11,198.9973126,-20.003125,0,5.739898468,90.00000001 +218.52,50.30085681,-3.043409103,10116.9832,-5.63E-11,198.9973188,-20.001875,0,5.739898468,90.00000001 +218.53,50.30085681,-3.043381217,10117.1832,-5.63E-11,198.997102,-20.001875,0,5.739898468,90.00000001 +218.54,50.30085681,-3.043353331,10117.3832,-9.38E-11,198.9973312,-20.003125,0,5.739898468,90.00000001 +218.55,50.30085681,-3.043325444,10117.5833,-9.53E-11,198.9973375,-20.003125,0,5.739898468,90.00000001 +218.56,50.30085681,-3.043297558,10117.7833,-6.41E-11,198.9971207,-20.001875,0,5.739898468,90.00000001 +218.57,50.30085681,-3.043269672,10117.9833,-7.19E-11,198.9973499,-20.001875,0,5.739898468,90.00000001 +218.58,50.30085681,-3.043241785,10118.1833,-1.09E-10,198.9973561,-20.003125,0,5.739898468,90.00000001 +218.59,50.30085681,-3.043213899,10118.3834,-1.02E-10,198.9971393,-20.003125,0,5.739898468,90.00000001 +218.6,50.30085681,-3.043186013,10118.5834,-5.78E-11,198.9973686,-20.001875,0,5.739898468,90.00000001 +218.61,50.30085681,-3.043158126,10118.7834,-5.63E-11,198.9973748,-20.001875,0,5.739898468,90.00000001 +218.62,50.30085681,-3.04313024,10118.9834,-9.38E-11,198.997158,-20.003125,0,5.739898468,90.00000001 +218.63,50.30085681,-3.043102354,10119.1835,-9.38E-11,198.9973872,-20.003125,0,5.739898468,90.00000001 +218.64,50.30085681,-3.043074467,10119.3835,-5.63E-11,198.9971704,-20.001875,0,5.739898468,90.00000001 +218.65,50.30085681,-3.043046581,10119.5835,-5.78E-11,198.9962846,-20.001875,0,5.739898468,90.00000001 +218.66,50.30085681,-3.043018695,10119.7835,-1.02E-10,198.9962909,-20.003125,0,5.739898468,90.00000001 +218.67,50.30085681,-3.042990809,10119.9836,-1.09E-10,198.9974121,-20.003125,0,5.739898468,90.00000001 +218.68,50.30085681,-3.042962922,10120.1836,-7.19E-11,198.9983103,-20.001875,0,5.739898468,90.00000001 +218.69,50.30085681,-3.042935036,10120.3836,-6.41E-11,198.9983165,-20.001875,0,5.739898468,90.00000001 +218.7,50.30085681,-3.042907149,10120.5836,-9.53E-11,198.9974307,-20.003125,0,5.739898468,90.00000001 +218.71,50.30085681,-3.042879263,10120.7837,-9.37E-11,198.996322,-20.003125,0,5.739898468,90.00000001 +218.72,50.30085681,-3.042851377,10120.9837,-5.62E-11,198.9963282,-20.001875,0,5.739898468,90.00000001 +218.73,50.30085681,-3.042823491,10121.1837,-5.62E-11,198.9974494,-20.001875,0,5.739898468,90.00000001 +218.74,50.30085681,-3.042795604,10121.3837,-9.22E-11,198.9981246,-20.003125,0,5.739898468,90.00000001 +218.75,50.30085681,-3.042767718,10121.5838,-8.59E-11,198.9974618,-20.003125,0,5.739898468,90.00000001 +218.76,50.30085681,-3.042739831,10121.7838,-4.06E-11,198.996353,-20.001875,0,5.739898468,90.00000001 +218.77,50.30085681,-3.042711946,10121.9838,-4.06E-11,198.9963593,-20.001875,0,5.739898468,90.00000001 +218.78,50.30085681,-3.042684059,10122.1838,-8.59E-11,198.9974805,-20.003125,0,5.739898468,90.00000001 +218.79,50.30085681,-3.042656173,10122.3839,-9.22E-11,198.9981557,-20.003125,0,5.739898468,90.00000001 +218.8,50.30085681,-3.042628286,10122.5839,-5.62E-11,198.9974929,-20.001875,0,5.739898468,90.00000001 +218.81,50.30085681,-3.0426004,10122.7839,-5.62E-11,198.9963841,-20.001875,0,5.739898468,90.00000001 +218.82,50.30085681,-3.042572514,10122.9839,-9.37E-11,198.9963904,-20.003125,0,5.739898468,90.00000001 +218.83,50.30085681,-3.042544628,10123.184,-9.53E-11,198.9972886,-20.003125,0,5.739898468,90.00000001 +218.84,50.30085681,-3.042516741,10123.384,-6.41E-11,198.9975178,-20.001875,0,5.739898468,90.00000001 +218.85,50.30085681,-3.042488855,10123.584,-7.19E-11,198.997301,-20.001875,0,5.739898468,90.00000001 +218.86,50.30085681,-3.042460969,10123.784,-1.09E-10,198.9975302,-20.003125,0,5.739898468,90.00000001 +218.87,50.30085681,-3.042433082,10123.9841,-1.02E-10,198.9975365,-20.003125,0,5.739898468,90.00000001 +218.88,50.30085681,-3.042405196,10124.1841,-5.78E-11,198.9973197,-20.001875,0,5.739898468,90.00000001 +218.89,50.30085681,-3.04237731,10124.3841,-5.63E-11,198.9975489,-20.001875,0,5.739898468,90.00000001 +218.9,50.30085681,-3.042349423,10124.5841,-9.38E-11,198.9975551,-20.003125,0,5.739898468,90.00000001 +218.91,50.30085681,-3.042321537,10124.7842,-9.37E-11,198.9973383,-20.003125,0,5.739898468,90.00000001 +218.92,50.30085681,-3.042293651,10124.9842,-5.62E-11,198.9975675,-20.001875,0,5.739898468,90.00000001 +218.93,50.30085681,-3.042265764,10125.1842,-5.78E-11,198.9973508,-20.001875,0,5.739898468,90.00000001 +218.94,50.30085681,-3.042237878,10125.3842,-1.02E-10,198.996465,-20.003125,0,5.739898468,90.00000001 +218.95,50.30085681,-3.042209992,10125.5843,-1.09E-10,198.9964712,-20.003125,0,5.739898468,90.00000001 +218.96,50.30085681,-3.042182106,10125.7843,-7.19E-11,198.9973694,-20.001875,0,5.739898468,90.00000001 +218.97,50.30085681,-3.042154219,10125.9843,-6.41E-11,198.9973756,-20.001875,0,5.739898468,90.00000001 +218.98,50.30085681,-3.042126333,10126.1843,-9.53E-11,198.9964899,-20.003125,0,5.739898468,90.00000001 +218.99,50.30085681,-3.042098447,10126.3844,-9.38E-11,198.9964961,-20.003125,0,5.739898468,90.00000001 +219,50.30085681,-3.042070561,10126.5844,-5.63E-11,198.9973943,-20.001875,0,5.739898468,90.00000001 +219.01,50.30085681,-3.042042674,10126.7844,-5.63E-11,198.9976235,-20.001875,0,5.739898468,90.00000001 +219.02,50.30085681,-3.042014788,10126.9844,-9.22E-11,198.9974067,-20.003125,0,5.739898468,90.00000001 +219.03,50.30085681,-3.041986902,10127.1845,-7.66E-11,198.9976359,-20.0034375,0,5.739898468,90.00000001 +219.04,50.30085681,-3.041959015,10127.3845,1.56E-11,198.9974192,-20.003125,0,5.739898468,90.00000001 +219.05,50.30085681,-3.041931129,10127.5845,1.00E-10,198.9965334,-20.0034375,0,5.739898468,90.00000001 +219.06,50.30085681,-3.041903243,10127.7846,1.02E-10,198.9965396,-20.003125,0,5.739898468,90.00000001 +219.07,50.30085681,-3.041875357,10127.9846,5.78E-11,198.9976608,-20.001875,0,5.739898468,90.00000001 +219.08,50.30085681,-3.04184747,10128.1846,5.62E-11,198.998336,-20.001875,0,5.739898468,90.00000001 +219.09,50.30085681,-3.041819584,10128.3846,9.37E-11,198.9976733,-20.003125,0,5.739898468,90.00000001 +219.1,50.30085681,-3.041791697,10128.5847,9.37E-11,198.9965645,-20.003125,0,5.739898468,90.00000001 +219.11,50.30085681,-3.041763812,10128.7847,5.62E-11,198.9965707,-20.001875,0,5.739898468,90.00000001 +219.12,50.30085681,-3.041735925,10128.9847,5.78E-11,198.9976919,-20.001875,0,5.739898468,90.00000001 +219.13,50.30085681,-3.041708039,10129.1847,1.02E-10,198.9983671,-20.003125,0,5.739898468,90.00000001 +219.14,50.30085681,-3.041680152,10129.3848,1.09E-10,198.9977044,-20.003125,0,5.739898468,90.00000001 +219.15,50.30085681,-3.041652266,10129.5848,7.19E-11,198.9965956,-20.001875,0,5.739898468,90.00000001 +219.16,50.30085681,-3.04162438,10129.7848,6.41E-11,198.9966018,-20.001875,0,5.739898468,90.00000001 +219.17,50.30085681,-3.041596494,10129.9848,9.53E-11,198.9975,-20.003125,0,5.739898468,90.00000001 +219.18,50.30085681,-3.041568607,10130.1849,9.37E-11,198.9977292,-20.003125,0,5.739898468,90.00000001 +219.19,50.30085681,-3.041540721,10130.3849,5.62E-11,198.9975124,-20.001875,0,5.739898468,90.00000001 +219.2,50.30085681,-3.041512835,10130.5849,5.62E-11,198.9977417,-20.001875,0,5.739898468,90.00000001 +219.21,50.30085681,-3.041484948,10130.7849,9.22E-11,198.9975249,-20.003125,0,5.739898468,90.00000001 +219.22,50.30085681,-3.041457062,10130.985,8.59E-11,198.9966391,-20.003125,0,5.739898468,90.00000001 +219.23,50.30085681,-3.041429176,10131.185,4.06E-11,198.9966453,-20.001875,0,5.739898468,90.00000001 +219.24,50.30085681,-3.04140129,10131.385,4.06E-11,198.9975435,-20.001875,0,5.739898468,90.00000001 +219.25,50.30085681,-3.041373403,10131.585,8.59E-11,198.9975498,-20.003125,0,5.739898468,90.00000001 +219.26,50.30085681,-3.041345517,10131.7851,9.22E-11,198.996664,-20.003125,0,5.739898468,90.00000001 +219.27,50.30085681,-3.041317631,10131.9851,5.63E-11,198.9966702,-20.001875,0,5.739898468,90.00000001 +219.28,50.30085681,-3.041289745,10132.1851,5.63E-11,198.9975684,-20.001875,0,5.739898468,90.00000001 +219.29,50.30085681,-3.041261858,10132.3851,9.38E-11,198.9977976,-20.003125,0,5.739898468,90.00000001 +219.3,50.30085681,-3.041233972,10132.5852,9.53E-11,198.9973578,-20.003125,0,5.739898468,90.00000001 +219.31,50.30085681,-3.041206086,10132.7852,6.41E-11,198.9969181,-20.001875,0,5.739898468,90.00000001 +219.32,50.30085681,-3.041178199,10132.9852,7.19E-11,198.9964783,-20.001875,0,5.739898468,90.00000001 +219.33,50.30085681,-3.041150314,10133.1852,1.09E-10,198.9967075,-20.003125,0,5.739898468,90.00000001 +219.34,50.30085681,-3.041122427,10133.3853,1.02E-10,198.9978287,-20.003125,0,5.739898468,90.00000001 +219.35,50.30085681,-3.041094541,10133.5853,5.78E-11,198.9985039,-20.001875,0,5.739898468,90.00000001 +219.36,50.30085681,-3.041066654,10133.7853,5.63E-11,198.9978412,-20.001875,0,5.739898468,90.00000001 +219.37,50.30085681,-3.041038768,10133.9853,9.38E-11,198.9965094,-20.003125,0,5.739898468,90.00000001 +219.38,50.30085681,-3.041010882,10134.1854,9.38E-11,198.9958466,-20.003125,0,5.739898468,90.00000001 +219.39,50.30085681,-3.040982996,10134.3854,5.63E-11,198.9965218,-20.001875,0,5.739898468,90.00000001 +219.4,50.30085681,-3.04095511,10134.5854,5.78E-11,198.997643,-20.001875,0,5.739898468,90.00000001 +219.41,50.30085681,-3.040927223,10134.7854,1.02E-10,198.9976493,-20.003125,0,5.739898468,90.00000001 +219.42,50.30085681,-3.040899337,10134.9855,1.09E-10,198.9967635,-20.003125,0,5.739898468,90.00000001 +219.43,50.30085681,-3.040871451,10135.1855,7.19E-11,198.9967697,-20.001875,0,5.739898468,90.00000001 +219.44,50.30085681,-3.040843565,10135.3855,6.41E-11,198.9976679,-20.001875,0,5.739898468,90.00000001 +219.45,50.30085681,-3.040815678,10135.5855,9.53E-11,198.9978971,-20.003125,0,5.739898468,90.00000001 +219.46,50.30085681,-3.040787792,10135.7856,9.38E-11,198.9976803,-20.003125,0,5.739898468,90.00000001 +219.47,50.30085681,-3.040759906,10135.9856,5.63E-11,198.9979096,-20.001875,0,5.739898468,90.00000001 +219.48,50.30085681,-3.040732019,10136.1856,5.63E-11,198.9976928,-20.001875,0,5.739898468,90.00000001 +219.49,50.30085681,-3.040704133,10136.3856,9.22E-11,198.996807,-20.003125,0,5.739898468,90.00000001 +219.5,50.30085681,-3.040676247,10136.5857,8.59E-11,198.9968132,-20.003125,0,5.739898468,90.00000001 +219.51,50.30085681,-3.040648361,10136.7857,4.06E-11,198.9977114,-20.001875,0,5.739898468,90.00000001 +219.52,50.30085681,-3.040620474,10136.9857,4.06E-11,198.9977177,-20.001875,0,5.739898468,90.00000001 +219.53,50.30085681,-3.040592588,10137.1857,8.59E-11,198.9966089,-20.003125,0,5.739898468,90.00000001 +219.54,50.30085681,-3.040564702,10137.3858,9.22E-11,198.9959461,-20.003125,0,5.739898468,90.00000001 +219.55,50.30085681,-3.040536816,10137.5858,5.62E-11,198.9966213,-20.001875,0,5.739898468,90.00000001 +219.56,50.30085681,-3.04050893,10137.7858,5.62E-11,198.9977425,-20.001875,0,5.739898468,90.00000001 +219.57,50.30085681,-3.040481043,10137.9858,9.37E-11,198.9977487,-20.003125,0,5.739898468,90.00000001 +219.58,50.30085681,-3.040453157,10138.1859,9.53E-11,198.996863,-20.003125,0,5.739898468,90.00000001 +219.59,50.30085681,-3.040425271,10138.3859,6.41E-11,198.9968692,-20.001875,0,5.739898468,90.00000001 +219.6,50.30085681,-3.040397385,10138.5859,7.19E-11,198.9977674,-20.001875,0,5.739898468,90.00000001 +219.61,50.30085681,-3.040369498,10138.7859,1.09E-10,198.9979966,-20.003125,0,5.739898468,90.00000001 +219.62,50.30085681,-3.040341612,10138.986,1.02E-10,198.9975568,-20.003125,0,5.739898468,90.00000001 +219.63,50.30085681,-3.040313726,10139.186,5.78E-11,198.9971171,-20.001875,0,5.739898468,90.00000001 +219.64,50.30085681,-3.040285839,10139.386,5.62E-11,198.9966773,-20.001875,0,5.739898468,90.00000001 +219.65,50.30085681,-3.040257954,10139.586,9.37E-11,198.9966835,-20.003125,0,5.739898468,90.00000001 +219.66,50.30085681,-3.040230067,10139.7861,9.37E-11,198.9971357,-20.003125,0,5.739898468,90.00000001 +219.67,50.30085681,-3.040202181,10139.9861,5.62E-11,198.9975879,-20.001875,0,5.739898468,90.00000001 +219.68,50.30085681,-3.040174295,10140.1861,5.78E-11,198.9980402,-20.001875,0,5.739898468,90.00000001 +219.69,50.30085681,-3.040146408,10140.3861,1.02E-10,198.9978234,-20.003125,0,5.739898468,90.00000001 +219.7,50.30085681,-3.040118522,10140.5862,1.09E-10,198.9967146,-20.003125,0,5.739898468,90.00000001 +219.71,50.30085681,-3.040090636,10140.7862,7.19E-11,198.9960518,-20.001875,0,5.739898468,90.00000001 +219.72,50.30085681,-3.04006275,10140.9862,6.41E-11,198.996727,-20.001875,0,5.739898468,90.00000001 +219.73,50.30085681,-3.040034864,10141.1862,9.53E-11,198.9978482,-20.003125,0,5.739898468,90.00000001 +219.74,50.30085681,-3.040006977,10141.3863,9.38E-11,198.9978545,-20.003125,0,5.739898468,90.00000001 +219.75,50.30085681,-3.039979091,10141.5863,5.63E-11,198.9969687,-20.001875,0,5.739898468,90.00000001 +219.76,50.30085681,-3.039951205,10141.7863,5.63E-11,198.9969749,-20.001875,0,5.739898468,90.00000001 +219.77,50.30085681,-3.039923319,10141.9863,9.22E-11,198.9978731,-20.003125,0,5.739898468,90.00000001 +219.78,50.30085681,-3.039895432,10142.1864,8.59E-11,198.9978793,-20.003125,0,5.739898468,90.00000001 +219.79,50.30085681,-3.039867546,10142.3864,4.06E-11,198.9967706,-20.001875,0,5.739898468,90.00000001 +219.8,50.30085681,-3.03983966,10142.5864,4.06E-11,198.9961078,-20.001875,0,5.739898468,90.00000001 +219.81,50.30085681,-3.039811774,10142.7864,8.59E-11,198.996783,-20.003125,0,5.739898468,90.00000001 +219.82,50.30085681,-3.039783888,10142.9865,9.22E-11,198.9979042,-20.003125,0,5.739898468,90.00000001 +219.83,50.30085681,-3.039756001,10143.1865,5.63E-11,198.9979104,-20.001875,0,5.739898468,90.00000001 +219.84,50.30085681,-3.039728115,10143.3865,5.63E-11,198.9968016,-20.001875,0,5.739898468,90.00000001 +219.85,50.30085681,-3.039700229,10143.5865,9.38E-11,198.9961389,-20.003125,0,5.739898468,90.00000001 +219.86,50.30085681,-3.039672343,10143.7866,9.53E-11,198.9968141,-20.003125,0,5.739898468,90.00000001 +219.87,50.30085681,-3.039644457,10143.9866,6.41E-11,198.9979353,-20.001875,0,5.739898468,90.00000001 +219.88,50.30085681,-3.03961657,10144.1866,7.19E-11,198.9979415,-20.001875,0,5.739898468,90.00000001 +219.89,50.30085681,-3.039588684,10144.3866,1.09E-10,198.9968327,-20.003125,0,5.739898468,90.00000001 +219.9,50.30085681,-3.039560798,10144.5867,9.22E-11,198.99617,-20.0034375,0,5.739898468,90.00000001 +219.91,50.30085681,-3.039532912,10144.7867,1.56E-12,198.9968452,-20.003125,0,5.739898468,90.00000001 +219.92,50.30085681,-3.039505026,10144.9867,-8.44E-11,198.9979664,-20.0034375,0,5.739898468,90.00000001 +219.93,50.30085681,-3.039477139,10145.1868,-9.37E-11,198.9979726,-20.003125,0,5.739898468,90.00000001 +219.94,50.30085681,-3.039449253,10145.3868,-5.62E-11,198.9970868,-20.001875,0,5.739898468,90.00000001 +219.95,50.30085681,-3.039421367,10145.5868,-5.62E-11,198.997093,-20.001875,0,5.739898468,90.00000001 +219.96,50.30085681,-3.039393481,10145.7868,-9.22E-11,198.9979913,-20.003125,0,5.739898468,90.00000001 +219.97,50.30085681,-3.039365594,10145.9869,-8.59E-11,198.9979975,-20.003125,0,5.739898468,90.00000001 +219.98,50.30085681,-3.039337708,10146.1869,-4.06E-11,198.9968887,-20.001875,0,5.739898468,90.00000001 +219.99,50.30085681,-3.039309822,10146.3869,-4.06E-11,198.9962259,-20.001875,0,5.739898468,90.00000001 +220,50.30085681,-3.039281936,10146.5869,-8.59E-11,198.9969011,-20.003125,0,5.739898468,90.00000001 +220.01,50.30085681,-3.03925405,10146.787,-9.22E-11,198.9980224,-20.003125,0,5.739898468,90.00000001 +220.02,50.30085681,-3.039226163,10146.987,-5.63E-11,198.9980286,-20.001875,0,5.739898468,90.00000001 +220.03,50.30085681,-3.039198277,10147.187,-5.63E-11,198.9969198,-20.001875,0,5.739898468,90.00000001 +220.04,50.30085681,-3.039170391,10147.387,-9.38E-11,198.996257,-20.003125,0,5.739898468,90.00000001 +220.05,50.30085681,-3.039142505,10147.5871,-9.53E-11,198.9969322,-20.003125,0,5.739898468,90.00000001 +220.06,50.30085681,-3.039114619,10147.7871,-6.41E-11,198.9980535,-20.001875,0,5.739898468,90.00000001 +220.07,50.30085681,-3.039086732,10147.9871,-7.19E-11,198.9980597,-20.001875,0,5.739898468,90.00000001 +220.08,50.30085681,-3.039058846,10148.1871,-1.09E-10,198.9969509,-20.003125,0,5.739898468,90.00000001 +220.09,50.30085681,-3.03903096,10148.3872,-1.02E-10,198.9962881,-20.003125,0,5.739898468,90.00000001 +220.1,50.30085681,-3.039003074,10148.5872,-5.78E-11,198.9969633,-20.001875,0,5.739898468,90.00000001 +220.11,50.30085681,-3.038975188,10148.7872,-5.63E-11,198.9980846,-20.001875,0,5.739898468,90.00000001 +220.12,50.30085681,-3.038947301,10148.9872,-9.38E-11,198.9980908,-20.003125,0,5.739898468,90.00000001 +220.13,50.30085681,-3.038919415,10149.1873,-9.38E-11,198.996982,-20.003125,0,5.739898468,90.00000001 +220.14,50.30085681,-3.038891529,10149.3873,-5.63E-11,198.9960962,-20.001875,0,5.739898468,90.00000001 +220.15,50.30085681,-3.038863643,10149.5873,-5.78E-11,198.9961024,-20.001875,0,5.739898468,90.00000001 +220.16,50.30085681,-3.038835757,10149.7873,-1.02E-10,198.9970006,-20.003125,0,5.739898468,90.00000001 +220.17,50.30085681,-3.038807871,10149.9874,-1.09E-10,198.9981219,-20.003125,0,5.739898468,90.00000001 +220.18,50.30085681,-3.038779984,10150.1874,-7.19E-11,198.9981281,-20.001875,0,5.739898468,90.00000001 +220.19,50.30085681,-3.038752098,10150.3874,-6.41E-11,198.9970193,-20.001875,0,5.739898468,90.00000001 +220.2,50.30085681,-3.038724212,10150.5874,-9.53E-11,198.9963565,-20.003125,0,5.739898468,90.00000001 +220.21,50.30085681,-3.038696326,10150.7875,-9.38E-11,198.9970317,-20.003125,0,5.739898468,90.00000001 +220.22,50.30085681,-3.03866844,10150.9875,-5.63E-11,198.998153,-20.001875,0,5.739898468,90.00000001 +220.23,50.30085681,-3.038640553,10151.1875,-5.63E-11,198.9981592,-20.001875,0,5.739898468,90.00000001 +220.24,50.30085681,-3.038612667,10151.3875,-9.22E-11,198.9970504,-20.003125,0,5.739898468,90.00000001 +220.25,50.30085681,-3.038584781,10151.5876,-8.59E-11,198.9963876,-20.003125,0,5.739898468,90.00000001 +220.26,50.30085681,-3.038556895,10151.7876,-4.06E-11,198.9970628,-20.001875,0,5.739898468,90.00000001 +220.27,50.30085681,-3.038529009,10151.9876,-4.06E-11,198.998184,-20.001875,0,5.739898468,90.00000001 +220.28,50.30085681,-3.038501122,10152.1876,-8.59E-11,198.9981903,-20.003125,0,5.739898468,90.00000001 +220.29,50.30085681,-3.038473236,10152.3877,-9.22E-11,198.9970815,-20.003125,0,5.739898468,90.00000001 +220.3,50.30085681,-3.03844535,10152.5877,-5.62E-11,198.9964187,-20.001875,0,5.739898468,90.00000001 +220.31,50.30085681,-3.038417464,10152.7877,-5.62E-11,198.9970939,-20.001875,0,5.739898468,90.00000001 +220.32,50.30085681,-3.038389578,10152.9877,-9.37E-11,198.9982151,-20.003125,0,5.739898468,90.00000001 +220.33,50.30085681,-3.038361691,10153.1878,-9.53E-11,198.9982214,-20.003125,0,5.739898468,90.00000001 +220.34,50.30085681,-3.038333805,10153.3878,-6.41E-11,198.9971126,-20.001875,0,5.739898468,90.00000001 +220.35,50.30085681,-3.038305919,10153.5878,-7.19E-11,198.9962268,-20.001875,0,5.739898468,90.00000001 +220.36,50.30085681,-3.038278033,10153.7878,-1.09E-10,198.996233,-20.003125,0,5.739898468,90.00000001 +220.37,50.30085681,-3.038250147,10153.9879,-1.02E-10,198.9969082,-20.003125,0,5.739898468,90.00000001 +220.38,50.30085681,-3.038222261,10154.1879,-5.78E-11,198.9973604,-20.001875,0,5.739898468,90.00000001 +220.39,50.30085681,-3.038194374,10154.3879,-5.62E-11,198.9971437,-20.001875,0,5.739898468,90.00000001 +220.4,50.30085681,-3.038166489,10154.5879,-9.37E-11,198.9971499,-20.003125,0,5.739898468,90.00000001 +220.41,50.30085681,-3.038138602,10154.788,-9.37E-11,198.9976021,-20.003125,0,5.739898468,90.00000001 +220.42,50.30085681,-3.038110716,10154.988,-5.62E-11,198.9978313,-20.001875,0,5.739898468,90.00000001 +220.43,50.30085681,-3.03808283,10155.188,-5.78E-11,198.9976145,-20.001875,0,5.739898468,90.00000001 +220.44,50.30085681,-3.038054943,10155.388,-1.02E-10,198.9971748,-20.003125,0,5.739898468,90.00000001 +220.45,50.30085681,-3.038027058,10155.5881,-1.09E-10,198.997181,-20.003125,0,5.739898468,90.00000001 +220.46,50.30085681,-3.037999171,10155.7881,-7.19E-11,198.9974102,-20.001875,0,5.739898468,90.00000001 +220.47,50.30085681,-3.037971285,10155.9881,-6.41E-11,198.9969704,-20.001875,0,5.739898468,90.00000001 +220.48,50.30085681,-3.037943399,10156.1881,-9.53E-11,198.9963076,-20.003125,0,5.739898468,90.00000001 +220.49,50.30085681,-3.037915513,10156.3882,-9.37E-11,198.9963138,-20.003125,0,5.739898468,90.00000001 +220.5,50.30085681,-3.037887627,10156.5882,-5.62E-11,198.9972121,-20.001875,0,5.739898468,90.00000001 +220.51,50.30085681,-3.037859741,10156.7882,-5.62E-11,198.9983333,-20.001875,0,5.739898468,90.00000001 +220.52,50.30085681,-3.037831854,10156.9882,-9.22E-11,198.9983395,-20.003125,0,5.739898468,90.00000001 +220.53,50.30085681,-3.037803968,10157.1883,-8.59E-11,198.9972307,-20.003125,0,5.739898468,90.00000001 +220.54,50.30085681,-3.037776082,10157.3883,-4.06E-11,198.9963449,-20.001875,0,5.739898468,90.00000001 +220.55,50.30085681,-3.037748196,10157.5883,-4.06E-11,198.9963511,-20.001875,0,5.739898468,90.00000001 +220.56,50.30085681,-3.03772031,10157.7883,-8.59E-11,198.9970264,-20.003125,0,5.739898468,90.00000001 +220.57,50.30085681,-3.037692424,10157.9884,-9.22E-11,198.9974786,-20.003125,0,5.739898468,90.00000001 +220.58,50.30085681,-3.037664537,10158.1884,-5.63E-11,198.9972618,-20.001875,0,5.739898468,90.00000001 +220.59,50.30085681,-3.037636652,10158.3884,-5.63E-11,198.997268,-20.001875,0,5.739898468,90.00000001 +220.6,50.30085681,-3.037608765,10158.5884,-9.38E-11,198.9974973,-20.003125,0,5.739898468,90.00000001 +220.61,50.30085681,-3.037580879,10158.7885,-9.53E-11,198.9970575,-20.003125,0,5.739898468,90.00000001 +220.62,50.30085681,-3.037552993,10158.9885,-6.41E-11,198.9966177,-20.001875,0,5.739898468,90.00000001 +220.63,50.30085681,-3.037525107,10159.1885,-7.19E-11,198.9972929,-20.001875,0,5.739898468,90.00000001 +220.64,50.30085681,-3.037497221,10159.3885,-1.09E-10,198.9984141,-20.003125,0,5.739898468,90.00000001 +220.65,50.30085681,-3.037469334,10159.5886,-1.02E-10,198.9984204,-20.003125,0,5.739898468,90.00000001 +220.66,50.30085681,-3.037441448,10159.7886,-5.78E-11,198.9973116,-20.001875,0,5.739898468,90.00000001 +220.67,50.30085681,-3.037413562,10159.9886,-5.62E-11,198.9964258,-20.001875,0,5.739898468,90.00000001 +220.68,50.30085681,-3.037385676,10160.1886,-9.37E-11,198.996432,-20.003125,0,5.739898468,90.00000001 +220.69,50.30085681,-3.03735779,10160.3887,-9.38E-11,198.9973302,-20.003125,0,5.739898468,90.00000001 +220.7,50.30085681,-3.037329904,10160.5887,-5.63E-11,198.9984514,-20.001875,0,5.739898468,90.00000001 +220.71,50.30085681,-3.037302017,10160.7887,-5.78E-11,198.9984577,-20.001875,0,5.739898468,90.00000001 +220.72,50.30085681,-3.037274131,10160.9887,-1.02E-10,198.9973489,-20.003125,0,5.739898468,90.00000001 +220.73,50.30085681,-3.037246245,10161.1888,-1.09E-10,198.9964631,-20.003125,0,5.739898468,90.00000001 +220.74,50.30085681,-3.037218359,10161.3888,-7.19E-11,198.9962463,-20.001875,0,5.739898468,90.00000001 +220.75,50.30085681,-3.037190473,10161.5888,-6.41E-11,198.9962525,-20.001875,0,5.739898468,90.00000001 +220.76,50.30085681,-3.037162587,10161.7888,-9.53E-11,198.9962587,-20.003125,0,5.739898468,90.00000001 +220.77,50.30085681,-3.037134701,10161.9889,-8.44E-11,198.996488,-20.0034375,0,5.739898468,90.00000001 +220.78,50.30085681,-3.037106815,10162.1889,0,198.9973862,-20.003125,0,5.739898468,90.00000001 +220.79,50.30085681,-3.037078929,10162.3889,8.44E-11,198.9985074,-20.0034375,0,5.739898468,90.00000001 +220.8,50.30085681,-3.037051042,10162.589,9.53E-11,198.9985136,-20.003125,0,5.739898468,90.00000001 +220.81,50.30085681,-3.037023156,10162.789,6.41E-11,198.9974048,-20.001875,0,5.739898468,90.00000001 +220.82,50.30085681,-3.03699527,10162.989,7.19E-11,198.996519,-20.001875,0,5.739898468,90.00000001 +220.83,50.30085681,-3.036967384,10163.189,1.09E-10,198.9965253,-20.003125,0,5.739898468,90.00000001 +220.84,50.30085681,-3.036939498,10163.3891,1.02E-10,198.9972005,-20.003125,0,5.739898468,90.00000001 +220.85,50.30085681,-3.036911612,10163.5891,5.78E-11,198.9976527,-20.001875,0,5.739898468,90.00000001 +220.86,50.30085681,-3.036883725,10163.7891,5.63E-11,198.9974359,-20.001875,0,5.739898468,90.00000001 +220.87,50.30085681,-3.03685584,10163.9891,9.38E-11,198.9974421,-20.003125,0,5.739898468,90.00000001 +220.88,50.30085681,-3.036827953,10164.1892,9.38E-11,198.9976714,-20.003125,0,5.739898468,90.00000001 +220.89,50.30085681,-3.036800067,10164.3892,5.47E-11,198.9972316,-20.001875,0,5.739898468,90.00000001 +220.9,50.30085681,-3.036772181,10164.5892,4.84E-11,198.9965688,-20.001875,0,5.739898468,90.00000001 +220.91,50.30085681,-3.036744295,10164.7892,7.81E-11,198.996575,-20.003125,0,5.739898468,90.00000001 +220.92,50.30085681,-3.036716409,10164.9893,7.81E-11,198.9974732,-20.003125,0,5.739898468,90.00000001 +220.93,50.30085681,-3.036688523,10165.1893,4.84E-11,198.9983715,-20.001875,0,5.739898468,90.00000001 +220.94,50.30085681,-3.036660636,10165.3893,5.47E-11,198.9977087,-20.001875,0,5.739898468,90.00000001 +220.95,50.30085681,-3.03663275,10165.5893,9.37E-11,198.9963769,-20.003125,0,5.739898468,90.00000001 +220.96,50.30085681,-3.036604865,10165.7894,9.38E-11,198.9966061,-20.003125,0,5.739898468,90.00000001 +220.97,50.30085681,-3.036576978,10165.9894,5.63E-11,198.9975043,-20.001875,0,5.739898468,90.00000001 +220.98,50.30085681,-3.036549092,10166.1894,5.63E-11,198.9972876,-20.001875,0,5.739898468,90.00000001 +220.99,50.30085681,-3.036521206,10166.3894,9.22E-11,198.9966248,-20.003125,0,5.739898468,90.00000001 +221,50.30085681,-3.03649332,10166.5895,8.59E-11,198.996631,-20.003125,0,5.739898468,90.00000001 +221.01,50.30085681,-3.036465434,10166.7895,4.06E-11,198.9975292,-20.001875,0,5.739898468,90.00000001 +221.02,50.30085681,-3.036437548,10166.9895,4.06E-11,198.9986504,-20.001875,0,5.739898468,90.00000001 +221.03,50.30085681,-3.036409661,10167.1895,8.59E-11,198.9986567,-20.003125,0,5.739898468,90.00000001 +221.04,50.30085681,-3.036381775,10167.3896,9.22E-11,198.9975479,-20.003125,0,5.739898468,90.00000001 +221.05,50.30085681,-3.036353889,10167.5896,5.62E-11,198.9966621,-20.001875,0,5.739898468,90.00000001 +221.06,50.30085681,-3.036326003,10167.7896,5.62E-11,198.9964453,-20.001875,0,5.739898468,90.00000001 +221.07,50.30085681,-3.036298117,10167.9896,9.37E-11,198.9964515,-20.003125,0,5.739898468,90.00000001 +221.08,50.30085681,-3.036270231,10168.1897,9.53E-11,198.9964577,-20.003125,0,5.739898468,90.00000001 +221.09,50.30085681,-3.036242345,10168.3897,6.41E-11,198.9966869,-20.001875,0,5.739898468,90.00000001 +221.1,50.30085681,-3.036214459,10168.5897,7.19E-11,198.9973622,-20.001875,0,5.739898468,90.00000001 +221.11,50.30085681,-3.036186573,10168.7897,1.09E-10,198.9978144,-20.003125,0,5.739898468,90.00000001 +221.12,50.30085681,-3.036158686,10168.9898,1.02E-10,198.9975976,-20.003125,0,5.739898468,90.00000001 +221.13,50.30085681,-3.036130801,10169.1898,5.78E-11,198.9976038,-20.001875,0,5.739898468,90.00000001 +221.14,50.30085681,-3.036102914,10169.3898,5.62E-11,198.9978331,-20.001875,0,5.739898468,90.00000001 +221.15,50.30085681,-3.036075028,10169.5898,9.37E-11,198.9973933,-20.003125,0,5.739898468,90.00000001 +221.16,50.30085681,-3.036047142,10169.7899,9.37E-11,198.9967305,-20.003125,0,5.739898468,90.00000001 +221.17,50.30085681,-3.036019256,10169.9899,5.47E-11,198.9965137,-20.001875,0,5.739898468,90.00000001 +221.18,50.30085681,-3.03599137,10170.1899,4.84E-11,198.9965199,-20.001875,0,5.739898468,90.00000001 +221.19,50.30085681,-3.035963484,10170.3899,7.81E-11,198.9965261,-20.003125,0,5.739898468,90.00000001 +221.2,50.30085681,-3.035935598,10170.59,7.81E-11,198.9965323,-20.003125,0,5.739898468,90.00000001 +221.21,50.30085681,-3.035907712,10170.79,4.84E-11,198.9967616,-20.001875,0,5.739898468,90.00000001 +221.22,50.30085681,-3.035879826,10170.99,5.47E-11,198.9976598,-20.001875,0,5.739898468,90.00000001 +221.23,50.30085681,-3.03585194,10171.19,9.38E-11,198.998781,-20.003125,0,5.739898468,90.00000001 +221.24,50.30085681,-3.035824053,10171.3901,9.37E-11,198.9987872,-20.003125,0,5.739898468,90.00000001 +221.25,50.30085681,-3.035796167,10171.5901,5.62E-11,198.9976785,-20.001875,0,5.739898468,90.00000001 +221.26,50.30085681,-3.035768281,10171.7901,5.62E-11,198.9967927,-20.001875,0,5.739898468,90.00000001 +221.27,50.30085681,-3.035740395,10171.9901,9.22E-11,198.9965759,-20.003125,0,5.739898468,90.00000001 +221.28,50.30085681,-3.035712509,10172.1902,8.59E-11,198.9965821,-20.003125,0,5.739898468,90.00000001 +221.29,50.30085681,-3.035684623,10172.3902,4.06E-11,198.9965883,-20.001875,0,5.739898468,90.00000001 +221.3,50.30085681,-3.035656737,10172.5902,4.06E-11,198.9965945,-20.001875,0,5.739898468,90.00000001 +221.31,50.30085681,-3.035628851,10172.7902,8.59E-11,198.9968238,-20.003125,0,5.739898468,90.00000001 +221.32,50.30085681,-3.035600965,10172.9903,9.22E-11,198.997499,-20.003125,0,5.739898468,90.00000001 +221.33,50.30085681,-3.035573079,10173.1903,5.63E-11,198.9979512,-20.001875,0,5.739898468,90.00000001 +221.34,50.30085681,-3.035545192,10173.3903,5.63E-11,198.9977344,-20.001875,0,5.739898468,90.00000001 +221.35,50.30085681,-3.035517307,10173.5903,9.38E-11,198.9977406,-20.003125,0,5.739898468,90.00000001 +221.36,50.30085681,-3.03548942,10173.7904,9.53E-11,198.9979699,-20.003125,0,5.739898468,90.00000001 +221.37,50.30085681,-3.035461534,10173.9904,6.41E-11,198.9975301,-20.001875,0,5.739898468,90.00000001 +221.38,50.30085681,-3.035433648,10174.1904,7.19E-11,198.9968673,-20.001875,0,5.739898468,90.00000001 +221.39,50.30085681,-3.035405762,10174.3904,1.09E-10,198.9966505,-20.003125,0,5.739898468,90.00000001 +221.4,50.30085681,-3.035377876,10174.5905,1.02E-10,198.9966567,-20.003125,0,5.739898468,90.00000001 +221.41,50.30085681,-3.03534999,10174.7905,5.78E-11,198.9966629,-20.001875,0,5.739898468,90.00000001 +221.42,50.30085681,-3.035322104,10174.9905,5.62E-11,198.9966692,-20.001875,0,5.739898468,90.00000001 +221.43,50.30085681,-3.035294218,10175.1905,9.37E-11,198.9968984,-20.003125,0,5.739898468,90.00000001 +221.44,50.30085681,-3.035266332,10175.3906,9.38E-11,198.9977966,-20.003125,0,5.739898468,90.00000001 +221.45,50.30085681,-3.035238446,10175.5906,5.63E-11,198.9986948,-20.001875,0,5.739898468,90.00000001 +221.46,50.30085681,-3.035210559,10175.7906,5.78E-11,198.998032,-20.001875,0,5.739898468,90.00000001 +221.47,50.30085681,-3.035182673,10175.9906,1.02E-10,198.9967002,-20.003125,0,5.739898468,90.00000001 +221.48,50.30085681,-3.035154788,10176.1907,1.09E-10,198.9969295,-20.003125,0,5.739898468,90.00000001 +221.49,50.30085681,-3.035126901,10176.3907,7.19E-11,198.9978277,-20.001875,0,5.739898468,90.00000001 +221.5,50.30085681,-3.035099015,10176.5907,6.41E-11,198.9976109,-20.001875,0,5.739898468,90.00000001 +221.51,50.30085681,-3.035071129,10176.7907,9.53E-11,198.9969481,-20.003125,0,5.739898468,90.00000001 +221.52,50.30085681,-3.035043243,10176.9908,9.37E-11,198.9967313,-20.003125,0,5.739898468,90.00000001 +221.53,50.30085681,-3.035015357,10177.1908,5.62E-11,198.9967376,-20.001875,0,5.739898468,90.00000001 +221.54,50.30085681,-3.034987471,10177.3908,5.62E-11,198.9967438,-20.001875,0,5.739898468,90.00000001 +221.55,50.30085681,-3.034959585,10177.5908,9.22E-11,198.99675,-20.003125,0,5.739898468,90.00000001 +221.56,50.30085681,-3.034931699,10177.7909,8.59E-11,198.9967562,-20.003125,0,5.739898468,90.00000001 +221.57,50.30085681,-3.034903813,10177.9909,4.06E-11,198.9969854,-20.001875,0,5.739898468,90.00000001 +221.58,50.30085681,-3.034875927,10178.1909,4.06E-11,198.9976607,-20.001875,0,5.739898468,90.00000001 +221.59,50.30085681,-3.034848041,10178.3909,8.59E-11,198.9981129,-20.003125,0,5.739898468,90.00000001 +221.6,50.30085681,-3.034820154,10178.591,9.22E-11,198.9978961,-20.003125,0,5.739898468,90.00000001 +221.61,50.30085681,-3.034792269,10178.791,5.62E-11,198.9979023,-20.001875,0,5.739898468,90.00000001 +221.62,50.30085681,-3.034764382,10178.991,5.62E-11,198.9981315,-20.001875,0,5.739898468,90.00000001 +221.63,50.30085681,-3.034736496,10179.191,9.37E-11,198.9976918,-20.003125,0,5.739898468,90.00000001 +221.64,50.30085681,-3.03470861,10179.3911,8.59E-11,198.997029,-20.0034375,0,5.739898468,90.00000001 +221.65,50.30085681,-3.034680724,10179.5911,7.81E-12,198.9968122,-20.003125,0,5.739898468,90.00000001 +221.66,50.30085681,-3.034652838,10179.7911,-6.88E-11,198.9968184,-20.0034375,0,5.739898468,90.00000001 +221.67,50.30085681,-3.034624952,10179.9912,-7.81E-11,198.9968246,-20.003125,0,5.739898468,90.00000001 +221.68,50.30085681,-3.034597066,10180.1912,-4.84E-11,198.9968308,-20.001875,0,5.739898468,90.00000001 +221.69,50.30085681,-3.03456918,10180.3912,-5.47E-11,198.9968371,-20.001875,0,5.739898468,90.00000001 +221.7,50.30085681,-3.034541294,10180.5912,-9.37E-11,198.9968433,-20.003125,0,5.739898468,90.00000001 +221.71,50.30085681,-3.034513408,10180.7913,-9.38E-11,198.9968495,-20.003125,0,5.739898468,90.00000001 +221.72,50.30085681,-3.034485522,10180.9913,-5.63E-11,198.9968557,-20.001875,0,5.739898468,90.00000001 +221.73,50.30085681,-3.034457636,10181.1913,-5.63E-11,198.9968619,-20.001875,0,5.739898468,90.00000001 +221.74,50.30085681,-3.03442975,10181.3913,-9.22E-11,198.9970911,-20.003125,0,5.739898468,90.00000001 +221.75,50.30085681,-3.034401864,10181.5914,-8.59E-11,198.9977664,-20.003125,0,5.739898468,90.00000001 +221.76,50.30085681,-3.034373978,10181.7914,-4.06E-11,198.9979956,-20.001875,0,5.739898468,90.00000001 +221.77,50.30085681,-3.034346091,10181.9914,-4.06E-11,198.9971098,-20.001875,0,5.739898468,90.00000001 +221.78,50.30085681,-3.034318206,10182.1914,-8.59E-11,198.996893,-20.003125,0,5.739898468,90.00000001 +221.79,50.30085681,-3.03429032,10182.3915,-9.22E-11,198.9980143,-20.003125,0,5.739898468,90.00000001 +221.8,50.30085681,-3.034262433,10182.5915,-5.62E-11,198.9980205,-20.001875,0,5.739898468,90.00000001 +221.81,50.30085681,-3.034234547,10182.7915,-5.62E-11,198.9969117,-20.001875,0,5.739898468,90.00000001 +221.82,50.30085681,-3.034206662,10182.9915,-9.37E-11,198.9971409,-20.003125,0,5.739898468,90.00000001 +221.83,50.30085681,-3.034178775,10183.1916,-9.53E-11,198.9980391,-20.003125,0,5.739898468,90.00000001 +221.84,50.30085681,-3.034150889,10183.3916,-6.41E-11,198.9978223,-20.001875,0,5.739898468,90.00000001 +221.85,50.30085681,-3.034123003,10183.5916,-7.19E-11,198.9971596,-20.001875,0,5.739898468,90.00000001 +221.86,50.30085681,-3.034095117,10183.7916,-1.09E-10,198.9969428,-20.003125,0,5.739898468,90.00000001 +221.87,50.30085681,-3.034067231,10183.9917,-1.02E-10,198.996949,-20.003125,0,5.739898468,90.00000001 +221.88,50.30085681,-3.034039345,10184.1917,-5.78E-11,198.9969552,-20.001875,0,5.739898468,90.00000001 +221.89,50.30085681,-3.034011459,10184.3917,-5.62E-11,198.9969614,-20.001875,0,5.739898468,90.00000001 +221.9,50.30085681,-3.033983573,10184.5917,-9.37E-11,198.9969676,-20.003125,0,5.739898468,90.00000001 +221.91,50.30085681,-3.033955687,10184.7918,-9.37E-11,198.9969739,-20.003125,0,5.739898468,90.00000001 +221.92,50.30085681,-3.033927801,10184.9918,-5.47E-11,198.9969801,-20.001875,0,5.739898468,90.00000001 +221.93,50.30085681,-3.033899915,10185.1918,-4.84E-11,198.9969863,-20.001875,0,5.739898468,90.00000001 +221.94,50.30085681,-3.033872029,10185.3918,-7.81E-11,198.9969925,-20.003125,0,5.739898468,90.00000001 +221.95,50.30085681,-3.033844143,10185.5919,-7.81E-11,198.9969987,-20.003125,0,5.739898468,90.00000001 +221.96,50.30085681,-3.033816257,10185.7919,-4.84E-11,198.997005,-20.001875,0,5.739898468,90.00000001 +221.97,50.30085681,-3.033788371,10185.9919,-5.47E-11,198.9970112,-20.001875,0,5.739898468,90.00000001 +221.98,50.30085681,-3.033760485,10186.1919,-9.38E-11,198.9970174,-20.003125,0,5.739898468,90.00000001 +221.99,50.30085681,-3.033732599,10186.392,-9.37E-11,198.9972466,-20.003125,0,5.739898468,90.00000001 +222,50.30085681,-3.033704713,10186.592,-5.62E-11,198.9979218,-20.001875,0,5.739898468,90.00000001 +222.01,50.30085681,-3.033676827,10186.792,-5.62E-11,198.9981511,-20.001875,0,5.739898468,90.00000001 +222.02,50.30085681,-3.03364894,10186.992,-9.22E-11,198.9972653,-20.003125,0,5.739898468,90.00000001 +222.03,50.30085681,-3.033621055,10187.1921,-8.59E-11,198.9970485,-20.003125,0,5.739898468,90.00000001 +222.04,50.30085681,-3.033593169,10187.3921,-4.06E-11,198.9981697,-20.001875,0,5.739898468,90.00000001 +222.05,50.30085681,-3.033565282,10187.5921,-4.06E-11,198.9979529,-20.001875,0,5.739898468,90.00000001 +222.06,50.30085681,-3.033537396,10187.7921,-8.59E-11,198.9961751,-20.003125,0,5.739898468,90.00000001 +222.07,50.30085681,-3.033509511,10187.9922,-9.22E-11,198.9961813,-20.003125,0,5.739898468,90.00000001 +222.08,50.30085681,-3.033481625,10188.1922,-5.63E-11,198.9979716,-20.001875,0,5.739898468,90.00000001 +222.09,50.30085681,-3.033453738,10188.3922,-5.63E-11,198.9982008,-20.001875,0,5.739898468,90.00000001 +222.1,50.30085681,-3.033425852,10188.5922,-9.38E-11,198.997092,-20.003125,0,5.739898468,90.00000001 +222.11,50.30085681,-3.033397967,10188.7923,-9.53E-11,198.9973212,-20.003125,0,5.739898468,90.00000001 +222.12,50.30085681,-3.03337008,10188.9923,-6.41E-11,198.9979965,-20.001875,0,5.739898468,90.00000001 +222.13,50.30085681,-3.033342194,10189.1923,-7.19E-11,198.9971107,-20.001875,0,5.739898468,90.00000001 +222.14,50.30085681,-3.033314308,10189.3923,-1.09E-10,198.9962249,-20.003125,0,5.739898468,90.00000001 +222.15,50.30085681,-3.033286423,10189.5924,-1.02E-10,198.9971231,-20.003125,0,5.739898468,90.00000001 +222.16,50.30085681,-3.033258536,10189.7924,-5.78E-11,198.9980213,-20.001875,0,5.739898468,90.00000001 +222.17,50.30085681,-3.03323065,10189.9924,-5.63E-11,198.9971355,-20.001875,0,5.739898468,90.00000001 +222.18,50.30085681,-3.033202764,10190.1924,-9.38E-11,198.9962497,-20.003125,0,5.739898468,90.00000001 +222.19,50.30085681,-3.033174879,10190.3925,-9.38E-11,198.997148,-20.003125,0,5.739898468,90.00000001 +222.2,50.30085681,-3.033146992,10190.5925,-5.47E-11,198.9982692,-20.001875,0,5.739898468,90.00000001 +222.21,50.30085681,-3.033119106,10190.7925,-4.84E-11,198.9980524,-20.001875,0,5.739898468,90.00000001 +222.22,50.30085681,-3.03309122,10190.9925,-7.81E-11,198.9973896,-20.003125,0,5.739898468,90.00000001 +222.23,50.30085681,-3.033063334,10191.1926,-7.81E-11,198.9971729,-20.003125,0,5.739898468,90.00000001 +222.24,50.30085681,-3.033035448,10191.3926,-4.84E-11,198.9971791,-20.001875,0,5.739898468,90.00000001 +222.25,50.30085681,-3.033007562,10191.5926,-5.47E-11,198.9971853,-20.001875,0,5.739898468,90.00000001 +222.26,50.30085681,-3.032979676,10191.7926,-9.37E-11,198.9971915,-20.003125,0,5.739898468,90.00000001 +222.27,50.30085681,-3.03295179,10191.9927,-9.37E-11,198.9971977,-20.003125,0,5.739898468,90.00000001 +222.28,50.30085681,-3.032923904,10192.1927,-5.62E-11,198.9972039,-20.001875,0,5.739898468,90.00000001 +222.29,50.30085681,-3.032896018,10192.3927,-5.62E-11,198.9972102,-20.001875,0,5.739898468,90.00000001 +222.3,50.30085681,-3.032868132,10192.5927,-9.22E-11,198.9972164,-20.003125,0,5.739898468,90.00000001 +222.31,50.30085681,-3.032840246,10192.7928,-8.59E-11,198.9972226,-20.003125,0,5.739898468,90.00000001 +222.32,50.30085681,-3.03281236,10192.9928,-4.06E-11,198.9972288,-20.001875,0,5.739898468,90.00000001 +222.33,50.30085681,-3.032784474,10193.1928,-4.06E-11,198.997235,-20.001875,0,5.739898468,90.00000001 +222.34,50.30085681,-3.032756588,10193.3928,-8.59E-11,198.9972413,-20.003125,0,5.739898468,90.00000001 +222.35,50.30085681,-3.032728702,10193.5929,-9.22E-11,198.9972475,-20.003125,0,5.739898468,90.00000001 +222.36,50.30085681,-3.032700816,10193.7929,-5.62E-11,198.9972537,-20.001875,0,5.739898468,90.00000001 +222.37,50.30085681,-3.03267293,10193.9929,-5.62E-11,198.9972599,-20.001875,0,5.739898468,90.00000001 +222.38,50.30085681,-3.032645044,10194.1929,-9.37E-11,198.9972661,-20.003125,0,5.739898468,90.00000001 +222.39,50.30085681,-3.032617158,10194.393,-9.53E-11,198.9972723,-20.003125,0,5.739898468,90.00000001 +222.4,50.30085681,-3.032589272,10194.593,-6.41E-11,198.9972786,-20.001875,0,5.739898468,90.00000001 +222.41,50.30085681,-3.032561386,10194.793,-7.19E-11,198.9972848,-20.001875,0,5.739898468,90.00000001 +222.42,50.30085681,-3.0325335,10194.993,-1.09E-10,198.997291,-20.003125,0,5.739898468,90.00000001 +222.43,50.30085681,-3.032505614,10195.1931,-1.02E-10,198.9972972,-20.003125,0,5.739898468,90.00000001 +222.44,50.30085681,-3.032477728,10195.3931,-5.78E-11,198.9973034,-20.001875,0,5.739898468,90.00000001 +222.45,50.30085681,-3.032449842,10195.5931,-5.63E-11,198.9973097,-20.001875,0,5.739898468,90.00000001 +222.46,50.30085681,-3.032421956,10195.7931,-9.38E-11,198.9973159,-20.003125,0,5.739898468,90.00000001 +222.47,50.30085681,-3.03239407,10195.9932,-9.37E-11,198.9973221,-20.003125,0,5.739898468,90.00000001 +222.48,50.30085681,-3.032366184,10196.1932,-5.47E-11,198.9971053,-20.001875,0,5.739898468,90.00000001 +222.49,50.30085681,-3.032338298,10196.3932,-4.84E-11,198.9964425,-20.001875,0,5.739898468,90.00000001 +222.5,50.30085681,-3.032310412,10196.5932,-7.81E-11,198.9962257,-20.003125,0,5.739898468,90.00000001 +222.51,50.30085681,-3.032282527,10196.7933,-6.88E-11,198.997347,-20.0034375,0,5.739898468,90.00000001 +222.52,50.30085681,-3.03225464,10196.9933,7.81E-12,198.9982452,-20.003125,0,5.739898468,90.00000001 +222.53,50.30085681,-3.032226754,10197.1933,8.59E-11,198.9973594,-20.0034375,0,5.739898468,90.00000001 +222.54,50.30085681,-3.032198868,10197.3934,9.37E-11,198.9964736,-20.003125,0,5.739898468,90.00000001 +222.55,50.30085681,-3.032170983,10197.5934,5.62E-11,198.9973718,-20.001875,0,5.739898468,90.00000001 +222.56,50.30085681,-3.032143096,10197.7934,5.62E-11,198.9982701,-20.001875,0,5.739898468,90.00000001 +222.57,50.30085681,-3.03211521,10197.9934,9.37E-11,198.9971613,-20.003125,0,5.739898468,90.00000001 +222.58,50.30085681,-3.032087324,10198.1935,9.53E-11,198.9956065,-20.003125,0,5.739898468,90.00000001 +222.59,50.30085681,-3.032059439,10198.3935,6.41E-11,198.9962817,-20.001875,0,5.739898468,90.00000001 +222.6,50.30085681,-3.032031553,10198.5935,7.19E-11,198.9982949,-20.001875,0,5.739898468,90.00000001 +222.61,50.30085681,-3.032003666,10198.7935,1.09E-10,198.9983012,-20.003125,0,5.739898468,90.00000001 +222.62,50.30085681,-3.03197578,10198.9936,1.02E-10,198.9963004,-20.003125,0,5.739898468,90.00000001 +222.63,50.30085681,-3.031947895,10199.1936,5.78E-11,198.9956376,-20.001875,0,5.739898468,90.00000001 +222.64,50.30085681,-3.031920009,10199.3936,5.62E-11,198.9972048,-20.001875,0,5.739898468,90.00000001 +222.65,50.30085681,-3.031892123,10199.5936,9.37E-11,198.998326,-20.003125,0,5.739898468,90.00000001 +222.66,50.30085681,-3.031864236,10199.7937,9.37E-11,198.9974402,-20.003125,0,5.739898468,90.00000001 +222.67,50.30085681,-3.031836351,10199.9937,5.47E-11,198.9963314,-20.001875,0,5.739898468,90.00000001 +222.68,50.30085681,-3.031808465,10200.1937,4.84E-11,198.9965607,-20.001875,0,5.739898468,90.00000001 +222.69,50.30085681,-3.031780579,10200.3937,7.81E-11,198.9972359,-20.003125,0,5.739898468,90.00000001 +222.7,50.30085681,-3.031752693,10200.5938,7.81E-11,198.9974651,-20.003125,0,5.739898468,90.00000001 +222.71,50.30085681,-3.031724807,10200.7938,4.84E-11,198.9974713,-20.001875,0,5.739898468,90.00000001 +222.72,50.30085681,-3.031696921,10200.9938,5.47E-11,198.9974776,-20.001875,0,5.739898468,90.00000001 +222.73,50.30085681,-3.031669035,10201.1938,9.38E-11,198.9974838,-20.003125,0,5.739898468,90.00000001 +222.74,50.30085681,-3.031641149,10201.3939,9.37E-11,198.99749,-20.003125,0,5.739898468,90.00000001 +222.75,50.30085681,-3.031613263,10201.5939,5.62E-11,198.9974962,-20.001875,0,5.739898468,90.00000001 +222.76,50.30085681,-3.031585377,10201.7939,5.78E-11,198.9975024,-20.001875,0,5.739898468,90.00000001 +222.77,50.30085681,-3.031557491,10201.9939,1.02E-10,198.9975086,-20.003125,0,5.739898468,90.00000001 +222.78,50.30085681,-3.031529605,10202.194,1.09E-10,198.9975149,-20.003125,0,5.739898468,90.00000001 +222.79,50.30085681,-3.031501719,10202.394,7.19E-11,198.9975211,-20.001875,0,5.739898468,90.00000001 +222.8,50.30085681,-3.031473833,10202.594,6.41E-11,198.9975273,-20.001875,0,5.739898468,90.00000001 +222.81,50.30085681,-3.031445947,10202.794,9.53E-11,198.9975335,-20.003125,0,5.739898468,90.00000001 +222.82,50.30085681,-3.031418061,10202.9941,9.38E-11,198.9975397,-20.003125,0,5.739898468,90.00000001 +222.83,50.30085681,-3.031390175,10203.1941,5.63E-11,198.997323,-20.001875,0,5.739898468,90.00000001 +222.84,50.30085681,-3.031362289,10203.3941,5.63E-11,198.9966602,-20.001875,0,5.739898468,90.00000001 +222.85,50.30085681,-3.031334403,10203.5941,9.38E-11,198.9964434,-20.003125,0,5.739898468,90.00000001 +222.86,50.30085681,-3.031306518,10203.7942,9.53E-11,198.9973416,-20.003125,0,5.739898468,90.00000001 +222.87,50.30085681,-3.031278631,10203.9942,6.41E-11,198.9975708,-20.001875,0,5.739898468,90.00000001 +222.88,50.30085681,-3.031250745,10204.1942,7.19E-11,198.996239,-20.001875,0,5.739898468,90.00000001 +222.89,50.30085681,-3.03122286,10204.3942,1.09E-10,198.9955762,-20.003125,0,5.739898468,90.00000001 +222.9,50.30085681,-3.031194974,10204.5943,1.02E-10,198.9964745,-20.003125,0,5.739898468,90.00000001 +222.91,50.30085681,-3.031167088,10204.7943,5.78E-11,198.9973727,-20.001875,0,5.739898468,90.00000001 +222.92,50.30085681,-3.031139202,10204.9943,5.63E-11,198.9976019,-20.001875,0,5.739898468,90.00000001 +222.93,50.30085681,-3.031111316,10205.1943,9.38E-11,198.9976081,-20.003125,0,5.739898468,90.00000001 +222.94,50.30085681,-3.03108343,10205.3944,9.38E-11,198.9976144,-20.003125,0,5.739898468,90.00000001 +222.95,50.30085681,-3.031055544,10205.5944,5.47E-11,198.9976206,-20.001875,0,5.739898468,90.00000001 +222.96,50.30085681,-3.031027658,10205.7944,4.84E-11,198.9976268,-20.001875,0,5.739898468,90.00000001 +222.97,50.30085681,-3.030999772,10205.9944,7.81E-11,198.997633,-20.003125,0,5.739898468,90.00000001 +222.98,50.30085681,-3.030971886,10206.1945,7.81E-11,198.9976392,-20.003125,0,5.739898468,90.00000001 +222.99,50.30085681,-3.030944,10206.3945,4.84E-11,198.9976455,-20.001875,0,5.739898468,90.00000001 +223,50.30085681,-3.030916114,10206.5945,5.47E-11,198.9976517,-20.001875,0,5.739898468,90.00000001 +223.01,50.30085681,-3.030888228,10206.7945,9.37E-11,198.9974349,-20.003125,0,5.739898468,90.00000001 +223.02,50.30085681,-3.030860342,10206.9946,9.38E-11,198.9965491,-20.003125,0,5.739898468,90.00000001 +223.03,50.30085681,-3.030832456,10207.1946,5.63E-11,198.9954403,-20.001875,0,5.739898468,90.00000001 +223.04,50.30085681,-3.030804571,10207.3946,5.78E-11,198.9956695,-20.001875,0,5.739898468,90.00000001 +223.05,50.30085681,-3.030776685,10207.5946,1.02E-10,198.9974598,-20.003125,0,5.739898468,90.00000001 +223.06,50.30085681,-3.030748799,10207.7947,1.09E-10,198.998581,-20.003125,0,5.739898468,90.00000001 +223.07,50.30085681,-3.030720912,10207.9947,7.19E-11,198.9976952,-20.001875,0,5.739898468,90.00000001 +223.08,50.30085681,-3.030693027,10208.1947,6.41E-11,198.9965864,-20.001875,0,5.739898468,90.00000001 +223.09,50.30085681,-3.030665141,10208.3947,9.53E-11,198.9968156,-20.003125,0,5.739898468,90.00000001 +223.1,50.30085681,-3.030637255,10208.5948,9.37E-11,198.9974909,-20.003125,0,5.739898468,90.00000001 +223.11,50.30085681,-3.030609369,10208.7948,5.62E-11,198.9977201,-20.001875,0,5.739898468,90.00000001 +223.12,50.30085681,-3.030581483,10208.9948,5.62E-11,198.9977263,-20.001875,0,5.739898468,90.00000001 +223.13,50.30085681,-3.030553597,10209.1948,9.37E-11,198.9977325,-20.003125,0,5.739898468,90.00000001 +223.14,50.30085681,-3.030525711,10209.3949,9.53E-11,198.9977387,-20.003125,0,5.739898468,90.00000001 +223.15,50.30085681,-3.030497825,10209.5949,6.41E-11,198.997745,-20.001875,0,5.739898468,90.00000001 +223.16,50.30085681,-3.030469939,10209.7949,7.19E-11,198.9975282,-20.001875,0,5.739898468,90.00000001 +223.17,50.30085681,-3.030442053,10209.9949,1.09E-10,198.9966424,-20.003125,0,5.739898468,90.00000001 +223.18,50.30085681,-3.030414167,10210.195,1.02E-10,198.9955336,-20.003125,0,5.739898468,90.00000001 +223.19,50.30085681,-3.030386282,10210.395,5.78E-11,198.9955398,-20.001875,0,5.739898468,90.00000001 +223.2,50.30085681,-3.030358396,10210.595,5.62E-11,198.996661,-20.001875,0,5.739898468,90.00000001 +223.21,50.30085681,-3.03033051,10210.795,9.37E-11,198.9975593,-20.003125,0,5.739898468,90.00000001 +223.22,50.30085681,-3.030302624,10210.9951,9.37E-11,198.9977885,-20.003125,0,5.739898468,90.00000001 +223.23,50.30085681,-3.030274738,10211.1951,5.47E-11,198.9977947,-20.001875,0,5.739898468,90.00000001 +223.24,50.30085681,-3.030246852,10211.3951,4.84E-11,198.9978009,-20.001875,0,5.739898468,90.00000001 +223.25,50.30085681,-3.030218966,10211.5951,7.81E-11,198.9978071,-20.003125,0,5.739898468,90.00000001 +223.26,50.30085681,-3.03019108,10211.7952,7.81E-11,198.9978134,-20.003125,0,5.739898468,90.00000001 +223.27,50.30085681,-3.030163194,10211.9952,4.84E-11,198.9975966,-20.001875,0,5.739898468,90.00000001 +223.28,50.30085681,-3.030135308,10212.1952,5.47E-11,198.9967108,-20.001875,0,5.739898468,90.00000001 +223.29,50.30085681,-3.030107422,10212.3952,9.38E-11,198.995825,-20.003125,0,5.739898468,90.00000001 +223.3,50.30085681,-3.030079537,10212.5953,9.38E-11,198.9967232,-20.003125,0,5.739898468,90.00000001 +223.31,50.30085681,-3.030051651,10212.7953,5.63E-11,198.9987365,-20.001875,0,5.739898468,90.00000001 +223.32,50.30085681,-3.030023764,10212.9953,5.63E-11,198.9987427,-20.001875,0,5.739898468,90.00000001 +223.33,50.30085681,-3.029995878,10213.1953,9.22E-11,198.9967419,-20.003125,0,5.739898468,90.00000001 +223.34,50.30085681,-3.029967993,10213.3954,8.59E-11,198.9958561,-20.003125,0,5.739898468,90.00000001 +223.35,50.30085681,-3.029940107,10213.5954,4.06E-11,198.9967543,-20.001875,0,5.739898468,90.00000001 +223.36,50.30085681,-3.029912221,10213.7954,4.06E-11,198.9976525,-20.001875,0,5.739898468,90.00000001 +223.37,50.30085681,-3.029884335,10213.9954,8.59E-11,198.9978818,-20.003125,0,5.739898468,90.00000001 +223.38,50.30085681,-3.029856449,10214.1955,9.22E-11,198.997665,-20.003125,0,5.739898468,90.00000001 +223.39,50.30085681,-3.029828563,10214.3955,5.63E-11,198.9967792,-20.001875,0,5.739898468,90.00000001 +223.4,50.30085681,-3.029800677,10214.5955,5.63E-11,198.9958934,-20.001875,0,5.739898468,90.00000001 +223.41,50.30085681,-3.029772792,10214.7955,9.38E-11,198.9967916,-20.003125,0,5.739898468,90.00000001 +223.42,50.30085681,-3.029744906,10214.9956,8.59E-11,198.9988049,-20.0034375,0,5.739898468,90.00000001 +223.43,50.30085681,-3.029717019,10215.1956,7.81E-12,198.9988111,-20.003125,0,5.739898468,90.00000001 +223.44,50.30085681,-3.029689133,10215.3956,-6.87E-11,198.9968103,-20.0034375,0,5.739898468,90.00000001 +223.45,50.30085681,-3.029661248,10215.5957,-7.81E-11,198.9959245,-20.003125,0,5.739898468,90.00000001 +223.46,50.30085681,-3.029633362,10215.7957,-4.84E-11,198.9968227,-20.001875,0,5.739898468,90.00000001 +223.47,50.30085681,-3.029605476,10215.9957,-5.47E-11,198.9977209,-20.001875,0,5.739898468,90.00000001 +223.48,50.30085681,-3.02957759,10216.1957,-9.38E-11,198.9979502,-20.003125,0,5.739898468,90.00000001 +223.49,50.30085681,-3.029549704,10216.3958,-9.37E-11,198.9977334,-20.003125,0,5.739898468,90.00000001 +223.5,50.30085681,-3.029521818,10216.5958,-5.62E-11,198.9968476,-20.001875,0,5.739898468,90.00000001 +223.51,50.30085681,-3.029493932,10216.7958,-5.78E-11,198.9957388,-20.001875,0,5.739898468,90.00000001 +223.52,50.30085681,-3.029466047,10216.9958,-1.02E-10,198.995745,-20.003125,0,5.739898468,90.00000001 +223.53,50.30085681,-3.029438161,10217.1959,-1.09E-10,198.9968662,-20.003125,0,5.739898468,90.00000001 +223.54,50.30085681,-3.029410275,10217.3959,-7.19E-11,198.9977645,-20.001875,0,5.739898468,90.00000001 +223.55,50.30085681,-3.029382389,10217.5959,-6.41E-11,198.9979937,-20.001875,0,5.739898468,90.00000001 +223.56,50.30085681,-3.029354503,10217.7959,-9.53E-11,198.9979999,-20.003125,0,5.739898468,90.00000001 +223.57,50.30085681,-3.029326617,10217.996,-9.38E-11,198.9980061,-20.003125,0,5.739898468,90.00000001 +223.58,50.30085681,-3.029298731,10218.196,-5.63E-11,198.9980123,-20.001875,0,5.739898468,90.00000001 +223.59,50.30085681,-3.029270845,10218.396,-5.63E-11,198.9980186,-20.001875,0,5.739898468,90.00000001 +223.6,50.30085681,-3.029242959,10218.596,-9.38E-11,198.9978018,-20.003125,0,5.739898468,90.00000001 +223.61,50.30085681,-3.029215073,10218.7961,-9.53E-11,198.996916,-20.003125,0,5.739898468,90.00000001 +223.62,50.30085681,-3.029187187,10218.9961,-6.41E-11,198.9958072,-20.001875,0,5.739898468,90.00000001 +223.63,50.30085681,-3.029159302,10219.1961,-7.19E-11,198.9958134,-20.001875,0,5.739898468,90.00000001 +223.64,50.30085681,-3.029131416,10219.3961,-1.09E-10,198.9969346,-20.003125,0,5.739898468,90.00000001 +223.65,50.30085681,-3.02910353,10219.5962,-1.02E-10,198.9978329,-20.003125,0,5.739898468,90.00000001 +223.66,50.30085681,-3.029075644,10219.7962,-5.78E-11,198.9980621,-20.001875,0,5.739898468,90.00000001 +223.67,50.30085681,-3.029047758,10219.9962,-5.63E-11,198.9978453,-20.001875,0,5.739898468,90.00000001 +223.68,50.30085681,-3.029019872,10220.1962,-9.38E-11,198.9969595,-20.003125,0,5.739898468,90.00000001 +223.69,50.30085681,-3.028991986,10220.3963,-9.38E-11,198.9958507,-20.003125,0,5.739898468,90.00000001 +223.7,50.30085681,-3.028964101,10220.5963,-5.47E-11,198.9958569,-20.001875,0,5.739898468,90.00000001 +223.71,50.30085681,-3.028936215,10220.7963,-4.84E-11,198.9969782,-20.001875,0,5.739898468,90.00000001 +223.72,50.30085681,-3.028908329,10220.9963,-7.81E-11,198.9978764,-20.003125,0,5.739898468,90.00000001 +223.73,50.30085681,-3.028880443,10221.1964,-7.81E-11,198.9981056,-20.003125,0,5.739898468,90.00000001 +223.74,50.30085681,-3.028852557,10221.3964,-4.84E-11,198.9981118,-20.001875,0,5.739898468,90.00000001 +223.75,50.30085681,-3.028824671,10221.5964,-5.47E-11,198.9981181,-20.001875,0,5.739898468,90.00000001 +223.76,50.30085681,-3.028796785,10221.7964,-9.37E-11,198.9981243,-20.003125,0,5.739898468,90.00000001 +223.77,50.30085681,-3.028768899,10221.9965,-9.38E-11,198.9981305,-20.003125,0,5.739898468,90.00000001 +223.78,50.30085681,-3.028741013,10222.1965,-5.63E-11,198.9979137,-20.001875,0,5.739898468,90.00000001 +223.79,50.30085681,-3.028713127,10222.3965,-5.78E-11,198.9970279,-20.001875,0,5.739898468,90.00000001 +223.8,50.30085681,-3.028685241,10222.5965,-1.02E-10,198.9959191,-20.003125,0,5.739898468,90.00000001 +223.81,50.30085681,-3.028657356,10222.7966,-1.09E-10,198.9959253,-20.003125,0,5.739898468,90.00000001 +223.82,50.30085681,-3.02862947,10222.9966,-7.19E-11,198.9970466,-20.001875,0,5.739898468,90.00000001 +223.83,50.30085681,-3.028601584,10223.1966,-6.41E-11,198.9979448,-20.001875,0,5.739898468,90.00000001 +223.84,50.30085681,-3.028573698,10223.3966,-9.53E-11,198.998174,-20.003125,0,5.739898468,90.00000001 +223.85,50.30085681,-3.028545812,10223.5967,-9.37E-11,198.9979572,-20.003125,0,5.739898468,90.00000001 +223.86,50.30085681,-3.028517926,10223.7967,-5.62E-11,198.9970714,-20.001875,0,5.739898468,90.00000001 +223.87,50.30085681,-3.02849004,10223.9967,-5.62E-11,198.9959626,-20.001875,0,5.739898468,90.00000001 +223.88,50.30085681,-3.028462155,10224.1967,-9.37E-11,198.9959689,-20.003125,0,5.739898468,90.00000001 +223.89,50.30085681,-3.028434269,10224.3968,-9.53E-11,198.9970901,-20.003125,0,5.739898468,90.00000001 +223.9,50.30085681,-3.028406383,10224.5968,-6.41E-11,198.9979883,-20.001875,0,5.739898468,90.00000001 +223.91,50.30085681,-3.028378497,10224.7968,-7.19E-11,198.9982176,-20.001875,0,5.739898468,90.00000001 +223.92,50.30085681,-3.028350611,10224.9968,-1.09E-10,198.9980008,-20.003125,0,5.739898468,90.00000001 +223.93,50.30085681,-3.028322725,10225.1969,-1.02E-10,198.997115,-20.003125,0,5.739898468,90.00000001 +223.94,50.30085681,-3.028294839,10225.3969,-5.78E-11,198.9960062,-20.001875,0,5.739898468,90.00000001 +223.95,50.30085681,-3.028266954,10225.5969,-5.62E-11,198.9960124,-20.001875,0,5.739898468,90.00000001 +223.96,50.30085681,-3.028239068,10225.7969,-9.37E-11,198.9971336,-20.003125,0,5.739898468,90.00000001 +223.97,50.30085681,-3.028211182,10225.997,-9.37E-11,198.9980319,-20.003125,0,5.739898468,90.00000001 +223.98,50.30085681,-3.028183296,10226.197,-5.47E-11,198.9982611,-20.001875,0,5.739898468,90.00000001 +223.99,50.30085681,-3.02815541,10226.397,-4.84E-11,198.9980443,-20.001875,0,5.739898468,90.00000001 +224,50.30085681,-3.028127524,10226.597,-7.81E-11,198.9971585,-20.003125,0,5.739898468,90.00000001 +224.01,50.30085681,-3.028099638,10226.7971,-7.81E-11,198.9960497,-20.003125,0,5.739898468,90.00000001 +224.02,50.30085681,-3.028071753,10226.9971,-4.84E-11,198.9960559,-20.001875,0,5.739898468,90.00000001 +224.03,50.30085681,-3.028043867,10227.1971,-5.47E-11,198.9971772,-20.001875,0,5.739898468,90.00000001 +224.04,50.30085681,-3.028015981,10227.3971,-9.38E-11,198.9980754,-20.003125,0,5.739898468,90.00000001 +224.05,50.30085681,-3.027988095,10227.5972,-9.37E-11,198.9983046,-20.003125,0,5.739898468,90.00000001 +224.06,50.30085681,-3.027960209,10227.7972,-5.62E-11,198.9980878,-20.001875,0,5.739898468,90.00000001 +224.07,50.30085681,-3.027932323,10227.9972,-5.78E-11,198.997202,-20.001875,0,5.739898468,90.00000001 +224.08,50.30085681,-3.027904437,10228.1972,-1.02E-10,198.9960932,-20.003125,0,5.739898468,90.00000001 +224.09,50.30085681,-3.027876552,10228.3973,-1.09E-10,198.9960994,-20.003125,0,5.739898468,90.00000001 +224.1,50.30085681,-3.027848666,10228.5973,-7.19E-11,198.9972207,-20.001875,0,5.739898468,90.00000001 +224.11,50.30085681,-3.02782078,10228.7973,-6.41E-11,198.9981189,-20.001875,0,5.739898468,90.00000001 +224.12,50.30085681,-3.027792894,10228.9973,-9.53E-11,198.9981251,-20.003125,0,5.739898468,90.00000001 +224.13,50.30085681,-3.027765008,10229.1974,-9.38E-11,198.9972393,-20.003125,0,5.739898468,90.00000001 +224.14,50.30085681,-3.027737122,10229.3974,-5.63E-11,198.9961305,-20.001875,0,5.739898468,90.00000001 +224.15,50.30085681,-3.027709237,10229.5974,-5.63E-11,198.9961368,-20.001875,0,5.739898468,90.00000001 +224.16,50.30085681,-3.027681351,10229.7974,-9.38E-11,198.997258,-20.003125,0,5.739898468,90.00000001 +224.17,50.30085681,-3.027653465,10229.9975,-9.53E-11,198.9981562,-20.003125,0,5.739898468,90.00000001 +224.18,50.30085681,-3.027625579,10230.1975,-6.41E-11,198.9981624,-20.001875,0,5.739898468,90.00000001 +224.19,50.30085681,-3.027597693,10230.3975,-7.19E-11,198.9972766,-20.001875,0,5.739898468,90.00000001 +224.2,50.30085681,-3.027569807,10230.5975,-1.09E-10,198.9961678,-20.003125,0,5.739898468,90.00000001 +224.21,50.30085681,-3.027541922,10230.7976,-1.02E-10,198.9961741,-20.003125,0,5.739898468,90.00000001 +224.22,50.30085681,-3.027514036,10230.9976,-5.78E-11,198.9970723,-20.001875,0,5.739898468,90.00000001 +224.23,50.30085681,-3.02748615,10231.1976,-5.62E-11,198.9970785,-20.001875,0,5.739898468,90.00000001 +224.24,50.30085681,-3.027458264,10231.3976,-9.37E-11,198.9961927,-20.003125,0,5.739898468,90.00000001 +224.25,50.30085681,-3.027430379,10231.5977,-9.38E-11,198.9961989,-20.003125,0,5.739898468,90.00000001 +224.26,50.30085681,-3.027402493,10231.7977,-5.47E-11,198.9973202,-20.001875,0,5.739898468,90.00000001 +224.27,50.30085681,-3.027374607,10231.9977,-4.84E-11,198.9982184,-20.001875,0,5.739898468,90.00000001 +224.28,50.30085681,-3.027346721,10232.1977,-7.81E-11,198.9984476,-20.003125,0,5.739898468,90.00000001 +224.29,50.30085681,-3.027318835,10232.3978,-6.87E-11,198.9982309,-20.0034375,0,5.739898468,90.00000001 +224.3,50.30085681,-3.027290949,10232.5978,7.81E-12,198.9973451,-20.003125,0,5.739898468,90.00000001 +224.31,50.30085681,-3.027263063,10232.7978,8.59E-11,198.9962362,-20.0034375,0,5.739898468,90.00000001 +224.32,50.30085681,-3.027235178,10232.9979,9.38E-11,198.9962425,-20.003125,0,5.739898468,90.00000001 +224.33,50.30085681,-3.027207292,10233.1979,5.63E-11,198.9973637,-20.001875,0,5.739898468,90.00000001 +224.34,50.30085681,-3.027179406,10233.3979,5.63E-11,198.9982619,-20.001875,0,5.739898468,90.00000001 +224.35,50.30085681,-3.02715152,10233.5979,9.22E-11,198.9984912,-20.003125,0,5.739898468,90.00000001 +224.36,50.30085681,-3.027123634,10233.798,8.59E-11,198.9982744,-20.003125,0,5.739898468,90.00000001 +224.37,50.30085681,-3.027095748,10233.998,4.06E-11,198.9973886,-20.001875,0,5.739898468,90.00000001 +224.38,50.30085681,-3.027067862,10234.198,4.06E-11,198.9962798,-20.001875,0,5.739898468,90.00000001 +224.39,50.30085681,-3.027039977,10234.398,8.59E-11,198.996063,-20.003125,0,5.739898468,90.00000001 +224.4,50.30085681,-3.027012091,10234.5981,9.22E-11,198.9962922,-20.003125,0,5.739898468,90.00000001 +224.41,50.30085681,-3.026984205,10234.7981,5.63E-11,198.9960754,-20.001875,0,5.739898468,90.00000001 +224.42,50.30085681,-3.02695632,10234.9981,5.63E-11,198.9963047,-20.001875,0,5.739898468,90.00000001 +224.43,50.30085681,-3.026928434,10235.1981,9.38E-11,198.9974259,-20.003125,0,5.739898468,90.00000001 +224.44,50.30085681,-3.026900548,10235.3982,9.38E-11,198.9983241,-20.003125,0,5.739898468,90.00000001 +224.45,50.30085681,-3.026872662,10235.5982,5.47E-11,198.9985534,-20.001875,0,5.739898468,90.00000001 +224.46,50.30085681,-3.026844776,10235.7982,4.84E-11,198.9983366,-20.001875,0,5.739898468,90.00000001 +224.47,50.30085681,-3.02681689,10235.9982,7.81E-11,198.9974508,-20.003125,0,5.739898468,90.00000001 +224.48,50.30085681,-3.026789004,10236.1983,7.81E-11,198.996342,-20.003125,0,5.739898468,90.00000001 +224.49,50.30085681,-3.026761119,10236.3983,4.84E-11,198.9963482,-20.001875,0,5.739898468,90.00000001 +224.5,50.30085681,-3.026733233,10236.5983,5.47E-11,198.9974694,-20.001875,0,5.739898468,90.00000001 +224.51,50.30085681,-3.026705347,10236.7983,9.37E-11,198.9983677,-20.003125,0,5.739898468,90.00000001 +224.52,50.30085681,-3.026677461,10236.9984,9.38E-11,198.9983739,-20.003125,0,5.739898468,90.00000001 +224.53,50.30085681,-3.026649575,10237.1984,5.63E-11,198.9974881,-20.001875,0,5.739898468,90.00000001 +224.54,50.30085681,-3.026621689,10237.3984,5.78E-11,198.9963793,-20.001875,0,5.739898468,90.00000001 +224.55,50.30085681,-3.026593804,10237.5984,1.02E-10,198.9963855,-20.003125,0,5.739898468,90.00000001 +224.56,50.30085681,-3.026565918,10237.7985,1.09E-10,198.9972837,-20.003125,0,5.739898468,90.00000001 +224.57,50.30085681,-3.026538032,10237.9985,7.19E-11,198.9972899,-20.001875,0,5.739898468,90.00000001 +224.58,50.30085681,-3.026510146,10238.1985,6.41E-11,198.9964041,-20.001875,0,5.739898468,90.00000001 +224.59,50.30085681,-3.026482261,10238.3985,9.53E-11,198.9964104,-20.003125,0,5.739898468,90.00000001 +224.6,50.30085681,-3.026454375,10238.5986,9.37E-11,198.9975316,-20.003125,0,5.739898468,90.00000001 +224.61,50.30085681,-3.026426489,10238.7986,5.62E-11,198.9984298,-20.001875,0,5.739898468,90.00000001 +224.62,50.30085681,-3.026398603,10238.9986,5.62E-11,198.9984361,-20.001875,0,5.739898468,90.00000001 +224.63,50.30085681,-3.026370717,10239.1986,9.22E-11,198.9975503,-20.003125,0,5.739898468,90.00000001 +224.64,50.30085681,-3.026342831,10239.3987,8.59E-11,198.9964415,-20.003125,0,5.739898468,90.00000001 +224.65,50.30085681,-3.026314946,10239.5987,4.06E-11,198.9964477,-20.001875,0,5.739898468,90.00000001 +224.66,50.30085681,-3.02628706,10239.7987,4.06E-11,198.9973459,-20.001875,0,5.739898468,90.00000001 +224.67,50.30085681,-3.026259174,10239.9987,8.59E-11,198.9973521,-20.003125,0,5.739898468,90.00000001 +224.68,50.30085681,-3.026231288,10240.1988,9.22E-11,198.9964663,-20.003125,0,5.739898468,90.00000001 +224.69,50.30085681,-3.026203403,10240.3988,5.62E-11,198.9964725,-20.001875,0,5.739898468,90.00000001 +224.7,50.30085681,-3.026175517,10240.5988,5.62E-11,198.9975938,-20.001875,0,5.739898468,90.00000001 +224.71,50.30085681,-3.026147631,10240.7988,9.37E-11,198.998492,-20.003125,0,5.739898468,90.00000001 +224.72,50.30085681,-3.026119745,10240.9989,9.37E-11,198.9984982,-20.003125,0,5.739898468,90.00000001 +224.73,50.30085681,-3.026091859,10241.1989,5.47E-11,198.9976124,-20.001875,0,5.739898468,90.00000001 +224.74,50.30085681,-3.026063973,10241.3989,4.84E-11,198.9965036,-20.001875,0,5.739898468,90.00000001 +224.75,50.30085681,-3.026036088,10241.5989,7.81E-11,198.9965099,-20.003125,0,5.739898468,90.00000001 +224.76,50.30085681,-3.026008202,10241.799,7.81E-11,198.9974081,-20.003125,0,5.739898468,90.00000001 +224.77,50.30085681,-3.025980316,10241.999,4.84E-11,198.9974143,-20.001875,0,5.739898468,90.00000001 +224.78,50.30085681,-3.02595243,10242.199,5.47E-11,198.9965285,-20.001875,0,5.739898468,90.00000001 +224.79,50.30085681,-3.025924545,10242.399,9.38E-11,198.9965347,-20.003125,0,5.739898468,90.00000001 +224.8,50.30085681,-3.025896659,10242.5991,9.37E-11,198.997433,-20.003125,0,5.739898468,90.00000001 +224.81,50.30085681,-3.025868773,10242.7991,5.62E-11,198.9974392,-20.001875,0,5.739898468,90.00000001 +224.82,50.30085681,-3.025840887,10242.9991,5.78E-11,198.9965534,-20.001875,0,5.739898468,90.00000001 +224.83,50.30085681,-3.025813002,10243.1991,1.02E-10,198.9965596,-20.003125,0,5.739898468,90.00000001 +224.84,50.30085681,-3.025785116,10243.3992,1.09E-10,198.9976808,-20.003125,0,5.739898468,90.00000001 +224.85,50.30085681,-3.02575723,10243.5992,7.19E-11,198.9985791,-20.001875,0,5.739898468,90.00000001 +224.86,50.30085681,-3.025729344,10243.7992,6.41E-11,198.9985853,-20.001875,0,5.739898468,90.00000001 +224.87,50.30085681,-3.025701458,10243.9992,9.53E-11,198.9976995,-20.003125,0,5.739898468,90.00000001 +224.88,50.30085681,-3.025673572,10244.1993,9.38E-11,198.9965907,-20.003125,0,5.739898468,90.00000001 +224.89,50.30085681,-3.025645687,10244.3993,5.63E-11,198.9963739,-20.001875,0,5.739898468,90.00000001 +224.9,50.30085681,-3.025617801,10244.5993,5.63E-11,198.9966031,-20.001875,0,5.739898468,90.00000001 +224.91,50.30085681,-3.025589915,10244.7993,9.38E-11,198.9963863,-20.003125,0,5.739898468,90.00000001 +224.92,50.30085681,-3.02556203,10244.9994,9.53E-11,198.9966156,-20.003125,0,5.739898468,90.00000001 +224.93,50.30085681,-3.025534144,10245.1994,6.41E-11,198.9977368,-20.001875,0,5.739898468,90.00000001 +224.94,50.30085681,-3.025506258,10245.3994,7.19E-11,198.998412,-20.001875,0,5.739898468,90.00000001 +224.95,50.30085681,-3.025478372,10245.5994,1.09E-10,198.9977493,-20.003125,0,5.739898468,90.00000001 +224.96,50.30085681,-3.025450486,10245.7995,1.02E-10,198.9966404,-20.003125,0,5.739898468,90.00000001 +224.97,50.30085681,-3.025422601,10245.9995,5.78E-11,198.9966467,-20.001875,0,5.739898468,90.00000001 +224.98,50.30085681,-3.025394715,10246.1995,5.62E-11,198.9977679,-20.001875,0,5.739898468,90.00000001 +224.99,50.30085681,-3.025366829,10246.3995,9.37E-11,198.9984431,-20.003125,0,5.739898468,90.00000001 +225,50.30085681,-3.025338943,10246.5996,9.38E-11,198.9977803,-20.003125,0,5.739898468,90.00000001 +225.01,50.30085681,-3.025311057,10246.7996,5.47E-11,198.9966715,-20.001875,0,5.739898468,90.00000001 +225.02,50.30085681,-3.025283172,10246.9996,4.84E-11,198.9964548,-20.001875,0,5.739898468,90.00000001 +225.03,50.30085681,-3.025255286,10247.1996,7.81E-11,198.996684,-20.003125,0,5.739898468,90.00000001 +225.04,50.30085681,-3.0252274,10247.3997,7.81E-11,198.9964672,-20.003125,0,5.739898468,90.00000001 +225.05,50.30085681,-3.025199515,10247.5997,4.84E-11,198.9966964,-20.001875,0,5.739898468,90.00000001 +225.06,50.30085681,-3.025171629,10247.7997,5.47E-11,198.9978177,-20.001875,0,5.739898468,90.00000001 +225.07,50.30085681,-3.025143743,10247.9997,9.37E-11,198.9984929,-20.003125,0,5.739898468,90.00000001 +225.08,50.30085681,-3.025115857,10248.1998,9.37E-11,198.9978301,-20.003125,0,5.739898468,90.00000001 +225.09,50.30085681,-3.025087971,10248.3998,5.62E-11,198.9967213,-20.001875,0,5.739898468,90.00000001 +225.1,50.30085681,-3.025060086,10248.5998,5.78E-11,198.9967275,-20.001875,0,5.739898468,90.00000001 +225.11,50.30085681,-3.0250322,10248.7998,1.02E-10,198.9978487,-20.003125,0,5.739898468,90.00000001 +225.12,50.30085681,-3.025004314,10248.9999,1.09E-10,198.998524,-20.003125,0,5.739898468,90.00000001 +225.13,50.30085681,-3.024976428,10249.1999,7.19E-11,198.9978612,-20.001875,0,5.739898468,90.00000001 +225.14,50.30085681,-3.024948542,10249.3999,6.41E-11,198.9965294,-20.001875,0,5.739898468,90.00000001 +225.15,50.30085681,-3.024920657,10249.5999,9.53E-11,198.9956436,-20.003125,0,5.739898468,90.00000001 +225.16,50.30085681,-3.024892771,10249.8,8.44E-11,198.9956498,-20.0034375,0,5.739898468,90.00000001 +225.17,50.30085681,-3.024864886,10250,-1.11E-15,198.996548,-20.003125,0,5.739898468,90.00000001 +225.18,50.30085681,-3.024837,10250.2,-8.44E-11,198.9976693,-20.0034375,0,5.739898468,90.00000001 +225.19,50.30085681,-3.024809114,10250.4001,-9.38E-11,198.9976755,-20.003125,0,5.739898468,90.00000001 +225.2,50.30085681,-3.024781228,10250.6001,-5.47E-11,198.9967897,-20.001875,0,5.739898468,90.00000001 +225.21,50.30085681,-3.024753343,10250.8001,-4.84E-11,198.9967959,-20.001875,0,5.739898468,90.00000001 +225.22,50.30085681,-3.024725457,10251.0001,-7.81E-11,198.9979172,-20.003125,0,5.739898468,90.00000001 +225.23,50.30085681,-3.024697571,10251.2002,-7.81E-11,198.9985924,-20.003125,0,5.739898468,90.00000001 +225.24,50.30085681,-3.024669685,10251.4002,-4.84E-11,198.9979296,-20.001875,0,5.739898468,90.00000001 +225.25,50.30085681,-3.024641799,10251.6002,-5.47E-11,198.9968208,-20.001875,0,5.739898468,90.00000001 +225.26,50.30085681,-3.024613914,10251.8002,-9.37E-11,198.996827,-20.003125,0,5.739898468,90.00000001 +225.27,50.30085681,-3.024586028,10252.0003,-9.38E-11,198.9977252,-20.003125,0,5.739898468,90.00000001 +225.28,50.30085681,-3.024558142,10252.2003,-5.63E-11,198.9977315,-20.001875,0,5.739898468,90.00000001 +225.29,50.30085681,-3.024530256,10252.4003,-5.78E-11,198.9968457,-20.001875,0,5.739898468,90.00000001 +225.3,50.30085681,-3.024502371,10252.6003,-1.02E-10,198.9966289,-20.003125,0,5.739898468,90.00000001 +225.31,50.30085681,-3.024474485,10252.8004,-1.09E-10,198.9968581,-20.003125,0,5.739898468,90.00000001 +225.32,50.30085681,-3.024446599,10253.0004,-7.19E-11,198.9966413,-20.001875,0,5.739898468,90.00000001 +225.33,50.30085681,-3.024418714,10253.2004,-6.41E-11,198.9966475,-20.001875,0,5.739898468,90.00000001 +225.34,50.30085681,-3.024390828,10253.4004,-9.53E-11,198.9968767,-20.003125,0,5.739898468,90.00000001 +225.35,50.30085681,-3.024362942,10253.6005,-9.37E-11,198.99666,-20.003125,0,5.739898468,90.00000001 +225.36,50.30085681,-3.024335057,10253.8005,-5.62E-11,198.9968892,-20.001875,0,5.739898468,90.00000001 +225.37,50.30085681,-3.024307171,10254.0005,-5.62E-11,198.9980104,-20.001875,0,5.739898468,90.00000001 +225.38,50.30085681,-3.024279285,10254.2005,-9.22E-11,198.9986857,-20.003125,0,5.739898468,90.00000001 +225.39,50.30085681,-3.024251399,10254.4006,-8.59E-11,198.9980229,-20.003125,0,5.739898468,90.00000001 +225.4,50.30085681,-3.024223513,10254.6006,-4.06E-11,198.9969141,-20.001875,0,5.739898468,90.00000001 +225.41,50.30085681,-3.024195628,10254.8006,-4.06E-11,198.9969203,-20.001875,0,5.739898468,90.00000001 +225.42,50.30085681,-3.024167742,10255.0006,-8.59E-11,198.9978185,-20.003125,0,5.739898468,90.00000001 +225.43,50.30085681,-3.024139856,10255.2007,-9.22E-11,198.9978247,-20.003125,0,5.739898468,90.00000001 +225.44,50.30085681,-3.02411197,10255.4007,-5.62E-11,198.9969389,-20.001875,0,5.739898468,90.00000001 +225.45,50.30085681,-3.024084085,10255.6007,-5.62E-11,198.9969451,-20.001875,0,5.739898468,90.00000001 +225.46,50.30085681,-3.024056199,10255.8007,-9.37E-11,198.9978434,-20.003125,0,5.739898468,90.00000001 +225.47,50.30085681,-3.024028313,10256.0008,-9.37E-11,198.9978496,-20.003125,0,5.739898468,90.00000001 +225.48,50.30085681,-3.024000427,10256.2008,-5.47E-11,198.9969638,-20.001875,0,5.739898468,90.00000001 +225.49,50.30085681,-3.023972542,10256.4008,-4.84E-11,198.996747,-20.001875,0,5.739898468,90.00000001 +225.5,50.30085681,-3.023944656,10256.6008,-7.81E-11,198.9969762,-20.003125,0,5.739898468,90.00000001 +225.51,50.30085681,-3.02391677,10256.8009,-7.81E-11,198.9967595,-20.003125,0,5.739898468,90.00000001 +225.52,50.30085681,-3.023888885,10257.0009,-4.84E-11,198.9967657,-20.001875,0,5.739898468,90.00000001 +225.53,50.30085681,-3.023860999,10257.2009,-5.47E-11,198.9969949,-20.001875,0,5.739898468,90.00000001 +225.54,50.30085681,-3.023833113,10257.4009,-9.38E-11,198.9967781,-20.003125,0,5.739898468,90.00000001 +225.55,50.30085681,-3.023805228,10257.601,-9.37E-11,198.9967843,-20.003125,0,5.739898468,90.00000001 +225.56,50.30085681,-3.023777342,10257.801,-5.62E-11,198.9970135,-20.001875,0,5.739898468,90.00000001 +225.57,50.30085681,-3.023749456,10258.001,-5.78E-11,198.9967968,-20.001875,0,5.739898468,90.00000001 +225.58,50.30085681,-3.023721571,10258.201,-1.02E-10,198.997026,-20.003125,0,5.739898468,90.00000001 +225.59,50.30085681,-3.023693685,10258.4011,-1.09E-10,198.9979242,-20.003125,0,5.739898468,90.00000001 +225.6,50.30085681,-3.023665799,10258.6011,-7.19E-11,198.9979304,-20.001875,0,5.739898468,90.00000001 +225.61,50.30085681,-3.023637913,10258.8011,-6.41E-11,198.9970446,-20.001875,0,5.739898468,90.00000001 +225.62,50.30085681,-3.023610028,10259.0011,-9.53E-11,198.9970509,-20.003125,0,5.739898468,90.00000001 +225.63,50.30085681,-3.023582142,10259.2012,-9.38E-11,198.9979491,-20.003125,0,5.739898468,90.00000001 +225.64,50.30085681,-3.023554256,10259.4012,-5.63E-11,198.9979553,-20.001875,0,5.739898468,90.00000001 +225.65,50.30085681,-3.02352637,10259.6012,-5.63E-11,198.9970695,-20.001875,0,5.739898468,90.00000001 +225.66,50.30085681,-3.023498485,10259.8012,-9.22E-11,198.9970757,-20.003125,0,5.739898468,90.00000001 +225.67,50.30085681,-3.023470599,10260.0013,-8.59E-11,198.997974,-20.003125,0,5.739898468,90.00000001 +225.68,50.30085681,-3.023442713,10260.2013,-4.06E-11,198.9979802,-20.001875,0,5.739898468,90.00000001 +225.69,50.30085681,-3.023414827,10260.4013,-4.06E-11,198.9970944,-20.001875,0,5.739898468,90.00000001 +225.7,50.30085681,-3.023386942,10260.6013,-8.59E-11,198.9971006,-20.003125,0,5.739898468,90.00000001 +225.71,50.30085681,-3.023359056,10260.8014,-9.22E-11,198.9979988,-20.003125,0,5.739898468,90.00000001 +225.72,50.30085681,-3.02333117,10261.0014,-5.62E-11,198.9980051,-20.001875,0,5.739898468,90.00000001 +225.73,50.30085681,-3.023303284,10261.2014,-5.62E-11,198.9971193,-20.001875,0,5.739898468,90.00000001 +225.74,50.30085681,-3.023275399,10261.4014,-9.37E-11,198.9969025,-20.003125,0,5.739898468,90.00000001 +225.75,50.30085681,-3.023247513,10261.6015,-9.38E-11,198.9971317,-20.003125,0,5.739898468,90.00000001 +225.76,50.30085681,-3.023219627,10261.8015,-5.47E-11,198.9969149,-20.001875,0,5.739898468,90.00000001 +225.77,50.30085681,-3.023191742,10262.0015,-4.84E-11,198.9969211,-20.001875,0,5.739898468,90.00000001 +225.78,50.30085681,-3.023163856,10262.2015,-7.81E-11,198.9971504,-20.003125,0,5.739898468,90.00000001 +225.79,50.30085681,-3.02313597,10262.4016,-7.81E-11,198.9969336,-20.003125,0,5.739898468,90.00000001 +225.8,50.30085681,-3.023108085,10262.6016,-4.84E-11,198.9969398,-20.001875,0,5.739898468,90.00000001 +225.81,50.30085681,-3.023080199,10262.8016,-5.47E-11,198.997169,-20.001875,0,5.739898468,90.00000001 +225.82,50.30085681,-3.023052313,10263.0016,-9.37E-11,198.9969522,-20.003125,0,5.739898468,90.00000001 +225.83,50.30085681,-3.023024428,10263.2017,-9.37E-11,198.9969584,-20.003125,0,5.739898468,90.00000001 +225.84,50.30085681,-3.022996542,10263.4017,-5.62E-11,198.9971877,-20.001875,0,5.739898468,90.00000001 +225.85,50.30085681,-3.022968656,10263.6017,-5.78E-11,198.9969709,-20.001875,0,5.739898468,90.00000001 +225.86,50.30085681,-3.022940771,10263.8017,-1.02E-10,198.9969771,-20.003125,0,5.739898468,90.00000001 +225.87,50.30085681,-3.022912885,10264.0018,-1.09E-10,198.9972063,-20.003125,0,5.739898468,90.00000001 +225.88,50.30085681,-3.022884999,10264.2018,-7.19E-11,198.9969895,-20.001875,0,5.739898468,90.00000001 +225.89,50.30085681,-3.022857114,10264.4018,-6.41E-11,198.9969958,-20.001875,0,5.739898468,90.00000001 +225.9,50.30085681,-3.022829228,10264.6018,-9.53E-11,198.997225,-20.003125,0,5.739898468,90.00000001 +225.91,50.30085681,-3.022801342,10264.8019,-9.37E-11,198.9970082,-20.003125,0,5.739898468,90.00000001 +225.92,50.30085681,-3.022773457,10265.0019,-5.62E-11,198.9970144,-20.001875,0,5.739898468,90.00000001 +225.93,50.30085681,-3.022745571,10265.2019,-5.62E-11,198.9972436,-20.001875,0,5.739898468,90.00000001 +225.94,50.30085681,-3.022717685,10265.4019,-9.22E-11,198.9970268,-20.003125,0,5.739898468,90.00000001 +225.95,50.30085681,-3.0226898,10265.602,-8.59E-11,198.9972561,-20.003125,0,5.739898468,90.00000001 +225.96,50.30085681,-3.022661914,10265.802,-4.06E-11,198.9981543,-20.001875,0,5.739898468,90.00000001 +225.97,50.30085681,-3.022634028,10266.002,-4.06E-11,198.9981605,-20.001875,0,5.739898468,90.00000001 +225.98,50.30085681,-3.022606142,10266.202,-8.59E-11,198.9972747,-20.003125,0,5.739898468,90.00000001 +225.99,50.30085681,-3.022578257,10266.4021,-9.22E-11,198.9970579,-20.003125,0,5.739898468,90.00000001 +226,50.30085681,-3.022550371,10266.6021,-5.63E-11,198.9972872,-20.001875,0,5.739898468,90.00000001 +226.01,50.30085681,-3.022522485,10266.8021,-5.63E-11,198.9970704,-20.001875,0,5.739898468,90.00000001 +226.02,50.30085681,-3.0224946,10267.0021,-9.38E-11,198.9970766,-20.003125,0,5.739898468,90.00000001 +226.03,50.30085681,-3.022466714,10267.2022,-8.44E-11,198.9973058,-20.0034375,0,5.739898468,90.00000001 +226.04,50.30085681,-3.022438828,10267.4022,1.56E-12,198.997089,-20.003125,0,5.739898468,90.00000001 +226.05,50.30085681,-3.022410943,10267.6022,9.22E-11,198.9970952,-20.0034375,0,5.739898468,90.00000001 +226.06,50.30085681,-3.022383057,10267.8023,1.09E-10,198.9973245,-20.003125,0,5.739898468,90.00000001 +226.07,50.30085681,-3.022355171,10268.0023,7.19E-11,198.9971077,-20.001875,0,5.739898468,90.00000001 +226.08,50.30085681,-3.022327286,10268.2023,6.41E-11,198.9971139,-20.001875,0,5.739898468,90.00000001 +226.09,50.30085681,-3.0222994,10268.4023,9.53E-11,198.9973431,-20.003125,0,5.739898468,90.00000001 +226.1,50.30085681,-3.022271514,10268.6024,9.37E-11,198.9971263,-20.003125,0,5.739898468,90.00000001 +226.11,50.30085681,-3.022243629,10268.8024,5.62E-11,198.9971326,-20.001875,0,5.739898468,90.00000001 +226.12,50.30085681,-3.022215743,10269.0024,5.62E-11,198.9973618,-20.001875,0,5.739898468,90.00000001 +226.13,50.30085681,-3.022187857,10269.2024,9.22E-11,198.997145,-20.003125,0,5.739898468,90.00000001 +226.14,50.30085681,-3.022159972,10269.4025,8.59E-11,198.9971512,-20.003125,0,5.739898468,90.00000001 +226.15,50.30085681,-3.022132086,10269.6025,4.06E-11,198.9973804,-20.001875,0,5.739898468,90.00000001 +226.16,50.30085681,-3.0221042,10269.8025,4.06E-11,198.9971636,-20.001875,0,5.739898468,90.00000001 +226.17,50.30085681,-3.022076315,10270.0025,8.59E-11,198.9971699,-20.003125,0,5.739898468,90.00000001 +226.18,50.30085681,-3.022048429,10270.2026,9.22E-11,198.9973991,-20.003125,0,5.739898468,90.00000001 +226.19,50.30085681,-3.022020543,10270.4026,5.62E-11,198.9971823,-20.001875,0,5.739898468,90.00000001 +226.2,50.30085681,-3.021992658,10270.6026,5.62E-11,198.9971885,-20.001875,0,5.739898468,90.00000001 +226.21,50.30085681,-3.021964772,10270.8026,9.37E-11,198.9974177,-20.003125,0,5.739898468,90.00000001 +226.22,50.30085681,-3.021936886,10271.0027,9.53E-11,198.997201,-20.003125,0,5.739898468,90.00000001 +226.23,50.30085681,-3.021909001,10271.2027,6.41E-11,198.9972072,-20.001875,0,5.739898468,90.00000001 +226.24,50.30085681,-3.021881115,10271.4027,7.19E-11,198.9974364,-20.001875,0,5.739898468,90.00000001 +226.25,50.30085681,-3.021853229,10271.6027,1.09E-10,198.9972196,-20.003125,0,5.739898468,90.00000001 +226.26,50.30085681,-3.021825344,10271.8028,1.02E-10,198.9972258,-20.003125,0,5.739898468,90.00000001 +226.27,50.30085681,-3.021797458,10272.0028,5.78E-11,198.9974551,-20.001875,0,5.739898468,90.00000001 +226.28,50.30085681,-3.021769572,10272.2028,5.63E-11,198.9972383,-20.001875,0,5.739898468,90.00000001 +226.29,50.30085681,-3.021741687,10272.4028,9.38E-11,198.9972445,-20.003125,0,5.739898468,90.00000001 +226.3,50.30085681,-3.021713801,10272.6029,9.37E-11,198.9974737,-20.003125,0,5.739898468,90.00000001 +226.31,50.30085681,-3.021685915,10272.8029,5.62E-11,198.9972569,-20.001875,0,5.739898468,90.00000001 +226.32,50.30085681,-3.02165803,10273.0029,5.78E-11,198.9972631,-20.001875,0,5.739898468,90.00000001 +226.33,50.30085681,-3.021630144,10273.2029,1.02E-10,198.9974924,-20.003125,0,5.739898468,90.00000001 +226.34,50.30085681,-3.021602258,10273.403,1.09E-10,198.9970526,-20.003125,0,5.739898468,90.00000001 +226.35,50.30085681,-3.021574373,10273.603,7.19E-11,198.9963898,-20.001875,0,5.739898468,90.00000001 +226.36,50.30085681,-3.021546487,10273.803,6.41E-11,198.996396,-20.001875,0,5.739898468,90.00000001 +226.37,50.30085681,-3.021518602,10274.003,9.53E-11,198.9970712,-20.003125,0,5.739898468,90.00000001 +226.38,50.30085681,-3.021490716,10274.2031,9.38E-11,198.9975235,-20.003125,0,5.739898468,90.00000001 +226.39,50.30085681,-3.02146283,10274.4031,5.63E-11,198.9973067,-20.001875,0,5.739898468,90.00000001 +226.4,50.30085681,-3.021434945,10274.6031,5.63E-11,198.9973129,-20.001875,0,5.739898468,90.00000001 +226.41,50.30085681,-3.021407059,10274.8031,9.22E-11,198.9975421,-20.003125,0,5.739898468,90.00000001 +226.42,50.30085681,-3.021379173,10275.0032,8.59E-11,198.9973253,-20.003125,0,5.739898468,90.00000001 +226.43,50.30085681,-3.021351288,10275.2032,4.06E-11,198.9973315,-20.001875,0,5.739898468,90.00000001 +226.44,50.30085681,-3.021323402,10275.4032,4.06E-11,198.9975608,-20.001875,0,5.739898468,90.00000001 +226.45,50.30085681,-3.021295516,10275.6032,8.59E-11,198.997121,-20.003125,0,5.739898468,90.00000001 +226.46,50.30085681,-3.021267631,10275.8033,9.22E-11,198.9964582,-20.003125,0,5.739898468,90.00000001 +226.47,50.30085681,-3.021239745,10276.0033,5.63E-11,198.9964644,-20.001875,0,5.739898468,90.00000001 +226.48,50.30085681,-3.02121186,10276.2033,5.63E-11,198.9971396,-20.001875,0,5.739898468,90.00000001 +226.49,50.30085681,-3.021183974,10276.4033,9.38E-11,198.9975919,-20.003125,0,5.739898468,90.00000001 +226.5,50.30085681,-3.021156088,10276.6034,9.38E-11,198.9973751,-20.003125,0,5.739898468,90.00000001 +226.51,50.30085681,-3.021128203,10276.8034,5.47E-11,198.9973813,-20.001875,0,5.739898468,90.00000001 +226.52,50.30085681,-3.021100317,10277.0034,4.84E-11,198.9976105,-20.001875,0,5.739898468,90.00000001 +226.53,50.30085681,-3.021072431,10277.2034,7.81E-11,198.9973937,-20.003125,0,5.739898468,90.00000001 +226.54,50.30085681,-3.021044546,10277.4035,7.81E-11,198.9973999,-20.003125,0,5.739898468,90.00000001 +226.55,50.30085681,-3.02101666,10277.6035,4.84E-11,198.9976292,-20.001875,0,5.739898468,90.00000001 +226.56,50.30085681,-3.020988774,10277.8035,5.47E-11,198.9974124,-20.001875,0,5.739898468,90.00000001 +226.57,50.30085681,-3.020960889,10278.0035,9.37E-11,198.9974186,-20.003125,0,5.739898468,90.00000001 +226.58,50.30085681,-3.020933003,10278.2036,9.37E-11,198.9976478,-20.003125,0,5.739898468,90.00000001 +226.59,50.30085681,-3.020905117,10278.4036,5.62E-11,198.997431,-20.001875,0,5.739898468,90.00000001 +226.6,50.30085681,-3.020877232,10278.6036,5.78E-11,198.9974373,-20.001875,0,5.739898468,90.00000001 +226.61,50.30085681,-3.020849346,10278.8036,1.02E-10,198.9976665,-20.003125,0,5.739898468,90.00000001 +226.62,50.30085681,-3.02082146,10279.0037,1.09E-10,198.9974497,-20.003125,0,5.739898468,90.00000001 +226.63,50.30085681,-3.020793575,10279.2037,7.19E-11,198.9974559,-20.001875,0,5.739898468,90.00000001 +226.64,50.30085681,-3.020765689,10279.4037,6.41E-11,198.9976851,-20.001875,0,5.739898468,90.00000001 +226.65,50.30085681,-3.020737803,10279.6037,9.53E-11,198.9972453,-20.003125,0,5.739898468,90.00000001 +226.66,50.30085681,-3.020709918,10279.8038,9.37E-11,198.9965825,-20.003125,0,5.739898468,90.00000001 +226.67,50.30085681,-3.020682032,10280.0038,5.62E-11,198.9965888,-20.001875,0,5.739898468,90.00000001 +226.68,50.30085681,-3.020654147,10280.2038,5.62E-11,198.997264,-20.001875,0,5.739898468,90.00000001 +226.69,50.30085681,-3.020626261,10280.4038,9.22E-11,198.9977162,-20.003125,0,5.739898468,90.00000001 +226.7,50.30085681,-3.020598375,10280.6039,8.59E-11,198.9972764,-20.003125,0,5.739898468,90.00000001 +226.71,50.30085681,-3.02057049,10280.8039,4.06E-11,198.9966136,-20.001875,0,5.739898468,90.00000001 +226.72,50.30085681,-3.020542604,10281.0039,4.06E-11,198.9966199,-20.001875,0,5.739898468,90.00000001 +226.73,50.30085681,-3.020514719,10281.2039,8.59E-11,198.9972951,-20.003125,0,5.739898468,90.00000001 +226.74,50.30085681,-3.020486833,10281.404,9.22E-11,198.9977473,-20.003125,0,5.739898468,90.00000001 +226.75,50.30085681,-3.020458947,10281.604,5.63E-11,198.9973075,-20.001875,0,5.739898468,90.00000001 +226.76,50.30085681,-3.020431062,10281.804,5.63E-11,198.9966447,-20.001875,0,5.739898468,90.00000001 +226.77,50.30085681,-3.020403176,10282.004,9.38E-11,198.9964279,-20.003125,0,5.739898468,90.00000001 +226.78,50.30085681,-3.020375291,10282.2041,9.37E-11,198.9964342,-20.003125,0,5.739898468,90.00000001 +226.79,50.30085681,-3.020347405,10282.4041,5.47E-11,198.9966634,-20.001875,0,5.739898468,90.00000001 +226.8,50.30085681,-3.02031952,10282.6041,4.84E-11,198.9973386,-20.001875,0,5.739898468,90.00000001 +226.81,50.30085681,-3.020291634,10282.8041,7.81E-11,198.9977909,-20.003125,0,5.739898468,90.00000001 +226.82,50.30085681,-3.020263748,10283.0042,7.81E-11,198.9973511,-20.003125,0,5.739898468,90.00000001 +226.83,50.30085681,-3.020235863,10283.2042,4.84E-11,198.9966883,-20.001875,0,5.739898468,90.00000001 +226.84,50.30085681,-3.020207977,10283.4042,5.47E-11,198.9966945,-20.001875,0,5.739898468,90.00000001 +226.85,50.30085681,-3.020180092,10283.6042,9.38E-11,198.9973697,-20.003125,0,5.739898468,90.00000001 +226.86,50.30085681,-3.020152206,10283.8043,9.38E-11,198.9978219,-20.003125,0,5.739898468,90.00000001 +226.87,50.30085681,-3.02012432,10284.0043,5.63E-11,198.9976052,-20.001875,0,5.739898468,90.00000001 +226.88,50.30085681,-3.020096435,10284.2043,5.78E-11,198.9976114,-20.001875,0,5.739898468,90.00000001 +226.89,50.30085681,-3.020068549,10284.4043,1.02E-10,198.9978406,-20.003125,0,5.739898468,90.00000001 +226.9,50.30085681,-3.020040663,10284.6044,1.00E-10,198.9976238,-20.0034375,0,5.739898468,90.00000001 +226.91,50.30085681,-3.020012778,10284.8044,1.56E-11,198.99763,-20.003125,0,5.739898468,90.00000001 +226.92,50.30085681,-3.019984892,10285.0044,-7.66E-11,198.9978593,-20.0034375,0,5.739898468,90.00000001 +226.93,50.30085681,-3.019957006,10285.2045,-9.22E-11,198.9974195,-20.003125,0,5.739898468,90.00000001 +226.94,50.30085681,-3.019929121,10285.4045,-5.62E-11,198.9967567,-20.001875,0,5.739898468,90.00000001 +226.95,50.30085681,-3.019901235,10285.6045,-5.62E-11,198.9965399,-20.001875,0,5.739898468,90.00000001 +226.96,50.30085681,-3.01987335,10285.8045,-9.37E-11,198.9965461,-20.003125,0,5.739898468,90.00000001 +226.97,50.30085681,-3.019845464,10286.0046,-9.53E-11,198.9967753,-20.003125,0,5.739898468,90.00000001 +226.98,50.30085681,-3.019817579,10286.2046,-6.41E-11,198.9974506,-20.001875,0,5.739898468,90.00000001 +226.99,50.30085681,-3.019789693,10286.4046,-7.19E-11,198.9979028,-20.001875,0,5.739898468,90.00000001 +227,50.30085681,-3.019761807,10286.6046,-1.09E-10,198.997463,-20.003125,0,5.739898468,90.00000001 +227.01,50.30085681,-3.019733922,10286.8047,-1.02E-10,198.9968002,-20.003125,0,5.739898468,90.00000001 +227.02,50.30085681,-3.019706036,10287.0047,-5.78E-11,198.9965834,-20.001875,0,5.739898468,90.00000001 +227.03,50.30085681,-3.019678151,10287.2047,-5.63E-11,198.9965896,-20.001875,0,5.739898468,90.00000001 +227.04,50.30085681,-3.019650265,10287.4047,-9.38E-11,198.9968188,-20.003125,0,5.739898468,90.00000001 +227.05,50.30085681,-3.01962238,10287.6048,-9.37E-11,198.9974941,-20.003125,0,5.739898468,90.00000001 +227.06,50.30085681,-3.019594494,10287.8048,-5.62E-11,198.9979463,-20.001875,0,5.739898468,90.00000001 +227.07,50.30085681,-3.019566608,10288.0048,-5.78E-11,198.9977295,-20.001875,0,5.739898468,90.00000001 +227.08,50.30085681,-3.019538723,10288.2048,-1.02E-10,198.9977357,-20.003125,0,5.739898468,90.00000001 +227.09,50.30085681,-3.019510837,10288.4049,-1.09E-10,198.997965,-20.003125,0,5.739898468,90.00000001 +227.1,50.30085681,-3.019482951,10288.6049,-7.19E-11,198.9975252,-20.001875,0,5.739898468,90.00000001 +227.11,50.30085681,-3.019455066,10288.8049,-6.41E-11,198.9968624,-20.001875,0,5.739898468,90.00000001 +227.12,50.30085681,-3.01942718,10289.0049,-9.53E-11,198.9968686,-20.003125,0,5.739898468,90.00000001 +227.13,50.30085681,-3.019399295,10289.205,-9.38E-11,198.9975438,-20.003125,0,5.739898468,90.00000001 +227.14,50.30085681,-3.019371409,10289.405,-5.63E-11,198.9979961,-20.001875,0,5.739898468,90.00000001 +227.15,50.30085681,-3.019343523,10289.605,-5.63E-11,198.9975563,-20.001875,0,5.739898468,90.00000001 +227.16,50.30085681,-3.019315638,10289.805,-9.22E-11,198.9968935,-20.003125,0,5.739898468,90.00000001 +227.17,50.30085681,-3.019287752,10290.0051,-8.59E-11,198.9966767,-20.003125,0,5.739898468,90.00000001 +227.18,50.30085681,-3.019259867,10290.2051,-4.06E-11,198.9966829,-20.001875,0,5.739898468,90.00000001 +227.19,50.30085681,-3.019231981,10290.4051,-4.06E-11,198.9966891,-20.001875,0,5.739898468,90.00000001 +227.2,50.30085681,-3.019204096,10290.6051,-8.59E-11,198.9966953,-20.003125,0,5.739898468,90.00000001 +227.21,50.30085681,-3.01917621,10290.8052,-9.22E-11,198.9969246,-20.003125,0,5.739898468,90.00000001 +227.22,50.30085681,-3.019148325,10291.0052,-5.63E-11,198.9975998,-20.001875,0,5.739898468,90.00000001 +227.23,50.30085681,-3.019120439,10291.2052,-5.63E-11,198.998052,-20.001875,0,5.739898468,90.00000001 +227.24,50.30085681,-3.019092553,10291.4052,-9.38E-11,198.9978352,-20.003125,0,5.739898468,90.00000001 +227.25,50.30085681,-3.019064668,10291.6053,-9.53E-11,198.9978415,-20.003125,0,5.739898468,90.00000001 +227.26,50.30085681,-3.019036782,10291.8053,-6.41E-11,198.9980707,-20.001875,0,5.739898468,90.00000001 +227.27,50.30085681,-3.019008896,10292.0053,-7.19E-11,198.9976309,-20.001875,0,5.739898468,90.00000001 +227.28,50.30085681,-3.018981011,10292.2053,-1.09E-10,198.9969681,-20.003125,0,5.739898468,90.00000001 +227.29,50.30085681,-3.018953125,10292.4054,-1.02E-10,198.9967513,-20.003125,0,5.739898468,90.00000001 +227.3,50.30085681,-3.01892524,10292.6054,-5.78E-11,198.9967575,-20.001875,0,5.739898468,90.00000001 +227.31,50.30085681,-3.018897354,10292.8054,-5.62E-11,198.9967637,-20.001875,0,5.739898468,90.00000001 +227.32,50.30085681,-3.018869469,10293.0054,-9.37E-11,198.9967699,-20.003125,0,5.739898468,90.00000001 +227.33,50.30085681,-3.018841583,10293.2055,-9.38E-11,198.9967762,-20.003125,0,5.739898468,90.00000001 +227.34,50.30085681,-3.018813698,10293.4055,-5.63E-11,198.9967824,-20.001875,0,5.739898468,90.00000001 +227.35,50.30085681,-3.018785812,10293.6055,-5.78E-11,198.9970116,-20.001875,0,5.739898468,90.00000001 +227.36,50.30085681,-3.018757927,10293.8055,-1.02E-10,198.9976868,-20.003125,0,5.739898468,90.00000001 +227.37,50.30085681,-3.018730041,10294.0056,-1.09E-10,198.9981391,-20.003125,0,5.739898468,90.00000001 +227.38,50.30085681,-3.018702155,10294.2056,-7.19E-11,198.9976993,-20.001875,0,5.739898468,90.00000001 +227.39,50.30085681,-3.01867427,10294.4056,-6.41E-11,198.9970365,-20.001875,0,5.739898468,90.00000001 +227.4,50.30085681,-3.018646384,10294.6056,-9.53E-11,198.9968197,-20.003125,0,5.739898468,90.00000001 +227.41,50.30085681,-3.018618499,10294.8057,-9.37E-11,198.9968259,-20.003125,0,5.739898468,90.00000001 +227.42,50.30085681,-3.018590613,10295.0057,-5.62E-11,198.9968321,-20.001875,0,5.739898468,90.00000001 +227.43,50.30085681,-3.018562728,10295.2057,-5.62E-11,198.9968384,-20.001875,0,5.739898468,90.00000001 +227.44,50.30085681,-3.018534842,10295.4057,-9.22E-11,198.9968446,-20.003125,0,5.739898468,90.00000001 +227.45,50.30085681,-3.018506957,10295.6058,-8.59E-11,198.9968508,-20.003125,0,5.739898468,90.00000001 +227.46,50.30085681,-3.018479071,10295.8058,-4.06E-11,198.99708,-20.001875,0,5.739898468,90.00000001 +227.47,50.30085681,-3.018451186,10296.0058,-4.06E-11,198.9977553,-20.001875,0,5.739898468,90.00000001 +227.48,50.30085681,-3.0184233,10296.2058,-8.59E-11,198.9982075,-20.003125,0,5.739898468,90.00000001 +227.49,50.30085681,-3.018395414,10296.4059,-9.22E-11,198.9979907,-20.003125,0,5.739898468,90.00000001 +227.5,50.30085681,-3.018367529,10296.6059,-5.62E-11,198.9979969,-20.001875,0,5.739898468,90.00000001 +227.51,50.30085681,-3.018339643,10296.8059,-5.62E-11,198.9982261,-20.001875,0,5.739898468,90.00000001 +227.52,50.30085681,-3.018311757,10297.0059,-9.37E-11,198.9977863,-20.003125,0,5.739898468,90.00000001 +227.53,50.30085681,-3.018283872,10297.206,-9.53E-11,198.9969005,-20.003125,0,5.739898468,90.00000001 +227.54,50.30085681,-3.018255986,10297.406,-6.41E-11,198.9960147,-20.001875,0,5.739898468,90.00000001 +227.55,50.30085681,-3.018228101,10297.606,-7.19E-11,198.9955749,-20.001875,0,5.739898468,90.00000001 +227.56,50.30085681,-3.018200216,10297.806,-1.09E-10,198.9960272,-20.003125,0,5.739898468,90.00000001 +227.57,50.30085681,-3.01817233,10298.0061,-1.02E-10,198.9967024,-20.003125,0,5.739898468,90.00000001 +227.58,50.30085681,-3.018144445,10298.2061,-5.78E-11,198.9969316,-20.001875,0,5.739898468,90.00000001 +227.59,50.30085681,-3.018116559,10298.4061,-5.63E-11,198.9971609,-20.001875,0,5.739898468,90.00000001 +227.6,50.30085681,-3.018088674,10298.6061,-9.38E-11,198.9978361,-20.003125,0,5.739898468,90.00000001 +227.61,50.30085681,-3.018060788,10298.8062,-9.38E-11,198.9982883,-20.003125,0,5.739898468,90.00000001 +227.62,50.30085681,-3.018032902,10299.0062,-5.63E-11,198.9980715,-20.001875,0,5.739898468,90.00000001 +227.63,50.30085681,-3.018005017,10299.2062,-5.78E-11,198.9980778,-20.001875,0,5.739898468,90.00000001 +227.64,50.30085681,-3.017977131,10299.4062,-1.02E-10,198.998084,-20.003125,0,5.739898468,90.00000001 +227.65,50.30085681,-3.017949245,10299.6063,-1.09E-10,198.9969752,-20.003125,0,5.739898468,90.00000001 +227.66,50.30085681,-3.01792136,10299.8063,-7.19E-11,198.9958663,-20.001875,0,5.739898468,90.00000001 +227.67,50.30085681,-3.017893475,10300.0063,-6.41E-11,198.9960956,-20.001875,0,5.739898468,90.00000001 +227.68,50.30085681,-3.017865589,10300.2063,-9.53E-11,198.9967708,-20.003125,0,5.739898468,90.00000001 +227.69,50.30085681,-3.017837704,10300.4064,-9.38E-11,198.997,-20.003125,0,5.739898468,90.00000001 +227.7,50.30085681,-3.017809818,10300.6064,-5.63E-11,198.9972293,-20.001875,0,5.739898468,90.00000001 +227.71,50.30085681,-3.017781933,10300.8064,-5.63E-11,198.9979045,-20.001875,0,5.739898468,90.00000001 +227.72,50.30085681,-3.017754047,10301.0064,-9.22E-11,198.9983567,-20.003125,0,5.739898468,90.00000001 +227.73,50.30085681,-3.017726161,10301.2065,-8.59E-11,198.9979169,-20.003125,0,5.739898468,90.00000001 +227.74,50.30085681,-3.017698276,10301.4065,-4.06E-11,198.9972541,-20.001875,0,5.739898468,90.00000001 +227.75,50.30085681,-3.01767039,10301.6065,-4.06E-11,198.9970373,-20.001875,0,5.739898468,90.00000001 +227.76,50.30085681,-3.017642505,10301.8065,-8.59E-11,198.9970436,-20.003125,0,5.739898468,90.00000001 +227.77,50.30085681,-3.017614619,10302.0066,-8.28E-11,198.9970498,-20.0034375,0,5.739898468,90.00000001 +227.78,50.30085681,-3.017586734,10302.2066,0,198.997056,-20.003125,0,5.739898468,90.00000001 +227.79,50.30085681,-3.017558848,10302.4066,8.44E-11,198.9970622,-20.0034375,0,5.739898468,90.00000001 +227.8,50.30085681,-3.017530963,10302.6067,9.37E-11,198.9970684,-20.003125,0,5.739898468,90.00000001 +227.81,50.30085681,-3.017503077,10302.8067,5.62E-11,198.9972977,-20.001875,0,5.739898468,90.00000001 +227.82,50.30085681,-3.017475192,10303.0067,5.78E-11,198.9979729,-20.001875,0,5.739898468,90.00000001 +227.83,50.30085681,-3.017447306,10303.2067,1.02E-10,198.9982021,-20.003125,0,5.739898468,90.00000001 +227.84,50.30085681,-3.01741942,10303.4068,1.09E-10,198.9970933,-20.003125,0,5.739898468,90.00000001 +227.85,50.30085681,-3.017391535,10303.6068,7.19E-11,198.9959845,-20.001875,0,5.739898468,90.00000001 +227.86,50.30085681,-3.01736365,10303.8068,6.41E-11,198.9962137,-20.001875,0,5.739898468,90.00000001 +227.87,50.30085681,-3.017335764,10304.0068,9.53E-11,198.996889,-20.003125,0,5.739898468,90.00000001 +227.88,50.30085681,-3.017307879,10304.2069,9.38E-11,198.9971182,-20.003125,0,5.739898468,90.00000001 +227.89,50.30085681,-3.017279993,10304.4069,5.63E-11,198.9973474,-20.001875,0,5.739898468,90.00000001 +227.9,50.30085681,-3.017252108,10304.6069,5.63E-11,198.9980226,-20.001875,0,5.739898468,90.00000001 +227.91,50.30085681,-3.017224222,10304.8069,9.22E-11,198.9984749,-20.003125,0,5.739898468,90.00000001 +227.92,50.30085681,-3.017196336,10305.007,8.59E-11,198.9980351,-20.003125,0,5.739898468,90.00000001 +227.93,50.30085681,-3.017168451,10305.207,4.06E-11,198.9971493,-20.001875,0,5.739898468,90.00000001 +227.94,50.30085681,-3.017140565,10305.407,4.06E-11,198.9962635,-20.001875,0,5.739898468,90.00000001 +227.95,50.30085681,-3.01711268,10305.607,8.59E-11,198.9958237,-20.003125,0,5.739898468,90.00000001 +227.96,50.30085681,-3.017084795,10305.8071,9.22E-11,198.9962759,-20.003125,0,5.739898468,90.00000001 +227.97,50.30085681,-3.017056909,10306.0071,5.63E-11,198.9971741,-20.001875,0,5.739898468,90.00000001 +227.98,50.30085681,-3.017029024,10306.2071,5.63E-11,198.9980724,-20.001875,0,5.739898468,90.00000001 +227.99,50.30085681,-3.017001138,10306.4071,9.38E-11,198.9985246,-20.003125,0,5.739898468,90.00000001 +228,50.30085681,-3.016973252,10306.6072,9.53E-11,198.9980848,-20.003125,0,5.739898468,90.00000001 +228.01,50.30085681,-3.016945367,10306.8072,6.41E-11,198.997422,-20.001875,0,5.739898468,90.00000001 +228.02,50.30085681,-3.016917481,10307.0072,7.19E-11,198.9972052,-20.001875,0,5.739898468,90.00000001 +228.03,50.30085681,-3.016889596,10307.2072,1.09E-10,198.9969884,-20.003125,0,5.739898468,90.00000001 +228.04,50.30085681,-3.01686171,10307.4073,1.02E-10,198.9963256,-20.003125,0,5.739898468,90.00000001 +228.05,50.30085681,-3.016833825,10307.6073,5.78E-11,198.9961089,-20.001875,0,5.739898468,90.00000001 +228.06,50.30085681,-3.01680594,10307.8073,5.62E-11,198.9972301,-20.001875,0,5.739898468,90.00000001 +228.07,50.30085681,-3.016778054,10308.0073,9.37E-11,198.9983514,-20.003125,0,5.739898468,90.00000001 +228.08,50.30085681,-3.016750168,10308.2074,9.38E-11,198.9981346,-20.003125,0,5.739898468,90.00000001 +228.09,50.30085681,-3.016722283,10308.4074,5.63E-11,198.9974718,-20.001875,0,5.739898468,90.00000001 +228.1,50.30085681,-3.016694397,10308.6074,5.78E-11,198.997255,-20.001875,0,5.739898468,90.00000001 +228.11,50.30085681,-3.016666512,10308.8074,1.02E-10,198.9970382,-20.003125,0,5.739898468,90.00000001 +228.12,50.30085681,-3.016638626,10309.0075,1.09E-10,198.9963754,-20.003125,0,5.739898468,90.00000001 +228.13,50.30085681,-3.016610741,10309.2075,7.19E-11,198.9961586,-20.001875,0,5.739898468,90.00000001 +228.14,50.30085681,-3.016582856,10309.4075,6.41E-11,198.9972799,-20.001875,0,5.739898468,90.00000001 +228.15,50.30085681,-3.01655497,10309.6075,9.53E-11,198.9984011,-20.003125,0,5.739898468,90.00000001 +228.16,50.30085681,-3.016527084,10309.8076,9.37E-11,198.9981843,-20.003125,0,5.739898468,90.00000001 +228.17,50.30085681,-3.016499199,10310.0076,5.62E-11,198.9975215,-20.001875,0,5.739898468,90.00000001 +228.18,50.30085681,-3.016471313,10310.2076,5.62E-11,198.9973047,-20.001875,0,5.739898468,90.00000001 +228.19,50.30085681,-3.016443428,10310.4076,9.22E-11,198.9970879,-20.003125,0,5.739898468,90.00000001 +228.2,50.30085681,-3.016415542,10310.6077,8.59E-11,198.9964251,-20.003125,0,5.739898468,90.00000001 +228.21,50.30085681,-3.016387657,10310.8077,4.06E-11,198.9959853,-20.001875,0,5.739898468,90.00000001 +228.22,50.30085681,-3.016359772,10311.0077,4.06E-11,198.9964376,-20.001875,0,5.739898468,90.00000001 +228.23,50.30085681,-3.016331886,10311.2077,8.59E-11,198.9973358,-20.003125,0,5.739898468,90.00000001 +228.24,50.30085681,-3.016304001,10311.4078,9.22E-11,198.9982341,-20.003125,0,5.739898468,90.00000001 +228.25,50.30085681,-3.016276115,10311.6078,5.62E-11,198.9984633,-20.001875,0,5.739898468,90.00000001 +228.26,50.30085681,-3.016248229,10311.8078,5.62E-11,198.9973545,-20.001875,0,5.739898468,90.00000001 +228.27,50.30085681,-3.016220344,10312.0078,9.37E-11,198.9962457,-20.003125,0,5.739898468,90.00000001 +228.28,50.30085681,-3.016192459,10312.2079,9.53E-11,198.9964749,-20.003125,0,5.739898468,90.00000001 +228.29,50.30085681,-3.016164573,10312.4079,6.41E-11,198.9971501,-20.001875,0,5.739898468,90.00000001 +228.3,50.30085681,-3.016136688,10312.6079,7.19E-11,198.9973793,-20.001875,0,5.739898468,90.00000001 +228.31,50.30085681,-3.016108802,10312.8079,1.09E-10,198.9973856,-20.003125,0,5.739898468,90.00000001 +228.32,50.30085681,-3.016080917,10313.008,1.02E-10,198.9973918,-20.003125,0,5.739898468,90.00000001 +228.33,50.30085681,-3.016053031,10313.208,5.78E-11,198.997398,-20.001875,0,5.739898468,90.00000001 +228.34,50.30085681,-3.016025146,10313.408,5.63E-11,198.9971812,-20.001875,0,5.739898468,90.00000001 +228.35,50.30085681,-3.01599726,10313.608,9.38E-11,198.9965184,-20.003125,0,5.739898468,90.00000001 +228.36,50.30085681,-3.015969375,10313.8081,9.37E-11,198.9963016,-20.003125,0,5.739898468,90.00000001 +228.37,50.30085681,-3.01594149,10314.0081,5.62E-11,198.9974229,-20.001875,0,5.739898468,90.00000001 +228.38,50.30085681,-3.015913604,10314.2081,5.78E-11,198.9985441,-20.001875,0,5.739898468,90.00000001 +228.39,50.30085681,-3.015885718,10314.4081,1.02E-10,198.9983273,-20.003125,0,5.739898468,90.00000001 +228.4,50.30085681,-3.015857833,10314.6082,1.09E-10,198.9974415,-20.003125,0,5.739898468,90.00000001 +228.41,50.30085681,-3.015829947,10314.8082,7.19E-11,198.9965557,-20.001875,0,5.739898468,90.00000001 +228.42,50.30085681,-3.015802062,10315.0082,6.41E-11,198.9961159,-20.001875,0,5.739898468,90.00000001 +228.43,50.30085681,-3.015774177,10315.2082,9.53E-11,198.9965682,-20.003125,0,5.739898468,90.00000001 +228.44,50.30085681,-3.015746291,10315.4083,9.38E-11,198.9974664,-20.003125,0,5.739898468,90.00000001 +228.45,50.30085681,-3.015718406,10315.6083,5.63E-11,198.9983647,-20.001875,0,5.739898468,90.00000001 +228.46,50.30085681,-3.01569052,10315.8083,5.63E-11,198.9985939,-20.001875,0,5.739898468,90.00000001 +228.47,50.30085681,-3.015662634,10316.0083,9.22E-11,198.9974851,-20.003125,0,5.739898468,90.00000001 +228.48,50.30085681,-3.015634749,10316.2084,8.59E-11,198.9963762,-20.003125,0,5.739898468,90.00000001 +228.49,50.30085681,-3.015606864,10316.4084,4.06E-11,198.9966055,-20.001875,0,5.739898468,90.00000001 +228.5,50.30085681,-3.015578978,10316.6084,4.06E-11,198.9972807,-20.001875,0,5.739898468,90.00000001 +228.51,50.30085681,-3.015551093,10316.8084,8.59E-11,198.9975099,-20.003125,0,5.739898468,90.00000001 +228.52,50.30085681,-3.015523207,10317.0085,9.22E-11,198.9975162,-20.003125,0,5.739898468,90.00000001 +228.53,50.30085681,-3.015495322,10317.2085,5.62E-11,198.9972994,-20.001875,0,5.739898468,90.00000001 +228.54,50.30085681,-3.015467436,10317.4085,5.62E-11,198.9966366,-20.001875,0,5.739898468,90.00000001 +228.55,50.30085681,-3.015439551,10317.6085,9.37E-11,198.9961968,-20.003125,0,5.739898468,90.00000001 +228.56,50.30085681,-3.015411666,10317.8086,9.53E-11,198.996649,-20.003125,0,5.739898468,90.00000001 +228.57,50.30085681,-3.01538378,10318.0086,6.41E-11,198.9975472,-20.001875,0,5.739898468,90.00000001 +228.58,50.30085681,-3.015355895,10318.2086,7.19E-11,198.9984455,-20.001875,0,5.739898468,90.00000001 +228.59,50.30085681,-3.015328009,10318.4086,1.09E-10,198.9986747,-20.003125,0,5.739898468,90.00000001 +228.6,50.30085681,-3.015300123,10318.6087,1.02E-10,198.9975659,-20.003125,0,5.739898468,90.00000001 +228.61,50.30085681,-3.015272238,10318.8087,5.78E-11,198.9964571,-20.001875,0,5.739898468,90.00000001 +228.62,50.30085681,-3.015244353,10319.0087,5.62E-11,198.9966863,-20.001875,0,5.739898468,90.00000001 +228.63,50.30085681,-3.015216467,10319.2087,9.37E-11,198.9973615,-20.003125,0,5.739898468,90.00000001 +228.64,50.30085681,-3.015188582,10319.4088,9.37E-11,198.9975908,-20.003125,0,5.739898468,90.00000001 +228.65,50.30085681,-3.015160696,10319.6088,5.62E-11,198.997597,-20.001875,0,5.739898468,90.00000001 +228.66,50.30085681,-3.015132811,10319.8088,5.78E-11,198.9973802,-20.001875,0,5.739898468,90.00000001 +228.67,50.30085681,-3.015104925,10320.0088,1.02E-10,198.9967174,-20.003125,0,5.739898468,90.00000001 +228.68,50.30085681,-3.01507704,10320.2089,1.00E-10,198.9962776,-20.0034375,0,5.739898468,90.00000001 +228.69,50.30085681,-3.015049155,10320.4089,1.56E-11,198.9967298,-20.003125,0,5.739898468,90.00000001 +228.7,50.30085681,-3.015021269,10320.6089,-7.66E-11,198.9974051,-20.0034375,0,5.739898468,90.00000001 +228.71,50.30085681,-3.014993384,10320.809,-9.22E-11,198.9976343,-20.003125,0,5.739898468,90.00000001 +228.72,50.30085681,-3.014965498,10321.009,-5.63E-11,198.9976405,-20.001875,0,5.739898468,90.00000001 +228.73,50.30085681,-3.014937613,10321.209,-5.63E-11,198.9974237,-20.001875,0,5.739898468,90.00000001 +228.74,50.30085681,-3.014909727,10321.409,-9.38E-11,198.9967609,-20.003125,0,5.739898468,90.00000001 +228.75,50.30085681,-3.014881842,10321.6091,-9.53E-11,198.9965441,-20.003125,0,5.739898468,90.00000001 +228.76,50.30085681,-3.014853957,10321.8091,-6.41E-11,198.9976654,-20.001875,0,5.739898468,90.00000001 +228.77,50.30085681,-3.014826071,10322.0091,-7.19E-11,198.9985636,-20.001875,0,5.739898468,90.00000001 +228.78,50.30085681,-3.014798185,10322.2091,-1.09E-10,198.9976778,-20.003125,0,5.739898468,90.00000001 +228.79,50.30085681,-3.0147703,10322.4092,-1.02E-10,198.996569,-20.003125,0,5.739898468,90.00000001 +228.8,50.30085681,-3.014742415,10322.6092,-5.78E-11,198.9965752,-20.001875,0,5.739898468,90.00000001 +228.81,50.30085681,-3.014714529,10322.8092,-5.62E-11,198.9965814,-20.001875,0,5.739898468,90.00000001 +228.82,50.30085681,-3.014686644,10323.0092,-9.37E-11,198.9965877,-20.003125,0,5.739898468,90.00000001 +228.83,50.30085681,-3.014658759,10323.2093,-9.38E-11,198.9977089,-20.003125,0,5.739898468,90.00000001 +228.84,50.30085681,-3.014630873,10323.4093,-5.63E-11,198.9986072,-20.001875,0,5.739898468,90.00000001 +228.85,50.30085681,-3.014602987,10323.6093,-5.78E-11,198.9974984,-20.001875,0,5.739898468,90.00000001 +228.86,50.30085681,-3.014575102,10323.8093,-1.02E-10,198.9957205,-20.003125,0,5.739898468,90.00000001 +228.87,50.30085681,-3.014547217,10324.0094,-1.09E-10,198.9957267,-20.003125,0,5.739898468,90.00000001 +228.88,50.30085681,-3.014519332,10324.2094,-7.19E-11,198.997517,-20.001875,0,5.739898468,90.00000001 +228.89,50.30085681,-3.014491446,10324.4094,-6.41E-11,198.9986383,-20.001875,0,5.739898468,90.00000001 +228.9,50.30085681,-3.01446356,10324.6094,-9.53E-11,198.9977524,-20.003125,0,5.739898468,90.00000001 +228.91,50.30085681,-3.014435675,10324.8095,-9.37E-11,198.9966436,-20.003125,0,5.739898468,90.00000001 +228.92,50.30085681,-3.01440779,10325.0095,-5.62E-11,198.9968729,-20.001875,0,5.739898468,90.00000001 +228.93,50.30085681,-3.014379904,10325.2095,-5.62E-11,198.9975481,-20.001875,0,5.739898468,90.00000001 +228.94,50.30085681,-3.014352019,10325.4095,-9.22E-11,198.9977773,-20.003125,0,5.739898468,90.00000001 +228.95,50.30085681,-3.014324133,10325.6096,-8.59E-11,198.9977835,-20.003125,0,5.739898468,90.00000001 +228.96,50.30085681,-3.014296248,10325.8096,-4.06E-11,198.9975668,-20.001875,0,5.739898468,90.00000001 +228.97,50.30085681,-3.014268362,10326.0096,-4.06E-11,198.9969039,-20.001875,0,5.739898468,90.00000001 +228.98,50.30085681,-3.014240477,10326.2096,-8.59E-11,198.9964642,-20.003125,0,5.739898468,90.00000001 +228.99,50.30085681,-3.014212592,10326.4097,-9.22E-11,198.9969164,-20.003125,0,5.739898468,90.00000001 +229,50.30085681,-3.014184706,10326.6097,-5.62E-11,198.9975916,-20.001875,0,5.739898468,90.00000001 +229.01,50.30085681,-3.014156821,10326.8097,-5.62E-11,198.9975978,-20.001875,0,5.739898468,90.00000001 +229.02,50.30085681,-3.014128935,10327.0097,-9.37E-11,198.996935,-20.003125,0,5.739898468,90.00000001 +229.03,50.30085681,-3.01410105,10327.2098,-9.53E-11,198.9964952,-20.003125,0,5.739898468,90.00000001 +229.04,50.30085681,-3.014073165,10327.4098,-6.41E-11,198.9969475,-20.001875,0,5.739898468,90.00000001 +229.05,50.30085681,-3.014045279,10327.6098,-7.19E-11,198.9976227,-20.001875,0,5.739898468,90.00000001 +229.06,50.30085681,-3.014017394,10327.8098,-1.09E-10,198.9976289,-20.003125,0,5.739898468,90.00000001 +229.07,50.30085681,-3.013989508,10328.0099,-1.02E-10,198.9969661,-20.003125,0,5.739898468,90.00000001 +229.08,50.30085681,-3.013961623,10328.2099,-5.78E-11,198.9965263,-20.001875,0,5.739898468,90.00000001 +229.09,50.30085681,-3.013933738,10328.4099,-5.63E-11,198.9969786,-20.001875,0,5.739898468,90.00000001 +229.1,50.30085681,-3.013905852,10328.6099,-9.38E-11,198.9976538,-20.003125,0,5.739898468,90.00000001 +229.11,50.30085681,-3.013877967,10328.81,-9.37E-11,198.99766,-20.003125,0,5.739898468,90.00000001 +229.12,50.30085681,-3.013850081,10329.01,-5.62E-11,198.9969972,-20.001875,0,5.739898468,90.00000001 +229.13,50.30085681,-3.013822196,10329.21,-5.78E-11,198.9965574,-20.001875,0,5.739898468,90.00000001 +229.14,50.30085681,-3.013794311,10329.41,-1.02E-10,198.9970097,-20.003125,0,5.739898468,90.00000001 +229.15,50.30085681,-3.013766425,10329.6101,-1.09E-10,198.9976849,-20.003125,0,5.739898468,90.00000001 +229.16,50.30085681,-3.01373854,10329.8101,-7.19E-11,198.9979141,-20.001875,0,5.739898468,90.00000001 +229.17,50.30085681,-3.013710654,10330.0101,-6.41E-11,198.9979203,-20.001875,0,5.739898468,90.00000001 +229.18,50.30085681,-3.013682769,10330.2101,-9.53E-11,198.9977036,-20.003125,0,5.739898468,90.00000001 +229.19,50.30085681,-3.013654883,10330.4102,-9.38E-11,198.9970408,-20.003125,0,5.739898468,90.00000001 +229.2,50.30085681,-3.013626998,10330.6102,-5.63E-11,198.996601,-20.001875,0,5.739898468,90.00000001 +229.21,50.30085681,-3.013599113,10330.8102,-5.63E-11,198.9970532,-20.001875,0,5.739898468,90.00000001 +229.22,50.30085681,-3.013571227,10331.0102,-9.22E-11,198.9977284,-20.003125,0,5.739898468,90.00000001 +229.23,50.30085681,-3.013543342,10331.2103,-8.59E-11,198.9977346,-20.003125,0,5.739898468,90.00000001 +229.24,50.30085681,-3.013515456,10331.4103,-4.06E-11,198.9970718,-20.001875,0,5.739898468,90.00000001 +229.25,50.30085681,-3.013487571,10331.6103,-4.06E-11,198.996632,-20.001875,0,5.739898468,90.00000001 +229.26,50.30085681,-3.013459686,10331.8103,-8.59E-11,198.9970843,-20.003125,0,5.739898468,90.00000001 +229.27,50.30085681,-3.0134318,10332.0104,-9.22E-11,198.9977595,-20.003125,0,5.739898468,90.00000001 +229.28,50.30085681,-3.013403915,10332.2104,-5.62E-11,198.9977657,-20.001875,0,5.739898468,90.00000001 +229.29,50.30085681,-3.013376029,10332.4104,-5.62E-11,198.9971029,-20.001875,0,5.739898468,90.00000001 +229.3,50.30085681,-3.013348144,10332.6104,-9.37E-11,198.9966631,-20.003125,0,5.739898468,90.00000001 +229.31,50.30085681,-3.013320259,10332.8105,-9.53E-11,198.9968924,-20.003125,0,5.739898468,90.00000001 +229.32,50.30085681,-3.013292373,10333.0105,-6.41E-11,198.9968986,-20.001875,0,5.739898468,90.00000001 +229.33,50.30085681,-3.013264488,10333.2105,-7.19E-11,198.9966818,-20.001875,0,5.739898468,90.00000001 +229.34,50.30085681,-3.013236603,10333.4105,-1.09E-10,198.997134,-20.003125,0,5.739898468,90.00000001 +229.35,50.30085681,-3.013208717,10333.6106,-1.02E-10,198.9978093,-20.003125,0,5.739898468,90.00000001 +229.36,50.30085681,-3.013180832,10333.8106,-5.78E-11,198.9978155,-20.001875,0,5.739898468,90.00000001 +229.37,50.30085681,-3.013152946,10334.0106,-5.62E-11,198.9971527,-20.001875,0,5.739898468,90.00000001 +229.38,50.30085681,-3.013125061,10334.2106,-9.37E-11,198.9967129,-20.003125,0,5.739898468,90.00000001 +229.39,50.30085681,-3.013097176,10334.4107,-9.37E-11,198.9971651,-20.003125,0,5.739898468,90.00000001 +229.4,50.30085681,-3.01306929,10334.6107,-5.62E-11,198.9978404,-20.001875,0,5.739898468,90.00000001 +229.41,50.30085681,-3.013041405,10334.8107,-5.78E-11,198.9978466,-20.001875,0,5.739898468,90.00000001 +229.42,50.30085681,-3.013013519,10335.0107,-1.02E-10,198.9969608,-20.003125,0,5.739898468,90.00000001 +229.43,50.30085681,-3.012985634,10335.2108,-1.09E-10,198.9958519,-20.003125,0,5.739898468,90.00000001 +229.44,50.30085681,-3.012957749,10335.4108,-7.19E-11,198.9960812,-20.001875,0,5.739898468,90.00000001 +229.45,50.30085681,-3.012929864,10335.6108,-6.41E-11,198.9978715,-20.001875,0,5.739898468,90.00000001 +229.46,50.30085681,-3.012901978,10335.8108,-9.53E-11,198.9989927,-20.003125,0,5.739898468,90.00000001 +229.47,50.30085681,-3.012874092,10336.0109,-9.37E-11,198.9978839,-20.003125,0,5.739898468,90.00000001 +229.48,50.30085681,-3.012846207,10336.2109,-5.62E-11,198.996106,-20.001875,0,5.739898468,90.00000001 +229.49,50.30085681,-3.012818322,10336.4109,-5.62E-11,198.9961123,-20.001875,0,5.739898468,90.00000001 +229.5,50.30085681,-3.012790437,10336.6109,-9.22E-11,198.9979025,-20.003125,0,5.739898468,90.00000001 +229.51,50.30085681,-3.012762551,10336.811,-8.59E-11,198.9990238,-20.003125,0,5.739898468,90.00000001 +229.52,50.30085681,-3.012734665,10337.011,-4.06E-11,198.997915,-20.001875,0,5.739898468,90.00000001 +229.53,50.30085681,-3.01270678,10337.211,-4.06E-11,198.9961371,-20.001875,0,5.739898468,90.00000001 +229.54,50.30085681,-3.012678895,10337.411,-8.59E-11,198.9959203,-20.003125,0,5.739898468,90.00000001 +229.55,50.30085681,-3.01265101,10337.6111,-8.28E-11,198.9970416,-20.0034375,0,5.739898468,90.00000001 +229.56,50.30085681,-3.012623124,10337.8111,-1.11E-15,198.9979399,-20.003125,0,5.739898468,90.00000001 +229.57,50.30085681,-3.012595239,10338.0111,8.44E-11,198.9979461,-20.0034375,0,5.739898468,90.00000001 +229.58,50.30085681,-3.012567353,10338.2112,9.38E-11,198.9972833,-20.003125,0,5.739898468,90.00000001 +229.59,50.30085681,-3.012539468,10338.4112,5.63E-11,198.9968435,-20.001875,0,5.739898468,90.00000001 +229.6,50.30085681,-3.012511583,10338.6112,5.78E-11,198.9970727,-20.001875,0,5.739898468,90.00000001 +229.61,50.30085681,-3.012483697,10338.8112,1.02E-10,198.9970789,-20.003125,0,5.739898468,90.00000001 +229.62,50.30085681,-3.012455812,10339.0113,1.09E-10,198.9968621,-20.003125,0,5.739898468,90.00000001 +229.63,50.30085681,-3.012427927,10339.2113,7.19E-11,198.9973144,-20.001875,0,5.739898468,90.00000001 +229.64,50.30085681,-3.012400041,10339.4113,6.41E-11,198.9979896,-20.001875,0,5.739898468,90.00000001 +229.65,50.30085681,-3.012372156,10339.6113,9.53E-11,198.9979958,-20.003125,0,5.739898468,90.00000001 +229.66,50.30085681,-3.01234427,10339.8114,9.37E-11,198.997333,-20.003125,0,5.739898468,90.00000001 +229.67,50.30085681,-3.012316385,10340.0114,5.62E-11,198.9968932,-20.001875,0,5.739898468,90.00000001 +229.68,50.30085681,-3.0122885,10340.2114,5.62E-11,198.9971224,-20.001875,0,5.739898468,90.00000001 +229.69,50.30085681,-3.012260614,10340.4114,9.22E-11,198.9969057,-20.003125,0,5.739898468,90.00000001 +229.7,50.30085681,-3.012232729,10340.6115,8.59E-11,198.9960198,-20.003125,0,5.739898468,90.00000001 +229.71,50.30085681,-3.012204844,10340.8115,4.06E-11,198.9962491,-20.001875,0,5.739898468,90.00000001 +229.72,50.30085681,-3.012176959,10341.0115,4.06E-11,198.9980393,-20.001875,0,5.739898468,90.00000001 +229.73,50.30085681,-3.012149073,10341.2115,8.59E-11,198.9991606,-20.003125,0,5.739898468,90.00000001 +229.74,50.30085681,-3.012121187,10341.4116,9.22E-11,198.9980518,-20.003125,0,5.739898468,90.00000001 +229.75,50.30085681,-3.012093302,10341.6116,5.62E-11,198.9962739,-20.001875,0,5.739898468,90.00000001 +229.76,50.30085681,-3.012065417,10341.8116,5.62E-11,198.9960571,-20.001875,0,5.739898468,90.00000001 +229.77,50.30085681,-3.012037532,10342.0116,9.37E-11,198.9969554,-20.003125,0,5.739898468,90.00000001 +229.78,50.30085681,-3.012009646,10342.2117,9.53E-11,198.9971846,-20.003125,0,5.739898468,90.00000001 +229.79,50.30085681,-3.011981761,10342.4117,6.41E-11,198.9969678,-20.001875,0,5.739898468,90.00000001 +229.8,50.30085681,-3.011953876,10342.6117,7.19E-11,198.9974201,-20.001875,0,5.739898468,90.00000001 +229.81,50.30085681,-3.01192599,10342.8117,1.09E-10,198.9980953,-20.003125,0,5.739898468,90.00000001 +229.82,50.30085681,-3.011898105,10343.0118,1.02E-10,198.9981015,-20.003125,0,5.739898468,90.00000001 +229.83,50.30085681,-3.011870219,10343.2118,5.78E-11,198.9974387,-20.001875,0,5.739898468,90.00000001 +229.84,50.30085681,-3.011842334,10343.4118,5.63E-11,198.9969989,-20.001875,0,5.739898468,90.00000001 +229.85,50.30085681,-3.011814449,10343.6118,9.38E-11,198.9972282,-20.003125,0,5.739898468,90.00000001 +229.86,50.30085681,-3.011786563,10343.8119,9.37E-11,198.9970114,-20.003125,0,5.739898468,90.00000001 +229.87,50.30085681,-3.011758678,10344.0119,5.62E-11,198.9961255,-20.001875,0,5.739898468,90.00000001 +229.88,50.30085681,-3.011730793,10344.2119,5.78E-11,198.9963548,-20.001875,0,5.739898468,90.00000001 +229.89,50.30085681,-3.011702908,10344.4119,1.02E-10,198.9981451,-20.003125,0,5.739898468,90.00000001 +229.9,50.30085681,-3.011675022,10344.612,1.09E-10,198.9992663,-20.003125,0,5.739898468,90.00000001 +229.91,50.30085681,-3.011647136,10344.812,7.19E-11,198.9981575,-20.001875,0,5.739898468,90.00000001 +229.92,50.30085681,-3.011619251,10345.012,6.41E-11,198.9963796,-20.001875,0,5.739898468,90.00000001 +229.93,50.30085681,-3.011591366,10345.212,9.53E-11,198.9961629,-20.003125,0,5.739898468,90.00000001 +229.94,50.30085681,-3.011563481,10345.4121,9.38E-11,198.9970611,-20.003125,0,5.739898468,90.00000001 +229.95,50.30085681,-3.011535595,10345.6121,5.63E-11,198.9970673,-20.001875,0,5.739898468,90.00000001 +229.96,50.30085681,-3.01150771,10345.8121,5.63E-11,198.9961815,-20.001875,0,5.739898468,90.00000001 +229.97,50.30085681,-3.011479825,10346.0121,9.22E-11,198.9961877,-20.003125,0,5.739898468,90.00000001 +229.98,50.30085681,-3.01145194,10346.2122,8.59E-11,198.997086,-20.003125,0,5.739898468,90.00000001 +229.99,50.30085681,-3.011424054,10346.4122,4.06E-11,198.9973152,-20.001875,0,5.739898468,90.00000001 +230,50.30085681,-3.011396169,10346.6122,4.06E-11,198.9970984,-20.001875,0,5.739898468,90.00000001 +230.01,50.30085681,-3.011368284,10346.8122,8.59E-11,198.9975507,-20.003125,0,5.739898468,90.00000001 +230.02,50.30085681,-3.011340398,10347.0123,9.22E-11,198.9982259,-20.003125,0,5.739898468,90.00000001 +230.03,50.30085681,-3.011312513,10347.2123,5.63E-11,198.9982321,-20.001875,0,5.739898468,90.00000001 +230.04,50.30085681,-3.011284627,10347.4123,5.63E-11,198.9975693,-20.001875,0,5.739898468,90.00000001 +230.05,50.30085681,-3.011256742,10347.6123,9.38E-11,198.9971295,-20.003125,0,5.739898468,90.00000001 +230.06,50.30085681,-3.011228857,10347.8124,9.53E-11,198.9973587,-20.003125,0,5.739898468,90.00000001 +230.07,50.30085681,-3.011200971,10348.0124,6.41E-11,198.9971419,-20.001875,0,5.739898468,90.00000001 +230.08,50.30085681,-3.011173086,10348.2124,7.19E-11,198.9962561,-20.001875,0,5.739898468,90.00000001 +230.09,50.30085681,-3.011145201,10348.4124,1.09E-10,198.9962623,-20.003125,0,5.739898468,90.00000001 +230.1,50.30085681,-3.011117316,10348.6125,1.02E-10,198.9971606,-20.003125,0,5.739898468,90.00000001 +230.11,50.30085681,-3.01108943,10348.8125,5.78E-11,198.9973898,-20.001875,0,5.739898468,90.00000001 +230.12,50.30085681,-3.011061545,10349.0125,5.62E-11,198.997173,-20.001875,0,5.739898468,90.00000001 +230.13,50.30085681,-3.01103366,10349.2125,9.37E-11,198.9976253,-20.003125,0,5.739898468,90.00000001 +230.14,50.30085681,-3.011005774,10349.4126,9.37E-11,198.9983005,-20.003125,0,5.739898468,90.00000001 +230.15,50.30085681,-3.010977889,10349.6126,5.62E-11,198.9983067,-20.001875,0,5.739898468,90.00000001 +230.16,50.30085681,-3.010950003,10349.8126,5.78E-11,198.9976439,-20.001875,0,5.739898468,90.00000001 +230.17,50.30085681,-3.010922118,10350.0126,1.02E-10,198.9972041,-20.003125,0,5.739898468,90.00000001 +230.18,50.30085681,-3.010894233,10350.2127,1.09E-10,198.9974334,-20.003125,0,5.739898468,90.00000001 +230.19,50.30085681,-3.010866347,10350.4127,7.19E-11,198.9972166,-20.001875,0,5.739898468,90.00000001 +230.2,50.30085681,-3.010838462,10350.6127,6.41E-11,198.9963308,-20.001875,0,5.739898468,90.00000001 +230.21,50.30085681,-3.010810577,10350.8127,9.53E-11,198.996337,-20.003125,0,5.739898468,90.00000001 +230.22,50.30085681,-3.010782692,10351.0128,9.37E-11,198.9972352,-20.003125,0,5.739898468,90.00000001 +230.23,50.30085681,-3.010754806,10351.2128,5.62E-11,198.9974644,-20.001875,0,5.739898468,90.00000001 +230.24,50.30085681,-3.010726921,10351.4128,5.62E-11,198.9972477,-20.001875,0,5.739898468,90.00000001 +230.25,50.30085681,-3.010699036,10351.6128,9.22E-11,198.9974769,-20.003125,0,5.739898468,90.00000001 +230.26,50.30085681,-3.01067115,10351.8129,8.59E-11,198.9972601,-20.003125,0,5.739898468,90.00000001 +230.27,50.30085681,-3.010643265,10352.0129,4.06E-11,198.9963743,-20.001875,0,5.739898468,90.00000001 +230.28,50.30085681,-3.01061538,10352.2129,4.06E-11,198.9963805,-20.001875,0,5.739898468,90.00000001 +230.29,50.30085681,-3.010587495,10352.4129,8.59E-11,198.9972788,-20.003125,0,5.739898468,90.00000001 +230.3,50.30085681,-3.010559609,10352.613,9.22E-11,198.997508,-20.003125,0,5.739898468,90.00000001 +230.31,50.30085681,-3.010531724,10352.813,5.63E-11,198.9972912,-20.001875,0,5.739898468,90.00000001 +230.32,50.30085681,-3.010503839,10353.013,5.63E-11,198.9975204,-20.001875,0,5.739898468,90.00000001 +230.33,50.30085681,-3.010475953,10353.213,9.38E-11,198.9973036,-20.003125,0,5.739898468,90.00000001 +230.34,50.30085681,-3.010448068,10353.4131,9.53E-11,198.9964178,-20.003125,0,5.739898468,90.00000001 +230.35,50.30085681,-3.010420183,10353.6131,6.41E-11,198.996647,-20.001875,0,5.739898468,90.00000001 +230.36,50.30085681,-3.010392298,10353.8131,7.19E-11,198.9984373,-20.001875,0,5.739898468,90.00000001 +230.37,50.30085681,-3.010364412,10354.0131,1.09E-10,198.9995586,-20.003125,0,5.739898468,90.00000001 +230.38,50.30085681,-3.010336526,10354.2132,1.02E-10,198.9984498,-20.003125,0,5.739898468,90.00000001 +230.39,50.30085681,-3.010308641,10354.4132,5.78E-11,198.9966719,-20.001875,0,5.739898468,90.00000001 +230.4,50.30085681,-3.010280756,10354.6132,5.63E-11,198.9964551,-20.001875,0,5.739898468,90.00000001 +230.41,50.30085681,-3.010252871,10354.8132,9.38E-11,198.9973534,-20.003125,0,5.739898468,90.00000001 +230.42,50.30085681,-3.010224985,10355.0133,8.44E-11,198.9975826,-20.0034375,0,5.739898468,90.00000001 +230.43,50.30085681,-3.0101971,10355.2133,1.11E-15,198.9973658,-20.003125,0,5.739898468,90.00000001 +230.44,50.30085681,-3.010169215,10355.4133,-8.28E-11,198.997595,-20.0034375,0,5.739898468,90.00000001 +230.45,50.30085681,-3.010141329,10355.6134,-8.59E-11,198.9973782,-20.003125,0,5.739898468,90.00000001 +230.46,50.30085681,-3.010113444,10355.8134,-4.06E-11,198.9964924,-20.001875,0,5.739898468,90.00000001 +230.47,50.30085681,-3.010085559,10356.0134,-4.06E-11,198.9964986,-20.001875,0,5.739898468,90.00000001 +230.48,50.30085681,-3.010057674,10356.2134,-8.59E-11,198.9973969,-20.003125,0,5.739898468,90.00000001 +230.49,50.30085681,-3.010029788,10356.4135,-9.22E-11,198.9974031,-20.003125,0,5.739898468,90.00000001 +230.5,50.30085681,-3.010001903,10356.6135,-5.62E-11,198.9965173,-20.001875,0,5.739898468,90.00000001 +230.51,50.30085681,-3.009974018,10356.8135,-5.62E-11,198.9965235,-20.001875,0,5.739898468,90.00000001 +230.52,50.30085681,-3.009946133,10357.0135,-9.37E-11,198.9974218,-20.003125,0,5.739898468,90.00000001 +230.53,50.30085681,-3.009918247,10357.2136,-9.53E-11,198.997651,-20.003125,0,5.739898468,90.00000001 +230.54,50.30085681,-3.009890362,10357.4136,-6.41E-11,198.9974342,-20.001875,0,5.739898468,90.00000001 +230.55,50.30085681,-3.009862477,10357.6136,-7.19E-11,198.9976634,-20.001875,0,5.739898468,90.00000001 +230.56,50.30085681,-3.009834591,10357.8136,-1.09E-10,198.9974466,-20.003125,0,5.739898468,90.00000001 +230.57,50.30085681,-3.009806706,10358.0137,-1.02E-10,198.9965608,-20.003125,0,5.739898468,90.00000001 +230.58,50.30085681,-3.009778821,10358.2137,-5.78E-11,198.996567,-20.001875,0,5.739898468,90.00000001 +230.59,50.30085681,-3.009750936,10358.4137,-5.63E-11,198.9974653,-20.001875,0,5.739898468,90.00000001 +230.6,50.30085681,-3.00972305,10358.6137,-9.38E-11,198.9976945,-20.003125,0,5.739898468,90.00000001 +230.61,50.30085681,-3.009695165,10358.8138,-9.37E-11,198.9974777,-20.003125,0,5.739898468,90.00000001 +230.62,50.30085681,-3.00966728,10359.0138,-5.62E-11,198.997707,-20.001875,0,5.739898468,90.00000001 +230.63,50.30085681,-3.009639394,10359.2138,-5.78E-11,198.9974902,-20.001875,0,5.739898468,90.00000001 +230.64,50.30085681,-3.009611509,10359.4138,-1.02E-10,198.9966044,-20.003125,0,5.739898468,90.00000001 +230.65,50.30085681,-3.009583624,10359.6139,-1.09E-10,198.9966106,-20.003125,0,5.739898468,90.00000001 +230.66,50.30085681,-3.009555739,10359.8139,-7.19E-11,198.9975088,-20.001875,0,5.739898468,90.00000001 +230.67,50.30085681,-3.009527853,10360.0139,-6.41E-11,198.9977381,-20.001875,0,5.739898468,90.00000001 +230.68,50.30085681,-3.009499968,10360.2139,-9.53E-11,198.9975213,-20.003125,0,5.739898468,90.00000001 +230.69,50.30085681,-3.009472083,10360.414,-9.38E-11,198.9977505,-20.003125,0,5.739898468,90.00000001 +230.7,50.30085681,-3.009444197,10360.614,-5.63E-11,198.9975337,-20.001875,0,5.739898468,90.00000001 +230.71,50.30085681,-3.009416312,10360.814,-5.63E-11,198.9964249,-20.001875,0,5.739898468,90.00000001 +230.72,50.30085681,-3.009388427,10361.014,-9.22E-11,198.9955391,-20.003125,0,5.739898468,90.00000001 +230.73,50.30085681,-3.009360542,10361.2141,-8.59E-11,198.9955453,-20.003125,0,5.739898468,90.00000001 +230.74,50.30085681,-3.009332657,10361.4141,-4.06E-11,198.9964435,-20.001875,0,5.739898468,90.00000001 +230.75,50.30085681,-3.009304772,10361.6141,-4.06E-11,198.9975648,-20.001875,0,5.739898468,90.00000001 +230.76,50.30085681,-3.009276886,10361.8141,-8.59E-11,198.997794,-20.003125,0,5.739898468,90.00000001 +230.77,50.30085681,-3.009249001,10362.0142,-9.22E-11,198.9975772,-20.003125,0,5.739898468,90.00000001 +230.78,50.30085681,-3.009221116,10362.2142,-5.63E-11,198.9978065,-20.001875,0,5.739898468,90.00000001 +230.79,50.30085681,-3.00919323,10362.4142,-5.63E-11,198.9975897,-20.001875,0,5.739898468,90.00000001 +230.8,50.30085681,-3.009165345,10362.6142,-9.38E-11,198.9967038,-20.003125,0,5.739898468,90.00000001 +230.81,50.30085681,-3.00913746,10362.8143,-9.53E-11,198.9967101,-20.003125,0,5.739898468,90.00000001 +230.82,50.30085681,-3.009109575,10363.0143,-6.41E-11,198.9976083,-20.001875,0,5.739898468,90.00000001 +230.83,50.30085681,-3.009081689,10363.2143,-7.19E-11,198.9978375,-20.001875,0,5.739898468,90.00000001 +230.84,50.30085681,-3.009053804,10363.4143,-1.09E-10,198.9976208,-20.003125,0,5.739898468,90.00000001 +230.85,50.30085681,-3.009025919,10363.6144,-1.02E-10,198.99785,-20.003125,0,5.739898468,90.00000001 +230.86,50.30085681,-3.008998033,10363.8144,-5.78E-11,198.9976332,-20.001875,0,5.739898468,90.00000001 +230.87,50.30085681,-3.008970148,10364.0144,-5.62E-11,198.9967474,-20.001875,0,5.739898468,90.00000001 +230.88,50.30085681,-3.008942263,10364.2144,-9.37E-11,198.9967536,-20.003125,0,5.739898468,90.00000001 +230.89,50.30085681,-3.008914378,10364.4145,-9.38E-11,198.9976518,-20.003125,0,5.739898468,90.00000001 +230.9,50.30085681,-3.008886492,10364.6145,-5.63E-11,198.9978811,-20.001875,0,5.739898468,90.00000001 +230.91,50.30085681,-3.008858607,10364.8145,-5.78E-11,198.9976643,-20.001875,0,5.739898468,90.00000001 +230.92,50.30085681,-3.008830722,10365.0145,-1.02E-10,198.9978935,-20.003125,0,5.739898468,90.00000001 +230.93,50.30085681,-3.008802836,10365.2146,-1.09E-10,198.9976767,-20.003125,0,5.739898468,90.00000001 +230.94,50.30085681,-3.008774951,10365.4146,-7.19E-11,198.9965679,-20.001875,0,5.739898468,90.00000001 +230.95,50.30085681,-3.008747066,10365.6146,-6.41E-11,198.9956821,-20.001875,0,5.739898468,90.00000001 +230.96,50.30085681,-3.008719181,10365.8146,-9.53E-11,198.9956883,-20.003125,0,5.739898468,90.00000001 +230.97,50.30085681,-3.008691296,10366.0147,-9.37E-11,198.9965866,-20.003125,0,5.739898468,90.00000001 +230.98,50.30085681,-3.008663411,10366.2147,-5.62E-11,198.9977078,-20.001875,0,5.739898468,90.00000001 +230.99,50.30085681,-3.008635525,10366.4147,-5.62E-11,198.997714,-20.001875,0,5.739898468,90.00000001 +231,50.30085681,-3.00860764,10366.6147,-9.22E-11,198.9968282,-20.003125,0,5.739898468,90.00000001 +231.01,50.30085681,-3.008579755,10366.8148,-8.59E-11,198.9968344,-20.003125,0,5.739898468,90.00000001 +231.02,50.30085681,-3.00855187,10367.0148,-4.06E-11,198.9977327,-20.001875,0,5.739898468,90.00000001 +231.03,50.30085681,-3.008523984,10367.2148,-4.06E-11,198.9979619,-20.001875,0,5.739898468,90.00000001 +231.04,50.30085681,-3.008496099,10367.4148,-8.59E-11,198.9977451,-20.003125,0,5.739898468,90.00000001 +231.05,50.30085681,-3.008468214,10367.6149,-9.22E-11,198.9979744,-20.003125,0,5.739898468,90.00000001 +231.06,50.30085681,-3.008440328,10367.8149,-5.62E-11,198.9977576,-20.001875,0,5.739898468,90.00000001 +231.07,50.30085681,-3.008412443,10368.0149,-5.62E-11,198.9966487,-20.001875,0,5.739898468,90.00000001 +231.08,50.30085681,-3.008384558,10368.2149,-9.37E-11,198.9957629,-20.003125,0,5.739898468,90.00000001 +231.09,50.30085681,-3.008356673,10368.415,-9.53E-11,198.9957691,-20.003125,0,5.739898468,90.00000001 +231.1,50.30085681,-3.008328788,10368.615,-6.41E-11,198.9966674,-20.001875,0,5.739898468,90.00000001 +231.11,50.30085681,-3.008300903,10368.815,-7.19E-11,198.9977887,-20.001875,0,5.739898468,90.00000001 +231.12,50.30085681,-3.008273017,10369.015,-1.09E-10,198.9980179,-20.003125,0,5.739898468,90.00000001 +231.13,50.30085681,-3.008245132,10369.2151,-1.02E-10,198.9978011,-20.003125,0,5.739898468,90.00000001 +231.14,50.30085681,-3.008217247,10369.4151,-5.78E-11,198.9980303,-20.001875,0,5.739898468,90.00000001 +231.15,50.30085681,-3.008189361,10369.6151,-5.63E-11,198.9978135,-20.001875,0,5.739898468,90.00000001 +231.16,50.30085681,-3.008161476,10369.8151,-9.38E-11,198.9969277,-20.003125,0,5.739898468,90.00000001 +231.17,50.30085681,-3.008133591,10370.0152,-9.38E-11,198.9969339,-20.003125,0,5.739898468,90.00000001 +231.18,50.30085681,-3.008105706,10370.2152,-5.63E-11,198.9978322,-20.001875,0,5.739898468,90.00000001 +231.19,50.30085681,-3.00807782,10370.4152,-5.78E-11,198.9978384,-20.001875,0,5.739898468,90.00000001 +231.2,50.30085681,-3.008049935,10370.6152,-1.02E-10,198.9967296,-20.003125,0,5.739898468,90.00000001 +231.21,50.30085681,-3.00802205,10370.8153,-1.09E-10,198.9960668,-20.003125,0,5.739898468,90.00000001 +231.22,50.30085681,-3.007994165,10371.0153,-7.19E-11,198.996742,-20.001875,0,5.739898468,90.00000001 +231.23,50.30085681,-3.00796628,10371.2153,-6.41E-11,198.9978633,-20.001875,0,5.739898468,90.00000001 +231.24,50.30085681,-3.007938394,10371.4153,-9.53E-11,198.9978695,-20.003125,0,5.739898468,90.00000001 +231.25,50.30085681,-3.007910509,10371.6154,-9.38E-11,198.9969837,-20.003125,0,5.739898468,90.00000001 +231.26,50.30085681,-3.007882624,10371.8154,-5.63E-11,198.9969899,-20.001875,0,5.739898468,90.00000001 +231.27,50.30085681,-3.007854739,10372.0154,-5.63E-11,198.9978881,-20.001875,0,5.739898468,90.00000001 +231.28,50.30085681,-3.007826853,10372.2154,-9.22E-11,198.9978944,-20.003125,0,5.739898468,90.00000001 +231.29,50.30085681,-3.007798968,10372.4155,-7.66E-11,198.9967855,-20.0034375,0,5.739898468,90.00000001 +231.3,50.30085681,-3.007771083,10372.6155,1.56E-11,198.9961227,-20.003125,0,5.739898468,90.00000001 +231.31,50.30085681,-3.007743198,10372.8155,1.00E-10,198.996798,-20.0034375,0,5.739898468,90.00000001 +231.32,50.30085681,-3.007715313,10373.0156,1.02E-10,198.9979192,-20.003125,0,5.739898468,90.00000001 +231.33,50.30085681,-3.007687427,10373.2156,5.78E-11,198.9979255,-20.001875,0,5.739898468,90.00000001 +231.34,50.30085681,-3.007659542,10373.4156,5.63E-11,198.9970396,-20.001875,0,5.739898468,90.00000001 +231.35,50.30085681,-3.007631657,10373.6156,9.38E-11,198.9970459,-20.003125,0,5.739898468,90.00000001 +231.36,50.30085681,-3.007603772,10373.8157,9.37E-11,198.9979441,-20.003125,0,5.739898468,90.00000001 +231.37,50.30085681,-3.007575886,10374.0157,5.47E-11,198.9979503,-20.001875,0,5.739898468,90.00000001 +231.38,50.30085681,-3.007548001,10374.2157,4.84E-11,198.9968415,-20.001875,0,5.739898468,90.00000001 +231.39,50.30085681,-3.007520116,10374.4157,7.81E-11,198.9961787,-20.003125,0,5.739898468,90.00000001 +231.4,50.30085681,-3.007492231,10374.6158,7.81E-11,198.9968539,-20.003125,0,5.739898468,90.00000001 +231.41,50.30085681,-3.007464346,10374.8158,4.84E-11,198.9979752,-20.001875,0,5.739898468,90.00000001 +231.42,50.30085681,-3.00743646,10375.0158,5.47E-11,198.9979814,-20.001875,0,5.739898468,90.00000001 +231.43,50.30085681,-3.007408575,10375.2158,9.38E-11,198.9970956,-20.003125,0,5.739898468,90.00000001 +231.44,50.30085681,-3.00738069,10375.4159,9.38E-11,198.9968788,-20.003125,0,5.739898468,90.00000001 +231.45,50.30085681,-3.007352805,10375.6159,5.63E-11,198.997108,-20.001875,0,5.739898468,90.00000001 +231.46,50.30085681,-3.007324919,10375.8159,5.63E-11,198.9968912,-20.001875,0,5.739898468,90.00000001 +231.47,50.30085681,-3.007297035,10376.0159,9.22E-11,198.9968975,-20.003125,0,5.739898468,90.00000001 +231.48,50.30085681,-3.007269149,10376.216,8.59E-11,198.9971267,-20.003125,0,5.739898468,90.00000001 +231.49,50.30085681,-3.007241264,10376.416,4.06E-11,198.9969099,-20.001875,0,5.739898468,90.00000001 +231.5,50.30085681,-3.007213379,10376.616,4.06E-11,198.9971391,-20.001875,0,5.739898468,90.00000001 +231.51,50.30085681,-3.007185494,10376.816,8.59E-11,198.9980374,-20.003125,0,5.739898468,90.00000001 +231.52,50.30085681,-3.007157608,10377.0161,9.22E-11,198.9980436,-20.003125,0,5.739898468,90.00000001 +231.53,50.30085681,-3.007129723,10377.2161,5.63E-11,198.9969348,-20.001875,0,5.739898468,90.00000001 +231.54,50.30085681,-3.007101838,10377.4161,5.63E-11,198.996272,-20.001875,0,5.739898468,90.00000001 +231.55,50.30085681,-3.007073953,10377.6161,9.38E-11,198.9969472,-20.003125,0,5.739898468,90.00000001 +231.56,50.30085681,-3.007046068,10377.8162,9.53E-11,198.9980685,-20.003125,0,5.739898468,90.00000001 +231.57,50.30085681,-3.007018182,10378.0162,6.41E-11,198.9980747,-20.001875,0,5.739898468,90.00000001 +231.58,50.30085681,-3.006990297,10378.2162,7.19E-11,198.9969659,-20.001875,0,5.739898468,90.00000001 +231.59,50.30085681,-3.006962412,10378.4162,1.09E-10,198.99608,-20.003125,0,5.739898468,90.00000001 +231.6,50.30085681,-3.006934527,10378.6163,1.02E-10,198.9960863,-20.003125,0,5.739898468,90.00000001 +231.61,50.30085681,-3.006906642,10378.8163,5.78E-11,198.9969845,-20.001875,0,5.739898468,90.00000001 +231.62,50.30085681,-3.006878757,10379.0163,5.62E-11,198.9981058,-20.001875,0,5.739898468,90.00000001 +231.63,50.30085681,-3.006850871,10379.2163,9.37E-11,198.998112,-20.003125,0,5.739898468,90.00000001 +231.64,50.30085681,-3.006822986,10379.4164,9.38E-11,198.9970032,-20.003125,0,5.739898468,90.00000001 +231.65,50.30085681,-3.006795101,10379.6164,5.47E-11,198.9963404,-20.001875,0,5.739898468,90.00000001 +231.66,50.30085681,-3.006767216,10379.8164,4.84E-11,198.9970156,-20.001875,0,5.739898468,90.00000001 +231.67,50.30085681,-3.006739331,10380.0164,7.81E-11,198.9981369,-20.003125,0,5.739898468,90.00000001 +231.68,50.30085681,-3.006711445,10380.2165,7.81E-11,198.9981431,-20.003125,0,5.739898468,90.00000001 +231.69,50.30085681,-3.00668356,10380.4165,4.84E-11,198.9970343,-20.001875,0,5.739898468,90.00000001 +231.7,50.30085681,-3.006655675,10380.6165,5.47E-11,198.9961484,-20.001875,0,5.739898468,90.00000001 +231.71,50.30085681,-3.00662779,10380.8165,9.37E-11,198.9961547,-20.003125,0,5.739898468,90.00000001 +231.72,50.30085681,-3.006599905,10381.0166,9.37E-11,198.9970529,-20.003125,0,5.739898468,90.00000001 +231.73,50.30085681,-3.00657202,10381.2166,5.62E-11,198.9981742,-20.001875,0,5.739898468,90.00000001 +231.74,50.30085681,-3.006544134,10381.4166,5.62E-11,198.9984034,-20.001875,0,5.739898468,90.00000001 +231.75,50.30085681,-3.006516249,10381.6166,9.22E-11,198.9979636,-20.003125,0,5.739898468,90.00000001 +231.76,50.30085681,-3.006488364,10381.8167,8.59E-11,198.9975238,-20.003125,0,5.739898468,90.00000001 +231.77,50.30085681,-3.006460478,10382.0167,4.06E-11,198.997084,-20.001875,0,5.739898468,90.00000001 +231.78,50.30085681,-3.006432594,10382.2167,4.06E-11,198.9970902,-20.001875,0,5.739898468,90.00000001 +231.79,50.30085681,-3.006404708,10382.4167,8.59E-11,198.9973195,-20.003125,0,5.739898468,90.00000001 +231.8,50.30085681,-3.006376823,10382.6168,9.22E-11,198.9968797,-20.003125,0,5.739898468,90.00000001 +231.81,50.30085681,-3.006348938,10382.8168,5.62E-11,198.9962168,-20.001875,0,5.739898468,90.00000001 +231.82,50.30085681,-3.006321053,10383.0168,5.62E-11,198.9962231,-20.001875,0,5.739898468,90.00000001 +231.83,50.30085681,-3.006293168,10383.2168,9.37E-11,198.9971213,-20.003125,0,5.739898468,90.00000001 +231.84,50.30085681,-3.006265283,10383.4169,9.53E-11,198.9982426,-20.003125,0,5.739898468,90.00000001 +231.85,50.30085681,-3.006237397,10383.6169,6.41E-11,198.9982488,-20.001875,0,5.739898468,90.00000001 +231.86,50.30085681,-3.006209512,10383.8169,7.19E-11,198.99714,-20.001875,0,5.739898468,90.00000001 +231.87,50.30085681,-3.006181627,10384.0169,1.09E-10,198.9964772,-20.003125,0,5.739898468,90.00000001 +231.88,50.30085681,-3.006153742,10384.217,1.02E-10,198.9971524,-20.003125,0,5.739898468,90.00000001 +231.89,50.30085681,-3.006125857,10384.417,5.78E-11,198.9982737,-20.001875,0,5.739898468,90.00000001 +231.9,50.30085681,-3.006097971,10384.617,5.63E-11,198.9982799,-20.001875,0,5.739898468,90.00000001 +231.91,50.30085681,-3.006070086,10384.817,9.38E-11,198.9971711,-20.003125,0,5.739898468,90.00000001 +231.92,50.30085681,-3.006042201,10385.0171,9.37E-11,198.9962852,-20.003125,0,5.739898468,90.00000001 +231.93,50.30085681,-3.006014316,10385.2171,5.47E-11,198.9962915,-20.001875,0,5.739898468,90.00000001 +231.94,50.30085681,-3.005986431,10385.4171,4.84E-11,198.9971897,-20.001875,0,5.739898468,90.00000001 +231.95,50.30085681,-3.005958546,10385.6171,7.81E-11,198.998311,-20.003125,0,5.739898468,90.00000001 +231.96,50.30085681,-3.00593066,10385.8172,7.81E-11,198.9983172,-20.003125,0,5.739898468,90.00000001 +231.97,50.30085681,-3.005902775,10386.0172,4.84E-11,198.9972084,-20.001875,0,5.739898468,90.00000001 +231.98,50.30085681,-3.00587489,10386.2172,5.47E-11,198.9963226,-20.001875,0,5.739898468,90.00000001 +231.99,50.30085681,-3.005847005,10386.4172,9.37E-11,198.9961058,-20.003125,0,5.739898468,90.00000001 +232,50.30085681,-3.00581912,10386.6173,9.38E-11,198.996112,-20.003125,0,5.739898468,90.00000001 +232.01,50.30085681,-3.005791235,10386.8173,5.63E-11,198.9963412,-20.001875,0,5.739898468,90.00000001 +232.02,50.30085681,-3.00576335,10387.0173,5.63E-11,198.9972395,-20.001875,0,5.739898468,90.00000001 +232.03,50.30085681,-3.005735465,10387.2173,9.22E-11,198.9983607,-20.003125,0,5.739898468,90.00000001 +232.04,50.30085681,-3.005707579,10387.4174,8.59E-11,198.998367,-20.003125,0,5.739898468,90.00000001 +232.05,50.30085681,-3.005679694,10387.6174,4.06E-11,198.9972581,-20.001875,0,5.739898468,90.00000001 +232.06,50.30085681,-3.005651809,10387.8174,4.06E-11,198.9965953,-20.001875,0,5.739898468,90.00000001 +232.07,50.30085681,-3.005623924,10388.0174,8.59E-11,198.9972706,-20.003125,0,5.739898468,90.00000001 +232.08,50.30085681,-3.005596039,10388.2175,9.22E-11,198.9983918,-20.003125,0,5.739898468,90.00000001 +232.09,50.30085681,-3.005568153,10388.4175,5.62E-11,198.998398,-20.001875,0,5.739898468,90.00000001 +232.1,50.30085681,-3.005540268,10388.6175,5.62E-11,198.9972892,-20.001875,0,5.739898468,90.00000001 +232.11,50.30085681,-3.005512383,10388.8175,9.37E-11,198.9964034,-20.003125,0,5.739898468,90.00000001 +232.12,50.30085681,-3.005484498,10389.0176,9.53E-11,198.9961866,-20.003125,0,5.739898468,90.00000001 +232.13,50.30085681,-3.005456613,10389.2176,6.41E-11,198.9961928,-20.001875,0,5.739898468,90.00000001 +232.14,50.30085681,-3.005428728,10389.4176,7.19E-11,198.9964221,-20.001875,0,5.739898468,90.00000001 +232.15,50.30085681,-3.005400843,10389.6176,1.09E-10,198.9973203,-20.003125,0,5.739898468,90.00000001 +232.16,50.30085681,-3.005372958,10389.8177,9.22E-11,198.9984416,-20.0034375,0,5.739898468,90.00000001 +232.17,50.30085681,-3.005345072,10390.0177,1.56E-12,198.9984478,-20.003125,0,5.739898468,90.00000001 +232.18,50.30085681,-3.005317187,10390.2177,-8.44E-11,198.997339,-20.0034375,0,5.739898468,90.00000001 +232.19,50.30085681,-3.005289302,10390.4178,-9.38E-11,198.9966762,-20.003125,0,5.739898468,90.00000001 +232.2,50.30085681,-3.005261417,10390.6178,-5.63E-11,198.9971284,-20.001875,0,5.739898468,90.00000001 +232.21,50.30085681,-3.005233532,10390.8178,-5.63E-11,198.9975806,-20.001875,0,5.739898468,90.00000001 +232.22,50.30085681,-3.005205646,10391.0178,-9.22E-11,198.9973638,-20.003125,0,5.739898468,90.00000001 +232.23,50.30085681,-3.005177762,10391.2179,-8.59E-11,198.9973701,-20.003125,0,5.739898468,90.00000001 +232.24,50.30085681,-3.005149876,10391.4179,-4.06E-11,198.9975993,-20.001875,0,5.739898468,90.00000001 +232.25,50.30085681,-3.005121991,10391.6179,-4.06E-11,198.9971595,-20.001875,0,5.739898468,90.00000001 +232.26,50.30085681,-3.005094106,10391.8179,-8.59E-11,198.9964967,-20.003125,0,5.739898468,90.00000001 +232.27,50.30085681,-3.005066221,10392.018,-9.22E-11,198.9965029,-20.003125,0,5.739898468,90.00000001 +232.28,50.30085681,-3.005038336,10392.218,-5.63E-11,198.9971781,-20.001875,0,5.739898468,90.00000001 +232.29,50.30085681,-3.005010451,10392.418,-5.63E-11,198.9976304,-20.001875,0,5.739898468,90.00000001 +232.3,50.30085681,-3.004982565,10392.618,-9.38E-11,198.9974136,-20.003125,0,5.739898468,90.00000001 +232.31,50.30085681,-3.004954681,10392.8181,-9.53E-11,198.9974198,-20.003125,0,5.739898468,90.00000001 +232.32,50.30085681,-3.004926795,10393.0181,-6.41E-11,198.997649,-20.001875,0,5.739898468,90.00000001 +232.33,50.30085681,-3.00489891,10393.2181,-7.19E-11,198.9972092,-20.001875,0,5.739898468,90.00000001 +232.34,50.30085681,-3.004871025,10393.4181,-1.09E-10,198.9967694,-20.003125,0,5.739898468,90.00000001 +232.35,50.30085681,-3.00484314,10393.6182,-1.02E-10,198.9972217,-20.003125,0,5.739898468,90.00000001 +232.36,50.30085681,-3.004815255,10393.8182,-5.78E-11,198.9974509,-20.001875,0,5.739898468,90.00000001 +232.37,50.30085681,-3.004787369,10394.0182,-5.62E-11,198.9965651,-20.001875,0,5.739898468,90.00000001 +232.38,50.30085681,-3.004759485,10394.2182,-9.37E-11,198.9963483,-20.003125,0,5.739898468,90.00000001 +232.39,50.30085681,-3.0047316,10394.4183,-9.38E-11,198.9976926,-20.003125,0,5.739898468,90.00000001 +232.4,50.30085681,-3.004703714,10394.6183,-5.47E-11,198.9983678,-20.001875,0,5.739898468,90.00000001 +232.41,50.30085681,-3.004675829,10394.8183,-4.84E-11,198.997482,-20.001875,0,5.739898468,90.00000001 +232.42,50.30085681,-3.004647944,10395.0183,-7.81E-11,198.9965962,-20.003125,0,5.739898468,90.00000001 +232.43,50.30085681,-3.004620059,10395.2184,-7.81E-11,198.9963794,-20.003125,0,5.739898468,90.00000001 +232.44,50.30085681,-3.004592174,10395.4184,-4.84E-11,198.9966086,-20.001875,0,5.739898468,90.00000001 +232.45,50.30085681,-3.004564289,10395.6184,-5.47E-11,198.9975069,-20.001875,0,5.739898468,90.00000001 +232.46,50.30085681,-3.004536404,10395.8184,-9.37E-11,198.9986281,-20.003125,0,5.739898468,90.00000001 +232.47,50.30085681,-3.004508518,10396.0185,-9.37E-11,198.9986343,-20.003125,0,5.739898468,90.00000001 +232.48,50.30085681,-3.004480633,10396.2185,-5.62E-11,198.9975255,-20.001875,0,5.739898468,90.00000001 +232.49,50.30085681,-3.004452748,10396.4185,-5.62E-11,198.9966397,-20.001875,0,5.739898468,90.00000001 +232.5,50.30085681,-3.004424863,10396.6185,-9.22E-11,198.9964229,-20.003125,0,5.739898468,90.00000001 +232.51,50.30085681,-3.004396978,10396.8186,-8.59E-11,198.9964291,-20.003125,0,5.739898468,90.00000001 +232.52,50.30085681,-3.004369093,10397.0186,-4.06E-11,198.9966583,-20.001875,0,5.739898468,90.00000001 +232.53,50.30085681,-3.004341208,10397.2186,-4.06E-11,198.9973336,-20.001875,0,5.739898468,90.00000001 +232.54,50.30085681,-3.004313323,10397.4186,-8.59E-11,198.9977858,-20.003125,0,5.739898468,90.00000001 +232.55,50.30085681,-3.004285437,10397.6187,-9.22E-11,198.997569,-20.003125,0,5.739898468,90.00000001 +232.56,50.30085681,-3.004257553,10397.8187,-5.62E-11,198.9975753,-20.001875,0,5.739898468,90.00000001 +232.57,50.30085681,-3.004229667,10398.0187,-5.62E-11,198.9978045,-20.001875,0,5.739898468,90.00000001 +232.58,50.30085681,-3.004201782,10398.2187,-9.37E-11,198.9973647,-20.003125,0,5.739898468,90.00000001 +232.59,50.30085681,-3.004173897,10398.4188,-9.53E-11,198.9967019,-20.003125,0,5.739898468,90.00000001 +232.6,50.30085681,-3.004146012,10398.6188,-6.41E-11,198.9964851,-20.001875,0,5.739898468,90.00000001 +232.61,50.30085681,-3.004118127,10398.8188,-7.19E-11,198.9967143,-20.001875,0,5.739898468,90.00000001 +232.62,50.30085681,-3.004090242,10399.0188,-1.09E-10,198.9973896,-20.003125,0,5.739898468,90.00000001 +232.63,50.30085681,-3.004062357,10399.2189,-1.02E-10,198.9978418,-20.003125,0,5.739898468,90.00000001 +232.64,50.30085681,-3.004034471,10399.4189,-5.78E-11,198.997625,-20.001875,0,5.739898468,90.00000001 +232.65,50.30085681,-3.004006587,10399.6189,-5.63E-11,198.9976312,-20.001875,0,5.739898468,90.00000001 +232.66,50.30085681,-3.003978701,10399.8189,-9.38E-11,198.9978605,-20.003125,0,5.739898468,90.00000001 +232.67,50.30085681,-3.003950816,10400.019,-9.37E-11,198.9974206,-20.003125,0,5.739898468,90.00000001 +232.68,50.30085681,-3.003922931,10400.219,-5.47E-11,198.9967578,-20.001875,0,5.739898468,90.00000001 +232.69,50.30085681,-3.003895046,10400.419,-4.84E-11,198.996541,-20.001875,0,5.739898468,90.00000001 +232.7,50.30085681,-3.003867161,10400.619,-7.81E-11,198.9965473,-20.003125,0,5.739898468,90.00000001 +232.71,50.30085681,-3.003839276,10400.8191,-7.81E-11,198.9965535,-20.003125,0,5.739898468,90.00000001 +232.72,50.30085681,-3.003811391,10401.0191,-4.84E-11,198.9965597,-20.001875,0,5.739898468,90.00000001 +232.73,50.30085681,-3.003783506,10401.2191,-5.47E-11,198.9967889,-20.001875,0,5.739898468,90.00000001 +232.74,50.30085681,-3.003755621,10401.4191,-9.37E-11,198.9974642,-20.003125,0,5.739898468,90.00000001 +232.75,50.30085681,-3.003727736,10401.6192,-9.38E-11,198.9979164,-20.003125,0,5.739898468,90.00000001 +232.76,50.30085681,-3.00369985,10401.8192,-5.63E-11,198.9976996,-20.001875,0,5.739898468,90.00000001 +232.77,50.30085681,-3.003671966,10402.0192,-5.63E-11,198.9977058,-20.001875,0,5.739898468,90.00000001 +232.78,50.30085681,-3.00364408,10402.2192,-9.22E-11,198.9979351,-20.003125,0,5.739898468,90.00000001 +232.79,50.30085681,-3.003616195,10402.4193,-8.59E-11,198.9974953,-20.003125,0,5.739898468,90.00000001 +232.8,50.30085681,-3.00358831,10402.6193,-4.06E-11,198.9968325,-20.001875,0,5.739898468,90.00000001 +232.81,50.30085681,-3.003560425,10402.8193,-4.06E-11,198.9966157,-20.001875,0,5.739898468,90.00000001 +232.82,50.30085681,-3.00353254,10403.0193,-8.59E-11,198.9966219,-20.003125,0,5.739898468,90.00000001 +232.83,50.30085681,-3.003504655,10403.2194,-9.22E-11,198.9966281,-20.003125,0,5.739898468,90.00000001 +232.84,50.30085681,-3.00347677,10403.4194,-5.62E-11,198.9966343,-20.001875,0,5.739898468,90.00000001 +232.85,50.30085681,-3.003448885,10403.6194,-5.62E-11,198.9968635,-20.001875,0,5.739898468,90.00000001 +232.86,50.30085681,-3.003421,10403.8194,-9.37E-11,198.9975388,-20.003125,0,5.739898468,90.00000001 +232.87,50.30085681,-3.003393115,10404.0195,-9.53E-11,198.997991,-20.003125,0,5.739898468,90.00000001 +232.88,50.30085681,-3.003365229,10404.2195,-6.41E-11,198.9977742,-20.001875,0,5.739898468,90.00000001 +232.89,50.30085681,-3.003337345,10404.4195,-7.19E-11,198.9977805,-20.001875,0,5.739898468,90.00000001 +232.9,50.30085681,-3.003309459,10404.6195,-1.09E-10,198.9980097,-20.003125,0,5.739898468,90.00000001 +232.91,50.30085681,-3.003281574,10404.8196,-1.02E-10,198.9975699,-20.003125,0,5.739898468,90.00000001 +232.92,50.30085681,-3.003253689,10405.0196,-5.78E-11,198.9969071,-20.001875,0,5.739898468,90.00000001 +232.93,50.30085681,-3.003225804,10405.2196,-5.62E-11,198.9966903,-20.001875,0,5.739898468,90.00000001 +232.94,50.30085681,-3.003197919,10405.4196,-9.37E-11,198.9966965,-20.003125,0,5.739898468,90.00000001 +232.95,50.30085681,-3.003170034,10405.6197,-9.37E-11,198.9967027,-20.003125,0,5.739898468,90.00000001 +232.96,50.30085681,-3.003142149,10405.8197,-5.47E-11,198.9969319,-20.001875,0,5.739898468,90.00000001 +232.97,50.30085681,-3.003114264,10406.0197,-4.84E-11,198.9976072,-20.001875,0,5.739898468,90.00000001 +232.98,50.30085681,-3.003086379,10406.2197,-7.81E-11,198.9980594,-20.003125,0,5.739898468,90.00000001 +232.99,50.30085681,-3.003058493,10406.4198,-7.81E-11,198.9978426,-20.003125,0,5.739898468,90.00000001 +233,50.30085681,-3.003030609,10406.6198,-4.84E-11,198.9978489,-20.001875,0,5.739898468,90.00000001 +233.01,50.30085681,-3.003002723,10406.8198,-5.47E-11,198.9980781,-20.001875,0,5.739898468,90.00000001 +233.02,50.30085681,-3.002974838,10407.0198,-9.38E-11,198.9976383,-20.003125,0,5.739898468,90.00000001 +233.03,50.30085681,-3.002946953,10407.2199,-8.44E-11,198.9969755,-20.0034375,0,5.739898468,90.00000001 +233.04,50.30085681,-3.002919068,10407.4199,1.11E-15,198.9967587,-20.003125,0,5.739898468,90.00000001 +233.05,50.30085681,-3.002891183,10407.6199,8.44E-11,198.9967649,-20.0034375,0,5.739898468,90.00000001 +233.06,50.30085681,-3.002863298,10407.82,9.53E-11,198.9967711,-20.003125,0,5.739898468,90.00000001 +233.07,50.30085681,-3.002835413,10408.02,6.41E-11,198.9967773,-20.001875,0,5.739898468,90.00000001 +233.08,50.30085681,-3.002807528,10408.22,7.19E-11,198.9967836,-20.001875,0,5.739898468,90.00000001 +233.09,50.30085681,-3.002779643,10408.42,1.09E-10,198.9967898,-20.003125,0,5.739898468,90.00000001 +233.1,50.30085681,-3.002751758,10408.6201,1.02E-10,198.996796,-20.003125,0,5.739898468,90.00000001 +233.11,50.30085681,-3.002723873,10408.8201,5.78E-11,198.9968022,-20.001875,0,5.739898468,90.00000001 +233.12,50.30085681,-3.002695988,10409.0201,5.62E-11,198.9970314,-20.001875,0,5.739898468,90.00000001 +233.13,50.30085681,-3.002668103,10409.2201,9.37E-11,198.9977067,-20.003125,0,5.739898468,90.00000001 +233.14,50.30085681,-3.002640218,10409.4202,9.38E-11,198.9981589,-20.003125,0,5.739898468,90.00000001 +233.15,50.30085681,-3.002612332,10409.6202,5.47E-11,198.9977191,-20.001875,0,5.739898468,90.00000001 +233.16,50.30085681,-3.002584448,10409.8202,4.84E-11,198.9970563,-20.001875,0,5.739898468,90.00000001 +233.17,50.30085681,-3.002556562,10410.0202,7.81E-11,198.9970625,-20.003125,0,5.739898468,90.00000001 +233.18,50.30085681,-3.002528678,10410.2203,7.81E-11,198.9977378,-20.003125,0,5.739898468,90.00000001 +233.19,50.30085681,-3.002500792,10410.4203,4.84E-11,198.99819,-20.001875,0,5.739898468,90.00000001 +233.2,50.30085681,-3.002472907,10410.6203,5.47E-11,198.9977502,-20.001875,0,5.739898468,90.00000001 +233.21,50.30085681,-3.002445022,10410.8203,9.37E-11,198.9970874,-20.003125,0,5.739898468,90.00000001 +233.22,50.30085681,-3.002417137,10411.0204,9.37E-11,198.9968706,-20.003125,0,5.739898468,90.00000001 +233.23,50.30085681,-3.002389252,10411.2204,5.62E-11,198.9968768,-20.001875,0,5.739898468,90.00000001 +233.24,50.30085681,-3.002361367,10411.4204,5.78E-11,198.996883,-20.001875,0,5.739898468,90.00000001 +233.25,50.30085681,-3.002333482,10411.6204,1.02E-10,198.9968893,-20.003125,0,5.739898468,90.00000001 +233.26,50.30085681,-3.002305597,10411.8205,1.09E-10,198.9968955,-20.003125,0,5.739898468,90.00000001 +233.27,50.30085681,-3.002277712,10412.0205,7.19E-11,198.9969017,-20.001875,0,5.739898468,90.00000001 +233.28,50.30085681,-3.002249827,10412.2205,6.41E-11,198.9969079,-20.001875,0,5.739898468,90.00000001 +233.29,50.30085681,-3.002221942,10412.4205,9.53E-11,198.9969141,-20.003125,0,5.739898468,90.00000001 +233.3,50.30085681,-3.002194057,10412.6206,9.37E-11,198.9969204,-20.003125,0,5.739898468,90.00000001 +233.31,50.30085681,-3.002166172,10412.8206,5.62E-11,198.9969266,-20.001875,0,5.739898468,90.00000001 +233.32,50.30085681,-3.002138287,10413.0206,5.62E-11,198.9969328,-20.001875,0,5.739898468,90.00000001 +233.33,50.30085681,-3.002110402,10413.2206,9.37E-11,198.996939,-20.003125,0,5.739898468,90.00000001 +233.34,50.30085681,-3.002082517,10413.4207,9.53E-11,198.9971682,-20.003125,0,5.739898468,90.00000001 +233.35,50.30085681,-3.002054632,10413.6207,6.41E-11,198.9978435,-20.001875,0,5.739898468,90.00000001 +233.36,50.30085681,-3.002026747,10413.8207,7.19E-11,198.9982957,-20.001875,0,5.739898468,90.00000001 +233.37,50.30085681,-3.001998861,10414.0207,1.09E-10,198.9978559,-20.003125,0,5.739898468,90.00000001 +233.38,50.30085681,-3.001970977,10414.2208,1.02E-10,198.9971931,-20.003125,0,5.739898468,90.00000001 +233.39,50.30085681,-3.001943091,10414.4208,5.78E-11,198.9969763,-20.001875,0,5.739898468,90.00000001 +233.4,50.30085681,-3.001915207,10414.6208,5.63E-11,198.9969825,-20.001875,0,5.739898468,90.00000001 +233.41,50.30085681,-3.001887321,10414.8208,9.38E-11,198.9972118,-20.003125,0,5.739898468,90.00000001 +233.42,50.30085681,-3.001859437,10415.0209,9.37E-11,198.997887,-20.003125,0,5.739898468,90.00000001 +233.43,50.30085681,-3.001831551,10415.2209,5.47E-11,198.9983393,-20.001875,0,5.739898468,90.00000001 +233.44,50.30085681,-3.001803666,10415.4209,4.84E-11,198.9978995,-20.001875,0,5.739898468,90.00000001 +233.45,50.30085681,-3.001775781,10415.6209,7.81E-11,198.9972366,-20.003125,0,5.739898468,90.00000001 +233.46,50.30085681,-3.001747896,10415.821,7.81E-11,198.9970198,-20.003125,0,5.739898468,90.00000001 +233.47,50.30085681,-3.001720011,10416.021,4.84E-11,198.9970261,-20.001875,0,5.739898468,90.00000001 +233.48,50.30085681,-3.001692126,10416.221,5.47E-11,198.9970323,-20.001875,0,5.739898468,90.00000001 +233.49,50.30085681,-3.001664241,10416.421,9.38E-11,198.9970385,-20.003125,0,5.739898468,90.00000001 +233.5,50.30085681,-3.001636356,10416.6211,9.38E-11,198.9970447,-20.003125,0,5.739898468,90.00000001 +233.51,50.30085681,-3.001608471,10416.8211,5.63E-11,198.9970509,-20.001875,0,5.739898468,90.00000001 +233.52,50.30085681,-3.001580586,10417.0211,5.78E-11,198.9970572,-20.001875,0,5.739898468,90.00000001 +233.53,50.30085681,-3.001552701,10417.2211,1.02E-10,198.9970634,-20.003125,0,5.739898468,90.00000001 +233.54,50.30085681,-3.001524816,10417.4212,1.09E-10,198.9970696,-20.003125,0,5.739898468,90.00000001 +233.55,50.30085681,-3.001496931,10417.6212,7.19E-11,198.9970758,-20.001875,0,5.739898468,90.00000001 +233.56,50.30085681,-3.001469046,10417.8212,8.28E-11,198.997082,-20.00125,0,5.739898468,90.00000001 +233.57,50.30085681,-3.001441161,10418.0212,1.61E-10,198.9973113,-19.9990625,0,5.739898468,90.00000001 +233.58,50.30085681,-3.001413276,10418.2213,1.98E-10,198.9984325,-19.9903125,0,5.738727572,90.00000001 +233.59,50.30085681,-3.001385391,10418.4211,1.67E-10,199.0006689,-19.9740625,0,5.732872917,90.00000001 +233.6,50.30085681,-3.001357505,10418.6208,1.30E-10,199.0029052,-19.953125,0,5.725847309,90.00000001 +233.61,50.30085681,-3.001329619,10418.8202,1.08E-10,199.0042494,-19.9296875,0,5.718821757,90.00000001 +233.62,50.30085681,-3.001301733,10419.0194,1.00E-10,199.0058167,-19.905,0,5.711796149,90.00000001 +233.63,50.30085681,-3.001273847,10419.2183,9.84E-11,199.008945,-19.88,0,5.704770598,90.00000001 +233.64,50.30085681,-3.00124596,10419.417,8.28E-11,199.0125194,-19.8553125,0,5.697744989,90.00000001 +233.65,50.30085681,-3.001218072,10419.6154,3.59E-11,199.0147557,-19.8315625,0,5.690719438,90.00000001 +233.66,50.30085681,-3.001190185,10419.8136,-2.66E-11,199.0163229,-19.8084375,0,5.683693829,90.00000001 +233.67,50.30085681,-3.001162297,10420.0116,-6.56E-11,199.0187822,-19.7846875,0,5.676668278,90.00000001 +233.68,50.30085681,-3.001134409,10420.2093,-7.50E-11,199.0219105,-19.76,0,5.66964267,90.00000001 +233.69,50.30085681,-3.00110652,10420.4068,-7.66E-11,199.0245928,-19.735,0,5.662617119,90.00000001 +233.7,50.30085681,-3.001078631,10420.604,-8.28E-11,199.026829,-19.71,0,5.65559151,90.00000001 +233.71,50.30085681,-3.001050742,10420.801,-9.22E-11,199.0292882,-19.685,0,5.648565959,90.00000001 +233.72,50.30085681,-3.001022852,10420.9977,-9.84E-11,199.0315245,-19.66,0,5.64154035,90.00000001 +233.73,50.30085681,-3.000994962,10421.1942,-9.06E-11,199.0328686,-19.6353125,0,5.634514799,90.00000001 +233.74,50.30085681,-3.000967072,10421.3904,-5.16E-11,199.0344358,-19.6115625,0,5.627489248,90.00000001 +233.75,50.30085681,-3.000939182,10421.5864,1.56E-12,199.0377871,-19.588125,0,5.62046364,90.00000001 +233.76,50.30085681,-3.000911291,10421.7822,1.56E-12,199.0420304,-19.5634375,0,5.613438088,90.00000001 +233.77,50.30085681,-3.000883399,10421.9777,-7.66E-11,199.0447126,-19.538125,0,5.60641248,90.00000001 +233.78,50.30085681,-3.000855507,10422.1729,-1.69E-10,199.0458337,-19.51375,0,5.599386929,90.00000001 +233.79,50.30085681,-3.000827616,10422.368,-2.08E-10,199.0474009,-19.49,0,5.59236132,90.00000001 +233.8,50.30085681,-3.000799723,10422.5627,-1.77E-10,199.04986,-19.46625,0,5.585335769,90.00000001 +233.81,50.30085681,-3.000771831,10422.7573,-9.22E-11,199.0527652,-19.441875,0,5.578310161,90.00000001 +233.82,50.30085681,-3.000743938,10422.9516,-1.41E-11,199.0556704,-19.4165625,0,5.571284609,90.00000001 +233.83,50.30085681,-3.000716044,10423.1456,-6.25E-12,199.0576836,-19.391875,0,5.564259001,90.00000001 +233.84,50.30085681,-3.000688151,10423.3394,-5.16E-11,199.0592507,-19.3684375,0,5.55723345,90.00000001 +233.85,50.30085681,-3.000660257,10423.533,-8.28E-11,199.0617098,-19.3446875,0,5.550207841,90.00000001 +233.86,50.30085681,-3.000632363,10423.7263,-8.28E-11,199.064838,-19.32,0,5.54318229,90.00000001 +233.87,50.30085681,-3.000604468,10423.9194,-7.66E-11,199.0675201,-19.295,0,5.536156682,90.00000001 +233.88,50.30085681,-3.000576573,10424.1122,-7.50E-11,199.0697562,-19.27,0,5.52913113,90.00000001 +233.89,50.30085681,-3.000548678,10424.3048,-7.50E-11,199.0722153,-19.245,0,5.522105522,90.00000001 +233.9,50.30085681,-3.000520782,10424.4971,-8.28E-11,199.0746744,-19.2203125,0,5.515079971,90.00000001 +233.91,50.30085681,-3.000492886,10424.6892,-1.14E-10,199.0769105,-19.1965625,0,5.508054362,90.00000001 +233.92,50.30085681,-3.00046499,10424.881,-1.52E-10,199.0793696,-19.173125,0,5.501028811,90.00000001 +233.93,50.30085681,-3.000437093,10425.0727,-1.38E-10,199.0816057,-19.1484375,0,5.494003203,90.00000001 +233.94,50.30085681,-3.000409196,10425.264,-5.94E-11,199.0829497,-19.123125,0,5.486977651,90.00000001 +233.95,50.30085681,-3.000381299,10425.4551,1.87E-11,199.0845167,-19.09875,0,5.479952043,90.00000001 +233.96,50.30085681,-3.000353402,10425.646,4.22E-11,199.0876448,-19.075,0,5.472926492,90.00000001 +233.97,50.30085681,-3.000325504,10425.8366,1.25E-11,199.0912189,-19.0515625,0,5.465900883,90.00000001 +233.98,50.30085681,-3.000297605,10426.027,-2.66E-11,199.0934549,-19.028125,0,5.458875332,90.00000001 +233.99,50.30085681,-3.000269707,10426.2172,-2.19E-11,199.0950219,-19.003125,0,5.451849724,90.00000001 +234,50.30085681,-3.000241808,10426.4071,1.09E-11,199.097481,-18.976875,0,5.444824172,90.00000001 +234.01,50.30085681,-3.000213909,10426.5967,3.13E-12,199.100609,-18.951875,0,5.437798564,90.00000001 +234.02,50.30085681,-3.000186009,10426.7861,-4.22E-11,199.103291,-18.9284375,0,5.430773013,90.00000001 +234.03,50.30085681,-3.000158109,10426.9753,-6.56E-11,199.105304,-18.9046875,0,5.423747404,90.00000001 +234.04,50.30085681,-3.000130209,10427.1642,-5.94E-11,199.107094,-18.88,0,5.416721853,90.00000001 +234.05,50.30085681,-3.000102308,10427.3529,-5.31E-11,199.109107,-18.855,0,5.409696245,90.00000001 +234.06,50.30085681,-3.000074408,10427.5413,-5.78E-11,199.111566,-18.83,0,5.402670693,90.00000001 +234.07,50.30085681,-3.000046506,10427.7295,-5.78E-11,199.1140249,-18.8053125,0,5.395645085,90.00000001 +234.08,50.30085681,-3.000018605,10427.9174,-2.66E-11,199.1160379,-18.7815625,0,5.388619534,90.00000001 +234.09,50.30085681,-2.999990703,10428.1051,2.81E-11,199.1178278,-18.7584375,0,5.381593925,90.00000001 +234.1,50.30085681,-2.999962801,10428.2926,6.56E-11,199.1198407,-18.7346875,0,5.374568374,90.00000001 +234.11,50.30085681,-2.999934899,10428.4798,7.34E-11,199.1222997,-18.71,0,5.367542766,90.00000001 +234.12,50.30085681,-2.999906996,10428.6668,6.72E-11,199.1247586,-18.685,0,5.360517214,90.00000001 +234.13,50.30085681,-2.999879093,10428.8535,5.78E-11,199.1269945,-18.66,0,5.353491606,90.00000001 +234.14,50.30085681,-2.99985119,10429.04,5.31E-11,199.1296765,-18.635,0,5.346466055,90.00000001 +234.15,50.30085681,-2.999823286,10429.2262,5.94E-11,199.1328044,-18.61,0,5.339440446,90.00000001 +234.16,50.30085681,-2.999795382,10429.4122,6.56E-11,199.1352633,-18.5853125,0,5.332414895,90.00000001 +234.17,50.30085681,-2.999767477,10429.5979,4.22E-11,199.1368302,-18.5615625,0,5.325389287,90.00000001 +234.18,50.30085681,-2.999739573,10429.7834,-1.25E-11,199.1388431,-18.5384375,0,5.318363735,90.00000001 +234.19,50.30085681,-2.999711668,10429.9687,-5.78E-11,199.141525,-18.5146875,0,5.311338127,90.00000001 +234.2,50.30085681,-2.999683762,10430.1537,-7.19E-11,199.1435378,-18.49,0,5.304312576,90.00000001 +234.21,50.30085681,-2.999655857,10430.3385,-6.72E-11,199.1451047,-18.465,0,5.297286967,90.00000001 +234.22,50.30085681,-2.999627951,10430.523,-5.94E-11,199.1475635,-18.44,0,5.290261416,90.00000001 +234.23,50.30085681,-2.999600045,10430.7073,-5.16E-11,199.1506914,-18.4153125,0,5.283235807,90.00000001 +234.24,50.30085681,-2.999572138,10430.8913,-2.81E-11,199.1533733,-18.3915625,0,5.276210256,90.00000001 +234.25,50.30085681,-2.999544231,10431.0751,3.13E-12,199.1553861,-18.368125,0,5.269184648,90.00000001 +234.26,50.30085681,-2.999516324,10431.2587,-3.12E-12,199.1571759,-18.343125,0,5.262159097,90.00000001 +234.27,50.30085681,-2.999488416,10431.442,-3.59E-11,199.1591887,-18.316875,0,5.255133488,90.00000001 +234.28,50.30085681,-2.999460509,10431.625,-2.66E-11,199.1616475,-18.291875,0,5.248107937,90.00000001 +234.29,50.30085681,-2.9994326,10431.8078,2.66E-11,199.1641063,-18.2684375,0,5.241082328,90.00000001 +234.3,50.30085681,-2.999404692,10431.9904,5.62E-11,199.1661191,-18.245,0,5.234056777,90.00000001 +234.31,50.30085681,-2.999376783,10432.1727,2.81E-11,199.1679089,-18.2215625,0,5.227031169,90.00000001 +234.32,50.30085681,-2.999348874,10432.3548,-1.72E-11,199.1699217,-18.198125,0,5.220005618,90.00000001 +234.33,50.30085681,-2.999320965,10432.5367,-1.09E-11,199.1726034,-18.173125,0,5.212980009,90.00000001 +234.34,50.30085681,-2.999293055,10432.7183,3.59E-11,199.1757313,-18.146875,0,5.205954458,90.00000001 +234.35,50.30085681,-2.999265145,10432.8996,4.06E-11,199.17819,-18.121875,0,5.198928849,90.00000001 +234.36,50.30085681,-2.999237234,10433.0807,-1.25E-11,199.1795337,-18.0984375,0,5.191903298,90.00000001 +234.37,50.30085681,-2.999209324,10433.2616,-6.56E-11,199.1808774,-18.0746875,0,5.18487769,90.00000001 +234.38,50.30085681,-2.999181413,10433.4422,-8.91E-11,199.1831132,-18.05,0,5.177852139,90.00000001 +234.39,50.30085681,-2.999153502,10433.6226,-9.06E-11,199.1855719,-18.025,0,5.17082653,90.00000001 +234.4,50.30085681,-2.99912559,10433.8027,-8.28E-11,199.1878076,-18,0,5.163800979,90.00000001 +234.41,50.30085681,-2.999097679,10433.9826,-6.87E-11,199.1902663,-17.9753125,0,5.15677537,90.00000001 +234.42,50.30085681,-2.999069766,10434.1622,-3.59E-11,199.1929481,-17.9515625,0,5.149749819,90.00000001 +234.43,50.30085681,-2.999041854,10434.3416,3.12E-12,199.1958528,-17.928125,0,5.142724211,90.00000001 +234.44,50.30085681,-2.999013941,10434.5208,-4.69E-12,199.1985345,-17.9034375,0,5.13569866,90.00000001 +234.45,50.30085681,-2.998986027,10434.6997,-7.50E-11,199.1996551,-17.878125,0,5.128673051,90.00000001 +234.46,50.30085681,-2.998958114,10434.8783,-1.53E-10,199.2001067,-17.85375,0,5.1216475,90.00000001 +234.47,50.30085681,-2.998930201,10435.0568,-1.94E-10,199.2023424,-17.8296875,0,5.114621891,90.00000001 +234.48,50.30085681,-2.998902287,10435.2349,-2.08E-10,199.2056931,-17.805,0,5.10759634,90.00000001 +234.49,50.30085681,-2.998874372,10435.4129,-2.08E-10,199.2079288,-17.7803125,0,5.100570732,90.00000001 +234.5,50.30085681,-2.998846458,10435.5905,-1.67E-10,199.2094954,-17.75625,0,5.093545181,90.00000001 +234.51,50.30085681,-2.998818543,10435.768,-7.50E-11,199.211954,-17.731875,0,5.086519572,90.00000001 +234.52,50.30085681,-2.998790628,10435.9452,9.37E-12,199.2150817,-17.7065625,0,5.079494021,90.00000001 +234.53,50.30085681,-2.998762712,10436.1221,1.72E-11,199.2177633,-17.681875,0,5.072468412,90.00000001 +234.54,50.30085681,-2.998734796,10436.2988,-3.59E-11,199.2197759,-17.6584375,0,5.065442861,90.00000001 +234.55,50.30085681,-2.99870688,10436.4753,-8.28E-11,199.2213425,-17.6346875,0,5.058417253,90.00000001 +234.56,50.30085681,-2.998678963,10436.6515,-9.84E-11,199.2226861,-17.61,0,5.051391702,90.00000001 +234.57,50.30085681,-2.998651047,10436.8275,-9.06E-11,199.2249217,-17.5853125,0,5.044366093,90.00000001 +234.58,50.30085681,-2.99862313,10437.0032,-5.16E-11,199.2284953,-17.5615625,0,5.037340542,90.00000001 +234.59,50.30085681,-2.998595212,10437.1787,1.56E-12,199.2313999,-17.538125,0,5.030314933,90.00000001 +234.6,50.30085681,-2.998567294,10437.354,1.09E-11,199.2320744,-17.513125,0,5.023289382,90.00000001 +234.61,50.30085681,-2.998539376,10437.529,-2.03E-11,199.2323029,-17.486875,0,5.016263774,90.00000001 +234.62,50.30085681,-2.998511459,10437.7037,-1.88E-11,199.2345384,-17.461875,0,5.009238223,90.00000001 +234.63,50.30085681,-2.99848354,10437.8782,2.66E-11,199.238112,-17.4384375,0,5.002212614,90.00000001 +234.64,50.30085681,-2.998455621,10438.0525,5.78E-11,199.2410166,-17.4146875,0,4.995187063,90.00000001 +234.65,50.30085681,-2.998427702,10438.2265,5.78E-11,199.2430291,-17.39,0,4.988161454,90.00000001 +234.66,50.30085681,-2.998399782,10438.4003,4.22E-11,199.2450417,-17.3653125,0,4.981135903,90.00000001 +234.67,50.30085681,-2.998371863,10438.5738,3.13E-12,199.2475002,-17.3415625,0,4.974110295,90.00000001 +234.68,50.30085681,-2.998343942,10438.7471,-4.22E-11,199.2499587,-17.318125,0,4.967084744,90.00000001 +234.69,50.30085681,-2.998316022,10438.9202,-3.59E-11,199.2519712,-17.293125,0,4.960059135,90.00000001 +234.7,50.30085681,-2.998288101,10439.093,1.09E-11,199.2535377,-17.266875,0,4.953033584,90.00000001 +234.71,50.30085681,-2.99826018,10439.2655,1.72E-11,199.2546581,-17.241875,0,4.946007975,90.00000001 +234.72,50.30085681,-2.998232259,10439.4378,-2.81E-11,199.2560015,-17.2184375,0,4.938982424,90.00000001 +234.73,50.30085681,-2.998204338,10439.6099,-6.56E-11,199.25846,-17.1946875,0,4.931956873,90.00000001 +234.74,50.30085681,-2.998176416,10439.7817,-7.34E-11,199.2615875,-17.17,0,4.924931265,90.00000001 +234.75,50.30085681,-2.998148494,10439.9533,-5.78E-11,199.264046,-17.1453125,0,4.917905713,90.00000001 +234.76,50.30085681,-2.998120571,10440.1246,-1.09E-11,199.2653894,-17.1215625,0,4.910880105,90.00000001 +234.77,50.30085681,-2.998092649,10440.2957,4.22E-11,199.2667328,-17.098125,0,4.903854554,90.00000001 +234.78,50.30085681,-2.998064726,10440.4666,4.37E-11,199.2691912,-17.073125,0,4.896828945,90.00000001 +234.79,50.30085681,-2.998036803,10440.6372,4.69E-12,199.2723187,-17.046875,0,4.889803394,90.00000001 +234.8,50.30085681,-2.998008879,10440.8075,-1.56E-12,199.2750001,-17.021875,0,4.882777785,90.00000001 +234.81,50.30085681,-2.997980955,10440.9776,3.59E-11,199.2770125,-16.9984375,0,4.875752234,90.00000001 +234.82,50.30085681,-2.997953031,10441.1475,5.78E-11,199.2788019,-16.975,0,4.868726626,90.00000001 +234.83,50.30085681,-2.997925106,10441.3171,1.88E-11,199.2808143,-16.95125,0,4.861701075,90.00000001 +234.84,50.30085681,-2.997897182,10441.4865,-7.34E-11,199.2830497,-16.926875,0,4.854675466,90.00000001 +234.85,50.30085681,-2.997869256,10441.6557,-1.52E-10,199.2846161,-16.9015625,0,4.847649915,90.00000001 +234.86,50.30085681,-2.997841331,10441.8245,-1.52E-10,199.2855134,-16.876875,0,4.840624306,90.00000001 +234.87,50.30085681,-2.997813406,10441.9932,-9.84E-11,199.2873027,-16.8534375,0,4.833598755,90.00000001 +234.88,50.30085681,-2.99778548,10442.1616,-5.00E-11,199.2904301,-16.829375,0,4.826573147,90.00000001 +234.89,50.30085681,-2.997757554,10442.3298,4.69E-12,199.2937805,-16.80375,0,4.819547596,90.00000001 +234.9,50.30085681,-2.997729627,10442.4977,9.22E-11,199.2962389,-16.778125,0,4.812521987,90.00000001 +234.91,50.30085681,-2.9977017,10442.6653,1.77E-10,199.2975822,-16.75375,0,4.805496436,90.00000001 +234.92,50.30085681,-2.997673773,10442.8328,2.08E-10,199.2987024,-16.73,0,4.798470827,90.00000001 +234.93,50.30085681,-2.997645846,10442.9999,1.69E-10,199.3002687,-16.70625,0,4.791445276,90.00000001 +234.94,50.30085681,-2.997617918,10443.1669,7.50E-11,199.302504,-16.681875,0,4.784419668,90.00000001 +234.95,50.30085681,-2.997589991,10443.3336,-1.09E-11,199.3056314,-16.6565625,0,4.777394117,90.00000001 +234.96,50.30085681,-2.997562062,10443.5,-2.66E-11,199.3083127,-16.631875,0,4.770368508,90.00000001 +234.97,50.30085681,-2.997534133,10443.6662,1.09E-11,199.309433,-16.6084375,0,4.763342957,90.00000001 +234.98,50.30085681,-2.997506205,10443.8322,4.22E-11,199.3107762,-16.5846875,0,4.756317348,90.00000001 +234.99,50.30085681,-2.997478276,10443.9979,5.00E-11,199.3132345,-16.56,0,4.749291797,90.00000001 +235,50.30085681,-2.997450346,10444.1634,5.16E-11,199.3154698,-16.535,0,4.742266189,90.00000001 +235.01,50.30085681,-2.997422417,10444.3286,5.78E-11,199.317482,-16.51,0,4.735240638,90.00000001 +235.02,50.30085681,-2.997394487,10444.4936,6.72E-11,199.3194942,-16.485,0,4.728215029,90.00000001 +235.03,50.30085681,-2.997366556,10444.6583,7.34E-11,199.3212835,-16.46,0,4.721189478,90.00000001 +235.04,50.30085681,-2.997338627,10444.8228,6.56E-11,199.3237417,-16.4353125,0,4.714163869,90.00000001 +235.05,50.30085681,-2.997310695,10444.987,2.81E-11,199.326423,-16.4115625,0,4.707138318,90.00000001 +235.06,50.30085681,-2.997282764,10445.151,-2.66E-11,199.3279892,-16.3884375,0,4.70011271,90.00000001 +235.07,50.30085681,-2.997254833,10445.3148,-5.78E-11,199.3288863,-16.3646875,0,4.693087159,90.00000001 +235.08,50.30085681,-2.997226901,10445.4783,-5.78E-11,199.3300065,-16.34,0,4.68606155,90.00000001 +235.09,50.30085681,-2.99719897,10445.6416,-5.31E-11,199.3322417,-16.315,0,4.679035999,90.00000001 +235.1,50.30085681,-2.997171038,10445.8046,-5.78E-11,199.3355919,-16.29,0,4.67201039,90.00000001 +235.11,50.30085681,-2.997143105,10445.9674,-5.63E-11,199.3380501,-16.2653125,0,4.664984839,90.00000001 +235.12,50.30085681,-2.997115172,10446.1299,-1.88E-11,199.3391702,-16.2415625,0,4.657959231,90.00000001 +235.13,50.30085681,-2.99708724,10446.2922,3.28E-11,199.3407364,-16.218125,0,4.65093368,90.00000001 +235.14,50.30085681,-2.997059306,10446.4543,2.66E-11,199.3429715,-16.193125,0,4.643908071,90.00000001 +235.15,50.30085681,-2.997031373,10446.6161,-2.66E-11,199.3452067,-16.166875,0,4.63688252,90.00000001 +235.16,50.30085681,-2.997003439,10446.7776,-3.28E-11,199.3476649,-16.141875,0,4.629856911,90.00000001 +235.17,50.30085681,-2.996975505,10446.9389,1.88E-11,199.3499,-16.1184375,0,4.62283136,90.00000001 +235.18,50.30085681,-2.99694757,10447.1,4.69E-11,199.3514661,-16.095,0,4.615805752,90.00000001 +235.19,50.30085681,-2.996919636,10447.2608,1.09E-11,199.3534782,-16.0715625,0,4.608780201,90.00000001 +235.2,50.30085681,-2.996891701,10447.4214,-4.06E-11,199.3559364,-16.048125,0,4.601754592,90.00000001 +235.21,50.30085681,-2.996863765,10447.5818,-3.59E-11,199.3572794,-16.023125,0,4.594729041,90.00000001 +235.22,50.30085681,-2.99683583,10447.7419,1.09E-11,199.3583995,-15.996875,0,4.587703432,90.00000001 +235.23,50.30085681,-2.996807895,10447.9017,1.72E-11,199.3610806,-15.971875,0,4.580677881,90.00000001 +235.24,50.30085681,-2.996779958,10448.0613,-1.88E-11,199.3642077,-15.948125,0,4.573652273,90.00000001 +235.25,50.30085681,-2.996752022,10448.2207,-9.38E-12,199.3664428,-15.9234375,0,4.566626722,90.00000001 +235.26,50.30085681,-2.996724085,10448.3798,6.56E-11,199.3680089,-15.8984375,0,4.559601113,90.00000001 +235.27,50.30085681,-2.996696148,10448.5386,1.11E-10,199.3689058,-15.875,0,4.552575562,90.00000001 +235.28,50.30085681,-2.996668211,10448.6973,5.78E-11,199.3693568,-15.8515625,0,4.545549953,90.00000001 +235.29,50.30085681,-2.996640274,10448.8557,-3.59E-11,199.3706998,-15.82625,0,4.538524402,90.00000001 +235.3,50.30085681,-2.996612337,10449.0138,-8.75E-11,199.3738269,-15.8003125,0,4.531498794,90.00000001 +235.31,50.30085681,-2.996584399,10449.1717,-8.12E-11,199.3774,-15.7753125,0,4.524473242,90.00000001 +235.32,50.30085681,-2.99655646,10449.3293,-2.81E-11,199.379635,-15.7515625,0,4.517447634,90.00000001 +235.33,50.30085681,-2.996528522,10449.4867,4.22E-11,199.380978,-15.7284375,0,4.510422083,90.00000001 +235.34,50.30085681,-2.996500583,10449.6439,8.13E-11,199.382321,-15.7046875,0,4.503396474,90.00000001 +235.35,50.30085681,-2.996472644,10449.8008,8.28E-11,199.383664,-15.68,0,4.496370923,90.00000001 +235.36,50.30085681,-2.996444705,10449.9575,7.81E-11,199.3856759,-15.655,0,4.489345315,90.00000001 +235.37,50.30085681,-2.996416766,10450.1139,8.28E-11,199.388357,-15.63,0,4.482319763,90.00000001 +235.38,50.30085681,-2.996388825,10450.2701,8.28E-11,199.3905919,-15.6053125,0,4.475294155,90.00000001 +235.39,50.30085681,-2.996360886,10450.426,5.16E-11,199.3928269,-15.5815625,0,4.468268604,90.00000001 +235.4,50.30085681,-2.996332945,10450.5817,6.25E-12,199.3952849,-15.558125,0,4.461242995,90.00000001 +235.41,50.30085681,-2.996305004,10450.7372,4.69E-12,199.3964048,-15.533125,0,4.454217444,90.00000001 +235.42,50.30085681,-2.996277063,10450.8924,3.44E-11,199.3968557,-15.506875,0,4.447191836,90.00000001 +235.43,50.30085681,-2.996249123,10451.0473,1.88E-11,199.3990906,-15.481875,0,4.440166284,90.00000001 +235.44,50.30085681,-2.996221181,10451.202,-4.22E-11,199.4024406,-15.4584375,0,4.433140676,90.00000001 +235.45,50.30085681,-2.996193239,10451.3565,-8.28E-11,199.4044525,-15.4346875,0,4.426115125,90.00000001 +235.46,50.30085681,-2.996165297,10451.5107,-9.06E-11,199.4051264,-15.41,0,4.419089516,90.00000001 +235.47,50.30085681,-2.996137355,10451.6647,-8.28E-11,199.4062462,-15.3853125,0,4.412063965,90.00000001 +235.48,50.30085681,-2.996109413,10451.8184,-4.22E-11,199.4084811,-15.3615625,0,4.405038357,90.00000001 +235.49,50.30085681,-2.99608147,10451.9719,1.88E-11,199.410939,-15.338125,0,4.398012805,90.00000001 +235.5,50.30085681,-2.996053527,10452.1252,2.50E-11,199.4131739,-15.3134375,0,4.390987197,90.00000001 +235.51,50.30085681,-2.996025584,10452.2782,-5.16E-11,199.4154088,-15.288125,0,4.383961646,90.00000001 +235.52,50.30085681,-2.99599764,10452.4309,-1.34E-10,199.4169747,-15.2634375,0,4.376936037,90.00000001 +235.53,50.30085681,-2.995969696,10452.5835,-1.36E-10,199.4180945,-15.2384375,0,4.369910486,90.00000001 +235.54,50.30085681,-2.995941753,10452.7357,-6.72E-11,199.4203294,-15.2134375,0,4.362884878,90.00000001 +235.55,50.30085681,-2.995913808,10452.8877,-2.97E-11,199.4227872,-15.19,0,4.355859326,90.00000001 +235.56,50.30085681,-2.995885863,10453.0395,-8.28E-11,199.423907,-15.1665625,0,4.348833718,90.00000001 +235.57,50.30085681,-2.995857919,10453.1911,-1.61E-10,199.4252498,-15.1415625,0,4.341808167,90.00000001 +235.58,50.30085681,-2.995829974,10453.3423,-1.77E-10,199.4277077,-15.116875,0,4.334782558,90.00000001 +235.59,50.30085681,-2.995802028,10453.4934,-1.37E-10,199.4297195,-15.0934375,0,4.327757007,90.00000001 +235.6,50.30085681,-2.995774083,10453.6442,-8.91E-11,199.4312852,-15.069375,0,4.320731399,90.00000001 +235.61,50.30085681,-2.995746137,10453.7948,-2.03E-11,199.4335201,-15.04375,0,4.313705847,90.00000001 +235.62,50.30085681,-2.995718191,10453.9451,8.13E-11,199.4357549,-15.018125,0,4.306680239,90.00000001 +235.63,50.30085681,-2.995690244,10454.0951,1.67E-10,199.4370976,-14.99375,0,4.299654688,90.00000001 +235.64,50.30085681,-2.995662298,10454.245,1.92E-10,199.4384404,-14.97,0,4.292629079,90.00000001 +235.65,50.30085681,-2.995634351,10454.3945,1.53E-10,199.4408981,-14.94625,0,4.285603528,90.00000001 +235.66,50.30085681,-2.995606404,10454.5439,6.72E-11,199.443802,-14.921875,0,4.27857792,90.00000001 +235.67,50.30085681,-2.995578456,10454.693,-1.25E-11,199.4455907,-14.8965625,0,4.271552368,90.00000001 +235.68,50.30085681,-2.995550508,10454.8418,-2.66E-11,199.4464874,-14.871875,0,4.26452676,90.00000001 +235.69,50.30085681,-2.995522561,10454.9904,3.12E-12,199.4478301,-14.848125,0,4.257501209,90.00000001 +235.7,50.30085681,-2.995494612,10455.1388,-4.69E-12,199.4493958,-14.8234375,0,4.2504756,90.00000001 +235.71,50.30085681,-2.995466664,10455.2869,-7.50E-11,199.4511845,-14.798125,0,4.243450049,90.00000001 +235.72,50.30085681,-2.995438716,10455.4347,-1.53E-10,199.4538653,-14.77375,0,4.236424441,90.00000001 +235.73,50.30085681,-2.995410766,10455.5824,-1.84E-10,199.4561,-14.75,0,4.229398889,90.00000001 +235.74,50.30085681,-2.995382817,10455.7297,-1.52E-10,199.4572196,-14.72625,0,4.222373338,90.00000001 +235.75,50.30085681,-2.995354868,10455.8769,-6.72E-11,199.4587853,-14.701875,0,4.21534773,90.00000001 +235.76,50.30085681,-2.995326918,10456.0238,1.09E-11,199.460797,-14.6765625,0,4.208322179,90.00000001 +235.77,50.30085681,-2.995298968,10456.1704,1.87E-11,199.4621396,-14.651875,0,4.20129657,90.00000001 +235.78,50.30085681,-2.995271018,10456.3168,-1.88E-11,199.4634823,-14.628125,0,4.194271019,90.00000001 +235.79,50.30085681,-2.995243068,10456.463,-1.09E-11,199.465717,-14.6034375,0,4.18724541,90.00000001 +235.8,50.30085681,-2.995215117,10456.6089,6.72E-11,199.4679516,-14.578125,0,4.180219859,90.00000001 +235.81,50.30085681,-2.995187166,10456.7545,1.52E-10,199.4692942,-14.55375,0,4.173194251,90.00000001 +235.82,50.30085681,-2.995159215,10456.9,1.92E-10,199.4706368,-14.5296875,0,4.1661687,90.00000001 +235.83,50.30085681,-2.995131264,10457.0451,2.00E-10,199.4728715,-14.505,0,4.159143091,90.00000001 +235.84,50.30085681,-2.995103312,10457.1901,1.92E-10,199.4753291,-14.4803125,0,4.15211754,90.00000001 +235.85,50.30085681,-2.99507536,10457.3347,1.52E-10,199.4773408,-14.45625,0,4.145091931,90.00000001 +235.86,50.30085681,-2.995047408,10457.4792,6.72E-11,199.4789063,-14.431875,0,4.13806638,90.00000001 +235.87,50.30085681,-2.995019455,10457.6234,-1.09E-11,199.4802489,-14.4065625,0,4.131040772,90.00000001 +235.88,50.30085681,-2.994991503,10457.7673,-1.87E-11,199.4822605,-14.381875,0,4.12401522,90.00000001 +235.89,50.30085681,-2.99496355,10457.911,2.66E-11,199.4849411,-14.3584375,0,4.116989612,90.00000001 +235.9,50.30085681,-2.994935596,10458.0545,5.78E-11,199.4869527,-14.3346875,0,4.109964061,90.00000001 +235.91,50.30085681,-2.994907643,10458.1977,5.78E-11,199.4882953,-14.31,0,4.102938452,90.00000001 +235.92,50.30085681,-2.994879689,10458.3407,4.22E-11,199.4896378,-14.2853125,0,4.095912901,90.00000001 +235.93,50.30085681,-2.994851735,10458.4834,3.13E-12,199.4907573,-14.2615625,0,4.088887293,90.00000001 +235.94,50.30085681,-2.994823781,10458.6259,-4.22E-11,199.4920998,-14.238125,0,4.081861741,90.00000001 +235.95,50.30085681,-2.994795827,10458.7682,-3.59E-11,199.4943344,-14.213125,0,4.074836133,90.00000001 +235.96,50.30085681,-2.994767872,10458.9102,1.09E-11,199.4965689,-14.186875,0,4.067810582,90.00000001 +235.97,50.30085681,-2.994739917,10459.0519,1.72E-11,199.4979114,-14.161875,0,4.060784973,90.00000001 +235.98,50.30085681,-2.994711962,10459.1934,-2.81E-11,199.4990309,-14.1384375,0,4.053759422,90.00000001 +235.99,50.30085681,-2.994684007,10459.3347,-6.56E-11,199.5005964,-14.1146875,0,4.046733814,90.00000001 +236,50.30085681,-2.994656051,10459.4757,-7.50E-11,199.5026079,-14.09,0,4.039708262,90.00000001 +236.01,50.30085681,-2.994628096,10459.6165,-7.66E-11,199.5048424,-14.065,0,4.032682654,90.00000001 +236.02,50.30085681,-2.994600139,10459.757,-8.12E-11,199.5064078,-14.04,0,4.025657103,90.00000001 +236.03,50.30085681,-2.994572183,10459.8973,-7.34E-11,199.5073043,-14.0153125,0,4.018631494,90.00000001 +236.04,50.30085681,-2.994544227,10460.0373,-2.66E-11,199.5090927,-13.9915625,0,4.011605943,90.00000001 +236.05,50.30085681,-2.99451627,10460.1771,3.28E-11,199.5119962,-13.968125,0,4.004580335,90.00000001 +236.06,50.30085681,-2.994488313,10460.3167,2.50E-11,199.5144537,-13.9434375,0,3.997554783,90.00000001 +236.07,50.30085681,-2.994460355,10460.456,-6.72E-11,199.5157962,-13.918125,0,3.990529175,90.00000001 +236.08,50.30085681,-2.994432398,10460.595,-1.67E-10,199.5169155,-13.89375,0,3.983503624,90.00000001 +236.09,50.30085681,-2.99440444,10460.7339,-2.16E-10,199.5182579,-13.8696875,0,3.976478015,90.00000001 +236.1,50.30085681,-2.994376482,10460.8724,-2.25E-10,199.5196003,-13.845,0,3.969452464,90.00000001 +236.11,50.30085681,-2.994348524,10461.0108,-2.17E-10,199.5216118,-13.8203125,0,3.962426856,90.00000001 +236.12,50.30085681,-2.994320566,10461.1488,-1.77E-10,199.5240692,-13.79625,0,3.955401304,90.00000001 +236.13,50.30085681,-2.994292606,10461.2867,-9.22E-11,199.5254116,-13.771875,0,3.948375696,90.00000001 +236.14,50.30085681,-2.994264648,10461.4243,-1.25E-11,199.5263079,-13.7465625,0,3.941350145,90.00000001 +236.15,50.30085681,-2.994236689,10461.5616,3.13E-12,199.5283193,-13.721875,0,3.934324536,90.00000001 +236.16,50.30085681,-2.994208729,10461.6987,-2.81E-11,199.5307767,-13.6984375,0,3.927298985,90.00000001 +236.17,50.30085681,-2.99418077,10461.8356,-5.16E-11,199.5325651,-13.6746875,0,3.920273377,90.00000001 +236.18,50.30085681,-2.994152809,10461.9722,-5.94E-11,199.5339074,-13.65,0,3.913247825,90.00000001 +236.19,50.30085681,-2.99412485,10462.1086,-6.87E-11,199.5356958,-13.625,0,3.906222217,90.00000001 +236.2,50.30085681,-2.994096889,10462.2447,-8.13E-11,199.5377071,-13.6,0,3.899196666,90.00000001 +236.21,50.30085681,-2.994068928,10462.3806,-9.06E-11,199.5390494,-13.575,0,3.892171057,90.00000001 +236.22,50.30085681,-2.994040968,10462.5162,-8.91E-11,199.5399457,-13.55,0,3.885145506,90.00000001 +236.23,50.30085681,-2.994013006,10462.6516,-6.56E-11,199.541065,-13.5253125,0,3.878119898,90.00000001 +236.24,50.30085681,-2.993985046,10462.7867,-1.25E-11,199.5430763,-13.5015625,0,3.871094346,90.00000001 +236.25,50.30085681,-2.993957084,10462.9216,5.00E-11,199.5457567,-13.4784375,0,3.864068738,90.00000001 +236.26,50.30085681,-2.993929122,10463.0563,8.28E-11,199.547768,-13.4546875,0,3.857043187,90.00000001 +236.27,50.30085681,-2.99390116,10463.1907,8.28E-11,199.5491102,-13.43,0,3.850017578,90.00000001 +236.28,50.30085681,-2.993873198,10463.3249,7.66E-11,199.5504525,-13.405,0,3.842992027,90.00000001 +236.29,50.30085681,-2.993845235,10463.4588,7.50E-11,199.5515717,-13.38,0,3.835966419,90.00000001 +236.3,50.30085681,-2.993817273,10463.5925,7.50E-11,199.552691,-13.355,0,3.828940867,90.00000001 +236.31,50.30085681,-2.99378931,10463.7259,7.50E-11,199.5542562,-13.33,0,3.821915259,90.00000001 +236.32,50.30085681,-2.993761347,10463.8591,6.72E-11,199.5562675,-13.3053125,0,3.814889708,90.00000001 +236.33,50.30085681,-2.993733384,10463.992,3.59E-11,199.5587248,-13.2815625,0,3.807864099,90.00000001 +236.34,50.30085681,-2.99370542,10464.1247,-1.09E-11,199.560959,-13.2584375,0,3.800838548,90.00000001 +236.35,50.30085681,-2.993677456,10464.2572,-4.37E-11,199.5620782,-13.2346875,0,3.79381294,90.00000001 +236.36,50.30085681,-2.993649492,10464.3894,-5.94E-11,199.5625284,-13.21,0,3.786787388,90.00000001 +236.37,50.30085681,-2.993621528,10464.5214,-7.50E-11,199.5636475,-13.185,0,3.77976178,90.00000001 +236.38,50.30085681,-2.993593564,10464.6531,-8.91E-11,199.5661048,-13.16,0,3.772736229,90.00000001 +236.39,50.30085681,-2.993565599,10464.7846,-9.06E-11,199.5692311,-13.135,0,3.76571062,90.00000001 +236.4,50.30085681,-2.993537634,10464.9158,-8.28E-11,199.5716883,-13.11,0,3.758685069,90.00000001 +236.41,50.30085681,-2.993509668,10465.0468,-6.88E-11,199.5728074,-13.0853125,0,3.751659461,90.00000001 +236.42,50.30085681,-2.993481703,10465.1775,-3.59E-11,199.5730345,-13.0615625,0,3.744633909,90.00000001 +236.43,50.30085681,-2.993453737,10465.308,1.56E-12,199.5732616,-13.038125,0,3.737608301,90.00000001 +236.44,50.30085681,-2.993425772,10465.4383,-1.41E-11,199.5743807,-13.0134375,0,3.73058275,90.00000001 +236.45,50.30085681,-2.993397806,10465.5683,-1.00E-10,199.5768379,-12.988125,0,3.723557141,90.00000001 +236.46,50.30085681,-2.99336984,10465.698,-1.92E-10,199.5799641,-12.96375,0,3.71653159,90.00000001 +236.47,50.30085681,-2.993341873,10465.8276,-2.22E-10,199.5824213,-12.94,0,3.709505982,90.00000001 +236.48,50.30085681,-2.993313906,10465.9568,-1.69E-10,199.5835404,-12.91625,0,3.70248043,90.00000001 +236.49,50.30085681,-2.993285939,10466.0859,-6.09E-11,199.5839905,-12.891875,0,3.695454822,90.00000001 +236.5,50.30085681,-2.993257972,10466.2147,3.59E-11,199.5851095,-12.86625,0,3.688429271,90.00000001 +236.51,50.30085681,-2.993230005,10466.3432,8.12E-11,199.5873437,-12.8403125,0,3.681403662,90.00000001 +236.52,50.30085681,-2.993202037,10466.4715,8.28E-11,199.5895778,-12.8153125,0,3.674378111,90.00000001 +236.53,50.30085681,-2.993174069,10466.5995,4.22E-11,199.5906969,-12.7915625,0,3.667352503,90.00000001 +236.54,50.30085681,-2.993146101,10466.7273,-2.81E-11,199.5911469,-12.7684375,0,3.660326951,90.00000001 +236.55,50.30085681,-2.993118133,10466.8549,-8.13E-11,199.5922659,-12.7446875,0,3.653301343,90.00000001 +236.56,50.30085681,-2.993090165,10466.9822,-9.84E-11,199.5945,-12.72,0,3.646275792,90.00000001 +236.57,50.30085681,-2.993062196,10467.1093,-1.00E-10,199.5969571,-12.695,0,3.639250183,90.00000001 +236.58,50.30085681,-2.993034227,10467.2361,-9.84E-11,199.5989682,-12.67,0,3.632224632,90.00000001 +236.59,50.30085681,-2.993006258,10467.3627,-8.28E-11,199.6005332,-12.6453125,0,3.625199023,90.00000001 +236.6,50.30085681,-2.992978288,10467.489,-3.59E-11,199.6016522,-12.6215625,0,3.618173472,90.00000001 +236.61,50.30085681,-2.992950319,10467.6151,1.72E-11,199.6029942,-12.598125,0,3.611147864,90.00000001 +236.62,50.30085681,-2.992922349,10467.741,2.03E-11,199.6052283,-12.573125,0,3.604122313,90.00000001 +236.63,50.30085681,-2.992894379,10467.8666,-1.09E-11,199.6072393,-12.546875,0,3.597096704,90.00000001 +236.64,50.30085681,-2.992866408,10467.9919,-3.13E-12,199.6076892,-12.521875,0,3.590071153,90.00000001 +236.65,50.30085681,-2.992838438,10468.117,4.22E-11,199.6076931,-12.4984375,0,3.583045544,90.00000001 +236.66,50.30085681,-2.992810468,10468.2419,6.72E-11,199.6090351,-12.4746875,0,3.576019993,90.00000001 +236.67,50.30085681,-2.992782497,10468.3665,6.88E-11,199.6112691,-12.45,0,3.568994385,90.00000001 +236.68,50.30085681,-2.992754526,10468.4909,6.72E-11,199.6135031,-12.4253125,0,3.561968834,90.00000001 +236.69,50.30085681,-2.992726555,10468.615,4.22E-11,199.6159601,-12.4015625,0,3.554943225,90.00000001 +236.7,50.30085681,-2.992698583,10468.7389,-3.12E-12,199.6181941,-12.378125,0,3.547917674,90.00000001 +236.71,50.30085681,-2.992670611,10468.8626,-1.09E-11,199.619313,-12.353125,0,3.540892065,90.00000001 +236.72,50.30085681,-2.992642639,10468.986,2.19E-11,199.6197629,-12.326875,0,3.533866514,90.00000001 +236.73,50.30085681,-2.992614667,10469.1091,2.66E-11,199.6206588,-12.301875,0,3.526840906,90.00000001 +236.74,50.30085681,-2.992586695,10469.232,-1.25E-11,199.6220007,-12.2784375,0,3.519815355,90.00000001 +236.75,50.30085681,-2.992558722,10469.3547,-5.16E-11,199.6233426,-12.2546875,0,3.512789803,90.00000001 +236.76,50.30085681,-2.99253075,10469.4771,-7.34E-11,199.6253535,-12.23,0,3.505764195,90.00000001 +236.77,50.30085681,-2.992502777,10469.5993,-7.19E-11,199.6280335,-12.2053125,0,3.498738644,90.00000001 +236.78,50.30085681,-2.992474803,10469.7212,-2.66E-11,199.6298214,-12.1815625,0,3.491713035,90.00000001 +236.79,50.30085681,-2.99244683,10469.8429,3.28E-11,199.6302712,-12.158125,0,3.484687484,90.00000001 +236.8,50.30085681,-2.992418856,10469.9644,3.44E-11,199.630498,-12.133125,0,3.477661876,90.00000001 +236.81,50.30085681,-2.992390883,10470.0856,-1.09E-11,199.6316169,-12.106875,0,3.470636324,90.00000001 +236.82,50.30085681,-2.992362909,10470.2065,-1.72E-11,199.6340738,-12.081875,0,3.463610716,90.00000001 +236.83,50.30085681,-2.992334935,10470.3272,2.81E-11,199.6369767,-12.0584375,0,3.456585165,90.00000001 +236.84,50.30085681,-2.99230696,10470.4477,6.72E-11,199.6387646,-12.0346875,0,3.449559556,90.00000001 +236.85,50.30085681,-2.992278985,10470.5679,8.28E-11,199.6396604,-12.01,0,3.442534005,90.00000001 +236.86,50.30085681,-2.992251011,10470.6879,9.22E-11,199.6410022,-11.985,0,3.435508397,90.00000001 +236.87,50.30085681,-2.992223035,10470.8076,9.69E-11,199.642344,-11.96,0,3.428482845,90.00000001 +236.88,50.30085681,-2.99219506,10470.9271,8.12E-11,199.6432398,-11.9353125,0,3.421457237,90.00000001 +236.89,50.30085681,-2.992167085,10471.0463,2.81E-11,199.6448046,-11.9115625,0,3.414431686,90.00000001 +236.9,50.30085681,-2.992139109,10471.1653,-3.28E-11,199.6468154,-11.888125,0,3.407406077,90.00000001 +236.91,50.30085681,-2.992111133,10471.2841,-3.44E-11,199.6479342,-11.863125,0,3.400380526,90.00000001 +236.92,50.30085681,-2.992083157,10471.4026,1.09E-11,199.6483839,-11.836875,0,3.393354918,90.00000001 +236.93,50.30085681,-2.992055181,10471.5208,1.56E-11,199.6495027,-11.811875,0,3.386329366,90.00000001 +236.94,50.30085681,-2.992027205,10471.6388,-3.59E-11,199.6517365,-11.7884375,0,3.379303758,90.00000001 +236.95,50.30085681,-2.991999228,10471.7566,-8.13E-11,199.6539703,-11.7646875,0,3.372278207,90.00000001 +236.96,50.30085681,-2.991971251,10471.8741,-8.91E-11,199.655312,-11.74,0,3.365252598,90.00000001 +236.97,50.30085681,-2.991943274,10471.9914,-6.56E-11,199.6566537,-11.7153125,0,3.358227047,90.00000001 +236.98,50.30085681,-2.991915297,10472.1084,-1.25E-11,199.6586645,-11.6915625,0,3.351201439,90.00000001 +236.99,50.30085681,-2.991887319,10472.2252,4.06E-11,199.6600062,-11.668125,0,3.344175887,90.00000001 +237,50.30085681,-2.991859341,10472.3418,3.59E-11,199.6602329,-11.643125,0,3.337150279,90.00000001 +237.01,50.30085681,-2.991831364,10472.4581,-1.09E-11,199.6613516,-11.616875,0,3.330124728,90.00000001 +237.02,50.30085681,-2.991803386,10472.5741,-1.72E-11,199.6638083,-11.591875,0,3.323099119,90.00000001 +237.03,50.30085681,-2.991775407,10472.6899,2.81E-11,199.6658191,-11.5684375,0,3.316073568,90.00000001 +237.04,50.30085681,-2.991747429,10472.8055,6.56E-11,199.6671607,-11.5446875,0,3.30904796,90.00000001 +237.05,50.30085681,-2.99171945,10472.9208,7.34E-11,199.6685024,-11.52,0,3.302022408,90.00000001 +237.06,50.30085681,-2.991691471,10473.0359,5.78E-11,199.6696211,-11.4953125,0,3.2949968,90.00000001 +237.07,50.30085681,-2.991663492,10473.1507,1.09E-11,199.6707397,-11.4715625,0,3.287971249,90.00000001 +237.08,50.30085681,-2.991635513,10473.2653,-4.22E-11,199.6720814,-11.448125,0,3.28094564,90.00000001 +237.09,50.30085681,-2.991607533,10473.3797,-4.38E-11,199.6732,-11.423125,0,3.273920089,90.00000001 +237.1,50.30085681,-2.991579554,10473.4938,-4.69E-12,199.6743186,-11.396875,0,3.266894481,90.00000001 +237.11,50.30085681,-2.991551574,10473.6076,1.56E-12,199.6758833,-11.371875,0,3.259868929,90.00000001 +237.12,50.30085681,-2.991523594,10473.7212,-3.59E-11,199.6778939,-11.3484375,0,3.252843321,90.00000001 +237.13,50.30085681,-2.991495614,10473.8346,-6.72E-11,199.6803506,-11.3246875,0,3.24581777,90.00000001 +237.14,50.30085681,-2.991467633,10473.9477,-7.50E-11,199.6823612,-11.3,0,3.238792161,90.00000001 +237.15,50.30085681,-2.991439652,10474.0606,-7.66E-11,199.6825878,-11.275,0,3.23176661,90.00000001 +237.16,50.30085681,-2.991411671,10474.1732,-8.28E-11,199.6819222,-11.25,0,3.224741001,90.00000001 +237.17,50.30085681,-2.991383691,10474.2856,-8.28E-11,199.6830408,-11.2253125,0,3.21771545,90.00000001 +237.18,50.30085681,-2.99135571,10474.3977,-5.16E-11,199.6861665,-11.2015625,0,3.210689842,90.00000001 +237.19,50.30085681,-2.991327728,10474.5096,-6.25E-12,199.6884001,-11.178125,0,3.203664291,90.00000001 +237.2,50.30085681,-2.991299746,10474.6213,-4.69E-12,199.6886266,-11.153125,0,3.196638682,90.00000001 +237.21,50.30085681,-2.991271765,10474.7327,-3.59E-11,199.6890761,-11.126875,0,3.189613131,90.00000001 +237.22,50.30085681,-2.991243783,10474.8438,-2.66E-11,199.6910867,-11.101875,0,3.182587522,90.00000001 +237.23,50.30085681,-2.991215801,10474.9547,2.66E-11,199.6933203,-11.0784375,0,3.175561971,90.00000001 +237.24,50.30085681,-2.991187818,10475.0654,6.56E-11,199.6946618,-11.0546875,0,3.168536363,90.00000001 +237.25,50.30085681,-2.991159836,10475.1758,7.50E-11,199.6957803,-11.03,0,3.161510812,90.00000001 +237.26,50.30085681,-2.991131853,10475.286,6.72E-11,199.6973448,-11.0053125,0,3.154485203,90.00000001 +237.27,50.30085681,-2.99110387,10475.3959,3.59E-11,199.6991324,-10.9815625,0,3.147459652,90.00000001 +237.28,50.30085681,-2.991075887,10475.5056,-1.56E-12,199.7006969,-10.958125,0,3.140434043,90.00000001 +237.29,50.30085681,-2.991047903,10475.6151,4.69E-12,199.7015924,-10.933125,0,3.133408492,90.00000001 +237.3,50.30085681,-2.99101992,10475.7243,4.38E-11,199.7018188,-10.906875,0,3.126382884,90.00000001 +237.31,50.30085681,-2.990991936,10475.8332,4.22E-11,199.7022682,-10.881875,0,3.119357333,90.00000001 +237.32,50.30085681,-2.990963953,10475.9419,-1.09E-11,199.7040557,-10.8584375,0,3.112331724,90.00000001 +237.33,50.30085681,-2.990935969,10476.0504,-5.78E-11,199.7067352,-10.8346875,0,3.105306173,90.00000001 +237.34,50.30085681,-2.990907984,10476.1586,-7.34E-11,199.7085227,-10.81,0,3.098280564,90.00000001 +237.35,50.30085681,-2.99088,10476.2666,-6.56E-11,199.7089721,-10.7853125,0,3.091255013,90.00000001 +237.36,50.30085681,-2.990852015,10476.3743,-2.66E-11,199.7091985,-10.7615625,0,3.084229405,90.00000001 +237.37,50.30085681,-2.990824031,10476.4818,2.66E-11,199.7103169,-10.738125,0,3.077203854,90.00000001 +237.38,50.30085681,-2.990796046,10476.5891,3.59E-11,199.7127734,-10.713125,0,3.070178245,90.00000001 +237.39,50.30085681,-2.990768061,10476.6961,4.69E-12,199.7156759,-10.686875,0,3.063152694,90.00000001 +237.4,50.30085681,-2.990740075,10476.8028,6.25E-12,199.7172403,-10.661875,0,3.056127085,90.00000001 +237.41,50.30085681,-2.990712089,10476.9093,5.16E-11,199.7172436,-10.6384375,0,3.049101534,90.00000001 +237.42,50.30085681,-2.990684104,10477.0156,8.28E-11,199.71747,-10.6146875,0,3.042075926,90.00000001 +237.43,50.30085681,-2.990656118,10477.1216,8.28E-11,199.7188114,-10.59,0,3.035050375,90.00000001 +237.44,50.30085681,-2.990628132,10477.2274,7.66E-11,199.7205988,-10.565,0,3.028024766,90.00000001 +237.45,50.30085681,-2.990600146,10477.3329,7.50E-11,199.7221631,-10.54,0,3.020999215,90.00000001 +237.46,50.30085681,-2.990572159,10477.4382,7.50E-11,199.7232815,-10.515,0,3.013973606,90.00000001 +237.47,50.30085681,-2.990544173,10477.5432,7.34E-11,199.7243998,-10.49,0,3.006948055,90.00000001 +237.48,50.30085681,-2.990516186,10477.648,5.78E-11,199.7257412,-10.4653125,0,2.999922447,90.00000001 +237.49,50.30085681,-2.990488199,10477.7525,1.09E-11,199.7268595,-10.4415625,0,2.992896896,90.00000001 +237.5,50.30085681,-2.990460212,10477.8568,-5.16E-11,199.7279778,-10.4184375,0,2.985871287,90.00000001 +237.51,50.30085681,-2.990432225,10477.9609,-9.06E-11,199.7293191,-10.3946875,0,2.978845736,90.00000001 +237.52,50.30085681,-2.990404237,10478.0647,-9.84E-11,199.7306605,-10.37,0,2.971820127,90.00000001 +237.53,50.30085681,-2.99037625,10478.1683,-9.22E-11,199.7324478,-10.345,0,2.964794576,90.00000001 +237.54,50.30085681,-2.990348262,10478.2716,-8.28E-11,199.7342351,-10.32,0,2.957768968,90.00000001 +237.55,50.30085681,-2.990320273,10478.3747,-7.66E-11,199.7349074,-10.295,0,2.950743417,90.00000001 +237.56,50.30085681,-2.990292286,10478.4775,-7.34E-11,199.7353566,-10.27,0,2.943717808,90.00000001 +237.57,50.30085681,-2.990264297,10478.5801,-5.78E-11,199.7366979,-10.2453125,0,2.936692257,90.00000001 +237.58,50.30085681,-2.990236309,10478.6824,-1.25E-11,199.7384852,-10.2215625,0,2.929666648,90.00000001 +237.59,50.30085681,-2.99020832,10478.7845,4.22E-11,199.7400495,-10.1984375,0,2.922641097,90.00000001 +237.6,50.30085681,-2.990180331,10478.8864,6.56E-11,199.7411677,-10.1746875,0,2.915615489,90.00000001 +237.61,50.30085681,-2.990152342,10478.988,5.94E-11,199.742286,-10.15,0,2.908589938,90.00000001 +237.62,50.30085681,-2.990124353,10479.0894,5.31E-11,199.7436272,-10.125,0,2.901564329,90.00000001 +237.63,50.30085681,-2.990096363,10479.1905,5.78E-11,199.7447454,-10.1,0,2.894538778,90.00000001 +237.64,50.30085681,-2.990068374,10479.2914,6.72E-11,199.7458636,-10.075,0,2.887513169,90.00000001 +237.65,50.30085681,-2.990040384,10479.392,7.34E-11,199.7474279,-10.05,0,2.880487618,90.00000001 +237.66,50.30085681,-2.990012394,10479.4924,7.50E-11,199.7492151,-10.025,0,2.87346201,90.00000001 +237.67,50.30085681,-2.989984404,10479.5925,8.44E-11,199.7507793,-10.0003125,0,2.866436458,90.00000001 +237.68,50.30085681,-2.989956413,10479.6924,1.23E-10,199.7516745,-9.9765625,0,2.85941085,90.00000001 +237.69,50.30085681,-2.989928423,10479.792,1.77E-10,199.7521236,-9.953125,0,2.852385299,90.00000001 +237.7,50.30085681,-2.989900432,10479.8915,1.77E-10,199.7530188,-9.9284375,0,2.84535969,90.00000001 +237.71,50.30085681,-2.989872442,10479.9906,9.69E-11,199.7543599,-9.903125,0,2.838334139,90.00000001 +237.72,50.30085681,-2.98984445,10480.0895,-3.13E-12,199.7557011,-9.87875,0,2.831308531,90.00000001 +237.73,50.30085681,-2.98981646,10480.1882,-6.56E-11,199.7574883,-9.8546875,0,2.824282979,90.00000001 +237.74,50.30085681,-2.989788468,10480.2866,-8.91E-11,199.7592755,-9.83,0,2.817257428,90.00000001 +237.75,50.30085681,-2.989760476,10480.3848,-8.13E-11,199.7599476,-9.8053125,0,2.81023182,90.00000001 +237.76,50.30085681,-2.989732485,10480.4827,-3.59E-11,199.7603967,-9.7815625,0,2.803206269,90.00000001 +237.77,50.30085681,-2.989704493,10480.5804,1.56E-11,199.7615148,-9.758125,0,2.79618066,90.00000001 +237.78,50.30085681,-2.989676501,10480.6779,1.09E-11,199.7626329,-9.733125,0,2.789155109,90.00000001 +237.79,50.30085681,-2.989648509,10480.7751,-3.44E-11,199.763751,-9.706875,0,2.7821295,90.00000001 +237.8,50.30085681,-2.989620517,10480.872,-3.28E-11,199.7650921,-9.681875,0,2.775103949,90.00000001 +237.81,50.30085681,-2.989592524,10480.9687,2.66E-11,199.7662102,-9.6584375,0,2.768078341,90.00000001 +237.82,50.30085681,-2.989564532,10481.0652,7.19E-11,199.7673282,-9.6346875,0,2.76105279,90.00000001 +237.83,50.30085681,-2.989536539,10481.1614,7.34E-11,199.7688923,-9.61,0,2.754027181,90.00000001 +237.84,50.30085681,-2.989508546,10481.2574,6.09E-11,199.7706794,-9.585,0,2.74700163,90.00000001 +237.85,50.30085681,-2.989480553,10481.3531,5.94E-11,199.7722435,-9.56,0,2.739976021,90.00000001 +237.86,50.30085681,-2.989452559,10481.4486,5.78E-11,199.7733616,-9.5353125,0,2.73295047,90.00000001 +237.87,50.30085681,-2.989424566,10481.5438,2.66E-11,199.7744796,-9.5115625,0,2.725924862,90.00000001 +237.88,50.30085681,-2.989396572,10481.6388,-1.72E-11,199.7758206,-9.488125,0,2.718899311,90.00000001 +237.89,50.30085681,-2.989368578,10481.7336,-1.56E-12,199.7767156,-9.4634375,0,2.711873702,90.00000001 +237.9,50.30085681,-2.989340584,10481.8281,9.06E-11,199.7769416,-9.438125,0,2.704848151,90.00000001 +237.91,50.30085681,-2.98931259,10481.9223,1.73E-10,199.7771676,-9.4134375,0,2.697822542,90.00000001 +237.92,50.30085681,-2.989284596,10482.0164,1.61E-10,199.7782856,-9.3884375,0,2.690796991,90.00000001 +237.93,50.30085681,-2.989256602,10482.1101,7.81E-11,199.7805186,-9.3634375,0,2.683771383,90.00000001 +237.94,50.30085681,-2.989228607,10482.2036,2.97E-11,199.7827517,-9.3403125,0,2.676745832,90.00000001 +237.95,50.30085681,-2.989200612,10482.2969,4.22E-11,199.7838696,-9.3178125,0,2.669720223,90.00000001 +237.96,50.30085681,-2.989172617,10482.39,3.44E-11,199.7840956,-9.293125,0,2.662694672,90.00000001 +237.97,50.30085681,-2.989144622,10482.4828,-1.25E-11,199.7843215,-9.266875,0,2.655669063,90.00000001 +237.98,50.30085681,-2.989116627,10482.5753,-2.50E-11,199.7852164,-9.241875,0,2.648643512,90.00000001 +237.99,50.30085681,-2.989088632,10482.6676,3.12E-12,199.7865574,-9.218125,0,2.641617904,90.00000001 +238,50.30085681,-2.989060636,10482.7597,4.69E-12,199.7878983,-9.193125,0,2.634592353,90.00000001 +238.01,50.30085681,-2.989032641,10482.8515,-1.88E-11,199.7896853,-9.166875,0,2.627566744,90.00000001 +238.02,50.30085681,-2.989004645,10482.943,-1.25E-11,199.7914723,-9.1421875,0,2.620541193,90.00000001 +238.03,50.30085681,-2.988976648,10483.0343,-4.69E-12,199.7921441,-9.1196875,0,2.613515584,90.00000001 +238.04,50.30085681,-2.988948653,10483.1254,-5.94E-11,199.792593,-9.0965625,0,2.606490033,90.00000001 +238.05,50.30085681,-2.988920656,10483.2163,-1.36E-10,199.7939339,-9.0715625,0,2.599464425,90.00000001 +238.06,50.30085681,-2.98889266,10483.3068,-1.42E-10,199.7957209,-9.0465625,0,2.592438874,90.00000001 +238.07,50.30085681,-2.988864663,10483.3972,-6.72E-11,199.7972848,-9.021875,0,2.585413265,90.00000001 +238.08,50.30085681,-2.988836666,10483.4873,1.09E-11,199.7981796,-8.9965625,0,2.578387714,90.00000001 +238.09,50.30085681,-2.988808669,10483.5771,1.72E-11,199.7984055,-8.971875,0,2.571362105,90.00000001 +238.1,50.30085681,-2.988780672,10483.6667,-3.59E-11,199.7986313,-8.9484375,0,2.564336554,90.00000001 +238.11,50.30085681,-2.988752675,10483.7561,-8.28E-11,199.7997491,-8.9246875,0,2.557310946,90.00000001 +238.12,50.30085681,-2.988724678,10483.8452,-9.84E-11,199.801982,-8.9,0,2.550285395,90.00000001 +238.13,50.30085681,-2.98869668,10483.9341,-1.00E-10,199.8042149,-8.875,0,2.543259786,90.00000001 +238.14,50.30085681,-2.988668682,10484.0227,-9.84E-11,199.8053328,-8.85,0,2.536234235,90.00000001 +238.15,50.30085681,-2.988640684,10484.1111,-9.22E-11,199.8055585,-8.825,0,2.529208626,90.00000001 +238.16,50.30085681,-2.988612686,10484.1992,-8.28E-11,199.8057843,-8.8,0,2.522183075,90.00000001 +238.17,50.30085681,-2.988584688,10484.2871,-6.72E-11,199.8069021,-8.7753125,0,2.515157467,90.00000001 +238.18,50.30085681,-2.98855669,10484.3747,-2.81E-11,199.808912,-8.7515625,0,2.508131916,90.00000001 +238.19,50.30085681,-2.988528691,10484.4621,2.81E-11,199.8102528,-8.7284375,0,2.501106307,90.00000001 +238.2,50.30085681,-2.988500692,10484.5493,6.56E-11,199.8102555,-8.7046875,0,2.494080756,90.00000001 +238.21,50.30085681,-2.988472694,10484.6362,7.34E-11,199.8104812,-8.68,0,2.487055147,90.00000001 +238.22,50.30085681,-2.988444695,10484.7229,6.72E-11,199.811599,-8.655,0,2.480029596,90.00000001 +238.23,50.30085681,-2.988416696,10484.8093,5.78E-11,199.8127168,-8.63,0,2.473003988,90.00000001 +238.24,50.30085681,-2.988388697,10484.8955,5.31E-11,199.8140575,-8.605,0,2.465978436,90.00000001 +238.25,50.30085681,-2.988360698,10484.9814,5.78E-11,199.8160673,-8.58,0,2.458952828,90.00000001 +238.26,50.30085681,-2.988332698,10485.0671,5.62E-11,199.8174081,-8.5553125,0,2.451927277,90.00000001 +238.27,50.30085681,-2.988304698,10485.1525,1.88E-11,199.8176338,-8.5315625,0,2.444901668,90.00000001 +238.28,50.30085681,-2.988276699,10485.2377,-3.28E-11,199.8187515,-8.508125,0,2.437876117,90.00000001 +238.29,50.30085681,-2.988248699,10485.3227,-2.66E-11,199.8209843,-8.483125,0,2.430850509,90.00000001 +238.3,50.30085681,-2.988220698,10485.4074,2.66E-11,199.822102,-8.456875,0,2.423824957,90.00000001 +238.31,50.30085681,-2.988192698,10485.4918,3.28E-11,199.8223276,-8.431875,0,2.416799349,90.00000001 +238.32,50.30085681,-2.988164698,10485.576,-1.88E-11,199.8236683,-8.4084375,0,2.409773798,90.00000001 +238.33,50.30085681,-2.988136697,10485.66,-4.84E-11,199.8254551,-8.385,0,2.402748189,90.00000001 +238.34,50.30085681,-2.988108696,10485.7437,-1.09E-11,199.8259037,-8.36125,0,2.395722638,90.00000001 +238.35,50.30085681,-2.988080695,10485.8272,7.34E-11,199.8259063,-8.336875,0,2.38869703,90.00000001 +238.36,50.30085681,-2.988052695,10485.9105,1.45E-10,199.827024,-8.3115625,0,2.381671478,90.00000001 +238.37,50.30085681,-2.988024693,10485.9934,1.44E-10,199.8283647,-8.2865625,0,2.37464587,90.00000001 +238.38,50.30085681,-2.987996692,10486.0762,5.78E-11,199.8290363,-8.2621875,0,2.367620319,90.00000001 +238.39,50.30085681,-2.987968691,10486.1587,-6.72E-11,199.8297079,-8.2378125,0,2.36059471,90.00000001 +238.4,50.30085681,-2.987940689,10486.2409,-1.59E-10,199.8306025,-8.2134375,0,2.353569159,90.00000001 +238.41,50.30085681,-2.987912688,10486.323,-1.61E-10,199.8317201,-8.1884375,0,2.346543551,90.00000001 +238.42,50.30085681,-2.987884686,10486.4047,-8.28E-11,199.8332838,-8.163125,0,2.339517999,90.00000001 +238.43,50.30085681,-2.987856684,10486.4862,1.56E-12,199.8350704,-8.13875,0,2.332492391,90.00000001 +238.44,50.30085681,-2.987828682,10486.5675,3.28E-11,199.8364111,-8.115,0,2.32546684,90.00000001 +238.45,50.30085681,-2.987800679,10486.6485,3.13E-12,199.8366366,-8.0915625,0,2.318441231,90.00000001 +238.46,50.30085681,-2.987772677,10486.7293,-4.22E-11,199.8364161,-8.068125,0,2.31141568,90.00000001 +238.47,50.30085681,-2.987744675,10486.8099,-3.59E-11,199.8370877,-8.043125,0,2.304390072,90.00000001 +238.48,50.30085681,-2.987716672,10486.8902,1.09E-11,199.8386513,-8.016875,0,2.29736452,90.00000001 +238.49,50.30085681,-2.98768867,10486.9702,1.72E-11,199.8402149,-7.991875,0,2.290338912,90.00000001 +238.5,50.30085681,-2.987660666,10487.05,-2.81E-11,199.8413324,-7.9684375,0,2.283313361,90.00000001 +238.51,50.30085681,-2.987632664,10487.1296,-6.56E-11,199.8422269,-7.9446875,0,2.276287752,90.00000001 +238.52,50.30085681,-2.98760466,10487.2089,-7.34E-11,199.8428985,-7.92,0,2.269262201,90.00000001 +238.53,50.30085681,-2.987576657,10487.288,-6.72E-11,199.84357,-7.895,0,2.262236593,90.00000001 +238.54,50.30085681,-2.987548654,10487.3668,-5.78E-11,199.8449105,-7.87,0,2.255211041,90.00000001 +238.55,50.30085681,-2.98752065,10487.4454,-5.31E-11,199.846251,-7.845,0,2.248185433,90.00000001 +238.56,50.30085681,-2.987492646,10487.5237,-5.94E-11,199.8471455,-7.82,0,2.241159882,90.00000001 +238.57,50.30085681,-2.987464643,10487.6018,-6.56E-11,199.8484861,-7.7953125,0,2.234134273,90.00000001 +238.58,50.30085681,-2.987436638,10487.6796,-4.22E-11,199.8498266,-7.7715625,0,2.227108722,90.00000001 +238.59,50.30085681,-2.987408634,10487.7572,3.13E-12,199.850498,-7.748125,0,2.220083114,90.00000001 +238.6,50.30085681,-2.98738063,10487.8346,1.56E-12,199.8511695,-7.7234375,0,2.213057562,90.00000001 +238.61,50.30085681,-2.987352625,10487.9117,-7.81E-11,199.852064,-7.698125,0,2.206031954,90.00000001 +238.62,50.30085681,-2.987324621,10487.9885,-1.77E-10,199.8529584,-7.67375,0,2.199006403,90.00000001 +238.63,50.30085681,-2.987296616,10488.0652,-2.33E-10,199.8536298,-7.6496875,0,2.191980794,90.00000001 +238.64,50.30085681,-2.987268611,10488.1415,-2.48E-10,199.8543013,-7.625,0,2.184955243,90.00000001 +238.65,50.30085681,-2.987240607,10488.2177,-2.41E-10,199.8556417,-7.6003125,0,2.177929635,90.00000001 +238.66,50.30085681,-2.987212601,10488.2935,-1.94E-10,199.8567592,-7.57625,0,2.170904083,90.00000001 +238.67,50.30085681,-2.987184596,10488.3692,-1.00E-10,199.8567615,-7.551875,0,2.163878475,90.00000001 +238.68,50.30085681,-2.987156591,10488.4446,-1.41E-11,199.8572099,-7.5265625,0,2.156852924,90.00000001 +238.69,50.30085681,-2.987128586,10488.5197,1.56E-12,199.8589963,-7.501875,0,2.149827315,90.00000001 +238.7,50.30085681,-2.98710058,10488.5946,-3.59E-11,199.8603368,-7.4784375,0,2.142801764,90.00000001 +238.71,50.30085681,-2.987072574,10488.6693,-6.87E-11,199.8605621,-7.4546875,0,2.135776156,90.00000001 +238.72,50.30085681,-2.987044569,10488.7437,-8.28E-11,199.8616795,-7.43,0,2.128750604,90.00000001 +238.73,50.30085681,-2.987016563,10488.8179,-9.06E-11,199.863912,-7.405,0,2.121724996,90.00000001 +238.74,50.30085681,-2.986988556,10488.8918,-8.91E-11,199.8650293,-7.38,0,2.114699445,90.00000001 +238.75,50.30085681,-2.98696055,10488.9655,-7.50E-11,199.8650316,-7.355,0,2.107673894,90.00000001 +238.76,50.30085681,-2.986932544,10489.0389,-5.94E-11,199.8654799,-7.33,0,2.100648285,90.00000001 +238.77,50.30085681,-2.986904537,10489.1121,-4.38E-11,199.8661513,-7.3053125,0,2.093622734,90.00000001 +238.78,50.30085681,-2.986876531,10489.185,-1.09E-11,199.8665996,-7.2815625,0,2.086597125,90.00000001 +238.79,50.30085681,-2.986848524,10489.2577,3.59E-11,199.8674939,-7.2584375,0,2.079571574,90.00000001 +238.8,50.30085681,-2.986820518,10489.3302,6.72E-11,199.8688342,-7.2346875,0,2.072545966,90.00000001 +238.81,50.30085681,-2.98679251,10489.4024,6.56E-11,199.8699516,-7.2096875,0,2.065520414,90.00000001 +238.82,50.30085681,-2.986764504,10489.4744,1.88E-11,199.8708459,-7.18375,0,2.058494806,90.00000001 +238.83,50.30085681,-2.986736496,10489.5461,-7.66E-11,199.8715171,-7.158125,0,2.051469255,90.00000001 +238.84,50.30085681,-2.986708489,10489.6175,-1.77E-10,199.8721884,-7.13375,0,2.044443646,90.00000001 +238.85,50.30085681,-2.986680482,10489.6888,-2.23E-10,199.8735287,-7.11,0,2.037418095,90.00000001 +238.86,50.30085681,-2.986652474,10489.7597,-1.92E-10,199.874646,-7.08625,0,2.030392487,90.00000001 +238.87,50.30085681,-2.986624466,10489.8305,-1.00E-10,199.8748712,-7.061875,0,2.023366935,90.00000001 +238.88,50.30085681,-2.986596459,10489.901,-1.41E-11,199.8759885,-7.0365625,0,2.016341327,90.00000001 +238.89,50.30085681,-2.986568451,10489.9712,1.56E-12,199.8782208,-7.011875,0,2.009315776,90.00000001 +238.9,50.30085681,-2.986540442,10490.0412,-3.59E-11,199.8793381,-6.9884375,0,2.002290167,90.00000001 +238.91,50.30085681,-2.986512434,10490.111,-6.72E-11,199.8793403,-6.9646875,0,1.995264616,90.00000001 +238.92,50.30085681,-2.986484426,10490.1805,-7.50E-11,199.8797884,-6.94,0,1.988239008,90.00000001 +238.93,50.30085681,-2.986456417,10490.2498,-7.50E-11,199.8806827,-6.915,0,1.981213456,90.00000001 +238.94,50.30085681,-2.986428409,10490.3188,-7.34E-11,199.8815769,-6.89,0,1.974187848,90.00000001 +238.95,50.30085681,-2.9864004,10490.3876,-6.72E-11,199.882025,-6.865,0,1.967162297,90.00000001 +238.96,50.30085681,-2.986372391,10490.4561,-5.78E-11,199.8818042,-6.84,0,1.960136688,90.00000001 +238.97,50.30085681,-2.986344383,10490.5244,-4.38E-11,199.8822523,-6.8153125,0,1.953111137,90.00000001 +238.98,50.30085681,-2.986316374,10490.5924,-1.25E-11,199.8842616,-6.7915625,0,1.946085529,90.00000001 +238.99,50.30085681,-2.986288365,10490.6602,1.87E-11,199.8862708,-6.768125,0,1.939059977,90.00000001 +239,50.30085681,-2.986260355,10490.7278,4.69E-12,199.886719,-6.743125,0,1.932034369,90.00000001 +239.01,50.30085681,-2.986232346,10490.7951,-3.44E-11,199.8867211,-6.716875,0,1.925008818,90.00000001 +239.02,50.30085681,-2.986204337,10490.8621,-2.50E-11,199.8878382,-6.691875,0,1.917983209,90.00000001 +239.03,50.30085681,-2.986176327,10490.9289,3.44E-11,199.8889554,-6.6684375,0,1.910957658,90.00000001 +239.04,50.30085681,-2.986148317,10490.9955,8.12E-11,199.8889574,-6.6446875,0,1.90393205,90.00000001 +239.05,50.30085681,-2.986120308,10491.0618,8.91E-11,199.8891825,-6.62,0,1.896906498,90.00000001 +239.06,50.30085681,-2.986092298,10491.1279,6.56E-11,199.8905227,-6.5953125,0,1.88988089,90.00000001 +239.07,50.30085681,-2.986064288,10491.1937,1.25E-11,199.8923088,-6.5715625,0,1.882855339,90.00000001 +239.08,50.30085681,-2.986036278,10491.2593,-4.06E-11,199.893649,-6.548125,0,1.87582973,90.00000001 +239.09,50.30085681,-2.986008267,10491.3247,-3.44E-11,199.893874,-6.523125,0,1.868804179,90.00000001 +239.1,50.30085681,-2.985980257,10491.3898,1.88E-11,199.8938761,-6.496875,0,1.861778571,90.00000001 +239.11,50.30085681,-2.985952247,10491.4546,3.28E-11,199.8952162,-6.471875,0,1.854753019,90.00000001 +239.12,50.30085681,-2.985924236,10491.5192,-1.25E-11,199.8970023,-6.4484375,0,1.847727411,90.00000001 +239.13,50.30085681,-2.985896225,10491.5836,-5.94E-11,199.8974503,-6.4246875,0,1.84070186,90.00000001 +239.14,50.30085681,-2.985868214,10491.6477,-8.12E-11,199.8974523,-6.4,0,1.833676251,90.00000001 +239.15,50.30085681,-2.985840204,10491.7116,-8.12E-11,199.8985694,-6.3753125,0,1.8266507,90.00000001 +239.16,50.30085681,-2.985812192,10491.7752,-3.28E-11,199.8996864,-6.35125,0,1.819625092,90.00000001 +239.17,50.30085681,-2.985784181,10491.8386,7.34E-11,199.8996884,-6.326875,0,1.81259954,90.00000001 +239.18,50.30085681,-2.98575617,10491.9018,1.66E-10,199.8999134,-6.3015625,0,1.805573932,90.00000001 +239.19,50.30085681,-2.985728159,10491.9646,1.67E-10,199.9010304,-6.276875,0,1.798548381,90.00000001 +239.2,50.30085681,-2.985700147,10492.0273,1.08E-10,199.9021475,-6.2534375,0,1.791522772,90.00000001 +239.21,50.30085681,-2.985672136,10492.0897,5.94E-11,199.9032645,-6.229375,0,1.784497221,90.00000001 +239.22,50.30085681,-2.985644124,10492.1519,1.09E-11,199.9046045,-6.20375,0,1.777471613,90.00000001 +239.23,50.30085681,-2.985616112,10492.2138,-7.66E-11,199.9054985,-6.178125,0,1.770446061,90.00000001 +239.24,50.30085681,-2.9855881,10492.2754,-1.69E-10,199.9057234,-6.15375,0,1.763420453,90.00000001 +239.25,50.30085681,-2.985560088,10492.3369,-2.08E-10,199.9057253,-6.13,0,1.756394902,90.00000001 +239.26,50.30085681,-2.985532076,10492.398,-1.77E-10,199.9059503,-6.10625,0,1.749369293,90.00000001 +239.27,50.30085681,-2.985504064,10492.459,-9.22E-11,199.9068442,-6.081875,0,1.742343742,90.00000001 +239.28,50.30085681,-2.985476052,10492.5197,-3.12E-12,199.9081842,-6.05625,0,1.735318134,90.00000001 +239.29,50.30085681,-2.985448039,10492.5801,5.94E-11,199.9090781,-6.030625,0,1.728292582,90.00000001 +239.3,50.30085681,-2.985420027,10492.6403,1.22E-10,199.909303,-6.0065625,0,1.721266974,90.00000001 +239.31,50.30085681,-2.985392014,10492.7002,1.83E-10,199.9095279,-5.983125,0,1.714241423,90.00000001 +239.32,50.30085681,-2.985364002,10492.76,1.75E-10,199.9104218,-5.9584375,0,1.707215814,90.00000001 +239.33,50.30085681,-2.985335989,10492.8194,8.28E-11,199.9119848,-5.933125,0,1.700190263,90.00000001 +239.34,50.30085681,-2.985307976,10492.8786,-1.72E-11,199.9137708,-5.90875,0,1.693164655,90.00000001 +239.35,50.30085681,-2.985279963,10492.9376,-6.72E-11,199.9151107,-5.8846875,0,1.686139103,90.00000001 +239.36,50.30085681,-2.985251949,10492.9963,-8.28E-11,199.9151125,-5.86,0,1.679113495,90.00000001 +239.37,50.30085681,-2.985223936,10493.0548,-8.28E-11,199.9142223,-5.8353125,0,1.672087944,90.00000001 +239.38,50.30085681,-2.985195923,10493.113,-5.16E-11,199.9144471,-5.8115625,0,1.665062335,90.00000001 +239.39,50.30085681,-2.98516791,10493.171,-6.25E-12,199.916233,-5.788125,0,1.658036784,90.00000001 +239.4,50.30085681,-2.985139896,10493.2288,-1.41E-11,199.9175729,-5.7634375,0,1.651011176,90.00000001 +239.41,50.30085681,-2.985111882,10493.2863,-9.22E-11,199.9175747,-5.738125,0,1.643985624,90.00000001 +239.42,50.30085681,-2.985083869,10493.3435,-1.67E-10,199.9177995,-5.7134375,0,1.636960016,90.00000001 +239.43,50.30085681,-2.985055855,10493.4006,-1.61E-10,199.9189164,-5.6884375,0,1.629934465,90.00000001 +239.44,50.30085681,-2.985027841,10493.4573,-7.50E-11,199.9200332,-5.663125,0,1.622908856,90.00000001 +239.45,50.30085681,-2.984999827,10493.5138,1.87E-11,199.92115,-5.63875,0,1.615883305,90.00000001 +239.46,50.30085681,-2.984971813,10493.5701,5.78E-11,199.9222669,-5.615,0,1.608857697,90.00000001 +239.47,50.30085681,-2.984943798,10493.6261,3.59E-11,199.9224916,-5.5915625,0,1.601832145,90.00000001 +239.48,50.30085681,-2.984915784,10493.6819,-1.56E-12,199.9222704,-5.568125,0,1.594806537,90.00000001 +239.49,50.30085681,-2.98488777,10493.7375,4.69E-12,199.9227181,-5.543125,0,1.587780986,90.00000001 +239.5,50.30085681,-2.984859755,10493.7928,4.38E-11,199.9233889,-5.516875,0,1.580755377,90.00000001 +239.51,50.30085681,-2.984831741,10493.8478,4.22E-11,199.9236136,-5.491875,0,1.573729826,90.00000001 +239.52,50.30085681,-2.984803726,10493.9026,-1.09E-11,199.9240614,-5.4684375,0,1.566704217,90.00000001 +239.53,50.30085681,-2.984775712,10493.9572,-5.78E-11,199.9256242,-5.4446875,0,1.559678666,90.00000001 +239.54,50.30085681,-2.984747697,10494.0115,-7.34E-11,199.92741,-5.42,0,1.552653058,90.00000001 +239.55,50.30085681,-2.984719681,10494.0656,-7.50E-11,199.9280807,-5.395,0,1.545627507,90.00000001 +239.56,50.30085681,-2.984691667,10494.1194,-7.34E-11,199.9283054,-5.37,0,1.538601898,90.00000001 +239.57,50.30085681,-2.984663651,10494.173,-6.72E-11,199.9287531,-5.345,0,1.531576347,90.00000001 +239.58,50.30085681,-2.984635636,10494.2263,-5.78E-11,199.9292008,-5.32,0,1.524550738,90.00000001 +239.59,50.30085681,-2.984607621,10494.2794,-4.22E-11,199.9298715,-5.2953125,0,1.517525187,90.00000001 +239.6,50.30085681,-2.984579605,10494.3322,-3.12E-12,199.9305422,-5.2715625,0,1.510499579,90.00000001 +239.61,50.30085681,-2.98455159,10494.3848,4.22E-11,199.9307668,-5.248125,0,1.503474028,90.00000001 +239.62,50.30085681,-2.984523574,10494.4372,2.66E-11,199.9309915,-5.2234375,0,1.496448419,90.00000001 +239.63,50.30085681,-2.984495559,10494.4893,-6.72E-11,199.9318852,-5.198125,0,1.489422868,90.00000001 +239.64,50.30085681,-2.984467543,10494.5411,-1.67E-10,199.9332249,-5.17375,0,1.482397259,90.00000001 +239.65,50.30085681,-2.984439527,10494.5928,-2.16E-10,199.9341185,-5.1496875,0,1.475371708,90.00000001 +239.66,50.30085681,-2.984411511,10494.6441,-2.25E-10,199.9343431,-5.125,0,1.4683461,90.00000001 +239.67,50.30085681,-2.984383495,10494.6953,-2.16E-10,199.9345677,-5.1003125,0,1.461320549,90.00000001 +239.68,50.30085681,-2.984355479,10494.7461,-1.67E-10,199.9354614,-5.07625,0,1.45429494,90.00000001 +239.69,50.30085681,-2.984327463,10494.7968,-6.72E-11,199.936578,-5.051875,0,1.447269389,90.00000001 +239.7,50.30085681,-2.984299446,10494.8472,2.66E-11,199.9368026,-5.0265625,0,1.44024378,90.00000001 +239.71,50.30085681,-2.98427143,10494.8973,4.06E-11,199.9368042,-5.001875,0,1.433218229,90.00000001 +239.72,50.30085681,-2.984243414,10494.9472,-1.56E-12,199.9379208,-4.978125,0,1.426192621,90.00000001 +239.73,50.30085681,-2.984215397,10494.9969,-1.56E-12,199.9390374,-4.9534375,0,1.41916707,90.00000001 +239.74,50.30085681,-2.98418738,10495.0463,7.66E-11,199.939039,-4.928125,0,1.412141461,90.00000001 +239.75,50.30085681,-2.984159364,10495.0954,1.69E-10,199.9392635,-4.90375,0,1.40511591,90.00000001 +239.76,50.30085681,-2.984131347,10495.1444,2.06E-10,199.9403801,-4.88,0,1.398090359,90.00000001 +239.77,50.30085681,-2.98410333,10495.193,1.69E-10,199.9414967,-4.85625,0,1.39106475,90.00000001 +239.78,50.30085681,-2.984075313,10495.2415,7.66E-11,199.9426133,-4.831875,0,1.384039199,90.00000001 +239.79,50.30085681,-2.984047296,10495.2897,-1.09E-11,199.9437299,-4.80625,0,1.377013591,90.00000001 +239.8,50.30085681,-2.984019278,10495.3376,-4.84E-11,199.9437314,-4.7803125,0,1.369988039,90.00000001 +239.81,50.30085681,-2.983991261,10495.3853,-4.38E-11,199.9428408,-4.7553125,0,1.362962431,90.00000001 +239.82,50.30085681,-2.983963244,10495.4327,-1.09E-11,199.9428423,-4.7315625,0,1.35593688,90.00000001 +239.83,50.30085681,-2.983935227,10495.4799,3.75E-11,199.9439588,-4.7084375,0,1.348911271,90.00000001 +239.84,50.30085681,-2.983907209,10495.5269,7.50E-11,199.9448523,-4.6846875,0,1.34188572,90.00000001 +239.85,50.30085681,-2.983879192,10495.5736,8.91E-11,199.9452998,-4.66,0,1.334860112,90.00000001 +239.86,50.30085681,-2.983851174,10495.6201,8.28E-11,199.9461933,-4.635,0,1.32783456,90.00000001 +239.87,50.30085681,-2.983823157,10495.6663,6.72E-11,199.9473099,-4.61,0,1.320808952,90.00000001 +239.88,50.30085681,-2.983795138,10495.7123,5.16E-11,199.9475343,-4.5853125,0,1.313783401,90.00000001 +239.89,50.30085681,-2.983767121,10495.758,9.37E-12,199.9473127,-4.56125,0,1.306757792,90.00000001 +239.9,50.30085681,-2.983739103,10495.8035,-8.44E-11,199.9479832,-4.536875,0,1.299732241,90.00000001 +239.91,50.30085681,-2.983711085,10495.8488,-1.77E-10,199.9495457,-4.5115625,0,1.292706633,90.00000001 +239.92,50.30085681,-2.983683067,10495.8937,-1.91E-10,199.9508852,-4.486875,0,1.285681081,90.00000001 +239.93,50.30085681,-2.983655048,10495.9385,-1.39E-10,199.9511096,-4.4634375,0,1.278655473,90.00000001 +239.94,50.30085681,-2.98362703,10495.983,-9.22E-11,199.950888,-4.4396875,0,1.271629922,90.00000001 +239.95,50.30085681,-2.983599012,10496.0273,-7.66E-11,199.9513354,-4.415,0,1.264604313,90.00000001 +239.96,50.30085681,-2.983570993,10496.0713,-7.50E-11,199.9520058,-4.39,0,1.257578762,90.00000001 +239.97,50.30085681,-2.983542975,10496.1151,-7.50E-11,199.9522302,-4.365,0,1.250553154,90.00000001 +239.98,50.30085681,-2.983514956,10496.1586,-7.50E-11,199.9522315,-4.34,0,1.243527602,90.00000001 +239.99,50.30085681,-2.983486938,10496.2019,-7.66E-11,199.9524559,-4.315,0,1.236501994,90.00000001 +240,50.30085681,-2.983458919,10496.2449,-8.28E-11,199.9535723,-4.29,0,1.229476443,90.00000001 +240.01,50.30085681,-2.983430901,10496.2877,-8.28E-11,199.9553578,-4.2653125,0,1.222450834,90.00000001 +240.02,50.30085681,-2.983402881,10496.3302,-5.00E-11,199.9560281,-4.2415625,0,1.215425283,90.00000001 +240.03,50.30085681,-2.983374862,10496.3725,1.09E-11,199.9555834,-4.2184375,0,1.208399674,90.00000001 +240.04,50.30085681,-2.983346844,10496.4146,5.78E-11,199.9560308,-4.1946875,0,1.201374123,90.00000001 +240.05,50.30085681,-2.983318824,10496.4564,7.50E-11,199.9569241,-4.17,0,1.194348515,90.00000001 +240.06,50.30085681,-2.983290805,10496.498,8.44E-11,199.9569254,-4.145,0,1.187322964,90.00000001 +240.07,50.30085681,-2.983262786,10496.5393,9.84E-11,199.9571497,-4.12,0,1.180297355,90.00000001 +240.08,50.30085681,-2.983234767,10496.5804,1.06E-10,199.9580431,-4.095,0,1.173271804,90.00000001 +240.09,50.30085681,-2.983206747,10496.6212,9.84E-11,199.9582673,-4.07,0,1.166246195,90.00000001 +240.1,50.30085681,-2.983178728,10496.6618,7.66E-11,199.9582686,-4.0453125,0,1.159220644,90.00000001 +240.11,50.30085681,-2.983150709,10496.7021,3.59E-11,199.959608,-4.0215625,0,1.152195036,90.00000001 +240.12,50.30085681,-2.983122689,10496.7422,-1.09E-11,199.9613933,-3.998125,0,1.145169485,90.00000001 +240.13,50.30085681,-2.983094669,10496.7821,-2.03E-11,199.9616176,-3.973125,0,1.138143876,90.00000001 +240.14,50.30085681,-2.983066649,10496.8217,4.69E-12,199.9607268,-3.946875,0,1.131118325,90.00000001 +240.15,50.30085681,-2.98303863,10496.861,3.12E-12,199.960728,-3.921875,0,1.124092716,90.00000001 +240.16,50.30085681,-2.98301061,10496.9001,-3.59E-11,199.9618443,-3.8984375,0,1.117067165,90.00000001 +240.17,50.30085681,-2.98298259,10496.939,-6.72E-11,199.9627375,-3.8746875,0,1.110041557,90.00000001 +240.18,50.30085681,-2.98295457,10496.9776,-7.50E-11,199.9629618,-3.85,0,1.103016006,90.00000001 +240.19,50.30085681,-2.98292655,10497.016,-6.72E-11,199.963186,-3.8253125,0,1.095990397,90.00000001 +240.2,50.30085681,-2.98289853,10497.0541,-3.59E-11,199.9638562,-3.8015625,0,1.088964846,90.00000001 +240.21,50.30085681,-2.98287051,10497.092,1.56E-12,199.9643034,-3.778125,0,1.081939237,90.00000001 +240.22,50.30085681,-2.982842489,10497.1297,-4.69E-12,199.9640816,-3.753125,0,1.074913686,90.00000001 +240.23,50.30085681,-2.98281447,10497.1671,-4.37E-11,199.9643058,-3.726875,0,1.067888078,90.00000001 +240.24,50.30085681,-2.982786449,10497.2042,-4.22E-11,199.965422,-3.701875,0,1.060862527,90.00000001 +240.25,50.30085681,-2.982758429,10497.2411,1.09E-11,199.9663152,-3.6784375,0,1.053836918,90.00000001 +240.26,50.30085681,-2.982730408,10497.2778,5.78E-11,199.9665394,-3.6546875,0,1.046811367,90.00000001 +240.27,50.30085681,-2.982702388,10497.3142,7.34E-11,199.9667635,-3.63,0,1.039785758,90.00000001 +240.28,50.30085681,-2.982674367,10497.3504,7.50E-11,199.9676567,-3.605,0,1.032760207,90.00000001 +240.29,50.30085681,-2.982646347,10497.3863,7.50E-11,199.9687729,-3.58,0,1.025734599,90.00000001 +240.3,50.30085681,-2.982618325,10497.422,7.66E-11,199.968997,-3.555,0,1.018709048,90.00000001 +240.31,50.30085681,-2.982590305,10497.4574,8.28E-11,199.9687751,-3.53,0,1.011683439,90.00000001 +240.32,50.30085681,-2.982562284,10497.4926,8.28E-11,199.9692222,-3.5053125,0,1.004657888,90.00000001 +240.33,50.30085681,-2.982534263,10497.5275,5.16E-11,199.9698924,-3.4815625,0,0.997632279,90.00000001 +240.34,50.30085681,-2.982506242,10497.5622,-3.13E-12,199.9701165,-3.4584375,0,0.990606728,90.00000001 +240.35,50.30085681,-2.982478221,10497.5967,-4.22E-11,199.9703406,-3.4346875,0,0.98358112,90.00000001 +240.36,50.30085681,-2.9824502,10497.6309,-5.78E-11,199.9712337,-3.41,0,0.976555569,90.00000001 +240.37,50.30085681,-2.982422179,10497.6649,-6.72E-11,199.9723498,-3.385,0,0.96952996,90.00000001 +240.38,50.30085681,-2.982394157,10497.6986,-7.34E-11,199.9723509,-3.36,0,0.962504409,90.00000001 +240.39,50.30085681,-2.982366136,10497.7321,-7.50E-11,199.9714599,-3.335,0,0.9554788,90.00000001 +240.4,50.30085681,-2.982338115,10497.7653,-7.34E-11,199.9714609,-3.31,0,0.948453249,90.00000001 +240.41,50.30085681,-2.982310094,10497.7983,-5.78E-11,199.972577,-3.2853125,0,0.941427641,90.00000001 +240.42,50.30085681,-2.982282072,10497.831,-1.09E-11,199.9734701,-3.2615625,0,0.93440209,90.00000001 +240.43,50.30085681,-2.982254051,10497.8635,4.22E-11,199.9736941,-3.238125,0,0.927376481,90.00000001 +240.44,50.30085681,-2.982226029,10497.8958,4.38E-11,199.9739181,-3.213125,0,0.92035093,90.00000001 +240.45,50.30085681,-2.982198008,10497.9278,4.69E-12,199.9745882,-3.186875,0,0.913325321,90.00000001 +240.46,50.30085681,-2.982169986,10497.9595,-1.56E-12,199.9752582,-3.161875,0,0.90629977,90.00000001 +240.47,50.30085681,-2.982141964,10497.991,3.59E-11,199.9757052,-3.1384375,0,0.899274162,90.00000001 +240.48,50.30085681,-2.982113943,10498.0223,6.72E-11,199.9761522,-3.1146875,0,0.892248611,90.00000001 +240.49,50.30085681,-2.98208592,10498.0533,7.50E-11,199.9761532,-3.09,0,0.885223002,90.00000001 +240.5,50.30085681,-2.982057899,10498.0841,7.66E-11,199.9759311,-3.065,0,0.878197451,90.00000001 +240.51,50.30085681,-2.982029877,10498.1146,8.28E-11,199.9763781,-3.04,0,0.871171842,90.00000001 +240.52,50.30085681,-2.982001855,10498.1449,8.13E-11,199.9770481,-3.0153125,0,0.864146291,90.00000001 +240.53,50.30085681,-2.981973833,10498.1749,4.22E-11,199.977272,-2.9915625,0,0.857120683,90.00000001 +240.54,50.30085681,-2.981945811,10498.2047,-2.66E-11,199.977496,-2.9684375,0,0.850095132,90.00000001 +240.55,50.30085681,-2.981917789,10498.2343,-7.19E-11,199.978389,-2.9446875,0,0.843069523,90.00000001 +240.56,50.30085681,-2.981889767,10498.2636,-6.41E-11,199.979728,-2.9196875,0,0.836043972,90.00000001 +240.57,50.30085681,-2.981861744,10498.2927,-4.69E-12,199.9806209,-2.89375,0,0.829018363,90.00000001 +240.58,50.30085681,-2.981833722,10498.3215,9.06E-11,199.9806218,-2.868125,0,0.821992812,90.00000001 +240.59,50.30085681,-2.981805699,10498.35,1.75E-10,199.9799537,-2.84375,0,0.814967204,90.00000001 +240.6,50.30085681,-2.981777677,10498.3784,2.00E-10,199.9795085,-2.82,0,0.807941652,90.00000001 +240.61,50.30085681,-2.981749655,10498.4064,1.53E-10,199.9799554,-2.79625,0,0.800916044,90.00000001 +240.62,50.30085681,-2.981721632,10498.4343,6.09E-11,199.9806254,-2.771875,0,0.793890493,90.00000001 +240.63,50.30085681,-2.98169361,10498.4619,-9.37E-12,199.9808492,-2.7465625,0,0.786864884,90.00000001 +240.64,50.30085681,-2.981665587,10498.4892,-3.12E-12,199.9810731,-2.721875,0,0.779839333,90.00000001 +240.65,50.30085681,-2.981637565,10498.5163,4.06E-11,199.981743,-2.698125,0,0.772813725,90.00000001 +240.66,50.30085681,-2.981609542,10498.5432,3.44E-11,199.9821899,-2.673125,0,0.765788173,90.00000001 +240.67,50.30085681,-2.981581519,10498.5698,-1.88E-11,199.9819677,-2.646875,0,0.758762565,90.00000001 +240.68,50.30085681,-2.981553497,10498.5961,-3.28E-11,199.9821915,-2.621875,0,0.751737014,90.00000001 +240.69,50.30085681,-2.981525474,10498.6222,1.25E-11,199.9833074,-2.5984375,0,0.744711405,90.00000001 +240.7,50.30085681,-2.981497451,10498.6481,5.00E-11,199.9842003,-2.575,0,0.737685854,90.00000001 +240.71,50.30085681,-2.981469428,10498.6737,3.44E-11,199.9844241,-2.5515625,0,0.730660246,90.00000001 +240.72,50.30085681,-2.981441405,10498.6991,-3.13E-12,199.9844249,-2.528125,0,0.723634694,90.00000001 +240.73,50.30085681,-2.981413382,10498.7243,-4.69E-12,199.9844256,-2.503125,0,0.716609086,90.00000001 +240.74,50.30085681,-2.981385359,10498.7492,1.88E-11,199.9844264,-2.476875,0,0.709583535,90.00000001 +240.75,50.30085681,-2.981357336,10498.7738,3.13E-12,199.9844272,-2.451875,0,0.702557984,90.00000001 +240.76,50.30085681,-2.981329313,10498.7982,-4.06E-11,199.984428,-2.428125,0,0.695532375,90.00000001 +240.77,50.30085681,-2.98130129,10498.8224,-2.66E-11,199.9846517,-2.4034375,0,0.688506824,90.00000001 +240.78,50.30085681,-2.981273267,10498.8463,6.72E-11,199.9855445,-2.378125,0,0.681481215,90.00000001 +240.79,50.30085681,-2.981245244,10498.8699,1.67E-10,199.9868833,-2.35375,0,0.674455664,90.00000001 +240.8,50.30085681,-2.98121722,10498.8934,2.16E-10,199.9877761,-2.3296875,0,0.667430056,90.00000001 +240.81,50.30085681,-2.981189197,10498.9165,2.25E-10,199.9877769,-2.305,0,0.660404505,90.00000001 +240.82,50.30085681,-2.981161173,10498.9395,2.17E-10,199.9871085,-2.2803125,0,0.653378896,90.00000001 +240.83,50.30085681,-2.98113315,10498.9621,1.77E-10,199.9866632,-2.25625,0,0.646353345,90.00000001 +240.84,50.30085681,-2.981105127,10498.9846,9.22E-11,199.9871099,-2.231875,0,0.639327736,90.00000001 +240.85,50.30085681,-2.981077103,10499.0068,1.41E-11,199.9877797,-2.2065625,0,0.632302185,90.00000001 +240.86,50.30085681,-2.98104908,10499.0287,6.25E-12,199.9880034,-2.181875,0,0.625276577,90.00000001 +240.87,50.30085681,-2.981021056,10499.0504,5.16E-11,199.9882271,-2.1584375,0,0.618251026,90.00000001 +240.88,50.30085681,-2.980993033,10499.0719,8.28E-11,199.9888968,-2.1346875,0,0.611225417,90.00000001 +240.89,50.30085681,-2.980965009,10499.0931,8.28E-11,199.9893435,-2.11,0,0.604199866,90.00000001 +240.9,50.30085681,-2.980936985,10499.1141,7.66E-11,199.9891211,-2.085,0,0.597174257,90.00000001 +240.91,50.30085681,-2.980908962,10499.1348,7.50E-11,199.9891218,-2.06,0,0.590148706,90.00000001 +240.92,50.30085681,-2.980880938,10499.1553,7.50E-11,199.9893454,-2.035,0,0.583123098,90.00000001 +240.93,50.30085681,-2.980852914,10499.1755,7.34E-11,199.989123,-2.01,0,0.576097547,90.00000001 +240.94,50.30085681,-2.980824891,10499.1955,5.78E-11,199.9893467,-1.9853125,0,0.569071938,90.00000001 +240.95,50.30085681,-2.980796867,10499.2152,1.09E-11,199.9904624,-1.9615625,0,0.562046387,90.00000001 +240.96,50.30085681,-2.980768843,10499.2347,-4.06E-11,199.991355,-1.938125,0,0.555020778,90.00000001 +240.97,50.30085681,-2.980740819,10499.254,-3.44E-11,199.9915786,-1.913125,0,0.547995227,90.00000001 +240.98,50.30085681,-2.980712795,10499.273,1.88E-11,199.9915792,-1.886875,0,0.540969619,90.00000001 +240.99,50.30085681,-2.980684771,10499.2917,3.28E-11,199.9915798,-1.861875,0,0.533944068,90.00000001 +241,50.30085681,-2.980656747,10499.3102,-1.25E-11,199.9915804,-1.8384375,0,0.526918459,90.00000001 +241.01,50.30085681,-2.980628723,10499.3285,-5.00E-11,199.991581,-1.815,0,0.519892908,90.00000001 +241.02,50.30085681,-2.980600699,10499.3465,-2.50E-11,199.9915815,-1.79125,0,0.512867299,90.00000001 +241.03,50.30085681,-2.980572675,10499.3643,5.94E-11,199.9915821,-1.766875,0,0.505841748,90.00000001 +241.04,50.30085681,-2.980544651,10499.3819,1.45E-10,199.9918056,-1.7415625,0,0.49881614,90.00000001 +241.05,50.30085681,-2.980516627,10499.3991,1.59E-10,199.9924752,-1.7165625,0,0.491790589,90.00000001 +241.06,50.30085681,-2.980488603,10499.4162,8.13E-11,199.9929218,-1.6921875,0,0.48476498,90.00000001 +241.07,50.30085681,-2.980460578,10499.433,-4.37E-11,199.9926993,-1.6678125,0,0.477739429,90.00000001 +241.08,50.30085681,-2.980432555,10499.4495,-1.44E-10,199.9926998,-1.6434375,0,0.47071382,90.00000001 +241.09,50.30085681,-2.98040453,10499.4659,-1.59E-10,199.9931463,-1.6184375,0,0.463688269,90.00000001 +241.1,50.30085681,-2.980376506,10499.4819,-8.91E-11,199.9935929,-1.593125,0,0.456662661,90.00000001 +241.11,50.30085681,-2.980348482,10499.4977,1.56E-12,199.9940394,-1.56875,0,0.44963711,90.00000001 +241.12,50.30085681,-2.980320457,10499.5133,4.06E-11,199.9940399,-1.545,0,0.442611501,90.00000001 +241.13,50.30085681,-2.980292433,10499.5286,1.56E-12,199.9938174,-1.52125,0,0.43558595,90.00000001 +241.14,50.30085681,-2.980264409,10499.5437,-9.06E-11,199.9942638,-1.496875,0,0.428560341,90.00000001 +241.15,50.30085681,-2.980236384,10499.5586,-1.69E-10,199.9949334,-1.4715625,0,0.42153479,90.00000001 +241.16,50.30085681,-2.98020836,10499.5731,-1.67E-10,199.9951568,-1.4465625,0,0.414509182,90.00000001 +241.17,50.30085681,-2.980180335,10499.5875,-7.34E-11,199.9951573,-1.4221875,0,0.40748363,90.00000001 +241.18,50.30085681,-2.980152311,10499.6016,6.72E-11,199.9951577,-1.3978125,0,0.400458022,90.00000001 +241.19,50.30085681,-2.980124286,10499.6154,1.73E-10,199.9951581,-1.3734375,0,0.393432471,90.00000001 +241.2,50.30085681,-2.980096262,10499.6291,1.75E-10,199.9951586,-1.3484375,0,0.386406862,90.00000001 +241.21,50.30085681,-2.980068237,10499.6424,8.28E-11,199.995382,-1.323125,0,0.379381311,90.00000001 +241.22,50.30085681,-2.980040213,10499.6555,-1.72E-11,199.9962745,-1.29875,0,0.372355703,90.00000001 +241.23,50.30085681,-2.980012188,10499.6684,-5.62E-11,199.9973899,-1.275,0,0.365330151,90.00000001 +241.24,50.30085681,-2.979984163,10499.681,-2.66E-11,199.9973903,-1.2515625,0,0.358304543,90.00000001 +241.25,50.30085681,-2.979956138,10499.6934,2.66E-11,199.9962757,-1.228125,0,0.351278992,90.00000001 +241.26,50.30085681,-2.979928114,10499.7056,3.59E-11,199.995384,-1.203125,0,0.344253383,90.00000001 +241.27,50.30085681,-2.979900089,10499.7175,3.12E-12,199.9953843,-1.176875,0,0.337227832,90.00000001 +241.28,50.30085681,-2.979872065,10499.7291,-3.13E-12,199.9962768,-1.151875,0,0.330202224,90.00000001 +241.29,50.30085681,-2.97984404,10499.7405,2.81E-11,199.9973922,-1.1284375,0,0.323176672,90.00000001 +241.3,50.30085681,-2.979816015,10499.7517,5.16E-11,199.9973925,-1.1046875,0,0.316151064,90.00000001 +241.31,50.30085681,-2.97978799,10499.7626,5.94E-11,199.9965008,-1.08,0,0.309125513,90.00000001 +241.32,50.30085681,-2.979759966,10499.7733,6.72E-11,199.9965012,-1.055,0,0.302099904,90.00000001 +241.33,50.30085681,-2.979731941,10499.7837,7.34E-11,199.9976166,-1.03,0,0.295074353,90.00000001 +241.34,50.30085681,-2.979703916,10499.7939,7.66E-11,199.9985089,-1.005,0,0.288048745,90.00000001 +241.35,50.30085681,-2.979675891,10499.8038,8.28E-11,199.9987323,-0.98,0,0.281023193,90.00000001 +241.36,50.30085681,-2.979647866,10499.8135,8.28E-11,199.9985095,-0.9553125,0,0.273997585,90.00000001 +241.37,50.30085681,-2.979619841,10499.8229,5.16E-11,199.9976178,-0.9315625,0,0.266972034,90.00000001 +241.38,50.30085681,-2.979591816,10499.8321,6.25E-12,199.996503,-0.908125,0,0.259946425,90.00000001 +241.39,50.30085681,-2.979563792,10499.8411,4.69E-12,199.9965033,-0.883125,0,0.252920874,90.00000001 +241.4,50.30085681,-2.979535767,10499.8498,3.59E-11,199.9976186,-0.856875,0,0.245895266,90.00000001 +241.41,50.30085681,-2.979507742,10499.8582,2.66E-11,199.9985109,-0.831875,0,0.238869714,90.00000001 +241.42,50.30085681,-2.979479717,10499.8664,-2.66E-11,199.9987342,-0.8084375,0,0.231844106,90.00000001 +241.43,50.30085681,-2.979451692,10499.8744,-5.63E-11,199.9987345,-0.785,0,0.224818555,90.00000001 +241.44,50.30085681,-2.979423667,10499.8821,-1.87E-11,199.9987347,-0.76125,0,0.217792946,90.00000001 +241.45,50.30085681,-2.979395642,10499.8896,7.34E-11,199.9987349,-0.736875,0,0.210767395,90.00000001 +241.46,50.30085681,-2.979367617,10499.8969,1.52E-10,199.9987352,-0.7115625,0,0.203741787,90.00000001 +241.47,50.30085681,-2.979339592,10499.9038,1.42E-10,199.9987354,-0.6865625,0,0.196716235,90.00000001 +241.48,50.30085681,-2.979311567,10499.9106,4.22E-11,199.9987356,-0.6621875,0,0.189690627,90.00000001 +241.49,50.30085681,-2.979283542,10499.9171,-9.06E-11,199.9987358,-0.6378125,0,0.182665076,90.00000001 +241.5,50.30085681,-2.979255517,10499.9233,-1.83E-10,199.998736,-0.6134375,0,0.175639467,90.00000001 +241.51,50.30085681,-2.979227492,10499.9294,-1.77E-10,199.9987362,-0.5884375,0,0.168613916,90.00000001 +241.52,50.30085681,-2.979199467,10499.9351,-8.28E-11,199.9987364,-0.563125,0,0.161588308,90.00000001 +241.53,50.30085681,-2.979171442,10499.9406,1.72E-11,199.9987365,-0.53875,0,0.154562756,90.00000001 +241.54,50.30085681,-2.979143417,10499.9459,5.62E-11,199.9989597,-0.515,0,0.147537148,90.00000001 +241.55,50.30085681,-2.979115392,10499.9509,1.72E-11,199.9998519,-0.49125,0,0.140511597,90.00000001 +241.56,50.30085681,-2.979087367,10499.9557,-8.28E-11,200.0009671,-0.466875,0,0.133485988,90.00000001 +241.57,50.30085681,-2.979059341,10499.9603,-1.77E-10,200.0009673,-0.4415625,0,0.126460437,90.00000001 +241.58,50.30085681,-2.979031316,10499.9645,-1.83E-10,199.9998523,-0.4165625,0,0.119434829,90.00000001 +241.59,50.30085681,-2.979003291,10499.9686,-9.06E-11,199.9991834,-0.3921875,0,0.112409277,90.00000001 +241.6,50.30085681,-2.978975266,10499.9724,4.22E-11,199.9998526,-0.3678125,0,0.105383669,90.00000001 +241.61,50.30085681,-2.978947241,10499.9759,1.42E-10,200.0009678,-0.3434375,0,0.098358118,90.00000001 +241.62,50.30085681,-2.978919215,10499.9793,1.52E-10,200.0009679,-0.3184375,0,0.091332509,90.00000001 +241.63,50.30085681,-2.97889119,10499.9823,7.34E-11,199.9998529,-0.293125,0,0.084306958,90.00000001 +241.64,50.30085681,-2.978863165,10499.9851,-1.87E-11,199.9989609,-0.26875,0,0.07728135,90.00000001 +241.65,50.30085681,-2.97883514,10499.9877,-5.62E-11,199.998738,-0.245,0,0.070255798,90.00000001 +241.66,50.30085681,-2.978807115,10499.99,-2.66E-11,199.9987381,-0.2215625,0,0.06323019,90.00000001 +241.67,50.30085681,-2.97877909,10499.9921,2.66E-11,199.9989611,-0.198125,0,0.056204639,90.00000001 +241.68,50.30085681,-2.978751065,10499.994,3.59E-11,199.9998533,-0.173125,0,0.04917903,90.00000001 +241.69,50.30085681,-2.97872304,10499.9956,4.69E-12,200.0009684,-0.146875,0,0.042153479,90.00000001 +241.7,50.30085681,-2.978695014,10499.9969,6.25E-12,200.0009684,-0.121875,0,0.035127871,90.00000001 +241.71,50.30085681,-2.978666989,10499.998,5.16E-11,199.9998534,-0.0984375,0,0.028102319,90.00000001 +241.72,50.30085681,-2.978638964,10499.9989,8.28E-11,199.9989614,-0.0746875,0,0.021076711,90.00000001 +241.73,50.30085681,-2.978610939,10499.9995,9.22E-11,199.9989614,-0.0503125,0,0.01405116,90.00000001 +241.74,50.30085681,-2.978582914,10499.9999,8.59E-11,199.9998534,-0.0278125,0,0.007025551,90.00000001 +241.75,50.30085681,-2.978554889,10500,3.75E-11,200.0009685,-0.01125,0,0.001170954,90.00000001 +241.76,50.30085681,-2.978526863,10500,-9.38E-12,200.0009685,-0.0028125,0,0,90.00000001 +241.77,50.30085681,-2.978498838,10500,-9.38E-12,199.9998535,-0.0003125,0,0,90.00000001 +241.78,50.30085681,-2.978470813,10500,0,199.9989614,0,0,0,90.00000001 +241.79,50.30085681,-2.978442788,10500,0,199.9987384,0,0,0,90.00000001 +241.8,50.30085681,-2.978414763,10500,0,199.9989614,0,0,0,90.00000001 +241.81,50.30085681,-2.978386738,10500,0,199.9998535,0,0,0,90.00000001 +241.82,50.30085681,-2.978358713,10500,0,200.0009685,0,0,0,90.00000001 +241.83,50.30085681,-2.978330687,10500,0,200.0009685,0,0,0,90.00000001 +241.84,50.30085681,-2.978302662,10500,0,199.9998535,0,0,0,90.00000001 +241.85,50.30085681,-2.978274637,10500,0,199.9989614,0,0,0,90.00000001 +241.86,50.30085681,-2.978246612,10500,0,199.9989614,0,0,0,90.00000001 +241.87,50.30085681,-2.978218587,10500,0,199.9998535,0,0,0,90.00000001 +241.88,50.30085681,-2.978190562,10500,0,200.0009685,0,0,0,90.00000001 +241.89,50.30085681,-2.978162536,10500,0,200.0009685,0,0,0,90.00000001 +241.9,50.30085681,-2.978134511,10500,0,199.9998535,0,0,0,90.00000001 +241.91,50.30085681,-2.978106486,10500,0,199.9991844,0,0,0,90.00000001 +241.92,50.30085681,-2.978078461,10500,0,199.9998535,0,0,0,90.00000001 +241.93,50.30085681,-2.978050436,10500,0,200.0009685,0,0,0,90.00000001 +241.94,50.30085681,-2.97802241,10500,0,200.0009685,0,0,0,90.00000001 +241.95,50.30085681,-2.977994385,10500,0,199.9998535,0,0,0,90.00000001 +241.96,50.30085681,-2.97796636,10500,0,199.9991844,0,0,0,90.00000001 +241.97,50.30085681,-2.977938335,10500,0,199.9998535,0,0,0,90.00000001 +241.98,50.30085681,-2.97791031,10500,0,200.0009685,0,0,0,90.00000001 +241.99,50.30085681,-2.977882284,10500,0,200.0009685,0,0,0,90.00000001 +242,50.30085681,-2.977854259,10500,0,199.9998535,0,0,0,90.00000001 +242.01,50.30085681,-2.977826234,10500,0,199.9991844,0,0,0,90.00000001 +242.02,50.30085681,-2.977798209,10500,0,199.9998535,0,0,0,90.00000001 +242.03,50.30085681,-2.977770184,10500,0,200.0009685,0,0,0,90.00000001 +242.04,50.30085681,-2.977742158,10500,0,200.0009685,0,0,0,90.00000001 +242.05,50.30085681,-2.977714133,10500,0,199.9998535,0,0,0,90.00000001 +242.06,50.30085681,-2.977686108,10500,0,199.9991844,0,0,0,90.00000001 +242.07,50.30085681,-2.977658083,10500,0,199.9998535,0,0,0,90.00000001 +242.08,50.30085681,-2.977630058,10500,0,200.0009685,0,0,0,90.00000001 +242.09,50.30085681,-2.977602032,10500,0,200.0009685,0,0,0,90.00000001 +242.1,50.30085681,-2.977574007,10500,0,199.9998535,0,0,0,90.00000001 +242.11,50.30085681,-2.977545982,10500,0,199.9991844,0,0,0,90.00000001 +242.12,50.30085681,-2.977517957,10500,0,199.9998535,0,0,0,90.00000001 +242.13,50.30085681,-2.977489932,10500,0,200.0009685,0,0,0,90.00000001 +242.14,50.30085681,-2.977461906,10500,0,200.0009685,0,0,0,90.00000001 +242.15,50.30085681,-2.977433881,10500,0,199.9998535,0,0,0,90.00000001 +242.16,50.30085681,-2.977405856,10500,0,199.9989614,0,0,0,90.00000001 +242.17,50.30085681,-2.977377831,10500,0,199.9989614,0,0,0,90.00000001 +242.18,50.30085681,-2.977349806,10500,0,199.9998535,0,0,0,90.00000001 +242.19,50.30085681,-2.977321781,10500,0,200.0009685,0,0,0,90.00000001 +242.2,50.30085681,-2.977293755,10500,0,200.0009685,0,0,0,90.00000001 +242.21,50.30085681,-2.97726573,10500,0,199.9998535,0,0,0,90.00000001 +242.22,50.30085681,-2.977237705,10500,0,199.9989614,0,0,0,90.00000001 +242.23,50.30085681,-2.97720968,10500,0,199.9989614,0,0,0,90.00000001 +242.24,50.30085681,-2.977181655,10500,0,199.9998535,0,0,0,90.00000001 +242.25,50.30085681,-2.97715363,10500,0,200.0009685,0,0,0,90.00000001 +242.26,50.30085681,-2.977125604,10500,0,200.0009685,0,0,0,90.00000001 +242.27,50.30085681,-2.977097579,10500,0,199.9998535,0,0,0,90.00000001 +242.28,50.30085681,-2.977069554,10500,0,199.9989614,0,0,0,90.00000001 +242.29,50.30085681,-2.977041529,10500,0,199.9989614,0,0,0,90.00000001 +242.3,50.30085681,-2.977013504,10500,0,199.9998535,0,0,0,90.00000001 +242.31,50.30085681,-2.976985479,10500,0,200.0009685,0,0,0,90.00000001 +242.32,50.30085681,-2.976957453,10500,0,200.0009685,0,0,0,90.00000001 +242.33,50.30085681,-2.976929428,10500,0,199.9998535,0,0,0,90.00000001 +242.34,50.30085681,-2.976901403,10500,0,199.9989614,0,0,0,90.00000001 +242.35,50.30085681,-2.976873378,10500,0,199.9987384,0,0,0,90.00000001 +242.36,50.30085681,-2.976845353,10500,0,199.9989614,0,0,0,90.00000001 +242.37,50.30085681,-2.976817328,10500,0,199.9998535,0,0,0,90.00000001 +242.38,50.30085681,-2.976789303,10500,0,200.0009685,0,0,0,90.00000001 +242.39,50.30085681,-2.976761277,10500,0,200.0009685,0,0,0,90.00000001 +242.4,50.30085681,-2.976733252,10500,0,199.9998535,0,0,0,90.00000001 +242.41,50.30085681,-2.976705227,10500,0,199.9989614,0,0,0,90.00000001 +242.42,50.30085681,-2.976677202,10500,0,199.9989614,0,0,0,90.00000001 +242.43,50.30085681,-2.976649177,10500,0,199.9998535,0,0,0,90.00000001 +242.44,50.30085681,-2.976621152,10500,0,200.0009685,0,0,0,90.00000001 +242.45,50.30085681,-2.976593126,10500,0,200.0009685,0,0,0,90.00000001 +242.46,50.30085681,-2.976565101,10500,0,199.9998535,0,0,0,90.00000001 +242.47,50.30085681,-2.976537076,10500,0,199.9989614,0,0,0,90.00000001 +242.48,50.30085681,-2.976509051,10500,0,199.9989614,0,0,0,90.00000001 +242.49,50.30085681,-2.976481026,10500,0,199.9998535,0,0,0,90.00000001 +242.5,50.30085681,-2.976453001,10500,0,200.0009685,0,0,0,90.00000001 +242.51,50.30085681,-2.976424975,10500,0,200.0009685,0,0,0,90.00000001 +242.52,50.30085681,-2.97639695,10500,0,199.9998535,0,0,0,90.00000001 +242.53,50.30085681,-2.976368925,10500,0,199.9991844,0,0,0,90.00000001 +242.54,50.30085681,-2.9763409,10500,0,199.9998535,0,0,0,90.00000001 +242.55,50.30085681,-2.976312875,10500,0,200.0009685,0,0,0,90.00000001 +242.56,50.30085681,-2.976284849,10500,0,200.0009685,0,0,0,90.00000001 +242.57,50.30085681,-2.976256824,10500,0,199.9998535,0,0,0,90.00000001 +242.58,50.30085681,-2.976228799,10500,0,199.9991844,0,0,0,90.00000001 +242.59,50.30085681,-2.976200774,10500,0,199.9998535,0,0,0,90.00000001 +242.6,50.30085681,-2.976172749,10500,0,200.0009685,0,0,0,90.00000001 +242.61,50.30085681,-2.976144723,10500,0,200.0009685,0,0,0,90.00000001 +242.62,50.30085681,-2.976116698,10500,0,199.9998535,0,0,0,90.00000001 +242.63,50.30085681,-2.976088673,10500,0,199.9991844,0,0,0,90.00000001 +242.64,50.30085681,-2.976060648,10500,0,199.9998535,0,0,0,90.00000001 +242.65,50.30085681,-2.976032623,10500,0,200.0009685,0,0,0,90.00000001 +242.66,50.30085681,-2.976004597,10500,0,200.0009685,0,0,0,90.00000001 +242.67,50.30085681,-2.975976572,10500,0,199.9998535,0,0,0,90.00000001 +242.68,50.30085681,-2.975948547,10500,0,199.9991844,0,0,0,90.00000001 +242.69,50.30085681,-2.975920522,10500,0,199.9998535,0,0,0,90.00000001 +242.7,50.30085681,-2.975892497,10500,0,200.0009685,0,0,0,90.00000001 +242.71,50.30085681,-2.975864471,10500,0,200.0009685,0,0,0,90.00000001 +242.72,50.30085681,-2.975836446,10500,0,199.9998535,0,0,0,90.00000001 +242.73,50.30085681,-2.975808421,10500,0,199.9991844,0,0,0,90.00000001 +242.74,50.30085681,-2.975780396,10500,0,199.9998535,0,0,0,90.00000001 +242.75,50.30085681,-2.975752371,10500,0,200.0009685,0,0,0,90.00000001 +242.76,50.30085681,-2.975724345,10500,0,200.0009685,0,0,0,90.00000001 +242.77,50.30085681,-2.97569632,10500,0,199.9998535,0,0,0,90.00000001 +242.78,50.30085681,-2.975668295,10500,0,199.9989614,0,0,0,90.00000001 +242.79,50.30085681,-2.97564027,10500,0,199.9989614,0,0,0,90.00000001 +242.8,50.30085681,-2.975612245,10500,0,199.9998535,0,0,0,90.00000001 +242.81,50.30085681,-2.97558422,10500,0,200.0009685,0,0,0,90.00000001 +242.82,50.30085681,-2.975556194,10500,0,200.0009685,0,0,0,90.00000001 +242.83,50.30085681,-2.975528169,10500,0,199.9998535,0,0,0,90.00000001 +242.84,50.30085681,-2.975500144,10500,0,199.9989614,0,0,0,90.00000001 +242.85,50.30085681,-2.975472119,10500,0,199.9989614,0,0,0,90.00000001 +242.86,50.30085681,-2.975444094,10500,0,199.9998535,0,0,0,90.00000001 +242.87,50.30085681,-2.975416069,10500,0,200.0009685,0,0,0,90.00000001 +242.88,50.30085681,-2.975388043,10500,0,200.0009685,0,0,0,90.00000001 +242.89,50.30085681,-2.975360018,10500,0,199.9998535,0,0,0,90.00000001 +242.9,50.30085681,-2.975331993,10500,0,199.9989614,0,0,0,90.00000001 +242.91,50.30085681,-2.975303968,10500,0,199.9987384,0,0,0,90.00000001 +242.92,50.30085681,-2.975275943,10500,0,199.9989614,0,0,0,90.00000001 +242.93,50.30085681,-2.975247918,10500,0,199.9998535,0,0,0,90.00000001 +242.94,50.30085681,-2.975219893,10500,0,200.0009685,0,0,0,90.00000001 +242.95,50.30085681,-2.975191867,10500,0,200.0009685,0,0,0,90.00000001 +242.96,50.30085681,-2.975163842,10500,0,199.9998535,0,0,0,90.00000001 +242.97,50.30085681,-2.975135817,10500,0,199.9989614,0,0,0,90.00000001 +242.98,50.30085681,-2.975107792,10500,0,199.9989614,0,0,0,90.00000001 +242.99,50.30085681,-2.975079767,10500,0,199.9998535,0,0,0,90.00000001 +243,50.30085681,-2.975051742,10500,0,200.0009685,0,0,0,90.00000001 +243.01,50.30085681,-2.975023716,10500,0,200.0009685,0,0,0,90.00000001 +243.02,50.30085681,-2.974995691,10500,0,199.9998535,0,0,0,90.00000001 +243.03,50.30085681,-2.974967666,10500,0,199.9989614,0,0,0,90.00000001 +243.04,50.30085681,-2.974939641,10500,0,199.9989614,0,0,0,90.00000001 +243.05,50.30085681,-2.974911616,10500,0,199.9998535,0,0,0,90.00000001 +243.06,50.30085681,-2.974883591,10500,0,200.0009685,0,0,0,90.00000001 +243.07,50.30085681,-2.974855565,10500,0,200.0009685,0,0,0,90.00000001 +243.08,50.30085681,-2.97482754,10500,0,199.9998535,0,0,0,90.00000001 +243.09,50.30085681,-2.974799515,10500,0,199.9989614,0,0,0,90.00000001 +243.1,50.30085681,-2.97477149,10500,0,199.9989614,0,0,0,90.00000001 +243.11,50.30085681,-2.974743465,10500,0,199.9998535,0,0,0,90.00000001 +243.12,50.30085681,-2.97471544,10500,0,200.0009685,0,0,0,90.00000001 +243.13,50.30085681,-2.974687414,10500,0,200.0009685,0,0,0,90.00000001 +243.14,50.30085681,-2.974659389,10500,0,199.9998535,0,0,0,90.00000001 +243.15,50.30085681,-2.974631364,10500,0,199.9991844,0,0,0,90.00000001 +243.16,50.30085681,-2.974603339,10500,0,199.9998535,0,0,0,90.00000001 +243.17,50.30085681,-2.974575314,10500,0,200.0009685,0,0,0,90.00000001 +243.18,50.30085681,-2.974547288,10500,0,200.0009685,0,0,0,90.00000001 +243.19,50.30085681,-2.974519263,10500,0,199.9998535,0,0,0,90.00000001 +243.2,50.30085681,-2.974491238,10500,0,199.9991844,0,0,0,90.00000001 +243.21,50.30085681,-2.974463213,10500,0,199.9998535,0,0,0,90.00000001 +243.22,50.30085681,-2.974435188,10500,0,200.0009685,0,0,0,90.00000001 +243.23,50.30085681,-2.974407162,10500,0,200.0009685,0,0,0,90.00000001 +243.24,50.30085681,-2.974379137,10500,0,199.9998535,0,0,0,90.00000001 +243.25,50.30085681,-2.974351112,10500,0,199.9991844,0,0,0,90.00000001 +243.26,50.30085681,-2.974323087,10500,0,199.9998535,0,0,0,90.00000001 +243.27,50.30085681,-2.974295062,10500,0,200.0009685,0,0,0,90.00000001 +243.28,50.30085681,-2.974267036,10500,0,200.0009685,0,0,0,90.00000001 +243.29,50.30085681,-2.974239011,10500,0,199.9998535,0,0,0,90.00000001 +243.3,50.30085681,-2.974210986,10500,0,199.9991844,0,0,0,90.00000001 +243.31,50.30085681,-2.974182961,10500,0,199.9998535,0,0,0,90.00000001 +243.32,50.30085681,-2.974154936,10500,0,200.0009685,0,0,0,90.00000001 +243.33,50.30085681,-2.97412691,10500,0,200.0009685,0,0,0,90.00000001 +243.34,50.30085681,-2.974098885,10500,0,199.9998535,0,0,0,90.00000001 +243.35,50.30085681,-2.97407086,10500,0,199.9991844,0,0,0,90.00000001 +243.36,50.30085681,-2.974042835,10500,0,199.9998535,0,0,0,90.00000001 +243.37,50.30085681,-2.97401481,10500,0,200.0009685,0,0,0,90.00000001 +243.38,50.30085681,-2.973986784,10500,0,200.0009685,0,0,0,90.00000001 +243.39,50.30085681,-2.973958759,10500,0,199.9998535,0,0,0,90.00000001 +243.4,50.30085681,-2.973930734,10500,0,199.9989614,0,0,0,90.00000001 +243.41,50.30085681,-2.973902709,10500,0,199.9989614,0,0,0,90.00000001 +243.42,50.30085681,-2.973874684,10500,0,199.9998535,0,0,0,90.00000001 +243.43,50.30085681,-2.973846659,10500,0,200.0009685,0,0,0,90.00000001 +243.44,50.30085681,-2.973818633,10500,0,200.0009685,0,0,0,90.00000001 +243.45,50.30085681,-2.973790608,10500,0,199.9998535,0,0,0,90.00000001 +243.46,50.30085681,-2.973762583,10500,0,199.9989614,0,0,0,90.00000001 +243.47,50.30085681,-2.973734558,10500,0,199.9989614,0,0,0,90.00000001 +243.48,50.30085681,-2.973706533,10500,0,199.9998535,0,0,0,90.00000001 +243.49,50.30085681,-2.973678508,10500,0,200.0009685,0,0,0,90.00000001 +243.5,50.30085681,-2.973650482,10500,0,200.0009685,0,0,0,90.00000001 +243.51,50.30085681,-2.973622457,10500,0,199.9998535,0,0,0,90.00000001 +243.52,50.30085681,-2.973594432,10500,0,199.9989614,0,0,0,90.00000001 +243.53,50.30085681,-2.973566407,10500,0,199.9987384,0,0,0,90.00000001 +243.54,50.30085681,-2.973538382,10500,0,199.9989614,0,0,0,90.00000001 +243.55,50.30085681,-2.973510357,10500,0,199.9998535,0,0,0,90.00000001 +243.56,50.30085681,-2.973482332,10500,0,200.0009685,0,0,0,90.00000001 +243.57,50.30085681,-2.973454306,10500,0,200.0009685,0,0,0,90.00000001 +243.58,50.30085681,-2.973426281,10500,0,199.9998535,0,0,0,90.00000001 +243.59,50.30085681,-2.973398256,10500,0,199.9989614,0,0,0,90.00000001 +243.6,50.30085681,-2.973370231,10500,0,199.9989614,0,0,0,90.00000001 +243.61,50.30085681,-2.973342206,10500,0,199.9998535,0,0,0,90.00000001 +243.62,50.30085681,-2.973314181,10500,0,200.0009685,0,0,0,90.00000001 +243.63,50.30085681,-2.973286155,10500,0,200.0009685,0,0,0,90.00000001 +243.64,50.30085681,-2.97325813,10500,0,199.9998535,0,0,0,90.00000001 +243.65,50.30085681,-2.973230105,10500,0,199.9989614,0,0,0,90.00000001 +243.66,50.30085681,-2.97320208,10500,0,199.9989614,0,0,0,90.00000001 +243.67,50.30085681,-2.973174055,10500,0,199.9998535,0,0,0,90.00000001 +243.68,50.30085681,-2.97314603,10500,0,200.0009685,0,0,0,90.00000001 +243.69,50.30085681,-2.973118004,10500,0,200.0009685,0,0,0,90.00000001 +243.7,50.30085681,-2.973089979,10500,0,199.9998535,0,0,0,90.00000001 +243.71,50.30085681,-2.973061954,10500,0,199.9989614,0,0,0,90.00000001 +243.72,50.30085681,-2.973033929,10500,0,199.9989614,0,0,0,90.00000001 +243.73,50.30085681,-2.973005904,10500,0,199.9998535,0,0,0,90.00000001 +243.74,50.30085681,-2.972977879,10500,0,200.0009685,0,0,0,90.00000001 +243.75,50.30085681,-2.972949853,10500,0,200.0009685,0,0,0,90.00000001 +243.76,50.30085681,-2.972921828,10500,0,199.9998535,0,0,0,90.00000001 +243.77,50.30085681,-2.972893803,10500,0,199.9991844,0,0,0,90.00000001 +243.78,50.30085681,-2.972865778,10500,0,199.9998535,0,0,0,90.00000001 +243.79,50.30085681,-2.972837753,10500,0,200.0009685,0,0,0,90.00000001 +243.8,50.30085681,-2.972809727,10500,0,200.0009685,0,0,0,90.00000001 +243.81,50.30085681,-2.972781702,10500,0,199.9998535,0,0,0,90.00000001 +243.82,50.30085681,-2.972753677,10500,0,199.9991844,0,0,0,90.00000001 +243.83,50.30085681,-2.972725652,10500,0,199.9998535,0,0,0,90.00000001 +243.84,50.30085681,-2.972697627,10500,0,200.0009685,0,0,0,90.00000001 +243.85,50.30085681,-2.972669601,10500,0,200.0009685,0,0,0,90.00000001 +243.86,50.30085681,-2.972641576,10500,0,199.9998535,0,0,0,90.00000001 +243.87,50.30085681,-2.972613551,10500,0,199.9991844,0,0,0,90.00000001 +243.88,50.30085681,-2.972585526,10500,0,199.9998535,0,0,0,90.00000001 +243.89,50.30085681,-2.972557501,10500,0,200.0009685,0,0,0,90.00000001 +243.9,50.30085681,-2.972529475,10500,0,200.0009685,0,0,0,90.00000001 +243.91,50.30085681,-2.97250145,10500,0,199.9998535,0,0,0,90.00000001 +243.92,50.30085681,-2.972473425,10500,0,199.9989614,0,0,0,90.00000001 +243.93,50.30085681,-2.9724454,10500,0,199.9989614,0,0,0,90.00000001 +243.94,50.30085681,-2.972417375,10500,0,199.9998535,0,0,0,90.00000001 +243.95,50.30085681,-2.97238935,10500,0,200.0009685,0,0,0,90.00000001 +243.96,50.30085681,-2.972361324,10500,0,200.0009685,0,0,0,90.00000001 +243.97,50.30085681,-2.972333299,10500,0,199.9998535,0,0,0,90.00000001 +243.98,50.30085681,-2.972305274,10500,0,199.9991844,0,0,0,90.00000001 +243.99,50.30085681,-2.972277249,10500,0,199.9998535,0,0,0,90.00000001 +244,50.30085681,-2.972249224,10500,0,200.0009685,0,0,0,90.00000001 +244.01,50.30085681,-2.972221198,10500,0,200.0009685,0,0,0,90.00000001 +244.02,50.30085681,-2.972193173,10500,0,199.9998535,0,0,0,90.00000001 +244.03,50.30085681,-2.972165148,10500,0,199.9991844,0,0,0,90.00000001 +244.04,50.30085681,-2.972137123,10500,0,199.9998535,0,0,0,90.00000001 +244.05,50.30085681,-2.972109098,10500,0,200.0009685,0,0,0,90.00000001 +244.06,50.30085681,-2.972081072,10500,0,200.0009685,0,0,0,90.00000001 +244.07,50.30085681,-2.972053047,10500,0,199.9998535,0,0,0,90.00000001 +244.08,50.30085681,-2.972025022,10500,0,199.9989614,0,0,0,90.00000001 +244.09,50.30085681,-2.971996997,10500,0,199.9987384,0,0,0,90.00000001 +244.1,50.30085681,-2.971968972,10500,0,199.9989614,0,0,0,90.00000001 +244.11,50.30085681,-2.971940947,10500,0,199.9998535,0,0,0,90.00000001 +244.12,50.30085681,-2.971912922,10500,0,200.0009685,0,0,0,90.00000001 +244.13,50.30085681,-2.971884896,10500,0,200.0009685,0,0,0,90.00000001 +244.14,50.30085681,-2.971856871,10500,0,199.9998535,0,0,0,90.00000001 +244.15,50.30085681,-2.971828846,10500,0,199.9989614,0,0,0,90.00000001 +244.16,50.30085681,-2.971800821,10500,0,199.9989614,0,0,0,90.00000001 +244.17,50.30085681,-2.971772796,10500,0,199.9998535,0,0,0,90.00000001 +244.18,50.30085681,-2.971744771,10500,0,200.0009685,0,0,0,90.00000001 +244.19,50.30085681,-2.971716745,10500,0,200.0009685,0,0,0,90.00000001 +244.2,50.30085681,-2.97168872,10500,0,199.9998535,0,0,0,90.00000001 +244.21,50.30085681,-2.971660695,10500,0,199.9989614,0,0,0,90.00000001 +244.22,50.30085681,-2.97163267,10500,0,199.9989614,0,0,0,90.00000001 +244.23,50.30085681,-2.971604645,10500,0,199.9998535,0,0,0,90.00000001 +244.24,50.30085681,-2.97157662,10500,0,200.0009685,0,0,0,90.00000001 +244.25,50.30085681,-2.971548594,10500,0,200.0009685,0,0,0,90.00000001 +244.26,50.30085681,-2.971520569,10500,0,199.9998535,0,0,0,90.00000001 +244.27,50.30085681,-2.971492544,10500,0,199.9989614,0,0,0,90.00000001 +244.28,50.30085681,-2.971464519,10500,0,199.9989614,0,0,0,90.00000001 +244.29,50.30085681,-2.971436494,10500,0,199.9998535,0,0,0,90.00000001 +244.3,50.30085681,-2.971408469,10500,0,200.0009685,0,0,0,90.00000001 +244.31,50.30085681,-2.971380443,10500,0,200.0009685,0,0,0,90.00000001 +244.32,50.30085681,-2.971352418,10500,0,199.9998535,0,0,0,90.00000001 +244.33,50.30085681,-2.971324393,10500,0,199.9989614,0,0,0,90.00000001 +244.34,50.30085681,-2.971296368,10500,0,199.9987384,0,0,0,90.00000001 +244.35,50.30085681,-2.971268343,10500,0,199.9989614,0,0,0,90.00000001 +244.36,50.30085681,-2.971240318,10500,0,199.9998535,0,0,0,90.00000001 +244.37,50.30085681,-2.971212293,10500,0,200.0009685,0,0,0,90.00000001 +244.38,50.30085681,-2.971184267,10500,0,200.0009685,0,0,0,90.00000001 +244.39,50.30085681,-2.971156242,10500,0,199.9998535,0,0,0,90.00000001 +244.4,50.30085681,-2.971128217,10500,0,199.9991844,0,0,0,90.00000001 +244.41,50.30085681,-2.971100192,10500,0,199.9998535,0,0,0,90.00000001 +244.42,50.30085681,-2.971072167,10500,0,200.0009685,0,0,0,90.00000001 +244.43,50.30085681,-2.971044141,10500,0,200.0009685,0,0,0,90.00000001 +244.44,50.30085681,-2.971016116,10500,0,199.9998535,0,0,0,90.00000001 +244.45,50.30085681,-2.970988091,10500,0,199.9991844,0,0,0,90.00000001 +244.46,50.30085681,-2.970960066,10500,0,199.9998535,0,0,0,90.00000001 +244.47,50.30085681,-2.970932041,10500,0,200.0009685,0,0,0,90.00000001 +244.48,50.30085681,-2.970904015,10500,0,200.0009685,0,0,0,90.00000001 +244.49,50.30085681,-2.97087599,10500,0,199.9998535,0,0,0,90.00000001 +244.5,50.30085681,-2.970847965,10500,0,199.9991844,0,0,0,90.00000001 +244.51,50.30085681,-2.97081994,10500,0,199.9998535,0,0,0,90.00000001 +244.52,50.30085681,-2.970791915,10500,0,200.0009685,0,0,0,90.00000001 +244.53,50.30085681,-2.970763889,10500,0,200.0009685,0,0,0,90.00000001 +244.54,50.30085681,-2.970735864,10500,0,199.9998535,0,0,0,90.00000001 +244.55,50.30085681,-2.970707839,10500,0,199.9991844,0,0,0,90.00000001 +244.56,50.30085681,-2.970679814,10500,0,199.9998535,0,0,0,90.00000001 +244.57,50.30085681,-2.970651789,10500,0,200.0009685,0,0,0,90.00000001 +244.58,50.30085681,-2.970623763,10500,0,200.0009685,0,0,0,90.00000001 +244.59,50.30085681,-2.970595738,10500,0,199.9998535,0,0,0,90.00000001 +244.6,50.30085681,-2.970567713,10500,0,199.9991844,0,0,0,90.00000001 +244.61,50.30085681,-2.970539688,10500,0,199.9998535,0,0,0,90.00000001 +244.62,50.30085681,-2.970511663,10500,0,200.0009685,0,0,0,90.00000001 +244.63,50.30085681,-2.970483637,10500,0,200.0009685,0,0,0,90.00000001 +244.64,50.30085681,-2.970455612,10500,0,199.9998535,0,0,0,90.00000001 +244.65,50.30085681,-2.970427587,10500,0,199.9989614,0,0,0,90.00000001 +244.66,50.30085681,-2.970399562,10500,0,199.9989614,0,0,0,90.00000001 +244.67,50.30085681,-2.970371537,10500,0,199.9998535,0,0,0,90.00000001 +244.68,50.30085681,-2.970343512,10500,0,200.0009685,0,0,0,90.00000001 +244.69,50.30085681,-2.970315486,10500,0,200.0009685,0,0,0,90.00000001 +244.7,50.30085681,-2.970287461,10500,0,199.9998535,0,0,0,90.00000001 +244.71,50.30085681,-2.970259436,10500,0,199.9989614,0,0,0,90.00000001 +244.72,50.30085681,-2.970231411,10500,0,199.9989614,0,0,0,90.00000001 +244.73,50.30085681,-2.970203386,10500,0,199.9998535,0,0,0,90.00000001 +244.74,50.30085681,-2.970175361,10500,0,200.0009685,0,0,0,90.00000001 +244.75,50.30085681,-2.970147335,10500,0,200.0009685,0,0,0,90.00000001 +244.76,50.30085681,-2.97011931,10500,0,199.9998535,0,0,0,90.00000001 +244.77,50.30085681,-2.970091285,10500,0,199.9989614,0,0,0,90.00000001 +244.78,50.30085681,-2.97006326,10500,0,199.9989614,0,0,0,90.00000001 +244.79,50.30085681,-2.970035235,10500,0,199.9998535,0,0,0,90.00000001 +244.8,50.30085681,-2.97000721,10500,0,200.0009685,0,0,0,90.00000001 +244.81,50.30085681,-2.969979184,10500,0,200.0009685,0,0,0,90.00000001 +244.82,50.30085681,-2.969951159,10500,0,199.9998535,0,0,0,90.00000001 +244.83,50.30085681,-2.969923134,10500,0,199.9989614,0,0,0,90.00000001 +244.84,50.30085681,-2.969895109,10500,0,199.9989614,0,0,0,90.00000001 +244.85,50.30085681,-2.969867084,10500,0,199.9998535,0,0,0,90.00000001 +244.86,50.30085681,-2.969839059,10500,0,200.0009685,0,0,0,90.00000001 +244.87,50.30085681,-2.969811033,10500,0,200.0009685,0,0,0,90.00000001 +244.88,50.30085681,-2.969783008,10500,0,199.9998535,0,0,0,90.00000001 +244.89,50.30085681,-2.969754983,10500,0,199.9989614,0,0,0,90.00000001 +244.9,50.30085681,-2.969726958,10500,0,199.9989614,0,0,0,90.00000001 +244.91,50.30085681,-2.969698933,10500,0,199.9998535,0,0,0,90.00000001 +244.92,50.30085681,-2.969670908,10500,0,200.0009685,0,0,0,90.00000001 +244.93,50.30085681,-2.969642882,10500,0,200.0009685,0,0,0,90.00000001 +244.94,50.30085681,-2.969614857,10500,0,199.9998535,0,0,0,90.00000001 +244.95,50.30085681,-2.969586832,10500,0,199.9989614,0,0,0,90.00000001 +244.96,50.30085681,-2.969558807,10500,0,199.9987384,0,0,0,90.00000001 +244.97,50.30085681,-2.969530782,10500,0,199.9989614,0,0,0,90.00000001 +244.98,50.30085681,-2.969502757,10500,0,199.9998535,0,0,0,90.00000001 +244.99,50.30085681,-2.969474732,10500,0,200.0009685,0,0,0,90.00000001 +245,50.30085681,-2.969446706,10500,0,200.0009685,0,0,0,90.00000001 +245.01,50.30085681,-2.969418681,10500,0,199.9998535,0,0,0,90.00000001 +245.02,50.30085681,-2.969390656,10500,0,199.9991844,0,0,0,90.00000001 +245.03,50.30085681,-2.969362631,10500,0,199.9998535,0,0,0,90.00000001 +245.04,50.30085681,-2.969334606,10500,0,200.0009685,0,0,0,90.00000001 +245.05,50.30085681,-2.96930658,10500,0,200.0009685,0,0,0,90.00000001 +245.06,50.30085681,-2.969278555,10500,0,199.9998535,0,0,0,90.00000001 +245.07,50.30085681,-2.96925053,10500,0,199.9991844,0,0,0,90.00000001 +245.08,50.30085681,-2.969222505,10500,0,199.9998535,0,0,0,90.00000001 +245.09,50.30085681,-2.96919448,10500,0,200.0009685,0,0,0,90.00000001 +245.1,50.30085681,-2.969166454,10500,0,200.0009685,0,0,0,90.00000001 +245.11,50.30085681,-2.969138429,10500,0,199.9998535,0,0,0,90.00000001 +245.12,50.30085681,-2.969110404,10500,0,199.9991844,0,0,0,90.00000001 +245.13,50.30085681,-2.969082379,10500,0,199.9998535,0,0,0,90.00000001 +245.14,50.30085681,-2.969054354,10500,0,200.0009685,0,0,0,90.00000001 +245.15,50.30085681,-2.969026328,10500,0,200.0009685,0,0,0,90.00000001 +245.16,50.30085681,-2.968998303,10500,0,199.9998535,0,0,0,90.00000001 +245.17,50.30085681,-2.968970278,10500,0,199.9991844,0,0,0,90.00000001 +245.18,50.30085681,-2.968942253,10500,0,199.9998535,0,0,0,90.00000001 +245.19,50.30085681,-2.968914228,10500,0,200.0009685,0,0,0,90.00000001 +245.2,50.30085681,-2.968886202,10500,0,200.0009685,0,0,0,90.00000001 +245.21,50.30085681,-2.968858177,10500,0,199.9998535,0,0,0,90.00000001 +245.22,50.30085681,-2.968830152,10500,0,199.9991844,0,0,0,90.00000001 +245.23,50.30085681,-2.968802127,10500,0,199.9998535,0,0,0,90.00000001 +245.24,50.30085681,-2.968774102,10500,0,200.0009685,0,0,0,90.00000001 +245.25,50.30085681,-2.968746076,10500,0,200.0009685,0,0,0,90.00000001 +245.26,50.30085681,-2.968718051,10500,0,199.9998535,0,0,0,90.00000001 +245.27,50.30085681,-2.968690026,10500,0,199.9989614,0,0,0,90.00000001 +245.28,50.30085681,-2.968662001,10500,0,199.9989614,0,0,0,90.00000001 +245.29,50.30085681,-2.968633976,10500,0,199.9998535,0,0,0,90.00000001 +245.3,50.30085681,-2.968605951,10500,0,200.0009685,0,0,0,90.00000001 +245.31,50.30085681,-2.968577925,10500,0,200.0009685,0,0,0,90.00000001 +245.32,50.30085681,-2.9685499,10500,0,199.9998535,0,0,0,90.00000001 +245.33,50.30085681,-2.968521875,10500,0,199.9989614,0,0,0,90.00000001 +245.34,50.30085681,-2.96849385,10500,0,199.9989614,0,0,0,90.00000001 +245.35,50.30085681,-2.968465825,10500,0,199.9998535,0,0,0,90.00000001 +245.36,50.30085681,-2.9684378,10500,0,200.0009685,0,0,0,90.00000001 +245.37,50.30085681,-2.968409774,10500,0,200.0009685,0,0,0,90.00000001 +245.38,50.30085681,-2.968381749,10500,0,199.9998535,0,0,0,90.00000001 +245.39,50.30085681,-2.968353724,10500,0,199.9989614,0,0,0,90.00000001 +245.4,50.30085681,-2.968325699,10500,0,199.9989614,0,0,0,90.00000001 +245.41,50.30085681,-2.968297674,10500,0,199.9998535,0,0,0,90.00000001 +245.42,50.30085681,-2.968269649,10500,0,200.0009685,0,0,0,90.00000001 +245.43,50.30085681,-2.968241623,10500,0,200.0009685,0,0,0,90.00000001 +245.44,50.30085681,-2.968213598,10500,0,199.9998535,0,0,0,90.00000001 +245.45,50.30085681,-2.968185573,10500,0,199.9989614,0,0,0,90.00000001 +245.46,50.30085681,-2.968157548,10500,0,199.9989614,0,0,0,90.00000001 +245.47,50.30085681,-2.968129523,10500,0,199.9998535,0,0,0,90.00000001 +245.48,50.30085681,-2.968101498,10500,0,200.0009685,0,0,0,90.00000001 +245.49,50.30085681,-2.968073472,10500,0,200.0009685,0,0,0,90.00000001 +245.5,50.30085681,-2.968045447,10500,0,199.9998535,0,0,0,90.00000001 +245.51,50.30085681,-2.968017422,10500,0,199.9989614,0,0,0,90.00000001 +245.52,50.30085681,-2.967989397,10500,0,199.9987384,0,0,0,90.00000001 +245.53,50.30085681,-2.967961372,10500,0,199.9989614,0,0,0,90.00000001 +245.54,50.30085681,-2.967933347,10500,0,199.9998535,0,0,0,90.00000001 +245.55,50.30085681,-2.967905322,10500,0,200.0009685,0,0,0,90.00000001 +245.56,50.30085681,-2.967877296,10500,0,200.0009685,0,0,0,90.00000001 +245.57,50.30085681,-2.967849271,10500,0,199.9998535,0,0,0,90.00000001 +245.58,50.30085681,-2.967821246,10500,0,199.9989614,0,0,0,90.00000001 +245.59,50.30085681,-2.967793221,10500,0,199.9989614,0,0,0,90.00000001 +245.6,50.30085681,-2.967765196,10500,0,199.9998535,0,0,0,90.00000001 +245.61,50.30085681,-2.967737171,10500,0,200.0009685,0,0,0,90.00000001 +245.62,50.30085681,-2.967709145,10500,0,200.0009685,0,0,0,90.00000001 +245.63,50.30085681,-2.96768112,10500,0,199.9998535,0,0,0,90.00000001 +245.64,50.30085681,-2.967653095,10500,0,199.9991844,0,0,0,90.00000001 +245.65,50.30085681,-2.96762507,10500,0,199.9998535,0,0,0,90.00000001 +245.66,50.30085681,-2.967597045,10500,0,200.0009685,0,0,0,90.00000001 +245.67,50.30085681,-2.967569019,10500,0,200.0009685,0,0,0,90.00000001 +245.68,50.30085681,-2.967540994,10500,0,199.9998535,0,0,0,90.00000001 +245.69,50.30085681,-2.967512969,10500,0,199.9991844,0,0,0,90.00000001 +245.7,50.30085681,-2.967484944,10500,0,199.9998535,0,0,0,90.00000001 +245.71,50.30085681,-2.967456919,10500,0,200.0009685,0,0,0,90.00000001 +245.72,50.30085681,-2.967428893,10500,0,200.0009685,0,0,0,90.00000001 +245.73,50.30085681,-2.967400868,10500,0,199.9998535,0,0,0,90.00000001 +245.74,50.30085681,-2.967372843,10500,0,199.9991844,0,0,0,90.00000001 +245.75,50.30085681,-2.967344818,10500,0,199.9998535,0,0,0,90.00000001 +245.76,50.30085681,-2.967316793,10500,0,200.0009685,0,0,0,90.00000001 +245.77,50.30085681,-2.967288767,10500,0,200.0009685,0,0,0,90.00000001 +245.78,50.30085681,-2.967260742,10500,0,199.9998535,0,0,0,90.00000001 +245.79,50.30085681,-2.967232717,10500,0,199.9991844,0,0,0,90.00000001 +245.8,50.30085681,-2.967204692,10500,0,199.9998535,0,0,0,90.00000001 +245.81,50.30085681,-2.967176667,10500,0,200.0009685,0,0,0,90.00000001 +245.82,50.30085681,-2.967148641,10500,0,200.0009685,0,0,0,90.00000001 +245.83,50.30085681,-2.967120616,10500,0,199.9998535,0,0,0,90.00000001 +245.84,50.30085681,-2.967092591,10500,0,199.9991844,0,0,0,90.00000001 +245.85,50.30085681,-2.967064566,10500,0,199.9998535,0,0,0,90.00000001 +245.86,50.30085681,-2.967036541,10500,0,200.0009685,0,0,0,90.00000001 +245.87,50.30085681,-2.967008515,10500,0,200.0009685,0,0,0,90.00000001 +245.88,50.30085681,-2.96698049,10500,0,199.9998535,0,0,0,90.00000001 +245.89,50.30085681,-2.966952465,10500,0,199.9989614,0,0,0,90.00000001 +245.9,50.30085681,-2.96692444,10500,0,199.9989614,0,0,0,90.00000001 +245.91,50.30085681,-2.966896415,10500,0,199.9998535,0,0,0,90.00000001 +245.92,50.30085681,-2.96686839,10500,0,200.0009685,0,0,0,90.00000001 +245.93,50.30085681,-2.966840364,10500,0,200.0009685,0,0,0,90.00000001 +245.94,50.30085681,-2.966812339,10500,0,199.9998535,0,0,0,90.00000001 +245.95,50.30085681,-2.966784314,10500,0,199.9989614,0,0,0,90.00000001 +245.96,50.30085681,-2.966756289,10500,0,199.9989614,0,0,0,90.00000001 +245.97,50.30085681,-2.966728264,10500,0,199.9998535,0,0,0,90.00000001 +245.98,50.30085681,-2.966700239,10500,0,200.0009685,0,0,0,90.00000001 +245.99,50.30085681,-2.966672213,10500,0,200.0009685,0,0,0,90.00000001 +246,50.30085681,-2.966644188,10500,0,199.9998535,0,0,0,90.00000001 +246.01,50.30085681,-2.966616163,10500,0,199.9989614,0,0,0,90.00000001 +246.02,50.30085681,-2.966588138,10500,0,199.9989614,0,0,0,90.00000001 +246.03,50.30085681,-2.966560113,10500,0,199.9998535,0,0,0,90.00000001 +246.04,50.30085681,-2.966532088,10500,0,200.0009685,0,0,0,90.00000001 +246.05,50.30085681,-2.966504062,10500,0,200.0009685,0,0,0,90.00000001 +246.06,50.30085681,-2.966476037,10500,0,199.9998535,0,0,0,90.00000001 +246.07,50.30085681,-2.966448012,10500,0,199.9989614,0,0,0,90.00000001 +246.08,50.30085681,-2.966419987,10500,0,199.9987384,0,0,0,90.00000001 +246.09,50.30085681,-2.966391962,10500,0,199.9989614,0,0,0,90.00000001 +246.1,50.30085681,-2.966363937,10500,0,199.9998535,0,0,0,90.00000001 +246.11,50.30085681,-2.966335912,10500,0,200.0009685,0,0,0,90.00000001 +246.12,50.30085681,-2.966307886,10500,0,200.0009685,0,0,0,90.00000001 +246.13,50.30085681,-2.966279861,10500,0,199.9998535,0,0,0,90.00000001 +246.14,50.30085681,-2.966251836,10500,0,199.9989614,0,0,0,90.00000001 +246.15,50.30085681,-2.966223811,10500,0,199.9989614,0,0,0,90.00000001 +246.16,50.30085681,-2.966195786,10500,0,199.9998535,0,0,0,90.00000001 +246.17,50.30085681,-2.966167761,10500,0,200.0009685,0,0,0,90.00000001 +246.18,50.30085681,-2.966139735,10500,0,200.0009685,0,0,0,90.00000001 +246.19,50.30085681,-2.96611171,10500,0,199.9998535,0,0,0,90.00000001 +246.2,50.30085681,-2.966083685,10500,0,199.9989614,0,0,0,90.00000001 +246.21,50.30085681,-2.96605566,10500,0,199.9989614,0,0,0,90.00000001 +246.22,50.30085681,-2.966027635,10500,0,199.9998535,0,0,0,90.00000001 +246.23,50.30085681,-2.96599961,10500,0,200.0009685,0,0,0,90.00000001 +246.24,50.30085681,-2.965971584,10500,0,200.0009685,0,0,0,90.00000001 +246.25,50.30085681,-2.965943559,10500,0,199.9998535,0,0,0,90.00000001 +246.26,50.30085681,-2.965915534,10500,0,199.9991844,0,0,0,90.00000001 +246.27,50.30085681,-2.965887509,10500,0,199.9998535,0,0,0,90.00000001 +246.28,50.30085681,-2.965859484,10500,0,200.0009685,0,0,0,90.00000001 +246.29,50.30085681,-2.965831458,10500,0,200.0009685,0,0,0,90.00000001 +246.3,50.30085681,-2.965803433,10500,0,199.9998535,0,0,0,90.00000001 +246.31,50.30085681,-2.965775408,10500,0,199.9989614,0,0,0,90.00000001 +246.32,50.30085681,-2.965747383,10500,0,199.9989614,0,0,0,90.00000001 +246.33,50.30085681,-2.965719358,10500,0,199.9998535,0,0,0,90.00000001 +246.34,50.30085681,-2.965691333,10500,0,200.0009685,0,0,0,90.00000001 +246.35,50.30085681,-2.965663307,10500,0,200.0009685,0,0,0,90.00000001 +246.36,50.30085681,-2.965635282,10500,0,199.9998535,0,0,0,90.00000001 +246.37,50.30085681,-2.965607257,10500,0,199.9991844,0,0,0,90.00000001 +246.38,50.30085681,-2.965579232,10500,0,199.9998535,0,0,0,90.00000001 +246.39,50.30085681,-2.965551207,10500,0,200.0009685,0,0,0,90.00000001 +246.4,50.30085681,-2.965523181,10500,0,200.0009685,0,0,0,90.00000001 +246.41,50.30085681,-2.965495156,10500,0,199.9998535,0,0,0,90.00000001 +246.42,50.30085681,-2.965467131,10500,0,199.9991844,0,0,0,90.00000001 +246.43,50.30085681,-2.965439106,10500,0,199.9998535,0,0,0,90.00000001 +246.44,50.30085681,-2.965411081,10500,0,200.0009685,0,0,0,90.00000001 +246.45,50.30085681,-2.965383055,10500,0,200.0009685,0,0,0,90.00000001 +246.46,50.30085681,-2.96535503,10500,0,199.9998535,0,0,0,90.00000001 +246.47,50.30085681,-2.965327005,10500,0,199.9991844,0,0,0,90.00000001 +246.48,50.30085681,-2.96529898,10500,0,199.9998535,0,0,0,90.00000001 +246.49,50.30085681,-2.965270955,10500,0,200.0009685,0,0,0,90.00000001 +246.5,50.30085681,-2.965242929,10500,0,200.0009685,0,0,0,90.00000001 +246.51,50.30085681,-2.965214904,10500,0,199.9998535,0,0,0,90.00000001 +246.52,50.30085681,-2.965186879,10500,0,199.9991844,0,0,0,90.00000001 +246.53,50.30085681,-2.965158854,10500,0,199.9998535,0,0,0,90.00000001 +246.54,50.30085681,-2.965130829,10500,0,200.0009685,0,0,0,90.00000001 +246.55,50.30085681,-2.965102803,10500,0,200.0009685,0,0,0,90.00000001 +246.56,50.30085681,-2.965074778,10500,0,199.9998535,0,0,0,90.00000001 +246.57,50.30085681,-2.965046753,10500,0,199.9989614,0,0,0,90.00000001 +246.58,50.30085681,-2.965018728,10500,0,199.9989614,0,0,0,90.00000001 +246.59,50.30085681,-2.964990703,10500,0,199.9998535,0,0,0,90.00000001 +246.6,50.30085681,-2.964962678,10500,0,200.0009685,0,0,0,90.00000001 +246.61,50.30085681,-2.964934652,10500,0,200.0009685,0,0,0,90.00000001 +246.62,50.30085681,-2.964906627,10500,0,199.9998535,0,0,0,90.00000001 +246.63,50.30085681,-2.964878602,10500,0,199.9989614,0,0,0,90.00000001 +246.64,50.30085681,-2.964850577,10500,0,199.9987384,0,0,0,90.00000001 +246.65,50.30085681,-2.964822552,10500,0,199.9989614,0,0,0,90.00000001 +246.66,50.30085681,-2.964794527,10500,0,199.9998535,0,0,0,90.00000001 +246.67,50.30085681,-2.964766502,10500,0,200.0009685,0,0,0,90.00000001 +246.68,50.30085681,-2.964738476,10500,0,200.0009685,0,0,0,90.00000001 +246.69,50.30085681,-2.964710451,10500,0,199.9998535,0,0,0,90.00000001 +246.7,50.30085681,-2.964682426,10500,0,199.9989614,0,0,0,90.00000001 +246.71,50.30085681,-2.964654401,10500,0,199.9989614,0,0,0,90.00000001 +246.72,50.30085681,-2.964626376,10500,0,199.9998535,0,0,0,90.00000001 +246.73,50.30085681,-2.964598351,10500,0,200.0009685,0,0,0,90.00000001 +246.74,50.30085681,-2.964570325,10500,0,200.0009685,0,0,0,90.00000001 +246.75,50.30085681,-2.9645423,10500,0,199.9998535,0,0,0,90.00000001 +246.76,50.30085681,-2.964514275,10500,0,199.9989614,0,0,0,90.00000001 +246.77,50.30085681,-2.96448625,10500,0,199.9989614,0,0,0,90.00000001 +246.78,50.30085681,-2.964458225,10500,0,199.9998535,0,0,0,90.00000001 +246.79,50.30085681,-2.9644302,10500,0,200.0009685,0,0,0,90.00000001 +246.8,50.30085681,-2.964402174,10500,0,200.0009685,0,0,0,90.00000001 +246.81,50.30085681,-2.964374149,10500,0,199.9998535,0,0,0,90.00000001 +246.82,50.30085681,-2.964346124,10500,0,199.9989614,0,0,0,90.00000001 +246.83,50.30085681,-2.964318099,10500,0,199.9989614,0,0,0,90.00000001 +246.84,50.30085681,-2.964290074,10500,0,199.9998535,0,0,0,90.00000001 +246.85,50.30085681,-2.964262049,10500,0,200.0009685,0,0,0,90.00000001 +246.86,50.30085681,-2.964234023,10500,0,200.0009685,0,0,0,90.00000001 +246.87,50.30085681,-2.964205998,10500,0,199.9998535,0,0,0,90.00000001 +246.88,50.30085681,-2.964177973,10500,0,199.9989614,0,0,0,90.00000001 +246.89,50.30085681,-2.964149948,10500,0,199.9989614,0,0,0,90.00000001 +246.9,50.30085681,-2.964121923,10500,0,199.9998535,0,0,0,90.00000001 +246.91,50.30085681,-2.964093898,10500,0,200.0009685,0,0,0,90.00000001 +246.92,50.30085681,-2.964065872,10500,0,200.0009685,0,0,0,90.00000001 +246.93,50.30085681,-2.964037847,10500,0,199.9998535,0,0,0,90.00000001 +246.94,50.30085681,-2.964009822,10500,0,199.9991844,0,0,0,90.00000001 +246.95,50.30085681,-2.963981797,10500,0,199.9998535,0,0,0,90.00000001 +246.96,50.30085681,-2.963953772,10500,0,200.0009685,0,0,0,90.00000001 +246.97,50.30085681,-2.963925746,10500,0,200.0009685,0,0,0,90.00000001 +246.98,50.30085681,-2.963897721,10500,0,199.9998535,0,0,0,90.00000001 +246.99,50.30085681,-2.963869696,10500,0,199.9991844,0,0,0,90.00000001 +247,50.30085681,-2.963841671,10500,0,199.9998535,0,0,0,90.00000001 +247.01,50.30085681,-2.963813646,10500,0,200.0009685,0,0,0,90.00000001 +247.02,50.30085681,-2.96378562,10500,0,200.0009685,0,0,0,90.00000001 +247.03,50.30085681,-2.963757595,10500,0,199.9998535,0,0,0,90.00000001 +247.04,50.30085681,-2.96372957,10500,0,199.9991844,0,0,0,90.00000001 +247.05,50.30085681,-2.963701545,10500,0,199.9998535,0,0,0,90.00000001 +247.06,50.30085681,-2.96367352,10500,0,200.0009685,0,0,0,90.00000001 +247.07,50.30085681,-2.963645494,10500,0,200.0009685,0,0,0,90.00000001 +247.08,50.30085681,-2.963617469,10500,0,199.9998535,0,0,0,90.00000001 +247.09,50.30085681,-2.963589444,10500,0,199.9991844,0,0,0,90.00000001 +247.1,50.30085681,-2.963561419,10500,0,199.9998535,0,0,0,90.00000001 +247.11,50.30085681,-2.963533394,10500,0,200.0009685,0,0,0,90.00000001 +247.12,50.30085681,-2.963505368,10500,0,200.0009685,0,0,0,90.00000001 +247.13,50.30085681,-2.963477343,10500,0,199.9998535,0,0,0,90.00000001 +247.14,50.30085681,-2.963449318,10500,0,199.9991844,0,0,0,90.00000001 +247.15,50.30085681,-2.963421293,10500,0,199.9998535,0,0,0,90.00000001 +247.16,50.30085681,-2.963393268,10500,0,200.0009685,0,0,0,90.00000001 +247.17,50.30085681,-2.963365242,10500,0,200.0009685,0,0,0,90.00000001 +247.18,50.30085681,-2.963337217,10500,0,199.9998535,0,0,0,90.00000001 +247.19,50.30085681,-2.963309192,10500,0,199.9989614,0,0,0,90.00000001 +247.2,50.30085681,-2.963281167,10500,0,199.9987384,0,0,0,90.00000001 +247.21,50.30085681,-2.963253142,10500,0,199.9989614,0,0,0,90.00000001 +247.22,50.30085681,-2.963225117,10500,0,199.9998535,0,0,0,90.00000001 +247.23,50.30085681,-2.963197092,10500,0,200.0009685,0,0,0,90.00000001 +247.24,50.30085681,-2.963169066,10500,0,200.0009685,0,0,0,90.00000001 +247.25,50.30085681,-2.963141041,10500,0,199.9998535,0,0,0,90.00000001 +247.26,50.30085681,-2.963113016,10500,0,199.9989614,0,0,0,90.00000001 +247.27,50.30085681,-2.963084991,10500,0,199.9989614,0,0,0,90.00000001 +247.28,50.30085681,-2.963056966,10500,0,199.9998535,0,0,0,90.00000001 +247.29,50.30085681,-2.963028941,10500,0,200.0009685,0,0,0,90.00000001 +247.3,50.30085681,-2.963000915,10500,0,200.0009685,0,0,0,90.00000001 +247.31,50.30085681,-2.96297289,10500,0,199.9998535,0,0,0,90.00000001 +247.32,50.30085681,-2.962944865,10500,0,199.9989614,0,0,0,90.00000001 +247.33,50.30085681,-2.96291684,10500,0,199.9989614,0,0,0,90.00000001 +247.34,50.30085681,-2.962888815,10500,0,199.9998535,0,0,0,90.00000001 +247.35,50.30085681,-2.96286079,10500,0,200.0009685,0,0,0,90.00000001 +247.36,50.30085681,-2.962832764,10500,0,200.0009685,0,0,0,90.00000001 +247.37,50.30085681,-2.962804739,10500,0,199.9998535,0,0,0,90.00000001 +247.38,50.30085681,-2.962776714,10500,0,199.9989614,0,0,0,90.00000001 +247.39,50.30085681,-2.962748689,10500,0,199.9989614,0,0,0,90.00000001 +247.4,50.30085681,-2.962720664,10500,0,199.9998535,0,0,0,90.00000001 +247.41,50.30085681,-2.962692639,10500,0,200.0009685,0,0,0,90.00000001 +247.42,50.30085681,-2.962664613,10500,0,200.0009685,0,0,0,90.00000001 +247.43,50.30085681,-2.962636588,10500,0,199.9998535,0,0,0,90.00000001 +247.44,50.30085681,-2.962608563,10500,0,199.9989614,0,0,0,90.00000001 +247.45,50.30085681,-2.962580538,10500,0,199.9989614,0,0,0,90.00000001 +247.46,50.30085681,-2.962552513,10500,0,199.9998535,0,0,0,90.00000001 +247.47,50.30085681,-2.962524488,10500,0,200.0009685,0,0,0,90.00000001 +247.48,50.30085681,-2.962496462,10500,0,200.0009685,0,0,0,90.00000001 +247.49,50.30085681,-2.962468437,10500,0,199.9998535,0,0,0,90.00000001 +247.5,50.30085681,-2.962440412,10500,0,199.9989614,0,0,0,90.00000001 +247.51,50.30085681,-2.962412387,10500,0,199.9989614,0,0,0,90.00000001 +247.52,50.30085681,-2.962384362,10500,0,199.9998535,0,0,0,90.00000001 +247.53,50.30085681,-2.962356337,10500,0,200.0009685,0,0,0,90.00000001 +247.54,50.30085681,-2.962328311,10500,0,200.0009685,0,0,0,90.00000001 +247.55,50.30085681,-2.962300286,10500,0,199.9998535,0,0,0,90.00000001 +247.56,50.30085681,-2.962272261,10500,0,199.9991844,0,0,0,90.00000001 +247.57,50.30085681,-2.962244236,10500,0,199.9998535,0,0,0,90.00000001 +247.58,50.30085681,-2.962216211,10500,0,200.0009685,0,0,0,90.00000001 +247.59,50.30085681,-2.962188185,10500,0,200.0009685,0,0,0,90.00000001 +247.6,50.30085681,-2.96216016,10500,0,199.9998535,0,0,0,90.00000001 +247.61,50.30085681,-2.962132135,10500,0,199.9991844,0,0,0,90.00000001 +247.62,50.30085681,-2.96210411,10500,0,199.9998535,0,0,0,90.00000001 +247.63,50.30085681,-2.962076085,10500,0,200.0009685,0,0,0,90.00000001 +247.64,50.30085681,-2.962048059,10500,0,200.0009685,0,0,0,90.00000001 +247.65,50.30085681,-2.962020034,10500,0,199.9998535,0,0,0,90.00000001 +247.66,50.30085681,-2.961992009,10500,0,199.9991844,0,0,0,90.00000001 +247.67,50.30085681,-2.961963984,10500,0,199.9998535,0,0,0,90.00000001 +247.68,50.30085681,-2.961935959,10500,0,200.0009685,0,0,0,90.00000001 +247.69,50.30085681,-2.961907933,10500,0,200.0009685,0,0,0,90.00000001 +247.7,50.30085681,-2.961879908,10500,0,199.9998535,0,0,0,90.00000001 +247.71,50.30085681,-2.961851883,10500,0,199.9991844,0,0,0,90.00000001 +247.72,50.30085681,-2.961823858,10500,0,199.9998535,0,0,0,90.00000001 +247.73,50.30085681,-2.961795833,10500,0,200.0009685,0,0,0,90.00000001 +247.74,50.30085681,-2.961767807,10500,0,200.0009685,0,0,0,90.00000001 +247.75,50.30085681,-2.961739782,10500,0,199.9998535,0,0,0,90.00000001 +247.76,50.30085681,-2.961711757,10500,0,199.9991844,0,0,0,90.00000001 +247.77,50.30085681,-2.961683732,10500,0,199.9998535,0,0,0,90.00000001 +247.78,50.30085681,-2.961655707,10500,0,200.0009685,0,0,0,90.00000001 +247.79,50.30085681,-2.961627681,10500,0,200.0009685,0,0,0,90.00000001 +247.8,50.30085681,-2.961599656,10500,0,199.9998535,0,0,0,90.00000001 +247.81,50.30085681,-2.961571631,10500,0,199.9989614,0,0,0,90.00000001 +247.82,50.30085681,-2.961543606,10500,0,199.9987384,0,0,0,90.00000001 +247.83,50.30085681,-2.961515581,10500,0,199.9989614,0,0,0,90.00000001 +247.84,50.30085681,-2.961487556,10500,0,199.9998535,0,0,0,90.00000001 +247.85,50.30085681,-2.961459531,10500,0,200.0009685,0,0,0,90.00000001 +247.86,50.30085681,-2.961431505,10500,0,200.0009685,0,0,0,90.00000001 +247.87,50.30085681,-2.96140348,10500,0,199.9998535,0,0,0,90.00000001 +247.88,50.30085681,-2.961375455,10500,0,199.9989614,0,0,0,90.00000001 +247.89,50.30085681,-2.96134743,10500,0,199.9989614,0,0,0,90.00000001 +247.9,50.30085681,-2.961319405,10500,0,199.9998535,0,0,0,90.00000001 +247.91,50.30085681,-2.96129138,10500,0,200.0009685,0,0,0,90.00000001 +247.92,50.30085681,-2.961263354,10500,0,200.0009685,0,0,0,90.00000001 +247.93,50.30085681,-2.961235329,10500,0,199.9998535,0,0,0,90.00000001 +247.94,50.30085681,-2.961207304,10500,0,199.9989614,0,0,0,90.00000001 +247.95,50.30085681,-2.961179279,10500,0,199.9989614,0,0,0,90.00000001 +247.96,50.30085681,-2.961151254,10500,0,199.9998535,0,0,0,90.00000001 +247.97,50.30085681,-2.961123229,10500,0,200.0009685,0,0,0,90.00000001 +247.98,50.30085681,-2.961095203,10500,0,200.0009685,0,0,0,90.00000001 +247.99,50.30085681,-2.961067178,10500,0,199.9998535,0,0,0,90.00000001 +248,50.30085681,-2.961039153,10500,0,199.9989614,0,0,0,90.00000001 +248.01,50.30085681,-2.961011128,10500,0,199.9989614,0,0,0,90.00000001 +248.02,50.30085681,-2.960983103,10500,0,199.9998535,0,0,0,90.00000001 +248.03,50.30085681,-2.960955078,10500,0,200.0009685,0,0,0,90.00000001 +248.04,50.30085681,-2.960927052,10500,0,200.0009685,0,0,0,90.00000001 +248.05,50.30085681,-2.960899027,10500,0,199.9998535,0,0,0,90.00000001 +248.06,50.30085681,-2.960871002,10500,0,199.9989614,0,0,0,90.00000001 +248.07,50.30085681,-2.960842977,10500,0,199.9987384,0,0,0,90.00000001 +248.08,50.30085681,-2.960814952,10500,0,199.9989614,0,0,0,90.00000001 +248.09,50.30085681,-2.960786927,10500,0,199.9998535,0,0,0,90.00000001 +248.1,50.30085681,-2.960758902,10500,0,200.0009685,0,0,0,90.00000001 +248.11,50.30085681,-2.960730876,10500,0,200.0009685,0,0,0,90.00000001 +248.12,50.30085681,-2.960702851,10500,0,199.9998535,0,0,0,90.00000001 +248.13,50.30085681,-2.960674826,10500,0,199.9991844,0,0,0,90.00000001 +248.14,50.30085681,-2.960646801,10500,0,199.9998535,0,0,0,90.00000001 +248.15,50.30085681,-2.960618776,10500,0,200.0009685,0,0,0,90.00000001 +248.16,50.30085681,-2.96059075,10500,0,200.0009685,0,0,0,90.00000001 +248.17,50.30085681,-2.960562725,10500,0,199.9998535,0,0,0,90.00000001 +248.18,50.30085681,-2.9605347,10500,0,199.9991844,0,0,0,90.00000001 +248.19,50.30085681,-2.960506675,10500,0,199.9998535,0,0,0,90.00000001 +248.2,50.30085681,-2.96047865,10500,0,200.0009685,0,0,0,90.00000001 +248.21,50.30085681,-2.960450624,10500,0,200.0009685,0,0,0,90.00000001 +248.22,50.30085681,-2.960422599,10500,0,199.9998535,0,0,0,90.00000001 +248.23,50.30085681,-2.960394574,10500,0,199.9991844,0,0,0,90.00000001 +248.24,50.30085681,-2.960366549,10500,0,199.9998535,0,0,0,90.00000001 +248.25,50.30085681,-2.960338524,10500,0,200.0009685,0,0,0,90.00000001 +248.26,50.30085681,-2.960310498,10500,0,200.0009685,0,0,0,90.00000001 +248.27,50.30085681,-2.960282473,10500,0,199.9998535,0,0,0,90.00000001 +248.28,50.30085681,-2.960254448,10500,0,199.9991844,0,0,0,90.00000001 +248.29,50.30085681,-2.960226423,10500,0,199.9998535,0,0,0,90.00000001 +248.3,50.30085681,-2.960198398,10500,0,200.0009685,0,0,0,90.00000001 +248.31,50.30085681,-2.960170372,10500,0,200.0009685,0,0,0,90.00000001 +248.32,50.30085681,-2.960142347,10500,0,199.9998535,0,0,0,90.00000001 +248.33,50.30085681,-2.960114322,10500,0,199.9991844,0,0,0,90.00000001 +248.34,50.30085681,-2.960086297,10500,0,199.9998535,0,0,0,90.00000001 +248.35,50.30085681,-2.960058272,10500,0,200.0009685,0,0,0,90.00000001 +248.36,50.30085681,-2.960030246,10500,0,200.0009685,0,0,0,90.00000001 +248.37,50.30085681,-2.960002221,10500,0,199.9998535,0,0,0,90.00000001 +248.38,50.30085681,-2.959974196,10500,0,199.9989614,0,0,0,90.00000001 +248.39,50.30085681,-2.959946171,10500,0,199.9989614,0,0,0,90.00000001 +248.4,50.30085681,-2.959918146,10500,0,199.9998535,0,0,0,90.00000001 +248.41,50.30085681,-2.959890121,10500,0,200.0009685,0,0,0,90.00000001 +248.42,50.30085681,-2.959862095,10500,0,200.0009685,0,0,0,90.00000001 +248.43,50.30085681,-2.95983407,10500,0,199.9998535,0,0,0,90.00000001 +248.44,50.30085681,-2.959806045,10500,0,199.9989614,0,0,0,90.00000001 +248.45,50.30085681,-2.95977802,10500,0,199.9989614,0,0,0,90.00000001 +248.46,50.30085681,-2.959749995,10500,0,199.9998535,0,0,0,90.00000001 +248.47,50.30085681,-2.95972197,10500,0,200.0009685,0,0,0,90.00000001 +248.48,50.30085681,-2.959693944,10500,0,200.0009685,0,0,0,90.00000001 +248.49,50.30085681,-2.959665919,10500,0,199.9998535,0,0,0,90.00000001 +248.5,50.30085681,-2.959637894,10500,0,199.9989614,0,0,0,90.00000001 +248.51,50.30085681,-2.959609869,10500,0,199.9989614,0,0,0,90.00000001 +248.52,50.30085681,-2.959581844,10500,0,199.9998535,0,0,0,90.00000001 +248.53,50.30085681,-2.959553819,10500,0,200.0009685,0,0,0,90.00000001 +248.54,50.30085681,-2.959525793,10500,0,200.0009685,0,0,0,90.00000001 +248.55,50.30085681,-2.959497768,10500,0,199.9998535,0,0,0,90.00000001 +248.56,50.30085681,-2.959469743,10500,0,199.9989614,0,0,0,90.00000001 +248.57,50.30085681,-2.959441718,10500,0,199.9989614,0,0,0,90.00000001 +248.58,50.30085681,-2.959413693,10500,0,199.9998535,0,0,0,90.00000001 +248.59,50.30085681,-2.959385668,10500,0,200.0009685,0,0,0,90.00000001 +248.6,50.30085681,-2.959357642,10500,0,200.0009685,0,0,0,90.00000001 +248.61,50.30085681,-2.959329617,10500,0,199.9998535,0,0,0,90.00000001 +248.62,50.30085681,-2.959301592,10500,0,199.9989614,0,0,0,90.00000001 +248.63,50.30085681,-2.959273567,10500,0,199.9987384,0,0,0,90.00000001 +248.64,50.30085681,-2.959245542,10500,0,199.9989614,0,0,0,90.00000001 +248.65,50.30085681,-2.959217517,10500,0,199.9998535,0,0,0,90.00000001 +248.66,50.30085681,-2.959189492,10500,0,200.0009685,0,0,0,90.00000001 +248.67,50.30085681,-2.959161466,10500,0,200.0009685,0,0,0,90.00000001 +248.68,50.30085681,-2.959133441,10500,0,199.9998535,0,0,0,90.00000001 +248.69,50.30085681,-2.959105416,10500,0,199.9989614,0,0,0,90.00000001 +248.7,50.30085681,-2.959077391,10500,0,199.9989614,0,0,0,90.00000001 +248.71,50.30085681,-2.959049366,10500,0,199.9998535,0,0,0,90.00000001 +248.72,50.30085681,-2.959021341,10500,0,200.0009685,0,0,0,90.00000001 +248.73,50.30085681,-2.958993315,10500,0,200.0009685,0,0,0,90.00000001 +248.74,50.30085681,-2.95896529,10500,0,199.9998535,0,0,0,90.00000001 +248.75,50.30085681,-2.958937265,10500,0,199.9989614,0,0,0,90.00000001 +248.76,50.30085681,-2.95890924,10500,0,199.9989614,0,0,0,90.00000001 +248.77,50.30085681,-2.958881215,10500,0,199.9998535,0,0,0,90.00000001 +248.78,50.30085681,-2.95885319,10500,0,200.0009685,0,0,0,90.00000001 +248.79,50.30085681,-2.958825164,10500,0,200.0009685,0,0,0,90.00000001 +248.8,50.30085681,-2.958797139,10500,0,199.9998535,0,0,0,90.00000001 +248.81,50.30085681,-2.958769114,10500,0,199.9991844,0,0,0,90.00000001 +248.82,50.30085681,-2.958741089,10500,0,199.9998535,0,0,0,90.00000001 +248.83,50.30085681,-2.958713064,10500,0,200.0009685,0,0,0,90.00000001 +248.84,50.30085681,-2.958685038,10500,0,200.0009685,0,0,0,90.00000001 +248.85,50.30085681,-2.958657013,10500,0,199.9998535,0,0,0,90.00000001 +248.86,50.30085681,-2.958628988,10500,0,199.9991844,0,0,0,90.00000001 +248.87,50.30085681,-2.958600963,10500,0,199.9998535,0,0,0,90.00000001 +248.88,50.30085681,-2.958572938,10500,0,200.0009685,0,0,0,90.00000001 +248.89,50.30085681,-2.958544912,10500,0,200.0009685,0,0,0,90.00000001 +248.9,50.30085681,-2.958516887,10500,0,199.9998535,0,0,0,90.00000001 +248.91,50.30085681,-2.958488862,10500,0,199.9991844,0,0,0,90.00000001 +248.92,50.30085681,-2.958460837,10500,0,199.9998535,0,0,0,90.00000001 +248.93,50.30085681,-2.958432812,10500,0,200.0009685,0,0,0,90.00000001 +248.94,50.30085681,-2.958404786,10500,0,200.0009685,0,0,0,90.00000001 +248.95,50.30085681,-2.958376761,10500,0,199.9998535,0,0,0,90.00000001 +248.96,50.30085681,-2.958348736,10500,0,199.9991844,0,0,0,90.00000001 +248.97,50.30085681,-2.958320711,10500,0,199.9998535,0,0,0,90.00000001 +248.98,50.30085681,-2.958292686,10500,0,200.0009685,0,0,0,90.00000001 +248.99,50.30085681,-2.95826466,10500,0,200.0009685,0,0,0,90.00000001 +249,50.30085681,-2.958236635,10500,0,199.9998535,0,0,0,90.00000001 +249.01,50.30085681,-2.95820861,10500,0,199.9991844,0,0,0,90.00000001 +249.02,50.30085681,-2.958180585,10500,0,199.9998535,0,0,0,90.00000001 +249.03,50.30085681,-2.95815256,10500,0,200.0009685,0,0,0,90.00000001 +249.04,50.30085681,-2.958124534,10500,0,200.0009685,0,0,0,90.00000001 +249.05,50.30085681,-2.958096509,10500,0,199.9998535,0,0,0,90.00000001 +249.06,50.30085681,-2.958068484,10500,0,199.9989614,0,0,0,90.00000001 +249.07,50.30085681,-2.958040459,10500,0,199.9989614,0,0,0,90.00000001 +249.08,50.30085681,-2.958012434,10500,0,199.9998535,0,0,0,90.00000001 +249.09,50.30085681,-2.957984409,10500,0,200.0009685,0,0,0,90.00000001 +249.1,50.30085681,-2.957956383,10500,0,200.0009685,0,0,0,90.00000001 +249.11,50.30085681,-2.957928358,10500,0,199.9998535,0,0,0,90.00000001 +249.12,50.30085681,-2.957900333,10500,0,199.9989614,0,0,0,90.00000001 +249.13,50.30085681,-2.957872308,10500,0,199.9989614,0,0,0,90.00000001 +249.14,50.30085681,-2.957844283,10500,0,199.9998535,0,0,0,90.00000001 +249.15,50.30085681,-2.957816258,10500,0,200.0009685,0,0,0,90.00000001 +249.16,50.30085681,-2.957788232,10500,0,200.0009685,0,0,0,90.00000001 +249.17,50.30085681,-2.957760207,10500,0,199.9998535,0,0,0,90.00000001 +249.18,50.30085681,-2.957732182,10500,0,199.9989614,0,0,0,90.00000001 +249.19,50.30085681,-2.957704157,10500,0,199.9989614,0,0,0,90.00000001 +249.2,50.30085681,-2.957676132,10500,0,199.9998535,0,0,0,90.00000001 +249.21,50.30085681,-2.957648107,10500,0,200.0009685,0,0,0,90.00000001 +249.22,50.30085681,-2.957620081,10500,0,200.0009685,0,0,0,90.00000001 +249.23,50.30085681,-2.957592056,10500,0,199.9998535,0,0,0,90.00000001 +249.24,50.30085681,-2.957564031,10500,0,199.9989614,0,0,0,90.00000001 +249.25,50.30085681,-2.957536006,10500,0,199.9987384,0,0,0,90.00000001 +249.26,50.30085681,-2.957507981,10500,0,199.9989614,0,0,0,90.00000001 +249.27,50.30085681,-2.957479956,10500,0,199.9998535,0,0,0,90.00000001 +249.28,50.30085681,-2.957451931,10500,0,200.0009685,0,0,0,90.00000001 +249.29,50.30085681,-2.957423905,10500,0,200.0009685,0,0,0,90.00000001 +249.3,50.30085681,-2.95739588,10500,0,199.9998535,0,0,0,90.00000001 +249.31,50.30085681,-2.957367855,10500,0,199.9989614,0,0,0,90.00000001 +249.32,50.30085681,-2.95733983,10500,0,199.9989614,0,0,0,90.00000001 +249.33,50.30085681,-2.957311805,10500,0,199.9998535,0,0,0,90.00000001 +249.34,50.30085681,-2.95728378,10500,0,200.0009685,0,0,0,90.00000001 +249.35,50.30085681,-2.957255754,10500,0,200.0009685,0,0,0,90.00000001 +249.36,50.30085681,-2.957227729,10500,0,199.9998535,0,0,0,90.00000001 +249.37,50.30085681,-2.957199704,10500,0,199.9989614,0,0,0,90.00000001 +249.38,50.30085681,-2.957171679,10500,0,199.9989614,0,0,0,90.00000001 +249.39,50.30085681,-2.957143654,10500,0,199.9998535,0,0,0,90.00000001 +249.4,50.30085681,-2.957115629,10500,0,200.0009685,0,0,0,90.00000001 +249.41,50.30085681,-2.957087603,10500,0,200.0009685,0,0,0,90.00000001 +249.42,50.30085681,-2.957059578,10500,0,199.9998535,0,0,0,90.00000001 +249.43,50.30085681,-2.957031553,10500,0,199.9991844,0,0,0,90.00000001 +249.44,50.30085681,-2.957003528,10500,0,199.9998535,0,0,0,90.00000001 +249.45,50.30085681,-2.956975503,10500,0,200.0009685,0,0,0,90.00000001 +249.46,50.30085681,-2.956947477,10500,0,200.0009685,0,0,0,90.00000001 +249.47,50.30085681,-2.956919452,10500,0,199.9998535,0,0,0,90.00000001 +249.48,50.30085681,-2.956891427,10500,0,199.9991844,0,0,0,90.00000001 +249.49,50.30085681,-2.956863402,10500,0,199.9998535,0,0,0,90.00000001 +249.5,50.30085681,-2.956835377,10500,0,200.0009685,0,0,0,90.00000001 +249.51,50.30085681,-2.956807351,10500,0,200.0009685,0,0,0,90.00000001 +249.52,50.30085681,-2.956779326,10500,0,199.9998535,0,0,0,90.00000001 +249.53,50.30085681,-2.956751301,10500,0,199.9991844,0,0,0,90.00000001 +249.54,50.30085681,-2.956723276,10500,0,199.9998535,0,0,0,90.00000001 +249.55,50.30085681,-2.956695251,10500,0,200.0009685,0,0,0,90.00000001 +249.56,50.30085681,-2.956667225,10500,0,200.0009685,0,0,0,90.00000001 +249.57,50.30085681,-2.9566392,10500,0,199.9998535,0,0,0,90.00000001 +249.58,50.30085681,-2.956611175,10500,0,199.9991844,0,0,0,90.00000001 +249.59,50.30085681,-2.95658315,10500,0,199.9998535,0,0,0,90.00000001 +249.6,50.30085681,-2.956555125,10500,0,200.0009685,0,0,0,90.00000001 +249.61,50.30085681,-2.956527099,10500,0,200.0009685,0,0,0,90.00000001 +249.62,50.30085681,-2.956499074,10500,0,199.9998535,0,0,0,90.00000001 +249.63,50.30085681,-2.956471049,10500,0,199.9991844,0,0,0,90.00000001 +249.64,50.30085681,-2.956443024,10500,0,199.9998535,0,0,0,90.00000001 +249.65,50.30085681,-2.956414999,10500,0,200.0009685,0,0,0,90.00000001 +249.66,50.30085681,-2.956386973,10500,0,200.0009685,0,0,0,90.00000001 +249.67,50.30085681,-2.956358948,10500,0,199.9998535,0,0,0,90.00000001 +249.68,50.30085681,-2.956330923,10500,0,199.9989614,0,0,0,90.00000001 +249.69,50.30085681,-2.956302898,10500,0,199.9989614,0,0,0,90.00000001 +249.7,50.30085681,-2.956274873,10500,0,199.9998535,0,0,0,90.00000001 +249.71,50.30085681,-2.956246848,10500,0,200.0009685,0,0,0,90.00000001 +249.72,50.30085681,-2.956218822,10500,0,200.0009685,0,0,0,90.00000001 +249.73,50.30085681,-2.956190797,10500,0,199.9998535,0,0,0,90.00000001 +249.74,50.30085681,-2.956162772,10500,0,199.9989614,0,0,0,90.00000001 +249.75,50.30085681,-2.956134747,10500,0,199.9989614,0,0,0,90.00000001 +249.76,50.30085681,-2.956106722,10500,0,199.9998535,0,0,0,90.00000001 +249.77,50.30085681,-2.956078697,10500,0,200.0009685,0,0,0,90.00000001 +249.78,50.30085681,-2.956050671,10500,0,200.0009685,0,0,0,90.00000001 +249.79,50.30085681,-2.956022646,10500,0,199.9998535,0,0,0,90.00000001 +249.8,50.30085681,-2.955994621,10500,0,199.9989614,0,0,0,90.00000001 +249.81,50.30085681,-2.955966596,10500,0,199.9987384,0,0,0,90.00000001 +249.82,50.30085681,-2.955938571,10500,0,199.9989614,0,0,0,90.00000001 +249.83,50.30085681,-2.955910546,10500,0,199.9998535,0,0,0,90.00000001 +249.84,50.30085681,-2.955882521,10500,0,200.0009685,0,0,0,90.00000001 +249.85,50.30085681,-2.955854495,10500,0,200.0009685,0,0,0,90.00000001 +249.86,50.30085681,-2.95582647,10500,0,199.9998535,0,0,0,90.00000001 +249.87,50.30085681,-2.955798445,10500,0,199.9989614,0,0,0,90.00000001 +249.88,50.30085681,-2.95577042,10500,0,199.9989614,0,0,0,90.00000001 +249.89,50.30085681,-2.955742395,10500,0,199.9998535,0,0,0,90.00000001 +249.9,50.30085681,-2.95571437,10500,0,200.0009685,0,0,0,90.00000001 +249.91,50.30085681,-2.955686344,10500,0,200.0009685,0,0,0,90.00000001 +249.92,50.30085681,-2.955658319,10500,0,199.9998535,0,0,0,90.00000001 +249.93,50.30085681,-2.955630294,10500,0,199.9989614,0,0,0,90.00000001 +249.94,50.30085681,-2.955602269,10500,0,199.9989614,0,0,0,90.00000001 +249.95,50.30085681,-2.955574244,10500,0,199.9998535,0,0,0,90.00000001 +249.96,50.30085681,-2.955546219,10500,0,200.0009685,0,0,0,90.00000001 +249.97,50.30085681,-2.955518193,10500,0,200.0009685,0,0,0,90.00000001 +249.98,50.30085681,-2.955490168,10500,0,199.9998535,0,0,0,90.00000001 +249.99,50.30085681,-2.955462143,10500,0,199.9989614,0,0,0,90.00000001 +250,50.30085681,-2.955434118,10500,0,199.9989614,0,0,0,90.00000001 +250.01,50.30085681,-2.955406093,10500,0,199.9998535,0,0,0,90.00000001 +250.02,50.30085681,-2.955378068,10500,0,200.0009685,0,0,0,90.00000001 +250.03,50.30085681,-2.955350042,10500,0,200.0009685,0,0,0,90.00000001 +250.04,50.30085681,-2.955322017,10500,0,199.9998535,0,0,0,90.00000001 +250.05,50.30085681,-2.955293992,10500,0,199.9991844,0,0,0,90.00000001 +250.06,50.30085681,-2.955265967,10500,0,199.9998535,0,0,0,90.00000001 +250.07,50.30085681,-2.955237942,10500,0,200.0009685,0,0,0,90.00000001 +250.08,50.30085681,-2.955209916,10500,0,200.0009685,0,0,0,90.00000001 +250.09,50.30085681,-2.955181891,10500,0,199.9998535,0,0,0,90.00000001 +250.1,50.30085681,-2.955153866,10500,0,199.9991844,0,0,0,90.00000001 +250.11,50.30085681,-2.955125841,10500,0,199.9998535,0,0,0,90.00000001 +250.12,50.30085681,-2.955097816,10500,0,200.0009685,0,0,0,90.00000001 +250.13,50.30085681,-2.95506979,10500,0,200.0009685,0,0,0,90.00000001 +250.14,50.30085681,-2.955041765,10500,0,199.9998535,0,0,0,90.00000001 +250.15,50.30085681,-2.95501374,10500,0,199.9991844,0,0,0,90.00000001 +250.16,50.30085681,-2.954985715,10500,0,199.9998535,0,0,0,90.00000001 +250.17,50.30085681,-2.95495769,10500,0,200.0009685,0,0,0,90.00000001 +250.18,50.30085681,-2.954929664,10500,0,200.0009685,0,0,0,90.00000001 +250.19,50.30085681,-2.954901639,10500,0,199.9998535,0,0,0,90.00000001 +250.2,50.30085681,-2.954873614,10500,0,199.9991844,0,0,0,90.00000001 +250.21,50.30085681,-2.954845589,10500,0,199.9998535,0,0,0,90.00000001 +250.22,50.30085681,-2.954817564,10500,0,200.0009685,0,0,0,90.00000001 +250.23,50.30085681,-2.954789538,10500,0,200.0009685,0,0,0,90.00000001 +250.24,50.30085681,-2.954761513,10500,0,199.9998535,0,0,0,90.00000001 +250.25,50.30085681,-2.954733488,10500,0,199.9991844,0,0,0,90.00000001 +250.26,50.30085681,-2.954705463,10500,0,199.9998535,0,0,0,90.00000001 +250.27,50.30085681,-2.954677438,10500,0,200.0009685,0,0,0,90.00000001 +250.28,50.30085681,-2.954649412,10500,0,200.0009685,0,0,0,90.00000001 +250.29,50.30085681,-2.954621387,10500,0,199.9998535,0,0,0,90.00000001 +250.3,50.30085681,-2.954593362,10500,0,199.9989614,0,0,0,90.00000001 +250.31,50.30085681,-2.954565337,10500,0,199.9989614,0,0,0,90.00000001 +250.32,50.30085681,-2.954537312,10500,0,199.9998535,0,0,0,90.00000001 +250.33,50.30085681,-2.954509287,10500,0,200.0009685,0,0,0,90.00000001 +250.34,50.30085681,-2.954481261,10500,0,200.0009685,0,0,0,90.00000001 +250.35,50.30085681,-2.954453236,10500,0,199.9998535,0,0,0,90.00000001 +250.36,50.30085681,-2.954425211,10500,0,199.9989614,0,0,0,90.00000001 +250.37,50.30085681,-2.954397186,10500,0,199.9987384,0,0,0,90.00000001 +250.38,50.30085681,-2.954369161,10500,0,199.9989614,0,0,0,90.00000001 +250.39,50.30085681,-2.954341136,10500,0,199.9998535,0,0,0,90.00000001 +250.4,50.30085681,-2.954313111,10500,0,200.0009685,0,0,0,90.00000001 +250.41,50.30085681,-2.954285085,10500,0,200.0009685,0,0,0,90.00000001 +250.42,50.30085681,-2.95425706,10500,0,199.9998535,0,0,0,90.00000001 +250.43,50.30085681,-2.954229035,10500,0,199.9989614,0,0,0,90.00000001 +250.44,50.30085681,-2.95420101,10500,0,199.9989614,0,0,0,90.00000001 +250.45,50.30085681,-2.954172985,10500,0,199.9998535,0,0,0,90.00000001 +250.46,50.30085681,-2.95414496,10500,0,200.0009685,0,0,0,90.00000001 +250.47,50.30085681,-2.954116934,10500,0,200.0009685,0,0,0,90.00000001 +250.48,50.30085681,-2.954088909,10500,0,199.9998535,0,0,0,90.00000001 +250.49,50.30085681,-2.954060884,10500,0,199.9989614,0,0,0,90.00000001 +250.5,50.30085681,-2.954032859,10500,0,199.9989614,0,0,0,90.00000001 +250.51,50.30085681,-2.954004834,10500,0,199.9998535,0,0,0,90.00000001 +250.52,50.30085681,-2.953976809,10500,0,200.0009685,0,0,0,90.00000001 +250.53,50.30085681,-2.953948783,10500,0,200.0009685,0,0,0,90.00000001 +250.54,50.30085681,-2.953920758,10500,0,199.9998535,0,0,0,90.00000001 +250.55,50.30085681,-2.953892733,10500,0,199.9989614,0,0,0,90.00000001 +250.56,50.30085681,-2.953864708,10500,0,199.9989614,0,0,0,90.00000001 +250.57,50.30085681,-2.953836683,10500,0,199.9998535,0,0,0,90.00000001 +250.58,50.30085681,-2.953808658,10500,0,200.0009685,0,0,0,90.00000001 +250.59,50.30085681,-2.953780632,10500,0,200.0009685,0,0,0,90.00000001 +250.6,50.30085681,-2.953752607,10500,0,199.9998535,0,0,0,90.00000001 +250.61,50.30085681,-2.953724582,10500,0,199.9989614,0,0,0,90.00000001 +250.62,50.30085681,-2.953696557,10500,0,199.9989614,0,0,0,90.00000001 +250.63,50.30085681,-2.953668532,10500,0,199.9998535,0,0,0,90.00000001 +250.64,50.30085681,-2.953640507,10500,0,200.0009685,0,0,0,90.00000001 +250.65,50.30085681,-2.953612481,10500,0,200.0009685,0,0,0,90.00000001 +250.66,50.30085681,-2.953584456,10500,0,199.9998535,0,0,0,90.00000001 +250.67,50.30085681,-2.953556431,10500,0,199.9991844,0,0,0,90.00000001 +250.68,50.30085681,-2.953528406,10500,0,199.9998535,0,0,0,90.00000001 +250.69,50.30085681,-2.953500381,10500,0,200.0009685,0,0,0,90.00000001 +250.7,50.30085681,-2.953472355,10500,0,200.0009685,0,0,0,90.00000001 +250.71,50.30085681,-2.95344433,10500,0,199.9998535,0,0,0,90.00000001 +250.72,50.30085681,-2.953416305,10500,0,199.9991844,0,0,0,90.00000001 +250.73,50.30085681,-2.95338828,10500,0,199.9998535,0,0,0,90.00000001 +250.74,50.30085681,-2.953360255,10500,0,200.0009685,0,0,0,90.00000001 +250.75,50.30085681,-2.953332229,10500,0,200.0009685,0,0,0,90.00000001 +250.76,50.30085681,-2.953304204,10500,0,199.9998535,0,0,0,90.00000001 +250.77,50.30085681,-2.953276179,10500,0,199.9989614,0,0,0,90.00000001 +250.78,50.30085681,-2.953248154,10500,0,199.9989614,0,0,0,90.00000001 +250.79,50.30085681,-2.953220129,10500,0,199.9998535,0,0,0,90.00000001 +250.8,50.30085681,-2.953192104,10500,0,200.0009685,0,0,0,90.00000001 +250.81,50.30085681,-2.953164078,10500,0,200.0009685,0,0,0,90.00000001 +250.82,50.30085681,-2.953136053,10500,0,199.9998535,0,0,0,90.00000001 +250.83,50.30085681,-2.953108028,10500,0,199.9991844,0,0,0,90.00000001 +250.84,50.30085681,-2.953080003,10500,0,199.9998535,0,0,0,90.00000001 +250.85,50.30085681,-2.953051978,10500,0,200.0009685,0,0,0,90.00000001 +250.86,50.30085681,-2.953023952,10500,0,200.0009685,0,0,0,90.00000001 +250.87,50.30085681,-2.952995927,10500,0,199.9998535,0,0,0,90.00000001 +250.88,50.30085681,-2.952967902,10500,0,199.9991844,0,0,0,90.00000001 +250.89,50.30085681,-2.952939877,10500,0,199.9998535,0,0,0,90.00000001 +250.9,50.30085681,-2.952911852,10500,0,200.0009685,0,0,0,90.00000001 +250.91,50.30085681,-2.952883826,10500,0,200.0009685,0,0,0,90.00000001 +250.92,50.30085681,-2.952855801,10500,0,199.9998535,0,0,0,90.00000001 +250.93,50.30085681,-2.952827776,10500,0,199.9989614,0,0,0,90.00000001 +250.94,50.30085681,-2.952799751,10500,0,199.9989614,0,0,0,90.00000001 +250.95,50.30085681,-2.952771726,10500,0,199.9998535,0,0,0,90.00000001 +250.96,50.30085681,-2.952743701,10500,0,200.0009685,0,0,0,90.00000001 +250.97,50.30085681,-2.952715675,10500,0,200.0009685,0,0,0,90.00000001 +250.98,50.30085681,-2.95268765,10500,0,199.9998535,0,0,0,90.00000001 +250.99,50.30085681,-2.952659625,10500,0,199.9989614,0,0,0,90.00000001 +251,50.30085681,-2.9526316,10500,0,199.9989614,0,0,0,90.00000001 +251.01,50.30085681,-2.952603575,10500,0,199.9998535,0,0,0,90.00000001 +251.02,50.30085681,-2.95257555,10500,0,200.0009685,0,0,0,90.00000001 +251.03,50.30085681,-2.952547524,10500,0,200.0009685,0,0,0,90.00000001 +251.04,50.30085681,-2.952519499,10500,0,199.9998535,0,0,0,90.00000001 +251.05,50.30085681,-2.952491474,10500,0,199.9989614,0,0,0,90.00000001 +251.06,50.30085681,-2.952463449,10500,0,199.9989614,0,0,0,90.00000001 +251.07,50.30085681,-2.952435424,10500,0,199.9998535,0,0,0,90.00000001 +251.08,50.30085681,-2.952407399,10500,0,200.0009685,0,0,0,90.00000001 +251.09,50.30085681,-2.952379373,10500,0,200.0009685,0,0,0,90.00000001 +251.1,50.30085681,-2.952351348,10500,0,199.9998535,0,0,0,90.00000001 +251.11,50.30085681,-2.952323323,10500,0,199.9989614,0,0,0,90.00000001 +251.12,50.30085681,-2.952295298,10500,0,199.9989614,0,0,0,90.00000001 +251.13,50.30085681,-2.952267273,10500,0,199.9998535,0,0,0,90.00000001 +251.14,50.30085681,-2.952239248,10500,0,200.0009685,0,0,0,90.00000001 +251.15,50.30085681,-2.952211222,10500,0,200.0009685,0,0,0,90.00000001 +251.16,50.30085681,-2.952183197,10500,0,199.9998535,0,0,0,90.00000001 +251.17,50.30085681,-2.952155172,10500,0,199.9989614,0,0,0,90.00000001 +251.18,50.30085681,-2.952127147,10500,0,199.9989614,0,0,0,90.00000001 +251.19,50.30085681,-2.952099122,10500,0,199.9998535,0,0,0,90.00000001 +251.2,50.30085681,-2.952071097,10500,0,200.0009685,0,0,0,90.00000001 +251.21,50.30085681,-2.952043071,10500,0,200.0009685,0,0,0,90.00000001 +251.22,50.30085681,-2.952015046,10500,0,199.9998535,0,0,0,90.00000001 +251.23,50.30085681,-2.951987021,10500,0,199.9989614,0,0,0,90.00000001 +251.24,50.30085681,-2.951958996,10500,0,199.9987384,0,0,0,90.00000001 +251.25,50.30085681,-2.951930971,10500,0,199.9989614,0,0,0,90.00000001 +251.26,50.30085681,-2.951902946,10500,0,199.9998535,0,0,0,90.00000001 +251.27,50.30085681,-2.951874921,10500,0,200.0009685,0,0,0,90.00000001 +251.28,50.30085681,-2.951846895,10500,0,200.0009685,0,0,0,90.00000001 +251.29,50.30085681,-2.95181887,10500,0,199.9998535,0,0,0,90.00000001 +251.3,50.30085681,-2.951790845,10500,0,199.9991844,0,0,0,90.00000001 +251.31,50.30085681,-2.95176282,10500,0,199.9998535,0,0,0,90.00000001 +251.32,50.30085681,-2.951734795,10500,0,200.0009685,0,0,0,90.00000001 +251.33,50.30085681,-2.951706769,10500,0,200.0009685,0,0,0,90.00000001 +251.34,50.30085681,-2.951678744,10500,0,199.9998535,0,0,0,90.00000001 +251.35,50.30085681,-2.951650719,10500,0,199.9991844,0,0,0,90.00000001 +251.36,50.30085681,-2.951622694,10500,0,199.9998535,0,0,0,90.00000001 +251.37,50.30085681,-2.951594669,10500,0,200.0009685,0,0,0,90.00000001 +251.38,50.30085681,-2.951566643,10500,0,200.0009685,0,0,0,90.00000001 +251.39,50.30085681,-2.951538618,10500,0,199.9998535,0,0,0,90.00000001 +251.4,50.30085681,-2.951510593,10500,0,199.9991844,0,0,0,90.00000001 +251.41,50.30085681,-2.951482568,10500,0,199.9998535,0,0,0,90.00000001 +251.42,50.30085681,-2.951454543,10500,0,200.0009685,0,0,0,90.00000001 +251.43,50.30085681,-2.951426517,10500,0,200.0009685,0,0,0,90.00000001 +251.44,50.30085681,-2.951398492,10500,0,199.9998535,0,0,0,90.00000001 +251.45,50.30085681,-2.951370467,10500,0,199.9991844,0,0,0,90.00000001 +251.46,50.30085681,-2.951342442,10500,0,199.9998535,0,0,0,90.00000001 +251.47,50.30085681,-2.951314417,10500,0,200.0009685,0,0,0,90.00000001 +251.48,50.30085681,-2.951286391,10500,0,200.0009685,0,0,0,90.00000001 +251.49,50.30085681,-2.951258366,10500,0,199.9998535,0,0,0,90.00000001 +251.5,50.30085681,-2.951230341,10500,0,199.9991844,0,0,0,90.00000001 +251.51,50.30085681,-2.951202316,10500,0,199.9998535,0,0,0,90.00000001 +251.52,50.30085681,-2.951174291,10500,0,200.0009685,0,0,0,90.00000001 +251.53,50.30085681,-2.951146265,10500,0,200.0009685,0,0,0,90.00000001 +251.54,50.30085681,-2.95111824,10500,0,199.9998535,0,0,0,90.00000001 +251.55,50.30085681,-2.951090215,10500,0,199.9989614,0,0,0,90.00000001 +251.56,50.30085681,-2.95106219,10500,0,199.9989614,0,0,0,90.00000001 +251.57,50.30085681,-2.951034165,10500,0,199.9998535,0,0,0,90.00000001 +251.58,50.30085681,-2.95100614,10500,0,200.0009685,0,0,0,90.00000001 +251.59,50.30085681,-2.950978114,10500,0,200.0009685,0,0,0,90.00000001 +251.6,50.30085681,-2.950950089,10500,0,199.9998535,0,0,0,90.00000001 +251.61,50.30085681,-2.950922064,10500,0,199.9989614,0,0,0,90.00000001 +251.62,50.30085681,-2.950894039,10500,0,199.9989614,0,0,0,90.00000001 +251.63,50.30085681,-2.950866014,10500,0,199.9998535,0,0,0,90.00000001 +251.64,50.30085681,-2.950837989,10500,0,200.0009685,0,0,0,90.00000001 +251.65,50.30085681,-2.950809963,10500,0,200.0009685,0,0,0,90.00000001 +251.66,50.30085681,-2.950781938,10500,0,199.9998535,0,0,0,90.00000001 +251.67,50.30085681,-2.950753913,10500,0,199.9989614,0,0,0,90.00000001 +251.68,50.30085681,-2.950725888,10500,0,199.9989614,0,0,0,90.00000001 +251.69,50.30085681,-2.950697863,10500,0,199.9998535,0,0,0,90.00000001 +251.7,50.30085681,-2.950669838,10500,0,200.0009685,0,0,0,90.00000001 +251.71,50.30085681,-2.950641812,10500,0,200.0009685,0,0,0,90.00000001 +251.72,50.30085681,-2.950613787,10500,0,199.9998535,0,0,0,90.00000001 +251.73,50.30085681,-2.950585762,10500,0,199.9989614,0,0,0,90.00000001 +251.74,50.30085681,-2.950557737,10500,0,199.9989614,0,0,0,90.00000001 +251.75,50.30085681,-2.950529712,10500,0,199.9998535,0,0,0,90.00000001 +251.76,50.30085681,-2.950501687,10500,0,200.0009685,0,0,0,90.00000001 +251.77,50.30085681,-2.950473661,10500,0,200.0009685,0,0,0,90.00000001 +251.78,50.30085681,-2.950445636,10500,0,199.9998535,0,0,0,90.00000001 +251.79,50.30085681,-2.950417611,10500,0,199.9989614,0,0,0,90.00000001 +251.8,50.30085681,-2.950389586,10500,0,199.9987384,0,0,0,90.00000001 +251.81,50.30085681,-2.950361561,10500,0,199.9989614,0,0,0,90.00000001 +251.82,50.30085681,-2.950333536,10500,0,199.9998535,0,0,0,90.00000001 +251.83,50.30085681,-2.950305511,10500,0,200.0009685,0,0,0,90.00000001 +251.84,50.30085681,-2.950277485,10500,0,200.0009685,0,0,0,90.00000001 +251.85,50.30085681,-2.95024946,10500,0,199.9998535,0,0,0,90.00000001 +251.86,50.30085681,-2.950221435,10500,0,199.9989614,0,0,0,90.00000001 +251.87,50.30085681,-2.95019341,10500,0,199.9989614,0,0,0,90.00000001 +251.88,50.30085681,-2.950165385,10500,0,199.9998535,0,0,0,90.00000001 +251.89,50.30085681,-2.95013736,10500,0,200.0009685,0,0,0,90.00000001 +251.9,50.30085681,-2.950109334,10500,0,200.0009685,0,0,0,90.00000001 +251.91,50.30085681,-2.950081309,10500,0,199.9998535,0,0,0,90.00000001 +251.92,50.30085681,-2.950053284,10500,0,199.9991844,0,0,0,90.00000001 +251.93,50.30085681,-2.950025259,10500,0,199.9998535,0,0,0,90.00000001 +251.94,50.30085681,-2.949997234,10500,0,200.0009685,0,0,0,90.00000001 +251.95,50.30085681,-2.949969208,10500,0,200.0009685,0,0,0,90.00000001 +251.96,50.30085681,-2.949941183,10500,0,199.9998535,0,0,0,90.00000001 +251.97,50.30085681,-2.949913158,10500,0,199.9991844,0,0,0,90.00000001 +251.98,50.30085681,-2.949885133,10500,0,199.9998535,0,0,0,90.00000001 +251.99,50.30085681,-2.949857108,10500,0,200.0009685,0,0,0,90.00000001 +252,50.30085681,-2.949829082,10500,0,200.0009685,0,0,0,90.00000001 +252.01,50.30085681,-2.949801057,10500,0,199.9998535,0,0,0,90.00000001 +252.02,50.30085681,-2.949773032,10500,0,199.9991844,0,0,0,90.00000001 +252.03,50.30085681,-2.949745007,10500,0,199.9998535,0,0,0,90.00000001 +252.04,50.30085681,-2.949716982,10500,0,200.0009685,0,0,0,90.00000001 +252.05,50.30085681,-2.949688956,10500,0,200.0009685,0,0,0,90.00000001 +252.06,50.30085681,-2.949660931,10500,0,199.9998535,0,0,0,90.00000001 +252.07,50.30085681,-2.949632906,10500,0,199.9991844,0,0,0,90.00000001 +252.08,50.30085681,-2.949604881,10500,0,199.9998535,0,0,0,90.00000001 +252.09,50.30085681,-2.949576856,10500,0,200.0009685,0,0,0,90.00000001 +252.1,50.30085681,-2.94954883,10500,0,200.0009685,0,0,0,90.00000001 +252.11,50.30085681,-2.949520805,10500,0,199.9998535,0,0,0,90.00000001 +252.12,50.30085681,-2.94949278,10500,0,199.9991844,0,0,0,90.00000001 +252.13,50.30085681,-2.949464755,10500,0,199.9998535,0,0,0,90.00000001 +252.14,50.30085681,-2.94943673,10500,0,200.0009685,0,0,0,90.00000001 +252.15,50.30085681,-2.949408704,10500,0,200.0009685,0,0,0,90.00000001 +252.16,50.30085681,-2.949380679,10500,0,199.9998535,0,0,0,90.00000001 +252.17,50.30085681,-2.949352654,10500,0,199.9989614,0,0,0,90.00000001 +252.18,50.30085681,-2.949324629,10500,0,199.9989614,0,0,0,90.00000001 +252.19,50.30085681,-2.949296604,10500,0,199.9998535,0,0,0,90.00000001 +252.2,50.30085681,-2.949268579,10500,0,200.0009685,0,0,0,90.00000001 +252.21,50.30085681,-2.949240553,10500,0,200.0009685,0,0,0,90.00000001 +252.22,50.30085681,-2.949212528,10500,0,199.9998535,0,0,0,90.00000001 +252.23,50.30085681,-2.949184503,10500,0,199.9989614,0,0,0,90.00000001 +252.24,50.30085681,-2.949156478,10500,0,199.9989614,0,0,0,90.00000001 +252.25,50.30085681,-2.949128453,10500,0,199.9998535,0,0,0,90.00000001 +252.26,50.30085681,-2.949100428,10500,0,200.0009685,0,0,0,90.00000001 +252.27,50.30085681,-2.949072402,10500,0,200.0009685,0,0,0,90.00000001 +252.28,50.30085681,-2.949044377,10500,0,199.9998535,0,0,0,90.00000001 +252.29,50.30085681,-2.949016352,10500,0,199.9989614,0,0,0,90.00000001 +252.3,50.30085681,-2.948988327,10500,0,199.9989614,0,0,0,90.00000001 +252.31,50.30085681,-2.948960302,10500,0,199.9998535,0,0,0,90.00000001 +252.32,50.30085681,-2.948932277,10500,0,200.0009685,0,0,0,90.00000001 +252.33,50.30085681,-2.948904251,10500,0,200.0009685,0,0,0,90.00000001 +252.34,50.30085681,-2.948876226,10500,0,199.9998535,0,0,0,90.00000001 +252.35,50.30085681,-2.948848201,10500,0,199.9989614,0,0,0,90.00000001 +252.36,50.30085681,-2.948820176,10500,0,199.9987384,0,0,0,90.00000001 +252.37,50.30085681,-2.948792151,10500,0,199.9989614,0,0,0,90.00000001 +252.38,50.30085681,-2.948764126,10500,0,199.9998535,0,0,0,90.00000001 +252.39,50.30085681,-2.948736101,10500,0,200.0009685,0,0,0,90.00000001 +252.4,50.30085681,-2.948708075,10500,0,200.0009685,0,0,0,90.00000001 +252.41,50.30085681,-2.94868005,10500,0,199.9998535,0,0,0,90.00000001 +252.42,50.30085681,-2.948652025,10500,0,199.9989614,0,0,0,90.00000001 +252.43,50.30085681,-2.948624,10500,0,199.9989614,0,0,0,90.00000001 +252.44,50.30085681,-2.948595975,10500,0,199.9998535,0,0,0,90.00000001 +252.45,50.30085681,-2.94856795,10500,0,200.0009685,0,0,0,90.00000001 +252.46,50.30085681,-2.948539924,10500,0,200.0009685,0,0,0,90.00000001 +252.47,50.30085681,-2.948511899,10500,0,199.9998535,0,0,0,90.00000001 +252.48,50.30085681,-2.948483874,10500,0,199.9989614,0,0,0,90.00000001 +252.49,50.30085681,-2.948455849,10500,0,199.9989614,0,0,0,90.00000001 +252.5,50.30085681,-2.948427824,10500,0,199.9998535,0,0,0,90.00000001 +252.51,50.30085681,-2.948399799,10500,0,200.0009685,0,0,0,90.00000001 +252.52,50.30085681,-2.948371773,10500,0,200.0009685,0,0,0,90.00000001 +252.53,50.30085681,-2.948343748,10500,0,199.9998535,0,0,0,90.00000001 +252.54,50.30085681,-2.948315723,10500,0,199.9991844,0,0,0,90.00000001 +252.55,50.30085681,-2.948287698,10500,0,199.9998535,0,0,0,90.00000001 +252.56,50.30085681,-2.948259673,10500,0,200.0009685,0,0,0,90.00000001 +252.57,50.30085681,-2.948231647,10500,0,200.0009685,0,0,0,90.00000001 +252.58,50.30085681,-2.948203622,10500,0,199.9998535,0,0,0,90.00000001 +252.59,50.30085681,-2.948175597,10500,0,199.9991844,0,0,0,90.00000001 +252.6,50.30085681,-2.948147572,10500,0,199.9998535,0,0,0,90.00000001 +252.61,50.30085681,-2.948119547,10500,0,200.0009685,0,0,0,90.00000001 +252.62,50.30085681,-2.948091521,10500,0,200.0009685,0,0,0,90.00000001 +252.63,50.30085681,-2.948063496,10500,0,199.9998535,0,0,0,90.00000001 +252.64,50.30085681,-2.948035471,10500,0,199.9991844,0,0,0,90.00000001 +252.65,50.30085681,-2.948007446,10500,0,199.9998535,0,0,0,90.00000001 +252.66,50.30085681,-2.947979421,10500,0,200.0009685,0,0,0,90.00000001 +252.67,50.30085681,-2.947951395,10500,0,200.0009685,0,0,0,90.00000001 +252.68,50.30085681,-2.94792337,10500,0,199.9998535,0,0,0,90.00000001 +252.69,50.30085681,-2.947895345,10500,0,199.9991844,0,0,0,90.00000001 +252.7,50.30085681,-2.94786732,10500,0,199.9998535,0,0,0,90.00000001 +252.71,50.30085681,-2.947839295,10500,0,200.0009685,0,0,0,90.00000001 +252.72,50.30085681,-2.947811269,10500,0,200.0009685,0,0,0,90.00000001 +252.73,50.30085681,-2.947783244,10500,0,199.9998535,0,0,0,90.00000001 +252.74,50.30085681,-2.947755219,10500,0,199.9991844,0,0,0,90.00000001 +252.75,50.30085681,-2.947727194,10500,0,199.9998535,0,0,0,90.00000001 +252.76,50.30085681,-2.947699169,10500,0,200.0009685,0,0,0,90.00000001 +252.77,50.30085681,-2.947671143,10500,0,200.0009685,0,0,0,90.00000001 +252.78,50.30085681,-2.947643118,10500,0,199.9998535,0,0,0,90.00000001 +252.79,50.30085681,-2.947615093,10500,0,199.9989614,0,0,0,90.00000001 +252.8,50.30085681,-2.947587068,10500,0,199.9989614,0,0,0,90.00000001 +252.81,50.30085681,-2.947559043,10500,0,199.9998535,0,0,0,90.00000001 +252.82,50.30085681,-2.947531018,10500,0,200.0009685,0,0,0,90.00000001 +252.83,50.30085681,-2.947502992,10500,0,200.0009685,0,0,0,90.00000001 +252.84,50.30085681,-2.947474967,10500,0,199.9998535,0,0,0,90.00000001 +252.85,50.30085681,-2.947446942,10500,0,199.9989614,0,0,0,90.00000001 +252.86,50.30085681,-2.947418917,10500,0,199.9989614,0,0,0,90.00000001 +252.87,50.30085681,-2.947390892,10500,0,199.9998535,0,0,0,90.00000001 +252.88,50.30085681,-2.947362867,10500,0,200.0009685,0,0,0,90.00000001 +252.89,50.30085681,-2.947334841,10500,0,200.0009685,0,0,0,90.00000001 +252.9,50.30085681,-2.947306816,10500,0,199.9998535,0,0,0,90.00000001 +252.91,50.30085681,-2.947278791,10500,0,199.9989614,0,0,0,90.00000001 +252.92,50.30085681,-2.947250766,10500,0,199.9987384,0,0,0,90.00000001 +252.93,50.30085681,-2.947222741,10500,0,199.9989614,0,0,0,90.00000001 +252.94,50.30085681,-2.947194716,10500,0,199.9998535,0,0,0,90.00000001 +252.95,50.30085681,-2.947166691,10500,0,200.0009685,0,0,0,90.00000001 +252.96,50.30085681,-2.947138665,10500,0,200.0009685,0,0,0,90.00000001 +252.97,50.30085681,-2.94711064,10500,0,199.9998535,0,0,0,90.00000001 +252.98,50.30085681,-2.947082615,10500,0,199.9989614,0,0,0,90.00000001 +252.99,50.30085681,-2.94705459,10500,0,199.9989614,0,0,0,90.00000001 +253,50.30085681,-2.947026565,10500,0,199.9998535,0,0,0,90.00000001 +253.01,50.30085681,-2.94699854,10500,0,200.0009685,0,0,0,90.00000001 +253.02,50.30085681,-2.946970514,10500,0,200.0009685,0,0,0,90.00000001 +253.03,50.30085681,-2.946942489,10500,0,199.9998535,0,0,0,90.00000001 +253.04,50.30085681,-2.946914464,10500,0,199.9989614,0,0,0,90.00000001 +253.05,50.30085681,-2.946886439,10500,0,199.9989614,0,0,0,90.00000001 +253.06,50.30085681,-2.946858414,10500,0,199.9998535,0,0,0,90.00000001 +253.07,50.30085681,-2.946830389,10500,0,200.0009685,0,0,0,90.00000001 +253.08,50.30085681,-2.946802363,10500,0,200.0009685,0,0,0,90.00000001 +253.09,50.30085681,-2.946774338,10500,0,199.9998535,0,0,0,90.00000001 +253.1,50.30085681,-2.946746313,10500,0,199.9989614,0,0,0,90.00000001 +253.11,50.30085681,-2.946718288,10500,0,199.9989614,0,0,0,90.00000001 +253.12,50.30085681,-2.946690263,10500,0,199.9998535,0,0,0,90.00000001 +253.13,50.30085681,-2.946662238,10500,0,200.0009685,0,0,0,90.00000001 +253.14,50.30085681,-2.946634212,10500,0,200.0009685,0,0,0,90.00000001 +253.15,50.30085681,-2.946606187,10500,0,199.9998535,0,0,0,90.00000001 +253.16,50.30085681,-2.946578162,10500,0,199.9989614,0,0,0,90.00000001 +253.17,50.30085681,-2.946550137,10500,0,199.9989614,0,0,0,90.00000001 +253.18,50.30085681,-2.946522112,10500,0,199.9998535,0,0,0,90.00000001 +253.19,50.30085681,-2.946494087,10500,0,200.0009685,0,0,0,90.00000001 +253.2,50.30085681,-2.946466061,10500,0,200.0009685,0,0,0,90.00000001 +253.21,50.30085681,-2.946438036,10500,0,199.9998535,0,0,0,90.00000001 +253.22,50.30085681,-2.946410011,10500,0,199.9991844,0,0,0,90.00000001 +253.23,50.30085681,-2.946381986,10500,0,199.9998535,0,0,0,90.00000001 +253.24,50.30085681,-2.946353961,10500,0,200.0009685,0,0,0,90.00000001 +253.25,50.30085681,-2.946325935,10500,0,200.0009685,0,0,0,90.00000001 +253.26,50.30085681,-2.94629791,10500,0,199.9998535,0,0,0,90.00000001 +253.27,50.30085681,-2.946269885,10500,0,199.9991844,0,0,0,90.00000001 +253.28,50.30085681,-2.94624186,10500,0,199.9998535,0,0,0,90.00000001 +253.29,50.30085681,-2.946213835,10500,0,200.0009685,0,0,0,90.00000001 +253.3,50.30085681,-2.946185809,10500,0,200.0009685,0,0,0,90.00000001 +253.31,50.30085681,-2.946157784,10500,0,199.9998535,0,0,0,90.00000001 +253.32,50.30085681,-2.946129759,10500,0,199.9991844,0,0,0,90.00000001 +253.33,50.30085681,-2.946101734,10500,0,199.9998535,0,0,0,90.00000001 +253.34,50.30085681,-2.946073709,10500,0,200.0009685,0,0,0,90.00000001 +253.35,50.30085681,-2.946045683,10500,0,200.0009685,0,0,0,90.00000001 +253.36,50.30085681,-2.946017658,10500,0,199.9998535,0,0,0,90.00000001 +253.37,50.30085681,-2.945989633,10500,0,199.9991844,0,0,0,90.00000001 +253.38,50.30085681,-2.945961608,10500,0,199.9998535,0,0,0,90.00000001 +253.39,50.30085681,-2.945933583,10500,0,200.0009685,0,0,0,90.00000001 +253.4,50.30085681,-2.945905557,10500,0,200.0009685,0,0,0,90.00000001 +253.41,50.30085681,-2.945877532,10500,0,199.9998535,0,0,0,90.00000001 +253.42,50.30085681,-2.945849507,10500,0,199.9991844,0,0,0,90.00000001 +253.43,50.30085681,-2.945821482,10500,0,199.9998535,0,0,0,90.00000001 +253.44,50.30085681,-2.945793457,10500,0,200.0009685,0,0,0,90.00000001 +253.45,50.30085681,-2.945765431,10500,0,200.0009685,0,0,0,90.00000001 +253.46,50.30085681,-2.945737406,10500,0,199.9998535,0,0,0,90.00000001 +253.47,50.30085681,-2.945709381,10500,0,199.9989614,0,0,0,90.00000001 +253.48,50.30085681,-2.945681356,10500,0,199.9989614,0,0,0,90.00000001 +253.49,50.30085681,-2.945653331,10500,0,199.9998535,0,0,0,90.00000001 +253.5,50.30085681,-2.945625306,10500,0,200.0009685,0,0,0,90.00000001 +253.51,50.30085681,-2.94559728,10500,0,200.0009685,0,0,0,90.00000001 +253.52,50.30085681,-2.945569255,10500,0,199.9998535,0,0,0,90.00000001 +253.53,50.30085681,-2.94554123,10500,0,199.9989614,0,0,0,90.00000001 +253.54,50.30085681,-2.945513205,10500,0,199.9987384,0,0,0,90.00000001 +253.55,50.30085681,-2.94548518,10500,0,199.9989614,0,0,0,90.00000001 +253.56,50.30085681,-2.945457155,10500,0,199.9998535,0,0,0,90.00000001 +253.57,50.30085681,-2.94542913,10500,0,200.0009685,0,0,0,90.00000001 +253.58,50.30085681,-2.945401104,10500,0,200.0009685,0,0,0,90.00000001 +253.59,50.30085681,-2.945373079,10500,0,199.9998535,0,0,0,90.00000001 +253.6,50.30085681,-2.945345054,10500,0,199.9989614,0,0,0,90.00000001 +253.61,50.30085681,-2.945317029,10500,0,199.9989614,0,0,0,90.00000001 +253.62,50.30085681,-2.945289004,10500,0,199.9998535,0,0,0,90.00000001 +253.63,50.30085681,-2.945260979,10500,0,200.0009685,0,0,0,90.00000001 +253.64,50.30085681,-2.945232953,10500,0,200.0009685,0,0,0,90.00000001 +253.65,50.30085681,-2.945204928,10500,0,199.9998535,0,0,0,90.00000001 +253.66,50.30085681,-2.945176903,10500,0,199.9989614,0,0,0,90.00000001 +253.67,50.30085681,-2.945148878,10500,0,199.9989614,0,0,0,90.00000001 +253.68,50.30085681,-2.945120853,10500,0,199.9998535,0,0,0,90.00000001 +253.69,50.30085681,-2.945092828,10500,0,200.0009685,0,0,0,90.00000001 +253.7,50.30085681,-2.945064802,10500,0,200.0009685,0,0,0,90.00000001 +253.71,50.30085681,-2.945036777,10500,0,199.9998535,0,0,0,90.00000001 +253.72,50.30085681,-2.945008752,10500,0,199.9989614,0,0,0,90.00000001 +253.73,50.30085681,-2.944980727,10500,0,199.9989614,0,0,0,90.00000001 +253.74,50.30085681,-2.944952702,10500,0,199.9998535,0,0,0,90.00000001 +253.75,50.30085681,-2.944924677,10500,0,200.0009685,0,0,0,90.00000001 +253.76,50.30085681,-2.944896651,10500,0,200.0009685,0,0,0,90.00000001 +253.77,50.30085681,-2.944868626,10500,0,199.9998535,0,0,0,90.00000001 +253.78,50.30085681,-2.944840601,10500,0,199.9989614,0,0,0,90.00000001 +253.79,50.30085681,-2.944812576,10500,0,199.9989614,0,0,0,90.00000001 +253.8,50.30085681,-2.944784551,10500,0,199.9998535,0,0,0,90.00000001 +253.81,50.30085681,-2.944756526,10500,0,200.0009685,0,0,0,90.00000001 +253.82,50.30085681,-2.9447285,10500,0,200.0009685,0,0,0,90.00000001 +253.83,50.30085681,-2.944700475,10500,0,199.9998535,0,0,0,90.00000001 +253.84,50.30085681,-2.94467245,10500,0,199.9991844,0,0,0,90.00000001 +253.85,50.30085681,-2.944644425,10500,0,199.9998535,0,0,0,90.00000001 +253.86,50.30085681,-2.9446164,10500,0,200.0009685,0,0,0,90.00000001 +253.87,50.30085681,-2.944588374,10500,0,200.0009685,0,0,0,90.00000001 +253.88,50.30085681,-2.944560349,10500,0,199.9998535,0,0,0,90.00000001 +253.89,50.30085681,-2.944532324,10500,0,199.9991844,0,0,0,90.00000001 +253.9,50.30085681,-2.944504299,10500,0,199.9998535,0,0,0,90.00000001 +253.91,50.30085681,-2.944476274,10500,0,200.0009685,0,0,0,90.00000001 +253.92,50.30085681,-2.944448248,10500,0,200.0009685,0,0,0,90.00000001 +253.93,50.30085681,-2.944420223,10500,0,199.9998535,0,0,0,90.00000001 +253.94,50.30085681,-2.944392198,10500,0,199.9991844,0,0,0,90.00000001 +253.95,50.30085681,-2.944364173,10500,0,199.9998535,0,0,0,90.00000001 +253.96,50.30085681,-2.944336148,10500,0,200.0009685,0,0,0,90.00000001 +253.97,50.30085681,-2.944308122,10500,0,200.0009685,0,0,0,90.00000001 +253.98,50.30085681,-2.944280097,10500,0,199.9998535,0,0,0,90.00000001 +253.99,50.30085681,-2.944252072,10500,0,199.9991844,0,0,0,90.00000001 +254,50.30085681,-2.944224047,10500,0,199.9998535,0,0,0,90.00000001 +254.01,50.30085681,-2.944196022,10500,0,200.0009685,0,0,0,90.00000001 +254.02,50.30085681,-2.944167996,10500,0,200.0009685,0,0,0,90.00000001 +254.03,50.30085681,-2.944139971,10500,0,199.9998535,0,0,0,90.00000001 +254.04,50.30085681,-2.944111946,10500,0,199.9991844,0,0,0,90.00000001 +254.05,50.30085681,-2.944083921,10500,0,199.9998535,0,0,0,90.00000001 +254.06,50.30085681,-2.944055896,10500,0,200.0009685,0,0,0,90.00000001 +254.07,50.30085681,-2.94402787,10500,0,200.0009685,0,0,0,90.00000001 +254.08,50.30085681,-2.943999845,10500,0,199.9998535,0,0,0,90.00000001 +254.09,50.30085681,-2.94397182,10500,0,199.9989614,0,0,0,90.00000001 +254.1,50.30085681,-2.943943795,10500,0,199.9987384,0,0,0,90.00000001 +254.11,50.30085681,-2.94391577,10500,0,199.9989614,0,0,0,90.00000001 +254.12,50.30085681,-2.943887745,10500,0,199.9998535,0,0,0,90.00000001 +254.13,50.30085681,-2.94385972,10500,0,200.0009685,0,0,0,90.00000001 +254.14,50.30085681,-2.943831694,10500,0,200.0009685,0,0,0,90.00000001 +254.15,50.30085681,-2.943803669,10500,0,199.9998535,0,0,0,90.00000001 +254.16,50.30085681,-2.943775644,10500,0,199.9989614,0,0,0,90.00000001 +254.17,50.30085681,-2.943747619,10500,0,199.9989614,0,0,0,90.00000001 +254.18,50.30085681,-2.943719594,10500,0,199.9998535,0,0,0,90.00000001 +254.19,50.30085681,-2.943691569,10500,0,200.0009685,0,0,0,90.00000001 +254.2,50.30085681,-2.943663543,10500,0,200.0009685,0,0,0,90.00000001 +254.21,50.30085681,-2.943635518,10500,0,199.9998535,0,0,0,90.00000001 +254.22,50.30085681,-2.943607493,10500,0,199.9989614,0,0,0,90.00000001 +254.23,50.30085681,-2.943579468,10500,0,199.9989614,0,0,0,90.00000001 +254.24,50.30085681,-2.943551443,10500,0,199.9998535,0,0,0,90.00000001 +254.25,50.30085681,-2.943523418,10500,0,200.0009685,0,0,0,90.00000001 +254.26,50.30085681,-2.943495392,10500,0,200.0009685,0,0,0,90.00000001 +254.27,50.30085681,-2.943467367,10500,0,199.9998535,0,0,0,90.00000001 +254.28,50.30085681,-2.943439342,10500,0,199.9989614,0,0,0,90.00000001 +254.29,50.30085681,-2.943411317,10500,0,199.9989614,0,0,0,90.00000001 +254.3,50.30085681,-2.943383292,10500,0,199.9998535,0,0,0,90.00000001 +254.31,50.30085681,-2.943355267,10500,0,200.0009685,0,0,0,90.00000001 +254.32,50.30085681,-2.943327241,10500,0,200.0009685,0,0,0,90.00000001 +254.33,50.30085681,-2.943299216,10500,0,199.9998535,0,0,0,90.00000001 +254.34,50.30085681,-2.943271191,10500,0,199.9989614,0,0,0,90.00000001 +254.35,50.30085681,-2.943243166,10500,0,199.9987384,0,0,0,90.00000001 +254.36,50.30085681,-2.943215141,10500,0,199.9989614,0,0,0,90.00000001 +254.37,50.30085681,-2.943187116,10500,0,199.9998535,0,0,0,90.00000001 +254.38,50.30085681,-2.943159091,10500,0,200.0009685,0,0,0,90.00000001 +254.39,50.30085681,-2.943131065,10500,0,200.0009685,0,0,0,90.00000001 +254.4,50.30085681,-2.94310304,10500,0,199.9998535,0,0,0,90.00000001 +254.41,50.30085681,-2.943075015,10500,0,199.9991844,0,0,0,90.00000001 +254.42,50.30085681,-2.94304699,10500,0,199.9998535,0,0,0,90.00000001 +254.43,50.30085681,-2.943018965,10500,0,200.0009685,0,0,0,90.00000001 +254.44,50.30085681,-2.942990939,10500,0,200.0009685,0,0,0,90.00000001 +254.45,50.30085681,-2.942962914,10500,0,199.9998535,0,0,0,90.00000001 +254.46,50.30085681,-2.942934889,10500,0,199.9991844,0,0,0,90.00000001 +254.47,50.30085681,-2.942906864,10500,0,199.9998535,0,0,0,90.00000001 +254.48,50.30085681,-2.942878839,10500,0,200.0009685,0,0,0,90.00000001 +254.49,50.30085681,-2.942850813,10500,0,200.0009685,0,0,0,90.00000001 +254.5,50.30085681,-2.942822788,10500,0,199.9998535,0,0,0,90.00000001 +254.51,50.30085681,-2.942794763,10500,0,199.9991844,0,0,0,90.00000001 +254.52,50.30085681,-2.942766738,10500,0,199.9998535,0,0,0,90.00000001 +254.53,50.30085681,-2.942738713,10500,0,200.0009685,0,0,0,90.00000001 +254.54,50.30085681,-2.942710687,10500,0,200.0009685,0,0,0,90.00000001 +254.55,50.30085681,-2.942682662,10500,0,199.9998535,0,0,0,90.00000001 +254.56,50.30085681,-2.942654637,10500,0,199.9991844,0,0,0,90.00000001 +254.57,50.30085681,-2.942626612,10500,0,199.9998535,0,0,0,90.00000001 +254.58,50.30085681,-2.942598587,10500,0,200.0009685,0,0,0,90.00000001 +254.59,50.30085681,-2.942570561,10500,0,200.0009685,0,0,0,90.00000001 +254.6,50.30085681,-2.942542536,10500,0,199.9998535,0,0,0,90.00000001 +254.61,50.30085681,-2.942514511,10500,0,199.9991844,0,0,0,90.00000001 +254.62,50.30085681,-2.942486486,10500,0,199.9998535,0,0,0,90.00000001 +254.63,50.30085681,-2.942458461,10500,0,200.0009685,0,0,0,90.00000001 +254.64,50.30085681,-2.942430435,10500,0,200.0009685,0,0,0,90.00000001 +254.65,50.30085681,-2.94240241,10500,0,199.9998535,0,0,0,90.00000001 +254.66,50.30085681,-2.942374385,10500,0,199.9989614,0,0,0,90.00000001 +254.67,50.30085681,-2.94234636,10500,0,199.9989614,0,0,0,90.00000001 +254.68,50.30085681,-2.942318335,10500,0,199.9998535,0,0,0,90.00000001 +254.69,50.30085681,-2.94229031,10500,0,200.0009685,0,0,0,90.00000001 +254.7,50.30085681,-2.942262284,10500,0,200.0009685,0,0,0,90.00000001 +254.71,50.30085681,-2.942234259,10500,0,199.9998535,0,0,0,90.00000001 +254.72,50.30085681,-2.942206234,10500,0,199.9989614,0,0,0,90.00000001 +254.73,50.30085681,-2.942178209,10500,0,199.9989614,0,0,0,90.00000001 +254.74,50.30085681,-2.942150184,10500,0,199.9998535,0,0,0,90.00000001 +254.75,50.30085681,-2.942122159,10500,0,200.0009685,0,0,0,90.00000001 +254.76,50.30085681,-2.942094133,10500,0,200.0009685,0,0,0,90.00000001 +254.77,50.30085681,-2.942066108,10500,0,199.9998535,0,0,0,90.00000001 +254.78,50.30085681,-2.942038083,10500,0,199.9989614,0,0,0,90.00000001 +254.79,50.30085681,-2.942010058,10500,0,199.9989614,0,0,0,90.00000001 +254.8,50.30085681,-2.941982033,10500,0,199.9998535,0,0,0,90.00000001 +254.81,50.30085681,-2.941954008,10500,0,200.0009685,0,0,0,90.00000001 +254.82,50.30085681,-2.941925982,10500,0,200.0009685,0,0,0,90.00000001 +254.83,50.30085681,-2.941897957,10500,0,199.9998535,0,0,0,90.00000001 +254.84,50.30085681,-2.941869932,10500,0,199.9989614,0,0,0,90.00000001 +254.85,50.30085681,-2.941841907,10500,0,199.9989614,0,0,0,90.00000001 +254.86,50.30085681,-2.941813882,10500,0,199.9998535,0,0,0,90.00000001 +254.87,50.30085681,-2.941785857,10500,0,200.0009685,0,0,0,90.00000001 +254.88,50.30085681,-2.941757831,10500,0,200.0009685,0,0,0,90.00000001 +254.89,50.30085681,-2.941729806,10500,0,199.9998535,0,0,0,90.00000001 +254.9,50.30085681,-2.941701781,10500,0,199.9989614,0,0,0,90.00000001 +254.91,50.30085681,-2.941673756,10500,0,199.9989614,0,0,0,90.00000001 +254.92,50.30085681,-2.941645731,10500,0,199.9998535,0,0,0,90.00000001 +254.93,50.30085681,-2.941617706,10500,0,200.0009685,0,0,0,90.00000001 +254.94,50.30085681,-2.94158968,10500,0,200.0009685,0,0,0,90.00000001 +254.95,50.30085681,-2.941561655,10500,0,199.9998535,0,0,0,90.00000001 +254.96,50.30085681,-2.94153363,10500,0,199.9989614,0,0,0,90.00000001 +254.97,50.30085681,-2.941505605,10500,0,199.9987384,0,0,0,90.00000001 +254.98,50.30085681,-2.94147758,10500,0,199.9989614,0,0,0,90.00000001 +254.99,50.30085681,-2.941449555,10500,0,199.9998535,0,0,0,90.00000001 +255,50.30085681,-2.94142153,10500,0,200.0009685,0,0,0,90.00000001 +255.01,50.30085681,-2.941393504,10500,0,200.0009685,0,0,0,90.00000001 +255.02,50.30085681,-2.941365479,10500,0,199.9998535,0,0,0,90.00000001 +255.03,50.30085681,-2.941337454,10500,0,199.9991844,0,0,0,90.00000001 +255.04,50.30085681,-2.941309429,10500,0,199.9998535,0,0,0,90.00000001 +255.05,50.30085681,-2.941281404,10500,0,200.0009685,0,0,0,90.00000001 +255.06,50.30085681,-2.941253378,10500,0,200.0009685,0,0,0,90.00000001 +255.07,50.30085681,-2.941225353,10500,0,199.9998535,0,0,0,90.00000001 +255.08,50.30085681,-2.941197328,10500,0,199.9991844,0,0,0,90.00000001 +255.09,50.30085681,-2.941169303,10500,0,199.9998535,0,0,0,90.00000001 +255.1,50.30085681,-2.941141278,10500,0,200.0009685,0,0,0,90.00000001 +255.11,50.30085681,-2.941113252,10500,0,200.0009685,0,0,0,90.00000001 +255.12,50.30085681,-2.941085227,10500,0,199.9998535,0,0,0,90.00000001 +255.13,50.30085681,-2.941057202,10500,0,199.9991844,0,0,0,90.00000001 +255.14,50.30085681,-2.941029177,10500,0,199.9998535,0,0,0,90.00000001 +255.15,50.30085681,-2.941001152,10500,0,200.0009685,0,0,0,90.00000001 +255.16,50.30085681,-2.940973126,10500,0,200.0009685,0,0,0,90.00000001 +255.17,50.30085681,-2.940945101,10500,0,199.9998535,0,0,0,90.00000001 +255.18,50.30085681,-2.940917076,10500,0,199.9991844,0,0,0,90.00000001 +255.19,50.30085681,-2.940889051,10500,0,199.9998535,0,0,0,90.00000001 +255.2,50.30085681,-2.940861026,10500,0,200.0009685,0,0,0,90.00000001 +255.21,50.30085681,-2.940833,10500,0,200.0009685,0,0,0,90.00000001 +255.22,50.30085681,-2.940804975,10500,0,199.9998535,0,0,0,90.00000001 +255.23,50.30085681,-2.94077695,10500,0,199.9989614,0,0,0,90.00000001 +255.24,50.30085681,-2.940748925,10500,0,199.9989614,0,0,0,90.00000001 +255.25,50.30085681,-2.9407209,10500,0,199.9998535,0,0,0,90.00000001 +255.26,50.30085681,-2.940692875,10500,0,200.0009685,0,0,0,90.00000001 +255.27,50.30085681,-2.940664849,10500,0,200.0009685,0,0,0,90.00000001 +255.28,50.30085681,-2.940636824,10500,0,199.9998535,0,0,0,90.00000001 +255.29,50.30085681,-2.940608799,10500,0,199.9991844,0,0,0,90.00000001 +255.3,50.30085681,-2.940580774,10500,0,199.9998535,0,0,0,90.00000001 +255.31,50.30085681,-2.940552749,10500,0,200.0009685,0,0,0,90.00000001 +255.32,50.30085681,-2.940524723,10500,0,200.0009685,0,0,0,90.00000001 +255.33,50.30085681,-2.940496698,10500,0,199.9998535,0,0,0,90.00000001 +255.34,50.30085681,-2.940468673,10500,0,199.9989614,0,0,0,90.00000001 +255.35,50.30085681,-2.940440648,10500,0,199.9989614,0,0,0,90.00000001 +255.36,50.30085681,-2.940412623,10500,0,199.9998535,0,0,0,90.00000001 +255.37,50.30085681,-2.940384598,10500,0,200.0009685,0,0,0,90.00000001 +255.38,50.30085681,-2.940356572,10500,0,200.0009685,0,0,0,90.00000001 +255.39,50.30085681,-2.940328547,10500,0,199.9998535,0,0,0,90.00000001 +255.4,50.30085681,-2.940300522,10500,0,199.9989614,0,0,0,90.00000001 +255.41,50.30085681,-2.940272497,10500,0,199.9989614,0,0,0,90.00000001 +255.42,50.30085681,-2.940244472,10500,0,199.9998535,0,0,0,90.00000001 +255.43,50.30085681,-2.940216447,10500,0,200.0009685,0,0,0,90.00000001 +255.44,50.30085681,-2.940188421,10500,0,200.0009685,0,0,0,90.00000001 +255.45,50.30085681,-2.940160396,10500,0,199.9998535,0,0,0,90.00000001 +255.46,50.30085681,-2.940132371,10500,0,199.9989614,0,0,0,90.00000001 +255.47,50.30085681,-2.940104346,10500,0,199.9989614,0,0,0,90.00000001 +255.48,50.30085681,-2.940076321,10500,0,199.9998535,0,0,0,90.00000001 +255.49,50.30085681,-2.940048296,10500,0,200.0009685,0,0,0,90.00000001 +255.5,50.30085681,-2.94002027,10500,0,200.0009685,0,0,0,90.00000001 +255.51,50.30085681,-2.939992245,10500,0,199.9998535,0,0,0,90.00000001 +255.52,50.30085681,-2.93996422,10500,0,199.9989614,0,0,0,90.00000001 +255.53,50.30085681,-2.939936195,10500,0,199.9987384,0,0,0,90.00000001 +255.54,50.30085681,-2.93990817,10500,0,199.9989614,0,0,0,90.00000001 +255.55,50.30085681,-2.939880145,10500,0,199.9998535,0,0,0,90.00000001 +255.56,50.30085681,-2.93985212,10500,0,200.0009685,0,0,0,90.00000001 +255.57,50.30085681,-2.939824094,10500,0,200.0009685,0,0,0,90.00000001 +255.58,50.30085681,-2.939796069,10500,0,199.9998535,0,0,0,90.00000001 +255.59,50.30085681,-2.939768044,10500,0,199.9989614,0,0,0,90.00000001 +255.6,50.30085681,-2.939740019,10500,0,199.9989614,0,0,0,90.00000001 +255.61,50.30085681,-2.939711994,10500,0,199.9998535,0,0,0,90.00000001 +255.62,50.30085681,-2.939683969,10500,0,200.0009685,0,0,0,90.00000001 +255.63,50.30085681,-2.939655943,10500,0,200.0009685,0,0,0,90.00000001 +255.64,50.30085681,-2.939627918,10500,0,199.9998535,0,0,0,90.00000001 +255.65,50.30085681,-2.939599893,10500,0,199.9989614,0,0,0,90.00000001 +255.66,50.30085681,-2.939571868,10500,0,199.9989614,0,0,0,90.00000001 +255.67,50.30085681,-2.939543843,10500,0,199.9998535,0,0,0,90.00000001 +255.68,50.30085681,-2.939515818,10500,0,200.0009685,0,0,0,90.00000001 +255.69,50.30085681,-2.939487792,10500,0,200.0009685,0,0,0,90.00000001 +255.7,50.30085681,-2.939459767,10500,0,199.9998535,0,0,0,90.00000001 +255.71,50.30085681,-2.939431742,10500,0,199.9991844,0,0,0,90.00000001 +255.72,50.30085681,-2.939403717,10500,0,199.9998535,0,0,0,90.00000001 +255.73,50.30085681,-2.939375692,10500,0,200.0009685,0,0,0,90.00000001 +255.74,50.30085681,-2.939347666,10500,0,200.0009685,0,0,0,90.00000001 +255.75,50.30085681,-2.939319641,10500,0,199.9998535,0,0,0,90.00000001 +255.76,50.30085681,-2.939291616,10500,0,199.9991844,0,0,0,90.00000001 +255.77,50.30085681,-2.939263591,10500,0,199.9998535,0,0,0,90.00000001 +255.78,50.30085681,-2.939235566,10500,0,200.0009685,0,0,0,90.00000001 +255.79,50.30085681,-2.93920754,10500,0,200.0009685,0,0,0,90.00000001 +255.8,50.30085681,-2.939179515,10500,0,199.9998535,0,0,0,90.00000001 +255.81,50.30085681,-2.93915149,10500,0,199.9991844,0,0,0,90.00000001 +255.82,50.30085681,-2.939123465,10500,0,199.9998535,0,0,0,90.00000001 +255.83,50.30085681,-2.93909544,10500,0,200.0009685,0,0,0,90.00000001 +255.84,50.30085681,-2.939067414,10500,0,200.0009685,0,0,0,90.00000001 +255.85,50.30085681,-2.939039389,10500,0,199.9998535,0,0,0,90.00000001 +255.86,50.30085681,-2.939011364,10500,0,199.9991844,0,0,0,90.00000001 +255.87,50.30085681,-2.938983339,10500,0,199.9998535,0,0,0,90.00000001 +255.88,50.30085681,-2.938955314,10500,0,200.0009685,0,0,0,90.00000001 +255.89,50.30085681,-2.938927288,10500,0,200.0009685,0,0,0,90.00000001 +255.9,50.30085681,-2.938899263,10500,0,199.9998535,0,0,0,90.00000001 +255.91,50.30085681,-2.938871238,10500,0,199.9991844,0,0,0,90.00000001 +255.92,50.30085681,-2.938843213,10500,0,199.9998535,0,0,0,90.00000001 +255.93,50.30085681,-2.938815188,10500,0,200.0009685,0,0,0,90.00000001 +255.94,50.30085681,-2.938787162,10500,0,200.0009685,0,0,0,90.00000001 +255.95,50.30085681,-2.938759137,10500,0,199.9998535,0,0,0,90.00000001 +255.96,50.30085681,-2.938731112,10500,0,199.9989614,0,0,0,90.00000001 +255.97,50.30085681,-2.938703087,10500,0,199.9989614,0,0,0,90.00000001 +255.98,50.30085681,-2.938675062,10500,0,199.9998535,0,0,0,90.00000001 +255.99,50.30085681,-2.938647037,10500,0,200.0009685,0,0,0,90.00000001 +256,50.30085681,-2.938619011,10500,0,200.0009685,0,0,0,90.00000001 +256.01,50.30085681,-2.938590986,10500,0,199.9998535,0,0,0,90.00000001 +256.02,50.30085681,-2.938562961,10500,0,199.9989614,0,0,0,90.00000001 +256.03,50.30085681,-2.938534936,10500,0,199.9989614,0,0,0,90.00000001 +256.04,50.30085681,-2.938506911,10500,0,199.9998535,0,0,0,90.00000001 +256.05,50.30085681,-2.938478886,10500,0,200.0009685,0,0,0,90.00000001 +256.06,50.30085681,-2.93845086,10500,0,200.0009685,0,0,0,90.00000001 +256.07,50.30085681,-2.938422835,10500,0,199.9998535,0,0,0,90.00000001 +256.08,50.30085681,-2.93839481,10500,0,199.9989614,0,0,0,90.00000001 +256.09,50.30085681,-2.938366785,10500,0,199.9987384,0,0,0,90.00000001 +256.1,50.30085681,-2.93833876,10500,0,199.9989614,0,0,0,90.00000001 +256.11,50.30085681,-2.938310735,10500,0,199.9998535,0,0,0,90.00000001 +256.12,50.30085681,-2.93828271,10500,0,200.0009685,0,0,0,90.00000001 +256.13,50.30085681,-2.938254684,10500,0,200.0009685,0,0,0,90.00000001 +256.14,50.30085681,-2.938226659,10500,0,199.9998535,0,0,0,90.00000001 +256.15,50.30085681,-2.938198634,10500,0,199.9989614,0,0,0,90.00000001 +256.16,50.30085681,-2.938170609,10500,0,199.9989614,0,0,0,90.00000001 +256.17,50.30085681,-2.938142584,10500,0,199.9998535,0,0,0,90.00000001 +256.18,50.30085681,-2.938114559,10500,0,200.0009685,0,0,0,90.00000001 +256.19,50.30085681,-2.938086533,10500,0,200.0009685,0,0,0,90.00000001 +256.2,50.30085681,-2.938058508,10500,0,199.9998535,0,0,0,90.00000001 +256.21,50.30085681,-2.938030483,10500,0,199.9989614,0,0,0,90.00000001 +256.22,50.30085681,-2.938002458,10500,0,199.9989614,0,0,0,90.00000001 +256.23,50.30085681,-2.937974433,10500,0,199.9998535,0,0,0,90.00000001 +256.24,50.30085681,-2.937946408,10500,0,200.0009685,0,0,0,90.00000001 +256.25,50.30085681,-2.937918382,10500,0,200.0009685,0,0,0,90.00000001 +256.26,50.30085681,-2.937890357,10500,0,199.9998535,0,0,0,90.00000001 +256.27,50.30085681,-2.937862332,10500,0,199.9989614,0,0,0,90.00000001 +256.28,50.30085681,-2.937834307,10500,0,199.9989614,0,0,0,90.00000001 +256.29,50.30085681,-2.937806282,10500,0,199.9998535,0,0,0,90.00000001 +256.3,50.30085681,-2.937778257,10500,0,200.0009685,0,0,0,90.00000001 +256.31,50.30085681,-2.937750231,10500,0,200.0009685,0,0,0,90.00000001 +256.32,50.30085681,-2.937722206,10500,0,199.9998535,0,0,0,90.00000001 +256.33,50.30085681,-2.937694181,10500,0,199.9991844,0,0,0,90.00000001 +256.34,50.30085681,-2.937666156,10500,0,199.9998535,0,0,0,90.00000001 +256.35,50.30085681,-2.937638131,10500,0,200.0009685,0,0,0,90.00000001 +256.36,50.30085681,-2.937610105,10500,0,200.0009685,0,0,0,90.00000001 +256.37,50.30085681,-2.93758208,10500,0,199.9998535,0,0,0,90.00000001 +256.38,50.30085681,-2.937554055,10500,0,199.9991844,0,0,0,90.00000001 +256.39,50.30085681,-2.93752603,10500,0,199.9998535,0,0,0,90.00000001 +256.4,50.30085681,-2.937498005,10500,0,200.0009685,0,0,0,90.00000001 +256.41,50.30085681,-2.937469979,10500,0,200.0009685,0,0,0,90.00000001 +256.42,50.30085681,-2.937441954,10500,0,199.9998535,0,0,0,90.00000001 +256.43,50.30085681,-2.937413929,10500,0,199.9991844,0,0,0,90.00000001 +256.44,50.30085681,-2.937385904,10500,0,199.9998535,0,0,0,90.00000001 +256.45,50.30085681,-2.937357879,10500,0,200.0009685,0,0,0,90.00000001 +256.46,50.30085681,-2.937329853,10500,0,200.0009685,0,0,0,90.00000001 +256.47,50.30085681,-2.937301828,10500,0,199.9998535,0,0,0,90.00000001 +256.48,50.30085681,-2.937273803,10500,0,199.9991844,0,0,0,90.00000001 +256.49,50.30085681,-2.937245778,10500,0,199.9998535,0,0,0,90.00000001 +256.5,50.30085681,-2.937217753,10500,0,200.0009685,0,0,0,90.00000001 +256.51,50.30085681,-2.937189727,10500,0,200.0009685,0,0,0,90.00000001 +256.52,50.30085681,-2.937161702,10500,0,199.9998535,0,0,0,90.00000001 +256.53,50.30085681,-2.937133677,10500,0,199.9991844,0,0,0,90.00000001 +256.54,50.30085681,-2.937105652,10500,0,199.9998535,0,0,0,90.00000001 +256.55,50.30085681,-2.937077627,10500,0,200.0009685,0,0,0,90.00000001 +256.56,50.30085681,-2.937049601,10500,0,200.0009685,0,0,0,90.00000001 +256.57,50.30085681,-2.937021576,10500,0,199.9998535,0,0,0,90.00000001 +256.58,50.30085681,-2.936993551,10500,0,199.9989614,0,0,0,90.00000001 +256.59,50.30085681,-2.936965526,10500,0,199.9989614,0,0,0,90.00000001 +256.6,50.30085681,-2.936937501,10500,0,199.9998535,0,0,0,90.00000001 +256.61,50.30085681,-2.936909476,10500,0,200.0009685,0,0,0,90.00000001 +256.62,50.30085681,-2.93688145,10500,0,200.0009685,0,0,0,90.00000001 +256.63,50.30085681,-2.936853425,10500,0,199.9998535,0,0,0,90.00000001 +256.64,50.30085681,-2.9368254,10500,0,199.9989614,0,0,0,90.00000001 +256.65,50.30085681,-2.936797375,10500,0,199.9987384,0,0,0,90.00000001 +256.66,50.30085681,-2.93676935,10500,0,199.9989614,0,0,0,90.00000001 +256.67,50.30085681,-2.936741325,10500,0,199.9998535,0,0,0,90.00000001 +256.68,50.30085681,-2.9367133,10500,0,200.0009685,0,0,0,90.00000001 +256.69,50.30085681,-2.936685274,10500,0,200.0009685,0,0,0,90.00000001 +256.7,50.30085681,-2.936657249,10500,0,199.9998535,0,0,0,90.00000001 +256.71,50.30085681,-2.936629224,10500,0,199.9989614,0,0,0,90.00000001 +256.72,50.30085681,-2.936601199,10500,0,199.9989614,0,0,0,90.00000001 +256.73,50.30085681,-2.936573174,10500,0,199.9998535,0,0,0,90.00000001 +256.74,50.30085681,-2.936545149,10500,0,200.0009685,0,0,0,90.00000001 +256.75,50.30085681,-2.936517123,10500,0,200.0009685,0,0,0,90.00000001 +256.76,50.30085681,-2.936489098,10500,0,199.9998535,0,0,0,90.00000001 +256.77,50.30085681,-2.936461073,10500,0,199.9989614,0,0,0,90.00000001 +256.78,50.30085681,-2.936433048,10500,0,199.9989614,0,0,0,90.00000001 +256.79,50.30085681,-2.936405023,10500,0,199.9998535,0,0,0,90.00000001 +256.8,50.30085681,-2.936376998,10500,0,200.0009685,0,0,0,90.00000001 +256.81,50.30085681,-2.936348972,10500,0,200.0009685,0,0,0,90.00000001 +256.82,50.30085681,-2.936320947,10500,0,199.9998535,0,0,0,90.00000001 +256.83,50.30085681,-2.936292922,10500,0,199.9989614,0,0,0,90.00000001 +256.84,50.30085681,-2.936264897,10500,0,199.9989614,0,0,0,90.00000001 +256.85,50.30085681,-2.936236872,10500,0,199.9998535,0,0,0,90.00000001 +256.86,50.30085681,-2.936208847,10500,0,200.0009685,0,0,0,90.00000001 +256.87,50.30085681,-2.936180821,10500,0,200.0009685,0,0,0,90.00000001 +256.88,50.30085681,-2.936152796,10500,0,199.9998535,0,0,0,90.00000001 +256.89,50.30085681,-2.936124771,10500,0,199.9989614,0,0,0,90.00000001 +256.9,50.30085681,-2.936096746,10500,0,199.9989614,0,0,0,90.00000001 +256.91,50.30085681,-2.936068721,10500,0,199.9998535,0,0,0,90.00000001 +256.92,50.30085681,-2.936040696,10500,0,200.0009685,0,0,0,90.00000001 +256.93,50.30085681,-2.93601267,10500,0,200.0009685,0,0,0,90.00000001 +256.94,50.30085681,-2.935984645,10500,0,199.9998535,0,0,0,90.00000001 +256.95,50.30085681,-2.93595662,10500,0,199.9991844,0,0,0,90.00000001 +256.96,50.30085681,-2.935928595,10500,0,199.9998535,0,0,0,90.00000001 +256.97,50.30085681,-2.93590057,10500,0,200.0009685,0,0,0,90.00000001 +256.98,50.30085681,-2.935872544,10500,0,200.0009685,0,0,0,90.00000001 +256.99,50.30085681,-2.935844519,10500,0,199.9998535,0,0,0,90.00000001 +257,50.30085681,-2.935816494,10500,0,199.9991844,0,0,0,90.00000001 +257.01,50.30085681,-2.935788469,10500,0,199.9998535,0,0,0,90.00000001 +257.02,50.30085681,-2.935760444,10500,0,200.0009685,0,0,0,90.00000001 +257.03,50.30085681,-2.935732418,10500,0,200.0009685,0,0,0,90.00000001 +257.04,50.30085681,-2.935704393,10500,0,199.9998535,0,0,0,90.00000001 +257.05,50.30085681,-2.935676368,10500,0,199.9991844,0,0,0,90.00000001 +257.06,50.30085681,-2.935648343,10500,0,199.9998535,0,0,0,90.00000001 +257.07,50.30085681,-2.935620318,10500,0,200.0009685,0,0,0,90.00000001 +257.08,50.30085681,-2.935592292,10500,0,200.0009685,0,0,0,90.00000001 +257.09,50.30085681,-2.935564267,10500,0,199.9998535,0,0,0,90.00000001 +257.1,50.30085681,-2.935536242,10500,0,199.9991844,0,0,0,90.00000001 +257.11,50.30085681,-2.935508217,10500,0,199.9998535,0,0,0,90.00000001 +257.12,50.30085681,-2.935480192,10500,0,200.0009685,0,0,0,90.00000001 +257.13,50.30085681,-2.935452166,10500,0,200.0009685,0,0,0,90.00000001 +257.14,50.30085681,-2.935424141,10500,0,199.9998535,0,0,0,90.00000001 +257.15,50.30085681,-2.935396116,10500,0,199.9991844,0,0,0,90.00000001 +257.16,50.30085681,-2.935368091,10500,0,199.9998535,0,0,0,90.00000001 +257.17,50.30085681,-2.935340066,10500,0,200.0009685,0,0,0,90.00000001 +257.18,50.30085681,-2.93531204,10500,0,200.0009685,0,0,0,90.00000001 +257.19,50.30085681,-2.935284015,10500,0,199.9998535,0,0,0,90.00000001 +257.2,50.30085681,-2.93525599,10500,0,199.9989614,0,0,0,90.00000001 +257.21,50.30085681,-2.935227965,10500,0,199.9987384,0,0,0,90.00000001 +257.22,50.30085681,-2.93519994,10500,0,199.9989614,0,0,0,90.00000001 +257.23,50.30085681,-2.935171915,10500,0,199.9998535,0,0,0,90.00000001 +257.24,50.30085681,-2.93514389,10500,0,200.0009685,0,0,0,90.00000001 +257.25,50.30085681,-2.935115864,10500,0,200.0009685,0,0,0,90.00000001 +257.26,50.30085681,-2.935087839,10500,0,199.9998535,0,0,0,90.00000001 +257.27,50.30085681,-2.935059814,10500,0,199.9989614,0,0,0,90.00000001 +257.28,50.30085681,-2.935031789,10500,0,199.9989614,0,0,0,90.00000001 +257.29,50.30085681,-2.935003764,10500,0,199.9998535,0,0,0,90.00000001 +257.3,50.30085681,-2.934975739,10500,0,200.0009685,0,0,0,90.00000001 +257.31,50.30085681,-2.934947713,10500,0,200.0009685,0,0,0,90.00000001 +257.32,50.30085681,-2.934919688,10500,0,199.9998535,0,0,0,90.00000001 +257.33,50.30085681,-2.934891663,10500,0,199.9989614,0,0,0,90.00000001 +257.34,50.30085681,-2.934863638,10500,0,199.9989614,0,0,0,90.00000001 +257.35,50.30085681,-2.934835613,10500,0,199.9998535,0,0,0,90.00000001 +257.36,50.30085681,-2.934807588,10500,0,200.0009685,0,0,0,90.00000001 +257.37,50.30085681,-2.934779562,10500,0,200.0009685,0,0,0,90.00000001 +257.38,50.30085681,-2.934751537,10500,0,199.9998535,0,0,0,90.00000001 +257.39,50.30085681,-2.934723512,10500,0,199.9989614,0,0,0,90.00000001 +257.4,50.30085681,-2.934695487,10500,0,199.9989614,0,0,0,90.00000001 +257.41,50.30085681,-2.934667462,10500,0,199.9998535,0,0,0,90.00000001 +257.42,50.30085681,-2.934639437,10500,0,200.0009685,0,0,0,90.00000001 +257.43,50.30085681,-2.934611411,10500,0,200.0009685,0,0,0,90.00000001 +257.44,50.30085681,-2.934583386,10500,0,199.9998535,0,0,0,90.00000001 +257.45,50.30085681,-2.934555361,10500,0,199.9989614,0,0,0,90.00000001 +257.46,50.30085681,-2.934527336,10500,0,199.9989614,0,0,0,90.00000001 +257.47,50.30085681,-2.934499311,10500,0,199.9998535,0,0,0,90.00000001 +257.48,50.30085681,-2.934471286,10500,0,200.0009685,0,0,0,90.00000001 +257.49,50.30085681,-2.93444326,10500,0,200.0009685,0,0,0,90.00000001 +257.5,50.30085681,-2.934415235,10500,0,199.9998535,0,0,0,90.00000001 +257.51,50.30085681,-2.93438721,10500,0,199.9989614,0,0,0,90.00000001 +257.52,50.30085681,-2.934359185,10500,0,199.9989614,0,0,0,90.00000001 +257.53,50.30085681,-2.93433116,10500,0,199.9998535,0,0,0,90.00000001 +257.54,50.30085681,-2.934303135,10500,0,200.0009685,0,0,0,90.00000001 +257.55,50.30085681,-2.934275109,10500,0,200.0009685,0,0,0,90.00000001 +257.56,50.30085681,-2.934247084,10500,0,199.9998535,0,0,0,90.00000001 +257.57,50.30085681,-2.934219059,10500,0,199.9991844,0,0,0,90.00000001 +257.58,50.30085681,-2.934191034,10500,0,199.9998535,0,0,0,90.00000001 +257.59,50.30085681,-2.934163009,10500,0,200.0009685,0,0,0,90.00000001 +257.6,50.30085681,-2.934134983,10500,0,200.0009685,0,0,0,90.00000001 +257.61,50.30085681,-2.934106958,10500,0,199.9998535,0,0,0,90.00000001 +257.62,50.30085681,-2.934078933,10500,0,199.9989614,0,0,0,90.00000001 +257.63,50.30085681,-2.934050908,10500,0,199.9989614,0,0,0,90.00000001 +257.64,50.30085681,-2.934022883,10500,0,199.9998535,0,0,0,90.00000001 +257.65,50.30085681,-2.933994858,10500,0,200.0009685,0,0,0,90.00000001 +257.66,50.30085681,-2.933966832,10500,0,200.0009685,0,0,0,90.00000001 +257.67,50.30085681,-2.933938807,10500,0,199.9998535,0,0,0,90.00000001 +257.68,50.30085681,-2.933910782,10500,0,199.9991844,0,0,0,90.00000001 +257.69,50.30085681,-2.933882757,10500,0,199.9998535,0,0,0,90.00000001 +257.7,50.30085681,-2.933854732,10500,0,200.0009685,0,0,0,90.00000001 +257.71,50.30085681,-2.933826706,10500,0,200.0009685,0,0,0,90.00000001 +257.72,50.30085681,-2.933798681,10500,0,199.9998535,0,0,0,90.00000001 +257.73,50.30085681,-2.933770656,10500,0,199.9991844,0,0,0,90.00000001 +257.74,50.30085681,-2.933742631,10500,0,199.9998535,0,0,0,90.00000001 +257.75,50.30085681,-2.933714606,10500,0,200.0009685,0,0,0,90.00000001 +257.76,50.30085681,-2.93368658,10500,0,200.0009685,0,0,0,90.00000001 +257.77,50.30085681,-2.933658555,10500,0,199.9998535,0,0,0,90.00000001 +257.78,50.30085681,-2.93363053,10500,0,199.9991844,0,0,0,90.00000001 +257.79,50.30085681,-2.933602505,10500,0,199.9998535,0,0,0,90.00000001 +257.8,50.30085681,-2.93357448,10500,0,200.0009685,0,0,0,90.00000001 +257.81,50.30085681,-2.933546454,10500,0,200.0009685,0,0,0,90.00000001 +257.82,50.30085681,-2.933518429,10500,0,199.9998535,0,0,0,90.00000001 +257.83,50.30085681,-2.933490404,10500,0,199.9989614,0,0,0,90.00000001 +257.84,50.30085681,-2.933462379,10500,0,199.9989614,0,0,0,90.00000001 +257.85,50.30085681,-2.933434354,10500,0,199.9998535,0,0,0,90.00000001 +257.86,50.30085681,-2.933406329,10500,0,200.0009685,0,0,0,90.00000001 +257.87,50.30085681,-2.933378303,10500,0,200.0009685,0,0,0,90.00000001 +257.88,50.30085681,-2.933350278,10500,0,199.9998535,0,0,0,90.00000001 +257.89,50.30085681,-2.933322253,10500,0,199.9989614,0,0,0,90.00000001 +257.9,50.30085681,-2.933294228,10500,0,199.9989614,0,0,0,90.00000001 +257.91,50.30085681,-2.933266203,10500,0,199.9998535,0,0,0,90.00000001 +257.92,50.30085681,-2.933238178,10500,0,200.0009685,0,0,0,90.00000001 +257.93,50.30085681,-2.933210152,10500,0,200.0009685,0,0,0,90.00000001 +257.94,50.30085681,-2.933182127,10500,0,199.9998535,0,0,0,90.00000001 +257.95,50.30085681,-2.933154102,10500,0,199.9989614,0,0,0,90.00000001 +257.96,50.30085681,-2.933126077,10500,0,199.9989614,0,0,0,90.00000001 +257.97,50.30085681,-2.933098052,10500,0,199.9998535,0,0,0,90.00000001 +257.98,50.30085681,-2.933070027,10500,0,200.0009685,0,0,0,90.00000001 +257.99,50.30085681,-2.933042001,10500,0,200.0009685,0,0,0,90.00000001 +258,50.30085681,-2.933013976,10500,0,199.9998535,0,0,0,90.00000001 +258.01,50.30085681,-2.932985951,10500,0,199.9989614,0,0,0,90.00000001 +258.02,50.30085681,-2.932957926,10500,0,199.9989614,0,0,0,90.00000001 +258.03,50.30085681,-2.932929901,10500,0,199.9998535,0,0,0,90.00000001 +258.04,50.30085681,-2.932901876,10500,0,200.0009685,0,0,0,90.00000001 +258.05,50.30085681,-2.93287385,10500,0,200.0009685,0,0,0,90.00000001 +258.06,50.30085681,-2.932845825,10500,0,199.9998535,0,0,0,90.00000001 +258.07,50.30085681,-2.9328178,10500,0,199.9989614,0,0,0,90.00000001 +258.08,50.30085681,-2.932789775,10500,0,199.9987384,0,0,0,90.00000001 +258.09,50.30085681,-2.93276175,10500,0,199.9989614,0,0,0,90.00000001 +258.1,50.30085681,-2.932733725,10500,0,199.9998535,0,0,0,90.00000001 +258.11,50.30085681,-2.9327057,10500,0,200.0009685,0,0,0,90.00000001 +258.12,50.30085681,-2.932677674,10500,0,200.0009685,0,0,0,90.00000001 +258.13,50.30085681,-2.932649649,10500,0,199.9998535,0,0,0,90.00000001 +258.14,50.30085681,-2.932621624,10500,0,199.9989614,0,0,0,90.00000001 +258.15,50.30085681,-2.932593599,10500,0,199.9989614,0,0,0,90.00000001 +258.16,50.30085681,-2.932565574,10500,0,199.9998535,0,0,0,90.00000001 +258.17,50.30085681,-2.932537549,10500,0,200.0009685,0,0,0,90.00000001 +258.18,50.30085681,-2.932509523,10500,0,200.0009685,0,0,0,90.00000001 +258.19,50.30085681,-2.932481498,10500,0,199.9998535,0,0,0,90.00000001 +258.2,50.30085681,-2.932453473,10500,0,199.9991844,0,0,0,90.00000001 +258.21,50.30085681,-2.932425448,10500,0,199.9998535,0,0,0,90.00000001 +258.22,50.30085681,-2.932397423,10500,0,200.0009685,0,0,0,90.00000001 +258.23,50.30085681,-2.932369397,10500,0,200.0009685,0,0,0,90.00000001 +258.24,50.30085681,-2.932341372,10500,0,199.9998535,0,0,0,90.00000001 +258.25,50.30085681,-2.932313347,10500,0,199.9991844,0,0,0,90.00000001 +258.26,50.30085681,-2.932285322,10500,0,199.9998535,0,0,0,90.00000001 +258.27,50.30085681,-2.932257297,10500,0,200.0009685,0,0,0,90.00000001 +258.28,50.30085681,-2.932229271,10500,0,200.0009685,0,0,0,90.00000001 +258.29,50.30085681,-2.932201246,10500,0,199.9998535,0,0,0,90.00000001 +258.3,50.30085681,-2.932173221,10500,0,199.9991844,0,0,0,90.00000001 +258.31,50.30085681,-2.932145196,10500,0,199.9998535,0,0,0,90.00000001 +258.32,50.30085681,-2.932117171,10500,0,200.0009685,0,0,0,90.00000001 +258.33,50.30085681,-2.932089145,10500,0,200.0009685,0,0,0,90.00000001 +258.34,50.30085681,-2.93206112,10500,0,199.9998535,0,0,0,90.00000001 +258.35,50.30085681,-2.932033095,10500,0,199.9991844,0,0,0,90.00000001 +258.36,50.30085681,-2.93200507,10500,0,199.9998535,0,0,0,90.00000001 +258.37,50.30085681,-2.931977045,10500,0,200.0009685,0,0,0,90.00000001 +258.38,50.30085681,-2.931949019,10500,0,200.0009685,0,0,0,90.00000001 +258.39,50.30085681,-2.931920994,10500,0,199.9998535,0,0,0,90.00000001 +258.4,50.30085681,-2.931892969,10500,0,199.9991844,0,0,0,90.00000001 +258.41,50.30085681,-2.931864944,10500,0,199.9998535,0,0,0,90.00000001 +258.42,50.30085681,-2.931836919,10500,0,200.0009685,0,0,0,90.00000001 +258.43,50.30085681,-2.931808893,10500,0,200.0009685,0,0,0,90.00000001 +258.44,50.30085681,-2.931780868,10500,0,199.9998535,0,0,0,90.00000001 +258.45,50.30085681,-2.931752843,10500,0,199.9989614,0,0,0,90.00000001 +258.46,50.30085681,-2.931724818,10500,0,199.9989614,0,0,0,90.00000001 +258.47,50.30085681,-2.931696793,10500,0,199.9998535,0,0,0,90.00000001 +258.48,50.30085681,-2.931668768,10500,0,200.0009685,0,0,0,90.00000001 +258.49,50.30085681,-2.931640742,10500,0,200.0009685,0,0,0,90.00000001 +258.5,50.30085681,-2.931612717,10500,0,199.9998535,0,0,0,90.00000001 +258.51,50.30085681,-2.931584692,10500,0,199.9989614,0,0,0,90.00000001 +258.52,50.30085681,-2.931556667,10500,0,199.9989614,0,0,0,90.00000001 +258.53,50.30085681,-2.931528642,10500,0,199.9998535,0,0,0,90.00000001 +258.54,50.30085681,-2.931500617,10500,0,200.0009685,0,0,0,90.00000001 +258.55,50.30085681,-2.931472591,10500,0,200.0009685,0,0,0,90.00000001 +258.56,50.30085681,-2.931444566,10500,0,199.9998535,0,0,0,90.00000001 +258.57,50.30085681,-2.931416541,10500,0,199.9989614,0,0,0,90.00000001 +258.58,50.30085681,-2.931388516,10500,0,199.9989614,0,0,0,90.00000001 +258.59,50.30085681,-2.931360491,10500,0,199.9998535,0,0,0,90.00000001 +258.6,50.30085681,-2.931332466,10500,0,200.0009685,0,0,0,90.00000001 +258.61,50.30085681,-2.93130444,10500,0,200.0009685,0,0,0,90.00000001 +258.62,50.30085681,-2.931276415,10500,0,199.9998535,0,0,0,90.00000001 +258.63,50.30085681,-2.93124839,10500,0,199.9989614,0,0,0,90.00000001 +258.64,50.30085681,-2.931220365,10500,0,199.9987384,0,0,0,90.00000001 +258.65,50.30085681,-2.93119234,10500,0,199.9989614,0,0,0,90.00000001 +258.66,50.30085681,-2.931164315,10500,0,199.9998535,0,0,0,90.00000001 +258.67,50.30085681,-2.93113629,10500,0,200.0009685,0,0,0,90.00000001 +258.68,50.30085681,-2.931108264,10500,0,200.0009685,0,0,0,90.00000001 +258.69,50.30085681,-2.931080239,10500,0,199.9998535,0,0,0,90.00000001 +258.7,50.30085681,-2.931052214,10500,0,199.9989614,0,0,0,90.00000001 +258.71,50.30085681,-2.931024189,10500,0,199.9989614,0,0,0,90.00000001 +258.72,50.30085681,-2.930996164,10500,0,199.9998535,0,0,0,90.00000001 +258.73,50.30085681,-2.930968139,10500,0,200.0009685,0,0,0,90.00000001 +258.74,50.30085681,-2.930940113,10500,0,200.0009685,0,0,0,90.00000001 +258.75,50.30085681,-2.930912088,10500,0,199.9998535,0,0,0,90.00000001 +258.76,50.30085681,-2.930884063,10500,0,199.9989614,0,0,0,90.00000001 +258.77,50.30085681,-2.930856038,10500,0,199.9989614,0,0,0,90.00000001 +258.78,50.30085681,-2.930828013,10500,0,199.9998535,0,0,0,90.00000001 +258.79,50.30085681,-2.930799988,10500,0,200.0009685,0,0,0,90.00000001 +258.8,50.30085681,-2.930771962,10500,0,200.0009685,0,0,0,90.00000001 +258.81,50.30085681,-2.930743937,10500,0,199.9998535,0,0,0,90.00000001 +258.82,50.30085681,-2.930715912,10500,0,199.9991844,0,0,0,90.00000001 +258.83,50.30085681,-2.930687887,10500,0,199.9998535,0,0,0,90.00000001 +258.84,50.30085681,-2.930659862,10500,0,200.0009685,0,0,0,90.00000001 +258.85,50.30085681,-2.930631836,10500,0,200.0009685,0,0,0,90.00000001 +258.86,50.30085681,-2.930603811,10500,0,199.9998535,0,0,0,90.00000001 +258.87,50.30085681,-2.930575786,10500,0,199.9991844,0,0,0,90.00000001 +258.88,50.30085681,-2.930547761,10500,0,199.9998535,0,0,0,90.00000001 +258.89,50.30085681,-2.930519736,10500,0,200.0009685,0,0,0,90.00000001 +258.9,50.30085681,-2.93049171,10500,0,200.0009685,0,0,0,90.00000001 +258.91,50.30085681,-2.930463685,10500,0,199.9998535,0,0,0,90.00000001 +258.92,50.30085681,-2.93043566,10500,0,199.9991844,0,0,0,90.00000001 +258.93,50.30085681,-2.930407635,10500,0,199.9998535,0,0,0,90.00000001 +258.94,50.30085681,-2.93037961,10500,0,200.0009685,0,0,0,90.00000001 +258.95,50.30085681,-2.930351584,10500,0,200.0009685,0,0,0,90.00000001 +258.96,50.30085681,-2.930323559,10500,0,199.9998535,0,0,0,90.00000001 +258.97,50.30085681,-2.930295534,10500,0,199.9991844,0,0,0,90.00000001 +258.98,50.30085681,-2.930267509,10500,0,199.9998535,0,0,0,90.00000001 +258.99,50.30085681,-2.930239484,10500,0,200.0009685,0,0,0,90.00000001 +259,50.30085681,-2.930211458,10500,0,200.0009685,0,0,0,90.00000001 +259.01,50.30085681,-2.930183433,10500,0,199.9998535,0,0,0,90.00000001 +259.02,50.30085681,-2.930155408,10500,0,199.9991844,0,0,0,90.00000001 +259.03,50.30085681,-2.930127383,10500,0,199.9998535,0,0,0,90.00000001 +259.04,50.30085681,-2.930099358,10500,0,200.0009685,0,0,0,90.00000001 +259.05,50.30085681,-2.930071332,10500,0,200.0009685,0,0,0,90.00000001 +259.06,50.30085681,-2.930043307,10500,0,199.9998535,0,0,0,90.00000001 +259.07,50.30085681,-2.930015282,10500,0,199.9989614,0,0,0,90.00000001 +259.08,50.30085681,-2.929987257,10500,0,199.9989614,0,0,0,90.00000001 +259.09,50.30085681,-2.929959232,10500,0,199.9998535,0,0,0,90.00000001 +259.1,50.30085681,-2.929931207,10500,0,200.0009685,0,0,0,90.00000001 +259.11,50.30085681,-2.929903181,10500,0,200.0009685,0,0,0,90.00000001 +259.12,50.30085681,-2.929875156,10500,0,199.9998535,0,0,0,90.00000001 +259.13,50.30085681,-2.929847131,10500,0,199.9989614,0,0,0,90.00000001 +259.14,50.30085681,-2.929819106,10500,0,199.9989614,0,0,0,90.00000001 +259.15,50.30085681,-2.929791081,10500,0,199.9998535,0,0,0,90.00000001 +259.16,50.30085681,-2.929763056,10500,0,200.0009685,0,0,0,90.00000001 +259.17,50.30085681,-2.92973503,10500,0,200.0009685,0,0,0,90.00000001 +259.18,50.30085681,-2.929707005,10500,0,199.9998535,0,0,0,90.00000001 +259.19,50.30085681,-2.92967898,10500,0,199.9989614,0,0,0,90.00000001 +259.2,50.30085681,-2.929650955,10500,0,199.9989614,0,0,0,90.00000001 +259.21,50.30085681,-2.92962293,10500,0,199.9998535,0,0,0,90.00000001 +259.22,50.30085681,-2.929594905,10500,0,200.0009685,0,0,0,90.00000001 +259.23,50.30085681,-2.929566879,10500,0,200.0009685,0,0,0,90.00000001 +259.24,50.30085681,-2.929538854,10500,0,199.9998535,0,0,0,90.00000001 +259.25,50.30085681,-2.929510829,10500,0,199.9989614,0,0,0,90.00000001 +259.26,50.30085681,-2.929482804,10500,0,199.9987384,0,0,0,90.00000001 +259.27,50.30085681,-2.929454779,10500,0,199.9989614,0,0,0,90.00000001 +259.28,50.30085681,-2.929426754,10500,0,199.9998535,0,0,0,90.00000001 +259.29,50.30085681,-2.929398729,10500,0,200.0009685,0,0,0,90.00000001 +259.3,50.30085681,-2.929370703,10500,0,200.0009685,0,0,0,90.00000001 +259.31,50.30085681,-2.929342678,10500,0,199.9998535,0,0,0,90.00000001 +259.32,50.30085681,-2.929314653,10500,0,199.9989614,0,0,0,90.00000001 +259.33,50.30085681,-2.929286628,10500,0,199.9989614,0,0,0,90.00000001 +259.34,50.30085681,-2.929258603,10500,0,199.9998535,0,0,0,90.00000001 +259.35,50.30085681,-2.929230578,10500,0,200.0009685,0,0,0,90.00000001 +259.36,50.30085681,-2.929202552,10500,0,200.0009685,0,0,0,90.00000001 +259.37,50.30085681,-2.929174527,10500,0,199.9998535,0,0,0,90.00000001 +259.38,50.30085681,-2.929146502,10500,0,199.9989614,0,0,0,90.00000001 +259.39,50.30085681,-2.929118477,10500,0,199.9989614,0,0,0,90.00000001 +259.4,50.30085681,-2.929090452,10500,0,199.9998535,0,0,0,90.00000001 +259.41,50.30085681,-2.929062427,10500,0,200.0009685,0,0,0,90.00000001 +259.42,50.30085681,-2.929034401,10500,0,200.0009685,0,0,0,90.00000001 +259.43,50.30085681,-2.929006376,10500,0,199.9998535,0,0,0,90.00000001 +259.44,50.30085681,-2.928978351,10500,0,199.9991844,0,0,0,90.00000001 +259.45,50.30085681,-2.928950326,10500,0,199.9998535,0,0,0,90.00000001 +259.46,50.30085681,-2.928922301,10500,0,200.0009685,0,0,0,90.00000001 +259.47,50.30085681,-2.928894275,10500,0,200.0009685,0,0,0,90.00000001 +259.48,50.30085681,-2.92886625,10500,0,199.9998535,0,0,0,90.00000001 +259.49,50.30085681,-2.928838225,10500,0,199.9991844,0,0,0,90.00000001 +259.5,50.30085681,-2.9288102,10500,0,199.9998535,0,0,0,90.00000001 +259.51,50.30085681,-2.928782175,10500,0,200.0009685,0,0,0,90.00000001 +259.52,50.30085681,-2.928754149,10500,0,200.0009685,0,0,0,90.00000001 +259.53,50.30085681,-2.928726124,10500,0,199.9998535,0,0,0,90.00000001 +259.54,50.30085681,-2.928698099,10500,0,199.9991844,0,0,0,90.00000001 +259.55,50.30085681,-2.928670074,10500,0,199.9998535,0,0,0,90.00000001 +259.56,50.30085681,-2.928642049,10500,0,200.0009685,0,0,0,90.00000001 +259.57,50.30085681,-2.928614023,10500,0,200.0009685,0,0,0,90.00000001 +259.58,50.30085681,-2.928585998,10500,0,199.9998535,0,0,0,90.00000001 +259.59,50.30085681,-2.928557973,10500,0,199.9991844,0,0,0,90.00000001 +259.6,50.30085681,-2.928529948,10500,0,199.9998535,0,0,0,90.00000001 +259.61,50.30085681,-2.928501923,10500,0,200.0009685,0,0,0,90.00000001 +259.62,50.30085681,-2.928473897,10500,0,200.0009685,0,0,0,90.00000001 +259.63,50.30085681,-2.928445872,10500,0,199.9998535,0,0,0,90.00000001 +259.64,50.30085681,-2.928417847,10500,0,199.9991844,0,0,0,90.00000001 +259.65,50.30085681,-2.928389822,10500,0,199.9998535,0,0,0,90.00000001 +259.66,50.30085681,-2.928361797,10500,0,200.0009685,0,0,0,90.00000001 +259.67,50.30085681,-2.928333771,10500,0,200.0009685,0,0,0,90.00000001 +259.68,50.30085681,-2.928305746,10500,0,199.9998535,0,0,0,90.00000001 +259.69,50.30085681,-2.928277721,10500,0,199.9989614,0,0,0,90.00000001 +259.7,50.30085681,-2.928249696,10500,0,199.9989614,0,0,0,90.00000001 +259.71,50.30085681,-2.928221671,10500,0,199.9998535,0,0,0,90.00000001 +259.72,50.30085681,-2.928193646,10500,0,200.0009685,0,0,0,90.00000001 +259.73,50.30085681,-2.92816562,10500,0,200.0009685,0,0,0,90.00000001 +259.74,50.30085681,-2.928137595,10500,0,199.9998535,0,0,0,90.00000001 +259.75,50.30085681,-2.92810957,10500,0,199.9989614,0,0,0,90.00000001 +259.76,50.30085681,-2.928081545,10500,0,199.9989614,0,0,0,90.00000001 +259.77,50.30085681,-2.92805352,10500,0,199.9998535,0,0,0,90.00000001 +259.78,50.30085681,-2.928025495,10500,0,200.0009685,0,0,0,90.00000001 +259.79,50.30085681,-2.927997469,10500,0,200.0009685,0,0,0,90.00000001 +259.8,50.30085681,-2.927969444,10500,0,199.9998535,0,0,0,90.00000001 +259.81,50.30085681,-2.927941419,10500,0,199.9989614,0,0,0,90.00000001 +259.82,50.30085681,-2.927913394,10500,0,199.9987384,0,0,0,90.00000001 +259.83,50.30085681,-2.927885369,10500,0,199.9989614,0,0,0,90.00000001 +259.84,50.30085681,-2.927857344,10500,0,199.9998535,0,0,0,90.00000001 +259.85,50.30085681,-2.927829319,10500,0,200.0009685,0,0,0,90.00000001 +259.86,50.30085681,-2.927801293,10500,0,200.0009685,0,0,0,90.00000001 +259.87,50.30085681,-2.927773268,10500,0,199.9998535,0,0,0,90.00000001 +259.88,50.30085681,-2.927745243,10500,0,199.9989614,0,0,0,90.00000001 +259.89,50.30085681,-2.927717218,10500,0,199.9989614,0,0,0,90.00000001 +259.9,50.30085681,-2.927689193,10500,0,199.9998535,0,0,0,90.00000001 +259.91,50.30085681,-2.927661168,10500,0,200.0009685,0,0,0,90.00000001 +259.92,50.30085681,-2.927633142,10500,0,200.0009685,0,0,0,90.00000001 +259.93,50.30085681,-2.927605117,10500,0,199.9998535,0,0,0,90.00000001 +259.94,50.30085681,-2.927577092,10500,0,199.9989614,0,0,0,90.00000001 +259.95,50.30085681,-2.927549067,10500,0,199.9989614,0,0,0,90.00000001 +259.96,50.30085681,-2.927521042,10500,0,199.9998535,0,0,0,90.00000001 +259.97,50.30085681,-2.927493017,10500,0,200.0009685,0,0,0,90.00000001 +259.98,50.30085681,-2.927464991,10500,0,200.0009685,0,0,0,90.00000001 +259.99,50.30085681,-2.927436966,10500,0,199.9998535,0,0,0,90.00000001 +260,50.30085681,-2.927408941,10500,0,199.9989614,0,0,0,90.00000001 +260.01,50.30085681,-2.927380916,10500,0,199.9989614,0,0,0,90.00000001 +260.02,50.30085681,-2.927352891,10500,0,199.9998535,0,0,0,90.00000001 +260.03,50.30085681,-2.927324866,10500,0,200.0009685,0,0,0,90.00000001 +260.04,50.30085681,-2.92729684,10500,0,200.0009685,0,0,0,90.00000001 +260.05,50.30085681,-2.927268815,10500,0,199.9998535,0,0,0,90.00000001 +260.06,50.30085681,-2.92724079,10500,0,199.9989614,0,0,0,90.00000001 +260.07,50.30085681,-2.927212765,10500,0,199.9989614,0,0,0,90.00000001 +260.08,50.30085681,-2.92718474,10500,0,199.9998535,0,0,0,90.00000001 +260.09,50.30085681,-2.927156715,10500,0,200.0009685,0,0,0,90.00000001 +260.1,50.30085681,-2.927128689,10500,0,200.0009685,0,0,0,90.00000001 +260.11,50.30085681,-2.927100664,10500,0,199.9998535,0,0,0,90.00000001 +260.12,50.30085681,-2.927072639,10500,0,199.9991844,0,0,0,90.00000001 +260.13,50.30085681,-2.927044614,10500,0,199.9998535,0,0,0,90.00000001 +260.14,50.30085681,-2.927016589,10500,0,200.0009685,0,0,0,90.00000001 +260.15,50.30085681,-2.926988563,10500,0,200.0009685,0,0,0,90.00000001 +260.16,50.30085681,-2.926960538,10500,0,199.9998535,0,0,0,90.00000001 +260.17,50.30085681,-2.926932513,10500,0,199.9991844,0,0,0,90.00000001 +260.18,50.30085681,-2.926904488,10500,0,199.9998535,0,0,0,90.00000001 +260.19,50.30085681,-2.926876463,10500,0,200.0009685,0,0,0,90.00000001 +260.2,50.30085681,-2.926848437,10500,0,200.0009685,0,0,0,90.00000001 +260.21,50.30085681,-2.926820412,10500,0,199.9998535,0,0,0,90.00000001 +260.22,50.30085681,-2.926792387,10500,0,199.9991844,0,0,0,90.00000001 +260.23,50.30085681,-2.926764362,10500,0,199.9998535,0,0,0,90.00000001 +260.24,50.30085681,-2.926736337,10500,0,200.0009685,0,0,0,90.00000001 +260.25,50.30085681,-2.926708311,10500,0,200.0009685,0,0,0,90.00000001 +260.26,50.30085681,-2.926680286,10500,0,199.9998535,0,0,0,90.00000001 +260.27,50.30085681,-2.926652261,10500,0,199.9991844,0,0,0,90.00000001 +260.28,50.30085681,-2.926624236,10500,0,199.9998535,0,0,0,90.00000001 +260.29,50.30085681,-2.926596211,10500,0,200.0009685,0,0,0,90.00000001 +260.3,50.30085681,-2.926568185,10500,0,200.0009685,0,0,0,90.00000001 +260.31,50.30085681,-2.92654016,10500,0,199.9998535,0,0,0,90.00000001 +260.32,50.30085681,-2.926512135,10500,0,199.9991844,0,0,0,90.00000001 +260.33,50.30085681,-2.92648411,10500,0,199.9998535,0,0,0,90.00000001 +260.34,50.30085681,-2.926456085,10500,0,200.0009685,0,0,0,90.00000001 +260.35,50.30085681,-2.926428059,10500,0,200.0009685,0,0,0,90.00000001 +260.36,50.30085681,-2.926400034,10500,0,199.9998535,0,0,0,90.00000001 +260.37,50.30085681,-2.926372009,10500,0,199.9989614,0,0,0,90.00000001 +260.38,50.30085681,-2.926343984,10500,0,199.9987384,0,0,0,90.00000001 +260.39,50.30085681,-2.926315959,10500,0,199.9989614,0,0,0,90.00000001 +260.4,50.30085681,-2.926287934,10500,0,199.9998535,0,0,0,90.00000001 +260.41,50.30085681,-2.926259909,10500,0,200.0009685,0,0,0,90.00000001 +260.42,50.30085681,-2.926231883,10500,0,200.0009685,0,0,0,90.00000001 +260.43,50.30085681,-2.926203858,10500,0,199.9998535,0,0,0,90.00000001 +260.44,50.30085681,-2.926175833,10500,0,199.9989614,0,0,0,90.00000001 +260.45,50.30085681,-2.926147808,10500,0,199.9989614,0,0,0,90.00000001 +260.46,50.30085681,-2.926119783,10500,0,199.9998535,0,0,0,90.00000001 +260.47,50.30085681,-2.926091758,10500,0,200.0009685,0,0,0,90.00000001 +260.48,50.30085681,-2.926063732,10500,0,200.0009685,0,0,0,90.00000001 +260.49,50.30085681,-2.926035707,10500,0,199.9998535,0,0,0,90.00000001 +260.5,50.30085681,-2.926007682,10500,0,199.9989614,0,0,0,90.00000001 +260.51,50.30085681,-2.925979657,10500,0,199.9989614,0,0,0,90.00000001 +260.52,50.30085681,-2.925951632,10500,0,199.9998535,0,0,0,90.00000001 +260.53,50.30085681,-2.925923607,10500,0,200.0009685,0,0,0,90.00000001 +260.54,50.30085681,-2.925895581,10500,0,200.0009685,0,0,0,90.00000001 +260.55,50.30085681,-2.925867556,10500,0,199.9998535,0,0,0,90.00000001 +260.56,50.30085681,-2.925839531,10500,0,199.9989614,0,0,0,90.00000001 +260.57,50.30085681,-2.925811506,10500,0,199.9989614,0,0,0,90.00000001 +260.58,50.30085681,-2.925783481,10500,0,199.9998535,0,0,0,90.00000001 +260.59,50.30085681,-2.925755456,10500,0,200.0009685,0,0,0,90.00000001 +260.6,50.30085681,-2.92572743,10500,0,200.0009685,0,0,0,90.00000001 +260.61,50.30085681,-2.925699405,10500,0,199.9998535,0,0,0,90.00000001 +260.62,50.30085681,-2.92567138,10500,0,199.9989614,0,0,0,90.00000001 +260.63,50.30085681,-2.925643355,10500,0,199.9989614,0,0,0,90.00000001 +260.64,50.30085681,-2.92561533,10500,0,199.9998535,0,0,0,90.00000001 +260.65,50.30085681,-2.925587305,10500,0,200.0009685,0,0,0,90.00000001 +260.66,50.30085681,-2.925559279,10500,0,200.0009685,0,0,0,90.00000001 +260.67,50.30085681,-2.925531254,10500,0,199.9998535,0,0,0,90.00000001 +260.68,50.30085681,-2.925503229,10500,0,199.9989614,0,0,0,90.00000001 +260.69,50.30085681,-2.925475204,10500,0,199.9989614,0,0,0,90.00000001 +260.7,50.30085681,-2.925447179,10500,0,199.9998535,0,0,0,90.00000001 +260.71,50.30085681,-2.925419154,10500,0,200.0009685,0,0,0,90.00000001 +260.72,50.30085681,-2.925391128,10500,0,200.0009685,0,0,0,90.00000001 +260.73,50.30085681,-2.925363103,10500,0,199.9998535,0,0,0,90.00000001 +260.74,50.30085681,-2.925335078,10500,0,199.9991844,0,0,0,90.00000001 +260.75,50.30085681,-2.925307053,10500,0,199.9998535,0,0,0,90.00000001 +260.76,50.30085681,-2.925279028,10500,0,200.0009685,0,0,0,90.00000001 +260.77,50.30085681,-2.925251002,10500,0,200.0009685,0,0,0,90.00000001 +260.78,50.30085681,-2.925222977,10500,0,199.9998535,0,0,0,90.00000001 +260.79,50.30085681,-2.925194952,10500,0,199.9991844,0,0,0,90.00000001 +260.8,50.30085681,-2.925166927,10500,0,199.9998535,0,0,0,90.00000001 +260.81,50.30085681,-2.925138902,10500,0,200.0009685,0,0,0,90.00000001 +260.82,50.30085681,-2.925110876,10500,0,200.0009685,0,0,0,90.00000001 +260.83,50.30085681,-2.925082851,10500,0,199.9998535,0,0,0,90.00000001 +260.84,50.30085681,-2.925054826,10500,0,199.9991844,0,0,0,90.00000001 +260.85,50.30085681,-2.925026801,10500,0,199.9998535,0,0,0,90.00000001 +260.86,50.30085681,-2.924998776,10500,0,200.0009685,0,0,0,90.00000001 +260.87,50.30085681,-2.92497075,10500,0,200.0009685,0,0,0,90.00000001 +260.88,50.30085681,-2.924942725,10500,0,199.9998535,0,0,0,90.00000001 +260.89,50.30085681,-2.9249147,10500,0,199.9991844,0,0,0,90.00000001 +260.9,50.30085681,-2.924886675,10500,0,199.9998535,0,0,0,90.00000001 +260.91,50.30085681,-2.92485865,10500,0,200.0009685,0,0,0,90.00000001 +260.92,50.30085681,-2.924830624,10500,0,200.0009685,0,0,0,90.00000001 +260.93,50.30085681,-2.924802599,10500,0,199.9998535,0,0,0,90.00000001 +260.94,50.30085681,-2.924774574,10500,0,199.9989614,0,0,0,90.00000001 +260.95,50.30085681,-2.924746549,10500,0,199.9989614,0,0,0,90.00000001 +260.96,50.30085681,-2.924718524,10500,0,199.9998535,0,0,0,90.00000001 +260.97,50.30085681,-2.924690499,10500,0,200.0009685,0,0,0,90.00000001 +260.98,50.30085681,-2.924662473,10500,0,200.0009685,0,0,0,90.00000001 +260.99,50.30085681,-2.924634448,10500,0,199.9998535,0,0,0,90.00000001 +261,50.30085681,-2.924606423,10500,0,199.9989614,0,0,0,90.00000001 +261.01,50.30085681,-2.924578398,10500,0,199.9989614,0,0,0,90.00000001 +261.02,50.30085681,-2.924550373,10500,0,199.9998535,0,0,0,90.00000001 +261.03,50.30085681,-2.924522348,10500,0,200.0009685,0,0,0,90.00000001 +261.04,50.30085681,-2.924494322,10500,0,200.0009685,0,0,0,90.00000001 +261.05,50.30085681,-2.924466297,10500,0,199.9998535,0,0,0,90.00000001 +261.06,50.30085681,-2.924438272,10500,0,199.9989614,0,0,0,90.00000001 +261.07,50.30085681,-2.924410247,10500,0,199.9989614,0,0,0,90.00000001 +261.08,50.30085681,-2.924382222,10500,0,199.9998535,0,0,0,90.00000001 +261.09,50.30085681,-2.924354197,10500,0,200.0009685,0,0,0,90.00000001 +261.1,50.30085681,-2.924326171,10500,0,200.0009685,0,0,0,90.00000001 +261.11,50.30085681,-2.924298146,10500,0,199.9998535,0,0,0,90.00000001 +261.12,50.30085681,-2.924270121,10500,0,199.9989614,0,0,0,90.00000001 +261.13,50.30085681,-2.924242096,10500,0,199.9989614,0,0,0,90.00000001 +261.14,50.30085681,-2.924214071,10500,0,199.9998535,0,0,0,90.00000001 +261.15,50.30085681,-2.924186046,10500,0,200.0009685,0,0,0,90.00000001 +261.16,50.30085681,-2.92415802,10500,0,200.0009685,0,0,0,90.00000001 +261.17,50.30085681,-2.924129995,10500,0,199.9998535,0,0,0,90.00000001 +261.18,50.30085681,-2.92410197,10500,0,199.9989614,0,0,0,90.00000001 +261.19,50.30085681,-2.924073945,10500,0,199.9989614,0,0,0,90.00000001 +261.2,50.30085681,-2.92404592,10500,0,199.9998535,0,0,0,90.00000001 +261.21,50.30085681,-2.924017895,10500,0,200.0009685,0,0,0,90.00000001 +261.22,50.30085681,-2.923989869,10500,0,200.0009685,0,0,0,90.00000001 +261.23,50.30085681,-2.923961844,10500,0,199.9998535,0,0,0,90.00000001 +261.24,50.30085681,-2.923933819,10500,0,199.9989614,0,0,0,90.00000001 +261.25,50.30085681,-2.923905794,10500,0,199.9987384,0,0,0,90.00000001 +261.26,50.30085681,-2.923877769,10500,0,199.9989614,0,0,0,90.00000001 +261.27,50.30085681,-2.923849744,10500,0,199.9998535,0,0,0,90.00000001 +261.28,50.30085681,-2.923821719,10500,0,200.0009685,0,0,0,90.00000001 +261.29,50.30085681,-2.923793693,10500,0,200.0009685,0,0,0,90.00000001 +261.3,50.30085681,-2.923765668,10500,0,199.9998535,0,0,0,90.00000001 +261.31,50.30085681,-2.923737643,10500,0,199.9991844,0,0,0,90.00000001 +261.32,50.30085681,-2.923709618,10500,0,199.9998535,0,0,0,90.00000001 +261.33,50.30085681,-2.923681593,10500,0,200.0009685,0,0,0,90.00000001 +261.34,50.30085681,-2.923653567,10500,0,200.0009685,0,0,0,90.00000001 +261.35,50.30085681,-2.923625542,10500,0,199.9998535,0,0,0,90.00000001 +261.36,50.30085681,-2.923597517,10500,0,199.9991844,0,0,0,90.00000001 +261.37,50.30085681,-2.923569492,10500,0,199.9998535,0,0,0,90.00000001 +261.38,50.30085681,-2.923541467,10500,0,200.0009685,0,0,0,90.00000001 +261.39,50.30085681,-2.923513441,10500,0,200.0009685,0,0,0,90.00000001 +261.4,50.30085681,-2.923485416,10500,0,199.9998535,0,0,0,90.00000001 +261.41,50.30085681,-2.923457391,10500,0,199.9991844,0,0,0,90.00000001 +261.42,50.30085681,-2.923429366,10500,0,199.9998535,0,0,0,90.00000001 +261.43,50.30085681,-2.923401341,10500,0,200.0009685,0,0,0,90.00000001 +261.44,50.30085681,-2.923373315,10500,0,200.0009685,0,0,0,90.00000001 +261.45,50.30085681,-2.92334529,10500,0,199.9998535,0,0,0,90.00000001 +261.46,50.30085681,-2.923317265,10500,0,199.9991844,0,0,0,90.00000001 +261.47,50.30085681,-2.92328924,10500,0,199.9998535,0,0,0,90.00000001 +261.48,50.30085681,-2.923261215,10500,0,200.0009685,0,0,0,90.00000001 +261.49,50.30085681,-2.923233189,10500,0,200.0009685,0,0,0,90.00000001 +261.5,50.30085681,-2.923205164,10500,0,199.9998535,0,0,0,90.00000001 +261.51,50.30085681,-2.923177139,10500,0,199.9991844,0,0,0,90.00000001 +261.52,50.30085681,-2.923149114,10500,0,199.9998535,0,0,0,90.00000001 +261.53,50.30085681,-2.923121089,10500,0,200.0009685,0,0,0,90.00000001 +261.54,50.30085681,-2.923093063,10500,0,200.0009685,0,0,0,90.00000001 +261.55,50.30085681,-2.923065038,10500,0,199.9998535,0,0,0,90.00000001 +261.56,50.30085681,-2.923037013,10500,0,199.9989614,0,0,0,90.00000001 +261.57,50.30085681,-2.923008988,10500,0,199.9989614,0,0,0,90.00000001 +261.58,50.30085681,-2.922980963,10500,0,199.9998535,0,0,0,90.00000001 +261.59,50.30085681,-2.922952938,10500,0,200.0009685,0,0,0,90.00000001 +261.6,50.30085681,-2.922924912,10500,0,200.0009685,0,0,0,90.00000001 +261.61,50.30085681,-2.922896887,10500,0,199.9998535,0,0,0,90.00000001 +261.62,50.30085681,-2.922868862,10500,0,199.9989614,0,0,0,90.00000001 +261.63,50.30085681,-2.922840837,10500,0,199.9989614,0,0,0,90.00000001 +261.64,50.30085681,-2.922812812,10500,0,199.9998535,0,0,0,90.00000001 +261.65,50.30085681,-2.922784787,10500,0,200.0009685,0,0,0,90.00000001 +261.66,50.30085681,-2.922756761,10500,0,200.0009685,0,0,0,90.00000001 +261.67,50.30085681,-2.922728736,10500,0,199.9998535,0,0,0,90.00000001 +261.68,50.30085681,-2.922700711,10500,0,199.9989614,0,0,0,90.00000001 +261.69,50.30085681,-2.922672686,10500,0,199.9989614,0,0,0,90.00000001 +261.7,50.30085681,-2.922644661,10500,0,199.9998535,0,0,0,90.00000001 +261.71,50.30085681,-2.922616636,10500,0,200.0009685,0,0,0,90.00000001 +261.72,50.30085681,-2.92258861,10500,0,200.0009685,0,0,0,90.00000001 +261.73,50.30085681,-2.922560585,10500,0,199.9998535,0,0,0,90.00000001 +261.74,50.30085681,-2.92253256,10500,0,199.9989614,0,0,0,90.00000001 +261.75,50.30085681,-2.922504535,10500,0,199.9989614,0,0,0,90.00000001 +261.76,50.30085681,-2.92247651,10500,0,199.9998535,0,0,0,90.00000001 +261.77,50.30085681,-2.922448485,10500,0,200.0009685,0,0,0,90.00000001 +261.78,50.30085681,-2.922420459,10500,0,200.0009685,0,0,0,90.00000001 +261.79,50.30085681,-2.922392434,10500,0,199.9998535,0,0,0,90.00000001 +261.8,50.30085681,-2.922364409,10500,0,199.9989614,0,0,0,90.00000001 +261.81,50.30085681,-2.922336384,10500,0,199.9987384,0,0,0,90.00000001 +261.82,50.30085681,-2.922308359,10500,0,199.9989614,0,0,0,90.00000001 +261.83,50.30085681,-2.922280334,10500,0,199.9998535,0,0,0,90.00000001 +261.84,50.30085681,-2.922252309,10500,0,200.0009685,0,0,0,90.00000001 +261.85,50.30085681,-2.922224283,10500,0,200.0009685,0,0,0,90.00000001 +261.86,50.30085681,-2.922196258,10500,0,199.9998535,0,0,0,90.00000001 +261.87,50.30085681,-2.922168233,10500,0,199.9989614,0,0,0,90.00000001 +261.88,50.30085681,-2.922140208,10500,0,199.9989614,0,0,0,90.00000001 +261.89,50.30085681,-2.922112183,10500,0,199.9998535,0,0,0,90.00000001 +261.9,50.30085681,-2.922084158,10500,0,200.0009685,0,0,0,90.00000001 +261.91,50.30085681,-2.922056132,10500,0,200.0009685,0,0,0,90.00000001 +261.92,50.30085681,-2.922028107,10500,0,199.9998535,0,0,0,90.00000001 +261.93,50.30085681,-2.922000082,10500,0,199.9991844,0,0,0,90.00000001 +261.94,50.30085681,-2.921972057,10500,0,199.9998535,0,0,0,90.00000001 +261.95,50.30085681,-2.921944032,10500,0,200.0009685,0,0,0,90.00000001 +261.96,50.30085681,-2.921916006,10500,0,200.0009685,0,0,0,90.00000001 +261.97,50.30085681,-2.921887981,10500,0,199.9998535,0,0,0,90.00000001 +261.98,50.30085681,-2.921859956,10500,0,199.9991844,0,0,0,90.00000001 +261.99,50.30085681,-2.921831931,10500,0,199.9998535,0,0,0,90.00000001 +262,50.30085681,-2.921803906,10500,0,200.0009685,0,0,0,90.00000001 +262.01,50.30085681,-2.92177588,10500,0,200.0009685,0,0,0,90.00000001 +262.02,50.30085681,-2.921747855,10500,0,199.9998535,0,0,0,90.00000001 +262.03,50.30085681,-2.92171983,10500,0,199.9991844,0,0,0,90.00000001 +262.04,50.30085681,-2.921691805,10500,0,199.9998535,0,0,0,90.00000001 +262.05,50.30085681,-2.92166378,10500,0,200.0009685,0,0,0,90.00000001 +262.06,50.30085681,-2.921635754,10500,0,200.0009685,0,0,0,90.00000001 +262.07,50.30085681,-2.921607729,10500,0,199.9998535,0,0,0,90.00000001 +262.08,50.30085681,-2.921579704,10500,0,199.9989614,0,0,0,90.00000001 +262.09,50.30085681,-2.921551679,10500,0,199.9989614,0,0,0,90.00000001 +262.1,50.30085681,-2.921523654,10500,0,199.9998535,0,0,0,90.00000001 +262.11,50.30085681,-2.921495629,10500,0,200.0009685,0,0,0,90.00000001 +262.12,50.30085681,-2.921467603,10500,0,200.0009685,0,0,0,90.00000001 +262.13,50.30085681,-2.921439578,10500,0,199.9998535,0,0,0,90.00000001 +262.14,50.30085681,-2.921411553,10500,0,199.9991844,0,0,0,90.00000001 +262.15,50.30085681,-2.921383528,10500,0,199.9998535,0,0,0,90.00000001 +262.16,50.30085681,-2.921355503,10500,0,200.0009685,0,0,0,90.00000001 +262.17,50.30085681,-2.921327477,10500,0,200.0009685,0,0,0,90.00000001 +262.18,50.30085681,-2.921299452,10500,0,199.9998535,0,0,0,90.00000001 +262.19,50.30085681,-2.921271427,10500,0,199.9991844,0,0,0,90.00000001 +262.2,50.30085681,-2.921243402,10500,0,199.9998535,0,0,0,90.00000001 +262.21,50.30085681,-2.921215377,10500,0,200.0009685,0,0,0,90.00000001 +262.22,50.30085681,-2.921187351,10500,0,200.0009685,0,0,0,90.00000001 +262.23,50.30085681,-2.921159326,10500,0,199.9998535,0,0,0,90.00000001 +262.24,50.30085681,-2.921131301,10500,0,199.9989614,0,0,0,90.00000001 +262.25,50.30085681,-2.921103276,10500,0,199.9989614,0,0,0,90.00000001 +262.26,50.30085681,-2.921075251,10500,0,199.9998535,0,0,0,90.00000001 +262.27,50.30085681,-2.921047226,10500,0,200.0009685,0,0,0,90.00000001 +262.28,50.30085681,-2.9210192,10500,0,200.0009685,0,0,0,90.00000001 +262.29,50.30085681,-2.920991175,10500,0,199.9998535,0,0,0,90.00000001 +262.3,50.30085681,-2.92096315,10500,0,199.9989614,0,0,0,90.00000001 +262.31,50.30085681,-2.920935125,10500,0,199.9989614,0,0,0,90.00000001 +262.32,50.30085681,-2.9209071,10500,0,199.9998535,0,0,0,90.00000001 +262.33,50.30085681,-2.920879075,10500,0,200.0009685,0,0,0,90.00000001 +262.34,50.30085681,-2.920851049,10500,0,200.0009685,0,0,0,90.00000001 +262.35,50.30085681,-2.920823024,10500,0,199.9998535,0,0,0,90.00000001 +262.36,50.30085681,-2.920794999,10500,0,199.9989614,0,0,0,90.00000001 +262.37,50.30085681,-2.920766974,10500,0,199.9987384,0,0,0,90.00000001 +262.38,50.30085681,-2.920738949,10500,0,199.9989614,0,0,0,90.00000001 +262.39,50.30085681,-2.920710924,10500,0,199.9998535,0,0,0,90.00000001 +262.4,50.30085681,-2.920682899,10500,0,200.0009685,0,0,0,90.00000001 +262.41,50.30085681,-2.920654873,10500,0,200.0009685,0,0,0,90.00000001 +262.42,50.30085681,-2.920626848,10500,0,199.9998535,0,0,0,90.00000001 +262.43,50.30085681,-2.920598823,10500,0,199.9989614,0,0,0,90.00000001 +262.44,50.30085681,-2.920570798,10500,0,199.9989614,0,0,0,90.00000001 +262.45,50.30085681,-2.920542773,10500,0,199.9998535,0,0,0,90.00000001 +262.46,50.30085681,-2.920514748,10500,0,200.0009685,0,0,0,90.00000001 +262.47,50.30085681,-2.920486722,10500,0,200.0009685,0,0,0,90.00000001 +262.48,50.30085681,-2.920458697,10500,0,199.9998535,0,0,0,90.00000001 +262.49,50.30085681,-2.920430672,10500,0,199.9989614,0,0,0,90.00000001 +262.5,50.30085681,-2.920402647,10500,0,199.9989614,0,0,0,90.00000001 +262.51,50.30085681,-2.920374622,10500,0,199.9998535,0,0,0,90.00000001 +262.52,50.30085681,-2.920346597,10500,0,200.0009685,0,0,0,90.00000001 +262.53,50.30085681,-2.920318571,10500,0,200.0009685,0,0,0,90.00000001 +262.54,50.30085681,-2.920290546,10500,0,199.9998535,0,0,0,90.00000001 +262.55,50.30085681,-2.920262521,10500,0,199.9989614,0,0,0,90.00000001 +262.56,50.30085681,-2.920234496,10500,0,199.9989614,0,0,0,90.00000001 +262.57,50.30085681,-2.920206471,10500,0,199.9998535,0,0,0,90.00000001 +262.58,50.30085681,-2.920178446,10500,0,200.0009685,0,0,0,90.00000001 +262.59,50.30085681,-2.92015042,10500,0,200.0009685,0,0,0,90.00000001 +262.6,50.30085681,-2.920122395,10500,0,199.9998535,0,0,0,90.00000001 +262.61,50.30085681,-2.92009437,10500,0,199.9991844,0,0,0,90.00000001 +262.62,50.30085681,-2.920066345,10500,0,199.9998535,0,0,0,90.00000001 +262.63,50.30085681,-2.92003832,10500,0,200.0009685,0,0,0,90.00000001 +262.64,50.30085681,-2.920010294,10500,0,200.0009685,0,0,0,90.00000001 +262.65,50.30085681,-2.919982269,10500,0,199.9998535,0,0,0,90.00000001 +262.66,50.30085681,-2.919954244,10500,0,199.9991844,0,0,0,90.00000001 +262.67,50.30085681,-2.919926219,10500,0,199.9998535,0,0,0,90.00000001 +262.68,50.30085681,-2.919898194,10500,0,200.0009685,0,0,0,90.00000001 +262.69,50.30085681,-2.919870168,10500,0,200.0009685,0,0,0,90.00000001 +262.7,50.30085681,-2.919842143,10500,0,199.9998535,0,0,0,90.00000001 +262.71,50.30085681,-2.919814118,10500,0,199.9991844,0,0,0,90.00000001 +262.72,50.30085681,-2.919786093,10500,0,199.9998535,0,0,0,90.00000001 +262.73,50.30085681,-2.919758068,10500,0,200.0009685,0,0,0,90.00000001 +262.74,50.30085681,-2.919730042,10500,0,200.0009685,0,0,0,90.00000001 +262.75,50.30085681,-2.919702017,10500,0,199.9998535,0,0,0,90.00000001 +262.76,50.30085681,-2.919673992,10500,0,199.9991844,0,0,0,90.00000001 +262.77,50.30085681,-2.919645967,10500,0,199.9998535,0,0,0,90.00000001 +262.78,50.30085681,-2.919617942,10500,0,200.0009685,0,0,0,90.00000001 +262.79,50.30085681,-2.919589916,10500,0,200.0009685,0,0,0,90.00000001 +262.8,50.30085681,-2.919561891,10500,0,199.9998535,0,0,0,90.00000001 +262.81,50.30085681,-2.919533866,10500,0,199.9991844,0,0,0,90.00000001 +262.82,50.30085681,-2.919505841,10500,0,199.9998535,0,0,0,90.00000001 +262.83,50.30085681,-2.919477816,10500,0,200.0009685,0,0,0,90.00000001 +262.84,50.30085681,-2.91944979,10500,0,200.0009685,0,0,0,90.00000001 +262.85,50.30085681,-2.919421765,10500,0,199.9998535,0,0,0,90.00000001 +262.86,50.30085681,-2.91939374,10500,0,199.9989614,0,0,0,90.00000001 +262.87,50.30085681,-2.919365715,10500,0,199.9989614,0,0,0,90.00000001 +262.88,50.30085681,-2.91933769,10500,0,199.9998535,0,0,0,90.00000001 +262.89,50.30085681,-2.919309665,10500,0,200.0009685,0,0,0,90.00000001 +262.9,50.30085681,-2.919281639,10500,0,200.0009685,0,0,0,90.00000001 +262.91,50.30085681,-2.919253614,10500,0,199.9998535,0,0,0,90.00000001 +262.92,50.30085681,-2.919225589,10500,0,199.9989614,0,0,0,90.00000001 +262.93,50.30085681,-2.919197564,10500,0,199.9987384,0,0,0,90.00000001 +262.94,50.30085681,-2.919169539,10500,0,199.9989614,0,0,0,90.00000001 +262.95,50.30085681,-2.919141514,10500,0,199.9998535,0,0,0,90.00000001 +262.96,50.30085681,-2.919113489,10500,0,200.0009685,0,0,0,90.00000001 +262.97,50.30085681,-2.919085463,10500,0,200.0009685,0,0,0,90.00000001 +262.98,50.30085681,-2.919057438,10500,0,199.9998535,0,0,0,90.00000001 +262.99,50.30085681,-2.919029413,10500,0,199.9989614,0,0,0,90.00000001 +263,50.30085681,-2.919001388,10500,0,199.9989614,0,0,0,90.00000001 +263.01,50.30085681,-2.918973363,10500,0,199.9998535,0,0,0,90.00000001 +263.02,50.30085681,-2.918945338,10500,0,200.0009685,0,0,0,90.00000001 +263.03,50.30085681,-2.918917312,10500,0,200.0009685,0,0,0,90.00000001 +263.04,50.30085681,-2.918889287,10500,0,199.9998535,0,0,0,90.00000001 +263.05,50.30085681,-2.918861262,10500,0,199.9989614,0,0,0,90.00000001 +263.06,50.30085681,-2.918833237,10500,0,199.9989614,0,0,0,90.00000001 +263.07,50.30085681,-2.918805212,10500,0,199.9998535,0,0,0,90.00000001 +263.08,50.30085681,-2.918777187,10500,0,200.0009685,0,0,0,90.00000001 +263.09,50.30085681,-2.918749161,10500,0,200.0009685,0,0,0,90.00000001 +263.1,50.30085681,-2.918721136,10500,0,199.9998535,0,0,0,90.00000001 +263.11,50.30085681,-2.918693111,10500,0,199.9989614,0,0,0,90.00000001 +263.12,50.30085681,-2.918665086,10500,0,199.9989614,0,0,0,90.00000001 +263.13,50.30085681,-2.918637061,10500,0,199.9998535,0,0,0,90.00000001 +263.14,50.30085681,-2.918609036,10500,0,200.0009685,0,0,0,90.00000001 +263.15,50.30085681,-2.91858101,10500,0,200.0009685,0,0,0,90.00000001 +263.16,50.30085681,-2.918552985,10500,0,199.9998535,0,0,0,90.00000001 +263.17,50.30085681,-2.91852496,10500,0,199.9989614,0,0,0,90.00000001 +263.18,50.30085681,-2.918496935,10500,0,199.9989614,0,0,0,90.00000001 +263.19,50.30085681,-2.91846891,10500,0,199.9998535,0,0,0,90.00000001 +263.2,50.30085681,-2.918440885,10500,0,200.0009685,0,0,0,90.00000001 +263.21,50.30085681,-2.918412859,10500,0,200.0009685,0,0,0,90.00000001 +263.22,50.30085681,-2.918384834,10500,0,199.9998535,0,0,0,90.00000001 +263.23,50.30085681,-2.918356809,10500,0,199.9991844,0,0,0,90.00000001 +263.24,50.30085681,-2.918328784,10500,0,199.9998535,0,0,0,90.00000001 +263.25,50.30085681,-2.918300759,10500,0,200.0009685,0,0,0,90.00000001 +263.26,50.30085681,-2.918272733,10500,0,200.0009685,0,0,0,90.00000001 +263.27,50.30085681,-2.918244708,10500,0,199.9998535,0,0,0,90.00000001 +263.28,50.30085681,-2.918216683,10500,0,199.9991844,0,0,0,90.00000001 +263.29,50.30085681,-2.918188658,10500,0,199.9998535,0,0,0,90.00000001 +263.3,50.30085681,-2.918160633,10500,0,200.0009685,0,0,0,90.00000001 +263.31,50.30085681,-2.918132607,10500,0,200.0009685,0,0,0,90.00000001 +263.32,50.30085681,-2.918104582,10500,0,199.9998535,0,0,0,90.00000001 +263.33,50.30085681,-2.918076557,10500,0,199.9991844,0,0,0,90.00000001 +263.34,50.30085681,-2.918048532,10500,0,199.9998535,0,0,0,90.00000001 +263.35,50.30085681,-2.918020507,10500,0,200.0009685,0,0,0,90.00000001 +263.36,50.30085681,-2.917992481,10500,0,200.0009685,0,0,0,90.00000001 +263.37,50.30085681,-2.917964456,10500,0,199.9998535,0,0,0,90.00000001 +263.38,50.30085681,-2.917936431,10500,0,199.9991844,0,0,0,90.00000001 +263.39,50.30085681,-2.917908406,10500,0,199.9998535,0,0,0,90.00000001 +263.4,50.30085681,-2.917880381,10500,0,200.0009685,0,0,0,90.00000001 +263.41,50.30085681,-2.917852355,10500,0,200.0009685,0,0,0,90.00000001 +263.42,50.30085681,-2.91782433,10500,0,199.9998535,0,0,0,90.00000001 +263.43,50.30085681,-2.917796305,10500,0,199.9991844,0,0,0,90.00000001 +263.44,50.30085681,-2.91776828,10500,0,199.9998535,0,0,0,90.00000001 +263.45,50.30085681,-2.917740255,10500,0,200.0009685,0,0,0,90.00000001 +263.46,50.30085681,-2.917712229,10500,0,200.0009685,0,0,0,90.00000001 +263.47,50.30085681,-2.917684204,10500,0,199.9998535,0,0,0,90.00000001 +263.48,50.30085681,-2.917656179,10500,0,199.9989614,0,0,0,90.00000001 +263.49,50.30085681,-2.917628154,10500,0,199.9989614,0,0,0,90.00000001 +263.5,50.30085681,-2.917600129,10500,0,199.9998535,0,0,0,90.00000001 +263.51,50.30085681,-2.917572104,10500,0,200.0009685,0,0,0,90.00000001 +263.52,50.30085681,-2.917544078,10500,0,200.0009685,0,0,0,90.00000001 +263.53,50.30085681,-2.917516053,10500,0,199.9998535,0,0,0,90.00000001 +263.54,50.30085681,-2.917488028,10500,0,199.9989614,0,0,0,90.00000001 +263.55,50.30085681,-2.917460003,10500,0,199.9987384,0,0,0,90.00000001 +263.56,50.30085681,-2.917431978,10500,0,199.9989614,0,0,0,90.00000001 +263.57,50.30085681,-2.917403953,10500,0,199.9998535,0,0,0,90.00000001 +263.58,50.30085681,-2.917375928,10500,0,200.0009685,0,0,0,90.00000001 +263.59,50.30085681,-2.917347902,10500,0,200.0009685,0,0,0,90.00000001 +263.6,50.30085681,-2.917319877,10500,0,199.9998535,0,0,0,90.00000001 +263.61,50.30085681,-2.917291852,10500,0,199.9989614,0,0,0,90.00000001 +263.62,50.30085681,-2.917263827,10500,0,199.9989614,0,0,0,90.00000001 +263.63,50.30085681,-2.917235802,10500,0,199.9998535,0,0,0,90.00000001 +263.64,50.30085681,-2.917207777,10500,0,200.0009685,0,0,0,90.00000001 +263.65,50.30085681,-2.917179751,10500,0,200.0009685,0,0,0,90.00000001 +263.66,50.30085681,-2.917151726,10500,0,199.9998535,0,0,0,90.00000001 +263.67,50.30085681,-2.917123701,10500,0,199.9989614,0,0,0,90.00000001 +263.68,50.30085681,-2.917095676,10500,0,199.9989614,0,0,0,90.00000001 +263.69,50.30085681,-2.917067651,10500,0,199.9998535,0,0,0,90.00000001 +263.7,50.30085681,-2.917039626,10500,0,200.0009685,0,0,0,90.00000001 +263.71,50.30085681,-2.9170116,10500,0,200.0009685,0,0,0,90.00000001 +263.72,50.30085681,-2.916983575,10500,0,199.9998535,0,0,0,90.00000001 +263.73,50.30085681,-2.91695555,10500,0,199.9989614,0,0,0,90.00000001 +263.74,50.30085681,-2.916927525,10500,0,199.9989614,0,0,0,90.00000001 +263.75,50.30085681,-2.9168995,10500,0,199.9998535,0,0,0,90.00000001 +263.76,50.30085681,-2.916871475,10500,0,200.0009685,0,0,0,90.00000001 +263.77,50.30085681,-2.916843449,10500,0,200.0009685,0,0,0,90.00000001 +263.78,50.30085681,-2.916815424,10500,0,199.9998535,0,0,0,90.00000001 +263.79,50.30085681,-2.916787399,10500,0,199.9989614,0,0,0,90.00000001 +263.8,50.30085681,-2.916759374,10500,0,199.9989614,0,0,0,90.00000001 +263.81,50.30085681,-2.916731349,10500,0,199.9998535,0,0,0,90.00000001 +263.82,50.30085681,-2.916703324,10500,0,200.0009685,0,0,0,90.00000001 +263.83,50.30085681,-2.916675298,10500,0,200.0009685,0,0,0,90.00000001 +263.84,50.30085681,-2.916647273,10500,0,199.9998535,0,0,0,90.00000001 +263.85,50.30085681,-2.916619248,10500,0,199.9991844,0,0,0,90.00000001 +263.86,50.30085681,-2.916591223,10500,0,199.9998535,0,0,0,90.00000001 +263.87,50.30085681,-2.916563198,10500,0,200.0009685,0,0,0,90.00000001 +263.88,50.30085681,-2.916535172,10500,0,200.0009685,0,0,0,90.00000001 +263.89,50.30085681,-2.916507147,10500,0,199.9998535,0,0,0,90.00000001 +263.9,50.30085681,-2.916479122,10500,0,199.9991844,0,0,0,90.00000001 +263.91,50.30085681,-2.916451097,10500,0,199.9998535,0,0,0,90.00000001 +263.92,50.30085681,-2.916423072,10500,0,200.0009685,0,0,0,90.00000001 +263.93,50.30085681,-2.916395046,10500,0,200.0009685,0,0,0,90.00000001 +263.94,50.30085681,-2.916367021,10500,0,199.9998535,0,0,0,90.00000001 +263.95,50.30085681,-2.916338996,10500,0,199.9991844,0,0,0,90.00000001 +263.96,50.30085681,-2.916310971,10500,0,199.9998535,0,0,0,90.00000001 +263.97,50.30085681,-2.916282946,10500,0,200.0009685,0,0,0,90.00000001 +263.98,50.30085681,-2.91625492,10500,0,200.0009685,0,0,0,90.00000001 +263.99,50.30085681,-2.916226895,10500,0,199.9998535,0,0,0,90.00000001 +264,50.30085681,-2.91619887,10500,0,199.9991844,0,0,0,90.00000001 +264.01,50.30085681,-2.916170845,10500,0,199.9998535,0,0,0,90.00000001 +264.02,50.30085681,-2.91614282,10500,0,200.0009685,0,0,0,90.00000001 +264.03,50.30085681,-2.916114794,10500,0,200.0009685,0,0,0,90.00000001 +264.04,50.30085681,-2.916086769,10500,0,199.9998535,0,0,0,90.00000001 +264.05,50.30085681,-2.916058744,10500,0,199.9991844,0,0,0,90.00000001 +264.06,50.30085681,-2.916030719,10500,0,199.9998535,0,0,0,90.00000001 +264.07,50.30085681,-2.916002694,10500,0,200.0009685,0,0,0,90.00000001 +264.08,50.30085681,-2.915974668,10500,0,200.0009685,0,0,0,90.00000001 +264.09,50.30085681,-2.915946643,10500,0,199.9998535,0,0,0,90.00000001 +264.1,50.30085681,-2.915918618,10500,0,199.9989614,0,0,0,90.00000001 +264.11,50.30085681,-2.915890593,10500,0,199.9987384,0,0,0,90.00000001 +264.12,50.30085681,-2.915862568,10500,0,199.9989614,0,0,0,90.00000001 +264.13,50.30085681,-2.915834543,10500,0,199.9998535,0,0,0,90.00000001 +264.14,50.30085681,-2.915806518,10500,0,200.0009685,0,0,0,90.00000001 +264.15,50.30085681,-2.915778492,10500,0,200.0009685,0,0,0,90.00000001 +264.16,50.30085681,-2.915750467,10500,0,199.9998535,0,0,0,90.00000001 +264.17,50.30085681,-2.915722442,10500,0,199.9989614,0,0,0,90.00000001 +264.18,50.30085681,-2.915694417,10500,0,199.9989614,0,0,0,90.00000001 +264.19,50.30085681,-2.915666392,10500,0,199.9998535,0,0,0,90.00000001 +264.2,50.30085681,-2.915638367,10500,0,200.0009685,0,0,0,90.00000001 +264.21,50.30085681,-2.915610341,10500,0,200.0009685,0,0,0,90.00000001 +264.22,50.30085681,-2.915582316,10500,0,199.9998535,0,0,0,90.00000001 +264.23,50.30085681,-2.915554291,10500,0,199.9989614,0,0,0,90.00000001 +264.24,50.30085681,-2.915526266,10500,0,199.9989614,0,0,0,90.00000001 +264.25,50.30085681,-2.915498241,10500,0,199.9998535,0,0,0,90.00000001 +264.26,50.30085681,-2.915470216,10500,0,200.0009685,0,0,0,90.00000001 +264.27,50.30085681,-2.91544219,10500,0,200.0009685,0,0,0,90.00000001 +264.28,50.30085681,-2.915414165,10500,0,199.9998535,0,0,0,90.00000001 +264.29,50.30085681,-2.91538614,10500,0,199.9989614,0,0,0,90.00000001 +264.3,50.30085681,-2.915358115,10500,0,199.9989614,0,0,0,90.00000001 +264.31,50.30085681,-2.91533009,10500,0,199.9998535,0,0,0,90.00000001 +264.32,50.30085681,-2.915302065,10500,0,200.0009685,0,0,0,90.00000001 +264.33,50.30085681,-2.915274039,10500,0,200.0009685,0,0,0,90.00000001 +264.34,50.30085681,-2.915246014,10500,0,199.9998535,0,0,0,90.00000001 +264.35,50.30085681,-2.915217989,10500,0,199.9989614,0,0,0,90.00000001 +264.36,50.30085681,-2.915189964,10500,0,199.9987384,0,0,0,90.00000001 +264.37,50.30085681,-2.915161939,10500,0,199.9989614,0,0,0,90.00000001 +264.38,50.30085681,-2.915133914,10500,0,199.9998535,0,0,0,90.00000001 +264.39,50.30085681,-2.915105889,10500,0,200.0009685,0,0,0,90.00000001 +264.4,50.30085681,-2.915077863,10500,0,200.0009685,0,0,0,90.00000001 +264.41,50.30085681,-2.915049838,10500,0,199.9998535,0,0,0,90.00000001 +264.42,50.30085681,-2.915021813,10500,0,199.9991844,0,0,0,90.00000001 +264.43,50.30085681,-2.914993788,10500,0,199.9998535,0,0,0,90.00000001 +264.44,50.30085681,-2.914965763,10500,0,200.0009685,0,0,0,90.00000001 +264.45,50.30085681,-2.914937737,10500,0,200.0009685,0,0,0,90.00000001 +264.46,50.30085681,-2.914909712,10500,0,199.9998535,0,0,0,90.00000001 +264.47,50.30085681,-2.914881687,10500,0,199.9989614,0,0,0,90.00000001 +264.48,50.30085681,-2.914853662,10500,0,199.9989614,0,0,0,90.00000001 +264.49,50.30085681,-2.914825637,10500,0,199.9998535,0,0,0,90.00000001 +264.5,50.30085681,-2.914797612,10500,0,200.0009685,0,0,0,90.00000001 +264.51,50.30085681,-2.914769586,10500,0,200.0009685,0,0,0,90.00000001 +264.52,50.30085681,-2.914741561,10500,0,199.9998535,0,0,0,90.00000001 +264.53,50.30085681,-2.914713536,10500,0,199.9991844,0,0,0,90.00000001 +264.54,50.30085681,-2.914685511,10500,0,199.9998535,0,0,0,90.00000001 +264.55,50.30085681,-2.914657486,10500,0,200.0009685,0,0,0,90.00000001 +264.56,50.30085681,-2.91462946,10500,0,200.0009685,0,0,0,90.00000001 +264.57,50.30085681,-2.914601435,10500,0,199.9998535,0,0,0,90.00000001 +264.58,50.30085681,-2.91457341,10500,0,199.9991844,0,0,0,90.00000001 +264.59,50.30085681,-2.914545385,10500,0,199.9998535,0,0,0,90.00000001 +264.6,50.30085681,-2.91451736,10500,0,200.0009685,0,0,0,90.00000001 +264.61,50.30085681,-2.914489334,10500,0,200.0009685,0,0,0,90.00000001 +264.62,50.30085681,-2.914461309,10500,0,199.9998535,0,0,0,90.00000001 +264.63,50.30085681,-2.914433284,10500,0,199.9991844,0,0,0,90.00000001 +264.64,50.30085681,-2.914405259,10500,0,199.9998535,0,0,0,90.00000001 +264.65,50.30085681,-2.914377234,10500,0,200.0009685,0,0,0,90.00000001 +264.66,50.30085681,-2.914349208,10500,0,200.0009685,0,0,0,90.00000001 +264.67,50.30085681,-2.914321183,10500,0,199.9998535,0,0,0,90.00000001 +264.68,50.30085681,-2.914293158,10500,0,199.9991844,0,0,0,90.00000001 +264.69,50.30085681,-2.914265133,10500,0,199.9998535,0,0,0,90.00000001 +264.7,50.30085681,-2.914237108,10500,0,200.0009685,0,0,0,90.00000001 +264.71,50.30085681,-2.914209082,10500,0,200.0009685,0,0,0,90.00000001 +264.72,50.30085681,-2.914181057,10500,0,199.9998535,0,0,0,90.00000001 +264.73,50.30085681,-2.914153032,10500,0,199.9989614,0,0,0,90.00000001 +264.74,50.30085681,-2.914125007,10500,0,199.9989614,0,0,0,90.00000001 +264.75,50.30085681,-2.914096982,10500,0,199.9998535,0,0,0,90.00000001 +264.76,50.30085681,-2.914068957,10500,0,200.0009685,0,0,0,90.00000001 +264.77,50.30085681,-2.914040931,10500,0,200.0009685,0,0,0,90.00000001 +264.78,50.30085681,-2.914012906,10500,0,199.9998535,0,0,0,90.00000001 +264.79,50.30085681,-2.913984881,10500,0,199.9989614,0,0,0,90.00000001 +264.8,50.30085681,-2.913956856,10500,0,199.9989614,0,0,0,90.00000001 +264.81,50.30085681,-2.913928831,10500,0,199.9998535,0,0,0,90.00000001 +264.82,50.30085681,-2.913900806,10500,0,200.0009685,0,0,0,90.00000001 +264.83,50.30085681,-2.91387278,10500,0,200.0009685,0,0,0,90.00000001 +264.84,50.30085681,-2.913844755,10500,0,199.9998535,0,0,0,90.00000001 +264.85,50.30085681,-2.91381673,10500,0,199.9989614,0,0,0,90.00000001 +264.86,50.30085681,-2.913788705,10500,0,199.9989614,0,0,0,90.00000001 +264.87,50.30085681,-2.91376068,10500,0,199.9998535,0,0,0,90.00000001 +264.88,50.30085681,-2.913732655,10500,0,200.0009685,0,0,0,90.00000001 +264.89,50.30085681,-2.913704629,10500,0,200.0009685,0,0,0,90.00000001 +264.9,50.30085681,-2.913676604,10500,0,199.9998535,0,0,0,90.00000001 +264.91,50.30085681,-2.913648579,10500,0,199.9989614,0,0,0,90.00000001 +264.92,50.30085681,-2.913620554,10500,0,199.9989614,0,0,0,90.00000001 +264.93,50.30085681,-2.913592529,10500,0,199.9998535,0,0,0,90.00000001 +264.94,50.30085681,-2.913564504,10500,0,200.0009685,0,0,0,90.00000001 +264.95,50.30085681,-2.913536478,10500,0,200.0009685,0,0,0,90.00000001 +264.96,50.30085681,-2.913508453,10500,0,199.9998535,0,0,0,90.00000001 +264.97,50.30085681,-2.913480428,10500,0,199.9989614,0,0,0,90.00000001 +264.98,50.30085681,-2.913452403,10500,0,199.9987384,0,0,0,90.00000001 +264.99,50.30085681,-2.913424378,10500,0,199.9989614,0,0,0,90.00000001 +265,50.30085681,-2.913396353,10500,0,199.9998535,0,0,0,90.00000001 +265.01,50.30085681,-2.913368328,10500,0,200.0009685,0,0,0,90.00000001 +265.02,50.30085681,-2.913340302,10500,0,200.0009685,0,0,0,90.00000001 +265.03,50.30085681,-2.913312277,10500,0,199.9998535,0,0,0,90.00000001 +265.04,50.30085681,-2.913284252,10500,0,199.9989614,0,0,0,90.00000001 +265.05,50.30085681,-2.913256227,10500,0,199.9989614,0,0,0,90.00000001 +265.06,50.30085681,-2.913228202,10500,0,199.9998535,0,0,0,90.00000001 +265.07,50.30085681,-2.913200177,10500,0,200.0009685,0,0,0,90.00000001 +265.08,50.30085681,-2.913172151,10500,0,200.0009685,0,0,0,90.00000001 +265.09,50.30085681,-2.913144126,10500,0,199.9998535,0,0,0,90.00000001 +265.1,50.30085681,-2.913116101,10500,0,199.9991844,0,0,0,90.00000001 +265.11,50.30085681,-2.913088076,10500,0,199.9998535,0,0,0,90.00000001 +265.12,50.30085681,-2.913060051,10500,0,200.0009685,0,0,0,90.00000001 +265.13,50.30085681,-2.913032025,10500,0,200.0009685,0,0,0,90.00000001 +265.14,50.30085681,-2.913004,10500,0,199.9998535,0,0,0,90.00000001 +265.15,50.30085681,-2.912975975,10500,0,199.9991844,0,0,0,90.00000001 +265.16,50.30085681,-2.91294795,10500,0,199.9998535,0,0,0,90.00000001 +265.17,50.30085681,-2.912919925,10500,0,200.0009685,0,0,0,90.00000001 +265.18,50.30085681,-2.912891899,10500,0,200.0009685,0,0,0,90.00000001 +265.19,50.30085681,-2.912863874,10500,0,199.9998535,0,0,0,90.00000001 +265.2,50.30085681,-2.912835849,10500,0,199.9991844,0,0,0,90.00000001 +265.21,50.30085681,-2.912807824,10500,0,199.9998535,0,0,0,90.00000001 +265.22,50.30085681,-2.912779799,10500,0,200.0009685,0,0,0,90.00000001 +265.23,50.30085681,-2.912751773,10500,0,200.0009685,0,0,0,90.00000001 +265.24,50.30085681,-2.912723748,10500,0,199.9998535,0,0,0,90.00000001 +265.25,50.30085681,-2.912695723,10500,0,199.9991844,0,0,0,90.00000001 +265.26,50.30085681,-2.912667698,10500,0,199.9998535,0,0,0,90.00000001 +265.27,50.30085681,-2.912639673,10500,0,200.0009685,0,0,0,90.00000001 +265.28,50.30085681,-2.912611647,10500,0,200.0009685,0,0,0,90.00000001 +265.29,50.30085681,-2.912583622,10500,0,199.9998535,0,0,0,90.00000001 +265.3,50.30085681,-2.912555597,10500,0,199.9991844,0,0,0,90.00000001 +265.31,50.30085681,-2.912527572,10500,0,199.9998535,0,0,0,90.00000001 +265.32,50.30085681,-2.912499547,10500,0,200.0009685,0,0,0,90.00000001 +265.33,50.30085681,-2.912471521,10500,0,200.0009685,0,0,0,90.00000001 +265.34,50.30085681,-2.912443496,10500,0,199.9998535,0,0,0,90.00000001 +265.35,50.30085681,-2.912415471,10500,0,199.9989614,0,0,0,90.00000001 +265.36,50.30085681,-2.912387446,10500,0,199.9989614,0,0,0,90.00000001 +265.37,50.30085681,-2.912359421,10500,0,199.9998535,0,0,0,90.00000001 +265.38,50.30085681,-2.912331396,10500,0,200.0009685,0,0,0,90.00000001 +265.39,50.30085681,-2.91230337,10500,0,200.0009685,0,0,0,90.00000001 +265.4,50.30085681,-2.912275345,10500,0,199.9998535,0,0,0,90.00000001 +265.41,50.30085681,-2.91224732,10500,0,199.9989614,0,0,0,90.00000001 +265.42,50.30085681,-2.912219295,10500,0,199.9989614,0,0,0,90.00000001 +265.43,50.30085681,-2.91219127,10500,0,199.9998535,0,0,0,90.00000001 +265.44,50.30085681,-2.912163245,10500,0,200.0009685,0,0,0,90.00000001 +265.45,50.30085681,-2.912135219,10500,0,200.0009685,0,0,0,90.00000001 +265.46,50.30085681,-2.912107194,10500,0,199.9998535,0,0,0,90.00000001 +265.47,50.30085681,-2.912079169,10500,0,199.9989614,0,0,0,90.00000001 +265.48,50.30085681,-2.912051144,10500,0,199.9989614,0,0,0,90.00000001 +265.49,50.30085681,-2.912023119,10500,0,199.9998535,0,0,0,90.00000001 +265.5,50.30085681,-2.911995094,10500,0,200.0009685,0,0,0,90.00000001 +265.51,50.30085681,-2.911967068,10500,0,200.0009685,0,0,0,90.00000001 +265.52,50.30085681,-2.911939043,10500,0,199.9998535,0,0,0,90.00000001 +265.53,50.30085681,-2.911911018,10500,0,199.9989614,0,0,0,90.00000001 +265.54,50.30085681,-2.911882993,10500,0,199.9987384,0,0,0,90.00000001 +265.55,50.30085681,-2.911854968,10500,0,199.9989614,0,0,0,90.00000001 +265.56,50.30085681,-2.911826943,10500,0,199.9998535,0,0,0,90.00000001 +265.57,50.30085681,-2.911798918,10500,0,200.0009685,0,0,0,90.00000001 +265.58,50.30085681,-2.911770892,10500,0,200.0009685,0,0,0,90.00000001 +265.59,50.30085681,-2.911742867,10500,0,199.9998535,0,0,0,90.00000001 +265.6,50.30085681,-2.911714842,10500,0,199.9989614,0,0,0,90.00000001 +265.61,50.30085681,-2.911686817,10500,0,199.9989614,0,0,0,90.00000001 +265.62,50.30085681,-2.911658792,10500,0,199.9998535,0,0,0,90.00000001 +265.63,50.30085681,-2.911630767,10500,0,200.0009685,0,0,0,90.00000001 +265.64,50.30085681,-2.911602741,10500,0,200.0009685,0,0,0,90.00000001 +265.65,50.30085681,-2.911574716,10500,0,199.9998535,0,0,0,90.00000001 +265.66,50.30085681,-2.911546691,10500,0,199.9989614,0,0,0,90.00000001 +265.67,50.30085681,-2.911518666,10500,0,199.9989614,0,0,0,90.00000001 +265.68,50.30085681,-2.911490641,10500,0,199.9998535,0,0,0,90.00000001 +265.69,50.30085681,-2.911462616,10500,0,200.0009685,0,0,0,90.00000001 +265.7,50.30085681,-2.91143459,10500,0,200.0009685,0,0,0,90.00000001 +265.71,50.30085681,-2.911406565,10500,0,199.9998535,0,0,0,90.00000001 +265.72,50.30085681,-2.91137854,10500,0,199.9991844,0,0,0,90.00000001 +265.73,50.30085681,-2.911350515,10500,0,199.9998535,0,0,0,90.00000001 +265.74,50.30085681,-2.91132249,10500,0,200.0009685,0,0,0,90.00000001 +265.75,50.30085681,-2.911294464,10500,0,200.0009685,0,0,0,90.00000001 +265.76,50.30085681,-2.911266439,10500,0,199.9998535,0,0,0,90.00000001 +265.77,50.30085681,-2.911238414,10500,0,199.9991844,0,0,0,90.00000001 +265.78,50.30085681,-2.911210389,10500,0,199.9998535,0,0,0,90.00000001 +265.79,50.30085681,-2.911182364,10500,0,200.0009685,0,0,0,90.00000001 +265.8,50.30085681,-2.911154338,10500,0,200.0009685,0,0,0,90.00000001 +265.81,50.30085681,-2.911126313,10500,0,199.9998535,0,0,0,90.00000001 +265.82,50.30085681,-2.911098288,10500,0,199.9991844,0,0,0,90.00000001 +265.83,50.30085681,-2.911070263,10500,0,199.9998535,0,0,0,90.00000001 +265.84,50.30085681,-2.911042238,10500,0,200.0009685,0,0,0,90.00000001 +265.85,50.30085681,-2.911014212,10500,0,200.0009685,0,0,0,90.00000001 +265.86,50.30085681,-2.910986187,10500,0,199.9998535,0,0,0,90.00000001 +265.87,50.30085681,-2.910958162,10500,0,199.9991844,0,0,0,90.00000001 +265.88,50.30085681,-2.910930137,10500,0,199.9998535,0,0,0,90.00000001 +265.89,50.30085681,-2.910902112,10500,0,200.0009685,0,0,0,90.00000001 +265.9,50.30085681,-2.910874086,10500,0,200.0009685,0,0,0,90.00000001 +265.91,50.30085681,-2.910846061,10500,0,199.9998535,0,0,0,90.00000001 +265.92,50.30085681,-2.910818036,10500,0,199.9991844,0,0,0,90.00000001 +265.93,50.30085681,-2.910790011,10500,0,199.9998535,0,0,0,90.00000001 +265.94,50.30085681,-2.910761986,10500,0,200.0009685,0,0,0,90.00000001 +265.95,50.30085681,-2.91073396,10500,0,200.0009685,0,0,0,90.00000001 +265.96,50.30085681,-2.910705935,10500,0,199.9998535,0,0,0,90.00000001 +265.97,50.30085681,-2.91067791,10500,0,199.9989614,0,0,0,90.00000001 +265.98,50.30085681,-2.910649885,10500,0,199.9989614,0,0,0,90.00000001 +265.99,50.30085681,-2.91062186,10500,0,199.9998535,0,0,0,90.00000001 +266,50.30085681,-2.910593835,10500,0,200.0009685,0,0,0,90.00000001 +266.01,50.30085681,-2.910565809,10500,0,200.0009685,0,0,0,90.00000001 +266.02,50.30085681,-2.910537784,10500,0,199.9998535,0,0,0,90.00000001 +266.03,50.30085681,-2.910509759,10500,0,199.9989614,0,0,0,90.00000001 +266.04,50.30085681,-2.910481734,10500,0,199.9989614,0,0,0,90.00000001 +266.05,50.30085681,-2.910453709,10500,0,199.9998535,0,0,0,90.00000001 +266.06,50.30085681,-2.910425684,10500,0,200.0009685,0,0,0,90.00000001 +266.07,50.30085681,-2.910397658,10500,0,200.0009685,0,0,0,90.00000001 +266.08,50.30085681,-2.910369633,10500,0,199.9998535,0,0,0,90.00000001 +266.09,50.30085681,-2.910341608,10500,0,199.9989614,0,0,0,90.00000001 +266.1,50.30085681,-2.910313583,10500,0,199.9987384,0,0,0,90.00000001 +266.11,50.30085681,-2.910285558,10500,0,199.9989614,0,0,0,90.00000001 +266.12,50.30085681,-2.910257533,10500,0,199.9998535,0,0,0,90.00000001 +266.13,50.30085681,-2.910229508,10500,0,200.0009685,0,0,0,90.00000001 +266.14,50.30085681,-2.910201482,10500,0,200.0009685,0,0,0,90.00000001 +266.15,50.30085681,-2.910173457,10500,0,199.9998535,0,0,0,90.00000001 +266.16,50.30085681,-2.910145432,10500,0,199.9989614,0,0,0,90.00000001 +266.17,50.30085681,-2.910117407,10500,0,199.9989614,0,0,0,90.00000001 +266.18,50.30085681,-2.910089382,10500,0,199.9998535,0,0,0,90.00000001 +266.19,50.30085681,-2.910061357,10500,0,200.0009685,0,0,0,90.00000001 +266.2,50.30085681,-2.910033331,10500,0,200.0009685,0,0,0,90.00000001 +266.21,50.30085681,-2.910005306,10500,0,199.9998535,0,0,0,90.00000001 +266.22,50.30085681,-2.909977281,10500,0,199.9989614,0,0,0,90.00000001 +266.23,50.30085681,-2.909949256,10500,0,199.9989614,0,0,0,90.00000001 +266.24,50.30085681,-2.909921231,10500,0,199.9998535,0,0,0,90.00000001 +266.25,50.30085681,-2.909893206,10500,0,200.0009685,0,0,0,90.00000001 +266.26,50.30085681,-2.90986518,10500,0,200.0009685,0,0,0,90.00000001 +266.27,50.30085681,-2.909837155,10500,0,199.9998535,0,0,0,90.00000001 +266.28,50.30085681,-2.90980913,10500,0,199.9989614,0,0,0,90.00000001 +266.29,50.30085681,-2.909781105,10500,0,199.9989614,0,0,0,90.00000001 +266.3,50.30085681,-2.90975308,10500,0,199.9998535,0,0,0,90.00000001 +266.31,50.30085681,-2.909725055,10500,0,200.0009685,0,0,0,90.00000001 +266.32,50.30085681,-2.909697029,10500,0,200.0009685,0,0,0,90.00000001 +266.33,50.30085681,-2.909669004,10500,0,199.9998535,0,0,0,90.00000001 +266.34,50.30085681,-2.909640979,10500,0,199.9991844,0,0,0,90.00000001 +266.35,50.30085681,-2.909612954,10500,0,199.9998535,0,0,0,90.00000001 +266.36,50.30085681,-2.909584929,10500,0,200.0009685,0,0,0,90.00000001 +266.37,50.30085681,-2.909556903,10500,0,200.0009685,0,0,0,90.00000001 +266.38,50.30085681,-2.909528878,10500,0,199.9998535,0,0,0,90.00000001 +266.39,50.30085681,-2.909500853,10500,0,199.9991844,0,0,0,90.00000001 +266.4,50.30085681,-2.909472828,10500,0,199.9998535,0,0,0,90.00000001 +266.41,50.30085681,-2.909444803,10500,0,200.0009685,0,0,0,90.00000001 +266.42,50.30085681,-2.909416777,10500,0,200.0009685,0,0,0,90.00000001 +266.43,50.30085681,-2.909388752,10500,0,199.9998535,0,0,0,90.00000001 +266.44,50.30085681,-2.909360727,10500,0,199.9991844,0,0,0,90.00000001 +266.45,50.30085681,-2.909332702,10500,0,199.9998535,0,0,0,90.00000001 +266.46,50.30085681,-2.909304677,10500,0,200.0009685,0,0,0,90.00000001 +266.47,50.30085681,-2.909276651,10500,0,200.0009685,0,0,0,90.00000001 +266.48,50.30085681,-2.909248626,10500,0,199.9998535,0,0,0,90.00000001 +266.49,50.30085681,-2.909220601,10500,0,199.9991844,0,0,0,90.00000001 +266.5,50.30085681,-2.909192576,10500,0,199.9998535,0,0,0,90.00000001 +266.51,50.30085681,-2.909164551,10500,0,200.0009685,0,0,0,90.00000001 +266.52,50.30085681,-2.909136525,10500,0,200.0009685,0,0,0,90.00000001 +266.53,50.30085681,-2.9091085,10500,0,199.9998535,0,0,0,90.00000001 +266.54,50.30085681,-2.909080475,10500,0,199.9989614,0,0,0,90.00000001 +266.55,50.30085681,-2.90905245,10500,0,199.9989614,0,0,0,90.00000001 +266.56,50.30085681,-2.909024425,10500,0,199.9998535,0,0,0,90.00000001 +266.57,50.30085681,-2.9089964,10500,0,200.0009685,0,0,0,90.00000001 +266.58,50.30085681,-2.908968374,10500,0,200.0009685,0,0,0,90.00000001 +266.59,50.30085681,-2.908940349,10500,0,199.9998535,0,0,0,90.00000001 +266.6,50.30085681,-2.908912324,10500,0,199.9991844,0,0,0,90.00000001 +266.61,50.30085681,-2.908884299,10500,0,199.9998535,0,0,0,90.00000001 +266.62,50.30085681,-2.908856274,10500,0,200.0009685,0,0,0,90.00000001 +266.63,50.30085681,-2.908828248,10500,0,200.0009685,0,0,0,90.00000001 +266.64,50.30085681,-2.908800223,10500,0,199.9998535,0,0,0,90.00000001 +266.65,50.30085681,-2.908772198,10500,0,199.9989614,0,0,0,90.00000001 +266.66,50.30085681,-2.908744173,10500,0,199.9987384,0,0,0,90.00000001 +266.67,50.30085681,-2.908716148,10500,0,199.9989614,0,0,0,90.00000001 +266.68,50.30085681,-2.908688123,10500,0,199.9998535,0,0,0,90.00000001 +266.69,50.30085681,-2.908660098,10500,0,200.0009685,0,0,0,90.00000001 +266.7,50.30085681,-2.908632072,10500,0,200.0009685,0,0,0,90.00000001 +266.71,50.30085681,-2.908604047,10500,0,199.9998535,0,0,0,90.00000001 +266.72,50.30085681,-2.908576022,10500,0,199.9989614,0,0,0,90.00000001 +266.73,50.30085681,-2.908547997,10500,0,199.9989614,0,0,0,90.00000001 +266.74,50.30085681,-2.908519972,10500,0,199.9998535,0,0,0,90.00000001 +266.75,50.30085681,-2.908491947,10500,0,200.0009685,0,0,0,90.00000001 +266.76,50.30085681,-2.908463921,10500,0,200.0009685,0,0,0,90.00000001 +266.77,50.30085681,-2.908435896,10500,0,199.9998535,0,0,0,90.00000001 +266.78,50.30085681,-2.908407871,10500,0,199.9989614,0,0,0,90.00000001 +266.79,50.30085681,-2.908379846,10500,0,199.9989614,0,0,0,90.00000001 +266.8,50.30085681,-2.908351821,10500,0,199.9998535,0,0,0,90.00000001 +266.81,50.30085681,-2.908323796,10500,0,200.0009685,0,0,0,90.00000001 +266.82,50.30085681,-2.90829577,10500,0,200.0009685,0,0,0,90.00000001 +266.83,50.30085681,-2.908267745,10500,0,199.9998535,0,0,0,90.00000001 +266.84,50.30085681,-2.90823972,10500,0,199.9989614,0,0,0,90.00000001 +266.85,50.30085681,-2.908211695,10500,0,199.9989614,0,0,0,90.00000001 +266.86,50.30085681,-2.90818367,10500,0,199.9998535,0,0,0,90.00000001 +266.87,50.30085681,-2.908155645,10500,0,200.0009685,0,0,0,90.00000001 +266.88,50.30085681,-2.908127619,10500,0,200.0009685,0,0,0,90.00000001 +266.89,50.30085681,-2.908099594,10500,0,199.9998535,0,0,0,90.00000001 +266.9,50.30085681,-2.908071569,10500,0,199.9989614,0,0,0,90.00000001 +266.91,50.30085681,-2.908043544,10500,0,199.9989614,0,0,0,90.00000001 +266.92,50.30085681,-2.908015519,10500,0,199.9998535,0,0,0,90.00000001 +266.93,50.30085681,-2.907987494,10500,0,200.0009685,0,0,0,90.00000001 +266.94,50.30085681,-2.907959468,10500,0,200.0009685,0,0,0,90.00000001 +266.95,50.30085681,-2.907931443,10500,0,199.9998535,0,0,0,90.00000001 +266.96,50.30085681,-2.907903418,10500,0,199.9989614,0,0,0,90.00000001 +266.97,50.30085681,-2.907875393,10500,0,199.9989614,0,0,0,90.00000001 +266.98,50.30085681,-2.907847368,10500,0,199.9998535,0,0,0,90.00000001 +266.99,50.30085681,-2.907819343,10500,0,200.0009685,0,0,0,90.00000001 +267,50.30085681,-2.907791317,10500,0,200.0009685,0,0,0,90.00000001 +267.01,50.30085681,-2.907763292,10500,0,199.9998535,0,0,0,90.00000001 +267.02,50.30085681,-2.907735267,10500,0,199.9991844,0,0,0,90.00000001 +267.03,50.30085681,-2.907707242,10500,0,199.9998535,0,0,0,90.00000001 +267.04,50.30085681,-2.907679217,10500,0,200.0009685,0,0,0,90.00000001 +267.05,50.30085681,-2.907651191,10500,0,200.0009685,0,0,0,90.00000001 +267.06,50.30085681,-2.907623166,10500,0,199.9998535,0,0,0,90.00000001 +267.07,50.30085681,-2.907595141,10500,0,199.9991844,0,0,0,90.00000001 +267.08,50.30085681,-2.907567116,10500,0,199.9998535,0,0,0,90.00000001 +267.09,50.30085681,-2.907539091,10500,0,200.0009685,0,0,0,90.00000001 +267.1,50.30085681,-2.907511065,10500,0,200.0009685,0,0,0,90.00000001 +267.11,50.30085681,-2.90748304,10500,0,199.9998535,0,0,0,90.00000001 +267.12,50.30085681,-2.907455015,10500,0,199.9991844,0,0,0,90.00000001 +267.13,50.30085681,-2.90742699,10500,0,199.9998535,0,0,0,90.00000001 +267.14,50.30085681,-2.907398965,10500,0,200.0009685,0,0,0,90.00000001 +267.15,50.30085681,-2.907370939,10500,0,200.0009685,0,0,0,90.00000001 +267.16,50.30085681,-2.907342914,10500,0,199.9998535,0,0,0,90.00000001 +267.17,50.30085681,-2.907314889,10500,0,199.9991844,0,0,0,90.00000001 +267.18,50.30085681,-2.907286864,10500,0,199.9998535,0,0,0,90.00000001 +267.19,50.30085681,-2.907258839,10500,0,200.0009685,0,0,0,90.00000001 +267.2,50.30085681,-2.907230813,10500,0,200.0009685,0,0,0,90.00000001 +267.21,50.30085681,-2.907202788,10500,0,199.9998535,0,0,0,90.00000001 +267.22,50.30085681,-2.907174763,10500,0,199.9989614,0,0,0,90.00000001 +267.23,50.30085681,-2.907146738,10500,0,199.9989614,0,0,0,90.00000001 +267.24,50.30085681,-2.907118713,10500,0,199.9998535,0,0,0,90.00000001 +267.25,50.30085681,-2.907090688,10500,0,200.0009685,0,0,0,90.00000001 +267.26,50.30085681,-2.907062662,10500,0,200.0009685,0,0,0,90.00000001 +267.27,50.30085681,-2.907034637,10500,0,199.9998535,0,0,0,90.00000001 +267.28,50.30085681,-2.907006612,10500,0,199.9989614,0,0,0,90.00000001 +267.29,50.30085681,-2.906978587,10500,0,199.9989614,0,0,0,90.00000001 +267.3,50.30085681,-2.906950562,10500,0,199.9998535,0,0,0,90.00000001 +267.31,50.30085681,-2.906922537,10500,0,200.0009685,0,0,0,90.00000001 +267.32,50.30085681,-2.906894511,10500,0,200.0009685,0,0,0,90.00000001 +267.33,50.30085681,-2.906866486,10500,0,199.9998535,0,0,0,90.00000001 +267.34,50.30085681,-2.906838461,10500,0,199.9989614,0,0,0,90.00000001 +267.35,50.30085681,-2.906810436,10500,0,199.9989614,0,0,0,90.00000001 +267.36,50.30085681,-2.906782411,10500,0,199.9998535,0,0,0,90.00000001 +267.37,50.30085681,-2.906754386,10500,0,200.0009685,0,0,0,90.00000001 +267.38,50.30085681,-2.90672636,10500,0,200.0009685,0,0,0,90.00000001 +267.39,50.30085681,-2.906698335,10500,0,199.9998535,0,0,0,90.00000001 +267.4,50.30085681,-2.90667031,10500,0,199.9989614,0,0,0,90.00000001 +267.41,50.30085681,-2.906642285,10500,0,199.9989614,0,0,0,90.00000001 +267.42,50.30085681,-2.90661426,10500,0,199.9998535,0,0,0,90.00000001 +267.43,50.30085681,-2.906586235,10500,0,200.0009685,0,0,0,90.00000001 +267.44,50.30085681,-2.906558209,10500,0,200.0009685,0,0,0,90.00000001 +267.45,50.30085681,-2.906530184,10500,0,199.9998535,0,0,0,90.00000001 +267.46,50.30085681,-2.906502159,10500,0,199.9989614,0,0,0,90.00000001 +267.47,50.30085681,-2.906474134,10500,0,199.9989614,0,0,0,90.00000001 +267.48,50.30085681,-2.906446109,10500,0,199.9998535,0,0,0,90.00000001 +267.49,50.30085681,-2.906418084,10500,0,200.0009685,0,0,0,90.00000001 +267.5,50.30085681,-2.906390058,10500,0,200.0009685,0,0,0,90.00000001 +267.51,50.30085681,-2.906362033,10500,0,199.9998535,0,0,0,90.00000001 +267.52,50.30085681,-2.906334008,10500,0,199.9989614,0,0,0,90.00000001 +267.53,50.30085681,-2.906305983,10500,0,199.9987384,0,0,0,90.00000001 +267.54,50.30085681,-2.906277958,10500,0,199.9989614,0,0,0,90.00000001 +267.55,50.30085681,-2.906249933,10500,0,199.9998535,0,0,0,90.00000001 +267.56,50.30085681,-2.906221908,10500,0,200.0009685,0,0,0,90.00000001 +267.57,50.30085681,-2.906193882,10500,0,200.0009685,0,0,0,90.00000001 +267.58,50.30085681,-2.906165857,10500,0,199.9998535,0,0,0,90.00000001 +267.59,50.30085681,-2.906137832,10500,0,199.9991844,0,0,0,90.00000001 +267.6,50.30085681,-2.906109807,10500,0,199.9998535,0,0,0,90.00000001 +267.61,50.30085681,-2.906081782,10500,0,200.0009685,0,0,0,90.00000001 +267.62,50.30085681,-2.906053756,10500,0,200.0009685,0,0,0,90.00000001 +267.63,50.30085681,-2.906025731,10500,0,199.9998535,0,0,0,90.00000001 +267.64,50.30085681,-2.905997706,10500,0,199.9991844,0,0,0,90.00000001 +267.65,50.30085681,-2.905969681,10500,0,199.9998535,0,0,0,90.00000001 +267.66,50.30085681,-2.905941656,10500,0,200.0009685,0,0,0,90.00000001 +267.67,50.30085681,-2.90591363,10500,0,200.0009685,0,0,0,90.00000001 +267.68,50.30085681,-2.905885605,10500,0,199.9998535,0,0,0,90.00000001 +267.69,50.30085681,-2.90585758,10500,0,199.9991844,0,0,0,90.00000001 +267.7,50.30085681,-2.905829555,10500,0,199.9998535,0,0,0,90.00000001 +267.71,50.30085681,-2.90580153,10500,0,200.0009685,0,0,0,90.00000001 +267.72,50.30085681,-2.905773504,10500,0,200.0009685,0,0,0,90.00000001 +267.73,50.30085681,-2.905745479,10500,0,199.9998535,0,0,0,90.00000001 +267.74,50.30085681,-2.905717454,10500,0,199.9991844,0,0,0,90.00000001 +267.75,50.30085681,-2.905689429,10500,0,199.9998535,0,0,0,90.00000001 +267.76,50.30085681,-2.905661404,10500,0,200.0009685,0,0,0,90.00000001 +267.77,50.30085681,-2.905633378,10500,0,200.0009685,0,0,0,90.00000001 +267.78,50.30085681,-2.905605353,10500,0,199.9998535,0,0,0,90.00000001 +267.79,50.30085681,-2.905577328,10500,0,199.9991844,0,0,0,90.00000001 +267.8,50.30085681,-2.905549303,10500,0,199.9998535,0,0,0,90.00000001 +267.81,50.30085681,-2.905521278,10500,0,200.0009685,0,0,0,90.00000001 +267.82,50.30085681,-2.905493252,10500,0,200.0009685,0,0,0,90.00000001 +267.83,50.30085681,-2.905465227,10500,0,199.9998535,0,0,0,90.00000001 +267.84,50.30085681,-2.905437202,10500,0,199.9989614,0,0,0,90.00000001 +267.85,50.30085681,-2.905409177,10500,0,199.9989614,0,0,0,90.00000001 +267.86,50.30085681,-2.905381152,10500,0,199.9998535,0,0,0,90.00000001 +267.87,50.30085681,-2.905353127,10500,0,200.0009685,0,0,0,90.00000001 +267.88,50.30085681,-2.905325101,10500,0,200.0009685,0,0,0,90.00000001 +267.89,50.30085681,-2.905297076,10500,0,199.9998535,0,0,0,90.00000001 +267.9,50.30085681,-2.905269051,10500,0,199.9989614,0,0,0,90.00000001 +267.91,50.30085681,-2.905241026,10500,0,199.9989614,0,0,0,90.00000001 +267.92,50.30085681,-2.905213001,10500,0,199.9998535,0,0,0,90.00000001 +267.93,50.30085681,-2.905184976,10500,0,200.0009685,0,0,0,90.00000001 +267.94,50.30085681,-2.90515695,10500,0,200.0009685,0,0,0,90.00000001 +267.95,50.30085681,-2.905128925,10500,0,199.9998535,0,0,0,90.00000001 +267.96,50.30085681,-2.9051009,10500,0,199.9989614,0,0,0,90.00000001 +267.97,50.30085681,-2.905072875,10500,0,199.9989614,0,0,0,90.00000001 +267.98,50.30085681,-2.90504485,10500,0,199.9998535,0,0,0,90.00000001 +267.99,50.30085681,-2.905016825,10500,0,200.0009685,0,0,0,90.00000001 +268,50.30085681,-2.904988799,10500,0,200.0009685,0,0,0,90.00000001 +268.01,50.30085681,-2.904960774,10500,0,199.9998535,0,0,0,90.00000001 +268.02,50.30085681,-2.904932749,10500,0,199.9989614,0,0,0,90.00000001 +268.03,50.30085681,-2.904904724,10500,0,199.9989614,0,0,0,90.00000001 +268.04,50.30085681,-2.904876699,10500,0,199.9998535,0,0,0,90.00000001 +268.05,50.30085681,-2.904848674,10500,0,200.0009685,0,0,0,90.00000001 +268.06,50.30085681,-2.904820648,10500,0,200.0009685,0,0,0,90.00000001 +268.07,50.30085681,-2.904792623,10500,0,199.9998535,0,0,0,90.00000001 +268.08,50.30085681,-2.904764598,10500,0,199.9989614,0,0,0,90.00000001 +268.09,50.30085681,-2.904736573,10500,0,199.9987384,0,0,0,90.00000001 +268.1,50.30085681,-2.904708548,10500,0,199.9989614,0,0,0,90.00000001 +268.11,50.30085681,-2.904680523,10500,0,199.9998535,0,0,0,90.00000001 +268.12,50.30085681,-2.904652498,10500,0,200.0009685,0,0,0,90.00000001 +268.13,50.30085681,-2.904624472,10500,0,200.0009685,0,0,0,90.00000001 +268.14,50.30085681,-2.904596447,10500,0,199.9998535,0,0,0,90.00000001 +268.15,50.30085681,-2.904568422,10500,0,199.9989614,0,0,0,90.00000001 +268.16,50.30085681,-2.904540397,10500,0,199.9989614,0,0,0,90.00000001 +268.17,50.30085681,-2.904512372,10500,0,199.9998535,0,0,0,90.00000001 +268.18,50.30085681,-2.904484347,10500,0,200.0009685,0,0,0,90.00000001 +268.19,50.30085681,-2.904456321,10500,0,200.0009685,0,0,0,90.00000001 +268.2,50.30085681,-2.904428296,10500,0,199.9998535,0,0,0,90.00000001 +268.21,50.30085681,-2.904400271,10500,0,199.9991844,0,0,0,90.00000001 +268.22,50.30085681,-2.904372246,10500,0,199.9998535,0,0,0,90.00000001 +268.23,50.30085681,-2.904344221,10500,0,200.0009685,0,0,0,90.00000001 +268.24,50.30085681,-2.904316195,10500,0,200.0009685,0,0,0,90.00000001 +268.25,50.30085681,-2.90428817,10500,0,199.9998535,0,0,0,90.00000001 +268.26,50.30085681,-2.904260145,10500,0,199.9991844,0,0,0,90.00000001 +268.27,50.30085681,-2.90423212,10500,0,199.9998535,0,0,0,90.00000001 +268.28,50.30085681,-2.904204095,10500,0,200.0009685,0,0,0,90.00000001 +268.29,50.30085681,-2.904176069,10500,0,200.0009685,0,0,0,90.00000001 +268.3,50.30085681,-2.904148044,10500,0,199.9998535,0,0,0,90.00000001 +268.31,50.30085681,-2.904120019,10500,0,199.9991844,0,0,0,90.00000001 +268.32,50.30085681,-2.904091994,10500,0,199.9998535,0,0,0,90.00000001 +268.33,50.30085681,-2.904063969,10500,0,200.0009685,0,0,0,90.00000001 +268.34,50.30085681,-2.904035943,10500,0,200.0009685,0,0,0,90.00000001 +268.35,50.30085681,-2.904007918,10500,0,199.9998535,0,0,0,90.00000001 +268.36,50.30085681,-2.903979893,10500,0,199.9991844,0,0,0,90.00000001 +268.37,50.30085681,-2.903951868,10500,0,199.9998535,0,0,0,90.00000001 +268.38,50.30085681,-2.903923843,10500,0,200.0009685,0,0,0,90.00000001 +268.39,50.30085681,-2.903895817,10500,0,200.0009685,0,0,0,90.00000001 +268.4,50.30085681,-2.903867792,10500,0,199.9998535,0,0,0,90.00000001 +268.41,50.30085681,-2.903839767,10500,0,199.9991844,0,0,0,90.00000001 +268.42,50.30085681,-2.903811742,10500,0,199.9998535,0,0,0,90.00000001 +268.43,50.30085681,-2.903783717,10500,0,200.0009685,0,0,0,90.00000001 +268.44,50.30085681,-2.903755691,10500,0,200.0009685,0,0,0,90.00000001 +268.45,50.30085681,-2.903727666,10500,0,199.9998535,0,0,0,90.00000001 +268.46,50.30085681,-2.903699641,10500,0,199.9989614,0,0,0,90.00000001 +268.47,50.30085681,-2.903671616,10500,0,199.9989614,0,0,0,90.00000001 +268.48,50.30085681,-2.903643591,10500,0,199.9998535,0,0,0,90.00000001 +268.49,50.30085681,-2.903615566,10500,0,200.0009685,0,0,0,90.00000001 +268.5,50.30085681,-2.90358754,10500,0,200.0009685,0,0,0,90.00000001 +268.51,50.30085681,-2.903559515,10500,0,199.9998535,0,0,0,90.00000001 +268.52,50.30085681,-2.90353149,10500,0,199.9989614,0,0,0,90.00000001 +268.53,50.30085681,-2.903503465,10500,0,199.9989614,0,0,0,90.00000001 +268.54,50.30085681,-2.90347544,10500,0,199.9998535,0,0,0,90.00000001 +268.55,50.30085681,-2.903447415,10500,0,200.0009685,0,0,0,90.00000001 +268.56,50.30085681,-2.903419389,10500,0,200.0009685,0,0,0,90.00000001 +268.57,50.30085681,-2.903391364,10500,0,199.9998535,0,0,0,90.00000001 +268.58,50.30085681,-2.903363339,10500,0,199.9989614,0,0,0,90.00000001 +268.59,50.30085681,-2.903335314,10500,0,199.9989614,0,0,0,90.00000001 +268.6,50.30085681,-2.903307289,10500,0,199.9998535,0,0,0,90.00000001 +268.61,50.30085681,-2.903279264,10500,0,200.0009685,0,0,0,90.00000001 +268.62,50.30085681,-2.903251238,10500,0,200.0009685,0,0,0,90.00000001 +268.63,50.30085681,-2.903223213,10500,0,199.9998535,0,0,0,90.00000001 +268.64,50.30085681,-2.903195188,10500,0,199.9989614,0,0,0,90.00000001 +268.65,50.30085681,-2.903167163,10500,0,199.9987384,0,0,0,90.00000001 +268.66,50.30085681,-2.903139138,10500,0,199.9989614,0,0,0,90.00000001 +268.67,50.30085681,-2.903111113,10500,0,199.9998535,0,0,0,90.00000001 +268.68,50.30085681,-2.903083088,10500,0,200.0009685,0,0,0,90.00000001 +268.69,50.30085681,-2.903055062,10500,0,200.0009685,0,0,0,90.00000001 +268.7,50.30085681,-2.903027037,10500,0,199.9998535,0,0,0,90.00000001 +268.71,50.30085681,-2.902999012,10500,0,199.9989614,0,0,0,90.00000001 +268.72,50.30085681,-2.902970987,10500,0,199.9989614,0,0,0,90.00000001 +268.73,50.30085681,-2.902942962,10500,0,199.9998535,0,0,0,90.00000001 +268.74,50.30085681,-2.902914937,10500,0,200.0009685,0,0,0,90.00000001 +268.75,50.30085681,-2.902886911,10500,0,200.0009685,0,0,0,90.00000001 +268.76,50.30085681,-2.902858886,10500,0,199.9998535,0,0,0,90.00000001 +268.77,50.30085681,-2.902830861,10500,0,199.9989614,0,0,0,90.00000001 +268.78,50.30085681,-2.902802836,10500,0,199.9989614,0,0,0,90.00000001 +268.79,50.30085681,-2.902774811,10500,0,199.9998535,0,0,0,90.00000001 +268.8,50.30085681,-2.902746786,10500,0,200.0009685,0,0,0,90.00000001 +268.81,50.30085681,-2.90271876,10500,0,200.0009685,0,0,0,90.00000001 +268.82,50.30085681,-2.902690735,10500,0,199.9998535,0,0,0,90.00000001 +268.83,50.30085681,-2.90266271,10500,0,199.9991844,0,0,0,90.00000001 +268.84,50.30085681,-2.902634685,10500,0,199.9998535,0,0,0,90.00000001 +268.85,50.30085681,-2.90260666,10500,0,200.0009685,0,0,0,90.00000001 +268.86,50.30085681,-2.902578634,10500,0,200.0009685,0,0,0,90.00000001 +268.87,50.30085681,-2.902550609,10500,0,199.9998535,0,0,0,90.00000001 +268.88,50.30085681,-2.902522584,10500,0,199.9989614,0,0,0,90.00000001 +268.89,50.30085681,-2.902494559,10500,0,199.9989614,0,0,0,90.00000001 +268.9,50.30085681,-2.902466534,10500,0,199.9998535,0,0,0,90.00000001 +268.91,50.30085681,-2.902438509,10500,0,200.0009685,0,0,0,90.00000001 +268.92,50.30085681,-2.902410483,10500,0,200.0009685,0,0,0,90.00000001 +268.93,50.30085681,-2.902382458,10500,0,199.9998535,0,0,0,90.00000001 +268.94,50.30085681,-2.902354433,10500,0,199.9991844,0,0,0,90.00000001 +268.95,50.30085681,-2.902326408,10500,0,199.9998535,0,0,0,90.00000001 +268.96,50.30085681,-2.902298383,10500,0,200.0009685,0,0,0,90.00000001 +268.97,50.30085681,-2.902270357,10500,0,200.0009685,0,0,0,90.00000001 +268.98,50.30085681,-2.902242332,10500,0,199.9998535,0,0,0,90.00000001 +268.99,50.30085681,-2.902214307,10500,0,199.9991844,0,0,0,90.00000001 +269,50.30085681,-2.902186282,10500,0,199.9998535,0,0,0,90.00000001 +269.01,50.30085681,-2.902158257,10500,0,200.0009685,0,0,0,90.00000001 +269.02,50.30085681,-2.902130231,10500,0,200.0009685,0,0,0,90.00000001 +269.03,50.30085681,-2.902102206,10500,0,199.9998535,0,0,0,90.00000001 +269.04,50.30085681,-2.902074181,10500,0,199.9991844,0,0,0,90.00000001 +269.05,50.30085681,-2.902046156,10500,0,199.9998535,0,0,0,90.00000001 +269.06,50.30085681,-2.902018131,10500,0,200.0009685,0,0,0,90.00000001 +269.07,50.30085681,-2.901990105,10500,0,200.0009685,0,0,0,90.00000001 +269.08,50.30085681,-2.90196208,10500,0,199.9998535,0,0,0,90.00000001 +269.09,50.30085681,-2.901934055,10500,0,199.9991844,0,0,0,90.00000001 +269.1,50.30085681,-2.90190603,10500,0,199.9998535,0,0,0,90.00000001 +269.11,50.30085681,-2.901878005,10500,0,200.0009685,0,0,0,90.00000001 +269.12,50.30085681,-2.901849979,10500,0,200.0009685,0,0,0,90.00000001 +269.13,50.30085681,-2.901821954,10500,0,199.9998535,0,0,0,90.00000001 +269.14,50.30085681,-2.901793929,10500,0,199.9989614,0,0,0,90.00000001 +269.15,50.30085681,-2.901765904,10500,0,199.9989614,0,0,0,90.00000001 +269.16,50.30085681,-2.901737879,10500,0,199.9998535,0,0,0,90.00000001 +269.17,50.30085681,-2.901709854,10500,0,200.0009685,0,0,0,90.00000001 +269.18,50.30085681,-2.901681828,10500,0,200.0009685,0,0,0,90.00000001 +269.19,50.30085681,-2.901653803,10500,0,199.9998535,0,0,0,90.00000001 +269.2,50.30085681,-2.901625778,10500,0,199.9989614,0,0,0,90.00000001 +269.21,50.30085681,-2.901597753,10500,0,199.9989614,0,0,0,90.00000001 +269.22,50.30085681,-2.901569728,10500,0,199.9998535,0,0,0,90.00000001 +269.23,50.30085681,-2.901541703,10500,0,200.0009685,0,0,0,90.00000001 +269.24,50.30085681,-2.901513677,10500,0,200.0009685,0,0,0,90.00000001 +269.25,50.30085681,-2.901485652,10500,0,199.9998535,0,0,0,90.00000001 +269.26,50.30085681,-2.901457627,10500,0,199.9989614,0,0,0,90.00000001 +269.27,50.30085681,-2.901429602,10500,0,199.9987384,0,0,0,90.00000001 +269.28,50.30085681,-2.901401577,10500,0,199.9989614,0,0,0,90.00000001 +269.29,50.30085681,-2.901373552,10500,0,199.9998535,0,0,0,90.00000001 +269.3,50.30085681,-2.901345527,10500,0,200.0009685,0,0,0,90.00000001 +269.31,50.30085681,-2.901317501,10500,0,200.0009685,0,0,0,90.00000001 +269.32,50.30085681,-2.901289476,10500,0,199.9998535,0,0,0,90.00000001 +269.33,50.30085681,-2.901261451,10500,0,199.9989614,0,0,0,90.00000001 +269.34,50.30085681,-2.901233426,10500,0,199.9989614,0,0,0,90.00000001 +269.35,50.30085681,-2.901205401,10500,0,199.9998535,0,0,0,90.00000001 +269.36,50.30085681,-2.901177376,10500,0,200.0009685,0,0,0,90.00000001 +269.37,50.30085681,-2.90114935,10500,0,200.0009685,0,0,0,90.00000001 +269.38,50.30085681,-2.901121325,10500,0,199.9998535,0,0,0,90.00000001 +269.39,50.30085681,-2.9010933,10500,0,199.9989614,0,0,0,90.00000001 +269.4,50.30085681,-2.901065275,10500,0,199.9989614,0,0,0,90.00000001 +269.41,50.30085681,-2.90103725,10500,0,199.9998535,0,0,0,90.00000001 +269.42,50.30085681,-2.901009225,10500,0,200.0009685,0,0,0,90.00000001 +269.43,50.30085681,-2.900981199,10500,0,200.0009685,0,0,0,90.00000001 +269.44,50.30085681,-2.900953174,10500,0,199.9998535,0,0,0,90.00000001 +269.45,50.30085681,-2.900925149,10500,0,199.9989614,0,0,0,90.00000001 +269.46,50.30085681,-2.900897124,10500,0,199.9989614,0,0,0,90.00000001 +269.47,50.30085681,-2.900869099,10500,0,199.9998535,0,0,0,90.00000001 +269.48,50.30085681,-2.900841074,10500,0,200.0009685,0,0,0,90.00000001 +269.49,50.30085681,-2.900813048,10500,0,200.0009685,0,0,0,90.00000001 +269.5,50.30085681,-2.900785023,10500,0,199.9998535,0,0,0,90.00000001 +269.51,50.30085681,-2.900756998,10500,0,199.9991844,0,0,0,90.00000001 +269.52,50.30085681,-2.900728973,10500,0,199.9998535,0,0,0,90.00000001 +269.53,50.30085681,-2.900700948,10500,0,200.0009685,0,0,0,90.00000001 +269.54,50.30085681,-2.900672922,10500,0,200.0009685,0,0,0,90.00000001 +269.55,50.30085681,-2.900644897,10500,0,199.9998535,0,0,0,90.00000001 +269.56,50.30085681,-2.900616872,10500,0,199.9991844,0,0,0,90.00000001 +269.57,50.30085681,-2.900588847,10500,0,199.9998535,0,0,0,90.00000001 +269.58,50.30085681,-2.900560822,10500,0,200.0009685,0,0,0,90.00000001 +269.59,50.30085681,-2.900532796,10500,0,200.0009685,0,0,0,90.00000001 +269.6,50.30085681,-2.900504771,10500,0,199.9998535,0,0,0,90.00000001 +269.61,50.30085681,-2.900476746,10500,0,199.9991844,0,0,0,90.00000001 +269.62,50.30085681,-2.900448721,10500,0,199.9998535,0,0,0,90.00000001 +269.63,50.30085681,-2.900420696,10500,0,200.0009685,0,0,0,90.00000001 +269.64,50.30085681,-2.90039267,10500,0,200.0009685,0,0,0,90.00000001 +269.65,50.30085681,-2.900364645,10500,0,199.9998535,0,0,0,90.00000001 +269.66,50.30085681,-2.90033662,10500,0,199.9991844,0,0,0,90.00000001 +269.67,50.30085681,-2.900308595,10500,0,199.9998535,0,0,0,90.00000001 +269.68,50.30085681,-2.90028057,10500,0,200.0009685,0,0,0,90.00000001 +269.69,50.30085681,-2.900252544,10500,0,200.0009685,0,0,0,90.00000001 +269.7,50.30085681,-2.900224519,10500,0,199.9998535,0,0,0,90.00000001 +269.71,50.30085681,-2.900196494,10500,0,199.9991844,0,0,0,90.00000001 +269.72,50.30085681,-2.900168469,10500,0,199.9998535,0,0,0,90.00000001 +269.73,50.30085681,-2.900140444,10500,0,200.0009685,0,0,0,90.00000001 +269.74,50.30085681,-2.900112418,10500,0,200.0009685,0,0,0,90.00000001 +269.75,50.30085681,-2.900084393,10500,0,199.9998535,0,0,0,90.00000001 +269.76,50.30085681,-2.900056368,10500,0,199.9989614,0,0,0,90.00000001 +269.77,50.30085681,-2.900028343,10500,0,199.9989614,0,0,0,90.00000001 +269.78,50.30085681,-2.900000318,10500,0,199.9998535,0,0,0,90.00000001 +269.79,50.30085681,-2.899972293,10500,0,200.0009685,0,0,0,90.00000001 +269.8,50.30085681,-2.899944267,10500,0,200.0009685,0,0,0,90.00000001 +269.81,50.30085681,-2.899916242,10500,0,199.9998535,0,0,0,90.00000001 +269.82,50.30085681,-2.899888217,10500,0,199.9989614,0,0,0,90.00000001 +269.83,50.30085681,-2.899860192,10500,0,199.9987384,0,0,0,90.00000001 +269.84,50.30085681,-2.899832167,10500,0,199.9989614,0,0,0,90.00000001 +269.85,50.30085681,-2.899804142,10500,0,199.9998535,0,0,0,90.00000001 +269.86,50.30085681,-2.899776117,10500,0,200.0009685,0,0,0,90.00000001 +269.87,50.30085681,-2.899748091,10500,0,200.0009685,0,0,0,90.00000001 +269.88,50.30085681,-2.899720066,10500,0,199.9998535,0,0,0,90.00000001 +269.89,50.30085681,-2.899692041,10500,0,199.9989614,0,0,0,90.00000001 +269.9,50.30085681,-2.899664016,10500,0,199.9989614,0,0,0,90.00000001 +269.91,50.30085681,-2.899635991,10500,0,199.9998535,0,0,0,90.00000001 +269.92,50.30085681,-2.899607966,10500,0,200.0009685,0,0,0,90.00000001 +269.93,50.30085681,-2.89957994,10500,0,200.0009685,0,0,0,90.00000001 +269.94,50.30085681,-2.899551915,10500,0,199.9998535,0,0,0,90.00000001 +269.95,50.30085681,-2.89952389,10500,0,199.9989614,0,0,0,90.00000001 +269.96,50.30085681,-2.899495865,10500,0,199.9989614,0,0,0,90.00000001 +269.97,50.30085681,-2.89946784,10500,0,199.9998535,0,0,0,90.00000001 +269.98,50.30085681,-2.899439815,10500,0,200.0009685,0,0,0,90.00000001 +269.99,50.30085681,-2.899411789,10500,0,200.0009685,0,0,0,90.00000001 +270,50.30085681,-2.899383764,10500,0,199.9998535,0,0,0,90.00000001 +270.01,50.30085681,-2.899355739,10500,0,199.9989614,0,0,0,90.00000001 +270.02,50.30085681,-2.899327714,10500,0,199.9989614,0,0,0,90.00000001 +270.03,50.30085681,-2.899299689,10500,0,199.9998535,0,0,0,90.00000001 +270.04,50.30085681,-2.899271664,10500,0,200.0009685,0,0,0,90.00000001 +270.05,50.30085681,-2.899243638,10500,0,200.0009685,0,0,0,90.00000001 +270.06,50.30085681,-2.899215613,10500,0,199.9998535,0,0,0,90.00000001 +270.07,50.30085681,-2.899187588,10500,0,199.9989614,0,0,0,90.00000001 +270.08,50.30085681,-2.899159563,10500,0,199.9989614,0,0,0,90.00000001 +270.09,50.30085681,-2.899131538,10500,0,199.9998535,0,0,0,90.00000001 +270.1,50.30085681,-2.899103513,10500,0,200.0009685,0,0,0,90.00000001 +270.11,50.30085681,-2.899075487,10500,0,200.0009685,0,0,0,90.00000001 +270.12,50.30085681,-2.899047462,10500,0,199.9998535,0,0,0,90.00000001 +270.13,50.30085681,-2.899019437,10500,0,199.9991844,0,0,0,90.00000001 +270.14,50.30085681,-2.898991412,10500,0,199.9998535,0,0,0,90.00000001 +270.15,50.30085681,-2.898963387,10500,0,200.0009685,0,0,0,90.00000001 +270.16,50.30085681,-2.898935361,10500,0,200.0009685,0,0,0,90.00000001 +270.17,50.30085681,-2.898907336,10500,0,199.9998535,0,0,0,90.00000001 +270.18,50.30085681,-2.898879311,10500,0,199.9991844,0,0,0,90.00000001 +270.19,50.30085681,-2.898851286,10500,0,199.9998535,0,0,0,90.00000001 +270.2,50.30085681,-2.898823261,10500,0,200.0009685,0,0,0,90.00000001 +270.21,50.30085681,-2.898795235,10500,0,200.0009685,0,0,0,90.00000001 +270.22,50.30085681,-2.89876721,10500,0,199.9998535,0,0,0,90.00000001 +270.23,50.30085681,-2.898739185,10500,0,199.9991844,0,0,0,90.00000001 +270.24,50.30085681,-2.89871116,10500,0,199.9998535,0,0,0,90.00000001 +270.25,50.30085681,-2.898683135,10500,0,200.0009685,0,0,0,90.00000001 +270.26,50.30085681,-2.898655109,10500,0,200.0009685,0,0,0,90.00000001 +270.27,50.30085681,-2.898627084,10500,0,199.9998535,0,0,0,90.00000001 +270.28,50.30085681,-2.898599059,10500,0,199.9991844,0,0,0,90.00000001 +270.29,50.30085681,-2.898571034,10500,0,199.9998535,0,0,0,90.00000001 +270.3,50.30085681,-2.898543009,10500,0,200.0009685,0,0,0,90.00000001 +270.31,50.30085681,-2.898514983,10500,0,200.0009685,0,0,0,90.00000001 +270.32,50.30085681,-2.898486958,10500,0,199.9998535,0,0,0,90.00000001 +270.33,50.30085681,-2.898458933,10500,0,199.9991844,0,0,0,90.00000001 +270.34,50.30085681,-2.898430908,10500,0,199.9998535,0,0,0,90.00000001 +270.35,50.30085681,-2.898402883,10500,0,200.0009685,0,0,0,90.00000001 +270.36,50.30085681,-2.898374857,10500,0,200.0009685,0,0,0,90.00000001 +270.37,50.30085681,-2.898346832,10500,0,199.9998535,0,0,0,90.00000001 +270.38,50.30085681,-2.898318807,10500,0,199.9989614,0,0,0,90.00000001 +270.39,50.30085681,-2.898290782,10500,0,199.9987384,0,0,0,90.00000001 +270.4,50.30085681,-2.898262757,10500,0,199.9989614,0,0,0,90.00000001 +270.41,50.30085681,-2.898234732,10500,0,199.9998535,0,0,0,90.00000001 +270.42,50.30085681,-2.898206707,10500,0,200.0009685,0,0,0,90.00000001 +270.43,50.30085681,-2.898178681,10500,0,200.0009685,0,0,0,90.00000001 +270.44,50.30085681,-2.898150656,10500,0,199.9998535,0,0,0,90.00000001 +270.45,50.30085681,-2.898122631,10500,0,199.9989614,0,0,0,90.00000001 +270.46,50.30085681,-2.898094606,10500,0,199.9989614,0,0,0,90.00000001 +270.47,50.30085681,-2.898066581,10500,0,199.9998535,0,0,0,90.00000001 +270.48,50.30085681,-2.898038556,10500,0,200.0009685,0,0,0,90.00000001 +270.49,50.30085681,-2.89801053,10500,0,200.0009685,0,0,0,90.00000001 +270.5,50.30085681,-2.897982505,10500,0,199.9998535,0,0,0,90.00000001 +270.51,50.30085681,-2.89795448,10500,0,199.9989614,0,0,0,90.00000001 +270.52,50.30085681,-2.897926455,10500,0,199.9989614,0,0,0,90.00000001 +270.53,50.30085681,-2.89789843,10500,0,199.9998535,0,0,0,90.00000001 +270.54,50.30085681,-2.897870405,10500,0,200.0009685,0,0,0,90.00000001 +270.55,50.30085681,-2.897842379,10500,0,200.0009685,0,0,0,90.00000001 +270.56,50.30085681,-2.897814354,10500,0,199.9998535,0,0,0,90.00000001 +270.57,50.30085681,-2.897786329,10500,0,199.9989614,0,0,0,90.00000001 +270.58,50.30085681,-2.897758304,10500,0,199.9989614,0,0,0,90.00000001 +270.59,50.30085681,-2.897730279,10500,0,199.9998535,0,0,0,90.00000001 +270.6,50.30085681,-2.897702254,10500,0,200.0009685,0,0,0,90.00000001 +270.61,50.30085681,-2.897674228,10500,0,200.0009685,0,0,0,90.00000001 +270.62,50.30085681,-2.897646203,10500,0,199.9998535,0,0,0,90.00000001 +270.63,50.30085681,-2.897618178,10500,0,199.9989614,0,0,0,90.00000001 +270.64,50.30085681,-2.897590153,10500,0,199.9989614,0,0,0,90.00000001 +270.65,50.30085681,-2.897562128,10500,0,199.9998535,0,0,0,90.00000001 +270.66,50.30085681,-2.897534103,10500,0,200.0009685,0,0,0,90.00000001 +270.67,50.30085681,-2.897506077,10500,0,200.0009685,0,0,0,90.00000001 +270.68,50.30085681,-2.897478052,10500,0,199.9998535,0,0,0,90.00000001 +270.69,50.30085681,-2.897450027,10500,0,199.9989614,0,0,0,90.00000001 +270.7,50.30085681,-2.897422002,10500,0,199.9989614,0,0,0,90.00000001 +270.71,50.30085681,-2.897393977,10500,0,199.9998535,0,0,0,90.00000001 +270.72,50.30085681,-2.897365952,10500,0,200.0009685,0,0,0,90.00000001 +270.73,50.30085681,-2.897337926,10500,0,200.0009685,0,0,0,90.00000001 +270.74,50.30085681,-2.897309901,10500,0,199.9998535,0,0,0,90.00000001 +270.75,50.30085681,-2.897281876,10500,0,199.9991844,0,0,0,90.00000001 +270.76,50.30085681,-2.897253851,10500,0,199.9998535,0,0,0,90.00000001 +270.77,50.30085681,-2.897225826,10500,0,200.0009685,0,0,0,90.00000001 +270.78,50.30085681,-2.8971978,10500,0,200.0009685,0,0,0,90.00000001 +270.79,50.30085681,-2.897169775,10500,0,199.9998535,0,0,0,90.00000001 +270.8,50.30085681,-2.89714175,10500,0,199.9991844,0,0,0,90.00000001 +270.81,50.30085681,-2.897113725,10500,0,199.9998535,0,0,0,90.00000001 +270.82,50.30085681,-2.8970857,10500,0,200.0009685,0,0,0,90.00000001 +270.83,50.30085681,-2.897057674,10500,0,200.0009685,0,0,0,90.00000001 +270.84,50.30085681,-2.897029649,10500,0,199.9998535,0,0,0,90.00000001 +270.85,50.30085681,-2.897001624,10500,0,199.9991844,0,0,0,90.00000001 +270.86,50.30085681,-2.896973599,10500,0,199.9998535,0,0,0,90.00000001 +270.87,50.30085681,-2.896945574,10500,0,200.0009685,0,0,0,90.00000001 +270.88,50.30085681,-2.896917548,10500,0,200.0009685,0,0,0,90.00000001 +270.89,50.30085681,-2.896889523,10500,0,199.9998535,0,0,0,90.00000001 +270.9,50.30085681,-2.896861498,10500,0,199.9991844,0,0,0,90.00000001 +270.91,50.30085681,-2.896833473,10500,0,199.9998535,0,0,0,90.00000001 +270.92,50.30085681,-2.896805448,10500,0,200.0009685,0,0,0,90.00000001 +270.93,50.30085681,-2.896777422,10500,0,200.0009685,0,0,0,90.00000001 +270.94,50.30085681,-2.896749397,10500,0,199.9998535,0,0,0,90.00000001 +270.95,50.30085681,-2.896721372,10500,0,199.9989614,0,0,0,90.00000001 +270.96,50.30085681,-2.896693347,10500,0,199.9989614,0,0,0,90.00000001 +270.97,50.30085681,-2.896665322,10500,0,199.9998535,0,0,0,90.00000001 +270.98,50.30085681,-2.896637297,10500,0,200.0009685,0,0,0,90.00000001 +270.99,50.30085681,-2.896609271,10500,0,200.0009685,0,0,0,90.00000001 +271,50.30085681,-2.896581246,10500,0,199.9998535,0,0,0,90.00000001 +271.01,50.30085681,-2.896553221,10500,0,199.9989614,0,0,0,90.00000001 +271.02,50.30085681,-2.896525196,10500,0,199.9989614,0,0,0,90.00000001 +271.03,50.30085681,-2.896497171,10500,0,199.9998535,0,0,0,90.00000001 +271.04,50.30085681,-2.896469146,10500,0,200.0009685,0,0,0,90.00000001 +271.05,50.30085681,-2.89644112,10500,0,200.0009685,0,0,0,90.00000001 +271.06,50.30085681,-2.896413095,10500,0,199.9998535,0,0,0,90.00000001 +271.07,50.30085681,-2.89638507,10500,0,199.9989614,0,0,0,90.00000001 +271.08,50.30085681,-2.896357045,10500,0,199.9989614,0,0,0,90.00000001 +271.09,50.30085681,-2.89632902,10500,0,199.9998535,0,0,0,90.00000001 +271.1,50.30085681,-2.896300995,10500,0,200.0009685,0,0,0,90.00000001 +271.11,50.30085681,-2.896272969,10500,0,200.0009685,0,0,0,90.00000001 +271.12,50.30085681,-2.896244944,10500,0,199.9998535,0,0,0,90.00000001 +271.13,50.30085681,-2.896216919,10500,0,199.9989614,0,0,0,90.00000001 +271.14,50.30085681,-2.896188894,10500,0,199.9989614,0,0,0,90.00000001 +271.15,50.30085681,-2.896160869,10500,0,199.9998535,0,0,0,90.00000001 +271.16,50.30085681,-2.896132844,10500,0,200.0009685,0,0,0,90.00000001 +271.17,50.30085681,-2.896104818,10500,0,200.0009685,0,0,0,90.00000001 +271.18,50.30085681,-2.896076793,10500,0,199.9998535,0,0,0,90.00000001 +271.19,50.30085681,-2.896048768,10500,0,199.9989614,0,0,0,90.00000001 +271.2,50.30085681,-2.896020743,10500,0,199.9989614,0,0,0,90.00000001 +271.21,50.30085681,-2.895992718,10500,0,199.9998535,0,0,0,90.00000001 +271.22,50.30085681,-2.895964693,10500,0,200.0009685,0,0,0,90.00000001 +271.23,50.30085681,-2.895936667,10500,0,200.0009685,0,0,0,90.00000001 +271.24,50.30085681,-2.895908642,10500,0,199.9998535,0,0,0,90.00000001 +271.25,50.30085681,-2.895880617,10500,0,199.9989614,0,0,0,90.00000001 +271.26,50.30085681,-2.895852592,10500,0,199.9987384,0,0,0,90.00000001 +271.27,50.30085681,-2.895824567,10500,0,199.9989614,0,0,0,90.00000001 +271.28,50.30085681,-2.895796542,10500,0,199.9998535,0,0,0,90.00000001 +271.29,50.30085681,-2.895768517,10500,0,200.0009685,0,0,0,90.00000001 +271.3,50.30085681,-2.895740491,10500,0,200.0009685,0,0,0,90.00000001 +271.31,50.30085681,-2.895712466,10500,0,199.9998535,0,0,0,90.00000001 +271.32,50.30085681,-2.895684441,10500,0,199.9989614,0,0,0,90.00000001 +271.33,50.30085681,-2.895656416,10500,0,199.9989614,0,0,0,90.00000001 +271.34,50.30085681,-2.895628391,10500,0,199.9998535,0,0,0,90.00000001 +271.35,50.30085681,-2.895600366,10500,0,200.0009685,0,0,0,90.00000001 +271.36,50.30085681,-2.89557234,10500,0,200.0009685,0,0,0,90.00000001 +271.37,50.30085681,-2.895544315,10500,0,199.9998535,0,0,0,90.00000001 +271.38,50.30085681,-2.89551629,10500,0,199.9991844,0,0,0,90.00000001 +271.39,50.30085681,-2.895488265,10500,0,199.9998535,0,0,0,90.00000001 +271.4,50.30085681,-2.89546024,10500,0,200.0009685,0,0,0,90.00000001 +271.41,50.30085681,-2.895432214,10500,0,200.0009685,0,0,0,90.00000001 +271.42,50.30085681,-2.895404189,10500,0,199.9998535,0,0,0,90.00000001 +271.43,50.30085681,-2.895376164,10500,0,199.9991844,0,0,0,90.00000001 +271.44,50.30085681,-2.895348139,10500,0,199.9998535,0,0,0,90.00000001 +271.45,50.30085681,-2.895320114,10500,0,200.0009685,0,0,0,90.00000001 +271.46,50.30085681,-2.895292088,10500,0,200.0009685,0,0,0,90.00000001 +271.47,50.30085681,-2.895264063,10500,0,199.9998535,0,0,0,90.00000001 +271.48,50.30085681,-2.895236038,10500,0,199.9991844,0,0,0,90.00000001 +271.49,50.30085681,-2.895208013,10500,0,199.9998535,0,0,0,90.00000001 +271.5,50.30085681,-2.895179988,10500,0,200.0009685,0,0,0,90.00000001 +271.51,50.30085681,-2.895151962,10500,0,200.0009685,0,0,0,90.00000001 +271.52,50.30085681,-2.895123937,10500,0,199.9998535,0,0,0,90.00000001 +271.53,50.30085681,-2.895095912,10500,0,199.9991844,0,0,0,90.00000001 +271.54,50.30085681,-2.895067887,10500,0,199.9998535,0,0,0,90.00000001 +271.55,50.30085681,-2.895039862,10500,0,200.0009685,0,0,0,90.00000001 +271.56,50.30085681,-2.895011836,10500,0,200.0009685,0,0,0,90.00000001 +271.57,50.30085681,-2.894983811,10500,0,199.9998535,0,0,0,90.00000001 +271.58,50.30085681,-2.894955786,10500,0,199.9991844,0,0,0,90.00000001 +271.59,50.30085681,-2.894927761,10500,0,199.9998535,0,0,0,90.00000001 +271.6,50.30085681,-2.894899736,10500,0,200.0009685,0,0,0,90.00000001 +271.61,50.30085681,-2.89487171,10500,0,200.0009685,0,0,0,90.00000001 +271.62,50.30085681,-2.894843685,10500,0,199.9998535,0,0,0,90.00000001 +271.63,50.30085681,-2.89481566,10500,0,199.9989614,0,0,0,90.00000001 +271.64,50.30085681,-2.894787635,10500,0,199.9989614,0,0,0,90.00000001 +271.65,50.30085681,-2.89475961,10500,0,199.9998535,0,0,0,90.00000001 +271.66,50.30085681,-2.894731585,10500,0,200.0009685,0,0,0,90.00000001 +271.67,50.30085681,-2.894703559,10500,0,200.0009685,0,0,0,90.00000001 +271.68,50.30085681,-2.894675534,10500,0,199.9998535,0,0,0,90.00000001 +271.69,50.30085681,-2.894647509,10500,0,199.9989614,0,0,0,90.00000001 +271.7,50.30085681,-2.894619484,10500,0,199.9989614,0,0,0,90.00000001 +271.71,50.30085681,-2.894591459,10500,0,199.9998535,0,0,0,90.00000001 +271.72,50.30085681,-2.894563434,10500,0,200.0009685,0,0,0,90.00000001 +271.73,50.30085681,-2.894535408,10500,0,200.0009685,0,0,0,90.00000001 +271.74,50.30085681,-2.894507383,10500,0,199.9998535,0,0,0,90.00000001 +271.75,50.30085681,-2.894479358,10500,0,199.9989614,0,0,0,90.00000001 +271.76,50.30085681,-2.894451333,10500,0,199.9989614,0,0,0,90.00000001 +271.77,50.30085681,-2.894423308,10500,0,199.9998535,0,0,0,90.00000001 +271.78,50.30085681,-2.894395283,10500,0,200.0009685,0,0,0,90.00000001 +271.79,50.30085681,-2.894367257,10500,0,200.0009685,0,0,0,90.00000001 +271.8,50.30085681,-2.894339232,10500,0,199.9998535,0,0,0,90.00000001 +271.81,50.30085681,-2.894311207,10500,0,199.9989614,0,0,0,90.00000001 +271.82,50.30085681,-2.894283182,10500,0,199.9987384,0,0,0,90.00000001 +271.83,50.30085681,-2.894255157,10500,0,199.9989614,0,0,0,90.00000001 +271.84,50.30085681,-2.894227132,10500,0,199.9998535,0,0,0,90.00000001 +271.85,50.30085681,-2.894199107,10500,0,200.0009685,0,0,0,90.00000001 +271.86,50.30085681,-2.894171081,10500,0,200.0009685,0,0,0,90.00000001 +271.87,50.30085681,-2.894143056,10500,0,199.9998535,0,0,0,90.00000001 +271.88,50.30085681,-2.894115031,10500,0,199.9989614,0,0,0,90.00000001 +271.89,50.30085681,-2.894087006,10500,0,199.9989614,0,0,0,90.00000001 +271.9,50.30085681,-2.894058981,10500,0,199.9998535,0,0,0,90.00000001 +271.91,50.30085681,-2.894030956,10500,0,200.0009685,0,0,0,90.00000001 +271.92,50.30085681,-2.89400293,10500,0,200.0009685,0,0,0,90.00000001 +271.93,50.30085681,-2.893974905,10500,0,199.9998535,0,0,0,90.00000001 +271.94,50.30085681,-2.89394688,10500,0,199.9989614,0,0,0,90.00000001 +271.95,50.30085681,-2.893918855,10500,0,199.9989614,0,0,0,90.00000001 +271.96,50.30085681,-2.89389083,10500,0,199.9998535,0,0,0,90.00000001 +271.97,50.30085681,-2.893862805,10500,0,200.0009685,0,0,0,90.00000001 +271.98,50.30085681,-2.893834779,10500,0,200.0009685,0,0,0,90.00000001 +271.99,50.30085681,-2.893806754,10500,0,199.9998535,0,0,0,90.00000001 +272,50.30085681,-2.893778729,10500,0,199.9991844,0,0,0,90.00000001 +272.01,50.30085681,-2.893750704,10500,0,199.9998535,0,0,0,90.00000001 +272.02,50.30085681,-2.893722679,10500,0,200.0009685,0,0,0,90.00000001 +272.03,50.30085681,-2.893694653,10500,0,200.0009685,0,0,0,90.00000001 +272.04,50.30085681,-2.893666628,10500,0,199.9998535,0,0,0,90.00000001 +272.05,50.30085681,-2.893638603,10500,0,199.9991844,0,0,0,90.00000001 +272.06,50.30085681,-2.893610578,10500,0,199.9998535,0,0,0,90.00000001 +272.07,50.30085681,-2.893582553,10500,0,200.0009685,0,0,0,90.00000001 +272.08,50.30085681,-2.893554527,10500,0,200.0009685,0,0,0,90.00000001 +272.09,50.30085681,-2.893526502,10500,0,199.9998535,0,0,0,90.00000001 +272.1,50.30085681,-2.893498477,10500,0,199.9991844,0,0,0,90.00000001 +272.11,50.30085681,-2.893470452,10500,0,199.9998535,0,0,0,90.00000001 +272.12,50.30085681,-2.893442427,10500,0,200.0009685,0,0,0,90.00000001 +272.13,50.30085681,-2.893414401,10500,0,200.0009685,0,0,0,90.00000001 +272.14,50.30085681,-2.893386376,10500,0,199.9998535,0,0,0,90.00000001 +272.15,50.30085681,-2.893358351,10500,0,199.9991844,0,0,0,90.00000001 +272.16,50.30085681,-2.893330326,10500,0,199.9998535,0,0,0,90.00000001 +272.17,50.30085681,-2.893302301,10500,0,200.0009685,0,0,0,90.00000001 +272.18,50.30085681,-2.893274275,10500,0,200.0009685,0,0,0,90.00000001 +272.19,50.30085681,-2.89324625,10500,0,199.9998535,0,0,0,90.00000001 +272.2,50.30085681,-2.893218225,10500,0,199.9991844,0,0,0,90.00000001 +272.21,50.30085681,-2.8931902,10500,0,199.9998535,0,0,0,90.00000001 +272.22,50.30085681,-2.893162175,10500,0,200.0009685,0,0,0,90.00000001 +272.23,50.30085681,-2.893134149,10500,0,200.0009685,0,0,0,90.00000001 +272.24,50.30085681,-2.893106124,10500,0,199.9998535,0,0,0,90.00000001 +272.25,50.30085681,-2.893078099,10500,0,199.9989614,0,0,0,90.00000001 +272.26,50.30085681,-2.893050074,10500,0,199.9989614,0,0,0,90.00000001 +272.27,50.30085681,-2.893022049,10500,0,199.9998535,0,0,0,90.00000001 +272.28,50.30085681,-2.892994024,10500,0,200.0009685,0,0,0,90.00000001 +272.29,50.30085681,-2.892965998,10500,0,200.0009685,0,0,0,90.00000001 +272.3,50.30085681,-2.892937973,10500,0,199.9998535,0,0,0,90.00000001 +272.31,50.30085681,-2.892909948,10500,0,199.9989614,0,0,0,90.00000001 +272.32,50.30085681,-2.892881923,10500,0,199.9989614,0,0,0,90.00000001 +272.33,50.30085681,-2.892853898,10500,0,199.9998535,0,0,0,90.00000001 +272.34,50.30085681,-2.892825873,10500,0,200.0009685,0,0,0,90.00000001 +272.35,50.30085681,-2.892797847,10500,0,200.0009685,0,0,0,90.00000001 +272.36,50.30085681,-2.892769822,10500,0,199.9998535,0,0,0,90.00000001 +272.37,50.30085681,-2.892741797,10500,0,199.9989614,0,0,0,90.00000001 +272.38,50.30085681,-2.892713772,10500,0,199.9987384,0,0,0,90.00000001 +272.39,50.30085681,-2.892685747,10500,0,199.9989614,0,0,0,90.00000001 +272.4,50.30085681,-2.892657722,10500,0,199.9998535,0,0,0,90.00000001 +272.41,50.30085681,-2.892629697,10500,0,200.0009685,0,0,0,90.00000001 +272.42,50.30085681,-2.892601671,10500,0,200.0009685,0,0,0,90.00000001 +272.43,50.30085681,-2.892573646,10500,0,199.9998535,0,0,0,90.00000001 +272.44,50.30085681,-2.892545621,10500,0,199.9989614,0,0,0,90.00000001 +272.45,50.30085681,-2.892517596,10500,0,199.9989614,0,0,0,90.00000001 +272.46,50.30085681,-2.892489571,10500,0,199.9998535,0,0,0,90.00000001 +272.47,50.30085681,-2.892461546,10500,0,200.0009685,0,0,0,90.00000001 +272.48,50.30085681,-2.89243352,10500,0,200.0009685,0,0,0,90.00000001 +272.49,50.30085681,-2.892405495,10500,0,199.9998535,0,0,0,90.00000001 +272.5,50.30085681,-2.89237747,10500,0,199.9989614,0,0,0,90.00000001 +272.51,50.30085681,-2.892349445,10500,0,199.9989614,0,0,0,90.00000001 +272.52,50.30085681,-2.89232142,10500,0,199.9998535,0,0,0,90.00000001 +272.53,50.30085681,-2.892293395,10500,0,200.0009685,0,0,0,90.00000001 +272.54,50.30085681,-2.892265369,10500,0,200.0009685,0,0,0,90.00000001 +272.55,50.30085681,-2.892237344,10500,0,199.9998535,0,0,0,90.00000001 +272.56,50.30085681,-2.892209319,10500,0,199.9989614,0,0,0,90.00000001 +272.57,50.30085681,-2.892181294,10500,0,199.9989614,0,0,0,90.00000001 +272.58,50.30085681,-2.892153269,10500,0,199.9998535,0,0,0,90.00000001 +272.59,50.30085681,-2.892125244,10500,0,200.0009685,0,0,0,90.00000001 +272.6,50.30085681,-2.892097218,10500,0,200.0009685,0,0,0,90.00000001 +272.61,50.30085681,-2.892069193,10500,0,199.9998535,0,0,0,90.00000001 +272.62,50.30085681,-2.892041168,10500,0,199.9991844,0,0,0,90.00000001 +272.63,50.30085681,-2.892013143,10500,0,199.9998535,0,0,0,90.00000001 +272.64,50.30085681,-2.891985118,10500,0,200.0009685,0,0,0,90.00000001 +272.65,50.30085681,-2.891957092,10500,0,200.0009685,0,0,0,90.00000001 +272.66,50.30085681,-2.891929067,10500,0,199.9998535,0,0,0,90.00000001 +272.67,50.30085681,-2.891901042,10500,0,199.9991844,0,0,0,90.00000001 +272.68,50.30085681,-2.891873017,10500,0,199.9998535,0,0,0,90.00000001 +272.69,50.30085681,-2.891844992,10500,0,200.0009685,0,0,0,90.00000001 +272.7,50.30085681,-2.891816966,10500,0,200.0009685,0,0,0,90.00000001 +272.71,50.30085681,-2.891788941,10500,0,199.9998535,0,0,0,90.00000001 +272.72,50.30085681,-2.891760916,10500,0,199.9991844,0,0,0,90.00000001 +272.73,50.30085681,-2.891732891,10500,0,199.9998535,0,0,0,90.00000001 +272.74,50.30085681,-2.891704866,10500,0,200.0009685,0,0,0,90.00000001 +272.75,50.30085681,-2.89167684,10500,0,200.0009685,0,0,0,90.00000001 +272.76,50.30085681,-2.891648815,10500,0,199.9998535,0,0,0,90.00000001 +272.77,50.30085681,-2.89162079,10500,0,199.9991844,0,0,0,90.00000001 +272.78,50.30085681,-2.891592765,10500,0,199.9998535,0,0,0,90.00000001 +272.79,50.30085681,-2.89156474,10500,0,200.0009685,0,0,0,90.00000001 +272.8,50.30085681,-2.891536714,10500,0,200.0009685,0,0,0,90.00000001 +272.81,50.30085681,-2.891508689,10500,0,199.9998535,0,0,0,90.00000001 +272.82,50.30085681,-2.891480664,10500,0,199.9991844,0,0,0,90.00000001 +272.83,50.30085681,-2.891452639,10500,0,199.9998535,0,0,0,90.00000001 +272.84,50.30085681,-2.891424614,10500,0,200.0009685,0,0,0,90.00000001 +272.85,50.30085681,-2.891396588,10500,0,200.0009685,0,0,0,90.00000001 +272.86,50.30085681,-2.891368563,10500,0,199.9998535,0,0,0,90.00000001 +272.87,50.30085681,-2.891340538,10500,0,199.9989614,0,0,0,90.00000001 +272.88,50.30085681,-2.891312513,10500,0,199.9989614,0,0,0,90.00000001 +272.89,50.30085681,-2.891284488,10500,0,199.9998535,0,0,0,90.00000001 +272.9,50.30085681,-2.891256463,10500,0,200.0009685,0,0,0,90.00000001 +272.91,50.30085681,-2.891228437,10500,0,200.0009685,0,0,0,90.00000001 +272.92,50.30085681,-2.891200412,10500,0,199.9998535,0,0,0,90.00000001 +272.93,50.30085681,-2.891172387,10500,0,199.9989614,0,0,0,90.00000001 +272.94,50.30085681,-2.891144362,10500,0,199.9987384,0,0,0,90.00000001 +272.95,50.30085681,-2.891116337,10500,0,199.9989614,0,0,0,90.00000001 +272.96,50.30085681,-2.891088312,10500,0,199.9998535,0,0,0,90.00000001 +272.97,50.30085681,-2.891060287,10500,0,200.0009685,0,0,0,90.00000001 +272.98,50.30085681,-2.891032261,10500,0,200.0009685,0,0,0,90.00000001 +272.99,50.30085681,-2.891004236,10500,0,199.9998535,0,0,0,90.00000001 +273,50.30085681,-2.890976211,10500,0,199.9989614,0,0,0,90.00000001 +273.01,50.30085681,-2.890948186,10500,0,199.9989614,0,0,0,90.00000001 +273.02,50.30085681,-2.890920161,10500,0,199.9998535,0,0,0,90.00000001 +273.03,50.30085681,-2.890892136,10500,0,200.0009685,0,0,0,90.00000001 +273.04,50.30085681,-2.89086411,10500,0,200.0009685,0,0,0,90.00000001 +273.05,50.30085681,-2.890836085,10500,0,199.9998535,0,0,0,90.00000001 +273.06,50.30085681,-2.89080806,10500,0,199.9989614,0,0,0,90.00000001 +273.07,50.30085681,-2.890780035,10500,0,199.9989614,0,0,0,90.00000001 +273.08,50.30085681,-2.89075201,10500,0,199.9998535,0,0,0,90.00000001 +273.09,50.30085681,-2.890723985,10500,0,200.0009685,0,0,0,90.00000001 +273.1,50.30085681,-2.890695959,10500,0,200.0009685,0,0,0,90.00000001 +273.11,50.30085681,-2.890667934,10500,0,199.9998535,0,0,0,90.00000001 +273.12,50.30085681,-2.890639909,10500,0,199.9989614,0,0,0,90.00000001 +273.13,50.30085681,-2.890611884,10500,0,199.9989614,0,0,0,90.00000001 +273.14,50.30085681,-2.890583859,10500,0,199.9998535,0,0,0,90.00000001 +273.15,50.30085681,-2.890555834,10500,0,200.0009685,0,0,0,90.00000001 +273.16,50.30085681,-2.890527808,10500,0,200.0009685,0,0,0,90.00000001 +273.17,50.30085681,-2.890499783,10500,0,199.9998535,0,0,0,90.00000001 +273.18,50.30085681,-2.890471758,10500,0,199.9989614,0,0,0,90.00000001 +273.19,50.30085681,-2.890443733,10500,0,199.9989614,0,0,0,90.00000001 +273.2,50.30085681,-2.890415708,10500,0,199.9998535,0,0,0,90.00000001 +273.21,50.30085681,-2.890387683,10500,0,200.0009685,0,0,0,90.00000001 +273.22,50.30085681,-2.890359657,10500,0,200.0009685,0,0,0,90.00000001 +273.23,50.30085681,-2.890331632,10500,0,199.9998535,0,0,0,90.00000001 +273.24,50.30085681,-2.890303607,10500,0,199.9991844,0,0,0,90.00000001 +273.25,50.30085681,-2.890275582,10500,0,199.9998535,0,0,0,90.00000001 +273.26,50.30085681,-2.890247557,10500,0,200.0009685,0,0,0,90.00000001 +273.27,50.30085681,-2.890219531,10500,0,200.0009685,0,0,0,90.00000001 +273.28,50.30085681,-2.890191506,10500,0,199.9998535,0,0,0,90.00000001 +273.29,50.30085681,-2.890163481,10500,0,199.9991844,0,0,0,90.00000001 +273.3,50.30085681,-2.890135456,10500,0,199.9998535,0,0,0,90.00000001 +273.31,50.30085681,-2.890107431,10500,0,200.0009685,0,0,0,90.00000001 +273.32,50.30085681,-2.890079405,10500,0,200.0009685,0,0,0,90.00000001 +273.33,50.30085681,-2.89005138,10500,0,199.9998535,0,0,0,90.00000001 +273.34,50.30085681,-2.890023355,10500,0,199.9989614,0,0,0,90.00000001 +273.35,50.30085681,-2.88999533,10500,0,199.9989614,0,0,0,90.00000001 +273.36,50.30085681,-2.889967305,10500,0,199.9998535,0,0,0,90.00000001 +273.37,50.30085681,-2.88993928,10500,0,200.0009685,0,0,0,90.00000001 +273.38,50.30085681,-2.889911254,10500,0,200.0009685,0,0,0,90.00000001 +273.39,50.30085681,-2.889883229,10500,0,199.9998535,0,0,0,90.00000001 +273.4,50.30085681,-2.889855204,10500,0,199.9991844,0,0,0,90.00000001 +273.41,50.30085681,-2.889827179,10500,0,199.9998535,0,0,0,90.00000001 +273.42,50.30085681,-2.889799154,10500,0,200.0009685,0,0,0,90.00000001 +273.43,50.30085681,-2.889771128,10500,0,200.0009685,0,0,0,90.00000001 +273.44,50.30085681,-2.889743103,10500,0,199.9998535,0,0,0,90.00000001 +273.45,50.30085681,-2.889715078,10500,0,199.9991844,0,0,0,90.00000001 +273.46,50.30085681,-2.889687053,10500,0,199.9998535,0,0,0,90.00000001 +273.47,50.30085681,-2.889659028,10500,0,200.0009685,0,0,0,90.00000001 +273.48,50.30085681,-2.889631002,10500,0,200.0009685,0,0,0,90.00000001 +273.49,50.30085681,-2.889602977,10500,0,199.9998535,0,0,0,90.00000001 +273.5,50.30085681,-2.889574952,10500,0,199.9991844,0,0,0,90.00000001 +273.51,50.30085681,-2.889546927,10500,0,199.9998535,0,0,0,90.00000001 +273.52,50.30085681,-2.889518902,10500,0,200.0009685,0,0,0,90.00000001 +273.53,50.30085681,-2.889490876,10500,0,200.0009685,0,0,0,90.00000001 +273.54,50.30085681,-2.889462851,10500,0,199.9998535,0,0,0,90.00000001 +273.55,50.30085681,-2.889434826,10500,0,199.9989614,0,0,0,90.00000001 +273.56,50.30085681,-2.889406801,10500,0,199.9987384,0,0,0,90.00000001 +273.57,50.30085681,-2.889378776,10500,0,199.9989614,0,0,0,90.00000001 +273.58,50.30085681,-2.889350751,10500,0,199.9998535,0,0,0,90.00000001 +273.59,50.30085681,-2.889322726,10500,0,200.0009685,0,0,0,90.00000001 +273.6,50.30085681,-2.8892947,10500,0,200.0009685,0,0,0,90.00000001 +273.61,50.30085681,-2.889266675,10500,0,199.9998535,0,0,0,90.00000001 +273.62,50.30085681,-2.88923865,10500,0,199.9989614,0,0,0,90.00000001 +273.63,50.30085681,-2.889210625,10500,0,199.9989614,0,0,0,90.00000001 +273.64,50.30085681,-2.8891826,10500,0,199.9998535,0,0,0,90.00000001 +273.65,50.30085681,-2.889154575,10500,0,200.0009685,0,0,0,90.00000001 +273.66,50.30085681,-2.889126549,10500,0,200.0009685,0,0,0,90.00000001 +273.67,50.30085681,-2.889098524,10500,0,199.9998535,0,0,0,90.00000001 +273.68,50.30085681,-2.889070499,10500,0,199.9989614,0,0,0,90.00000001 +273.69,50.30085681,-2.889042474,10500,0,199.9989614,0,0,0,90.00000001 +273.7,50.30085681,-2.889014449,10500,0,199.9998535,0,0,0,90.00000001 +273.71,50.30085681,-2.888986424,10500,0,200.0009685,0,0,0,90.00000001 +273.72,50.30085681,-2.888958398,10500,0,200.0009685,0,0,0,90.00000001 +273.73,50.30085681,-2.888930373,10500,0,199.9998535,0,0,0,90.00000001 +273.74,50.30085681,-2.888902348,10500,0,199.9989614,0,0,0,90.00000001 +273.75,50.30085681,-2.888874323,10500,0,199.9989614,0,0,0,90.00000001 +273.76,50.30085681,-2.888846298,10500,0,199.9998535,0,0,0,90.00000001 +273.77,50.30085681,-2.888818273,10500,0,200.0009685,0,0,0,90.00000001 +273.78,50.30085681,-2.888790247,10500,0,200.0009685,0,0,0,90.00000001 +273.79,50.30085681,-2.888762222,10500,0,199.9998535,0,0,0,90.00000001 +273.8,50.30085681,-2.888734197,10500,0,199.9989614,0,0,0,90.00000001 +273.81,50.30085681,-2.888706172,10500,0,199.9987384,0,0,0,90.00000001 +273.82,50.30085681,-2.888678147,10500,0,199.9989614,0,0,0,90.00000001 +273.83,50.30085681,-2.888650122,10500,0,199.9998535,0,0,0,90.00000001 +273.84,50.30085681,-2.888622097,10500,0,200.0009685,0,0,0,90.00000001 +273.85,50.30085681,-2.888594071,10500,0,200.0009685,0,0,0,90.00000001 +273.86,50.30085681,-2.888566046,10500,0,199.9998535,0,0,0,90.00000001 +273.87,50.30085681,-2.888538021,10500,0,199.9991844,0,0,0,90.00000001 +273.88,50.30085681,-2.888509996,10500,0,199.9998535,0,0,0,90.00000001 +273.89,50.30085681,-2.888481971,10500,0,200.0009685,0,0,0,90.00000001 +273.9,50.30085681,-2.888453945,10500,0,200.0009685,0,0,0,90.00000001 +273.91,50.30085681,-2.88842592,10500,0,199.9998535,0,0,0,90.00000001 +273.92,50.30085681,-2.888397895,10500,0,199.9991844,0,0,0,90.00000001 +273.93,50.30085681,-2.88836987,10500,0,199.9998535,0,0,0,90.00000001 +273.94,50.30085681,-2.888341845,10500,0,200.0009685,0,0,0,90.00000001 +273.95,50.30085681,-2.888313819,10500,0,200.0009685,0,0,0,90.00000001 +273.96,50.30085681,-2.888285794,10500,0,199.9998535,0,0,0,90.00000001 +273.97,50.30085681,-2.888257769,10500,0,199.9991844,0,0,0,90.00000001 +273.98,50.30085681,-2.888229744,10500,0,199.9998535,0,0,0,90.00000001 +273.99,50.30085681,-2.888201719,10500,0,200.0009685,0,0,0,90.00000001 +274,50.30085681,-2.888173693,10500,0,200.0009685,0,0,0,90.00000001 +274.01,50.30085681,-2.888145668,10500,0,199.9998535,0,0,0,90.00000001 +274.02,50.30085681,-2.888117643,10500,0,199.9991844,0,0,0,90.00000001 +274.03,50.30085681,-2.888089618,10500,0,199.9998535,0,0,0,90.00000001 +274.04,50.30085681,-2.888061593,10500,0,200.0009685,0,0,0,90.00000001 +274.05,50.30085681,-2.888033567,10500,0,200.0009685,0,0,0,90.00000001 +274.06,50.30085681,-2.888005542,10500,0,199.9998535,0,0,0,90.00000001 +274.07,50.30085681,-2.887977517,10500,0,199.9991844,0,0,0,90.00000001 +274.08,50.30085681,-2.887949492,10500,0,199.9998535,0,0,0,90.00000001 +274.09,50.30085681,-2.887921467,10500,0,200.0009685,0,0,0,90.00000001 +274.1,50.30085681,-2.887893441,10500,0,200.0009685,0,0,0,90.00000001 +274.11,50.30085681,-2.887865416,10500,0,199.9998535,0,0,0,90.00000001 +274.12,50.30085681,-2.887837391,10500,0,199.9989614,0,0,0,90.00000001 +274.13,50.30085681,-2.887809366,10500,0,199.9989614,0,0,0,90.00000001 +274.14,50.30085681,-2.887781341,10500,0,199.9998535,0,0,0,90.00000001 +274.15,50.30085681,-2.887753316,10500,0,200.0009685,0,0,0,90.00000001 +274.16,50.30085681,-2.88772529,10500,0,200.0009685,0,0,0,90.00000001 +274.17,50.30085681,-2.887697265,10500,0,199.9998535,0,0,0,90.00000001 +274.18,50.30085681,-2.88766924,10500,0,199.9989614,0,0,0,90.00000001 +274.19,50.30085681,-2.887641215,10500,0,199.9989614,0,0,0,90.00000001 +274.2,50.30085681,-2.88761319,10500,0,199.9998535,0,0,0,90.00000001 +274.21,50.30085681,-2.887585165,10500,0,200.0009685,0,0,0,90.00000001 +274.22,50.30085681,-2.887557139,10500,0,200.0009685,0,0,0,90.00000001 +274.23,50.30085681,-2.887529114,10500,0,199.9998535,0,0,0,90.00000001 +274.24,50.30085681,-2.887501089,10500,0,199.9989614,0,0,0,90.00000001 +274.25,50.30085681,-2.887473064,10500,0,199.9989614,0,0,0,90.00000001 +274.26,50.30085681,-2.887445039,10500,0,199.9998535,0,0,0,90.00000001 +274.27,50.30085681,-2.887417014,10500,0,200.0009685,0,0,0,90.00000001 +274.28,50.30085681,-2.887388988,10500,0,200.0009685,0,0,0,90.00000001 +274.29,50.30085681,-2.887360963,10500,0,199.9998535,0,0,0,90.00000001 +274.3,50.30085681,-2.887332938,10500,0,199.9989614,0,0,0,90.00000001 +274.31,50.30085681,-2.887304913,10500,0,199.9989614,0,0,0,90.00000001 +274.32,50.30085681,-2.887276888,10500,0,199.9998535,0,0,0,90.00000001 +274.33,50.30085681,-2.887248863,10500,0,200.0009685,0,0,0,90.00000001 +274.34,50.30085681,-2.887220837,10500,0,200.0009685,0,0,0,90.00000001 +274.35,50.30085681,-2.887192812,10500,0,199.9998535,0,0,0,90.00000001 +274.36,50.30085681,-2.887164787,10500,0,199.9989614,0,0,0,90.00000001 +274.37,50.30085681,-2.887136762,10500,0,199.9987384,0,0,0,90.00000001 +274.38,50.30085681,-2.887108737,10500,0,199.9989614,0,0,0,90.00000001 +274.39,50.30085681,-2.887080712,10500,0,199.9998535,0,0,0,90.00000001 +274.4,50.30085681,-2.887052687,10500,0,200.0009685,0,0,0,90.00000001 +274.41,50.30085681,-2.887024661,10500,0,200.0009685,0,0,0,90.00000001 +274.42,50.30085681,-2.886996636,10500,0,199.9998535,0,0,0,90.00000001 +274.43,50.30085681,-2.886968611,10500,0,199.9989614,0,0,0,90.00000001 +274.44,50.30085681,-2.886940586,10500,0,199.9989614,0,0,0,90.00000001 +274.45,50.30085681,-2.886912561,10500,0,199.9998535,0,0,0,90.00000001 +274.46,50.30085681,-2.886884536,10500,0,200.0009685,0,0,0,90.00000001 +274.47,50.30085681,-2.88685651,10500,0,200.0009685,0,0,0,90.00000001 +274.48,50.30085681,-2.886828485,10500,0,199.9998535,0,0,0,90.00000001 +274.49,50.30085681,-2.88680046,10500,0,199.9991844,0,0,0,90.00000001 +274.5,50.30085681,-2.886772435,10500,0,199.9998535,0,0,0,90.00000001 +274.51,50.30085681,-2.88674441,10500,0,200.0009685,0,0,0,90.00000001 +274.52,50.30085681,-2.886716384,10500,0,200.0009685,0,0,0,90.00000001 +274.53,50.30085681,-2.886688359,10500,0,199.9998535,0,0,0,90.00000001 +274.54,50.30085681,-2.886660334,10500,0,199.9991844,0,0,0,90.00000001 +274.55,50.30085681,-2.886632309,10500,0,199.9998535,0,0,0,90.00000001 +274.56,50.30085681,-2.886604284,10500,0,200.0009685,0,0,0,90.00000001 +274.57,50.30085681,-2.886576258,10500,0,200.0009685,0,0,0,90.00000001 +274.58,50.30085681,-2.886548233,10500,0,199.9998535,0,0,0,90.00000001 +274.59,50.30085681,-2.886520208,10500,0,199.9991844,0,0,0,90.00000001 +274.6,50.30085681,-2.886492183,10500,0,199.9998535,0,0,0,90.00000001 +274.61,50.30085681,-2.886464158,10500,0,200.0009685,0,0,0,90.00000001 +274.62,50.30085681,-2.886436132,10500,0,200.0009685,0,0,0,90.00000001 +274.63,50.30085681,-2.886408107,10500,0,199.9998535,0,0,0,90.00000001 +274.64,50.30085681,-2.886380082,10500,0,199.9991844,0,0,0,90.00000001 +274.65,50.30085681,-2.886352057,10500,0,199.9998535,0,0,0,90.00000001 +274.66,50.30085681,-2.886324032,10500,0,200.0009685,0,0,0,90.00000001 +274.67,50.30085681,-2.886296006,10500,0,200.0009685,0,0,0,90.00000001 +274.68,50.30085681,-2.886267981,10500,0,199.9998535,0,0,0,90.00000001 +274.69,50.30085681,-2.886239956,10500,0,199.9991844,0,0,0,90.00000001 +274.7,50.30085681,-2.886211931,10500,0,199.9998535,0,0,0,90.00000001 +274.71,50.30085681,-2.886183906,10500,0,200.0009685,0,0,0,90.00000001 +274.72,50.30085681,-2.88615588,10500,0,200.0009685,0,0,0,90.00000001 +274.73,50.30085681,-2.886127855,10500,0,199.9998535,0,0,0,90.00000001 +274.74,50.30085681,-2.88609983,10500,0,199.9989614,0,0,0,90.00000001 +274.75,50.30085681,-2.886071805,10500,0,199.9989614,0,0,0,90.00000001 +274.76,50.30085681,-2.88604378,10500,0,199.9998535,0,0,0,90.00000001 +274.77,50.30085681,-2.886015755,10500,0,200.0009685,0,0,0,90.00000001 +274.78,50.30085681,-2.885987729,10500,0,200.0009685,0,0,0,90.00000001 +274.79,50.30085681,-2.885959704,10500,0,199.9998535,0,0,0,90.00000001 +274.8,50.30085681,-2.885931679,10500,0,199.9989614,0,0,0,90.00000001 +274.81,50.30085681,-2.885903654,10500,0,199.9989614,0,0,0,90.00000001 +274.82,50.30085681,-2.885875629,10500,0,199.9998535,0,0,0,90.00000001 +274.83,50.30085681,-2.885847604,10500,0,200.0009685,0,0,0,90.00000001 +274.84,50.30085681,-2.885819578,10500,0,200.0009685,0,0,0,90.00000001 +274.85,50.30085681,-2.885791553,10500,0,199.9998535,0,0,0,90.00000001 +274.86,50.30085681,-2.885763528,10500,0,199.9989614,0,0,0,90.00000001 +274.87,50.30085681,-2.885735503,10500,0,199.9989614,0,0,0,90.00000001 +274.88,50.30085681,-2.885707478,10500,0,199.9998535,0,0,0,90.00000001 +274.89,50.30085681,-2.885679453,10500,0,200.0009685,0,0,0,90.00000001 +274.9,50.30085681,-2.885651427,10500,0,200.0009685,0,0,0,90.00000001 +274.91,50.30085681,-2.885623402,10500,0,199.9998535,0,0,0,90.00000001 +274.92,50.30085681,-2.885595377,10500,0,199.9989614,0,0,0,90.00000001 +274.93,50.30085681,-2.885567352,10500,0,199.9989614,0,0,0,90.00000001 +274.94,50.30085681,-2.885539327,10500,0,199.9998535,0,0,0,90.00000001 +274.95,50.30085681,-2.885511302,10500,0,200.0009685,0,0,0,90.00000001 +274.96,50.30085681,-2.885483276,10500,0,200.0009685,0,0,0,90.00000001 +274.97,50.30085681,-2.885455251,10500,0,199.9998535,0,0,0,90.00000001 +274.98,50.30085681,-2.885427226,10500,0,199.9989614,0,0,0,90.00000001 +274.99,50.30085681,-2.885399201,10500,0,199.9987384,0,0,0,90.00000001 +275,50.30085681,-2.885371176,10500,0,199.9989614,0,0,0,90.00000001 +275.01,50.30085681,-2.885343151,10500,0,199.9998535,0,0,0,90.00000001 +275.02,50.30085681,-2.885315126,10500,0,200.0009685,0,0,0,90.00000001 +275.03,50.30085681,-2.8852871,10500,0,200.0009685,0,0,0,90.00000001 +275.04,50.30085681,-2.885259075,10500,0,199.9998535,0,0,0,90.00000001 +275.05,50.30085681,-2.88523105,10500,0,199.9989614,0,0,0,90.00000001 +275.06,50.30085681,-2.885203025,10500,0,199.9989614,0,0,0,90.00000001 +275.07,50.30085681,-2.885175,10500,0,199.9998535,0,0,0,90.00000001 +275.08,50.30085681,-2.885146975,10500,0,200.0009685,0,0,0,90.00000001 +275.09,50.30085681,-2.885118949,10500,0,200.0009685,0,0,0,90.00000001 +275.1,50.30085681,-2.885090924,10500,0,199.9998535,0,0,0,90.00000001 +275.11,50.30085681,-2.885062899,10500,0,199.9991844,0,0,0,90.00000001 +275.12,50.30085681,-2.885034874,10500,0,199.9998535,0,0,0,90.00000001 +275.13,50.30085681,-2.885006849,10500,0,200.0009685,0,0,0,90.00000001 +275.14,50.30085681,-2.884978823,10500,0,200.0009685,0,0,0,90.00000001 +275.15,50.30085681,-2.884950798,10500,0,199.9998535,0,0,0,90.00000001 +275.16,50.30085681,-2.884922773,10500,0,199.9991844,0,0,0,90.00000001 +275.17,50.30085681,-2.884894748,10500,0,199.9998535,0,0,0,90.00000001 +275.18,50.30085681,-2.884866723,10500,0,200.0009685,0,0,0,90.00000001 +275.19,50.30085681,-2.884838697,10500,0,200.0009685,0,0,0,90.00000001 +275.2,50.30085681,-2.884810672,10500,0,199.9998535,0,0,0,90.00000001 +275.21,50.30085681,-2.884782647,10500,0,199.9991844,0,0,0,90.00000001 +275.22,50.30085681,-2.884754622,10500,0,199.9998535,0,0,0,90.00000001 +275.23,50.30085681,-2.884726597,10500,0,200.0009685,0,0,0,90.00000001 +275.24,50.30085681,-2.884698571,10500,0,200.0009685,0,0,0,90.00000001 +275.25,50.30085681,-2.884670546,10500,0,199.9998535,0,0,0,90.00000001 +275.26,50.30085681,-2.884642521,10500,0,199.9991844,0,0,0,90.00000001 +275.27,50.30085681,-2.884614496,10500,0,199.9998535,0,0,0,90.00000001 +275.28,50.30085681,-2.884586471,10500,0,200.0009685,0,0,0,90.00000001 +275.29,50.30085681,-2.884558445,10500,0,200.0009685,0,0,0,90.00000001 +275.3,50.30085681,-2.88453042,10500,0,199.9998535,0,0,0,90.00000001 +275.31,50.30085681,-2.884502395,10500,0,199.9991844,0,0,0,90.00000001 +275.32,50.30085681,-2.88447437,10500,0,199.9998535,0,0,0,90.00000001 +275.33,50.30085681,-2.884446345,10500,0,200.0009685,0,0,0,90.00000001 +275.34,50.30085681,-2.884418319,10500,0,200.0009685,0,0,0,90.00000001 +275.35,50.30085681,-2.884390294,10500,0,199.9998535,0,0,0,90.00000001 +275.36,50.30085681,-2.884362269,10500,0,199.9989614,0,0,0,90.00000001 +275.37,50.30085681,-2.884334244,10500,0,199.9989614,0,0,0,90.00000001 +275.38,50.30085681,-2.884306219,10500,0,199.9998535,0,0,0,90.00000001 +275.39,50.30085681,-2.884278194,10500,0,200.0009685,0,0,0,90.00000001 +275.4,50.30085681,-2.884250168,10500,0,200.0009685,0,0,0,90.00000001 +275.41,50.30085681,-2.884222143,10500,0,199.9998535,0,0,0,90.00000001 +275.42,50.30085681,-2.884194118,10500,0,199.9989614,0,0,0,90.00000001 +275.43,50.30085681,-2.884166093,10500,0,199.9989614,0,0,0,90.00000001 +275.44,50.30085681,-2.884138068,10500,0,199.9998535,0,0,0,90.00000001 +275.45,50.30085681,-2.884110043,10500,0,200.0009685,0,0,0,90.00000001 +275.46,50.30085681,-2.884082017,10500,0,200.0009685,0,0,0,90.00000001 +275.47,50.30085681,-2.884053992,10500,0,199.9998535,0,0,0,90.00000001 +275.48,50.30085681,-2.884025967,10500,0,199.9989614,0,0,0,90.00000001 +275.49,50.30085681,-2.883997942,10500,0,199.9989614,0,0,0,90.00000001 +275.5,50.30085681,-2.883969917,10500,0,199.9998535,0,0,0,90.00000001 +275.51,50.30085681,-2.883941892,10500,0,200.0009685,0,0,0,90.00000001 +275.52,50.30085681,-2.883913866,10500,0,200.0009685,0,0,0,90.00000001 +275.53,50.30085681,-2.883885841,10500,0,199.9998535,0,0,0,90.00000001 +275.54,50.30085681,-2.883857816,10500,0,199.9989614,0,0,0,90.00000001 +275.55,50.30085681,-2.883829791,10500,0,199.9987384,0,0,0,90.00000001 +275.56,50.30085681,-2.883801766,10500,0,199.9989614,0,0,0,90.00000001 +275.57,50.30085681,-2.883773741,10500,0,199.9998535,0,0,0,90.00000001 +275.58,50.30085681,-2.883745716,10500,0,200.0009685,0,0,0,90.00000001 +275.59,50.30085681,-2.88371769,10500,0,200.0009685,0,0,0,90.00000001 +275.6,50.30085681,-2.883689665,10500,0,199.9998535,0,0,0,90.00000001 +275.61,50.30085681,-2.88366164,10500,0,199.9989614,0,0,0,90.00000001 +275.62,50.30085681,-2.883633615,10500,0,199.9989614,0,0,0,90.00000001 +275.63,50.30085681,-2.88360559,10500,0,199.9998535,0,0,0,90.00000001 +275.64,50.30085681,-2.883577565,10500,0,200.0009685,0,0,0,90.00000001 +275.65,50.30085681,-2.883549539,10500,0,200.0009685,0,0,0,90.00000001 +275.66,50.30085681,-2.883521514,10500,0,199.9998535,0,0,0,90.00000001 +275.67,50.30085681,-2.883493489,10500,0,199.9989614,0,0,0,90.00000001 +275.68,50.30085681,-2.883465464,10500,0,199.9989614,0,0,0,90.00000001 +275.69,50.30085681,-2.883437439,10500,0,199.9998535,0,0,0,90.00000001 +275.7,50.30085681,-2.883409414,10500,0,200.0009685,0,0,0,90.00000001 +275.71,50.30085681,-2.883381388,10500,0,200.0009685,0,0,0,90.00000001 +275.72,50.30085681,-2.883353363,10500,0,199.9998535,0,0,0,90.00000001 +275.73,50.30085681,-2.883325338,10500,0,199.9989614,0,0,0,90.00000001 +275.74,50.30085681,-2.883297313,10500,0,199.9989614,0,0,0,90.00000001 +275.75,50.30085681,-2.883269288,10500,0,199.9998535,0,0,0,90.00000001 +275.76,50.30085681,-2.883241263,10500,0,200.0009685,0,0,0,90.00000001 +275.77,50.30085681,-2.883213237,10500,0,200.0009685,0,0,0,90.00000001 +275.78,50.30085681,-2.883185212,10500,0,199.9998535,0,0,0,90.00000001 +275.79,50.30085681,-2.883157187,10500,0,199.9991844,0,0,0,90.00000001 +275.8,50.30085681,-2.883129162,10500,0,199.9998535,0,0,0,90.00000001 +275.81,50.30085681,-2.883101137,10500,0,200.0009685,0,0,0,90.00000001 +275.82,50.30085681,-2.883073111,10500,0,200.0009685,0,0,0,90.00000001 +275.83,50.30085681,-2.883045086,10500,0,199.9998535,0,0,0,90.00000001 +275.84,50.30085681,-2.883017061,10500,0,199.9991844,0,0,0,90.00000001 +275.85,50.30085681,-2.882989036,10500,0,199.9998535,0,0,0,90.00000001 +275.86,50.30085681,-2.882961011,10500,0,200.0009685,0,0,0,90.00000001 +275.87,50.30085681,-2.882932985,10500,0,200.0009685,0,0,0,90.00000001 +275.88,50.30085681,-2.88290496,10500,0,199.9998535,0,0,0,90.00000001 +275.89,50.30085681,-2.882876935,10500,0,199.9991844,0,0,0,90.00000001 +275.9,50.30085681,-2.88284891,10500,0,199.9998535,0,0,0,90.00000001 +275.91,50.30085681,-2.882820885,10500,0,200.0009685,0,0,0,90.00000001 +275.92,50.30085681,-2.882792859,10500,0,200.0009685,0,0,0,90.00000001 +275.93,50.30085681,-2.882764834,10500,0,199.9998535,0,0,0,90.00000001 +275.94,50.30085681,-2.882736809,10500,0,199.9991844,0,0,0,90.00000001 +275.95,50.30085681,-2.882708784,10500,0,199.9998535,0,0,0,90.00000001 +275.96,50.30085681,-2.882680759,10500,0,200.0009685,0,0,0,90.00000001 +275.97,50.30085681,-2.882652733,10500,0,200.0009685,0,0,0,90.00000001 +275.98,50.30085681,-2.882624708,10500,0,199.9998535,0,0,0,90.00000001 +275.99,50.30085681,-2.882596683,10500,0,199.9991844,0,0,0,90.00000001 +276,50.30085681,-2.882568658,10500,0,199.9998535,0,0,0,90.00000001 +276.01,50.30085681,-2.882540633,10500,0,200.0009685,0,0,0,90.00000001 +276.02,50.30085681,-2.882512607,10500,0,200.0009685,0,0,0,90.00000001 +276.03,50.30085681,-2.882484582,10500,0,199.9998535,0,0,0,90.00000001 +276.04,50.30085681,-2.882456557,10500,0,199.9989614,0,0,0,90.00000001 +276.05,50.30085681,-2.882428532,10500,0,199.9989614,0,0,0,90.00000001 +276.06,50.30085681,-2.882400507,10500,0,199.9998535,0,0,0,90.00000001 +276.07,50.30085681,-2.882372482,10500,0,200.0009685,0,0,0,90.00000001 +276.08,50.30085681,-2.882344456,10500,0,200.0009685,0,0,0,90.00000001 +276.09,50.30085681,-2.882316431,10500,0,199.9998535,0,0,0,90.00000001 +276.1,50.30085681,-2.882288406,10500,0,199.9989614,0,0,0,90.00000001 +276.11,50.30085681,-2.882260381,10500,0,199.9987384,0,0,0,90.00000001 +276.12,50.30085681,-2.882232356,10500,0,199.9989614,0,0,0,90.00000001 +276.13,50.30085681,-2.882204331,10500,0,199.9998535,0,0,0,90.00000001 +276.14,50.30085681,-2.882176306,10500,0,200.0009685,0,0,0,90.00000001 +276.15,50.30085681,-2.88214828,10500,0,200.0009685,0,0,0,90.00000001 +276.16,50.30085681,-2.882120255,10500,0,199.9998535,0,0,0,90.00000001 +276.17,50.30085681,-2.88209223,10500,0,199.9989614,0,0,0,90.00000001 +276.18,50.30085681,-2.882064205,10500,0,199.9989614,0,0,0,90.00000001 +276.19,50.30085681,-2.88203618,10500,0,199.9998535,0,0,0,90.00000001 +276.2,50.30085681,-2.882008155,10500,0,200.0009685,0,0,0,90.00000001 +276.21,50.30085681,-2.881980129,10500,0,200.0009685,0,0,0,90.00000001 +276.22,50.30085681,-2.881952104,10500,0,199.9998535,0,0,0,90.00000001 +276.23,50.30085681,-2.881924079,10500,0,199.9989614,0,0,0,90.00000001 +276.24,50.30085681,-2.881896054,10500,0,199.9989614,0,0,0,90.00000001 +276.25,50.30085681,-2.881868029,10500,0,199.9998535,0,0,0,90.00000001 +276.26,50.30085681,-2.881840004,10500,0,200.0009685,0,0,0,90.00000001 +276.27,50.30085681,-2.881811978,10500,0,200.0009685,0,0,0,90.00000001 +276.28,50.30085681,-2.881783953,10500,0,199.9998535,0,0,0,90.00000001 +276.29,50.30085681,-2.881755928,10500,0,199.9989614,0,0,0,90.00000001 +276.3,50.30085681,-2.881727903,10500,0,199.9989614,0,0,0,90.00000001 +276.31,50.30085681,-2.881699878,10500,0,199.9998535,0,0,0,90.00000001 +276.32,50.30085681,-2.881671853,10500,0,200.0009685,0,0,0,90.00000001 +276.33,50.30085681,-2.881643827,10500,0,200.0009685,0,0,0,90.00000001 +276.34,50.30085681,-2.881615802,10500,0,199.9998535,0,0,0,90.00000001 +276.35,50.30085681,-2.881587777,10500,0,199.9989614,0,0,0,90.00000001 +276.36,50.30085681,-2.881559752,10500,0,199.9989614,0,0,0,90.00000001 +276.37,50.30085681,-2.881531727,10500,0,199.9998535,0,0,0,90.00000001 +276.38,50.30085681,-2.881503702,10500,0,200.0009685,0,0,0,90.00000001 +276.39,50.30085681,-2.881475676,10500,0,200.0009685,0,0,0,90.00000001 +276.4,50.30085681,-2.881447651,10500,0,199.9998535,0,0,0,90.00000001 +276.41,50.30085681,-2.881419626,10500,0,199.9991844,0,0,0,90.00000001 +276.42,50.30085681,-2.881391601,10500,0,199.9998535,0,0,0,90.00000001 +276.43,50.30085681,-2.881363576,10500,0,200.0009685,0,0,0,90.00000001 +276.44,50.30085681,-2.88133555,10500,0,200.0009685,0,0,0,90.00000001 +276.45,50.30085681,-2.881307525,10500,0,199.9998535,0,0,0,90.00000001 +276.46,50.30085681,-2.8812795,10500,0,199.9991844,0,0,0,90.00000001 +276.47,50.30085681,-2.881251475,10500,0,199.9998535,0,0,0,90.00000001 +276.48,50.30085681,-2.88122345,10500,0,200.0009685,0,0,0,90.00000001 +276.49,50.30085681,-2.881195424,10500,0,200.0009685,0,0,0,90.00000001 +276.5,50.30085681,-2.881167399,10500,0,199.9998535,0,0,0,90.00000001 +276.51,50.30085681,-2.881139374,10500,0,199.9991844,0,0,0,90.00000001 +276.52,50.30085681,-2.881111349,10500,0,199.9998535,0,0,0,90.00000001 +276.53,50.30085681,-2.881083324,10500,0,200.0009685,0,0,0,90.00000001 +276.54,50.30085681,-2.881055298,10500,0,200.0009685,0,0,0,90.00000001 +276.55,50.30085681,-2.881027273,10500,0,199.9998535,0,0,0,90.00000001 +276.56,50.30085681,-2.880999248,10500,0,199.9991844,0,0,0,90.00000001 +276.57,50.30085681,-2.880971223,10500,0,199.9998535,0,0,0,90.00000001 +276.58,50.30085681,-2.880943198,10500,0,200.0009685,0,0,0,90.00000001 +276.59,50.30085681,-2.880915172,10500,0,200.0009685,0,0,0,90.00000001 +276.6,50.30085681,-2.880887147,10500,0,199.9998535,0,0,0,90.00000001 +276.61,50.30085681,-2.880859122,10500,0,199.9991844,0,0,0,90.00000001 +276.62,50.30085681,-2.880831097,10500,0,199.9998535,0,0,0,90.00000001 +276.63,50.30085681,-2.880803072,10500,0,200.0009685,0,0,0,90.00000001 +276.64,50.30085681,-2.880775046,10500,0,200.0009685,0,0,0,90.00000001 +276.65,50.30085681,-2.880747021,10500,0,199.9998535,0,0,0,90.00000001 +276.66,50.30085681,-2.880718996,10500,0,199.9989614,0,0,0,90.00000001 +276.67,50.30085681,-2.880690971,10500,0,199.9987384,0,0,0,90.00000001 +276.68,50.30085681,-2.880662946,10500,0,199.9989614,0,0,0,90.00000001 +276.69,50.30085681,-2.880634921,10500,0,199.9998535,0,0,0,90.00000001 +276.7,50.30085681,-2.880606896,10500,0,200.0009685,0,0,0,90.00000001 +276.71,50.30085681,-2.88057887,10500,0,200.0009685,0,0,0,90.00000001 +276.72,50.30085681,-2.880550845,10500,0,199.9998535,0,0,0,90.00000001 +276.73,50.30085681,-2.88052282,10500,0,199.9989614,0,0,0,90.00000001 +276.74,50.30085681,-2.880494795,10500,0,199.9989614,0,0,0,90.00000001 +276.75,50.30085681,-2.88046677,10500,0,199.9998535,0,0,0,90.00000001 +276.76,50.30085681,-2.880438745,10500,0,200.0009685,0,0,0,90.00000001 +276.77,50.30085681,-2.880410719,10500,0,200.0009685,0,0,0,90.00000001 +276.78,50.30085681,-2.880382694,10500,0,199.9998535,0,0,0,90.00000001 +276.79,50.30085681,-2.880354669,10500,0,199.9989614,0,0,0,90.00000001 +276.8,50.30085681,-2.880326644,10500,0,199.9989614,0,0,0,90.00000001 +276.81,50.30085681,-2.880298619,10500,0,199.9998535,0,0,0,90.00000001 +276.82,50.30085681,-2.880270594,10500,0,200.0009685,0,0,0,90.00000001 +276.83,50.30085681,-2.880242568,10500,0,200.0009685,0,0,0,90.00000001 +276.84,50.30085681,-2.880214543,10500,0,199.9998535,0,0,0,90.00000001 +276.85,50.30085681,-2.880186518,10500,0,199.9989614,0,0,0,90.00000001 +276.86,50.30085681,-2.880158493,10500,0,199.9989614,0,0,0,90.00000001 +276.87,50.30085681,-2.880130468,10500,0,199.9998535,0,0,0,90.00000001 +276.88,50.30085681,-2.880102443,10500,0,200.0009685,0,0,0,90.00000001 +276.89,50.30085681,-2.880074417,10500,0,200.0009685,0,0,0,90.00000001 +276.9,50.30085681,-2.880046392,10500,0,199.9998535,0,0,0,90.00000001 +276.91,50.30085681,-2.880018367,10500,0,199.9989614,0,0,0,90.00000001 +276.92,50.30085681,-2.879990342,10500,0,199.9989614,0,0,0,90.00000001 +276.93,50.30085681,-2.879962317,10500,0,199.9998535,0,0,0,90.00000001 +276.94,50.30085681,-2.879934292,10500,0,200.0009685,0,0,0,90.00000001 +276.95,50.30085681,-2.879906266,10500,0,200.0009685,0,0,0,90.00000001 +276.96,50.30085681,-2.879878241,10500,0,199.9998535,0,0,0,90.00000001 +276.97,50.30085681,-2.879850216,10500,0,199.9989614,0,0,0,90.00000001 +276.98,50.30085681,-2.879822191,10500,0,199.9989614,0,0,0,90.00000001 +276.99,50.30085681,-2.879794166,10500,0,199.9998535,0,0,0,90.00000001 +277,50.30085681,-2.879766141,10500,0,200.0009685,0,0,0,90.00000001 +277.01,50.30085681,-2.879738115,10500,0,200.0009685,0,0,0,90.00000001 +277.02,50.30085681,-2.87971009,10500,0,199.9998535,0,0,0,90.00000001 +277.03,50.30085681,-2.879682065,10500,0,199.9991844,0,0,0,90.00000001 +277.04,50.30085681,-2.87965404,10500,0,199.9998535,0,0,0,90.00000001 +277.05,50.30085681,-2.879626015,10500,0,200.0009685,0,0,0,90.00000001 +277.06,50.30085681,-2.879597989,10500,0,200.0009685,0,0,0,90.00000001 +277.07,50.30085681,-2.879569964,10500,0,199.9998535,0,0,0,90.00000001 +277.08,50.30085681,-2.879541939,10500,0,199.9991844,0,0,0,90.00000001 +277.09,50.30085681,-2.879513914,10500,0,199.9998535,0,0,0,90.00000001 +277.1,50.30085681,-2.879485889,10500,0,200.0009685,0,0,0,90.00000001 +277.11,50.30085681,-2.879457863,10500,0,200.0009685,0,0,0,90.00000001 +277.12,50.30085681,-2.879429838,10500,0,199.9998535,0,0,0,90.00000001 +277.13,50.30085681,-2.879401813,10500,0,199.9991844,0,0,0,90.00000001 +277.14,50.30085681,-2.879373788,10500,0,199.9998535,0,0,0,90.00000001 +277.15,50.30085681,-2.879345763,10500,0,200.0009685,0,0,0,90.00000001 +277.16,50.30085681,-2.879317737,10500,0,200.0009685,0,0,0,90.00000001 +277.17,50.30085681,-2.879289712,10500,0,199.9998535,0,0,0,90.00000001 +277.18,50.30085681,-2.879261687,10500,0,199.9991844,0,0,0,90.00000001 +277.19,50.30085681,-2.879233662,10500,0,199.9998535,0,0,0,90.00000001 +277.2,50.30085681,-2.879205637,10500,0,200.0009685,0,0,0,90.00000001 +277.21,50.30085681,-2.879177611,10500,0,200.0009685,0,0,0,90.00000001 +277.22,50.30085681,-2.879149586,10500,0,199.9998535,0,0,0,90.00000001 +277.23,50.30085681,-2.879121561,10500,0,199.9989614,0,0,0,90.00000001 +277.24,50.30085681,-2.879093536,10500,0,199.9989614,0,0,0,90.00000001 +277.25,50.30085681,-2.879065511,10500,0,199.9998535,0,0,0,90.00000001 +277.26,50.30085681,-2.879037486,10500,0,200.0009685,0,0,0,90.00000001 +277.27,50.30085681,-2.87900946,10500,0,200.0009685,0,0,0,90.00000001 +277.28,50.30085681,-2.878981435,10500,0,199.9998535,0,0,0,90.00000001 +277.29,50.30085681,-2.87895341,10500,0,199.9989614,0,0,0,90.00000001 +277.3,50.30085681,-2.878925385,10500,0,199.9989614,0,0,0,90.00000001 +277.31,50.30085681,-2.87889736,10500,0,199.9998535,0,0,0,90.00000001 +277.32,50.30085681,-2.878869335,10500,0,200.0009685,0,0,0,90.00000001 +277.33,50.30085681,-2.878841309,10500,0,200.0009685,0,0,0,90.00000001 +277.34,50.30085681,-2.878813284,10500,0,199.9998535,0,0,0,90.00000001 +277.35,50.30085681,-2.878785259,10500,0,199.9989614,0,0,0,90.00000001 +277.36,50.30085681,-2.878757234,10500,0,199.9989614,0,0,0,90.00000001 +277.37,50.30085681,-2.878729209,10500,0,199.9998535,0,0,0,90.00000001 +277.38,50.30085681,-2.878701184,10500,0,200.0009685,0,0,0,90.00000001 +277.39,50.30085681,-2.878673158,10500,0,200.0009685,0,0,0,90.00000001 +277.4,50.30085681,-2.878645133,10500,0,199.9998535,0,0,0,90.00000001 +277.41,50.30085681,-2.878617108,10500,0,199.9989614,0,0,0,90.00000001 +277.42,50.30085681,-2.878589083,10500,0,199.9989614,0,0,0,90.00000001 +277.43,50.30085681,-2.878561058,10500,0,199.9998535,0,0,0,90.00000001 +277.44,50.30085681,-2.878533033,10500,0,200.0009685,0,0,0,90.00000001 +277.45,50.30085681,-2.878505007,10500,0,200.0009685,0,0,0,90.00000001 +277.46,50.30085681,-2.878476982,10500,0,199.9998535,0,0,0,90.00000001 +277.47,50.30085681,-2.878448957,10500,0,199.9989614,0,0,0,90.00000001 +277.48,50.30085681,-2.878420932,10500,0,199.9989614,0,0,0,90.00000001 +277.49,50.30085681,-2.878392907,10500,0,199.9998535,0,0,0,90.00000001 +277.5,50.30085681,-2.878364882,10500,0,200.0009685,0,0,0,90.00000001 +277.51,50.30085681,-2.878336856,10500,0,200.0009685,0,0,0,90.00000001 +277.52,50.30085681,-2.878308831,10500,0,199.9998535,0,0,0,90.00000001 +277.53,50.30085681,-2.878280806,10500,0,199.9989614,0,0,0,90.00000001 +277.54,50.30085681,-2.878252781,10500,0,199.9987384,0,0,0,90.00000001 +277.55,50.30085681,-2.878224756,10500,0,199.9989614,0,0,0,90.00000001 +277.56,50.30085681,-2.878196731,10500,0,199.9998535,0,0,0,90.00000001 +277.57,50.30085681,-2.878168706,10500,0,200.0009685,0,0,0,90.00000001 +277.58,50.30085681,-2.87814068,10500,0,200.0009685,0,0,0,90.00000001 +277.59,50.30085681,-2.878112655,10500,0,199.9998535,0,0,0,90.00000001 +277.6,50.30085681,-2.87808463,10500,0,199.9991844,0,0,0,90.00000001 +277.61,50.30085681,-2.878056605,10500,0,199.9998535,0,0,0,90.00000001 +277.62,50.30085681,-2.87802858,10500,0,200.0009685,0,0,0,90.00000001 +277.63,50.30085681,-2.878000554,10500,0,200.0009685,0,0,0,90.00000001 +277.64,50.30085681,-2.877972529,10500,0,199.9998535,0,0,0,90.00000001 +277.65,50.30085681,-2.877944504,10500,0,199.9991844,0,0,0,90.00000001 +277.66,50.30085681,-2.877916479,10500,0,199.9998535,0,0,0,90.00000001 +277.67,50.30085681,-2.877888454,10500,0,200.0009685,0,0,0,90.00000001 +277.68,50.30085681,-2.877860428,10500,0,200.0009685,0,0,0,90.00000001 +277.69,50.30085681,-2.877832403,10500,0,199.9998535,0,0,0,90.00000001 +277.7,50.30085681,-2.877804378,10500,0,199.9991844,0,0,0,90.00000001 +277.71,50.30085681,-2.877776353,10500,0,199.9998535,0,0,0,90.00000001 +277.72,50.30085681,-2.877748328,10500,0,200.0009685,0,0,0,90.00000001 +277.73,50.30085681,-2.877720302,10500,0,200.0009685,0,0,0,90.00000001 +277.74,50.30085681,-2.877692277,10500,0,199.9998535,0,0,0,90.00000001 +277.75,50.30085681,-2.877664252,10500,0,199.9991844,0,0,0,90.00000001 +277.76,50.30085681,-2.877636227,10500,0,199.9998535,0,0,0,90.00000001 +277.77,50.30085681,-2.877608202,10500,0,200.0009685,0,0,0,90.00000001 +277.78,50.30085681,-2.877580176,10500,0,200.0009685,0,0,0,90.00000001 +277.79,50.30085681,-2.877552151,10500,0,199.9998535,0,0,0,90.00000001 +277.8,50.30085681,-2.877524126,10500,0,199.9989614,0,0,0,90.00000001 +277.81,50.30085681,-2.877496101,10500,0,199.9989614,0,0,0,90.00000001 +277.82,50.30085681,-2.877468076,10500,0,199.9998535,0,0,0,90.00000001 +277.83,50.30085681,-2.877440051,10500,0,200.0009685,0,0,0,90.00000001 +277.84,50.30085681,-2.877412025,10500,0,200.0009685,0,0,0,90.00000001 +277.85,50.30085681,-2.877384,10500,0,199.9998535,0,0,0,90.00000001 +277.86,50.30085681,-2.877355975,10500,0,199.9991844,0,0,0,90.00000001 +277.87,50.30085681,-2.87732795,10500,0,199.9998535,0,0,0,90.00000001 +277.88,50.30085681,-2.877299925,10500,0,200.0009685,0,0,0,90.00000001 +277.89,50.30085681,-2.877271899,10500,0,200.0009685,0,0,0,90.00000001 +277.9,50.30085681,-2.877243874,10500,0,199.9998535,0,0,0,90.00000001 +277.91,50.30085681,-2.877215849,10500,0,199.9989614,0,0,0,90.00000001 +277.92,50.30085681,-2.877187824,10500,0,199.9989614,0,0,0,90.00000001 +277.93,50.30085681,-2.877159799,10500,0,199.9998535,0,0,0,90.00000001 +277.94,50.30085681,-2.877131774,10500,0,200.0009685,0,0,0,90.00000001 +277.95,50.30085681,-2.877103748,10500,0,200.0009685,0,0,0,90.00000001 +277.96,50.30085681,-2.877075723,10500,0,199.9998535,0,0,0,90.00000001 +277.97,50.30085681,-2.877047698,10500,0,199.9989614,0,0,0,90.00000001 +277.98,50.30085681,-2.877019673,10500,0,199.9989614,0,0,0,90.00000001 +277.99,50.30085681,-2.876991648,10500,0,199.9998535,0,0,0,90.00000001 +278,50.30085681,-2.876963623,10500,0,200.0009685,0,0,0,90.00000001 +278.01,50.30085681,-2.876935597,10500,0,200.0009685,0,0,0,90.00000001 +278.02,50.30085681,-2.876907572,10500,0,199.9998535,0,0,0,90.00000001 +278.03,50.30085681,-2.876879547,10500,0,199.9989614,0,0,0,90.00000001 +278.04,50.30085681,-2.876851522,10500,0,199.9989614,0,0,0,90.00000001 +278.05,50.30085681,-2.876823497,10500,0,199.9998535,0,0,0,90.00000001 +278.06,50.30085681,-2.876795472,10500,0,200.0009685,0,0,0,90.00000001 +278.07,50.30085681,-2.876767446,10500,0,200.0009685,0,0,0,90.00000001 +278.08,50.30085681,-2.876739421,10500,0,199.9998535,0,0,0,90.00000001 +278.09,50.30085681,-2.876711396,10500,0,199.9989614,0,0,0,90.00000001 +278.1,50.30085681,-2.876683371,10500,0,199.9987384,0,0,0,90.00000001 +278.11,50.30085681,-2.876655346,10500,0,199.9989614,0,0,0,90.00000001 +278.12,50.30085681,-2.876627321,10500,0,199.9998535,0,0,0,90.00000001 +278.13,50.30085681,-2.876599296,10500,0,200.0009685,0,0,0,90.00000001 +278.14,50.30085681,-2.87657127,10500,0,200.0009685,0,0,0,90.00000001 +278.15,50.30085681,-2.876543245,10500,0,199.9998535,0,0,0,90.00000001 +278.16,50.30085681,-2.87651522,10500,0,199.9989614,0,0,0,90.00000001 +278.17,50.30085681,-2.876487195,10500,0,199.9989614,0,0,0,90.00000001 +278.18,50.30085681,-2.87645917,10500,0,199.9998535,0,0,0,90.00000001 +278.19,50.30085681,-2.876431145,10500,0,200.0009685,0,0,0,90.00000001 +278.2,50.30085681,-2.876403119,10500,0,200.0009685,0,0,0,90.00000001 +278.21,50.30085681,-2.876375094,10500,0,199.9998535,0,0,0,90.00000001 +278.22,50.30085681,-2.876347069,10500,0,199.9989614,0,0,0,90.00000001 +278.23,50.30085681,-2.876319044,10500,0,199.9989614,0,0,0,90.00000001 +278.24,50.30085681,-2.876291019,10500,0,199.9998535,0,0,0,90.00000001 +278.25,50.30085681,-2.876262994,10500,0,200.0009685,0,0,0,90.00000001 +278.26,50.30085681,-2.876234968,10500,0,200.0009685,0,0,0,90.00000001 +278.27,50.30085681,-2.876206943,10500,0,199.9998535,0,0,0,90.00000001 +278.28,50.30085681,-2.876178918,10500,0,199.9991844,0,0,0,90.00000001 +278.29,50.30085681,-2.876150893,10500,0,199.9998535,0,0,0,90.00000001 +278.3,50.30085681,-2.876122868,10500,0,200.0009685,0,0,0,90.00000001 +278.31,50.30085681,-2.876094842,10500,0,200.0009685,0,0,0,90.00000001 +278.32,50.30085681,-2.876066817,10500,0,199.9998535,0,0,0,90.00000001 +278.33,50.30085681,-2.876038792,10500,0,199.9991844,0,0,0,90.00000001 +278.34,50.30085681,-2.876010767,10500,0,199.9998535,0,0,0,90.00000001 +278.35,50.30085681,-2.875982742,10500,0,200.0009685,0,0,0,90.00000001 +278.36,50.30085681,-2.875954716,10500,0,200.0009685,0,0,0,90.00000001 +278.37,50.30085681,-2.875926691,10500,0,199.9998535,0,0,0,90.00000001 +278.38,50.30085681,-2.875898666,10500,0,199.9991844,0,0,0,90.00000001 +278.39,50.30085681,-2.875870641,10500,0,199.9998535,0,0,0,90.00000001 +278.4,50.30085681,-2.875842616,10500,0,200.0009685,0,0,0,90.00000001 +278.41,50.30085681,-2.87581459,10500,0,200.0009685,0,0,0,90.00000001 +278.42,50.30085681,-2.875786565,10500,0,199.9998535,0,0,0,90.00000001 +278.43,50.30085681,-2.87575854,10500,0,199.9991844,0,0,0,90.00000001 +278.44,50.30085681,-2.875730515,10500,0,199.9998535,0,0,0,90.00000001 +278.45,50.30085681,-2.87570249,10500,0,200.0009685,0,0,0,90.00000001 +278.46,50.30085681,-2.875674464,10500,0,200.0009685,0,0,0,90.00000001 +278.47,50.30085681,-2.875646439,10500,0,199.9998535,0,0,0,90.00000001 +278.48,50.30085681,-2.875618414,10500,0,199.9991844,0,0,0,90.00000001 +278.49,50.30085681,-2.875590389,10500,0,199.9998535,0,0,0,90.00000001 +278.5,50.30085681,-2.875562364,10500,0,200.0009685,0,0,0,90.00000001 +278.51,50.30085681,-2.875534338,10500,0,200.0009685,0,0,0,90.00000001 +278.52,50.30085681,-2.875506313,10500,0,199.9998535,0,0,0,90.00000001 +278.53,50.30085681,-2.875478288,10500,0,199.9989614,0,0,0,90.00000001 +278.54,50.30085681,-2.875450263,10500,0,199.9989614,0,0,0,90.00000001 +278.55,50.30085681,-2.875422238,10500,0,199.9998535,0,0,0,90.00000001 +278.56,50.30085681,-2.875394213,10500,0,200.0009685,0,0,0,90.00000001 +278.57,50.30085681,-2.875366187,10500,0,200.0009685,0,0,0,90.00000001 +278.58,50.30085681,-2.875338162,10500,0,199.9998535,0,0,0,90.00000001 +278.59,50.30085681,-2.875310137,10500,0,199.9989614,0,0,0,90.00000001 +278.6,50.30085681,-2.875282112,10500,0,199.9989614,0,0,0,90.00000001 +278.61,50.30085681,-2.875254087,10500,0,199.9998535,0,0,0,90.00000001 +278.62,50.30085681,-2.875226062,10500,0,200.0009685,0,0,0,90.00000001 +278.63,50.30085681,-2.875198036,10500,0,200.0009685,0,0,0,90.00000001 +278.64,50.30085681,-2.875170011,10500,0,199.9998535,0,0,0,90.00000001 +278.65,50.30085681,-2.875141986,10500,0,199.9989614,0,0,0,90.00000001 +278.66,50.30085681,-2.875113961,10500,0,199.9987384,0,0,0,90.00000001 +278.67,50.30085681,-2.875085936,10500,0,199.9989614,0,0,0,90.00000001 +278.68,50.30085681,-2.875057911,10500,0,199.9998535,0,0,0,90.00000001 +278.69,50.30085681,-2.875029886,10500,0,200.0009685,0,0,0,90.00000001 +278.7,50.30085681,-2.87500186,10500,0,200.0009685,0,0,0,90.00000001 +278.71,50.30085681,-2.874973835,10500,0,199.9998535,0,0,0,90.00000001 +278.72,50.30085681,-2.87494581,10500,0,199.9989614,0,0,0,90.00000001 +278.73,50.30085681,-2.874917785,10500,0,199.9989614,0,0,0,90.00000001 +278.74,50.30085681,-2.87488976,10500,0,199.9998535,0,0,0,90.00000001 +278.75,50.30085681,-2.874861735,10500,0,200.0009685,0,0,0,90.00000001 +278.76,50.30085681,-2.874833709,10500,0,200.0009685,0,0,0,90.00000001 +278.77,50.30085681,-2.874805684,10500,0,199.9998535,0,0,0,90.00000001 +278.78,50.30085681,-2.874777659,10500,0,199.9989614,0,0,0,90.00000001 +278.79,50.30085681,-2.874749634,10500,0,199.9989614,0,0,0,90.00000001 +278.8,50.30085681,-2.874721609,10500,0,199.9998535,0,0,0,90.00000001 +278.81,50.30085681,-2.874693584,10500,0,200.0009685,0,0,0,90.00000001 +278.82,50.30085681,-2.874665558,10500,0,200.0009685,0,0,0,90.00000001 +278.83,50.30085681,-2.874637533,10500,0,199.9998535,0,0,0,90.00000001 +278.84,50.30085681,-2.874609508,10500,0,199.9989614,0,0,0,90.00000001 +278.85,50.30085681,-2.874581483,10500,0,199.9989614,0,0,0,90.00000001 +278.86,50.30085681,-2.874553458,10500,0,199.9998535,0,0,0,90.00000001 +278.87,50.30085681,-2.874525433,10500,0,200.0009685,0,0,0,90.00000001 +278.88,50.30085681,-2.874497407,10500,0,200.0009685,0,0,0,90.00000001 +278.89,50.30085681,-2.874469382,10500,0,199.9998535,0,0,0,90.00000001 +278.9,50.30085681,-2.874441357,10500,0,199.9991844,0,0,0,90.00000001 +278.91,50.30085681,-2.874413332,10500,0,199.9998535,0,0,0,90.00000001 +278.92,50.30085681,-2.874385307,10500,0,200.0009685,0,0,0,90.00000001 +278.93,50.30085681,-2.874357281,10500,0,200.0009685,0,0,0,90.00000001 +278.94,50.30085681,-2.874329256,10500,0,199.9998535,0,0,0,90.00000001 +278.95,50.30085681,-2.874301231,10500,0,199.9991844,0,0,0,90.00000001 +278.96,50.30085681,-2.874273206,10500,0,199.9998535,0,0,0,90.00000001 +278.97,50.30085681,-2.874245181,10500,0,200.0009685,0,0,0,90.00000001 +278.98,50.30085681,-2.874217155,10500,0,200.0009685,0,0,0,90.00000001 +278.99,50.30085681,-2.87418913,10500,0,199.9998535,0,0,0,90.00000001 +279,50.30085681,-2.874161105,10500,0,199.9991844,0,0,0,90.00000001 +279.01,50.30085681,-2.87413308,10500,0,199.9998535,0,0,0,90.00000001 +279.02,50.30085681,-2.874105055,10500,0,200.0009685,0,0,0,90.00000001 +279.03,50.30085681,-2.874077029,10500,0,200.0009685,0,0,0,90.00000001 +279.04,50.30085681,-2.874049004,10500,0,199.9998535,0,0,0,90.00000001 +279.05,50.30085681,-2.874020979,10500,0,199.9991844,0,0,0,90.00000001 +279.06,50.30085681,-2.873992954,10500,0,199.9998535,0,0,0,90.00000001 +279.07,50.30085681,-2.873964929,10500,0,200.0009685,0,0,0,90.00000001 +279.08,50.30085681,-2.873936903,10500,0,200.0009685,0,0,0,90.00000001 +279.09,50.30085681,-2.873908878,10500,0,199.9998535,0,0,0,90.00000001 +279.1,50.30085681,-2.873880853,10500,0,199.9991844,0,0,0,90.00000001 +279.11,50.30085681,-2.873852828,10500,0,199.9998535,0,0,0,90.00000001 +279.12,50.30085681,-2.873824803,10500,0,200.0009685,0,0,0,90.00000001 +279.13,50.30085681,-2.873796777,10500,0,200.0009685,0,0,0,90.00000001 +279.14,50.30085681,-2.873768752,10500,0,199.9998535,0,0,0,90.00000001 +279.15,50.30085681,-2.873740727,10500,0,199.9989614,0,0,0,90.00000001 +279.16,50.30085681,-2.873712702,10500,0,199.9989614,0,0,0,90.00000001 +279.17,50.30085681,-2.873684677,10500,0,199.9998535,0,0,0,90.00000001 +279.18,50.30085681,-2.873656652,10500,0,200.0009685,0,0,0,90.00000001 +279.19,50.30085681,-2.873628626,10500,0,200.0009685,0,0,0,90.00000001 +279.2,50.30085681,-2.873600601,10500,0,199.9998535,0,0,0,90.00000001 +279.21,50.30085681,-2.873572576,10500,0,199.9989614,0,0,0,90.00000001 +279.22,50.30085681,-2.873544551,10500,0,199.9989614,0,0,0,90.00000001 +279.23,50.30085681,-2.873516526,10500,0,199.9998535,0,0,0,90.00000001 +279.24,50.30085681,-2.873488501,10500,0,200.0009685,0,0,0,90.00000001 +279.25,50.30085681,-2.873460475,10500,0,200.0009685,0,0,0,90.00000001 +279.26,50.30085681,-2.87343245,10500,0,199.9998535,0,0,0,90.00000001 +279.27,50.30085681,-2.873404425,10500,0,199.9989614,0,0,0,90.00000001 +279.28,50.30085681,-2.8733764,10500,0,199.9987384,0,0,0,90.00000001 +279.29,50.30085681,-2.873348375,10500,0,199.9989614,0,0,0,90.00000001 +279.3,50.30085681,-2.87332035,10500,0,199.9998535,0,0,0,90.00000001 +279.31,50.30085681,-2.873292325,10500,0,200.0009685,0,0,0,90.00000001 +279.32,50.30085681,-2.873264299,10500,0,200.0009685,0,0,0,90.00000001 +279.33,50.30085681,-2.873236274,10500,0,199.9998535,0,0,0,90.00000001 +279.34,50.30085681,-2.873208249,10500,0,199.9989614,0,0,0,90.00000001 +279.35,50.30085681,-2.873180224,10500,0,199.9989614,0,0,0,90.00000001 +279.36,50.30085681,-2.873152199,10500,0,199.9998535,0,0,0,90.00000001 +279.37,50.30085681,-2.873124174,10500,0,200.0009685,0,0,0,90.00000001 +279.38,50.30085681,-2.873096148,10500,0,200.0009685,0,0,0,90.00000001 +279.39,50.30085681,-2.873068123,10500,0,199.9998535,0,0,0,90.00000001 +279.4,50.30085681,-2.873040098,10500,0,199.9989614,0,0,0,90.00000001 +279.41,50.30085681,-2.873012073,10500,0,199.9989614,0,0,0,90.00000001 +279.42,50.30085681,-2.872984048,10500,0,199.9998535,0,0,0,90.00000001 +279.43,50.30085681,-2.872956023,10500,0,200.0009685,0,0,0,90.00000001 +279.44,50.30085681,-2.872927997,10500,0,200.0009685,0,0,0,90.00000001 +279.45,50.30085681,-2.872899972,10500,0,199.9998535,0,0,0,90.00000001 +279.46,50.30085681,-2.872871947,10500,0,199.9989614,0,0,0,90.00000001 +279.47,50.30085681,-2.872843922,10500,0,199.9989614,0,0,0,90.00000001 +279.48,50.30085681,-2.872815897,10500,0,199.9998535,0,0,0,90.00000001 +279.49,50.30085681,-2.872787872,10500,0,200.0009685,0,0,0,90.00000001 +279.5,50.30085681,-2.872759846,10500,0,200.0009685,0,0,0,90.00000001 +279.51,50.30085681,-2.872731821,10500,0,199.9998535,0,0,0,90.00000001 +279.52,50.30085681,-2.872703796,10500,0,199.9991844,0,0,0,90.00000001 +279.53,50.30085681,-2.872675771,10500,0,199.9998535,0,0,0,90.00000001 +279.54,50.30085681,-2.872647746,10500,0,200.0009685,0,0,0,90.00000001 +279.55,50.30085681,-2.87261972,10500,0,200.0009685,0,0,0,90.00000001 +279.56,50.30085681,-2.872591695,10500,0,199.9998535,0,0,0,90.00000001 +279.57,50.30085681,-2.87256367,10500,0,199.9991844,0,0,0,90.00000001 +279.58,50.30085681,-2.872535645,10500,0,199.9998535,0,0,0,90.00000001 +279.59,50.30085681,-2.87250762,10500,0,200.0009685,0,0,0,90.00000001 +279.6,50.30085681,-2.872479594,10500,0,200.0009685,0,0,0,90.00000001 +279.61,50.30085681,-2.872451569,10500,0,199.9998535,0,0,0,90.00000001 +279.62,50.30085681,-2.872423544,10500,0,199.9991844,0,0,0,90.00000001 +279.63,50.30085681,-2.872395519,10500,0,199.9998535,0,0,0,90.00000001 +279.64,50.30085681,-2.872367494,10500,0,200.0009685,0,0,0,90.00000001 +279.65,50.30085681,-2.872339468,10500,0,200.0009685,0,0,0,90.00000001 +279.66,50.30085681,-2.872311443,10500,0,199.9998535,0,0,0,90.00000001 +279.67,50.30085681,-2.872283418,10500,0,199.9991844,0,0,0,90.00000001 +279.68,50.30085681,-2.872255393,10500,0,199.9998535,0,0,0,90.00000001 +279.69,50.30085681,-2.872227368,10500,0,200.0009685,0,0,0,90.00000001 +279.7,50.30085681,-2.872199342,10500,0,200.0009685,0,0,0,90.00000001 +279.71,50.30085681,-2.872171317,10500,0,199.9998535,0,0,0,90.00000001 +279.72,50.30085681,-2.872143292,10500,0,199.9991844,0,0,0,90.00000001 +279.73,50.30085681,-2.872115267,10500,0,199.9998535,0,0,0,90.00000001 +279.74,50.30085681,-2.872087242,10500,0,200.0009685,0,0,0,90.00000001 +279.75,50.30085681,-2.872059216,10500,0,200.0009685,0,0,0,90.00000001 +279.76,50.30085681,-2.872031191,10500,0,199.9998535,0,0,0,90.00000001 +279.77,50.30085681,-2.872003166,10500,0,199.9989614,0,0,0,90.00000001 +279.78,50.30085681,-2.871975141,10500,0,199.9989614,0,0,0,90.00000001 +279.79,50.30085681,-2.871947116,10500,0,199.9998535,0,0,0,90.00000001 +279.8,50.30085681,-2.871919091,10500,0,200.0009685,0,0,0,90.00000001 +279.81,50.30085681,-2.871891065,10500,0,200.0009685,0,0,0,90.00000001 +279.82,50.30085681,-2.87186304,10500,0,199.9998535,0,0,0,90.00000001 +279.83,50.30085681,-2.871835015,10500,0,199.9989614,0,0,0,90.00000001 +279.84,50.30085681,-2.87180699,10500,0,199.9987384,0,0,0,90.00000001 +279.85,50.30085681,-2.871778965,10500,0,199.9989614,0,0,0,90.00000001 +279.86,50.30085681,-2.87175094,10500,0,199.9998535,0,0,0,90.00000001 +279.87,50.30085681,-2.871722915,10500,0,200.0009685,0,0,0,90.00000001 +279.88,50.30085681,-2.871694889,10500,0,200.0009685,0,0,0,90.00000001 +279.89,50.30085681,-2.871666864,10500,0,199.9998535,0,0,0,90.00000001 +279.9,50.30085681,-2.871638839,10500,0,199.9989614,0,0,0,90.00000001 +279.91,50.30085681,-2.871610814,10500,0,199.9989614,0,0,0,90.00000001 +279.92,50.30085681,-2.871582789,10500,0,199.9998535,0,0,0,90.00000001 +279.93,50.30085681,-2.871554764,10500,0,200.0009685,0,0,0,90.00000001 +279.94,50.30085681,-2.871526738,10500,0,200.0009685,0,0,0,90.00000001 +279.95,50.30085681,-2.871498713,10500,0,199.9998535,0,0,0,90.00000001 +279.96,50.30085681,-2.871470688,10500,0,199.9989614,0,0,0,90.00000001 +279.97,50.30085681,-2.871442663,10500,0,199.9989614,0,0,0,90.00000001 +279.98,50.30085681,-2.871414638,10500,0,199.9998535,0,0,0,90.00000001 +279.99,50.30085681,-2.871386613,10500,0,200.0009685,0,0,0,90.00000001 +280,50.30085681,-2.871358587,10500,0,200.0009685,0,0,0,90.00000001 +280.01,50.30085681,-2.871330562,10500,0,199.9998535,0,0,0,90.00000001 +280.02,50.30085681,-2.871302537,10500,0,199.9989614,0,0,0,90.00000001 +280.03,50.30085681,-2.871274512,10500,0,199.9989614,0,0,0,90.00000001 +280.04,50.30085681,-2.871246487,10500,0,199.9998535,0,0,0,90.00000001 +280.05,50.30085681,-2.871218462,10500,0,200.0009685,0,0,0,90.00000001 +280.06,50.30085681,-2.871190436,10500,0,200.0009685,0,0,0,90.00000001 +280.07,50.30085681,-2.871162411,10500,0,199.9998535,0,0,0,90.00000001 +280.08,50.30085681,-2.871134386,10500,0,199.9989614,0,0,0,90.00000001 +280.09,50.30085681,-2.871106361,10500,0,199.9989614,0,0,0,90.00000001 +280.1,50.30085681,-2.871078336,10500,0,199.9998535,0,0,0,90.00000001 +280.11,50.30085681,-2.871050311,10500,0,200.0009685,0,0,0,90.00000001 +280.12,50.30085681,-2.871022285,10500,0,200.0009685,0,0,0,90.00000001 +280.13,50.30085681,-2.87099426,10500,0,199.9998535,0,0,0,90.00000001 +280.14,50.30085681,-2.870966235,10500,0,199.9991844,0,0,0,90.00000001 +280.15,50.30085681,-2.87093821,10500,0,199.9998535,0,0,0,90.00000001 +280.16,50.30085681,-2.870910185,10500,0,200.0009685,0,0,0,90.00000001 +280.17,50.30085681,-2.870882159,10500,0,200.0009685,0,0,0,90.00000001 +280.18,50.30085681,-2.870854134,10500,0,199.9998535,0,0,0,90.00000001 +280.19,50.30085681,-2.870826109,10500,0,199.9989614,0,0,0,90.00000001 +280.2,50.30085681,-2.870798084,10500,0,199.9989614,0,0,0,90.00000001 +280.21,50.30085681,-2.870770059,10500,0,199.9998535,0,0,0,90.00000001 +280.22,50.30085681,-2.870742034,10500,0,200.0009685,0,0,0,90.00000001 +280.23,50.30085681,-2.870714008,10500,0,200.0009685,0,0,0,90.00000001 +280.24,50.30085681,-2.870685983,10500,0,199.9998535,0,0,0,90.00000001 +280.25,50.30085681,-2.870657958,10500,0,199.9991844,0,0,0,90.00000001 +280.26,50.30085681,-2.870629933,10500,0,199.9998535,0,0,0,90.00000001 +280.27,50.30085681,-2.870601908,10500,0,200.0009685,0,0,0,90.00000001 +280.28,50.30085681,-2.870573882,10500,0,200.0009685,0,0,0,90.00000001 +280.29,50.30085681,-2.870545857,10500,0,199.9998535,0,0,0,90.00000001 +280.3,50.30085681,-2.870517832,10500,0,199.9991844,0,0,0,90.00000001 +280.31,50.30085681,-2.870489807,10500,0,199.9998535,0,0,0,90.00000001 +280.32,50.30085681,-2.870461782,10500,0,200.0009685,0,0,0,90.00000001 +280.33,50.30085681,-2.870433756,10500,0,200.0009685,0,0,0,90.00000001 +280.34,50.30085681,-2.870405731,10500,0,199.9998535,0,0,0,90.00000001 +280.35,50.30085681,-2.870377706,10500,0,199.9991844,0,0,0,90.00000001 +280.36,50.30085681,-2.870349681,10500,0,199.9998535,0,0,0,90.00000001 +280.37,50.30085681,-2.870321656,10500,0,200.0009685,0,0,0,90.00000001 +280.38,50.30085681,-2.87029363,10500,0,200.0009685,0,0,0,90.00000001 +280.39,50.30085681,-2.870265605,10500,0,199.9998535,0,0,0,90.00000001 +280.4,50.30085681,-2.87023758,10500,0,199.9989614,0,0,0,90.00000001 +280.41,50.30085681,-2.870209555,10500,0,199.9989614,0,0,0,90.00000001 +280.42,50.30085681,-2.87018153,10500,0,199.9998535,0,0,0,90.00000001 +280.43,50.30085681,-2.870153505,10500,0,200.0009685,0,0,0,90.00000001 +280.44,50.30085681,-2.870125479,10500,0,200.0009685,0,0,0,90.00000001 +280.45,50.30085681,-2.870097454,10500,0,199.9998535,0,0,0,90.00000001 +280.46,50.30085681,-2.870069429,10500,0,199.9989614,0,0,0,90.00000001 +280.47,50.30085681,-2.870041404,10500,0,199.9989614,0,0,0,90.00000001 +280.48,50.30085681,-2.870013379,10500,0,199.9998535,0,0,0,90.00000001 +280.49,50.30085681,-2.869985354,10500,0,200.0009685,0,0,0,90.00000001 +280.5,50.30085681,-2.869957328,10500,0,200.0009685,0,0,0,90.00000001 +280.51,50.30085681,-2.869929303,10500,0,199.9998535,0,0,0,90.00000001 +280.52,50.30085681,-2.869901278,10500,0,199.9989614,0,0,0,90.00000001 +280.53,50.30085681,-2.869873253,10500,0,199.9989614,0,0,0,90.00000001 +280.54,50.30085681,-2.869845228,10500,0,199.9998535,0,0,0,90.00000001 +280.55,50.30085681,-2.869817203,10500,0,200.0009685,0,0,0,90.00000001 +280.56,50.30085681,-2.869789177,10500,0,200.0009685,0,0,0,90.00000001 +280.57,50.30085681,-2.869761152,10500,0,199.9998535,0,0,0,90.00000001 +280.58,50.30085681,-2.869733127,10500,0,199.9989614,0,0,0,90.00000001 +280.59,50.30085681,-2.869705102,10500,0,199.9989614,0,0,0,90.00000001 +280.6,50.30085681,-2.869677077,10500,0,199.9998535,0,0,0,90.00000001 +280.61,50.30085681,-2.869649052,10500,0,200.0009685,0,0,0,90.00000001 +280.62,50.30085681,-2.869621026,10500,0,200.0009685,0,0,0,90.00000001 +280.63,50.30085681,-2.869593001,10500,0,199.9998535,0,0,0,90.00000001 +280.64,50.30085681,-2.869564976,10500,0,199.9989614,0,0,0,90.00000001 +280.65,50.30085681,-2.869536951,10500,0,199.9989614,0,0,0,90.00000001 +280.66,50.30085681,-2.869508926,10500,0,199.9998535,0,0,0,90.00000001 +280.67,50.30085681,-2.869480901,10500,0,200.0009685,0,0,0,90.00000001 +280.68,50.30085681,-2.869452875,10500,0,200.0009685,0,0,0,90.00000001 +280.69,50.30085681,-2.86942485,10500,0,199.9998535,0,0,0,90.00000001 +280.7,50.30085681,-2.869396825,10500,0,199.9989614,0,0,0,90.00000001 +280.71,50.30085681,-2.8693688,10500,0,199.9987384,0,0,0,90.00000001 +280.72,50.30085681,-2.869340775,10500,0,199.9989614,0,0,0,90.00000001 +280.73,50.30085681,-2.86931275,10500,0,199.9998535,0,0,0,90.00000001 +280.74,50.30085681,-2.869284725,10500,0,200.0009685,0,0,0,90.00000001 +280.75,50.30085681,-2.869256699,10500,0,200.0009685,0,0,0,90.00000001 +280.76,50.30085681,-2.869228674,10500,0,199.9998535,0,0,0,90.00000001 +280.77,50.30085681,-2.869200649,10500,0,199.9991844,0,0,0,90.00000001 +280.78,50.30085681,-2.869172624,10500,0,199.9998535,0,0,0,90.00000001 +280.79,50.30085681,-2.869144599,10500,0,200.0009685,0,0,0,90.00000001 +280.8,50.30085681,-2.869116573,10500,0,200.0009685,0,0,0,90.00000001 +280.81,50.30085681,-2.869088548,10500,0,199.9998535,0,0,0,90.00000001 +280.82,50.30085681,-2.869060523,10500,0,199.9991844,0,0,0,90.00000001 +280.83,50.30085681,-2.869032498,10500,0,199.9998535,0,0,0,90.00000001 +280.84,50.30085681,-2.869004473,10500,0,200.0009685,0,0,0,90.00000001 +280.85,50.30085681,-2.868976447,10500,0,200.0009685,0,0,0,90.00000001 +280.86,50.30085681,-2.868948422,10500,0,199.9998535,0,0,0,90.00000001 +280.87,50.30085681,-2.868920397,10500,0,199.9991844,0,0,0,90.00000001 +280.88,50.30085681,-2.868892372,10500,0,199.9998535,0,0,0,90.00000001 +280.89,50.30085681,-2.868864347,10500,0,200.0009685,0,0,0,90.00000001 +280.9,50.30085681,-2.868836321,10500,0,200.0009685,0,0,0,90.00000001 +280.91,50.30085681,-2.868808296,10500,0,199.9998535,0,0,0,90.00000001 +280.92,50.30085681,-2.868780271,10500,0,199.9991844,0,0,0,90.00000001 +280.93,50.30085681,-2.868752246,10500,0,199.9998535,0,0,0,90.00000001 +280.94,50.30085681,-2.868724221,10500,0,200.0009685,0,0,0,90.00000001 +280.95,50.30085681,-2.868696195,10500,0,200.0009685,0,0,0,90.00000001 +280.96,50.30085681,-2.86866817,10500,0,199.9998535,0,0,0,90.00000001 +280.97,50.30085681,-2.868640145,10500,0,199.9991844,0,0,0,90.00000001 +280.98,50.30085681,-2.86861212,10500,0,199.9998535,0,0,0,90.00000001 +280.99,50.30085681,-2.868584095,10500,0,200.0009685,0,0,0,90.00000001 +281,50.30085681,-2.868556069,10500,0,200.0009685,0,0,0,90.00000001 +281.01,50.30085681,-2.868528044,10500,0,199.9998535,0,0,0,90.00000001 +281.02,50.30085681,-2.868500019,10500,0,199.9989614,0,0,0,90.00000001 +281.03,50.30085681,-2.868471994,10500,0,199.9989614,0,0,0,90.00000001 +281.04,50.30085681,-2.868443969,10500,0,199.9998535,0,0,0,90.00000001 +281.05,50.30085681,-2.868415944,10500,0,200.0009685,0,0,0,90.00000001 +281.06,50.30085681,-2.868387918,10500,0,200.0009685,0,0,0,90.00000001 +281.07,50.30085681,-2.868359893,10500,0,199.9998535,0,0,0,90.00000001 +281.08,50.30085681,-2.868331868,10500,0,199.9989614,0,0,0,90.00000001 +281.09,50.30085681,-2.868303843,10500,0,199.9989614,0,0,0,90.00000001 +281.1,50.30085681,-2.868275818,10500,0,199.9998535,0,0,0,90.00000001 +281.11,50.30085681,-2.868247793,10500,0,200.0009685,0,0,0,90.00000001 +281.12,50.30085681,-2.868219767,10500,0,200.0009685,0,0,0,90.00000001 +281.13,50.30085681,-2.868191742,10500,0,199.9998535,0,0,0,90.00000001 +281.14,50.30085681,-2.868163717,10500,0,199.9989614,0,0,0,90.00000001 +281.15,50.30085681,-2.868135692,10500,0,199.9989614,0,0,0,90.00000001 +281.16,50.30085681,-2.868107667,10500,0,199.9998535,0,0,0,90.00000001 +281.17,50.30085681,-2.868079642,10500,0,200.0009685,0,0,0,90.00000001 +281.18,50.30085681,-2.868051616,10500,0,200.0009685,0,0,0,90.00000001 +281.19,50.30085681,-2.868023591,10500,0,199.9998535,0,0,0,90.00000001 +281.2,50.30085681,-2.867995566,10500,0,199.9989614,0,0,0,90.00000001 +281.21,50.30085681,-2.867967541,10500,0,199.9989614,0,0,0,90.00000001 +281.22,50.30085681,-2.867939516,10500,0,199.9998535,0,0,0,90.00000001 +281.23,50.30085681,-2.867911491,10500,0,200.0009685,0,0,0,90.00000001 +281.24,50.30085681,-2.867883465,10500,0,200.0009685,0,0,0,90.00000001 +281.25,50.30085681,-2.86785544,10500,0,199.9998535,0,0,0,90.00000001 +281.26,50.30085681,-2.867827415,10500,0,199.9989614,0,0,0,90.00000001 +281.27,50.30085681,-2.86779939,10500,0,199.9987384,0,0,0,90.00000001 +281.28,50.30085681,-2.867771365,10500,0,199.9989614,0,0,0,90.00000001 +281.29,50.30085681,-2.86774334,10500,0,199.9998535,0,0,0,90.00000001 +281.3,50.30085681,-2.867715315,10500,0,200.0009685,0,0,0,90.00000001 +281.31,50.30085681,-2.867687289,10500,0,200.0009685,0,0,0,90.00000001 +281.32,50.30085681,-2.867659264,10500,0,199.9998535,0,0,0,90.00000001 +281.33,50.30085681,-2.867631239,10500,0,199.9989614,0,0,0,90.00000001 +281.34,50.30085681,-2.867603214,10500,0,199.9989614,0,0,0,90.00000001 +281.35,50.30085681,-2.867575189,10500,0,199.9998535,0,0,0,90.00000001 +281.36,50.30085681,-2.867547164,10500,0,200.0009685,0,0,0,90.00000001 +281.37,50.30085681,-2.867519138,10500,0,200.0009685,0,0,0,90.00000001 +281.38,50.30085681,-2.867491113,10500,0,199.9998535,0,0,0,90.00000001 +281.39,50.30085681,-2.867463088,10500,0,199.9991844,0,0,0,90.00000001 +281.4,50.30085681,-2.867435063,10500,0,199.9998535,0,0,0,90.00000001 +281.41,50.30085681,-2.867407038,10500,0,200.0009685,0,0,0,90.00000001 +281.42,50.30085681,-2.867379012,10500,0,200.0009685,0,0,0,90.00000001 +281.43,50.30085681,-2.867350987,10500,0,199.9998535,0,0,0,90.00000001 +281.44,50.30085681,-2.867322962,10500,0,199.9991844,0,0,0,90.00000001 +281.45,50.30085681,-2.867294937,10500,0,199.9998535,0,0,0,90.00000001 +281.46,50.30085681,-2.867266912,10500,0,200.0009685,0,0,0,90.00000001 +281.47,50.30085681,-2.867238886,10500,0,200.0009685,0,0,0,90.00000001 +281.48,50.30085681,-2.867210861,10500,0,199.9998535,0,0,0,90.00000001 +281.49,50.30085681,-2.867182836,10500,0,199.9991844,0,0,0,90.00000001 +281.5,50.30085681,-2.867154811,10500,0,199.9998535,0,0,0,90.00000001 +281.51,50.30085681,-2.867126786,10500,0,200.0009685,0,0,0,90.00000001 +281.52,50.30085681,-2.86709876,10500,0,200.0009685,0,0,0,90.00000001 +281.53,50.30085681,-2.867070735,10500,0,199.9998535,0,0,0,90.00000001 +281.54,50.30085681,-2.86704271,10500,0,199.9991844,0,0,0,90.00000001 +281.55,50.30085681,-2.867014685,10500,0,199.9998535,0,0,0,90.00000001 +281.56,50.30085681,-2.86698666,10500,0,200.0009685,0,0,0,90.00000001 +281.57,50.30085681,-2.866958634,10500,0,200.0009685,0,0,0,90.00000001 +281.58,50.30085681,-2.866930609,10500,0,199.9998535,0,0,0,90.00000001 +281.59,50.30085681,-2.866902584,10500,0,199.9991844,0,0,0,90.00000001 +281.6,50.30085681,-2.866874559,10500,0,199.9998535,0,0,0,90.00000001 +281.61,50.30085681,-2.866846534,10500,0,200.0009685,0,0,0,90.00000001 +281.62,50.30085681,-2.866818508,10500,0,200.0009685,0,0,0,90.00000001 +281.63,50.30085681,-2.866790483,10500,0,199.9998535,0,0,0,90.00000001 +281.64,50.30085681,-2.866762458,10500,0,199.9989614,0,0,0,90.00000001 +281.65,50.30085681,-2.866734433,10500,0,199.9989614,0,0,0,90.00000001 +281.66,50.30085681,-2.866706408,10500,0,199.9998535,0,0,0,90.00000001 +281.67,50.30085681,-2.866678383,10500,0,200.0009685,0,0,0,90.00000001 +281.68,50.30085681,-2.866650357,10500,0,200.0009685,0,0,0,90.00000001 +281.69,50.30085681,-2.866622332,10500,0,199.9998535,0,0,0,90.00000001 +281.7,50.30085681,-2.866594307,10500,0,199.9989614,0,0,0,90.00000001 +281.71,50.30085681,-2.866566282,10500,0,199.9989614,0,0,0,90.00000001 +281.72,50.30085681,-2.866538257,10500,0,199.9998535,0,0,0,90.00000001 +281.73,50.30085681,-2.866510232,10500,0,200.0009685,0,0,0,90.00000001 +281.74,50.30085681,-2.866482206,10500,0,200.0009685,0,0,0,90.00000001 +281.75,50.30085681,-2.866454181,10500,0,199.9998535,0,0,0,90.00000001 +281.76,50.30085681,-2.866426156,10500,0,199.9989614,0,0,0,90.00000001 +281.77,50.30085681,-2.866398131,10500,0,199.9989614,0,0,0,90.00000001 +281.78,50.30085681,-2.866370106,10500,0,199.9998535,0,0,0,90.00000001 +281.79,50.30085681,-2.866342081,10500,0,200.0009685,0,0,0,90.00000001 +281.8,50.30085681,-2.866314055,10500,0,200.0009685,0,0,0,90.00000001 +281.81,50.30085681,-2.86628603,10500,0,199.9998535,0,0,0,90.00000001 +281.82,50.30085681,-2.866258005,10500,0,199.9989614,0,0,0,90.00000001 +281.83,50.30085681,-2.86622998,10500,0,199.9987384,0,0,0,90.00000001 +281.84,50.30085681,-2.866201955,10500,0,199.9989614,0,0,0,90.00000001 +281.85,50.30085681,-2.86617393,10500,0,199.9998535,0,0,0,90.00000001 +281.86,50.30085681,-2.866145905,10500,0,200.0009685,0,0,0,90.00000001 +281.87,50.30085681,-2.866117879,10500,0,200.0009685,0,0,0,90.00000001 +281.88,50.30085681,-2.866089854,10500,0,199.9998535,0,0,0,90.00000001 +281.89,50.30085681,-2.866061829,10500,0,199.9989614,0,0,0,90.00000001 +281.9,50.30085681,-2.866033804,10500,0,199.9989614,0,0,0,90.00000001 +281.91,50.30085681,-2.866005779,10500,0,199.9998535,0,0,0,90.00000001 +281.92,50.30085681,-2.865977754,10500,0,200.0009685,0,0,0,90.00000001 +281.93,50.30085681,-2.865949728,10500,0,200.0009685,0,0,0,90.00000001 +281.94,50.30085681,-2.865921703,10500,0,199.9998535,0,0,0,90.00000001 +281.95,50.30085681,-2.865893678,10500,0,199.9989614,0,0,0,90.00000001 +281.96,50.30085681,-2.865865653,10500,0,199.9989614,0,0,0,90.00000001 +281.97,50.30085681,-2.865837628,10500,0,199.9998535,0,0,0,90.00000001 +281.98,50.30085681,-2.865809603,10500,0,200.0009685,0,0,0,90.00000001 +281.99,50.30085681,-2.865781577,10500,0,200.0009685,0,0,0,90.00000001 +282,50.30085681,-2.865753552,10500,0,199.9998535,0,0,0,90.00000001 +282.01,50.30085681,-2.865725527,10500,0,199.9991844,0,0,0,90.00000001 +282.02,50.30085681,-2.865697502,10500,0,199.9998535,0,0,0,90.00000001 +282.03,50.30085681,-2.865669477,10500,0,200.0009685,0,0,0,90.00000001 +282.04,50.30085681,-2.865641451,10500,0,200.0009685,0,0,0,90.00000001 +282.05,50.30085681,-2.865613426,10500,0,199.9998535,0,0,0,90.00000001 +282.06,50.30085681,-2.865585401,10500,0,199.9991844,0,0,0,90.00000001 +282.07,50.30085681,-2.865557376,10500,0,199.9998535,0,0,0,90.00000001 +282.08,50.30085681,-2.865529351,10500,0,200.0009685,0,0,0,90.00000001 +282.09,50.30085681,-2.865501325,10500,0,200.0009685,0,0,0,90.00000001 +282.1,50.30085681,-2.8654733,10500,0,199.9998535,0,0,0,90.00000001 +282.11,50.30085681,-2.865445275,10500,0,199.9991844,0,0,0,90.00000001 +282.12,50.30085681,-2.86541725,10500,0,199.9998535,0,0,0,90.00000001 +282.13,50.30085681,-2.865389225,10500,0,200.0009685,0,0,0,90.00000001 +282.14,50.30085681,-2.865361199,10500,0,200.0009685,0,0,0,90.00000001 +282.15,50.30085681,-2.865333174,10500,0,199.9998535,0,0,0,90.00000001 +282.16,50.30085681,-2.865305149,10500,0,199.9991844,0,0,0,90.00000001 +282.17,50.30085681,-2.865277124,10500,0,199.9998535,0,0,0,90.00000001 +282.18,50.30085681,-2.865249099,10500,0,200.0009685,0,0,0,90.00000001 +282.19,50.30085681,-2.865221073,10500,0,200.0009685,0,0,0,90.00000001 +282.2,50.30085681,-2.865193048,10500,0,199.9998535,0,0,0,90.00000001 +282.21,50.30085681,-2.865165023,10500,0,199.9991844,0,0,0,90.00000001 +282.22,50.30085681,-2.865136998,10500,0,199.9998535,0,0,0,90.00000001 +282.23,50.30085681,-2.865108973,10500,0,200.0009685,0,0,0,90.00000001 +282.24,50.30085681,-2.865080947,10500,0,200.0009685,0,0,0,90.00000001 +282.25,50.30085681,-2.865052922,10500,0,199.9998535,0,0,0,90.00000001 +282.26,50.30085681,-2.865024897,10500,0,199.9989614,0,0,0,90.00000001 +282.27,50.30085681,-2.864996872,10500,0,199.9989614,0,0,0,90.00000001 +282.28,50.30085681,-2.864968847,10500,0,199.9998535,0,0,0,90.00000001 +282.29,50.30085681,-2.864940822,10500,0,200.0009685,0,0,0,90.00000001 +282.3,50.30085681,-2.864912796,10500,0,200.0009685,0,0,0,90.00000001 +282.31,50.30085681,-2.864884771,10500,0,199.9998535,0,0,0,90.00000001 +282.32,50.30085681,-2.864856746,10500,0,199.9989614,0,0,0,90.00000001 +282.33,50.30085681,-2.864828721,10500,0,199.9989614,0,0,0,90.00000001 +282.34,50.30085681,-2.864800696,10500,0,199.9998535,0,0,0,90.00000001 +282.35,50.30085681,-2.864772671,10500,0,200.0009685,0,0,0,90.00000001 +282.36,50.30085681,-2.864744645,10500,0,200.0009685,0,0,0,90.00000001 +282.37,50.30085681,-2.86471662,10500,0,199.9998535,0,0,0,90.00000001 +282.38,50.30085681,-2.864688595,10500,0,199.9989614,0,0,0,90.00000001 +282.39,50.30085681,-2.86466057,10500,0,199.9987384,0,0,0,90.00000001 +282.4,50.30085681,-2.864632545,10500,0,199.9989614,0,0,0,90.00000001 +282.41,50.30085681,-2.86460452,10500,0,199.9998535,0,0,0,90.00000001 +282.42,50.30085681,-2.864576495,10500,0,200.0009685,0,0,0,90.00000001 +282.43,50.30085681,-2.864548469,10500,0,200.0009685,0,0,0,90.00000001 +282.44,50.30085681,-2.864520444,10500,0,199.9998535,0,0,0,90.00000001 +282.45,50.30085681,-2.864492419,10500,0,199.9989614,0,0,0,90.00000001 +282.46,50.30085681,-2.864464394,10500,0,199.9989614,0,0,0,90.00000001 +282.47,50.30085681,-2.864436369,10500,0,199.9998535,0,0,0,90.00000001 +282.48,50.30085681,-2.864408344,10500,0,200.0009685,0,0,0,90.00000001 +282.49,50.30085681,-2.864380318,10500,0,200.0009685,0,0,0,90.00000001 +282.5,50.30085681,-2.864352293,10500,0,199.9998535,0,0,0,90.00000001 +282.51,50.30085681,-2.864324268,10500,0,199.9989614,0,0,0,90.00000001 +282.52,50.30085681,-2.864296243,10500,0,199.9989614,0,0,0,90.00000001 +282.53,50.30085681,-2.864268218,10500,0,199.9998535,0,0,0,90.00000001 +282.54,50.30085681,-2.864240193,10500,0,200.0009685,0,0,0,90.00000001 +282.55,50.30085681,-2.864212167,10500,0,200.0009685,0,0,0,90.00000001 +282.56,50.30085681,-2.864184142,10500,0,199.9998535,0,0,0,90.00000001 +282.57,50.30085681,-2.864156117,10500,0,199.9989614,0,0,0,90.00000001 +282.58,50.30085681,-2.864128092,10500,0,199.9989614,0,0,0,90.00000001 +282.59,50.30085681,-2.864100067,10500,0,199.9998535,0,0,0,90.00000001 +282.6,50.30085681,-2.864072042,10500,0,200.0009685,0,0,0,90.00000001 +282.61,50.30085681,-2.864044016,10500,0,200.0009685,0,0,0,90.00000001 +282.62,50.30085681,-2.864015991,10500,0,199.9998535,0,0,0,90.00000001 +282.63,50.30085681,-2.863987966,10500,0,199.9989614,0,0,0,90.00000001 +282.64,50.30085681,-2.863959941,10500,0,199.9989614,0,0,0,90.00000001 +282.65,50.30085681,-2.863931916,10500,0,199.9998535,0,0,0,90.00000001 +282.66,50.30085681,-2.863903891,10500,0,200.0009685,0,0,0,90.00000001 +282.67,50.30085681,-2.863875865,10500,0,200.0009685,0,0,0,90.00000001 +282.68,50.30085681,-2.86384784,10500,0,199.9998535,0,0,0,90.00000001 +282.69,50.30085681,-2.863819815,10500,0,199.9991844,0,0,0,90.00000001 +282.7,50.30085681,-2.86379179,10500,0,199.9998535,0,0,0,90.00000001 +282.71,50.30085681,-2.863763765,10500,0,200.0009685,0,0,0,90.00000001 +282.72,50.30085681,-2.863735739,10500,0,200.0009685,0,0,0,90.00000001 +282.73,50.30085681,-2.863707714,10500,0,199.9998535,0,0,0,90.00000001 +282.74,50.30085681,-2.863679689,10500,0,199.9991844,0,0,0,90.00000001 +282.75,50.30085681,-2.863651664,10500,0,199.9998535,0,0,0,90.00000001 +282.76,50.30085681,-2.863623639,10500,0,200.0009685,0,0,0,90.00000001 +282.77,50.30085681,-2.863595613,10500,0,200.0009685,0,0,0,90.00000001 +282.78,50.30085681,-2.863567588,10500,0,199.9998535,0,0,0,90.00000001 +282.79,50.30085681,-2.863539563,10500,0,199.9991844,0,0,0,90.00000001 +282.8,50.30085681,-2.863511538,10500,0,199.9998535,0,0,0,90.00000001 +282.81,50.30085681,-2.863483513,10500,0,200.0009685,0,0,0,90.00000001 +282.82,50.30085681,-2.863455487,10500,0,200.0009685,0,0,0,90.00000001 +282.83,50.30085681,-2.863427462,10500,0,199.9998535,0,0,0,90.00000001 +282.84,50.30085681,-2.863399437,10500,0,199.9991844,0,0,0,90.00000001 +282.85,50.30085681,-2.863371412,10500,0,199.9998535,0,0,0,90.00000001 +282.86,50.30085681,-2.863343387,10500,0,200.0009685,0,0,0,90.00000001 +282.87,50.30085681,-2.863315361,10500,0,200.0009685,0,0,0,90.00000001 +282.88,50.30085681,-2.863287336,10500,0,199.9998535,0,0,0,90.00000001 +282.89,50.30085681,-2.863259311,10500,0,199.9991844,0,0,0,90.00000001 +282.9,50.30085681,-2.863231286,10500,0,199.9998535,0,0,0,90.00000001 +282.91,50.30085681,-2.863203261,10500,0,200.0009685,0,0,0,90.00000001 +282.92,50.30085681,-2.863175235,10500,0,200.0009685,0,0,0,90.00000001 +282.93,50.30085681,-2.86314721,10500,0,199.9998535,0,0,0,90.00000001 +282.94,50.30085681,-2.863119185,10500,0,199.9989614,0,0,0,90.00000001 +282.95,50.30085681,-2.86309116,10500,0,199.9987384,0,0,0,90.00000001 +282.96,50.30085681,-2.863063135,10500,0,199.9989614,0,0,0,90.00000001 +282.97,50.30085681,-2.86303511,10500,0,199.9998535,0,0,0,90.00000001 +282.98,50.30085681,-2.863007085,10500,0,200.0009685,0,0,0,90.00000001 +282.99,50.30085681,-2.862979059,10500,0,200.0009685,0,0,0,90.00000001 +283,50.30085681,-2.862951034,10500,0,199.9998535,0,0,0,90.00000001 +283.01,50.30085681,-2.862923009,10500,0,199.9989614,0,0,0,90.00000001 +283.02,50.30085681,-2.862894984,10500,0,199.9989614,0,0,0,90.00000001 +283.03,50.30085681,-2.862866959,10500,0,199.9998535,0,0,0,90.00000001 +283.04,50.30085681,-2.862838934,10500,0,200.0009685,0,0,0,90.00000001 +283.05,50.30085681,-2.862810908,10500,0,200.0009685,0,0,0,90.00000001 +283.06,50.30085681,-2.862782883,10500,0,199.9998535,0,0,0,90.00000001 +283.07,50.30085681,-2.862754858,10500,0,199.9989614,0,0,0,90.00000001 +283.08,50.30085681,-2.862726833,10500,0,199.9989614,0,0,0,90.00000001 +283.09,50.30085681,-2.862698808,10500,0,199.9998535,0,0,0,90.00000001 +283.1,50.30085681,-2.862670783,10500,0,200.0009685,0,0,0,90.00000001 +283.11,50.30085681,-2.862642757,10500,0,200.0009685,0,0,0,90.00000001 +283.12,50.30085681,-2.862614732,10500,0,199.9998535,0,0,0,90.00000001 +283.13,50.30085681,-2.862586707,10500,0,199.9989614,0,0,0,90.00000001 +283.14,50.30085681,-2.862558682,10500,0,199.9989614,0,0,0,90.00000001 +283.15,50.30085681,-2.862530657,10500,0,199.9998535,0,0,0,90.00000001 +283.16,50.30085681,-2.862502632,10500,0,200.0009685,0,0,0,90.00000001 +283.17,50.30085681,-2.862474606,10500,0,200.0009685,0,0,0,90.00000001 +283.18,50.30085681,-2.862446581,10500,0,199.9998535,0,0,0,90.00000001 +283.19,50.30085681,-2.862418556,10500,0,199.9989614,0,0,0,90.00000001 +283.2,50.30085681,-2.862390531,10500,0,199.9989614,0,0,0,90.00000001 +283.21,50.30085681,-2.862362506,10500,0,199.9998535,0,0,0,90.00000001 +283.22,50.30085681,-2.862334481,10500,0,200.0009685,0,0,0,90.00000001 +283.23,50.30085681,-2.862306455,10500,0,200.0009685,0,0,0,90.00000001 +283.24,50.30085681,-2.86227843,10500,0,199.9998535,0,0,0,90.00000001 +283.25,50.30085681,-2.862250405,10500,0,199.9989614,0,0,0,90.00000001 +283.26,50.30085681,-2.86222238,10500,0,199.9989614,0,0,0,90.00000001 +283.27,50.30085681,-2.862194355,10500,0,199.9998535,0,0,0,90.00000001 +283.28,50.30085681,-2.86216633,10500,0,200.0009685,0,0,0,90.00000001 +283.29,50.30085681,-2.862138304,10500,0,200.0009685,0,0,0,90.00000001 +283.3,50.30085681,-2.862110279,10500,0,199.9998535,0,0,0,90.00000001 +283.31,50.30085681,-2.862082254,10500,0,199.9991844,0,0,0,90.00000001 +283.32,50.30085681,-2.862054229,10500,0,199.9998535,0,0,0,90.00000001 +283.33,50.30085681,-2.862026204,10500,0,200.0009685,0,0,0,90.00000001 +283.34,50.30085681,-2.861998178,10500,0,200.0009685,0,0,0,90.00000001 +283.35,50.30085681,-2.861970153,10500,0,199.9998535,0,0,0,90.00000001 +283.36,50.30085681,-2.861942128,10500,0,199.9991844,0,0,0,90.00000001 +283.37,50.30085681,-2.861914103,10500,0,199.9998535,0,0,0,90.00000001 +283.38,50.30085681,-2.861886078,10500,0,200.0009685,0,0,0,90.00000001 +283.39,50.30085681,-2.861858052,10500,0,200.0009685,0,0,0,90.00000001 +283.4,50.30085681,-2.861830027,10500,0,199.9998535,0,0,0,90.00000001 +283.41,50.30085681,-2.861802002,10500,0,199.9991844,0,0,0,90.00000001 +283.42,50.30085681,-2.861773977,10500,0,199.9998535,0,0,0,90.00000001 +283.43,50.30085681,-2.861745952,10500,0,200.0009685,0,0,0,90.00000001 +283.44,50.30085681,-2.861717926,10500,0,200.0009685,0,0,0,90.00000001 +283.45,50.30085681,-2.861689901,10500,0,199.9998535,0,0,0,90.00000001 +283.46,50.30085681,-2.861661876,10500,0,199.9991844,0,0,0,90.00000001 +283.47,50.30085681,-2.861633851,10500,0,199.9998535,0,0,0,90.00000001 +283.48,50.30085681,-2.861605826,10500,0,200.0009685,0,0,0,90.00000001 +283.49,50.30085681,-2.8615778,10500,0,200.0009685,0,0,0,90.00000001 +283.5,50.30085681,-2.861549775,10500,0,199.9998535,0,0,0,90.00000001 +283.51,50.30085681,-2.86152175,10500,0,199.9991844,0,0,0,90.00000001 +283.52,50.30085681,-2.861493725,10500,0,199.9998535,0,0,0,90.00000001 +283.53,50.30085681,-2.8614657,10500,0,200.0009685,0,0,0,90.00000001 +283.54,50.30085681,-2.861437674,10500,0,200.0009685,0,0,0,90.00000001 +283.55,50.30085681,-2.861409649,10500,0,199.9998535,0,0,0,90.00000001 +283.56,50.30085681,-2.861381624,10500,0,199.9989614,0,0,0,90.00000001 +283.57,50.30085681,-2.861353599,10500,0,199.9987384,0,0,0,90.00000001 +283.58,50.30085681,-2.861325574,10500,0,199.9989614,0,0,0,90.00000001 +283.59,50.30085681,-2.861297549,10500,0,199.9998535,0,0,0,90.00000001 +283.6,50.30085681,-2.861269524,10500,0,200.0009685,0,0,0,90.00000001 +283.61,50.30085681,-2.861241498,10500,0,200.0009685,0,0,0,90.00000001 +283.62,50.30085681,-2.861213473,10500,0,199.9998535,0,0,0,90.00000001 +283.63,50.30085681,-2.861185448,10500,0,199.9989614,0,0,0,90.00000001 +283.64,50.30085681,-2.861157423,10500,0,199.9989614,0,0,0,90.00000001 +283.65,50.30085681,-2.861129398,10500,0,199.9998535,0,0,0,90.00000001 +283.66,50.30085681,-2.861101373,10500,0,200.0009685,0,0,0,90.00000001 +283.67,50.30085681,-2.861073347,10500,0,200.0009685,0,0,0,90.00000001 +283.68,50.30085681,-2.861045322,10500,0,199.9998535,0,0,0,90.00000001 +283.69,50.30085681,-2.861017297,10500,0,199.9989614,0,0,0,90.00000001 +283.7,50.30085681,-2.860989272,10500,0,199.9989614,0,0,0,90.00000001 +283.71,50.30085681,-2.860961247,10500,0,199.9998535,0,0,0,90.00000001 +283.72,50.30085681,-2.860933222,10500,0,200.0009685,0,0,0,90.00000001 +283.73,50.30085681,-2.860905196,10500,0,200.0009685,0,0,0,90.00000001 +283.74,50.30085681,-2.860877171,10500,0,199.9998535,0,0,0,90.00000001 +283.75,50.30085681,-2.860849146,10500,0,199.9989614,0,0,0,90.00000001 +283.76,50.30085681,-2.860821121,10500,0,199.9989614,0,0,0,90.00000001 +283.77,50.30085681,-2.860793096,10500,0,199.9998535,0,0,0,90.00000001 +283.78,50.30085681,-2.860765071,10500,0,200.0009685,0,0,0,90.00000001 +283.79,50.30085681,-2.860737045,10500,0,200.0009685,0,0,0,90.00000001 +283.8,50.30085681,-2.86070902,10500,0,199.9998535,0,0,0,90.00000001 +283.81,50.30085681,-2.860680995,10500,0,199.9989614,0,0,0,90.00000001 +283.82,50.30085681,-2.86065297,10500,0,199.9987384,0,0,0,90.00000001 +283.83,50.30085681,-2.860624945,10500,0,199.9989614,0,0,0,90.00000001 +283.84,50.30085681,-2.86059692,10500,0,199.9998535,0,0,0,90.00000001 +283.85,50.30085681,-2.860568895,10500,0,200.0009685,0,0,0,90.00000001 +283.86,50.30085681,-2.860540869,10500,0,200.0009685,0,0,0,90.00000001 +283.87,50.30085681,-2.860512844,10500,0,199.9998535,0,0,0,90.00000001 +283.88,50.30085681,-2.860484819,10500,0,199.9991844,0,0,0,90.00000001 +283.89,50.30085681,-2.860456794,10500,0,199.9998535,0,0,0,90.00000001 +283.9,50.30085681,-2.860428769,10500,0,200.0009685,0,0,0,90.00000001 +283.91,50.30085681,-2.860400743,10500,0,200.0009685,0,0,0,90.00000001 +283.92,50.30085681,-2.860372718,10500,0,199.9998535,0,0,0,90.00000001 +283.93,50.30085681,-2.860344693,10500,0,199.9991844,0,0,0,90.00000001 +283.94,50.30085681,-2.860316668,10500,0,199.9998535,0,0,0,90.00000001 +283.95,50.30085681,-2.860288643,10500,0,200.0009685,0,0,0,90.00000001 +283.96,50.30085681,-2.860260617,10500,0,200.0009685,0,0,0,90.00000001 +283.97,50.30085681,-2.860232592,10500,0,199.9998535,0,0,0,90.00000001 +283.98,50.30085681,-2.860204567,10500,0,199.9991844,0,0,0,90.00000001 +283.99,50.30085681,-2.860176542,10500,0,199.9998535,0,0,0,90.00000001 +284,50.30085681,-2.860148517,10500,0,200.0009685,0,0,0,90.00000001 +284.01,50.30085681,-2.860120491,10500,0,200.0009685,0,0,0,90.00000001 +284.02,50.30085681,-2.860092466,10500,0,199.9998535,0,0,0,90.00000001 +284.03,50.30085681,-2.860064441,10500,0,199.9991844,0,0,0,90.00000001 +284.04,50.30085681,-2.860036416,10500,0,199.9998535,0,0,0,90.00000001 +284.05,50.30085681,-2.860008391,10500,0,200.0009685,0,0,0,90.00000001 +284.06,50.30085681,-2.859980365,10500,0,200.0009685,0,0,0,90.00000001 +284.07,50.30085681,-2.85995234,10500,0,199.9998535,0,0,0,90.00000001 +284.08,50.30085681,-2.859924315,10500,0,199.9991844,0,0,0,90.00000001 +284.09,50.30085681,-2.85989629,10500,0,199.9998535,0,0,0,90.00000001 +284.1,50.30085681,-2.859868265,10500,0,200.0009685,0,0,0,90.00000001 +284.11,50.30085681,-2.859840239,10500,0,200.0009685,0,0,0,90.00000001 +284.12,50.30085681,-2.859812214,10500,0,199.9998535,0,0,0,90.00000001 +284.13,50.30085681,-2.859784189,10500,0,199.9989614,0,0,0,90.00000001 +284.14,50.30085681,-2.859756164,10500,0,199.9989614,0,0,0,90.00000001 +284.15,50.30085681,-2.859728139,10500,0,199.9998535,0,0,0,90.00000001 +284.16,50.30085681,-2.859700114,10500,0,200.0009685,0,0,0,90.00000001 +284.17,50.30085681,-2.859672088,10500,0,200.0009685,0,0,0,90.00000001 +284.18,50.30085681,-2.859644063,10500,0,199.9998535,0,0,0,90.00000001 +284.19,50.30085681,-2.859616038,10500,0,199.9989614,0,0,0,90.00000001 +284.2,50.30085681,-2.859588013,10500,0,199.9989614,0,0,0,90.00000001 +284.21,50.30085681,-2.859559988,10500,0,199.9998535,0,0,0,90.00000001 +284.22,50.30085681,-2.859531963,10500,0,200.0009685,0,0,0,90.00000001 +284.23,50.30085681,-2.859503937,10500,0,200.0009685,0,0,0,90.00000001 +284.24,50.30085681,-2.859475912,10500,0,199.9998535,0,0,0,90.00000001 +284.25,50.30085681,-2.859447887,10500,0,199.9989614,0,0,0,90.00000001 +284.26,50.30085681,-2.859419862,10500,0,199.9989614,0,0,0,90.00000001 +284.27,50.30085681,-2.859391837,10500,0,199.9998535,0,0,0,90.00000001 +284.28,50.30085681,-2.859363812,10500,0,200.0009685,0,0,0,90.00000001 +284.29,50.30085681,-2.859335786,10500,0,200.0009685,0,0,0,90.00000001 +284.3,50.30085681,-2.859307761,10500,0,199.9998535,0,0,0,90.00000001 +284.31,50.30085681,-2.859279736,10500,0,199.9989614,0,0,0,90.00000001 +284.32,50.30085681,-2.859251711,10500,0,199.9989614,0,0,0,90.00000001 +284.33,50.30085681,-2.859223686,10500,0,199.9998535,0,0,0,90.00000001 +284.34,50.30085681,-2.859195661,10500,0,200.0009685,0,0,0,90.00000001 +284.35,50.30085681,-2.859167635,10500,0,200.0009685,0,0,0,90.00000001 +284.36,50.30085681,-2.85913961,10500,0,199.9998535,0,0,0,90.00000001 +284.37,50.30085681,-2.859111585,10500,0,199.9989614,0,0,0,90.00000001 +284.38,50.30085681,-2.85908356,10500,0,199.9987384,0,0,0,90.00000001 +284.39,50.30085681,-2.859055535,10500,0,199.9989614,0,0,0,90.00000001 +284.4,50.30085681,-2.85902751,10500,0,199.9998535,0,0,0,90.00000001 +284.41,50.30085681,-2.858999485,10500,0,200.0009685,0,0,0,90.00000001 +284.42,50.30085681,-2.858971459,10500,0,200.0009685,0,0,0,90.00000001 +284.43,50.30085681,-2.858943434,10500,0,199.9998535,0,0,0,90.00000001 +284.44,50.30085681,-2.858915409,10500,0,199.9989614,0,0,0,90.00000001 +284.45,50.30085681,-2.858887384,10500,0,199.9989614,0,0,0,90.00000001 +284.46,50.30085681,-2.858859359,10500,0,199.9998535,0,0,0,90.00000001 +284.47,50.30085681,-2.858831334,10500,0,200.0009685,0,0,0,90.00000001 +284.48,50.30085681,-2.858803308,10500,0,200.0009685,0,0,0,90.00000001 +284.49,50.30085681,-2.858775283,10500,0,199.9998535,0,0,0,90.00000001 +284.5,50.30085681,-2.858747258,10500,0,199.9991844,0,0,0,90.00000001 +284.51,50.30085681,-2.858719233,10500,0,199.9998535,0,0,0,90.00000001 +284.52,50.30085681,-2.858691208,10500,0,200.0009685,0,0,0,90.00000001 +284.53,50.30085681,-2.858663182,10500,0,200.0009685,0,0,0,90.00000001 +284.54,50.30085681,-2.858635157,10500,0,199.9998535,0,0,0,90.00000001 +284.55,50.30085681,-2.858607132,10500,0,199.9991844,0,0,0,90.00000001 +284.56,50.30085681,-2.858579107,10500,0,199.9998535,0,0,0,90.00000001 +284.57,50.30085681,-2.858551082,10500,0,200.0009685,0,0,0,90.00000001 +284.58,50.30085681,-2.858523056,10500,0,200.0009685,0,0,0,90.00000001 +284.59,50.30085681,-2.858495031,10500,0,199.9998535,0,0,0,90.00000001 +284.6,50.30085681,-2.858467006,10500,0,199.9991844,0,0,0,90.00000001 +284.61,50.30085681,-2.858438981,10500,0,199.9998535,0,0,0,90.00000001 +284.62,50.30085681,-2.858410956,10500,0,200.0009685,0,0,0,90.00000001 +284.63,50.30085681,-2.85838293,10500,0,200.0009685,0,0,0,90.00000001 +284.64,50.30085681,-2.858354905,10500,0,199.9998535,0,0,0,90.00000001 +284.65,50.30085681,-2.85832688,10500,0,199.9989614,0,0,0,90.00000001 +284.66,50.30085681,-2.858298855,10500,0,199.9989614,0,0,0,90.00000001 +284.67,50.30085681,-2.85827083,10500,0,199.9998535,0,0,0,90.00000001 +284.68,50.30085681,-2.858242805,10500,0,200.0009685,0,0,0,90.00000001 +284.69,50.30085681,-2.858214779,10500,0,200.0009685,0,0,0,90.00000001 +284.7,50.30085681,-2.858186754,10500,0,199.9998535,0,0,0,90.00000001 +284.71,50.30085681,-2.858158729,10500,0,199.9991844,0,0,0,90.00000001 +284.72,50.30085681,-2.858130704,10500,0,199.9998535,0,0,0,90.00000001 +284.73,50.30085681,-2.858102679,10500,0,200.0009685,0,0,0,90.00000001 +284.74,50.30085681,-2.858074653,10500,0,200.0009685,0,0,0,90.00000001 +284.75,50.30085681,-2.858046628,10500,0,199.9998535,0,0,0,90.00000001 +284.76,50.30085681,-2.858018603,10500,0,199.9991844,0,0,0,90.00000001 +284.77,50.30085681,-2.857990578,10500,0,199.9998535,0,0,0,90.00000001 +284.78,50.30085681,-2.857962553,10500,0,200.0009685,0,0,0,90.00000001 +284.79,50.30085681,-2.857934527,10500,0,200.0009685,0,0,0,90.00000001 +284.8,50.30085681,-2.857906502,10500,0,199.9998535,0,0,0,90.00000001 +284.81,50.30085681,-2.857878477,10500,0,199.9989614,0,0,0,90.00000001 +284.82,50.30085681,-2.857850452,10500,0,199.9989614,0,0,0,90.00000001 +284.83,50.30085681,-2.857822427,10500,0,199.9998535,0,0,0,90.00000001 +284.84,50.30085681,-2.857794402,10500,0,200.0009685,0,0,0,90.00000001 +284.85,50.30085681,-2.857766376,10500,0,200.0009685,0,0,0,90.00000001 +284.86,50.30085681,-2.857738351,10500,0,199.9998535,0,0,0,90.00000001 +284.87,50.30085681,-2.857710326,10500,0,199.9989614,0,0,0,90.00000001 +284.88,50.30085681,-2.857682301,10500,0,199.9989614,0,0,0,90.00000001 +284.89,50.30085681,-2.857654276,10500,0,199.9998535,0,0,0,90.00000001 +284.9,50.30085681,-2.857626251,10500,0,200.0009685,0,0,0,90.00000001 +284.91,50.30085681,-2.857598225,10500,0,200.0009685,0,0,0,90.00000001 +284.92,50.30085681,-2.8575702,10500,0,199.9998535,0,0,0,90.00000001 +284.93,50.30085681,-2.857542175,10500,0,199.9989614,0,0,0,90.00000001 +284.94,50.30085681,-2.85751415,10500,0,199.9989614,0,0,0,90.00000001 +284.95,50.30085681,-2.857486125,10500,0,199.9998535,0,0,0,90.00000001 +284.96,50.30085681,-2.8574581,10500,0,200.0009685,0,0,0,90.00000001 +284.97,50.30085681,-2.857430074,10500,0,200.0009685,0,0,0,90.00000001 +284.98,50.30085681,-2.857402049,10500,0,199.9998535,0,0,0,90.00000001 +284.99,50.30085681,-2.857374024,10500,0,199.9989614,0,0,0,90.00000001 +285,50.30085681,-2.857345999,10500,0,199.9987384,0,0,0,90.00000001 +285.01,50.30085681,-2.857317974,10500,0,199.9989614,0,0,0,90.00000001 +285.02,50.30085681,-2.857289949,10500,0,199.9998535,0,0,0,90.00000001 +285.03,50.30085681,-2.857261924,10500,0,200.0009685,0,0,0,90.00000001 +285.04,50.30085681,-2.857233898,10500,0,200.0009685,0,0,0,90.00000001 +285.05,50.30085681,-2.857205873,10500,0,199.9998535,0,0,0,90.00000001 +285.06,50.30085681,-2.857177848,10500,0,199.9989614,0,0,0,90.00000001 +285.07,50.30085681,-2.857149823,10500,0,199.9989614,0,0,0,90.00000001 +285.08,50.30085681,-2.857121798,10500,0,199.9998535,0,0,0,90.00000001 +285.09,50.30085681,-2.857093773,10500,0,200.0009685,0,0,0,90.00000001 +285.1,50.30085681,-2.857065747,10500,0,200.0009685,0,0,0,90.00000001 +285.11,50.30085681,-2.857037722,10500,0,199.9998535,0,0,0,90.00000001 +285.12,50.30085681,-2.857009697,10500,0,199.9989614,0,0,0,90.00000001 +285.13,50.30085681,-2.856981672,10500,0,199.9989614,0,0,0,90.00000001 +285.14,50.30085681,-2.856953647,10500,0,199.9998535,0,0,0,90.00000001 +285.15,50.30085681,-2.856925622,10500,0,200.0009685,0,0,0,90.00000001 +285.16,50.30085681,-2.856897596,10500,0,200.0009685,0,0,0,90.00000001 +285.17,50.30085681,-2.856869571,10500,0,199.9998535,0,0,0,90.00000001 +285.18,50.30085681,-2.856841546,10500,0,199.9991844,0,0,0,90.00000001 +285.19,50.30085681,-2.856813521,10500,0,199.9998535,0,0,0,90.00000001 +285.2,50.30085681,-2.856785496,10500,0,200.0009685,0,0,0,90.00000001 +285.21,50.30085681,-2.85675747,10500,0,200.0009685,0,0,0,90.00000001 +285.22,50.30085681,-2.856729445,10500,0,199.9998535,0,0,0,90.00000001 +285.23,50.30085681,-2.85670142,10500,0,199.9991844,0,0,0,90.00000001 +285.24,50.30085681,-2.856673395,10500,0,199.9998535,0,0,0,90.00000001 +285.25,50.30085681,-2.85664537,10500,0,200.0009685,0,0,0,90.00000001 +285.26,50.30085681,-2.856617344,10500,0,200.0009685,0,0,0,90.00000001 +285.27,50.30085681,-2.856589319,10500,0,199.9998535,0,0,0,90.00000001 +285.28,50.30085681,-2.856561294,10500,0,199.9991844,0,0,0,90.00000001 +285.29,50.30085681,-2.856533269,10500,0,199.9998535,0,0,0,90.00000001 +285.3,50.30085681,-2.856505244,10500,0,200.0009685,0,0,0,90.00000001 +285.31,50.30085681,-2.856477218,10500,0,200.0009685,0,0,0,90.00000001 +285.32,50.30085681,-2.856449193,10500,0,199.9998535,0,0,0,90.00000001 +285.33,50.30085681,-2.856421168,10500,0,199.9991844,0,0,0,90.00000001 +285.34,50.30085681,-2.856393143,10500,0,199.9998535,0,0,0,90.00000001 +285.35,50.30085681,-2.856365118,10500,0,200.0009685,0,0,0,90.00000001 +285.36,50.30085681,-2.856337092,10500,0,200.0009685,0,0,0,90.00000001 +285.37,50.30085681,-2.856309067,10500,0,199.9998535,0,0,0,90.00000001 +285.38,50.30085681,-2.856281042,10500,0,199.9991844,0,0,0,90.00000001 +285.39,50.30085681,-2.856253017,10500,0,199.9998535,0,0,0,90.00000001 +285.4,50.30085681,-2.856224992,10500,0,200.0009685,0,0,0,90.00000001 +285.41,50.30085681,-2.856196966,10500,0,200.0009685,0,0,0,90.00000001 +285.42,50.30085681,-2.856168941,10500,0,199.9998535,0,0,0,90.00000001 +285.43,50.30085681,-2.856140916,10500,0,199.9989614,0,0,0,90.00000001 +285.44,50.30085681,-2.856112891,10500,0,199.9989614,0,0,0,90.00000001 +285.45,50.30085681,-2.856084866,10500,0,199.9998535,0,0,0,90.00000001 +285.46,50.30085681,-2.856056841,10500,0,200.0009685,0,0,0,90.00000001 +285.47,50.30085681,-2.856028815,10500,0,200.0009685,0,0,0,90.00000001 +285.48,50.30085681,-2.85600079,10500,0,199.9998535,0,0,0,90.00000001 +285.49,50.30085681,-2.855972765,10500,0,199.9989614,0,0,0,90.00000001 +285.5,50.30085681,-2.85594474,10500,0,199.9989614,0,0,0,90.00000001 +285.51,50.30085681,-2.855916715,10500,0,199.9998535,0,0,0,90.00000001 +285.52,50.30085681,-2.85588869,10500,0,200.0009685,0,0,0,90.00000001 +285.53,50.30085681,-2.855860664,10500,0,200.0009685,0,0,0,90.00000001 +285.54,50.30085681,-2.855832639,10500,0,199.9998535,0,0,0,90.00000001 +285.55,50.30085681,-2.855804614,10500,0,199.9989614,0,0,0,90.00000001 +285.56,50.30085681,-2.855776589,10500,0,199.9987384,0,0,0,90.00000001 +285.57,50.30085681,-2.855748564,10500,0,199.9989614,0,0,0,90.00000001 +285.58,50.30085681,-2.855720539,10500,0,199.9998535,0,0,0,90.00000001 +285.59,50.30085681,-2.855692514,10500,0,200.0009685,0,0,0,90.00000001 +285.6,50.30085681,-2.855664488,10500,0,200.0009685,0,0,0,90.00000001 +285.61,50.30085681,-2.855636463,10500,0,199.9998535,0,0,0,90.00000001 +285.62,50.30085681,-2.855608438,10500,0,199.9989614,0,0,0,90.00000001 +285.63,50.30085681,-2.855580413,10500,0,199.9989614,0,0,0,90.00000001 +285.64,50.30085681,-2.855552388,10500,0,199.9998535,0,0,0,90.00000001 +285.65,50.30085681,-2.855524363,10500,0,200.0009685,0,0,0,90.00000001 +285.66,50.30085681,-2.855496337,10500,0,200.0009685,0,0,0,90.00000001 +285.67,50.30085681,-2.855468312,10500,0,199.9998535,0,0,0,90.00000001 +285.68,50.30085681,-2.855440287,10500,0,199.9989614,0,0,0,90.00000001 +285.69,50.30085681,-2.855412262,10500,0,199.9989614,0,0,0,90.00000001 +285.7,50.30085681,-2.855384237,10500,0,199.9998535,0,0,0,90.00000001 +285.71,50.30085681,-2.855356212,10500,0,200.0009685,0,0,0,90.00000001 +285.72,50.30085681,-2.855328186,10500,0,200.0009685,0,0,0,90.00000001 +285.73,50.30085681,-2.855300161,10500,0,199.9998535,0,0,0,90.00000001 +285.74,50.30085681,-2.855272136,10500,0,199.9989614,0,0,0,90.00000001 +285.75,50.30085681,-2.855244111,10500,0,199.9989614,0,0,0,90.00000001 +285.76,50.30085681,-2.855216086,10500,0,199.9998535,0,0,0,90.00000001 +285.77,50.30085681,-2.855188061,10500,0,200.0009685,0,0,0,90.00000001 +285.78,50.30085681,-2.855160035,10500,0,200.0009685,0,0,0,90.00000001 +285.79,50.30085681,-2.85513201,10500,0,199.9998535,0,0,0,90.00000001 +285.8,50.30085681,-2.855103985,10500,0,199.9991844,0,0,0,90.00000001 +285.81,50.30085681,-2.85507596,10500,0,199.9998535,0,0,0,90.00000001 +285.82,50.30085681,-2.855047935,10500,0,200.0009685,0,0,0,90.00000001 +285.83,50.30085681,-2.855019909,10500,0,200.0009685,0,0,0,90.00000001 +285.84,50.30085681,-2.854991884,10500,0,199.9998535,0,0,0,90.00000001 +285.85,50.30085681,-2.854963859,10500,0,199.9991844,0,0,0,90.00000001 +285.86,50.30085681,-2.854935834,10500,0,199.9998535,0,0,0,90.00000001 +285.87,50.30085681,-2.854907809,10500,0,200.0009685,0,0,0,90.00000001 +285.88,50.30085681,-2.854879783,10500,0,200.0009685,0,0,0,90.00000001 +285.89,50.30085681,-2.854851758,10500,0,199.9998535,0,0,0,90.00000001 +285.9,50.30085681,-2.854823733,10500,0,199.9991844,0,0,0,90.00000001 +285.91,50.30085681,-2.854795708,10500,0,199.9998535,0,0,0,90.00000001 +285.92,50.30085681,-2.854767683,10500,0,200.0009685,0,0,0,90.00000001 +285.93,50.30085681,-2.854739657,10500,0,200.0009685,0,0,0,90.00000001 +285.94,50.30085681,-2.854711632,10500,0,199.9998535,0,0,0,90.00000001 +285.95,50.30085681,-2.854683607,10500,0,199.9991844,0,0,0,90.00000001 +285.96,50.30085681,-2.854655582,10500,0,199.9998535,0,0,0,90.00000001 +285.97,50.30085681,-2.854627557,10500,0,200.0009685,0,0,0,90.00000001 +285.98,50.30085681,-2.854599531,10500,0,200.0009685,0,0,0,90.00000001 +285.99,50.30085681,-2.854571506,10500,0,199.9998535,0,0,0,90.00000001 +286,50.30085681,-2.854543481,10500,0,199.9991844,0,0,0,90.00000001 +286.01,50.30085681,-2.854515456,10500,0,199.9998535,0,0,0,90.00000001 +286.02,50.30085681,-2.854487431,10500,0,200.0009685,0,0,0,90.00000001 +286.03,50.30085681,-2.854459405,10500,0,200.0009685,0,0,0,90.00000001 +286.04,50.30085681,-2.85443138,10500,0,199.9998535,0,0,0,90.00000001 +286.05,50.30085681,-2.854403355,10500,0,199.9989614,0,0,0,90.00000001 +286.06,50.30085681,-2.85437533,10500,0,199.9989614,0,0,0,90.00000001 +286.07,50.30085681,-2.854347305,10500,0,199.9998535,0,0,0,90.00000001 +286.08,50.30085681,-2.85431928,10500,0,200.0009685,0,0,0,90.00000001 +286.09,50.30085681,-2.854291254,10500,0,200.0009685,0,0,0,90.00000001 +286.1,50.30085681,-2.854263229,10500,0,199.9998535,0,0,0,90.00000001 +286.11,50.30085681,-2.854235204,10500,0,199.9989614,0,0,0,90.00000001 +286.12,50.30085681,-2.854207179,10500,0,199.9987384,0,0,0,90.00000001 +286.13,50.30085681,-2.854179154,10500,0,199.9989614,0,0,0,90.00000001 +286.14,50.30085681,-2.854151129,10500,0,199.9998535,0,0,0,90.00000001 +286.15,50.30085681,-2.854123104,10500,0,200.0009685,0,0,0,90.00000001 +286.16,50.30085681,-2.854095078,10500,0,200.0009685,0,0,0,90.00000001 +286.17,50.30085681,-2.854067053,10500,0,199.9998535,0,0,0,90.00000001 +286.18,50.30085681,-2.854039028,10500,0,199.9989614,0,0,0,90.00000001 +286.19,50.30085681,-2.854011003,10500,0,199.9989614,0,0,0,90.00000001 +286.2,50.30085681,-2.853982978,10500,0,199.9998535,0,0,0,90.00000001 +286.21,50.30085681,-2.853954953,10500,0,200.0009685,0,0,0,90.00000001 +286.22,50.30085681,-2.853926927,10500,0,200.0009685,0,0,0,90.00000001 +286.23,50.30085681,-2.853898902,10500,0,199.9998535,0,0,0,90.00000001 +286.24,50.30085681,-2.853870877,10500,0,199.9989614,0,0,0,90.00000001 +286.25,50.30085681,-2.853842852,10500,0,199.9989614,0,0,0,90.00000001 +286.26,50.30085681,-2.853814827,10500,0,199.9998535,0,0,0,90.00000001 +286.27,50.30085681,-2.853786802,10500,0,200.0009685,0,0,0,90.00000001 +286.28,50.30085681,-2.853758776,10500,0,200.0009685,0,0,0,90.00000001 +286.29,50.30085681,-2.853730751,10500,0,199.9998535,0,0,0,90.00000001 +286.3,50.30085681,-2.853702726,10500,0,199.9989614,0,0,0,90.00000001 +286.31,50.30085681,-2.853674701,10500,0,199.9989614,0,0,0,90.00000001 +286.32,50.30085681,-2.853646676,10500,0,199.9998535,0,0,0,90.00000001 +286.33,50.30085681,-2.853618651,10500,0,200.0009685,0,0,0,90.00000001 +286.34,50.30085681,-2.853590625,10500,0,200.0009685,0,0,0,90.00000001 +286.35,50.30085681,-2.8535626,10500,0,199.9998535,0,0,0,90.00000001 +286.36,50.30085681,-2.853534575,10500,0,199.9989614,0,0,0,90.00000001 +286.37,50.30085681,-2.85350655,10500,0,199.9989614,0,0,0,90.00000001 +286.38,50.30085681,-2.853478525,10500,0,199.9998535,0,0,0,90.00000001 +286.39,50.30085681,-2.8534505,10500,0,200.0009685,0,0,0,90.00000001 +286.4,50.30085681,-2.853422474,10500,0,200.0009685,0,0,0,90.00000001 +286.41,50.30085681,-2.853394449,10500,0,199.9998535,0,0,0,90.00000001 +286.42,50.30085681,-2.853366424,10500,0,199.9991844,0,0,0,90.00000001 +286.43,50.30085681,-2.853338399,10500,0,199.9998535,0,0,0,90.00000001 +286.44,50.30085681,-2.853310374,10500,0,200.0009685,0,0,0,90.00000001 +286.45,50.30085681,-2.853282348,10500,0,200.0009685,0,0,0,90.00000001 +286.46,50.30085681,-2.853254323,10500,0,199.9998535,0,0,0,90.00000001 +286.47,50.30085681,-2.853226298,10500,0,199.9991844,0,0,0,90.00000001 +286.48,50.30085681,-2.853198273,10500,0,199.9998535,0,0,0,90.00000001 +286.49,50.30085681,-2.853170248,10500,0,200.0009685,0,0,0,90.00000001 +286.5,50.30085681,-2.853142222,10500,0,200.0009685,0,0,0,90.00000001 +286.51,50.30085681,-2.853114197,10500,0,199.9998535,0,0,0,90.00000001 +286.52,50.30085681,-2.853086172,10500,0,199.9991844,0,0,0,90.00000001 +286.53,50.30085681,-2.853058147,10500,0,199.9998535,0,0,0,90.00000001 +286.54,50.30085681,-2.853030122,10500,0,200.0009685,0,0,0,90.00000001 +286.55,50.30085681,-2.853002096,10500,0,200.0009685,0,0,0,90.00000001 +286.56,50.30085681,-2.852974071,10500,0,199.9998535,0,0,0,90.00000001 +286.57,50.30085681,-2.852946046,10500,0,199.9991844,0,0,0,90.00000001 +286.58,50.30085681,-2.852918021,10500,0,199.9998535,0,0,0,90.00000001 +286.59,50.30085681,-2.852889996,10500,0,200.0009685,0,0,0,90.00000001 +286.6,50.30085681,-2.85286197,10500,0,200.0009685,0,0,0,90.00000001 +286.61,50.30085681,-2.852833945,10500,0,199.9998535,0,0,0,90.00000001 +286.62,50.30085681,-2.85280592,10500,0,199.9991844,0,0,0,90.00000001 +286.63,50.30085681,-2.852777895,10500,0,199.9998535,0,0,0,90.00000001 +286.64,50.30085681,-2.85274987,10500,0,200.0009685,0,0,0,90.00000001 +286.65,50.30085681,-2.852721844,10500,0,200.0009685,0,0,0,90.00000001 +286.66,50.30085681,-2.852693819,10500,0,199.9998535,0,0,0,90.00000001 +286.67,50.30085681,-2.852665794,10500,0,199.9989614,0,0,0,90.00000001 +286.68,50.30085681,-2.852637769,10500,0,199.9987384,0,0,0,90.00000001 +286.69,50.30085681,-2.852609744,10500,0,199.9989614,0,0,0,90.00000001 +286.7,50.30085681,-2.852581719,10500,0,199.9998535,0,0,0,90.00000001 +286.71,50.30085681,-2.852553694,10500,0,200.0009685,0,0,0,90.00000001 +286.72,50.30085681,-2.852525668,10500,0,200.0009685,0,0,0,90.00000001 +286.73,50.30085681,-2.852497643,10500,0,199.9998535,0,0,0,90.00000001 +286.74,50.30085681,-2.852469618,10500,0,199.9989614,0,0,0,90.00000001 +286.75,50.30085681,-2.852441593,10500,0,199.9989614,0,0,0,90.00000001 +286.76,50.30085681,-2.852413568,10500,0,199.9998535,0,0,0,90.00000001 +286.77,50.30085681,-2.852385543,10500,0,200.0009685,0,0,0,90.00000001 +286.78,50.30085681,-2.852357517,10500,0,200.0009685,0,0,0,90.00000001 +286.79,50.30085681,-2.852329492,10500,0,199.9998535,0,0,0,90.00000001 +286.8,50.30085681,-2.852301467,10500,0,199.9989614,0,0,0,90.00000001 +286.81,50.30085681,-2.852273442,10500,0,199.9989614,0,0,0,90.00000001 +286.82,50.30085681,-2.852245417,10500,0,199.9998535,0,0,0,90.00000001 +286.83,50.30085681,-2.852217392,10500,0,200.0009685,0,0,0,90.00000001 +286.84,50.30085681,-2.852189366,10500,0,200.0009685,0,0,0,90.00000001 +286.85,50.30085681,-2.852161341,10500,0,199.9998535,0,0,0,90.00000001 +286.86,50.30085681,-2.852133316,10500,0,199.9989614,0,0,0,90.00000001 +286.87,50.30085681,-2.852105291,10500,0,199.9989614,0,0,0,90.00000001 +286.88,50.30085681,-2.852077266,10500,0,199.9998535,0,0,0,90.00000001 +286.89,50.30085681,-2.852049241,10500,0,200.0009685,0,0,0,90.00000001 +286.9,50.30085681,-2.852021215,10500,0,200.0009685,0,0,0,90.00000001 +286.91,50.30085681,-2.85199319,10500,0,199.9998535,0,0,0,90.00000001 +286.92,50.30085681,-2.851965165,10500,0,199.9989614,0,0,0,90.00000001 +286.93,50.30085681,-2.85193714,10500,0,199.9989614,0,0,0,90.00000001 +286.94,50.30085681,-2.851909115,10500,0,199.9998535,0,0,0,90.00000001 +286.95,50.30085681,-2.85188109,10500,0,200.0009685,0,0,0,90.00000001 +286.96,50.30085681,-2.851853064,10500,0,200.0009685,0,0,0,90.00000001 +286.97,50.30085681,-2.851825039,10500,0,199.9998535,0,0,0,90.00000001 +286.98,50.30085681,-2.851797014,10500,0,199.9989614,0,0,0,90.00000001 +286.99,50.30085681,-2.851768989,10500,0,199.9989614,0,0,0,90.00000001 +287,50.30085681,-2.851740964,10500,0,199.9998535,0,0,0,90.00000001 +287.01,50.30085681,-2.851712939,10500,0,200.0009685,0,0,0,90.00000001 +287.02,50.30085681,-2.851684913,10500,0,200.0009685,0,0,0,90.00000001 +287.03,50.30085681,-2.851656888,10500,0,199.9998535,0,0,0,90.00000001 +287.04,50.30085681,-2.851628863,10500,0,199.9989614,0,0,0,90.00000001 +287.05,50.30085681,-2.851600838,10500,0,199.9989614,0,0,0,90.00000001 +287.06,50.30085681,-2.851572813,10500,0,199.9998535,0,0,0,90.00000001 +287.07,50.30085681,-2.851544788,10500,0,200.0009685,0,0,0,90.00000001 +287.08,50.30085681,-2.851516762,10500,0,200.0009685,0,0,0,90.00000001 +287.09,50.30085681,-2.851488737,10500,0,199.9998535,0,0,0,90.00000001 +287.1,50.30085681,-2.851460712,10500,0,199.9991844,0,0,0,90.00000001 +287.11,50.30085681,-2.851432687,10500,0,199.9998535,0,0,0,90.00000001 +287.12,50.30085681,-2.851404662,10500,0,200.0009685,0,0,0,90.00000001 +287.13,50.30085681,-2.851376636,10500,0,200.0009685,0,0,0,90.00000001 +287.14,50.30085681,-2.851348611,10500,0,199.9998535,0,0,0,90.00000001 +287.15,50.30085681,-2.851320586,10500,0,199.9991844,0,0,0,90.00000001 +287.16,50.30085681,-2.851292561,10500,0,199.9998535,0,0,0,90.00000001 +287.17,50.30085681,-2.851264536,10500,0,200.0009685,0,0,0,90.00000001 +287.18,50.30085681,-2.85123651,10500,0,200.0009685,0,0,0,90.00000001 +287.19,50.30085681,-2.851208485,10500,0,199.9998535,0,0,0,90.00000001 +287.2,50.30085681,-2.85118046,10500,0,199.9991844,0,0,0,90.00000001 +287.21,50.30085681,-2.851152435,10500,0,199.9998535,0,0,0,90.00000001 +287.22,50.30085681,-2.85112441,10500,0,200.0009685,0,0,0,90.00000001 +287.23,50.30085681,-2.851096384,10500,0,200.0009685,0,0,0,90.00000001 +287.24,50.30085681,-2.851068359,10500,0,199.9998535,0,0,0,90.00000001 +287.25,50.30085681,-2.851040334,10500,0,199.9991844,0,0,0,90.00000001 +287.26,50.30085681,-2.851012309,10500,0,199.9998535,0,0,0,90.00000001 +287.27,50.30085681,-2.850984284,10500,0,200.0009685,0,0,0,90.00000001 +287.28,50.30085681,-2.850956258,10500,0,200.0009685,0,0,0,90.00000001 +287.29,50.30085681,-2.850928233,10500,0,199.9998535,0,0,0,90.00000001 +287.3,50.30085681,-2.850900208,10500,0,199.9989614,0,0,0,90.00000001 +287.31,50.30085681,-2.850872183,10500,0,199.9989614,0,0,0,90.00000001 +287.32,50.30085681,-2.850844158,10500,0,199.9998535,0,0,0,90.00000001 +287.33,50.30085681,-2.850816133,10500,0,200.0009685,0,0,0,90.00000001 +287.34,50.30085681,-2.850788107,10500,0,200.0009685,0,0,0,90.00000001 +287.35,50.30085681,-2.850760082,10500,0,199.9998535,0,0,0,90.00000001 +287.36,50.30085681,-2.850732057,10500,0,199.9989614,0,0,0,90.00000001 +287.37,50.30085681,-2.850704032,10500,0,199.9989614,0,0,0,90.00000001 +287.38,50.30085681,-2.850676007,10500,0,199.9998535,0,0,0,90.00000001 +287.39,50.30085681,-2.850647982,10500,0,200.0009685,0,0,0,90.00000001 +287.4,50.30085681,-2.850619956,10500,0,200.0009685,0,0,0,90.00000001 +287.41,50.30085681,-2.850591931,10500,0,199.9998535,0,0,0,90.00000001 +287.42,50.30085681,-2.850563906,10500,0,199.9989614,0,0,0,90.00000001 +287.43,50.30085681,-2.850535881,10500,0,199.9989614,0,0,0,90.00000001 +287.44,50.30085681,-2.850507856,10500,0,199.9998535,0,0,0,90.00000001 +287.45,50.30085681,-2.850479831,10500,0,200.0009685,0,0,0,90.00000001 +287.46,50.30085681,-2.850451805,10500,0,200.0009685,0,0,0,90.00000001 +287.47,50.30085681,-2.85042378,10500,0,199.9998535,0,0,0,90.00000001 +287.48,50.30085681,-2.850395755,10500,0,199.9989614,0,0,0,90.00000001 +287.49,50.30085681,-2.85036773,10500,0,199.9989614,0,0,0,90.00000001 +287.5,50.30085681,-2.850339705,10500,0,199.9998535,0,0,0,90.00000001 +287.51,50.30085681,-2.85031168,10500,0,200.0009685,0,0,0,90.00000001 +287.52,50.30085681,-2.850283654,10500,0,200.0009685,0,0,0,90.00000001 +287.53,50.30085681,-2.850255629,10500,0,199.9998535,0,0,0,90.00000001 +287.54,50.30085681,-2.850227604,10500,0,199.9989614,0,0,0,90.00000001 +287.55,50.30085681,-2.850199579,10500,0,199.9987384,0,0,0,90.00000001 +287.56,50.30085681,-2.850171554,10500,0,199.9989614,0,0,0,90.00000001 +287.57,50.30085681,-2.850143529,10500,0,199.9998535,0,0,0,90.00000001 +287.58,50.30085681,-2.850115504,10500,0,200.0009685,0,0,0,90.00000001 +287.59,50.30085681,-2.850087478,10500,0,200.0009685,0,0,0,90.00000001 +287.6,50.30085681,-2.850059453,10500,0,199.9998535,0,0,0,90.00000001 +287.61,50.30085681,-2.850031428,10500,0,199.9989614,0,0,0,90.00000001 +287.62,50.30085681,-2.850003403,10500,0,199.9989614,0,0,0,90.00000001 +287.63,50.30085681,-2.849975378,10500,0,199.9998535,0,0,0,90.00000001 +287.64,50.30085681,-2.849947353,10500,0,200.0009685,0,0,0,90.00000001 +287.65,50.30085681,-2.849919327,10500,0,200.0009685,0,0,0,90.00000001 +287.66,50.30085681,-2.849891302,10500,0,199.9998535,0,0,0,90.00000001 +287.67,50.30085681,-2.849863277,10500,0,199.9991844,0,0,0,90.00000001 +287.68,50.30085681,-2.849835252,10500,0,199.9998535,0,0,0,90.00000001 +287.69,50.30085681,-2.849807227,10500,0,200.0009685,0,0,0,90.00000001 +287.7,50.30085681,-2.849779201,10500,0,200.0009685,0,0,0,90.00000001 +287.71,50.30085681,-2.849751176,10500,0,199.9998535,0,0,0,90.00000001 +287.72,50.30085681,-2.849723151,10500,0,199.9991844,0,0,0,90.00000001 +287.73,50.30085681,-2.849695126,10500,0,199.9998535,0,0,0,90.00000001 +287.74,50.30085681,-2.849667101,10500,0,200.0009685,0,0,0,90.00000001 +287.75,50.30085681,-2.849639075,10500,0,200.0009685,0,0,0,90.00000001 +287.76,50.30085681,-2.84961105,10500,0,199.9998535,0,0,0,90.00000001 +287.77,50.30085681,-2.849583025,10500,0,199.9991844,0,0,0,90.00000001 +287.78,50.30085681,-2.849555,10500,0,199.9998535,0,0,0,90.00000001 +287.79,50.30085681,-2.849526975,10500,0,200.0009685,0,0,0,90.00000001 +287.8,50.30085681,-2.849498949,10500,0,200.0009685,0,0,0,90.00000001 +287.81,50.30085681,-2.849470924,10500,0,199.9998535,0,0,0,90.00000001 +287.82,50.30085681,-2.849442899,10500,0,199.9991844,0,0,0,90.00000001 +287.83,50.30085681,-2.849414874,10500,0,199.9998535,0,0,0,90.00000001 +287.84,50.30085681,-2.849386849,10500,0,200.0009685,0,0,0,90.00000001 +287.85,50.30085681,-2.849358823,10500,0,200.0009685,0,0,0,90.00000001 +287.86,50.30085681,-2.849330798,10500,0,199.9998535,0,0,0,90.00000001 +287.87,50.30085681,-2.849302773,10500,0,199.9991844,0,0,0,90.00000001 +287.88,50.30085681,-2.849274748,10500,0,199.9998535,0,0,0,90.00000001 +287.89,50.30085681,-2.849246723,10500,0,200.0009685,0,0,0,90.00000001 +287.9,50.30085681,-2.849218697,10500,0,200.0009685,0,0,0,90.00000001 +287.91,50.30085681,-2.849190672,10500,0,199.9998535,0,0,0,90.00000001 +287.92,50.30085681,-2.849162647,10500,0,199.9989614,0,0,0,90.00000001 +287.93,50.30085681,-2.849134622,10500,0,199.9989614,0,0,0,90.00000001 +287.94,50.30085681,-2.849106597,10500,0,199.9998535,0,0,0,90.00000001 +287.95,50.30085681,-2.849078572,10500,0,200.0009685,0,0,0,90.00000001 +287.96,50.30085681,-2.849050546,10500,0,200.0009685,0,0,0,90.00000001 +287.97,50.30085681,-2.849022521,10500,0,199.9998535,0,0,0,90.00000001 +287.98,50.30085681,-2.848994496,10500,0,199.9989614,0,0,0,90.00000001 +287.99,50.30085681,-2.848966471,10500,0,199.9989614,0,0,0,90.00000001 +288,50.30085681,-2.848938446,10500,0,199.9998535,0,0,0,90.00000001 +288.01,50.30085681,-2.848910421,10500,0,200.0009685,0,0,0,90.00000001 +288.02,50.30085681,-2.848882395,10500,0,200.0009685,0,0,0,90.00000001 +288.03,50.30085681,-2.84885437,10500,0,199.9998535,0,0,0,90.00000001 +288.04,50.30085681,-2.848826345,10500,0,199.9989614,0,0,0,90.00000001 +288.05,50.30085681,-2.84879832,10500,0,199.9989614,0,0,0,90.00000001 +288.06,50.30085681,-2.848770295,10500,0,199.9998535,0,0,0,90.00000001 +288.07,50.30085681,-2.84874227,10500,0,200.0009685,0,0,0,90.00000001 +288.08,50.30085681,-2.848714244,10500,0,200.0009685,0,0,0,90.00000001 +288.09,50.30085681,-2.848686219,10500,0,199.9998535,0,0,0,90.00000001 +288.1,50.30085681,-2.848658194,10500,0,199.9989614,0,0,0,90.00000001 +288.11,50.30085681,-2.848630169,10500,0,199.9987384,0,0,0,90.00000001 +288.12,50.30085681,-2.848602144,10500,0,199.9989614,0,0,0,90.00000001 +288.13,50.30085681,-2.848574119,10500,0,199.9998535,0,0,0,90.00000001 +288.14,50.30085681,-2.848546094,10500,0,200.0009685,0,0,0,90.00000001 +288.15,50.30085681,-2.848518068,10500,0,200.0009685,0,0,0,90.00000001 +288.16,50.30085681,-2.848490043,10500,0,199.9998535,0,0,0,90.00000001 +288.17,50.30085681,-2.848462018,10500,0,199.9989614,0,0,0,90.00000001 +288.18,50.30085681,-2.848433993,10500,0,199.9989614,0,0,0,90.00000001 +288.19,50.30085681,-2.848405968,10500,0,199.9998535,0,0,0,90.00000001 +288.2,50.30085681,-2.848377943,10500,0,200.0009685,0,0,0,90.00000001 +288.21,50.30085681,-2.848349917,10500,0,200.0009685,0,0,0,90.00000001 +288.22,50.30085681,-2.848321892,10500,0,199.9998535,0,0,0,90.00000001 +288.23,50.30085681,-2.848293867,10500,0,199.9989614,0,0,0,90.00000001 +288.24,50.30085681,-2.848265842,10500,0,199.9989614,0,0,0,90.00000001 +288.25,50.30085681,-2.848237817,10500,0,199.9998535,0,0,0,90.00000001 +288.26,50.30085681,-2.848209792,10500,0,200.0009685,0,0,0,90.00000001 +288.27,50.30085681,-2.848181766,10500,0,200.0009685,0,0,0,90.00000001 +288.28,50.30085681,-2.848153741,10500,0,199.9998535,0,0,0,90.00000001 +288.29,50.30085681,-2.848125716,10500,0,199.9991844,0,0,0,90.00000001 +288.3,50.30085681,-2.848097691,10500,0,199.9998535,0,0,0,90.00000001 +288.31,50.30085681,-2.848069666,10500,0,200.0009685,0,0,0,90.00000001 +288.32,50.30085681,-2.84804164,10500,0,200.0009685,0,0,0,90.00000001 +288.33,50.30085681,-2.848013615,10500,0,199.9998535,0,0,0,90.00000001 +288.34,50.30085681,-2.84798559,10500,0,199.9991844,0,0,0,90.00000001 +288.35,50.30085681,-2.847957565,10500,0,199.9998535,0,0,0,90.00000001 +288.36,50.30085681,-2.84792954,10500,0,200.0009685,0,0,0,90.00000001 +288.37,50.30085681,-2.847901514,10500,0,200.0009685,0,0,0,90.00000001 +288.38,50.30085681,-2.847873489,10500,0,199.9998535,0,0,0,90.00000001 +288.39,50.30085681,-2.847845464,10500,0,199.9991844,0,0,0,90.00000001 +288.4,50.30085681,-2.847817439,10500,0,199.9998535,0,0,0,90.00000001 +288.41,50.30085681,-2.847789414,10500,0,200.0009685,0,0,0,90.00000001 +288.42,50.30085681,-2.847761388,10500,0,200.0009685,0,0,0,90.00000001 +288.43,50.30085681,-2.847733363,10500,0,199.9998535,0,0,0,90.00000001 +288.44,50.30085681,-2.847705338,10500,0,199.9991844,0,0,0,90.00000001 +288.45,50.30085681,-2.847677313,10500,0,199.9998535,0,0,0,90.00000001 +288.46,50.30085681,-2.847649288,10500,0,200.0009685,0,0,0,90.00000001 +288.47,50.30085681,-2.847621262,10500,0,200.0009685,0,0,0,90.00000001 +288.48,50.30085681,-2.847593237,10500,0,199.9998535,0,0,0,90.00000001 +288.49,50.30085681,-2.847565212,10500,0,199.9991844,0,0,0,90.00000001 +288.5,50.30085681,-2.847537187,10500,0,199.9998535,0,0,0,90.00000001 +288.51,50.30085681,-2.847509162,10500,0,200.0009685,0,0,0,90.00000001 +288.52,50.30085681,-2.847481136,10500,0,200.0009685,0,0,0,90.00000001 +288.53,50.30085681,-2.847453111,10500,0,199.9998535,0,0,0,90.00000001 +288.54,50.30085681,-2.847425086,10500,0,199.9989614,0,0,0,90.00000001 +288.55,50.30085681,-2.847397061,10500,0,199.9989614,0,0,0,90.00000001 +288.56,50.30085681,-2.847369036,10500,0,199.9998535,0,0,0,90.00000001 +288.57,50.30085681,-2.847341011,10500,0,200.0009685,0,0,0,90.00000001 +288.58,50.30085681,-2.847312985,10500,0,200.0009685,0,0,0,90.00000001 +288.59,50.30085681,-2.84728496,10500,0,199.9998535,0,0,0,90.00000001 +288.6,50.30085681,-2.847256935,10500,0,199.9989614,0,0,0,90.00000001 +288.61,50.30085681,-2.84722891,10500,0,199.9989614,0,0,0,90.00000001 +288.62,50.30085681,-2.847200885,10500,0,199.9998535,0,0,0,90.00000001 +288.63,50.30085681,-2.84717286,10500,0,200.0009685,0,0,0,90.00000001 +288.64,50.30085681,-2.847144834,10500,0,200.0009685,0,0,0,90.00000001 +288.65,50.30085681,-2.847116809,10500,0,199.9998535,0,0,0,90.00000001 +288.66,50.30085681,-2.847088784,10500,0,199.9989614,0,0,0,90.00000001 +288.67,50.30085681,-2.847060759,10500,0,199.9987384,0,0,0,90.00000001 +288.68,50.30085681,-2.847032734,10500,0,199.9989614,0,0,0,90.00000001 +288.69,50.30085681,-2.847004709,10500,0,199.9998535,0,0,0,90.00000001 +288.7,50.30085681,-2.846976684,10500,0,200.0009685,0,0,0,90.00000001 +288.71,50.30085681,-2.846948658,10500,0,200.0009685,0,0,0,90.00000001 +288.72,50.30085681,-2.846920633,10500,0,199.9998535,0,0,0,90.00000001 +288.73,50.30085681,-2.846892608,10500,0,199.9989614,0,0,0,90.00000001 +288.74,50.30085681,-2.846864583,10500,0,199.9989614,0,0,0,90.00000001 +288.75,50.30085681,-2.846836558,10500,0,199.9998535,0,0,0,90.00000001 +288.76,50.30085681,-2.846808533,10500,0,200.0009685,0,0,0,90.00000001 +288.77,50.30085681,-2.846780507,10500,0,200.0009685,0,0,0,90.00000001 +288.78,50.30085681,-2.846752482,10500,0,199.9998535,0,0,0,90.00000001 +288.79,50.30085681,-2.846724457,10500,0,199.9989614,0,0,0,90.00000001 +288.8,50.30085681,-2.846696432,10500,0,199.9989614,0,0,0,90.00000001 +288.81,50.30085681,-2.846668407,10500,0,199.9998535,0,0,0,90.00000001 +288.82,50.30085681,-2.846640382,10500,0,200.0009685,0,0,0,90.00000001 +288.83,50.30085681,-2.846612356,10500,0,200.0009685,0,0,0,90.00000001 +288.84,50.30085681,-2.846584331,10500,0,199.9998535,0,0,0,90.00000001 +288.85,50.30085681,-2.846556306,10500,0,199.9989614,0,0,0,90.00000001 +288.86,50.30085681,-2.846528281,10500,0,199.9989614,0,0,0,90.00000001 +288.87,50.30085681,-2.846500256,10500,0,199.9998535,0,0,0,90.00000001 +288.88,50.30085681,-2.846472231,10500,0,200.0009685,0,0,0,90.00000001 +288.89,50.30085681,-2.846444205,10500,0,200.0009685,0,0,0,90.00000001 +288.9,50.30085681,-2.84641618,10500,0,199.9998535,0,0,0,90.00000001 +288.91,50.30085681,-2.846388155,10500,0,199.9991844,0,0,0,90.00000001 +288.92,50.30085681,-2.84636013,10500,0,199.9998535,0,0,0,90.00000001 +288.93,50.30085681,-2.846332105,10500,0,200.0009685,0,0,0,90.00000001 +288.94,50.30085681,-2.846304079,10500,0,200.0009685,0,0,0,90.00000001 +288.95,50.30085681,-2.846276054,10500,0,199.9998535,0,0,0,90.00000001 +288.96,50.30085681,-2.846248029,10500,0,199.9991844,0,0,0,90.00000001 +288.97,50.30085681,-2.846220004,10500,0,199.9998535,0,0,0,90.00000001 +288.98,50.30085681,-2.846191979,10500,0,200.0009685,0,0,0,90.00000001 +288.99,50.30085681,-2.846163953,10500,0,200.0009685,0,0,0,90.00000001 +289,50.30085681,-2.846135928,10500,0,199.9998535,0,0,0,90.00000001 +289.01,50.30085681,-2.846107903,10500,0,199.9991844,0,0,0,90.00000001 +289.02,50.30085681,-2.846079878,10500,0,199.9998535,0,0,0,90.00000001 +289.03,50.30085681,-2.846051853,10500,0,200.0009685,0,0,0,90.00000001 +289.04,50.30085681,-2.846023827,10500,0,200.0009685,0,0,0,90.00000001 +289.05,50.30085681,-2.845995802,10500,0,199.9998535,0,0,0,90.00000001 +289.06,50.30085681,-2.845967777,10500,0,199.9991844,0,0,0,90.00000001 +289.07,50.30085681,-2.845939752,10500,0,199.9998535,0,0,0,90.00000001 +289.08,50.30085681,-2.845911727,10500,0,200.0009685,0,0,0,90.00000001 +289.09,50.30085681,-2.845883701,10500,0,200.0009685,0,0,0,90.00000001 +289.1,50.30085681,-2.845855676,10500,0,199.9998535,0,0,0,90.00000001 +289.11,50.30085681,-2.845827651,10500,0,199.9989614,0,0,0,90.00000001 +289.12,50.30085681,-2.845799626,10500,0,199.9989614,0,0,0,90.00000001 +289.13,50.30085681,-2.845771601,10500,0,199.9998535,0,0,0,90.00000001 +289.14,50.30085681,-2.845743576,10500,0,200.0009685,0,0,0,90.00000001 +289.15,50.30085681,-2.84571555,10500,0,200.0009685,0,0,0,90.00000001 +289.16,50.30085681,-2.845687525,10500,0,199.9998535,0,0,0,90.00000001 +289.17,50.30085681,-2.8456595,10500,0,199.9991844,0,0,0,90.00000001 +289.18,50.30085681,-2.845631475,10500,0,199.9998535,0,0,0,90.00000001 +289.19,50.30085681,-2.84560345,10500,0,200.0009685,0,0,0,90.00000001 +289.2,50.30085681,-2.845575424,10500,0,200.0009685,0,0,0,90.00000001 +289.21,50.30085681,-2.845547399,10500,0,199.9998535,0,0,0,90.00000001 +289.22,50.30085681,-2.845519374,10500,0,199.9989614,0,0,0,90.00000001 +289.23,50.30085681,-2.845491349,10500,0,199.9989614,0,0,0,90.00000001 +289.24,50.30085681,-2.845463324,10500,0,199.9998535,0,0,0,90.00000001 +289.25,50.30085681,-2.845435299,10500,0,200.0009685,0,0,0,90.00000001 +289.26,50.30085681,-2.845407273,10500,0,200.0009685,0,0,0,90.00000001 +289.27,50.30085681,-2.845379248,10500,0,199.9998535,0,0,0,90.00000001 +289.28,50.30085681,-2.845351223,10500,0,199.9989614,0,0,0,90.00000001 +289.29,50.30085681,-2.845323198,10500,0,199.9987384,0,0,0,90.00000001 +289.3,50.30085681,-2.845295173,10500,0,199.9989614,0,0,0,90.00000001 +289.31,50.30085681,-2.845267148,10500,0,199.9998535,0,0,0,90.00000001 +289.32,50.30085681,-2.845239123,10500,0,200.0009685,0,0,0,90.00000001 +289.33,50.30085681,-2.845211097,10500,0,200.0009685,0,0,0,90.00000001 +289.34,50.30085681,-2.845183072,10500,0,199.9998535,0,0,0,90.00000001 +289.35,50.30085681,-2.845155047,10500,0,199.9989614,0,0,0,90.00000001 +289.36,50.30085681,-2.845127022,10500,0,199.9989614,0,0,0,90.00000001 +289.37,50.30085681,-2.845098997,10500,0,199.9998535,0,0,0,90.00000001 +289.38,50.30085681,-2.845070972,10500,0,200.0009685,0,0,0,90.00000001 +289.39,50.30085681,-2.845042946,10500,0,200.0009685,0,0,0,90.00000001 +289.4,50.30085681,-2.845014921,10500,0,199.9998535,0,0,0,90.00000001 +289.41,50.30085681,-2.844986896,10500,0,199.9989614,0,0,0,90.00000001 +289.42,50.30085681,-2.844958871,10500,0,199.9989614,0,0,0,90.00000001 +289.43,50.30085681,-2.844930846,10500,0,199.9998535,0,0,0,90.00000001 +289.44,50.30085681,-2.844902821,10500,0,200.0009685,0,0,0,90.00000001 +289.45,50.30085681,-2.844874795,10500,0,200.0009685,0,0,0,90.00000001 +289.46,50.30085681,-2.84484677,10500,0,199.9998535,0,0,0,90.00000001 +289.47,50.30085681,-2.844818745,10500,0,199.9989614,0,0,0,90.00000001 +289.48,50.30085681,-2.84479072,10500,0,199.9989614,0,0,0,90.00000001 +289.49,50.30085681,-2.844762695,10500,0,199.9998535,0,0,0,90.00000001 +289.5,50.30085681,-2.84473467,10500,0,200.0009685,0,0,0,90.00000001 +289.51,50.30085681,-2.844706644,10500,0,200.0009685,0,0,0,90.00000001 +289.52,50.30085681,-2.844678619,10500,0,199.9998535,0,0,0,90.00000001 +289.53,50.30085681,-2.844650594,10500,0,199.9989614,0,0,0,90.00000001 +289.54,50.30085681,-2.844622569,10500,0,199.9989614,0,0,0,90.00000001 +289.55,50.30085681,-2.844594544,10500,0,199.9998535,0,0,0,90.00000001 +289.56,50.30085681,-2.844566519,10500,0,200.0009685,0,0,0,90.00000001 +289.57,50.30085681,-2.844538493,10500,0,200.0009685,0,0,0,90.00000001 +289.58,50.30085681,-2.844510468,10500,0,199.9998535,0,0,0,90.00000001 +289.59,50.30085681,-2.844482443,10500,0,199.9991844,0,0,0,90.00000001 +289.6,50.30085681,-2.844454418,10500,0,199.9998535,0,0,0,90.00000001 +289.61,50.30085681,-2.844426393,10500,0,200.0009685,0,0,0,90.00000001 +289.62,50.30085681,-2.844398367,10500,0,200.0009685,0,0,0,90.00000001 +289.63,50.30085681,-2.844370342,10500,0,199.9998535,0,0,0,90.00000001 +289.64,50.30085681,-2.844342317,10500,0,199.9991844,0,0,0,90.00000001 +289.65,50.30085681,-2.844314292,10500,0,199.9998535,0,0,0,90.00000001 +289.66,50.30085681,-2.844286267,10500,0,200.0009685,0,0,0,90.00000001 +289.67,50.30085681,-2.844258241,10500,0,200.0009685,0,0,0,90.00000001 +289.68,50.30085681,-2.844230216,10500,0,199.9998535,0,0,0,90.00000001 +289.69,50.30085681,-2.844202191,10500,0,199.9991844,0,0,0,90.00000001 +289.7,50.30085681,-2.844174166,10500,0,199.9998535,0,0,0,90.00000001 +289.71,50.30085681,-2.844146141,10500,0,200.0009685,0,0,0,90.00000001 +289.72,50.30085681,-2.844118115,10500,0,200.0009685,0,0,0,90.00000001 +289.73,50.30085681,-2.84409009,10500,0,199.9998535,0,0,0,90.00000001 +289.74,50.30085681,-2.844062065,10500,0,199.9991844,0,0,0,90.00000001 +289.75,50.30085681,-2.84403404,10500,0,199.9998535,0,0,0,90.00000001 +289.76,50.30085681,-2.844006015,10500,0,200.0009685,0,0,0,90.00000001 +289.77,50.30085681,-2.843977989,10500,0,200.0009685,0,0,0,90.00000001 +289.78,50.30085681,-2.843949964,10500,0,199.9998535,0,0,0,90.00000001 +289.79,50.30085681,-2.843921939,10500,0,199.9991844,0,0,0,90.00000001 +289.8,50.30085681,-2.843893914,10500,0,199.9998535,0,0,0,90.00000001 +289.81,50.30085681,-2.843865889,10500,0,200.0009685,0,0,0,90.00000001 +289.82,50.30085681,-2.843837863,10500,0,200.0009685,0,0,0,90.00000001 +289.83,50.30085681,-2.843809838,10500,0,199.9998535,0,0,0,90.00000001 +289.84,50.30085681,-2.843781813,10500,0,199.9989614,0,0,0,90.00000001 +289.85,50.30085681,-2.843753788,10500,0,199.9987384,0,0,0,90.00000001 +289.86,50.30085681,-2.843725763,10500,0,199.9989614,0,0,0,90.00000001 +289.87,50.30085681,-2.843697738,10500,0,199.9998535,0,0,0,90.00000001 +289.88,50.30085681,-2.843669713,10500,0,200.0009685,0,0,0,90.00000001 +289.89,50.30085681,-2.843641687,10500,0,200.0009685,0,0,0,90.00000001 +289.9,50.30085681,-2.843613662,10500,0,199.9998535,0,0,0,90.00000001 +289.91,50.30085681,-2.843585637,10500,0,199.9989614,0,0,0,90.00000001 +289.92,50.30085681,-2.843557612,10500,0,199.9989614,0,0,0,90.00000001 +289.93,50.30085681,-2.843529587,10500,0,199.9998535,0,0,0,90.00000001 +289.94,50.30085681,-2.843501562,10500,0,200.0009685,0,0,0,90.00000001 +289.95,50.30085681,-2.843473536,10500,0,200.0009685,0,0,0,90.00000001 +289.96,50.30085681,-2.843445511,10500,0,199.9998535,0,0,0,90.00000001 +289.97,50.30085681,-2.843417486,10500,0,199.9989614,0,0,0,90.00000001 +289.98,50.30085681,-2.843389461,10500,0,199.9989614,0,0,0,90.00000001 +289.99,50.30085681,-2.843361436,10500,0,199.9998535,0,0,0,90.00000001 +290,50.30085681,-2.843333411,10500,0,200.0009685,0,0,0,90.00000001 +290.01,50.30085681,-2.843305385,10500,0,200.0009685,0,0,0,90.00000001 +290.02,50.30085681,-2.84327736,10500,0,199.9998535,0,0,0,90.00000001 +290.03,50.30085681,-2.843249335,10500,0,199.9989614,0,0,0,90.00000001 +290.04,50.30085681,-2.84322131,10500,0,199.9989614,0,0,0,90.00000001 +290.05,50.30085681,-2.843193285,10500,0,199.9998535,0,0,0,90.00000001 +290.06,50.30085681,-2.84316526,10500,0,200.0009685,0,0,0,90.00000001 +290.07,50.30085681,-2.843137234,10500,0,200.0009685,0,0,0,90.00000001 +290.08,50.30085681,-2.843109209,10500,0,199.9998535,0,0,0,90.00000001 +290.09,50.30085681,-2.843081184,10500,0,199.9989614,0,0,0,90.00000001 +290.1,50.30085681,-2.843053159,10500,0,199.9987384,0,0,0,90.00000001 +290.11,50.30085681,-2.843025134,10500,0,199.9989614,0,0,0,90.00000001 +290.12,50.30085681,-2.842997109,10500,0,199.9998535,0,0,0,90.00000001 +290.13,50.30085681,-2.842969084,10500,0,200.0009685,0,0,0,90.00000001 +290.14,50.30085681,-2.842941058,10500,0,200.0009685,0,0,0,90.00000001 +290.15,50.30085681,-2.842913033,10500,0,199.9998535,0,0,0,90.00000001 +290.16,50.30085681,-2.842885008,10500,0,199.9991844,0,0,0,90.00000001 +290.17,50.30085681,-2.842856983,10500,0,199.9998535,0,0,0,90.00000001 +290.18,50.30085681,-2.842828958,10500,0,200.0009685,0,0,0,90.00000001 +290.19,50.30085681,-2.842800932,10500,0,200.0009685,0,0,0,90.00000001 +290.2,50.30085681,-2.842772907,10500,0,199.9998535,0,0,0,90.00000001 +290.21,50.30085681,-2.842744882,10500,0,199.9991844,0,0,0,90.00000001 +290.22,50.30085681,-2.842716857,10500,0,199.9998535,0,0,0,90.00000001 +290.23,50.30085681,-2.842688832,10500,0,200.0009685,0,0,0,90.00000001 +290.24,50.30085681,-2.842660806,10500,0,200.0009685,0,0,0,90.00000001 +290.25,50.30085681,-2.842632781,10500,0,199.9998535,0,0,0,90.00000001 +290.26,50.30085681,-2.842604756,10500,0,199.9991844,0,0,0,90.00000001 +290.27,50.30085681,-2.842576731,10500,0,199.9998535,0,0,0,90.00000001 +290.28,50.30085681,-2.842548706,10500,0,200.0009685,0,0,0,90.00000001 +290.29,50.30085681,-2.84252068,10500,0,200.0009685,0,0,0,90.00000001 +290.3,50.30085681,-2.842492655,10500,0,199.9998535,0,0,0,90.00000001 +290.31,50.30085681,-2.84246463,10500,0,199.9991844,0,0,0,90.00000001 +290.32,50.30085681,-2.842436605,10500,0,199.9998535,0,0,0,90.00000001 +290.33,50.30085681,-2.84240858,10500,0,200.0009685,0,0,0,90.00000001 +290.34,50.30085681,-2.842380554,10500,0,200.0009685,0,0,0,90.00000001 +290.35,50.30085681,-2.842352529,10500,0,199.9998535,0,0,0,90.00000001 +290.36,50.30085681,-2.842324504,10500,0,199.9991844,0,0,0,90.00000001 +290.37,50.30085681,-2.842296479,10500,0,199.9998535,0,0,0,90.00000001 +290.38,50.30085681,-2.842268454,10500,0,200.0009685,0,0,0,90.00000001 +290.39,50.30085681,-2.842240428,10500,0,200.0009685,0,0,0,90.00000001 +290.4,50.30085681,-2.842212403,10500,0,199.9998535,0,0,0,90.00000001 +290.41,50.30085681,-2.842184378,10500,0,199.9989614,0,0,0,90.00000001 +290.42,50.30085681,-2.842156353,10500,0,199.9989614,0,0,0,90.00000001 +290.43,50.30085681,-2.842128328,10500,0,199.9998535,0,0,0,90.00000001 +290.44,50.30085681,-2.842100303,10500,0,200.0009685,0,0,0,90.00000001 +290.45,50.30085681,-2.842072277,10500,0,200.0009685,0,0,0,90.00000001 +290.46,50.30085681,-2.842044252,10500,0,199.9998535,0,0,0,90.00000001 +290.47,50.30085681,-2.842016227,10500,0,199.9989614,0,0,0,90.00000001 +290.48,50.30085681,-2.841988202,10500,0,199.9989614,0,0,0,90.00000001 +290.49,50.30085681,-2.841960177,10500,0,199.9998535,0,0,0,90.00000001 +290.5,50.30085681,-2.841932152,10500,0,200.0009685,0,0,0,90.00000001 +290.51,50.30085681,-2.841904126,10500,0,200.0009685,0,0,0,90.00000001 +290.52,50.30085681,-2.841876101,10500,0,199.9998535,0,0,0,90.00000001 +290.53,50.30085681,-2.841848076,10500,0,199.9989614,0,0,0,90.00000001 +290.54,50.30085681,-2.841820051,10500,0,199.9989614,0,0,0,90.00000001 +290.55,50.30085681,-2.841792026,10500,0,199.9998535,0,0,0,90.00000001 +290.56,50.30085681,-2.841764001,10500,0,200.0009685,0,0,0,90.00000001 +290.57,50.30085681,-2.841735975,10500,0,200.0009685,0,0,0,90.00000001 +290.58,50.30085681,-2.84170795,10500,0,199.9998535,0,0,0,90.00000001 +290.59,50.30085681,-2.841679925,10500,0,199.9989614,0,0,0,90.00000001 +290.6,50.30085681,-2.8416519,10500,0,199.9989614,0,0,0,90.00000001 +290.61,50.30085681,-2.841623875,10500,0,199.9998535,0,0,0,90.00000001 +290.62,50.30085681,-2.84159585,10500,0,200.0009685,0,0,0,90.00000001 +290.63,50.30085681,-2.841567824,10500,0,200.0009685,0,0,0,90.00000001 +290.64,50.30085681,-2.841539799,10500,0,199.9998535,0,0,0,90.00000001 +290.65,50.30085681,-2.841511774,10500,0,199.9989614,0,0,0,90.00000001 +290.66,50.30085681,-2.841483749,10500,0,199.9989614,0,0,0,90.00000001 +290.67,50.30085681,-2.841455724,10500,0,199.9998535,0,0,0,90.00000001 +290.68,50.30085681,-2.841427699,10500,0,200.0009685,0,0,0,90.00000001 +290.69,50.30085681,-2.841399673,10500,0,200.0009685,0,0,0,90.00000001 +290.7,50.30085681,-2.841371648,10500,0,199.9998535,0,0,0,90.00000001 +290.71,50.30085681,-2.841343623,10500,0,199.9989614,0,0,0,90.00000001 +290.72,50.30085681,-2.841315598,10500,0,199.9987384,0,0,0,90.00000001 +290.73,50.30085681,-2.841287573,10500,0,199.9989614,0,0,0,90.00000001 +290.74,50.30085681,-2.841259548,10500,0,199.9998535,0,0,0,90.00000001 +290.75,50.30085681,-2.841231523,10500,0,200.0009685,0,0,0,90.00000001 +290.76,50.30085681,-2.841203497,10500,0,200.0009685,0,0,0,90.00000001 +290.77,50.30085681,-2.841175472,10500,0,199.9998535,0,0,0,90.00000001 +290.78,50.30085681,-2.841147447,10500,0,199.9991844,0,0,0,90.00000001 +290.79,50.30085681,-2.841119422,10500,0,199.9998535,0,0,0,90.00000001 +290.8,50.30085681,-2.841091397,10500,0,200.0009685,0,0,0,90.00000001 +290.81,50.30085681,-2.841063371,10500,0,200.0009685,0,0,0,90.00000001 +290.82,50.30085681,-2.841035346,10500,0,199.9998535,0,0,0,90.00000001 +290.83,50.30085681,-2.841007321,10500,0,199.9991844,0,0,0,90.00000001 +290.84,50.30085681,-2.840979296,10500,0,199.9998535,0,0,0,90.00000001 +290.85,50.30085681,-2.840951271,10500,0,200.0009685,0,0,0,90.00000001 +290.86,50.30085681,-2.840923245,10500,0,200.0009685,0,0,0,90.00000001 +290.87,50.30085681,-2.84089522,10500,0,199.9998535,0,0,0,90.00000001 +290.88,50.30085681,-2.840867195,10500,0,199.9991844,0,0,0,90.00000001 +290.89,50.30085681,-2.84083917,10500,0,199.9998535,0,0,0,90.00000001 +290.9,50.30085681,-2.840811145,10500,0,200.0009685,0,0,0,90.00000001 +290.91,50.30085681,-2.840783119,10500,0,200.0009685,0,0,0,90.00000001 +290.92,50.30085681,-2.840755094,10500,0,199.9998535,0,0,0,90.00000001 +290.93,50.30085681,-2.840727069,10500,0,199.9991844,0,0,0,90.00000001 +290.94,50.30085681,-2.840699044,10500,0,199.9998535,0,0,0,90.00000001 +290.95,50.30085681,-2.840671019,10500,0,200.0009685,0,0,0,90.00000001 +290.96,50.30085681,-2.840642993,10500,0,200.0009685,0,0,0,90.00000001 +290.97,50.30085681,-2.840614968,10500,0,199.9998535,0,0,0,90.00000001 +290.98,50.30085681,-2.840586943,10500,0,199.9991844,0,0,0,90.00000001 +290.99,50.30085681,-2.840558918,10500,0,199.9998535,0,0,0,90.00000001 +291,50.30085681,-2.840530893,10500,0,200.0009685,0,0,0,90.00000001 +291.01,50.30085681,-2.840502867,10500,0,200.0009685,0,0,0,90.00000001 +291.02,50.30085681,-2.840474842,10500,0,199.9998535,0,0,0,90.00000001 +291.03,50.30085681,-2.840446817,10500,0,199.9989614,0,0,0,90.00000001 +291.04,50.30085681,-2.840418792,10500,0,199.9989614,0,0,0,90.00000001 +291.05,50.30085681,-2.840390767,10500,0,199.9998535,0,0,0,90.00000001 +291.06,50.30085681,-2.840362742,10500,0,200.0009685,0,0,0,90.00000001 +291.07,50.30085681,-2.840334716,10500,0,200.0009685,0,0,0,90.00000001 +291.08,50.30085681,-2.840306691,10500,0,199.9998535,0,0,0,90.00000001 +291.09,50.30085681,-2.840278666,10500,0,199.9989614,0,0,0,90.00000001 +291.1,50.30085681,-2.840250641,10500,0,199.9989614,0,0,0,90.00000001 +291.11,50.30085681,-2.840222616,10500,0,199.9998535,0,0,0,90.00000001 +291.12,50.30085681,-2.840194591,10500,0,200.0009685,0,0,0,90.00000001 +291.13,50.30085681,-2.840166565,10500,0,200.0009685,0,0,0,90.00000001 +291.14,50.30085681,-2.84013854,10500,0,199.9998535,0,0,0,90.00000001 +291.15,50.30085681,-2.840110515,10500,0,199.9989614,0,0,0,90.00000001 +291.16,50.30085681,-2.84008249,10500,0,199.9989614,0,0,0,90.00000001 +291.17,50.30085681,-2.840054465,10500,0,199.9998535,0,0,0,90.00000001 +291.18,50.30085681,-2.84002644,10500,0,200.0009685,0,0,0,90.00000001 +291.19,50.30085681,-2.839998414,10500,0,200.0009685,0,0,0,90.00000001 +291.2,50.30085681,-2.839970389,10500,0,199.9998535,0,0,0,90.00000001 +291.21,50.30085681,-2.839942364,10500,0,199.9989614,0,0,0,90.00000001 +291.22,50.30085681,-2.839914339,10500,0,199.9989614,0,0,0,90.00000001 +291.23,50.30085681,-2.839886314,10500,0,199.9998535,0,0,0,90.00000001 +291.24,50.30085681,-2.839858289,10500,0,200.0009685,0,0,0,90.00000001 +291.25,50.30085681,-2.839830263,10500,0,200.0009685,0,0,0,90.00000001 +291.26,50.30085681,-2.839802238,10500,0,199.9998535,0,0,0,90.00000001 +291.27,50.30085681,-2.839774213,10500,0,199.9989614,0,0,0,90.00000001 +291.28,50.30085681,-2.839746188,10500,0,199.9987384,0,0,0,90.00000001 +291.29,50.30085681,-2.839718163,10500,0,199.9989614,0,0,0,90.00000001 +291.3,50.30085681,-2.839690138,10500,0,199.9998535,0,0,0,90.00000001 +291.31,50.30085681,-2.839662113,10500,0,200.0009685,0,0,0,90.00000001 +291.32,50.30085681,-2.839634087,10500,0,200.0009685,0,0,0,90.00000001 +291.33,50.30085681,-2.839606062,10500,0,199.9998535,0,0,0,90.00000001 +291.34,50.30085681,-2.839578037,10500,0,199.9989614,0,0,0,90.00000001 +291.35,50.30085681,-2.839550012,10500,0,199.9989614,0,0,0,90.00000001 +291.36,50.30085681,-2.839521987,10500,0,199.9998535,0,0,0,90.00000001 +291.37,50.30085681,-2.839493962,10500,0,200.0009685,0,0,0,90.00000001 +291.38,50.30085681,-2.839465936,10500,0,200.0009685,0,0,0,90.00000001 +291.39,50.30085681,-2.839437911,10500,0,199.9998535,0,0,0,90.00000001 +291.4,50.30085681,-2.839409886,10500,0,199.9991844,0,0,0,90.00000001 +291.41,50.30085681,-2.839381861,10500,0,199.9998535,0,0,0,90.00000001 +291.42,50.30085681,-2.839353836,10500,0,200.0009685,0,0,0,90.00000001 +291.43,50.30085681,-2.83932581,10500,0,200.0009685,0,0,0,90.00000001 +291.44,50.30085681,-2.839297785,10500,0,199.9998535,0,0,0,90.00000001 +291.45,50.30085681,-2.83926976,10500,0,199.9991844,0,0,0,90.00000001 +291.46,50.30085681,-2.839241735,10500,0,199.9998535,0,0,0,90.00000001 +291.47,50.30085681,-2.83921371,10500,0,200.0009685,0,0,0,90.00000001 +291.48,50.30085681,-2.839185684,10500,0,200.0009685,0,0,0,90.00000001 +291.49,50.30085681,-2.839157659,10500,0,199.9998535,0,0,0,90.00000001 +291.5,50.30085681,-2.839129634,10500,0,199.9989614,0,0,0,90.00000001 +291.51,50.30085681,-2.839101609,10500,0,199.9989614,0,0,0,90.00000001 +291.52,50.30085681,-2.839073584,10500,0,199.9998535,0,0,0,90.00000001 +291.53,50.30085681,-2.839045559,10500,0,200.0009685,0,0,0,90.00000001 +291.54,50.30085681,-2.839017533,10500,0,200.0009685,0,0,0,90.00000001 +291.55,50.30085681,-2.838989508,10500,0,199.9998535,0,0,0,90.00000001 +291.56,50.30085681,-2.838961483,10500,0,199.9991844,0,0,0,90.00000001 +291.57,50.30085681,-2.838933458,10500,0,199.9998535,0,0,0,90.00000001 +291.58,50.30085681,-2.838905433,10500,0,200.0009685,0,0,0,90.00000001 +291.59,50.30085681,-2.838877407,10500,0,200.0009685,0,0,0,90.00000001 +291.6,50.30085681,-2.838849382,10500,0,199.9998535,0,0,0,90.00000001 +291.61,50.30085681,-2.838821357,10500,0,199.9991844,0,0,0,90.00000001 +291.62,50.30085681,-2.838793332,10500,0,199.9998535,0,0,0,90.00000001 +291.63,50.30085681,-2.838765307,10500,0,200.0009685,0,0,0,90.00000001 +291.64,50.30085681,-2.838737281,10500,0,200.0009685,0,0,0,90.00000001 +291.65,50.30085681,-2.838709256,10500,0,199.9998535,0,0,0,90.00000001 +291.66,50.30085681,-2.838681231,10500,0,199.9991844,0,0,0,90.00000001 +291.67,50.30085681,-2.838653206,10500,0,199.9998535,0,0,0,90.00000001 +291.68,50.30085681,-2.838625181,10500,0,200.0009685,0,0,0,90.00000001 +291.69,50.30085681,-2.838597155,10500,0,200.0009685,0,0,0,90.00000001 +291.7,50.30085681,-2.83856913,10500,0,199.9998535,0,0,0,90.00000001 +291.71,50.30085681,-2.838541105,10500,0,199.9989614,0,0,0,90.00000001 +291.72,50.30085681,-2.83851308,10500,0,199.9989614,0,0,0,90.00000001 +291.73,50.30085681,-2.838485055,10500,0,199.9998535,0,0,0,90.00000001 +291.74,50.30085681,-2.83845703,10500,0,200.0009685,0,0,0,90.00000001 +291.75,50.30085681,-2.838429004,10500,0,200.0009685,0,0,0,90.00000001 +291.76,50.30085681,-2.838400979,10500,0,199.9998535,0,0,0,90.00000001 +291.77,50.30085681,-2.838372954,10500,0,199.9989614,0,0,0,90.00000001 +291.78,50.30085681,-2.838344929,10500,0,199.9989614,0,0,0,90.00000001 +291.79,50.30085681,-2.838316904,10500,0,199.9998535,0,0,0,90.00000001 +291.8,50.30085681,-2.838288879,10500,0,200.0009685,0,0,0,90.00000001 +291.81,50.30085681,-2.838260853,10500,0,200.0009685,0,0,0,90.00000001 +291.82,50.30085681,-2.838232828,10500,0,199.9998535,0,0,0,90.00000001 +291.83,50.30085681,-2.838204803,10500,0,199.9989614,0,0,0,90.00000001 +291.84,50.30085681,-2.838176778,10500,0,199.9987384,0,0,0,90.00000001 +291.85,50.30085681,-2.838148753,10500,0,199.9989614,0,0,0,90.00000001 +291.86,50.30085681,-2.838120728,10500,0,199.9998535,0,0,0,90.00000001 +291.87,50.30085681,-2.838092703,10500,0,200.0009685,0,0,0,90.00000001 +291.88,50.30085681,-2.838064677,10500,0,200.0009685,0,0,0,90.00000001 +291.89,50.30085681,-2.838036652,10500,0,199.9998535,0,0,0,90.00000001 +291.9,50.30085681,-2.838008627,10500,0,199.9989614,0,0,0,90.00000001 +291.91,50.30085681,-2.837980602,10500,0,199.9989614,0,0,0,90.00000001 +291.92,50.30085681,-2.837952577,10500,0,199.9998535,0,0,0,90.00000001 +291.93,50.30085681,-2.837924552,10500,0,200.0009685,0,0,0,90.00000001 +291.94,50.30085681,-2.837896526,10500,0,200.0009685,0,0,0,90.00000001 +291.95,50.30085681,-2.837868501,10500,0,199.9998535,0,0,0,90.00000001 +291.96,50.30085681,-2.837840476,10500,0,199.9989614,0,0,0,90.00000001 +291.97,50.30085681,-2.837812451,10500,0,199.9989614,0,0,0,90.00000001 +291.98,50.30085681,-2.837784426,10500,0,199.9998535,0,0,0,90.00000001 +291.99,50.30085681,-2.837756401,10500,0,200.0009685,0,0,0,90.00000001 +292,50.30085681,-2.837728375,10500,0,200.0009685,0,0,0,90.00000001 +292.01,50.30085681,-2.83770035,10500,0,199.9998535,0,0,0,90.00000001 +292.02,50.30085681,-2.837672325,10500,0,199.9989614,0,0,0,90.00000001 +292.03,50.30085681,-2.8376443,10500,0,199.9989614,0,0,0,90.00000001 +292.04,50.30085681,-2.837616275,10500,0,199.9998535,0,0,0,90.00000001 +292.05,50.30085681,-2.83758825,10500,0,200.0009685,0,0,0,90.00000001 +292.06,50.30085681,-2.837560224,10500,0,200.0009685,0,0,0,90.00000001 +292.07,50.30085681,-2.837532199,10500,0,199.9998535,0,0,0,90.00000001 +292.08,50.30085681,-2.837504174,10500,0,199.9991844,0,0,0,90.00000001 +292.09,50.30085681,-2.837476149,10500,0,199.9998535,0,0,0,90.00000001 +292.1,50.30085681,-2.837448124,10500,0,200.0009685,0,0,0,90.00000001 +292.11,50.30085681,-2.837420098,10500,0,200.0009685,0,0,0,90.00000001 +292.12,50.30085681,-2.837392073,10500,0,199.9998535,0,0,0,90.00000001 +292.13,50.30085681,-2.837364048,10500,0,199.9991844,0,0,0,90.00000001 +292.14,50.30085681,-2.837336023,10500,0,199.9998535,0,0,0,90.00000001 +292.15,50.30085681,-2.837307998,10500,0,200.0009685,0,0,0,90.00000001 +292.16,50.30085681,-2.837279972,10500,0,200.0009685,0,0,0,90.00000001 +292.17,50.30085681,-2.837251947,10500,0,199.9998535,0,0,0,90.00000001 +292.18,50.30085681,-2.837223922,10500,0,199.9991844,0,0,0,90.00000001 +292.19,50.30085681,-2.837195897,10500,0,199.9998535,0,0,0,90.00000001 +292.2,50.30085681,-2.837167872,10500,0,200.0009685,0,0,0,90.00000001 +292.21,50.30085681,-2.837139846,10500,0,200.0009685,0,0,0,90.00000001 +292.22,50.30085681,-2.837111821,10500,0,199.9998535,0,0,0,90.00000001 +292.23,50.30085681,-2.837083796,10500,0,199.9991844,0,0,0,90.00000001 +292.24,50.30085681,-2.837055771,10500,0,199.9998535,0,0,0,90.00000001 +292.25,50.30085681,-2.837027746,10500,0,200.0009685,0,0,0,90.00000001 +292.26,50.30085681,-2.83699972,10500,0,200.0009685,0,0,0,90.00000001 +292.27,50.30085681,-2.836971695,10500,0,199.9998535,0,0,0,90.00000001 +292.28,50.30085681,-2.83694367,10500,0,199.9991844,0,0,0,90.00000001 +292.29,50.30085681,-2.836915645,10500,0,199.9998535,0,0,0,90.00000001 +292.3,50.30085681,-2.83688762,10500,0,200.0009685,0,0,0,90.00000001 +292.31,50.30085681,-2.836859594,10500,0,200.0009685,0,0,0,90.00000001 +292.32,50.30085681,-2.836831569,10500,0,199.9998535,0,0,0,90.00000001 +292.33,50.30085681,-2.836803544,10500,0,199.9989614,0,0,0,90.00000001 +292.34,50.30085681,-2.836775519,10500,0,199.9989614,0,0,0,90.00000001 +292.35,50.30085681,-2.836747494,10500,0,199.9998535,0,0,0,90.00000001 +292.36,50.30085681,-2.836719469,10500,0,200.0009685,0,0,0,90.00000001 +292.37,50.30085681,-2.836691443,10500,0,200.0009685,0,0,0,90.00000001 +292.38,50.30085681,-2.836663418,10500,0,199.9998535,0,0,0,90.00000001 +292.39,50.30085681,-2.836635393,10500,0,199.9989614,0,0,0,90.00000001 +292.4,50.30085681,-2.836607368,10500,0,199.9987384,0,0,0,90.00000001 +292.41,50.30085681,-2.836579343,10500,0,199.9989614,0,0,0,90.00000001 +292.42,50.30085681,-2.836551318,10500,0,199.9998535,0,0,0,90.00000001 +292.43,50.30085681,-2.836523293,10500,0,200.0009685,0,0,0,90.00000001 +292.44,50.30085681,-2.836495267,10500,0,200.0009685,0,0,0,90.00000001 +292.45,50.30085681,-2.836467242,10500,0,199.9998535,0,0,0,90.00000001 +292.46,50.30085681,-2.836439217,10500,0,199.9989614,0,0,0,90.00000001 +292.47,50.30085681,-2.836411192,10500,0,199.9989614,0,0,0,90.00000001 +292.48,50.30085681,-2.836383167,10500,0,199.9998535,0,0,0,90.00000001 +292.49,50.30085681,-2.836355142,10500,0,200.0009685,0,0,0,90.00000001 +292.5,50.30085681,-2.836327116,10500,0,200.0009685,0,0,0,90.00000001 +292.51,50.30085681,-2.836299091,10500,0,199.9998535,0,0,0,90.00000001 +292.52,50.30085681,-2.836271066,10500,0,199.9989614,0,0,0,90.00000001 +292.53,50.30085681,-2.836243041,10500,0,199.9989614,0,0,0,90.00000001 +292.54,50.30085681,-2.836215016,10500,0,199.9998535,0,0,0,90.00000001 +292.55,50.30085681,-2.836186991,10500,0,200.0009685,0,0,0,90.00000001 +292.56,50.30085681,-2.836158965,10500,0,200.0009685,0,0,0,90.00000001 +292.57,50.30085681,-2.83613094,10500,0,199.9998535,0,0,0,90.00000001 +292.58,50.30085681,-2.836102915,10500,0,199.9989614,0,0,0,90.00000001 +292.59,50.30085681,-2.83607489,10500,0,199.9989614,0,0,0,90.00000001 +292.6,50.30085681,-2.836046865,10500,0,199.9998535,0,0,0,90.00000001 +292.61,50.30085681,-2.83601884,10500,0,200.0009685,0,0,0,90.00000001 +292.62,50.30085681,-2.835990814,10500,0,200.0009685,0,0,0,90.00000001 +292.63,50.30085681,-2.835962789,10500,0,199.9998535,0,0,0,90.00000001 +292.64,50.30085681,-2.835934764,10500,0,199.9989614,0,0,0,90.00000001 +292.65,50.30085681,-2.835906739,10500,0,199.9989614,0,0,0,90.00000001 +292.66,50.30085681,-2.835878714,10500,0,199.9998535,0,0,0,90.00000001 +292.67,50.30085681,-2.835850689,10500,0,200.0009685,0,0,0,90.00000001 +292.68,50.30085681,-2.835822663,10500,0,200.0009685,0,0,0,90.00000001 +292.69,50.30085681,-2.835794638,10500,0,199.9998535,0,0,0,90.00000001 +292.7,50.30085681,-2.835766613,10500,0,199.9991844,0,0,0,90.00000001 +292.71,50.30085681,-2.835738588,10500,0,199.9998535,0,0,0,90.00000001 +292.72,50.30085681,-2.835710563,10500,0,200.0009685,0,0,0,90.00000001 +292.73,50.30085681,-2.835682537,10500,0,200.0009685,0,0,0,90.00000001 +292.74,50.30085681,-2.835654512,10500,0,199.9998535,0,0,0,90.00000001 +292.75,50.30085681,-2.835626487,10500,0,199.9991844,0,0,0,90.00000001 +292.76,50.30085681,-2.835598462,10500,0,199.9998535,0,0,0,90.00000001 +292.77,50.30085681,-2.835570437,10500,0,200.0009685,0,0,0,90.00000001 +292.78,50.30085681,-2.835542411,10500,0,200.0009685,0,0,0,90.00000001 +292.79,50.30085681,-2.835514386,10500,0,199.9998535,0,0,0,90.00000001 +292.8,50.30085681,-2.835486361,10500,0,199.9991844,0,0,0,90.00000001 +292.81,50.30085681,-2.835458336,10500,0,199.9998535,0,0,0,90.00000001 +292.82,50.30085681,-2.835430311,10500,0,200.0009685,0,0,0,90.00000001 +292.83,50.30085681,-2.835402285,10500,0,200.0009685,0,0,0,90.00000001 +292.84,50.30085681,-2.83537426,10500,0,199.9998535,0,0,0,90.00000001 +292.85,50.30085681,-2.835346235,10500,0,199.9991844,0,0,0,90.00000001 +292.86,50.30085681,-2.83531821,10500,0,199.9998535,0,0,0,90.00000001 +292.87,50.30085681,-2.835290185,10500,0,200.0009685,0,0,0,90.00000001 +292.88,50.30085681,-2.835262159,10500,0,200.0009685,0,0,0,90.00000001 +292.89,50.30085681,-2.835234134,10500,0,199.9998535,0,0,0,90.00000001 +292.9,50.30085681,-2.835206109,10500,0,199.9991844,0,0,0,90.00000001 +292.91,50.30085681,-2.835178084,10500,0,199.9998535,0,0,0,90.00000001 +292.92,50.30085681,-2.835150059,10500,0,200.0009685,0,0,0,90.00000001 +292.93,50.30085681,-2.835122033,10500,0,200.0009685,0,0,0,90.00000001 +292.94,50.30085681,-2.835094008,10500,0,199.9998535,0,0,0,90.00000001 +292.95,50.30085681,-2.835065983,10500,0,199.9989614,0,0,0,90.00000001 +292.96,50.30085681,-2.835037958,10500,0,199.9987384,0,0,0,90.00000001 +292.97,50.30085681,-2.835009933,10500,0,199.9989614,0,0,0,90.00000001 +292.98,50.30085681,-2.834981908,10500,0,199.9998535,0,0,0,90.00000001 +292.99,50.30085681,-2.834953883,10500,0,200.0009685,0,0,0,90.00000001 +293,50.30085681,-2.834925857,10500,0,200.0009685,0,0,0,90.00000001 +293.01,50.30085681,-2.834897832,10500,0,199.9998535,0,0,0,90.00000001 +293.02,50.30085681,-2.834869807,10500,0,199.9989614,0,0,0,90.00000001 +293.03,50.30085681,-2.834841782,10500,0,199.9989614,0,0,0,90.00000001 +293.04,50.30085681,-2.834813757,10500,0,199.9998535,0,0,0,90.00000001 +293.05,50.30085681,-2.834785732,10500,0,200.0009685,0,0,0,90.00000001 +293.06,50.30085681,-2.834757706,10500,0,200.0009685,0,0,0,90.00000001 +293.07,50.30085681,-2.834729681,10500,0,199.9998535,0,0,0,90.00000001 +293.08,50.30085681,-2.834701656,10500,0,199.9989614,0,0,0,90.00000001 +293.09,50.30085681,-2.834673631,10500,0,199.9989614,0,0,0,90.00000001 +293.1,50.30085681,-2.834645606,10500,0,199.9998535,0,0,0,90.00000001 +293.11,50.30085681,-2.834617581,10500,0,200.0009685,0,0,0,90.00000001 +293.12,50.30085681,-2.834589555,10500,0,200.0009685,0,0,0,90.00000001 +293.13,50.30085681,-2.83456153,10500,0,199.9998535,0,0,0,90.00000001 +293.14,50.30085681,-2.834533505,10500,0,199.9989614,0,0,0,90.00000001 +293.15,50.30085681,-2.83450548,10500,0,199.9989614,0,0,0,90.00000001 +293.16,50.30085681,-2.834477455,10500,0,199.9998535,0,0,0,90.00000001 +293.17,50.30085681,-2.83444943,10500,0,200.0009685,0,0,0,90.00000001 +293.18,50.30085681,-2.834421404,10500,0,200.0009685,0,0,0,90.00000001 +293.19,50.30085681,-2.834393379,10500,0,199.9998535,0,0,0,90.00000001 +293.2,50.30085681,-2.834365354,10500,0,199.9989614,0,0,0,90.00000001 +293.21,50.30085681,-2.834337329,10500,0,199.9989614,0,0,0,90.00000001 +293.22,50.30085681,-2.834309304,10500,0,199.9998535,0,0,0,90.00000001 +293.23,50.30085681,-2.834281279,10500,0,200.0009685,0,0,0,90.00000001 +293.24,50.30085681,-2.834253253,10500,0,200.0009685,0,0,0,90.00000001 +293.25,50.30085681,-2.834225228,10500,0,199.9998535,0,0,0,90.00000001 +293.26,50.30085681,-2.834197203,10500,0,199.9989614,0,0,0,90.00000001 +293.27,50.30085681,-2.834169178,10500,0,199.9989614,0,0,0,90.00000001 +293.28,50.30085681,-2.834141153,10500,0,199.9998535,0,0,0,90.00000001 +293.29,50.30085681,-2.834113128,10500,0,200.0009685,0,0,0,90.00000001 +293.3,50.30085681,-2.834085102,10500,0,200.0009685,0,0,0,90.00000001 +293.31,50.30085681,-2.834057077,10500,0,199.9998535,0,0,0,90.00000001 +293.32,50.30085681,-2.834029052,10500,0,199.9991844,0,0,0,90.00000001 +293.33,50.30085681,-2.834001027,10500,0,199.9998535,0,0,0,90.00000001 +293.34,50.30085681,-2.833973002,10500,0,200.0009685,0,0,0,90.00000001 +293.35,50.30085681,-2.833944976,10500,0,200.0009685,0,0,0,90.00000001 +293.36,50.30085681,-2.833916951,10500,0,199.9998535,0,0,0,90.00000001 +293.37,50.30085681,-2.833888926,10500,0,199.9991844,0,0,0,90.00000001 +293.38,50.30085681,-2.833860901,10500,0,199.9998535,0,0,0,90.00000001 +293.39,50.30085681,-2.833832876,10500,0,200.0009685,0,0,0,90.00000001 +293.4,50.30085681,-2.83380485,10500,0,200.0009685,0,0,0,90.00000001 +293.41,50.30085681,-2.833776825,10500,0,199.9998535,0,0,0,90.00000001 +293.42,50.30085681,-2.8337488,10500,0,199.9991844,0,0,0,90.00000001 +293.43,50.30085681,-2.833720775,10500,0,199.9998535,0,0,0,90.00000001 +293.44,50.30085681,-2.83369275,10500,0,200.0009685,0,0,0,90.00000001 +293.45,50.30085681,-2.833664724,10500,0,200.0009685,0,0,0,90.00000001 +293.46,50.30085681,-2.833636699,10500,0,199.9998535,0,0,0,90.00000001 +293.47,50.30085681,-2.833608674,10500,0,199.9991844,0,0,0,90.00000001 +293.48,50.30085681,-2.833580649,10500,0,199.9998535,0,0,0,90.00000001 +293.49,50.30085681,-2.833552624,10500,0,200.0009685,0,0,0,90.00000001 +293.5,50.30085681,-2.833524598,10500,0,200.0009685,0,0,0,90.00000001 +293.51,50.30085681,-2.833496573,10500,0,199.9998535,0,0,0,90.00000001 +293.52,50.30085681,-2.833468548,10500,0,199.9991844,0,0,0,90.00000001 +293.53,50.30085681,-2.833440523,10500,0,199.9998535,0,0,0,90.00000001 +293.54,50.30085681,-2.833412498,10500,0,200.0009685,0,0,0,90.00000001 +293.55,50.30085681,-2.833384472,10500,0,200.0009685,0,0,0,90.00000001 +293.56,50.30085681,-2.833356447,10500,0,199.9998535,0,0,0,90.00000001 +293.57,50.30085681,-2.833328422,10500,0,199.9989614,0,0,0,90.00000001 +293.58,50.30085681,-2.833300397,10500,0,199.9987384,0,0,0,90.00000001 +293.59,50.30085681,-2.833272372,10500,0,199.9989614,0,0,0,90.00000001 +293.6,50.30085681,-2.833244347,10500,0,199.9998535,0,0,0,90.00000001 +293.61,50.30085681,-2.833216322,10500,0,200.0009685,0,0,0,90.00000001 +293.62,50.30085681,-2.833188296,10500,0,200.0009685,0,0,0,90.00000001 +293.63,50.30085681,-2.833160271,10500,0,199.9998535,0,0,0,90.00000001 +293.64,50.30085681,-2.833132246,10500,0,199.9989614,0,0,0,90.00000001 +293.65,50.30085681,-2.833104221,10500,0,199.9989614,0,0,0,90.00000001 +293.66,50.30085681,-2.833076196,10500,0,199.9998535,0,0,0,90.00000001 +293.67,50.30085681,-2.833048171,10500,0,200.0009685,0,0,0,90.00000001 +293.68,50.30085681,-2.833020145,10500,0,200.0009685,0,0,0,90.00000001 +293.69,50.30085681,-2.83299212,10500,0,199.9998535,0,0,0,90.00000001 +293.7,50.30085681,-2.832964095,10500,0,199.9989614,0,0,0,90.00000001 +293.71,50.30085681,-2.83293607,10500,0,199.9989614,0,0,0,90.00000001 +293.72,50.30085681,-2.832908045,10500,0,199.9998535,0,0,0,90.00000001 +293.73,50.30085681,-2.83288002,10500,0,200.0009685,0,0,0,90.00000001 +293.74,50.30085681,-2.832851994,10500,0,200.0009685,0,0,0,90.00000001 +293.75,50.30085681,-2.832823969,10500,0,199.9998535,0,0,0,90.00000001 +293.76,50.30085681,-2.832795944,10500,0,199.9989614,0,0,0,90.00000001 +293.77,50.30085681,-2.832767919,10500,0,199.9989614,0,0,0,90.00000001 +293.78,50.30085681,-2.832739894,10500,0,199.9998535,0,0,0,90.00000001 +293.79,50.30085681,-2.832711869,10500,0,200.0009685,0,0,0,90.00000001 +293.8,50.30085681,-2.832683843,10500,0,200.0009685,0,0,0,90.00000001 +293.81,50.30085681,-2.832655818,10500,0,199.9998535,0,0,0,90.00000001 +293.82,50.30085681,-2.832627793,10500,0,199.9989614,0,0,0,90.00000001 +293.83,50.30085681,-2.832599768,10500,0,199.9987384,0,0,0,90.00000001 +293.84,50.30085681,-2.832571743,10500,0,199.9989614,0,0,0,90.00000001 +293.85,50.30085681,-2.832543718,10500,0,199.9998535,0,0,0,90.00000001 +293.86,50.30085681,-2.832515693,10500,0,200.0009685,0,0,0,90.00000001 +293.87,50.30085681,-2.832487667,10500,0,200.0009685,0,0,0,90.00000001 +293.88,50.30085681,-2.832459642,10500,0,199.9998535,0,0,0,90.00000001 +293.89,50.30085681,-2.832431617,10500,0,199.9989614,0,0,0,90.00000001 +293.9,50.30085681,-2.832403592,10500,0,199.9989614,0,0,0,90.00000001 +293.91,50.30085681,-2.832375567,10500,0,199.9998535,0,0,0,90.00000001 +293.92,50.30085681,-2.832347542,10500,0,200.0009685,0,0,0,90.00000001 +293.93,50.30085681,-2.832319516,10500,0,200.0009685,0,0,0,90.00000001 +293.94,50.30085681,-2.832291491,10500,0,199.9998535,0,0,0,90.00000001 +293.95,50.30085681,-2.832263466,10500,0,199.9991844,0,0,0,90.00000001 +293.96,50.30085681,-2.832235441,10500,0,199.9998535,0,0,0,90.00000001 +293.97,50.30085681,-2.832207416,10500,0,200.0009685,0,0,0,90.00000001 +293.98,50.30085681,-2.83217939,10500,0,200.0009685,0,0,0,90.00000001 +293.99,50.30085681,-2.832151365,10500,0,199.9998535,0,0,0,90.00000001 +294,50.30085681,-2.83212334,10500,0,199.9991844,0,0,0,90.00000001 +294.01,50.30085681,-2.832095315,10500,0,199.9998535,0,0,0,90.00000001 +294.02,50.30085681,-2.83206729,10500,0,200.0009685,0,0,0,90.00000001 +294.03,50.30085681,-2.832039264,10500,0,200.0009685,0,0,0,90.00000001 +294.04,50.30085681,-2.832011239,10500,0,199.9998535,0,0,0,90.00000001 +294.05,50.30085681,-2.831983214,10500,0,199.9991844,0,0,0,90.00000001 +294.06,50.30085681,-2.831955189,10500,0,199.9998535,0,0,0,90.00000001 +294.07,50.30085681,-2.831927164,10500,0,200.0009685,0,0,0,90.00000001 +294.08,50.30085681,-2.831899138,10500,0,200.0009685,0,0,0,90.00000001 +294.09,50.30085681,-2.831871113,10500,0,199.9998535,0,0,0,90.00000001 +294.1,50.30085681,-2.831843088,10500,0,199.9991844,0,0,0,90.00000001 +294.11,50.30085681,-2.831815063,10500,0,199.9998535,0,0,0,90.00000001 +294.12,50.30085681,-2.831787038,10500,0,200.0009685,0,0,0,90.00000001 +294.13,50.30085681,-2.831759012,10500,0,200.0009685,0,0,0,90.00000001 +294.14,50.30085681,-2.831730987,10500,0,199.9998535,0,0,0,90.00000001 +294.15,50.30085681,-2.831702962,10500,0,199.9991844,0,0,0,90.00000001 +294.16,50.30085681,-2.831674937,10500,0,199.9998535,0,0,0,90.00000001 +294.17,50.30085681,-2.831646912,10500,0,200.0009685,0,0,0,90.00000001 +294.18,50.30085681,-2.831618886,10500,0,200.0009685,0,0,0,90.00000001 +294.19,50.30085681,-2.831590861,10500,0,199.9998535,0,0,0,90.00000001 +294.2,50.30085681,-2.831562836,10500,0,199.9989614,0,0,0,90.00000001 +294.21,50.30085681,-2.831534811,10500,0,199.9989614,0,0,0,90.00000001 +294.22,50.30085681,-2.831506786,10500,0,199.9998535,0,0,0,90.00000001 +294.23,50.30085681,-2.831478761,10500,0,200.0009685,0,0,0,90.00000001 +294.24,50.30085681,-2.831450735,10500,0,200.0009685,0,0,0,90.00000001 +294.25,50.30085681,-2.83142271,10500,0,199.9998535,0,0,0,90.00000001 +294.26,50.30085681,-2.831394685,10500,0,199.9989614,0,0,0,90.00000001 +294.27,50.30085681,-2.83136666,10500,0,199.9989614,0,0,0,90.00000001 +294.28,50.30085681,-2.831338635,10500,0,199.9998535,0,0,0,90.00000001 +294.29,50.30085681,-2.83131061,10500,0,200.0009685,0,0,0,90.00000001 +294.3,50.30085681,-2.831282584,10500,0,200.0009685,0,0,0,90.00000001 +294.31,50.30085681,-2.831254559,10500,0,199.9998535,0,0,0,90.00000001 +294.32,50.30085681,-2.831226534,10500,0,199.9989614,0,0,0,90.00000001 +294.33,50.30085681,-2.831198509,10500,0,199.9989614,0,0,0,90.00000001 +294.34,50.30085681,-2.831170484,10500,0,199.9998535,0,0,0,90.00000001 +294.35,50.30085681,-2.831142459,10500,0,200.0009685,0,0,0,90.00000001 +294.36,50.30085681,-2.831114433,10500,0,200.0009685,0,0,0,90.00000001 +294.37,50.30085681,-2.831086408,10500,0,199.9998535,0,0,0,90.00000001 +294.38,50.30085681,-2.831058383,10500,0,199.9989614,0,0,0,90.00000001 +294.39,50.30085681,-2.831030358,10500,0,199.9987384,0,0,0,90.00000001 +294.4,50.30085681,-2.831002333,10500,0,199.9989614,0,0,0,90.00000001 +294.41,50.30085681,-2.830974308,10500,0,199.9998535,0,0,0,90.00000001 +294.42,50.30085681,-2.830946283,10500,0,200.0009685,0,0,0,90.00000001 +294.43,50.30085681,-2.830918257,10500,0,200.0009685,0,0,0,90.00000001 +294.44,50.30085681,-2.830890232,10500,0,199.9998535,0,0,0,90.00000001 +294.45,50.30085681,-2.830862207,10500,0,199.9989614,0,0,0,90.00000001 +294.46,50.30085681,-2.830834182,10500,0,199.9989614,0,0,0,90.00000001 +294.47,50.30085681,-2.830806157,10500,0,199.9998535,0,0,0,90.00000001 +294.48,50.30085681,-2.830778132,10500,0,200.0009685,0,0,0,90.00000001 +294.49,50.30085681,-2.830750106,10500,0,200.0009685,0,0,0,90.00000001 +294.5,50.30085681,-2.830722081,10500,0,199.9998535,0,0,0,90.00000001 +294.51,50.30085681,-2.830694056,10500,0,199.9989614,0,0,0,90.00000001 +294.52,50.30085681,-2.830666031,10500,0,199.9989614,0,0,0,90.00000001 +294.53,50.30085681,-2.830638006,10500,0,199.9998535,0,0,0,90.00000001 +294.54,50.30085681,-2.830609981,10500,0,200.0009685,0,0,0,90.00000001 +294.55,50.30085681,-2.830581955,10500,0,200.0009685,0,0,0,90.00000001 +294.56,50.30085681,-2.83055393,10500,0,199.9998535,0,0,0,90.00000001 +294.57,50.30085681,-2.830525905,10500,0,199.9991844,0,0,0,90.00000001 +294.58,50.30085681,-2.83049788,10500,0,199.9998535,0,0,0,90.00000001 +294.59,50.30085681,-2.830469855,10500,0,200.0009685,0,0,0,90.00000001 +294.6,50.30085681,-2.830441829,10500,0,200.0009685,0,0,0,90.00000001 +294.61,50.30085681,-2.830413804,10500,0,199.9998535,0,0,0,90.00000001 +294.62,50.30085681,-2.830385779,10500,0,199.9991844,0,0,0,90.00000001 +294.63,50.30085681,-2.830357754,10500,0,199.9998535,0,0,0,90.00000001 +294.64,50.30085681,-2.830329729,10500,0,200.0009685,0,0,0,90.00000001 +294.65,50.30085681,-2.830301703,10500,0,200.0009685,0,0,0,90.00000001 +294.66,50.30085681,-2.830273678,10500,0,199.9998535,0,0,0,90.00000001 +294.67,50.30085681,-2.830245653,10500,0,199.9991844,0,0,0,90.00000001 +294.68,50.30085681,-2.830217628,10500,0,199.9998535,0,0,0,90.00000001 +294.69,50.30085681,-2.830189603,10500,0,200.0009685,0,0,0,90.00000001 +294.7,50.30085681,-2.830161577,10500,0,200.0009685,0,0,0,90.00000001 +294.71,50.30085681,-2.830133552,10500,0,199.9998535,0,0,0,90.00000001 +294.72,50.30085681,-2.830105527,10500,0,199.9991844,0,0,0,90.00000001 +294.73,50.30085681,-2.830077502,10500,0,199.9998535,0,0,0,90.00000001 +294.74,50.30085681,-2.830049477,10500,0,200.0009685,0,0,0,90.00000001 +294.75,50.30085681,-2.830021451,10500,0,200.0009685,0,0,0,90.00000001 +294.76,50.30085681,-2.829993426,10500,0,199.9998535,0,0,0,90.00000001 +294.77,50.30085681,-2.829965401,10500,0,199.9991844,0,0,0,90.00000001 +294.78,50.30085681,-2.829937376,10500,0,199.9998535,0,0,0,90.00000001 +294.79,50.30085681,-2.829909351,10500,0,200.0009685,0,0,0,90.00000001 +294.8,50.30085681,-2.829881325,10500,0,200.0009685,0,0,0,90.00000001 +294.81,50.30085681,-2.8298533,10500,0,199.9998535,0,0,0,90.00000001 +294.82,50.30085681,-2.829825275,10500,0,199.9989614,0,0,0,90.00000001 +294.83,50.30085681,-2.82979725,10500,0,199.9989614,0,0,0,90.00000001 +294.84,50.30085681,-2.829769225,10500,0,199.9998535,0,0,0,90.00000001 +294.85,50.30085681,-2.8297412,10500,0,200.0009685,0,0,0,90.00000001 +294.86,50.30085681,-2.829713174,10500,0,200.0009685,0,0,0,90.00000001 +294.87,50.30085681,-2.829685149,10500,0,199.9998535,0,0,0,90.00000001 +294.88,50.30085681,-2.829657124,10500,0,199.9989614,0,0,0,90.00000001 +294.89,50.30085681,-2.829629099,10500,0,199.9989614,0,0,0,90.00000001 +294.9,50.30085681,-2.829601074,10500,0,199.9998535,0,0,0,90.00000001 +294.91,50.30085681,-2.829573049,10500,0,200.0009685,0,0,0,90.00000001 +294.92,50.30085681,-2.829545023,10500,0,200.0009685,0,0,0,90.00000001 +294.93,50.30085681,-2.829516998,10500,0,199.9998535,0,0,0,90.00000001 +294.94,50.30085681,-2.829488973,10500,0,199.9989614,0,0,0,90.00000001 +294.95,50.30085681,-2.829460948,10500,0,199.9989614,0,0,0,90.00000001 +294.96,50.30085681,-2.829432923,10500,0,199.9998535,0,0,0,90.00000001 +294.97,50.30085681,-2.829404898,10500,0,200.0009685,0,0,0,90.00000001 +294.98,50.30085681,-2.829376872,10500,0,200.0009685,0,0,0,90.00000001 +294.99,50.30085681,-2.829348847,10500,0,199.9998535,0,0,0,90.00000001 +295,50.30085681,-2.829320822,10500,0,199.9989614,0,0,0,90.00000001 +295.01,50.30085681,-2.829292797,10500,0,199.9987384,0,0,0,90.00000001 +295.02,50.30085681,-2.829264772,10500,0,199.9989614,0,0,0,90.00000001 +295.03,50.30085681,-2.829236747,10500,0,199.9998535,0,0,0,90.00000001 +295.04,50.30085681,-2.829208722,10500,0,200.0009685,0,0,0,90.00000001 +295.05,50.30085681,-2.829180696,10500,0,200.0009685,0,0,0,90.00000001 +295.06,50.30085681,-2.829152671,10500,0,199.9998535,0,0,0,90.00000001 +295.07,50.30085681,-2.829124646,10500,0,199.9989614,0,0,0,90.00000001 +295.08,50.30085681,-2.829096621,10500,0,199.9989614,0,0,0,90.00000001 +295.09,50.30085681,-2.829068596,10500,0,199.9998535,0,0,0,90.00000001 +295.1,50.30085681,-2.829040571,10500,0,200.0009685,0,0,0,90.00000001 +295.11,50.30085681,-2.829012545,10500,0,200.0009685,0,0,0,90.00000001 +295.12,50.30085681,-2.82898452,10500,0,199.9998535,0,0,0,90.00000001 +295.13,50.30085681,-2.828956495,10500,0,199.9989614,0,0,0,90.00000001 +295.14,50.30085681,-2.82892847,10500,0,199.9989614,0,0,0,90.00000001 +295.15,50.30085681,-2.828900445,10500,0,199.9998535,0,0,0,90.00000001 +295.16,50.30085681,-2.82887242,10500,0,200.0009685,0,0,0,90.00000001 +295.17,50.30085681,-2.828844394,10500,0,200.0009685,0,0,0,90.00000001 +295.18,50.30085681,-2.828816369,10500,0,199.9998535,0,0,0,90.00000001 +295.19,50.30085681,-2.828788344,10500,0,199.9991844,0,0,0,90.00000001 +295.2,50.30085681,-2.828760319,10500,0,199.9998535,0,0,0,90.00000001 +295.21,50.30085681,-2.828732294,10500,0,200.0009685,0,0,0,90.00000001 +295.22,50.30085681,-2.828704268,10500,0,200.0009685,0,0,0,90.00000001 +295.23,50.30085681,-2.828676243,10500,0,199.9998535,0,0,0,90.00000001 +295.24,50.30085681,-2.828648218,10500,0,199.9991844,0,0,0,90.00000001 +295.25,50.30085681,-2.828620193,10500,0,199.9998535,0,0,0,90.00000001 +295.26,50.30085681,-2.828592168,10500,0,200.0009685,0,0,0,90.00000001 +295.27,50.30085681,-2.828564142,10500,0,200.0009685,0,0,0,90.00000001 +295.28,50.30085681,-2.828536117,10500,0,199.9998535,0,0,0,90.00000001 +295.29,50.30085681,-2.828508092,10500,0,199.9991844,0,0,0,90.00000001 +295.3,50.30085681,-2.828480067,10500,0,199.9998535,0,0,0,90.00000001 +295.31,50.30085681,-2.828452042,10500,0,200.0009685,0,0,0,90.00000001 +295.32,50.30085681,-2.828424016,10500,0,200.0009685,0,0,0,90.00000001 +295.33,50.30085681,-2.828395991,10500,0,199.9998535,0,0,0,90.00000001 +295.34,50.30085681,-2.828367966,10500,0,199.9991844,0,0,0,90.00000001 +295.35,50.30085681,-2.828339941,10500,0,199.9998535,0,0,0,90.00000001 +295.36,50.30085681,-2.828311916,10500,0,200.0009685,0,0,0,90.00000001 +295.37,50.30085681,-2.82828389,10500,0,200.0009685,0,0,0,90.00000001 +295.38,50.30085681,-2.828255865,10500,0,199.9998535,0,0,0,90.00000001 +295.39,50.30085681,-2.82822784,10500,0,199.9991844,0,0,0,90.00000001 +295.4,50.30085681,-2.828199815,10500,0,199.9998535,0,0,0,90.00000001 +295.41,50.30085681,-2.82817179,10500,0,200.0009685,0,0,0,90.00000001 +295.42,50.30085681,-2.828143764,10500,0,200.0009685,0,0,0,90.00000001 +295.43,50.30085681,-2.828115739,10500,0,199.9998535,0,0,0,90.00000001 +295.44,50.30085681,-2.828087714,10500,0,199.9989614,0,0,0,90.00000001 +295.45,50.30085681,-2.828059689,10500,0,199.9989614,0,0,0,90.00000001 +295.46,50.30085681,-2.828031664,10500,0,199.9998535,0,0,0,90.00000001 +295.47,50.30085681,-2.828003639,10500,0,200.0009685,0,0,0,90.00000001 +295.48,50.30085681,-2.827975613,10500,0,200.0009685,0,0,0,90.00000001 +295.49,50.30085681,-2.827947588,10500,0,199.9998535,0,0,0,90.00000001 +295.5,50.30085681,-2.827919563,10500,0,199.9989614,0,0,0,90.00000001 +295.51,50.30085681,-2.827891538,10500,0,199.9989614,0,0,0,90.00000001 +295.52,50.30085681,-2.827863513,10500,0,199.9998535,0,0,0,90.00000001 +295.53,50.30085681,-2.827835488,10500,0,200.0009685,0,0,0,90.00000001 +295.54,50.30085681,-2.827807462,10500,0,200.0009685,0,0,0,90.00000001 +295.55,50.30085681,-2.827779437,10500,0,199.9998535,0,0,0,90.00000001 +295.56,50.30085681,-2.827751412,10500,0,199.9989614,0,0,0,90.00000001 +295.57,50.30085681,-2.827723387,10500,0,199.9987384,0,0,0,90.00000001 +295.58,50.30085681,-2.827695362,10500,0,199.9989614,0,0,0,90.00000001 +295.59,50.30085681,-2.827667337,10500,0,199.9998535,0,0,0,90.00000001 +295.6,50.30085681,-2.827639312,10500,0,200.0009685,0,0,0,90.00000001 +295.61,50.30085681,-2.827611286,10500,0,200.0009685,0,0,0,90.00000001 +295.62,50.30085681,-2.827583261,10500,0,199.9998535,0,0,0,90.00000001 +295.63,50.30085681,-2.827555236,10500,0,199.9989614,0,0,0,90.00000001 +295.64,50.30085681,-2.827527211,10500,0,199.9989614,0,0,0,90.00000001 +295.65,50.30085681,-2.827499186,10500,0,199.9998535,0,0,0,90.00000001 +295.66,50.30085681,-2.827471161,10500,0,200.0009685,0,0,0,90.00000001 +295.67,50.30085681,-2.827443135,10500,0,200.0009685,0,0,0,90.00000001 +295.68,50.30085681,-2.82741511,10500,0,199.9998535,0,0,0,90.00000001 +295.69,50.30085681,-2.827387085,10500,0,199.9989614,0,0,0,90.00000001 +295.7,50.30085681,-2.82735906,10500,0,199.9989614,0,0,0,90.00000001 +295.71,50.30085681,-2.827331035,10500,0,199.9998535,0,0,0,90.00000001 +295.72,50.30085681,-2.82730301,10500,0,200.0009685,0,0,0,90.00000001 +295.73,50.30085681,-2.827274984,10500,0,200.0009685,0,0,0,90.00000001 +295.74,50.30085681,-2.827246959,10500,0,199.9998535,0,0,0,90.00000001 +295.75,50.30085681,-2.827218934,10500,0,199.9989614,0,0,0,90.00000001 +295.76,50.30085681,-2.827190909,10500,0,199.9989614,0,0,0,90.00000001 +295.77,50.30085681,-2.827162884,10500,0,199.9998535,0,0,0,90.00000001 +295.78,50.30085681,-2.827134859,10500,0,200.0009685,0,0,0,90.00000001 +295.79,50.30085681,-2.827106833,10500,0,200.0009685,0,0,0,90.00000001 +295.8,50.30085681,-2.827078808,10500,0,199.9998535,0,0,0,90.00000001 +295.81,50.30085681,-2.827050783,10500,0,199.9991844,0,0,0,90.00000001 +295.82,50.30085681,-2.827022758,10500,0,199.9998535,0,0,0,90.00000001 +295.83,50.30085681,-2.826994733,10500,0,200.0009685,0,0,0,90.00000001 +295.84,50.30085681,-2.826966707,10500,0,200.0009685,0,0,0,90.00000001 +295.85,50.30085681,-2.826938682,10500,0,199.9998535,0,0,0,90.00000001 +295.86,50.30085681,-2.826910657,10500,0,199.9991844,0,0,0,90.00000001 +295.87,50.30085681,-2.826882632,10500,0,199.9998535,0,0,0,90.00000001 +295.88,50.30085681,-2.826854607,10500,0,200.0009685,0,0,0,90.00000001 +295.89,50.30085681,-2.826826581,10500,0,200.0009685,0,0,0,90.00000001 +295.9,50.30085681,-2.826798556,10500,0,199.9998535,0,0,0,90.00000001 +295.91,50.30085681,-2.826770531,10500,0,199.9991844,0,0,0,90.00000001 +295.92,50.30085681,-2.826742506,10500,0,199.9998535,0,0,0,90.00000001 +295.93,50.30085681,-2.826714481,10500,0,200.0009685,0,0,0,90.00000001 +295.94,50.30085681,-2.826686455,10500,0,200.0009685,0,0,0,90.00000001 +295.95,50.30085681,-2.82665843,10500,0,199.9998535,0,0,0,90.00000001 +295.96,50.30085681,-2.826630405,10500,0,199.9989614,0,0,0,90.00000001 +295.97,50.30085681,-2.82660238,10500,0,199.9989614,0,0,0,90.00000001 +295.98,50.30085681,-2.826574355,10500,0,199.9998535,0,0,0,90.00000001 +295.99,50.30085681,-2.82654633,10500,0,200.0009685,0,0,0,90.00000001 +296,50.30085681,-2.826518304,10500,0,200.0009685,0,0,0,90.00000001 +296.01,50.30085681,-2.826490279,10500,0,199.9998535,0,0,0,90.00000001 +296.02,50.30085681,-2.826462254,10500,0,199.9991844,0,0,0,90.00000001 +296.03,50.30085681,-2.826434229,10500,0,199.9998535,0,0,0,90.00000001 +296.04,50.30085681,-2.826406204,10500,0,200.0009685,0,0,0,90.00000001 +296.05,50.30085681,-2.826378178,10500,0,200.0009685,0,0,0,90.00000001 +296.06,50.30085681,-2.826350153,10500,0,199.9998535,0,0,0,90.00000001 +296.07,50.30085681,-2.826322128,10500,0,199.9991844,0,0,0,90.00000001 +296.08,50.30085681,-2.826294103,10500,0,199.9998535,0,0,0,90.00000001 +296.09,50.30085681,-2.826266078,10500,0,200.0009685,0,0,0,90.00000001 +296.1,50.30085681,-2.826238052,10500,0,200.0009685,0,0,0,90.00000001 +296.11,50.30085681,-2.826210027,10500,0,199.9998535,0,0,0,90.00000001 +296.12,50.30085681,-2.826182002,10500,0,199.9989614,0,0,0,90.00000001 +296.13,50.30085681,-2.826153977,10500,0,199.9987384,0,0,0,90.00000001 +296.14,50.30085681,-2.826125952,10500,0,199.9989614,0,0,0,90.00000001 +296.15,50.30085681,-2.826097927,10500,0,199.9998535,0,0,0,90.00000001 +296.16,50.30085681,-2.826069902,10500,0,200.0009685,0,0,0,90.00000001 +296.17,50.30085681,-2.826041876,10500,0,200.0009685,0,0,0,90.00000001 +296.18,50.30085681,-2.826013851,10500,0,199.9998535,0,0,0,90.00000001 +296.19,50.30085681,-2.825985826,10500,0,199.9989614,0,0,0,90.00000001 +296.2,50.30085681,-2.825957801,10500,0,199.9989614,0,0,0,90.00000001 +296.21,50.30085681,-2.825929776,10500,0,199.9998535,0,0,0,90.00000001 +296.22,50.30085681,-2.825901751,10500,0,200.0009685,0,0,0,90.00000001 +296.23,50.30085681,-2.825873725,10500,0,200.0009685,0,0,0,90.00000001 +296.24,50.30085681,-2.8258457,10500,0,199.9998535,0,0,0,90.00000001 +296.25,50.30085681,-2.825817675,10500,0,199.9989614,0,0,0,90.00000001 +296.26,50.30085681,-2.82578965,10500,0,199.9989614,0,0,0,90.00000001 +296.27,50.30085681,-2.825761625,10500,0,199.9998535,0,0,0,90.00000001 +296.28,50.30085681,-2.8257336,10500,0,200.0009685,0,0,0,90.00000001 +296.29,50.30085681,-2.825705574,10500,0,200.0009685,0,0,0,90.00000001 +296.3,50.30085681,-2.825677549,10500,0,199.9998535,0,0,0,90.00000001 +296.31,50.30085681,-2.825649524,10500,0,199.9989614,0,0,0,90.00000001 +296.32,50.30085681,-2.825621499,10500,0,199.9989614,0,0,0,90.00000001 +296.33,50.30085681,-2.825593474,10500,0,199.9998535,0,0,0,90.00000001 +296.34,50.30085681,-2.825565449,10500,0,200.0009685,0,0,0,90.00000001 +296.35,50.30085681,-2.825537423,10500,0,200.0009685,0,0,0,90.00000001 +296.36,50.30085681,-2.825509398,10500,0,199.9998535,0,0,0,90.00000001 +296.37,50.30085681,-2.825481373,10500,0,199.9989614,0,0,0,90.00000001 +296.38,50.30085681,-2.825453348,10500,0,199.9989614,0,0,0,90.00000001 +296.39,50.30085681,-2.825425323,10500,0,199.9998535,0,0,0,90.00000001 +296.4,50.30085681,-2.825397298,10500,0,200.0009685,0,0,0,90.00000001 +296.41,50.30085681,-2.825369272,10500,0,200.0009685,0,0,0,90.00000001 +296.42,50.30085681,-2.825341247,10500,0,199.9998535,0,0,0,90.00000001 +296.43,50.30085681,-2.825313222,10500,0,199.9989614,0,0,0,90.00000001 +296.44,50.30085681,-2.825285197,10500,0,199.9989614,0,0,0,90.00000001 +296.45,50.30085681,-2.825257172,10500,0,199.9998535,0,0,0,90.00000001 +296.46,50.30085681,-2.825229147,10500,0,200.0009685,0,0,0,90.00000001 +296.47,50.30085681,-2.825201121,10500,0,200.0009685,0,0,0,90.00000001 +296.48,50.30085681,-2.825173096,10500,0,199.9998535,0,0,0,90.00000001 +296.49,50.30085681,-2.825145071,10500,0,199.9991844,0,0,0,90.00000001 +296.5,50.30085681,-2.825117046,10500,0,199.9998535,0,0,0,90.00000001 +296.51,50.30085681,-2.825089021,10500,0,200.0009685,0,0,0,90.00000001 +296.52,50.30085681,-2.825060995,10500,0,200.0009685,0,0,0,90.00000001 +296.53,50.30085681,-2.82503297,10500,0,199.9998535,0,0,0,90.00000001 +296.54,50.30085681,-2.825004945,10500,0,199.9991844,0,0,0,90.00000001 +296.55,50.30085681,-2.82497692,10500,0,199.9998535,0,0,0,90.00000001 +296.56,50.30085681,-2.824948895,10500,0,200.0009685,0,0,0,90.00000001 +296.57,50.30085681,-2.824920869,10500,0,200.0009685,0,0,0,90.00000001 +296.58,50.30085681,-2.824892844,10500,0,199.9998535,0,0,0,90.00000001 +296.59,50.30085681,-2.824864819,10500,0,199.9991844,0,0,0,90.00000001 +296.6,50.30085681,-2.824836794,10500,0,199.9998535,0,0,0,90.00000001 +296.61,50.30085681,-2.824808769,10500,0,200.0009685,0,0,0,90.00000001 +296.62,50.30085681,-2.824780743,10500,0,200.0009685,0,0,0,90.00000001 +296.63,50.30085681,-2.824752718,10500,0,199.9998535,0,0,0,90.00000001 +296.64,50.30085681,-2.824724693,10500,0,199.9991844,0,0,0,90.00000001 +296.65,50.30085681,-2.824696668,10500,0,199.9998535,0,0,0,90.00000001 +296.66,50.30085681,-2.824668643,10500,0,200.0009685,0,0,0,90.00000001 +296.67,50.30085681,-2.824640617,10500,0,200.0009685,0,0,0,90.00000001 +296.68,50.30085681,-2.824612592,10500,0,199.9998535,0,0,0,90.00000001 +296.69,50.30085681,-2.824584567,10500,0,199.9989614,0,0,0,90.00000001 +296.7,50.30085681,-2.824556542,10500,0,199.9989614,0,0,0,90.00000001 +296.71,50.30085681,-2.824528517,10500,0,199.9998535,0,0,0,90.00000001 +296.72,50.30085681,-2.824500492,10500,0,200.0009685,0,0,0,90.00000001 +296.73,50.30085681,-2.824472466,10500,0,200.0009685,0,0,0,90.00000001 +296.74,50.30085681,-2.824444441,10500,0,199.9998535,0,0,0,90.00000001 +296.75,50.30085681,-2.824416416,10500,0,199.9989614,0,0,0,90.00000001 +296.76,50.30085681,-2.824388391,10500,0,199.9989614,0,0,0,90.00000001 +296.77,50.30085681,-2.824360366,10500,0,199.9998535,0,0,0,90.00000001 +296.78,50.30085681,-2.824332341,10500,0,200.0009685,0,0,0,90.00000001 +296.79,50.30085681,-2.824304315,10500,0,200.0009685,0,0,0,90.00000001 +296.8,50.30085681,-2.82427629,10500,0,199.9998535,0,0,0,90.00000001 +296.81,50.30085681,-2.824248265,10500,0,199.9989614,0,0,0,90.00000001 +296.82,50.30085681,-2.82422024,10500,0,199.9989614,0,0,0,90.00000001 +296.83,50.30085681,-2.824192215,10500,0,199.9998535,0,0,0,90.00000001 +296.84,50.30085681,-2.82416419,10500,0,200.0009685,0,0,0,90.00000001 +296.85,50.30085681,-2.824136164,10500,0,200.0009685,0,0,0,90.00000001 +296.86,50.30085681,-2.824108139,10500,0,199.9998535,0,0,0,90.00000001 +296.87,50.30085681,-2.824080114,10500,0,199.9989614,0,0,0,90.00000001 +296.88,50.30085681,-2.824052089,10500,0,199.9989614,0,0,0,90.00000001 +296.89,50.30085681,-2.824024064,10500,0,199.9998535,0,0,0,90.00000001 +296.9,50.30085681,-2.823996039,10500,0,200.0009685,0,0,0,90.00000001 +296.91,50.30085681,-2.823968013,10500,0,200.0009685,0,0,0,90.00000001 +296.92,50.30085681,-2.823939988,10500,0,199.9998535,0,0,0,90.00000001 +296.93,50.30085681,-2.823911963,10500,0,199.9989614,0,0,0,90.00000001 +296.94,50.30085681,-2.823883938,10500,0,199.9989614,0,0,0,90.00000001 +296.95,50.30085681,-2.823855913,10500,0,199.9998535,0,0,0,90.00000001 +296.96,50.30085681,-2.823827888,10500,0,200.0009685,0,0,0,90.00000001 +296.97,50.30085681,-2.823799862,10500,0,200.0009685,0,0,0,90.00000001 +296.98,50.30085681,-2.823771837,10500,0,199.9998535,0,0,0,90.00000001 +296.99,50.30085681,-2.823743812,10500,0,199.9989614,0,0,0,90.00000001 +297,50.30085681,-2.823715787,10500,0,199.9987384,0,0,0,90.00000001 +297.01,50.30085681,-2.823687762,10500,0,199.9989614,0,0,0,90.00000001 +297.02,50.30085681,-2.823659737,10500,0,199.9998535,0,0,0,90.00000001 +297.03,50.30085681,-2.823631712,10500,0,200.0009685,0,0,0,90.00000001 +297.04,50.30085681,-2.823603686,10500,0,200.0009685,0,0,0,90.00000001 +297.05,50.30085681,-2.823575661,10500,0,199.9998535,0,0,0,90.00000001 +297.06,50.30085681,-2.823547636,10500,0,199.9991844,0,0,0,90.00000001 +297.07,50.30085681,-2.823519611,10500,0,199.9998535,0,0,0,90.00000001 +297.08,50.30085681,-2.823491586,10500,0,200.0009685,0,0,0,90.00000001 +297.09,50.30085681,-2.82346356,10500,0,200.0009685,0,0,0,90.00000001 +297.1,50.30085681,-2.823435535,10500,0,199.9998535,0,0,0,90.00000001 +297.11,50.30085681,-2.82340751,10500,0,199.9991844,0,0,0,90.00000001 +297.12,50.30085681,-2.823379485,10500,0,199.9998535,0,0,0,90.00000001 +297.13,50.30085681,-2.82335146,10500,0,200.0009685,0,0,0,90.00000001 +297.14,50.30085681,-2.823323434,10500,0,200.0009685,0,0,0,90.00000001 +297.15,50.30085681,-2.823295409,10500,0,199.9998535,0,0,0,90.00000001 +297.16,50.30085681,-2.823267384,10500,0,199.9991844,0,0,0,90.00000001 +297.17,50.30085681,-2.823239359,10500,0,199.9998535,0,0,0,90.00000001 +297.18,50.30085681,-2.823211334,10500,0,200.0009685,0,0,0,90.00000001 +297.19,50.30085681,-2.823183308,10500,0,200.0009685,0,0,0,90.00000001 +297.2,50.30085681,-2.823155283,10500,0,199.9998535,0,0,0,90.00000001 +297.21,50.30085681,-2.823127258,10500,0,199.9991844,0,0,0,90.00000001 +297.22,50.30085681,-2.823099233,10500,0,199.9998535,0,0,0,90.00000001 +297.23,50.30085681,-2.823071208,10500,0,200.0009685,0,0,0,90.00000001 +297.24,50.30085681,-2.823043182,10500,0,200.0009685,0,0,0,90.00000001 +297.25,50.30085681,-2.823015157,10500,0,199.9998535,0,0,0,90.00000001 +297.26,50.30085681,-2.822987132,10500,0,199.9991844,0,0,0,90.00000001 +297.27,50.30085681,-2.822959107,10500,0,199.9998535,0,0,0,90.00000001 +297.28,50.30085681,-2.822931082,10500,0,200.0009685,0,0,0,90.00000001 +297.29,50.30085681,-2.822903056,10500,0,200.0009685,0,0,0,90.00000001 +297.3,50.30085681,-2.822875031,10500,0,199.9998535,0,0,0,90.00000001 +297.31,50.30085681,-2.822847006,10500,0,199.9989614,0,0,0,90.00000001 +297.32,50.30085681,-2.822818981,10500,0,199.9989614,0,0,0,90.00000001 +297.33,50.30085681,-2.822790956,10500,0,199.9998535,0,0,0,90.00000001 +297.34,50.30085681,-2.822762931,10500,0,200.0009685,0,0,0,90.00000001 +297.35,50.30085681,-2.822734905,10500,0,200.0009685,0,0,0,90.00000001 +297.36,50.30085681,-2.82270688,10500,0,199.9998535,0,0,0,90.00000001 +297.37,50.30085681,-2.822678855,10500,0,199.9989614,0,0,0,90.00000001 +297.38,50.30085681,-2.82265083,10500,0,199.9989614,0,0,0,90.00000001 +297.39,50.30085681,-2.822622805,10500,0,199.9998535,0,0,0,90.00000001 +297.4,50.30085681,-2.82259478,10500,0,200.0009685,0,0,0,90.00000001 +297.41,50.30085681,-2.822566754,10500,0,200.0009685,0,0,0,90.00000001 +297.42,50.30085681,-2.822538729,10500,0,199.9998535,0,0,0,90.00000001 +297.43,50.30085681,-2.822510704,10500,0,199.9989614,0,0,0,90.00000001 +297.44,50.30085681,-2.822482679,10500,0,199.9989614,0,0,0,90.00000001 +297.45,50.30085681,-2.822454654,10500,0,199.9998535,0,0,0,90.00000001 +297.46,50.30085681,-2.822426629,10500,0,200.0009685,0,0,0,90.00000001 +297.47,50.30085681,-2.822398603,10500,0,200.0009685,0,0,0,90.00000001 +297.48,50.30085681,-2.822370578,10500,0,199.9998535,0,0,0,90.00000001 +297.49,50.30085681,-2.822342553,10500,0,199.9989614,0,0,0,90.00000001 +297.5,50.30085681,-2.822314528,10500,0,199.9989614,0,0,0,90.00000001 +297.51,50.30085681,-2.822286503,10500,0,199.9998535,0,0,0,90.00000001 +297.52,50.30085681,-2.822258478,10500,0,200.0009685,0,0,0,90.00000001 +297.53,50.30085681,-2.822230452,10500,0,200.0009685,0,0,0,90.00000001 +297.54,50.30085681,-2.822202427,10500,0,199.9998535,0,0,0,90.00000001 +297.55,50.30085681,-2.822174402,10500,0,199.9989614,0,0,0,90.00000001 +297.56,50.30085681,-2.822146377,10500,0,199.9987384,0,0,0,90.00000001 +297.57,50.30085681,-2.822118352,10500,0,199.9989614,0,0,0,90.00000001 +297.58,50.30085681,-2.822090327,10500,0,199.9998535,0,0,0,90.00000001 +297.59,50.30085681,-2.822062302,10500,0,200.0009685,0,0,0,90.00000001 +297.6,50.30085681,-2.822034276,10500,0,200.0009685,0,0,0,90.00000001 +297.61,50.30085681,-2.822006251,10500,0,199.9998535,0,0,0,90.00000001 +297.62,50.30085681,-2.821978226,10500,0,199.9989614,0,0,0,90.00000001 +297.63,50.30085681,-2.821950201,10500,0,199.9989614,0,0,0,90.00000001 +297.64,50.30085681,-2.821922176,10500,0,199.9998535,0,0,0,90.00000001 +297.65,50.30085681,-2.821894151,10500,0,200.0009685,0,0,0,90.00000001 +297.66,50.30085681,-2.821866125,10500,0,200.0009685,0,0,0,90.00000001 +297.67,50.30085681,-2.8218381,10500,0,199.9998535,0,0,0,90.00000001 +297.68,50.30085681,-2.821810075,10500,0,199.9991844,0,0,0,90.00000001 +297.69,50.30085681,-2.82178205,10500,0,199.9998535,0,0,0,90.00000001 +297.7,50.30085681,-2.821754025,10500,0,200.0009685,0,0,0,90.00000001 +297.71,50.30085681,-2.821725999,10500,0,200.0009685,0,0,0,90.00000001 +297.72,50.30085681,-2.821697974,10500,0,199.9998535,0,0,0,90.00000001 +297.73,50.30085681,-2.821669949,10500,0,199.9991844,0,0,0,90.00000001 +297.74,50.30085681,-2.821641924,10500,0,199.9998535,0,0,0,90.00000001 +297.75,50.30085681,-2.821613899,10500,0,200.0009685,0,0,0,90.00000001 +297.76,50.30085681,-2.821585873,10500,0,200.0009685,0,0,0,90.00000001 +297.77,50.30085681,-2.821557848,10500,0,199.9998535,0,0,0,90.00000001 +297.78,50.30085681,-2.821529823,10500,0,199.9991844,0,0,0,90.00000001 +297.79,50.30085681,-2.821501798,10500,0,199.9998535,0,0,0,90.00000001 +297.8,50.30085681,-2.821473773,10500,0,200.0009685,0,0,0,90.00000001 +297.81,50.30085681,-2.821445747,10500,0,200.0009685,0,0,0,90.00000001 +297.82,50.30085681,-2.821417722,10500,0,199.9998535,0,0,0,90.00000001 +297.83,50.30085681,-2.821389697,10500,0,199.9991844,0,0,0,90.00000001 +297.84,50.30085681,-2.821361672,10500,0,199.9998535,0,0,0,90.00000001 +297.85,50.30085681,-2.821333647,10500,0,200.0009685,0,0,0,90.00000001 +297.86,50.30085681,-2.821305621,10500,0,200.0009685,0,0,0,90.00000001 +297.87,50.30085681,-2.821277596,10500,0,199.9998535,0,0,0,90.00000001 +297.88,50.30085681,-2.821249571,10500,0,199.9991844,0,0,0,90.00000001 +297.89,50.30085681,-2.821221546,10500,0,199.9998535,0,0,0,90.00000001 +297.9,50.30085681,-2.821193521,10500,0,200.0009685,0,0,0,90.00000001 +297.91,50.30085681,-2.821165495,10500,0,200.0009685,0,0,0,90.00000001 +297.92,50.30085681,-2.82113747,10500,0,199.9998535,0,0,0,90.00000001 +297.93,50.30085681,-2.821109445,10500,0,199.9989614,0,0,0,90.00000001 +297.94,50.30085681,-2.82108142,10500,0,199.9989614,0,0,0,90.00000001 +297.95,50.30085681,-2.821053395,10500,0,199.9998535,0,0,0,90.00000001 +297.96,50.30085681,-2.82102537,10500,0,200.0009685,0,0,0,90.00000001 +297.97,50.30085681,-2.820997344,10500,0,200.0009685,0,0,0,90.00000001 +297.98,50.30085681,-2.820969319,10500,0,199.9998535,0,0,0,90.00000001 +297.99,50.30085681,-2.820941294,10500,0,199.9989614,0,0,0,90.00000001 +298,50.30085681,-2.820913269,10500,0,199.9989614,0,0,0,90.00000001 +298.01,50.30085681,-2.820885244,10500,0,199.9998535,0,0,0,90.00000001 +298.02,50.30085681,-2.820857219,10500,0,200.0009685,0,0,0,90.00000001 +298.03,50.30085681,-2.820829193,10500,0,200.0009685,0,0,0,90.00000001 +298.04,50.30085681,-2.820801168,10500,0,199.9998535,0,0,0,90.00000001 +298.05,50.30085681,-2.820773143,10500,0,199.9989614,0,0,0,90.00000001 +298.06,50.30085681,-2.820745118,10500,0,199.9989614,0,0,0,90.00000001 +298.07,50.30085681,-2.820717093,10500,0,199.9998535,0,0,0,90.00000001 +298.08,50.30085681,-2.820689068,10500,0,200.0009685,0,0,0,90.00000001 +298.09,50.30085681,-2.820661042,10500,0,200.0009685,0,0,0,90.00000001 +298.1,50.30085681,-2.820633017,10500,0,199.9998535,0,0,0,90.00000001 +298.11,50.30085681,-2.820604992,10500,0,199.9989614,0,0,0,90.00000001 +298.12,50.30085681,-2.820576967,10500,0,199.9987384,0,0,0,90.00000001 +298.13,50.30085681,-2.820548942,10500,0,199.9989614,0,0,0,90.00000001 +298.14,50.30085681,-2.820520917,10500,0,199.9998535,0,0,0,90.00000001 +298.15,50.30085681,-2.820492892,10500,0,200.0009685,0,0,0,90.00000001 +298.16,50.30085681,-2.820464866,10500,0,200.0009685,0,0,0,90.00000001 +298.17,50.30085681,-2.820436841,10500,0,199.9998535,0,0,0,90.00000001 +298.18,50.30085681,-2.820408816,10500,0,199.9989614,0,0,0,90.00000001 +298.19,50.30085681,-2.820380791,10500,0,199.9989614,0,0,0,90.00000001 +298.2,50.30085681,-2.820352766,10500,0,199.9998535,0,0,0,90.00000001 +298.21,50.30085681,-2.820324741,10500,0,200.0009685,0,0,0,90.00000001 +298.22,50.30085681,-2.820296715,10500,0,200.0009685,0,0,0,90.00000001 +298.23,50.30085681,-2.82026869,10500,0,199.9998535,0,0,0,90.00000001 +298.24,50.30085681,-2.820240665,10500,0,199.9989614,0,0,0,90.00000001 +298.25,50.30085681,-2.82021264,10500,0,199.9989614,0,0,0,90.00000001 +298.26,50.30085681,-2.820184615,10500,0,199.9998535,0,0,0,90.00000001 +298.27,50.30085681,-2.82015659,10500,0,200.0009685,0,0,0,90.00000001 +298.28,50.30085681,-2.820128564,10500,0,200.0009685,0,0,0,90.00000001 +298.29,50.30085681,-2.820100539,10500,0,199.9998535,0,0,0,90.00000001 +298.3,50.30085681,-2.820072514,10500,0,199.9989614,0,0,0,90.00000001 +298.31,50.30085681,-2.820044489,10500,0,199.9989614,0,0,0,90.00000001 +298.32,50.30085681,-2.820016464,10500,0,199.9998535,0,0,0,90.00000001 +298.33,50.30085681,-2.819988439,10500,0,200.0009685,0,0,0,90.00000001 +298.34,50.30085681,-2.819960413,10500,0,200.0009685,0,0,0,90.00000001 +298.35,50.30085681,-2.819932388,10500,0,199.9998535,0,0,0,90.00000001 +298.36,50.30085681,-2.819904363,10500,0,199.9991844,0,0,0,90.00000001 +298.37,50.30085681,-2.819876338,10500,0,199.9998535,0,0,0,90.00000001 +298.38,50.30085681,-2.819848313,10500,0,200.0009685,0,0,0,90.00000001 +298.39,50.30085681,-2.819820287,10500,0,200.0009685,0,0,0,90.00000001 +298.4,50.30085681,-2.819792262,10500,0,199.9998535,0,0,0,90.00000001 +298.41,50.30085681,-2.819764237,10500,0,199.9991844,0,0,0,90.00000001 +298.42,50.30085681,-2.819736212,10500,0,199.9998535,0,0,0,90.00000001 +298.43,50.30085681,-2.819708187,10500,0,200.0009685,0,0,0,90.00000001 +298.44,50.30085681,-2.819680161,10500,0,200.0009685,0,0,0,90.00000001 +298.45,50.30085681,-2.819652136,10500,0,199.9998535,0,0,0,90.00000001 +298.46,50.30085681,-2.819624111,10500,0,199.9991844,0,0,0,90.00000001 +298.47,50.30085681,-2.819596086,10500,0,199.9998535,0,0,0,90.00000001 +298.48,50.30085681,-2.819568061,10500,0,200.0009685,0,0,0,90.00000001 +298.49,50.30085681,-2.819540035,10500,0,200.0009685,0,0,0,90.00000001 +298.5,50.30085681,-2.81951201,10500,0,199.9998535,0,0,0,90.00000001 +298.51,50.30085681,-2.819483985,10500,0,199.9991844,0,0,0,90.00000001 +298.52,50.30085681,-2.81945596,10500,0,199.9998535,0,0,0,90.00000001 +298.53,50.30085681,-2.819427935,10500,0,200.0009685,0,0,0,90.00000001 +298.54,50.30085681,-2.819399909,10500,0,200.0009685,0,0,0,90.00000001 +298.55,50.30085681,-2.819371884,10500,0,199.9998535,0,0,0,90.00000001 +298.56,50.30085681,-2.819343859,10500,0,199.9991844,0,0,0,90.00000001 +298.57,50.30085681,-2.819315834,10500,0,199.9998535,0,0,0,90.00000001 +298.58,50.30085681,-2.819287809,10500,0,200.0009685,0,0,0,90.00000001 +298.59,50.30085681,-2.819259783,10500,0,200.0009685,0,0,0,90.00000001 +298.6,50.30085681,-2.819231758,10500,0,199.9998535,0,0,0,90.00000001 +298.61,50.30085681,-2.819203733,10500,0,199.9989614,0,0,0,90.00000001 +298.62,50.30085681,-2.819175708,10500,0,199.9989614,0,0,0,90.00000001 +298.63,50.30085681,-2.819147683,10500,0,199.9998535,0,0,0,90.00000001 +298.64,50.30085681,-2.819119658,10500,0,200.0009685,0,0,0,90.00000001 +298.65,50.30085681,-2.819091632,10500,0,200.0009685,0,0,0,90.00000001 +298.66,50.30085681,-2.819063607,10500,0,199.9998535,0,0,0,90.00000001 +298.67,50.30085681,-2.819035582,10500,0,199.9989614,0,0,0,90.00000001 +298.68,50.30085681,-2.819007557,10500,0,199.9987384,0,0,0,90.00000001 +298.69,50.30085681,-2.818979532,10500,0,199.9989614,0,0,0,90.00000001 +298.7,50.30085681,-2.818951507,10500,0,199.9998535,0,0,0,90.00000001 +298.71,50.30085681,-2.818923482,10500,0,200.0009685,0,0,0,90.00000001 +298.72,50.30085681,-2.818895456,10500,0,200.0009685,0,0,0,90.00000001 +298.73,50.30085681,-2.818867431,10500,0,199.9998535,0,0,0,90.00000001 +298.74,50.30085681,-2.818839406,10500,0,199.9989614,0,0,0,90.00000001 +298.75,50.30085681,-2.818811381,10500,0,199.9989614,0,0,0,90.00000001 +298.76,50.30085681,-2.818783356,10500,0,199.9998535,0,0,0,90.00000001 +298.77,50.30085681,-2.818755331,10500,0,200.0009685,0,0,0,90.00000001 +298.78,50.30085681,-2.818727305,10500,0,200.0009685,0,0,0,90.00000001 +298.79,50.30085681,-2.81869928,10500,0,199.9998535,0,0,0,90.00000001 +298.8,50.30085681,-2.818671255,10500,0,199.9989614,0,0,0,90.00000001 +298.81,50.30085681,-2.81864323,10500,0,199.9989614,0,0,0,90.00000001 +298.82,50.30085681,-2.818615205,10500,0,199.9998535,0,0,0,90.00000001 +298.83,50.30085681,-2.81858718,10500,0,200.0009685,0,0,0,90.00000001 +298.84,50.30085681,-2.818559154,10500,0,200.0009685,0,0,0,90.00000001 +298.85,50.30085681,-2.818531129,10500,0,199.9998535,0,0,0,90.00000001 +298.86,50.30085681,-2.818503104,10500,0,199.9989614,0,0,0,90.00000001 +298.87,50.30085681,-2.818475079,10500,0,199.9989614,0,0,0,90.00000001 +298.88,50.30085681,-2.818447054,10500,0,199.9998535,0,0,0,90.00000001 +298.89,50.30085681,-2.818419029,10500,0,200.0009685,0,0,0,90.00000001 +298.9,50.30085681,-2.818391003,10500,0,200.0009685,0,0,0,90.00000001 +298.91,50.30085681,-2.818362978,10500,0,199.9998535,0,0,0,90.00000001 +298.92,50.30085681,-2.818334953,10500,0,199.9989614,0,0,0,90.00000001 +298.93,50.30085681,-2.818306928,10500,0,199.9989614,0,0,0,90.00000001 +298.94,50.30085681,-2.818278903,10500,0,199.9998535,0,0,0,90.00000001 +298.95,50.30085681,-2.818250878,10500,0,200.0009685,0,0,0,90.00000001 +298.96,50.30085681,-2.818222852,10500,0,200.0009685,0,0,0,90.00000001 +298.97,50.30085681,-2.818194827,10500,0,199.9998535,0,0,0,90.00000001 +298.98,50.30085681,-2.818166802,10500,0,199.9991844,0,0,0,90.00000001 +298.99,50.30085681,-2.818138777,10500,0,199.9998535,0,0,0,90.00000001 +299,50.30085681,-2.818110752,10500,0,200.0009685,0,0,0,90.00000001 +299.01,50.30085681,-2.818082726,10500,0,200.0009685,0,0,0,90.00000001 +299.02,50.30085681,-2.818054701,10500,0,199.9998535,0,0,0,90.00000001 +299.03,50.30085681,-2.818026676,10500,0,199.9991844,0,0,0,90.00000001 +299.04,50.30085681,-2.817998651,10500,0,199.9998535,0,0,0,90.00000001 +299.05,50.30085681,-2.817970626,10500,0,200.0009685,0,0,0,90.00000001 +299.06,50.30085681,-2.8179426,10500,0,200.0009685,0,0,0,90.00000001 +299.07,50.30085681,-2.817914575,10500,0,199.9998535,0,0,0,90.00000001 +299.08,50.30085681,-2.81788655,10500,0,199.9991844,0,0,0,90.00000001 +299.09,50.30085681,-2.817858525,10500,0,199.9998535,0,0,0,90.00000001 +299.1,50.30085681,-2.8178305,10500,0,200.0009685,0,0,0,90.00000001 +299.11,50.30085681,-2.817802474,10500,0,200.0009685,0,0,0,90.00000001 +299.12,50.30085681,-2.817774449,10500,0,199.9998535,0,0,0,90.00000001 +299.13,50.30085681,-2.817746424,10500,0,199.9991844,0,0,0,90.00000001 +299.14,50.30085681,-2.817718399,10500,0,199.9998535,0,0,0,90.00000001 +299.15,50.30085681,-2.817690374,10500,0,200.0009685,0,0,0,90.00000001 +299.16,50.30085681,-2.817662348,10500,0,200.0009685,0,0,0,90.00000001 +299.17,50.30085681,-2.817634323,10500,0,199.9998535,0,0,0,90.00000001 +299.18,50.30085681,-2.817606298,10500,0,199.9991844,0,0,0,90.00000001 +299.19,50.30085681,-2.817578273,10500,0,199.9998535,0,0,0,90.00000001 +299.2,50.30085681,-2.817550248,10500,0,200.0009685,0,0,0,90.00000001 +299.21,50.30085681,-2.817522222,10500,0,200.0009685,0,0,0,90.00000001 +299.22,50.30085681,-2.817494197,10500,0,199.9998535,0,0,0,90.00000001 +299.23,50.30085681,-2.817466172,10500,0,199.9989614,0,0,0,90.00000001 +299.24,50.30085681,-2.817438147,10500,0,199.9989614,0,0,0,90.00000001 +299.25,50.30085681,-2.817410122,10500,0,199.9998535,0,0,0,90.00000001 +299.26,50.30085681,-2.817382097,10500,0,200.0009685,0,0,0,90.00000001 +299.27,50.30085681,-2.817354071,10500,0,200.0009685,0,0,0,90.00000001 +299.28,50.30085681,-2.817326046,10500,0,199.9998535,0,0,0,90.00000001 +299.29,50.30085681,-2.817298021,10500,0,199.9989614,0,0,0,90.00000001 +299.3,50.30085681,-2.817269996,10500,0,199.9987384,0,0,0,90.00000001 +299.31,50.30085681,-2.817241971,10500,0,199.9989614,0,0,0,90.00000001 +299.32,50.30085681,-2.817213946,10500,0,199.9998535,0,0,0,90.00000001 +299.33,50.30085681,-2.817185921,10500,0,200.0009685,0,0,0,90.00000001 +299.34,50.30085681,-2.817157895,10500,0,200.0009685,0,0,0,90.00000001 +299.35,50.30085681,-2.81712987,10500,0,199.9998535,0,0,0,90.00000001 +299.36,50.30085681,-2.817101845,10500,0,199.9989614,0,0,0,90.00000001 +299.37,50.30085681,-2.81707382,10500,0,199.9989614,0,0,0,90.00000001 +299.38,50.30085681,-2.817045795,10500,0,199.9998535,0,0,0,90.00000001 +299.39,50.30085681,-2.81701777,10500,0,200.0009685,0,0,0,90.00000001 +299.4,50.30085681,-2.816989744,10500,0,200.0009685,0,0,0,90.00000001 +299.41,50.30085681,-2.816961719,10500,0,199.9998535,0,0,0,90.00000001 +299.42,50.30085681,-2.816933694,10500,0,199.9989614,0,0,0,90.00000001 +299.43,50.30085681,-2.816905669,10500,0,199.9989614,0,0,0,90.00000001 +299.44,50.30085681,-2.816877644,10500,0,199.9998535,0,0,0,90.00000001 +299.45,50.30085681,-2.816849619,10500,0,200.0009685,0,0,0,90.00000001 +299.46,50.30085681,-2.816821593,10500,0,200.0009685,0,0,0,90.00000001 +299.47,50.30085681,-2.816793568,10500,0,199.9998535,0,0,0,90.00000001 +299.48,50.30085681,-2.816765543,10500,0,199.9989614,0,0,0,90.00000001 +299.49,50.30085681,-2.816737518,10500,0,199.9989614,0,0,0,90.00000001 +299.5,50.30085681,-2.816709493,10500,0,199.9998535,0,0,0,90.00000001 +299.51,50.30085681,-2.816681468,10500,0,200.0009685,0,0,0,90.00000001 +299.52,50.30085681,-2.816653442,10500,0,200.0009685,0,0,0,90.00000001 +299.53,50.30085681,-2.816625417,10500,0,199.9998535,0,0,0,90.00000001 +299.54,50.30085681,-2.816597392,10500,0,199.9989614,0,0,0,90.00000001 +299.55,50.30085681,-2.816569367,10500,0,199.9989614,0,0,0,90.00000001 +299.56,50.30085681,-2.816541342,10500,0,199.9998535,0,0,0,90.00000001 +299.57,50.30085681,-2.816513317,10500,0,200.0009685,0,0,0,90.00000001 +299.58,50.30085681,-2.816485291,10500,0,200.0009685,0,0,0,90.00000001 +299.59,50.30085681,-2.816457266,10500,0,199.9998535,0,0,0,90.00000001 +299.6,50.30085681,-2.816429241,10500,0,199.9991844,0,0,0,90.00000001 +299.61,50.30085681,-2.816401216,10500,0,199.9998535,0,0,0,90.00000001 +299.62,50.30085681,-2.816373191,10500,0,200.0009685,0,0,0,90.00000001 +299.63,50.30085681,-2.816345165,10500,0,200.0009685,0,0,0,90.00000001 +299.64,50.30085681,-2.81631714,10500,0,199.9998535,0,0,0,90.00000001 +299.65,50.30085681,-2.816289115,10500,0,199.9991844,0,0,0,90.00000001 +299.66,50.30085681,-2.81626109,10500,0,199.9998535,0,0,0,90.00000001 +299.67,50.30085681,-2.816233065,10500,0,200.0009685,0,0,0,90.00000001 +299.68,50.30085681,-2.816205039,10500,0,200.0009685,0,0,0,90.00000001 +299.69,50.30085681,-2.816177014,10500,0,199.9998535,0,0,0,90.00000001 +299.7,50.30085681,-2.816148989,10500,0,199.9991844,0,0,0,90.00000001 +299.71,50.30085681,-2.816120964,10500,0,199.9998535,0,0,0,90.00000001 +299.72,50.30085681,-2.816092939,10500,0,200.0009685,0,0,0,90.00000001 +299.73,50.30085681,-2.816064913,10500,0,200.0009685,0,0,0,90.00000001 +299.74,50.30085681,-2.816036888,10500,0,199.9998535,0,0,0,90.00000001 +299.75,50.30085681,-2.816008863,10500,0,199.9991844,0,0,0,90.00000001 +299.76,50.30085681,-2.815980838,10500,0,199.9998535,0,0,0,90.00000001 +299.77,50.30085681,-2.815952813,10500,0,200.0009685,0,0,0,90.00000001 +299.78,50.30085681,-2.815924787,10500,0,200.0009685,0,0,0,90.00000001 +299.79,50.30085681,-2.815896762,10500,0,199.9998535,0,0,0,90.00000001 +299.8,50.30085681,-2.815868737,10500,0,199.9991844,0,0,0,90.00000001 +299.81,50.30085681,-2.815840712,10500,0,199.9998535,0,0,0,90.00000001 +299.82,50.30085681,-2.815812687,10500,0,200.0009685,0,0,0,90.00000001 +299.83,50.30085681,-2.815784661,10500,0,200.0009685,0,0,0,90.00000001 +299.84,50.30085681,-2.815756636,10500,0,199.9998535,0,0,0,90.00000001 +299.85,50.30085681,-2.815728611,10500,0,199.9989614,0,0,0,90.00000001 +299.86,50.30085681,-2.815700586,10500,0,199.9987384,0,0,0,90.00000001 +299.87,50.30085681,-2.815672561,10500,0,199.9989614,0,0,0,90.00000001 +299.88,50.30085681,-2.815644536,10500,0,199.9998535,0,0,0,90.00000001 +299.89,50.30085681,-2.815616511,10500,0,200.0009685,0,0,0,90.00000001 +299.9,50.30085681,-2.815588485,10500,0,200.0009685,0,0,0,90.00000001 +299.91,50.30085681,-2.81556046,10500,0,199.9998535,0,0,0,90.00000001 +299.92,50.30085681,-2.815532435,10500,0,199.9989614,0,0,0,90.00000001 +299.93,50.30085681,-2.81550441,10500,0,199.9989614,0,0,0,90.00000001 +299.94,50.30085681,-2.815476385,10500,0,199.9998535,0,0,0,90.00000001 +299.95,50.30085681,-2.81544836,10500,0,200.0009685,0,0,0,90.00000001 +299.96,50.30085681,-2.815420334,10500,0,200.0009685,0,0,0,90.00000001 +299.97,50.30085681,-2.815392309,10500,0,199.9998535,0,0,0,90.00000001 +299.98,50.30085681,-2.815364284,10500,0,199.9989614,0,0,0,90.00000001 +299.99,50.30085681,-2.815336259,10500,0,199.9989614,0,0,0,90.00000001 +300,50.30085681,-2.815308234,10500,0,199.9998535,0,0,0,90.00000001 +300.01,50.30085681,-2.815280209,10500,0,200.0009685,0,0,0,90.00000001 +300.02,50.30085681,-2.815252183,10500,0,200.0009685,0,0,0,90.00000001 +300.03,50.30085681,-2.815224158,10500,0,199.9998535,0,0,0,90.00000001 +300.04,50.30085681,-2.815196133,10500,0,199.9989614,0,0,0,90.00000001 +300.05,50.30085681,-2.815168108,10500,0,199.9989614,0,0,0,90.00000001 +300.06,50.30085681,-2.815140083,10500,0,199.9998535,0,0,0,90.00000001 +300.07,50.30085681,-2.815112058,10500,0,200.0009685,0,0,0,90.00000001 +300.08,50.30085681,-2.815084032,10500,0,200.0009685,0,0,0,90.00000001 +300.09,50.30085681,-2.815056007,10500,0,199.9998535,0,0,0,90.00000001 +300.1,50.30085681,-2.815027982,10500,0,199.9989614,0,0,0,90.00000001 +300.11,50.30085681,-2.814999957,10500,0,199.9987384,0,0,0,90.00000001 +300.12,50.30085681,-2.814971932,10500,0,199.9989614,0,0,0,90.00000001 +300.13,50.30085681,-2.814943907,10500,0,199.9998535,0,0,0,90.00000001 +300.14,50.30085681,-2.814915882,10500,0,200.0009685,0,0,0,90.00000001 +300.15,50.30085681,-2.814887856,10500,0,200.0009685,0,0,0,90.00000001 +300.16,50.30085681,-2.814859831,10500,0,199.9998535,0,0,0,90.00000001 +300.17,50.30085681,-2.814831806,10500,0,199.9991844,0,0,0,90.00000001 +300.18,50.30085681,-2.814803781,10500,0,199.9998535,0,0,0,90.00000001 +300.19,50.30085681,-2.814775756,10500,0,200.0009685,0,0,0,90.00000001 +300.2,50.30085681,-2.81474773,10500,0,200.0009685,0,0,0,90.00000001 +300.21,50.30085681,-2.814719705,10500,0,199.9998535,0,0,0,90.00000001 +300.22,50.30085681,-2.81469168,10500,0,199.9991844,0,0,0,90.00000001 +300.23,50.30085681,-2.814663655,10500,0,199.9998535,0,0,0,90.00000001 +300.24,50.30085681,-2.81463563,10500,0,200.0009685,0,0,0,90.00000001 +300.25,50.30085681,-2.814607604,10500,0,200.0009685,0,0,0,90.00000001 +300.26,50.30085681,-2.814579579,10500,0,199.9998535,0,0,0,90.00000001 +300.27,50.30085681,-2.814551554,10500,0,199.9991844,0,0,0,90.00000001 +300.28,50.30085681,-2.814523529,10500,0,199.9998535,0,0,0,90.00000001 +300.29,50.30085681,-2.814495504,10500,0,200.0009685,0,0,0,90.00000001 +300.3,50.30085681,-2.814467478,10500,0,200.0009685,0,0,0,90.00000001 +300.31,50.30085681,-2.814439453,10500,0,199.9998535,0,0,0,90.00000001 +300.32,50.30085681,-2.814411428,10500,0,199.9991844,0,0,0,90.00000001 +300.33,50.30085681,-2.814383403,10500,0,199.9998535,0,0,0,90.00000001 +300.34,50.30085681,-2.814355378,10500,0,200.0009685,0,0,0,90.00000001 +300.35,50.30085681,-2.814327352,10500,0,200.0009685,0,0,0,90.00000001 +300.36,50.30085681,-2.814299327,10500,0,199.9998535,0,0,0,90.00000001 +300.37,50.30085681,-2.814271302,10500,0,199.9989614,0,0,0,90.00000001 +300.38,50.30085681,-2.814243277,10500,0,199.9989614,0,0,0,90.00000001 +300.39,50.30085681,-2.814215252,10500,0,199.9998535,0,0,0,90.00000001 +300.4,50.30085681,-2.814187227,10500,0,200.0009685,0,0,0,90.00000001 +300.41,50.30085681,-2.814159201,10500,0,200.0009685,0,0,0,90.00000001 +300.42,50.30085681,-2.814131176,10500,0,199.9998535,0,0,0,90.00000001 +300.43,50.30085681,-2.814103151,10500,0,199.9991844,0,0,0,90.00000001 +300.44,50.30085681,-2.814075126,10500,0,199.9998535,0,0,0,90.00000001 +300.45,50.30085681,-2.814047101,10500,0,200.0009685,0,0,0,90.00000001 +300.46,50.30085681,-2.814019075,10500,0,200.0009685,0,0,0,90.00000001 +300.47,50.30085681,-2.81399105,10500,0,199.9998535,0,0,0,90.00000001 +300.48,50.30085681,-2.813963025,10500,0,199.9989614,0,0,0,90.00000001 +300.49,50.30085681,-2.813935,10500,0,199.9989614,0,0,0,90.00000001 +300.5,50.30085681,-2.813906975,10500,0,199.9998535,0,0,0,90.00000001 +300.51,50.30085681,-2.81387895,10500,0,200.0009685,0,0,0,90.00000001 +300.52,50.30085681,-2.813850924,10500,0,200.0009685,0,0,0,90.00000001 +300.53,50.30085681,-2.813822899,10500,0,199.9998535,0,0,0,90.00000001 +300.54,50.30085681,-2.813794874,10500,0,199.9989614,0,0,0,90.00000001 +300.55,50.30085681,-2.813766849,10500,0,199.9989614,0,0,0,90.00000001 +300.56,50.30085681,-2.813738824,10500,0,199.9998535,0,0,0,90.00000001 +300.57,50.30085681,-2.813710799,10500,0,200.0009685,0,0,0,90.00000001 +300.58,50.30085681,-2.813682773,10500,0,200.0009685,0,0,0,90.00000001 +300.59,50.30085681,-2.813654748,10500,0,199.9998535,0,0,0,90.00000001 +300.6,50.30085681,-2.813626723,10500,0,199.9989614,0,0,0,90.00000001 +300.61,50.30085681,-2.813598698,10500,0,199.9989614,0,0,0,90.00000001 +300.62,50.30085681,-2.813570673,10500,0,199.9998535,0,0,0,90.00000001 +300.63,50.30085681,-2.813542648,10500,0,200.0009685,0,0,0,90.00000001 +300.64,50.30085681,-2.813514622,10500,0,200.0009685,0,0,0,90.00000001 +300.65,50.30085681,-2.813486597,10500,0,199.9998535,0,0,0,90.00000001 +300.66,50.30085681,-2.813458572,10500,0,199.9989614,0,0,0,90.00000001 +300.67,50.30085681,-2.813430547,10500,0,199.9989614,0,0,0,90.00000001 +300.68,50.30085681,-2.813402522,10500,0,199.9998535,0,0,0,90.00000001 +300.69,50.30085681,-2.813374497,10500,0,200.0009685,0,0,0,90.00000001 +300.7,50.30085681,-2.813346471,10500,0,200.0009685,0,0,0,90.00000001 +300.71,50.30085681,-2.813318446,10500,0,199.9998535,0,0,0,90.00000001 +300.72,50.30085681,-2.813290421,10500,0,199.9989614,0,0,0,90.00000001 +300.73,50.30085681,-2.813262396,10500,0,199.9987384,0,0,0,90.00000001 +300.74,50.30085681,-2.813234371,10500,0,199.9989614,0,0,0,90.00000001 +300.75,50.30085681,-2.813206346,10500,0,199.9998535,0,0,0,90.00000001 +300.76,50.30085681,-2.813178321,10500,0,200.0009685,0,0,0,90.00000001 +300.77,50.30085681,-2.813150295,10500,0,200.0009685,0,0,0,90.00000001 +300.78,50.30085681,-2.81312227,10500,0,199.9998535,0,0,0,90.00000001 +300.79,50.30085681,-2.813094245,10500,0,199.9989614,0,0,0,90.00000001 +300.8,50.30085681,-2.81306622,10500,0,199.9989614,0,0,0,90.00000001 +300.81,50.30085681,-2.813038195,10500,0,199.9998535,0,0,0,90.00000001 +300.82,50.30085681,-2.81301017,10500,0,200.0009685,0,0,0,90.00000001 +300.83,50.30085681,-2.812982144,10500,0,200.0009685,0,0,0,90.00000001 +300.84,50.30085681,-2.812954119,10500,0,199.9998535,0,0,0,90.00000001 +300.85,50.30085681,-2.812926094,10500,0,199.9991844,0,0,0,90.00000001 +300.86,50.30085681,-2.812898069,10500,0,199.9998535,0,0,0,90.00000001 +300.87,50.30085681,-2.812870044,10500,0,200.0009685,0,0,0,90.00000001 +300.88,50.30085681,-2.812842018,10500,0,200.0009685,0,0,0,90.00000001 +300.89,50.30085681,-2.812813993,10500,0,199.9998535,0,0,0,90.00000001 +300.9,50.30085681,-2.812785968,10500,0,199.9991844,0,0,0,90.00000001 +300.91,50.30085681,-2.812757943,10500,0,199.9998535,0,0,0,90.00000001 +300.92,50.30085681,-2.812729918,10500,0,200.0009685,0,0,0,90.00000001 +300.93,50.30085681,-2.812701892,10500,0,200.0009685,0,0,0,90.00000001 +300.94,50.30085681,-2.812673867,10500,0,199.9998535,0,0,0,90.00000001 +300.95,50.30085681,-2.812645842,10500,0,199.9991844,0,0,0,90.00000001 +300.96,50.30085681,-2.812617817,10500,0,199.9998535,0,0,0,90.00000001 +300.97,50.30085681,-2.812589792,10500,0,200.0009685,0,0,0,90.00000001 +300.98,50.30085681,-2.812561766,10500,0,200.0009685,0,0,0,90.00000001 +300.99,50.30085681,-2.812533741,10500,0,199.9998535,0,0,0,90.00000001 +301,50.30085681,-2.812505716,10500,0,199.9991844,0,0,0,90.00000001 +301.01,50.30085681,-2.812477691,10500,0,199.9998535,0,0,0,90.00000001 +301.02,50.30085681,-2.812449666,10500,0,200.0009685,0,0,0,90.00000001 +301.03,50.30085681,-2.81242164,10500,0,200.0009685,0,0,0,90.00000001 +301.04,50.30085681,-2.812393615,10500,0,199.9998535,0,0,0,90.00000001 +301.05,50.30085681,-2.81236559,10500,0,199.9991844,0,0,0,90.00000001 +301.06,50.30085681,-2.812337565,10500,0,199.9998535,0,0,0,90.00000001 +301.07,50.30085681,-2.81230954,10500,0,200.0009685,0,0,0,90.00000001 +301.08,50.30085681,-2.812281514,10500,0,200.0009685,0,0,0,90.00000001 +301.09,50.30085681,-2.812253489,10500,0,199.9998535,0,0,0,90.00000001 +301.1,50.30085681,-2.812225464,10500,0,199.9989614,0,0,0,90.00000001 +301.11,50.30085681,-2.812197439,10500,0,199.9989614,0,0,0,90.00000001 +301.12,50.30085681,-2.812169414,10500,0,199.9998535,0,0,0,90.00000001 +301.13,50.30085681,-2.812141389,10500,0,200.0009685,0,0,0,90.00000001 +301.14,50.30085681,-2.812113363,10500,0,200.0009685,0,0,0,90.00000001 +301.15,50.30085681,-2.812085338,10500,0,199.9998535,0,0,0,90.00000001 +301.16,50.30085681,-2.812057313,10500,0,199.9989614,0,0,0,90.00000001 +301.17,50.30085681,-2.812029288,10500,0,199.9989614,0,0,0,90.00000001 +301.18,50.30085681,-2.812001263,10500,0,199.9998535,0,0,0,90.00000001 +301.19,50.30085681,-2.811973238,10500,0,200.0009685,0,0,0,90.00000001 +301.2,50.30085681,-2.811945212,10500,0,200.0009685,0,0,0,90.00000001 +301.21,50.30085681,-2.811917187,10500,0,199.9998535,0,0,0,90.00000001 +301.22,50.30085681,-2.811889162,10500,0,199.9989614,0,0,0,90.00000001 +301.23,50.30085681,-2.811861137,10500,0,199.9989614,0,0,0,90.00000001 +301.24,50.30085681,-2.811833112,10500,0,199.9998535,0,0,0,90.00000001 +301.25,50.30085681,-2.811805087,10500,0,200.0009685,0,0,0,90.00000001 +301.26,50.30085681,-2.811777061,10500,0,200.0009685,0,0,0,90.00000001 +301.27,50.30085681,-2.811749036,10500,0,199.9998535,0,0,0,90.00000001 +301.28,50.30085681,-2.811721011,10500,0,199.9989614,0,0,0,90.00000001 +301.29,50.30085681,-2.811692986,10500,0,199.9987384,0,0,0,90.00000001 +301.3,50.30085681,-2.811664961,10500,0,199.9989614,0,0,0,90.00000001 +301.31,50.30085681,-2.811636936,10500,0,199.9998535,0,0,0,90.00000001 +301.32,50.30085681,-2.811608911,10500,0,200.0009685,0,0,0,90.00000001 +301.33,50.30085681,-2.811580885,10500,0,200.0009685,0,0,0,90.00000001 +301.34,50.30085681,-2.81155286,10500,0,199.9998535,0,0,0,90.00000001 +301.35,50.30085681,-2.811524835,10500,0,199.9989614,0,0,0,90.00000001 +301.36,50.30085681,-2.81149681,10500,0,199.9989614,0,0,0,90.00000001 +301.37,50.30085681,-2.811468785,10500,0,199.9998535,0,0,0,90.00000001 +301.38,50.30085681,-2.81144076,10500,0,200.0009685,0,0,0,90.00000001 +301.39,50.30085681,-2.811412734,10500,0,200.0009685,0,0,0,90.00000001 +301.4,50.30085681,-2.811384709,10500,0,199.9998535,0,0,0,90.00000001 +301.41,50.30085681,-2.811356684,10500,0,199.9989614,0,0,0,90.00000001 +301.42,50.30085681,-2.811328659,10500,0,199.9989614,0,0,0,90.00000001 +301.43,50.30085681,-2.811300634,10500,0,199.9998535,0,0,0,90.00000001 +301.44,50.30085681,-2.811272609,10500,0,200.0009685,0,0,0,90.00000001 +301.45,50.30085681,-2.811244583,10500,0,200.0009685,0,0,0,90.00000001 +301.46,50.30085681,-2.811216558,10500,0,199.9998535,0,0,0,90.00000001 +301.47,50.30085681,-2.811188533,10500,0,199.9991844,0,0,0,90.00000001 +301.48,50.30085681,-2.811160508,10500,0,199.9998535,0,0,0,90.00000001 +301.49,50.30085681,-2.811132483,10500,0,200.0009685,0,0,0,90.00000001 +301.5,50.30085681,-2.811104457,10500,0,200.0009685,0,0,0,90.00000001 +301.51,50.30085681,-2.811076432,10500,0,199.9998535,0,0,0,90.00000001 +301.52,50.30085681,-2.811048407,10500,0,199.9991844,0,0,0,90.00000001 +301.53,50.30085681,-2.811020382,10500,0,199.9998535,0,0,0,90.00000001 +301.54,50.30085681,-2.810992357,10500,0,200.0009685,0,0,0,90.00000001 +301.55,50.30085681,-2.810964331,10500,0,200.0009685,0,0,0,90.00000001 +301.56,50.30085681,-2.810936306,10500,0,199.9998535,0,0,0,90.00000001 +301.57,50.30085681,-2.810908281,10500,0,199.9991844,0,0,0,90.00000001 +301.58,50.30085681,-2.810880256,10500,0,199.9998535,0,0,0,90.00000001 +301.59,50.30085681,-2.810852231,10500,0,200.0009685,0,0,0,90.00000001 +301.6,50.30085681,-2.810824205,10500,0,200.0009685,0,0,0,90.00000001 +301.61,50.30085681,-2.81079618,10500,0,199.9998535,0,0,0,90.00000001 +301.62,50.30085681,-2.810768155,10500,0,199.9991844,0,0,0,90.00000001 +301.63,50.30085681,-2.81074013,10500,0,199.9998535,0,0,0,90.00000001 +301.64,50.30085681,-2.810712105,10500,0,200.0009685,0,0,0,90.00000001 +301.65,50.30085681,-2.810684079,10500,0,200.0009685,0,0,0,90.00000001 +301.66,50.30085681,-2.810656054,10500,0,199.9998535,0,0,0,90.00000001 +301.67,50.30085681,-2.810628029,10500,0,199.9991844,0,0,0,90.00000001 +301.68,50.30085681,-2.810600004,10500,0,199.9998535,0,0,0,90.00000001 +301.69,50.30085681,-2.810571979,10500,0,200.0009685,0,0,0,90.00000001 +301.7,50.30085681,-2.810543953,10500,0,200.0009685,0,0,0,90.00000001 +301.71,50.30085681,-2.810515928,10500,0,199.9998535,0,0,0,90.00000001 +301.72,50.30085681,-2.810487903,10500,0,199.9989614,0,0,0,90.00000001 +301.73,50.30085681,-2.810459878,10500,0,199.9989614,0,0,0,90.00000001 +301.74,50.30085681,-2.810431853,10500,0,199.9998535,0,0,0,90.00000001 +301.75,50.30085681,-2.810403828,10500,0,200.0009685,0,0,0,90.00000001 +301.76,50.30085681,-2.810375802,10500,0,200.0009685,0,0,0,90.00000001 +301.77,50.30085681,-2.810347777,10500,0,199.9998535,0,0,0,90.00000001 +301.78,50.30085681,-2.810319752,10500,0,199.9989614,0,0,0,90.00000001 +301.79,50.30085681,-2.810291727,10500,0,199.9989614,0,0,0,90.00000001 +301.8,50.30085681,-2.810263702,10500,0,199.9998535,0,0,0,90.00000001 +301.81,50.30085681,-2.810235677,10500,0,200.0009685,0,0,0,90.00000001 +301.82,50.30085681,-2.810207651,10500,0,200.0009685,0,0,0,90.00000001 +301.83,50.30085681,-2.810179626,10500,0,199.9998535,0,0,0,90.00000001 +301.84,50.30085681,-2.810151601,10500,0,199.9989614,0,0,0,90.00000001 +301.85,50.30085681,-2.810123576,10500,0,199.9987384,0,0,0,90.00000001 +301.86,50.30085681,-2.810095551,10500,0,199.9989614,0,0,0,90.00000001 +301.87,50.30085681,-2.810067526,10500,0,199.9998535,0,0,0,90.00000001 +301.88,50.30085681,-2.810039501,10500,0,200.0009685,0,0,0,90.00000001 +301.89,50.30085681,-2.810011475,10500,0,200.0009685,0,0,0,90.00000001 +301.9,50.30085681,-2.80998345,10500,0,199.9998535,0,0,0,90.00000001 +301.91,50.30085681,-2.809955425,10500,0,199.9989614,0,0,0,90.00000001 +301.92,50.30085681,-2.8099274,10500,0,199.9989614,0,0,0,90.00000001 +301.93,50.30085681,-2.809899375,10500,0,199.9998535,0,0,0,90.00000001 +301.94,50.30085681,-2.80987135,10500,0,200.0009685,0,0,0,90.00000001 +301.95,50.30085681,-2.809843324,10500,0,200.0009685,0,0,0,90.00000001 +301.96,50.30085681,-2.809815299,10500,0,199.9998535,0,0,0,90.00000001 +301.97,50.30085681,-2.809787274,10500,0,199.9989614,0,0,0,90.00000001 +301.98,50.30085681,-2.809759249,10500,0,199.9989614,0,0,0,90.00000001 +301.99,50.30085681,-2.809731224,10500,0,199.9998535,0,0,0,90.00000001 +302,50.30085681,-2.809703199,10500,0,200.0009685,0,0,0,90.00000001 +302.01,50.30085681,-2.809675173,10500,0,200.0009685,0,0,0,90.00000001 +302.02,50.30085681,-2.809647148,10500,0,199.9998535,0,0,0,90.00000001 +302.03,50.30085681,-2.809619123,10500,0,199.9989614,0,0,0,90.00000001 +302.04,50.30085681,-2.809591098,10500,0,199.9989614,0,0,0,90.00000001 +302.05,50.30085681,-2.809563073,10500,0,199.9998535,0,0,0,90.00000001 +302.06,50.30085681,-2.809535048,10500,0,200.0009685,0,0,0,90.00000001 +302.07,50.30085681,-2.809507022,10500,0,200.0009685,0,0,0,90.00000001 +302.08,50.30085681,-2.809478997,10500,0,199.9998535,0,0,0,90.00000001 +302.09,50.30085681,-2.809450972,10500,0,199.9991844,0,0,0,90.00000001 +302.1,50.30085681,-2.809422947,10500,0,199.9998535,0,0,0,90.00000001 +302.11,50.30085681,-2.809394922,10500,0,200.0009685,0,0,0,90.00000001 +302.12,50.30085681,-2.809366896,10500,0,200.0009685,0,0,0,90.00000001 +302.13,50.30085681,-2.809338871,10500,0,199.9998535,0,0,0,90.00000001 +302.14,50.30085681,-2.809310846,10500,0,199.9991844,0,0,0,90.00000001 +302.15,50.30085681,-2.809282821,10500,0,199.9998535,0,0,0,90.00000001 +302.16,50.30085681,-2.809254796,10500,0,200.0009685,0,0,0,90.00000001 +302.17,50.30085681,-2.80922677,10500,0,200.0009685,0,0,0,90.00000001 +302.18,50.30085681,-2.809198745,10500,0,199.9998535,0,0,0,90.00000001 +302.19,50.30085681,-2.80917072,10500,0,199.9991844,0,0,0,90.00000001 +302.2,50.30085681,-2.809142695,10500,0,199.9998535,0,0,0,90.00000001 +302.21,50.30085681,-2.80911467,10500,0,200.0009685,0,0,0,90.00000001 +302.22,50.30085681,-2.809086644,10500,0,200.0009685,0,0,0,90.00000001 +302.23,50.30085681,-2.809058619,10500,0,199.9998535,0,0,0,90.00000001 +302.24,50.30085681,-2.809030594,10500,0,199.9991844,0,0,0,90.00000001 +302.25,50.30085681,-2.809002569,10500,0,199.9998535,0,0,0,90.00000001 +302.26,50.30085681,-2.808974544,10500,0,200.0009685,0,0,0,90.00000001 +302.27,50.30085681,-2.808946518,10500,0,200.0009685,0,0,0,90.00000001 +302.28,50.30085681,-2.808918493,10500,0,199.9998535,0,0,0,90.00000001 +302.29,50.30085681,-2.808890468,10500,0,199.9991844,0,0,0,90.00000001 +302.3,50.30085681,-2.808862443,10500,0,199.9998535,0,0,0,90.00000001 +302.31,50.30085681,-2.808834418,10500,0,200.0009685,0,0,0,90.00000001 +302.32,50.30085681,-2.808806392,10500,0,200.0009685,0,0,0,90.00000001 +302.33,50.30085681,-2.808778367,10500,0,199.9998535,0,0,0,90.00000001 +302.34,50.30085681,-2.808750342,10500,0,199.9989614,0,0,0,90.00000001 +302.35,50.30085681,-2.808722317,10500,0,199.9989614,0,0,0,90.00000001 +302.36,50.30085681,-2.808694292,10500,0,199.9998535,0,0,0,90.00000001 +302.37,50.30085681,-2.808666267,10500,0,200.0009685,0,0,0,90.00000001 +302.38,50.30085681,-2.808638241,10500,0,200.0009685,0,0,0,90.00000001 +302.39,50.30085681,-2.808610216,10500,0,199.9998535,0,0,0,90.00000001 +302.4,50.30085681,-2.808582191,10500,0,199.9989614,0,0,0,90.00000001 +302.41,50.30085681,-2.808554166,10500,0,199.9987384,0,0,0,90.00000001 +302.42,50.30085681,-2.808526141,10500,0,199.9989614,0,0,0,90.00000001 +302.43,50.30085681,-2.808498116,10500,0,199.9998535,0,0,0,90.00000001 +302.44,50.30085681,-2.808470091,10500,0,200.0009685,0,0,0,90.00000001 +302.45,50.30085681,-2.808442065,10500,0,200.0009685,0,0,0,90.00000001 +302.46,50.30085681,-2.80841404,10500,0,199.9998535,0,0,0,90.00000001 +302.47,50.30085681,-2.808386015,10500,0,199.9989614,0,0,0,90.00000001 +302.48,50.30085681,-2.80835799,10500,0,199.9989614,0,0,0,90.00000001 +302.49,50.30085681,-2.808329965,10500,0,199.9998535,0,0,0,90.00000001 +302.5,50.30085681,-2.80830194,10500,0,200.0009685,0,0,0,90.00000001 +302.51,50.30085681,-2.808273914,10500,0,200.0009685,0,0,0,90.00000001 +302.52,50.30085681,-2.808245889,10500,0,199.9998535,0,0,0,90.00000001 +302.53,50.30085681,-2.808217864,10500,0,199.9989614,0,0,0,90.00000001 +302.54,50.30085681,-2.808189839,10500,0,199.9989614,0,0,0,90.00000001 +302.55,50.30085681,-2.808161814,10500,0,199.9998535,0,0,0,90.00000001 +302.56,50.30085681,-2.808133789,10500,0,200.0009685,0,0,0,90.00000001 +302.57,50.30085681,-2.808105763,10500,0,200.0009685,0,0,0,90.00000001 +302.58,50.30085681,-2.808077738,10500,0,199.9998535,0,0,0,90.00000001 +302.59,50.30085681,-2.808049713,10500,0,199.9989614,0,0,0,90.00000001 +302.6,50.30085681,-2.808021688,10500,0,199.9989614,0,0,0,90.00000001 +302.61,50.30085681,-2.807993663,10500,0,199.9998535,0,0,0,90.00000001 +302.62,50.30085681,-2.807965638,10500,0,200.0009685,0,0,0,90.00000001 +302.63,50.30085681,-2.807937612,10500,0,200.0009685,0,0,0,90.00000001 +302.64,50.30085681,-2.807909587,10500,0,199.9998535,0,0,0,90.00000001 +302.65,50.30085681,-2.807881562,10500,0,199.9989614,0,0,0,90.00000001 +302.66,50.30085681,-2.807853537,10500,0,199.9989614,0,0,0,90.00000001 +302.67,50.30085681,-2.807825512,10500,0,199.9998535,0,0,0,90.00000001 +302.68,50.30085681,-2.807797487,10500,0,200.0009685,0,0,0,90.00000001 +302.69,50.30085681,-2.807769461,10500,0,200.0009685,0,0,0,90.00000001 +302.7,50.30085681,-2.807741436,10500,0,199.9998535,0,0,0,90.00000001 +302.71,50.30085681,-2.807713411,10500,0,199.9991844,0,0,0,90.00000001 +302.72,50.30085681,-2.807685386,10500,0,199.9998535,0,0,0,90.00000001 +302.73,50.30085681,-2.807657361,10500,0,200.0009685,0,0,0,90.00000001 +302.74,50.30085681,-2.807629335,10500,0,200.0009685,0,0,0,90.00000001 +302.75,50.30085681,-2.80760131,10500,0,199.9998535,0,0,0,90.00000001 +302.76,50.30085681,-2.807573285,10500,0,199.9989614,0,0,0,90.00000001 +302.77,50.30085681,-2.80754526,10500,0,199.9989614,0,0,0,90.00000001 +302.78,50.30085681,-2.807517235,10500,0,199.9998535,0,0,0,90.00000001 +302.79,50.30085681,-2.80748921,10500,0,200.0009685,0,0,0,90.00000001 +302.8,50.30085681,-2.807461184,10500,0,200.0009685,0,0,0,90.00000001 +302.81,50.30085681,-2.807433159,10500,0,199.9998535,0,0,0,90.00000001 +302.82,50.30085681,-2.807405134,10500,0,199.9991844,0,0,0,90.00000001 +302.83,50.30085681,-2.807377109,10500,0,199.9998535,0,0,0,90.00000001 +302.84,50.30085681,-2.807349084,10500,0,200.0009685,0,0,0,90.00000001 +302.85,50.30085681,-2.807321058,10500,0,200.0009685,0,0,0,90.00000001 +302.86,50.30085681,-2.807293033,10500,0,199.9998535,0,0,0,90.00000001 +302.87,50.30085681,-2.807265008,10500,0,199.9991844,0,0,0,90.00000001 +302.88,50.30085681,-2.807236983,10500,0,199.9998535,0,0,0,90.00000001 +302.89,50.30085681,-2.807208958,10500,0,200.0009685,0,0,0,90.00000001 +302.9,50.30085681,-2.807180932,10500,0,200.0009685,0,0,0,90.00000001 +302.91,50.30085681,-2.807152907,10500,0,199.9998535,0,0,0,90.00000001 +302.92,50.30085681,-2.807124882,10500,0,199.9991844,0,0,0,90.00000001 +302.93,50.30085681,-2.807096857,10500,0,199.9998535,0,0,0,90.00000001 +302.94,50.30085681,-2.807068832,10500,0,200.0009685,0,0,0,90.00000001 +302.95,50.30085681,-2.807040806,10500,0,200.0009685,0,0,0,90.00000001 +302.96,50.30085681,-2.807012781,10500,0,199.9998535,0,0,0,90.00000001 +302.97,50.30085681,-2.806984756,10500,0,199.9989614,0,0,0,90.00000001 +302.98,50.30085681,-2.806956731,10500,0,199.9989614,0,0,0,90.00000001 +302.99,50.30085681,-2.806928706,10500,0,199.9998535,0,0,0,90.00000001 +303,50.30085681,-2.806900681,10500,0,200.0009685,0,0,0,90.00000001 +303.01,50.30085681,-2.806872655,10500,0,200.0009685,0,0,0,90.00000001 +303.02,50.30085681,-2.80684463,10500,0,199.9998535,0,0,0,90.00000001 +303.03,50.30085681,-2.806816605,10500,0,199.9989614,0,0,0,90.00000001 +303.04,50.30085681,-2.80678858,10500,0,199.9989614,0,0,0,90.00000001 +303.05,50.30085681,-2.806760555,10500,0,199.9998535,0,0,0,90.00000001 +303.06,50.30085681,-2.80673253,10500,0,200.0009685,0,0,0,90.00000001 +303.07,50.30085681,-2.806704504,10500,0,200.0009685,0,0,0,90.00000001 +303.08,50.30085681,-2.806676479,10500,0,199.9998535,0,0,0,90.00000001 +303.09,50.30085681,-2.806648454,10500,0,199.9989614,0,0,0,90.00000001 +303.1,50.30085681,-2.806620429,10500,0,199.9989614,0,0,0,90.00000001 +303.11,50.30085681,-2.806592404,10500,0,199.9998535,0,0,0,90.00000001 +303.12,50.30085681,-2.806564379,10500,0,200.0009685,0,0,0,90.00000001 +303.13,50.30085681,-2.806536353,10500,0,200.0009685,0,0,0,90.00000001 +303.14,50.30085681,-2.806508328,10500,0,199.9998535,0,0,0,90.00000001 +303.15,50.30085681,-2.806480303,10500,0,199.9989614,0,0,0,90.00000001 +303.16,50.30085681,-2.806452278,10500,0,199.9989614,0,0,0,90.00000001 +303.17,50.30085681,-2.806424253,10500,0,199.9998535,0,0,0,90.00000001 +303.18,50.30085681,-2.806396228,10500,0,200.0009685,0,0,0,90.00000001 +303.19,50.30085681,-2.806368202,10500,0,200.0009685,0,0,0,90.00000001 +303.2,50.30085681,-2.806340177,10500,0,199.9998535,0,0,0,90.00000001 +303.21,50.30085681,-2.806312152,10500,0,199.9989614,0,0,0,90.00000001 +303.22,50.30085681,-2.806284127,10500,0,199.9989614,0,0,0,90.00000001 +303.23,50.30085681,-2.806256102,10500,0,199.9998535,0,0,0,90.00000001 +303.24,50.30085681,-2.806228077,10500,0,200.0009685,0,0,0,90.00000001 +303.25,50.30085681,-2.806200051,10500,0,200.0009685,0,0,0,90.00000001 +303.26,50.30085681,-2.806172026,10500,0,199.9998535,0,0,0,90.00000001 +303.27,50.30085681,-2.806144001,10500,0,199.9989614,0,0,0,90.00000001 +303.28,50.30085681,-2.806115976,10500,0,199.9987384,0,0,0,90.00000001 +303.29,50.30085681,-2.806087951,10500,0,199.9989614,0,0,0,90.00000001 +303.3,50.30085681,-2.806059926,10500,0,199.9998535,0,0,0,90.00000001 +303.31,50.30085681,-2.806031901,10500,0,200.0009685,0,0,0,90.00000001 +303.32,50.30085681,-2.806003875,10500,0,200.0009685,0,0,0,90.00000001 +303.33,50.30085681,-2.80597585,10500,0,199.9998535,0,0,0,90.00000001 +303.34,50.30085681,-2.805947825,10500,0,199.9991844,0,0,0,90.00000001 +303.35,50.30085681,-2.8059198,10500,0,199.9998535,0,0,0,90.00000001 +303.36,50.30085681,-2.805891775,10500,0,200.0009685,0,0,0,90.00000001 +303.37,50.30085681,-2.805863749,10500,0,200.0009685,0,0,0,90.00000001 +303.38,50.30085681,-2.805835724,10500,0,199.9998535,0,0,0,90.00000001 +303.39,50.30085681,-2.805807699,10500,0,199.9991844,0,0,0,90.00000001 +303.4,50.30085681,-2.805779674,10500,0,199.9998535,0,0,0,90.00000001 +303.41,50.30085681,-2.805751649,10500,0,200.0009685,0,0,0,90.00000001 +303.42,50.30085681,-2.805723623,10500,0,200.0009685,0,0,0,90.00000001 +303.43,50.30085681,-2.805695598,10500,0,199.9998535,0,0,0,90.00000001 +303.44,50.30085681,-2.805667573,10500,0,199.9991844,0,0,0,90.00000001 +303.45,50.30085681,-2.805639548,10500,0,199.9998535,0,0,0,90.00000001 +303.46,50.30085681,-2.805611523,10500,0,200.0009685,0,0,0,90.00000001 +303.47,50.30085681,-2.805583497,10500,0,200.0009685,0,0,0,90.00000001 +303.48,50.30085681,-2.805555472,10500,0,199.9998535,0,0,0,90.00000001 +303.49,50.30085681,-2.805527447,10500,0,199.9991844,0,0,0,90.00000001 +303.5,50.30085681,-2.805499422,10500,0,199.9998535,0,0,0,90.00000001 +303.51,50.30085681,-2.805471397,10500,0,200.0009685,0,0,0,90.00000001 +303.52,50.30085681,-2.805443371,10500,0,200.0009685,0,0,0,90.00000001 +303.53,50.30085681,-2.805415346,10500,0,199.9998535,0,0,0,90.00000001 +303.54,50.30085681,-2.805387321,10500,0,199.9991844,0,0,0,90.00000001 +303.55,50.30085681,-2.805359296,10500,0,199.9998535,0,0,0,90.00000001 +303.56,50.30085681,-2.805331271,10500,0,200.0009685,0,0,0,90.00000001 +303.57,50.30085681,-2.805303245,10500,0,200.0009685,0,0,0,90.00000001 +303.58,50.30085681,-2.80527522,10500,0,199.9998535,0,0,0,90.00000001 +303.59,50.30085681,-2.805247195,10500,0,199.9989614,0,0,0,90.00000001 +303.6,50.30085681,-2.80521917,10500,0,199.9989614,0,0,0,90.00000001 +303.61,50.30085681,-2.805191145,10500,0,199.9998535,0,0,0,90.00000001 +303.62,50.30085681,-2.80516312,10500,0,200.0009685,0,0,0,90.00000001 +303.63,50.30085681,-2.805135094,10500,0,200.0009685,0,0,0,90.00000001 +303.64,50.30085681,-2.805107069,10500,0,199.9998535,0,0,0,90.00000001 +303.65,50.30085681,-2.805079044,10500,0,199.9989614,0,0,0,90.00000001 +303.66,50.30085681,-2.805051019,10500,0,199.9989614,0,0,0,90.00000001 +303.67,50.30085681,-2.805022994,10500,0,199.9998535,0,0,0,90.00000001 +303.68,50.30085681,-2.804994969,10500,0,200.0009685,0,0,0,90.00000001 +303.69,50.30085681,-2.804966943,10500,0,200.0009685,0,0,0,90.00000001 +303.7,50.30085681,-2.804938918,10500,0,199.9998535,0,0,0,90.00000001 +303.71,50.30085681,-2.804910893,10500,0,199.9989614,0,0,0,90.00000001 +303.72,50.30085681,-2.804882868,10500,0,199.9989614,0,0,0,90.00000001 +303.73,50.30085681,-2.804854843,10500,0,199.9998535,0,0,0,90.00000001 +303.74,50.30085681,-2.804826818,10500,0,200.0009685,0,0,0,90.00000001 +303.75,50.30085681,-2.804798792,10500,0,200.0009685,0,0,0,90.00000001 +303.76,50.30085681,-2.804770767,10500,0,199.9998535,0,0,0,90.00000001 +303.77,50.30085681,-2.804742742,10500,0,199.9989614,0,0,0,90.00000001 +303.78,50.30085681,-2.804714717,10500,0,199.9989614,0,0,0,90.00000001 +303.79,50.30085681,-2.804686692,10500,0,199.9998535,0,0,0,90.00000001 +303.8,50.30085681,-2.804658667,10500,0,200.0009685,0,0,0,90.00000001 +303.81,50.30085681,-2.804630641,10500,0,200.0009685,0,0,0,90.00000001 +303.82,50.30085681,-2.804602616,10500,0,199.9998535,0,0,0,90.00000001 +303.83,50.30085681,-2.804574591,10500,0,199.9989614,0,0,0,90.00000001 +303.84,50.30085681,-2.804546566,10500,0,199.9987384,0,0,0,90.00000001 +303.85,50.30085681,-2.804518541,10500,0,199.9989614,0,0,0,90.00000001 +303.86,50.30085681,-2.804490516,10500,0,199.9998535,0,0,0,90.00000001 +303.87,50.30085681,-2.804462491,10500,0,200.0009685,0,0,0,90.00000001 +303.88,50.30085681,-2.804434465,10500,0,200.0009685,0,0,0,90.00000001 +303.89,50.30085681,-2.80440644,10500,0,199.9998535,0,0,0,90.00000001 +303.9,50.30085681,-2.804378415,10500,0,199.9989614,0,0,0,90.00000001 +303.91,50.30085681,-2.80435039,10500,0,199.9989614,0,0,0,90.00000001 +303.92,50.30085681,-2.804322365,10500,0,199.9998535,0,0,0,90.00000001 +303.93,50.30085681,-2.80429434,10500,0,200.0009685,0,0,0,90.00000001 +303.94,50.30085681,-2.804266314,10500,0,200.0009685,0,0,0,90.00000001 +303.95,50.30085681,-2.804238289,10500,0,199.9998535,0,0,0,90.00000001 +303.96,50.30085681,-2.804210264,10500,0,199.9991844,0,0,0,90.00000001 +303.97,50.30085681,-2.804182239,10500,0,199.9998535,0,0,0,90.00000001 +303.98,50.30085681,-2.804154214,10500,0,200.0009685,0,0,0,90.00000001 +303.99,50.30085681,-2.804126188,10500,0,200.0009685,0,0,0,90.00000001 +304,50.30085681,-2.804098163,10500,0,199.9998535,0,0,0,90.00000001 +304.01,50.30085681,-2.804070138,10500,0,199.9991844,0,0,0,90.00000001 +304.02,50.30085681,-2.804042113,10500,0,199.9998535,0,0,0,90.00000001 +304.03,50.30085681,-2.804014088,10500,0,200.0009685,0,0,0,90.00000001 +304.04,50.30085681,-2.803986062,10500,0,200.0009685,0,0,0,90.00000001 +304.05,50.30085681,-2.803958037,10500,0,199.9998535,0,0,0,90.00000001 +304.06,50.30085681,-2.803930012,10500,0,199.9991844,0,0,0,90.00000001 +304.07,50.30085681,-2.803901987,10500,0,199.9998535,0,0,0,90.00000001 +304.08,50.30085681,-2.803873962,10500,0,200.0009685,0,0,0,90.00000001 +304.09,50.30085681,-2.803845936,10500,0,200.0009685,0,0,0,90.00000001 +304.1,50.30085681,-2.803817911,10500,0,199.9998535,0,0,0,90.00000001 +304.11,50.30085681,-2.803789886,10500,0,199.9991844,0,0,0,90.00000001 +304.12,50.30085681,-2.803761861,10500,0,199.9998535,0,0,0,90.00000001 +304.13,50.30085681,-2.803733836,10500,0,200.0009685,0,0,0,90.00000001 +304.14,50.30085681,-2.80370581,10500,0,200.0009685,0,0,0,90.00000001 +304.15,50.30085681,-2.803677785,10500,0,199.9998535,0,0,0,90.00000001 +304.16,50.30085681,-2.80364976,10500,0,199.9991844,0,0,0,90.00000001 +304.17,50.30085681,-2.803621735,10500,0,199.9998535,0,0,0,90.00000001 +304.18,50.30085681,-2.80359371,10500,0,200.0009685,0,0,0,90.00000001 +304.19,50.30085681,-2.803565684,10500,0,200.0009685,0,0,0,90.00000001 +304.2,50.30085681,-2.803537659,10500,0,199.9998535,0,0,0,90.00000001 +304.21,50.30085681,-2.803509634,10500,0,199.9989614,0,0,0,90.00000001 +304.22,50.30085681,-2.803481609,10500,0,199.9989614,0,0,0,90.00000001 +304.23,50.30085681,-2.803453584,10500,0,199.9998535,0,0,0,90.00000001 +304.24,50.30085681,-2.803425559,10500,0,200.0009685,0,0,0,90.00000001 +304.25,50.30085681,-2.803397533,10500,0,200.0009685,0,0,0,90.00000001 +304.26,50.30085681,-2.803369508,10500,0,199.9998535,0,0,0,90.00000001 +304.27,50.30085681,-2.803341483,10500,0,199.9989614,0,0,0,90.00000001 +304.28,50.30085681,-2.803313458,10500,0,199.9989614,0,0,0,90.00000001 +304.29,50.30085681,-2.803285433,10500,0,199.9998535,0,0,0,90.00000001 +304.3,50.30085681,-2.803257408,10500,0,200.0009685,0,0,0,90.00000001 +304.31,50.30085681,-2.803229382,10500,0,200.0009685,0,0,0,90.00000001 +304.32,50.30085681,-2.803201357,10500,0,199.9998535,0,0,0,90.00000001 +304.33,50.30085681,-2.803173332,10500,0,199.9989614,0,0,0,90.00000001 +304.34,50.30085681,-2.803145307,10500,0,199.9989614,0,0,0,90.00000001 +304.35,50.30085681,-2.803117282,10500,0,199.9998535,0,0,0,90.00000001 +304.36,50.30085681,-2.803089257,10500,0,200.0009685,0,0,0,90.00000001 +304.37,50.30085681,-2.803061231,10500,0,200.0009685,0,0,0,90.00000001 +304.38,50.30085681,-2.803033206,10500,0,199.9998535,0,0,0,90.00000001 +304.39,50.30085681,-2.803005181,10500,0,199.9989614,0,0,0,90.00000001 +304.4,50.30085681,-2.802977156,10500,0,199.9987384,0,0,0,90.00000001 +304.41,50.30085681,-2.802949131,10500,0,199.9989614,0,0,0,90.00000001 +304.42,50.30085681,-2.802921106,10500,0,199.9998535,0,0,0,90.00000001 +304.43,50.30085681,-2.802893081,10500,0,200.0009685,0,0,0,90.00000001 +304.44,50.30085681,-2.802865055,10500,0,200.0009685,0,0,0,90.00000001 +304.45,50.30085681,-2.80283703,10500,0,199.9998535,0,0,0,90.00000001 +304.46,50.30085681,-2.802809005,10500,0,199.9989614,0,0,0,90.00000001 +304.47,50.30085681,-2.80278098,10500,0,199.9989614,0,0,0,90.00000001 +304.48,50.30085681,-2.802752955,10500,0,199.9998535,0,0,0,90.00000001 +304.49,50.30085681,-2.80272493,10500,0,200.0009685,0,0,0,90.00000001 +304.5,50.30085681,-2.802696904,10500,0,200.0009685,0,0,0,90.00000001 +304.51,50.30085681,-2.802668879,10500,0,199.9998535,0,0,0,90.00000001 +304.52,50.30085681,-2.802640854,10500,0,199.9989614,0,0,0,90.00000001 +304.53,50.30085681,-2.802612829,10500,0,199.9989614,0,0,0,90.00000001 +304.54,50.30085681,-2.802584804,10500,0,199.9998535,0,0,0,90.00000001 +304.55,50.30085681,-2.802556779,10500,0,200.0009685,0,0,0,90.00000001 +304.56,50.30085681,-2.802528753,10500,0,200.0009685,0,0,0,90.00000001 +304.57,50.30085681,-2.802500728,10500,0,199.9998535,0,0,0,90.00000001 +304.58,50.30085681,-2.802472703,10500,0,199.9991844,0,0,0,90.00000001 +304.59,50.30085681,-2.802444678,10500,0,199.9998535,0,0,0,90.00000001 +304.6,50.30085681,-2.802416653,10500,0,200.0009685,0,0,0,90.00000001 +304.61,50.30085681,-2.802388627,10500,0,200.0009685,0,0,0,90.00000001 +304.62,50.30085681,-2.802360602,10500,0,199.9998535,0,0,0,90.00000001 +304.63,50.30085681,-2.802332577,10500,0,199.9991844,0,0,0,90.00000001 +304.64,50.30085681,-2.802304552,10500,0,199.9998535,0,0,0,90.00000001 +304.65,50.30085681,-2.802276527,10500,0,200.0009685,0,0,0,90.00000001 +304.66,50.30085681,-2.802248501,10500,0,200.0009685,0,0,0,90.00000001 +304.67,50.30085681,-2.802220476,10500,0,199.9998535,0,0,0,90.00000001 +304.68,50.30085681,-2.802192451,10500,0,199.9991844,0,0,0,90.00000001 +304.69,50.30085681,-2.802164426,10500,0,199.9998535,0,0,0,90.00000001 +304.7,50.30085681,-2.802136401,10500,0,200.0009685,0,0,0,90.00000001 +304.71,50.30085681,-2.802108375,10500,0,200.0009685,0,0,0,90.00000001 +304.72,50.30085681,-2.80208035,10500,0,199.9998535,0,0,0,90.00000001 +304.73,50.30085681,-2.802052325,10500,0,199.9991844,0,0,0,90.00000001 +304.74,50.30085681,-2.8020243,10500,0,199.9998535,0,0,0,90.00000001 +304.75,50.30085681,-2.801996275,10500,0,200.0009685,0,0,0,90.00000001 +304.76,50.30085681,-2.801968249,10500,0,200.0009685,0,0,0,90.00000001 +304.77,50.30085681,-2.801940224,10500,0,199.9998535,0,0,0,90.00000001 +304.78,50.30085681,-2.801912199,10500,0,199.9991844,0,0,0,90.00000001 +304.79,50.30085681,-2.801884174,10500,0,199.9998535,0,0,0,90.00000001 +304.8,50.30085681,-2.801856149,10500,0,200.0009685,0,0,0,90.00000001 +304.81,50.30085681,-2.801828123,10500,0,200.0009685,0,0,0,90.00000001 +304.82,50.30085681,-2.801800098,10500,0,199.9998535,0,0,0,90.00000001 +304.83,50.30085681,-2.801772073,10500,0,199.9989614,0,0,0,90.00000001 +304.84,50.30085681,-2.801744048,10500,0,199.9989614,0,0,0,90.00000001 +304.85,50.30085681,-2.801716023,10500,0,199.9998535,0,0,0,90.00000001 +304.86,50.30085681,-2.801687998,10500,0,200.0009685,0,0,0,90.00000001 +304.87,50.30085681,-2.801659972,10500,0,200.0009685,0,0,0,90.00000001 +304.88,50.30085681,-2.801631947,10500,0,199.9998535,0,0,0,90.00000001 +304.89,50.30085681,-2.801603922,10500,0,199.9989614,0,0,0,90.00000001 +304.9,50.30085681,-2.801575897,10500,0,199.9989614,0,0,0,90.00000001 +304.91,50.30085681,-2.801547872,10500,0,199.9998535,0,0,0,90.00000001 +304.92,50.30085681,-2.801519847,10500,0,200.0009685,0,0,0,90.00000001 +304.93,50.30085681,-2.801491821,10500,0,200.0009685,0,0,0,90.00000001 +304.94,50.30085681,-2.801463796,10500,0,199.9998535,0,0,0,90.00000001 +304.95,50.30085681,-2.801435771,10500,0,199.9989614,0,0,0,90.00000001 +304.96,50.30085681,-2.801407746,10500,0,199.9989614,0,0,0,90.00000001 +304.97,50.30085681,-2.801379721,10500,0,199.9998535,0,0,0,90.00000001 +304.98,50.30085681,-2.801351696,10500,0,200.0009685,0,0,0,90.00000001 +304.99,50.30085681,-2.80132367,10500,0,200.0009685,0,0,0,90.00000001 +305,50.30085681,-2.801295645,10500,0,199.9998535,0,0,0,90.00000001 +305.01,50.30085681,-2.80126762,10500,0,199.9989614,0,0,0,90.00000001 +305.02,50.30085681,-2.801239595,10500,0,199.9987384,0,0,0,90.00000001 +305.03,50.30085681,-2.80121157,10500,0,199.9989614,0,0,0,90.00000001 +305.04,50.30085681,-2.801183545,10500,0,199.9998535,0,0,0,90.00000001 +305.05,50.30085681,-2.80115552,10500,0,200.0009685,0,0,0,90.00000001 +305.06,50.30085681,-2.801127494,10500,0,200.0009685,0,0,0,90.00000001 +305.07,50.30085681,-2.801099469,10500,0,199.9998535,0,0,0,90.00000001 +305.08,50.30085681,-2.801071444,10500,0,199.9989614,0,0,0,90.00000001 +305.09,50.30085681,-2.801043419,10500,0,199.9989614,0,0,0,90.00000001 +305.1,50.30085681,-2.801015394,10500,0,199.9998535,0,0,0,90.00000001 +305.11,50.30085681,-2.800987369,10500,0,200.0009685,0,0,0,90.00000001 +305.12,50.30085681,-2.800959343,10500,0,200.0009685,0,0,0,90.00000001 +305.13,50.30085681,-2.800931318,10500,0,199.9998535,0,0,0,90.00000001 +305.14,50.30085681,-2.800903293,10500,0,199.9989614,0,0,0,90.00000001 +305.15,50.30085681,-2.800875268,10500,0,199.9989614,0,0,0,90.00000001 +305.16,50.30085681,-2.800847243,10500,0,199.9998535,0,0,0,90.00000001 +305.17,50.30085681,-2.800819218,10500,0,200.0009685,0,0,0,90.00000001 +305.18,50.30085681,-2.800791192,10500,0,200.0009685,0,0,0,90.00000001 +305.19,50.30085681,-2.800763167,10500,0,199.9998535,0,0,0,90.00000001 +305.2,50.30085681,-2.800735142,10500,0,199.9989614,0,0,0,90.00000001 +305.21,50.30085681,-2.800707117,10500,0,199.9989614,0,0,0,90.00000001 +305.22,50.30085681,-2.800679092,10500,0,199.9998535,0,0,0,90.00000001 +305.23,50.30085681,-2.800651067,10500,0,200.0009685,0,0,0,90.00000001 +305.24,50.30085681,-2.800623041,10500,0,200.0009685,0,0,0,90.00000001 +305.25,50.30085681,-2.800595016,10500,0,199.9998535,0,0,0,90.00000001 +305.26,50.30085681,-2.800566991,10500,0,199.9991844,0,0,0,90.00000001 +305.27,50.30085681,-2.800538966,10500,0,199.9998535,0,0,0,90.00000001 +305.28,50.30085681,-2.800510941,10500,0,200.0009685,0,0,0,90.00000001 +305.29,50.30085681,-2.800482915,10500,0,200.0009685,0,0,0,90.00000001 +305.3,50.30085681,-2.80045489,10500,0,199.9998535,0,0,0,90.00000001 +305.31,50.30085681,-2.800426865,10500,0,199.9991844,0,0,0,90.00000001 +305.32,50.30085681,-2.80039884,10500,0,199.9998535,0,0,0,90.00000001 +305.33,50.30085681,-2.800370815,10500,0,200.0009685,0,0,0,90.00000001 +305.34,50.30085681,-2.800342789,10500,0,200.0009685,0,0,0,90.00000001 +305.35,50.30085681,-2.800314764,10500,0,199.9998535,0,0,0,90.00000001 +305.36,50.30085681,-2.800286739,10500,0,199.9991844,0,0,0,90.00000001 +305.37,50.30085681,-2.800258714,10500,0,199.9998535,0,0,0,90.00000001 +305.38,50.30085681,-2.800230689,10500,0,200.0009685,0,0,0,90.00000001 +305.39,50.30085681,-2.800202663,10500,0,200.0009685,0,0,0,90.00000001 +305.4,50.30085681,-2.800174638,10500,0,199.9998535,0,0,0,90.00000001 +305.41,50.30085681,-2.800146613,10500,0,199.9991844,0,0,0,90.00000001 +305.42,50.30085681,-2.800118588,10500,0,199.9998535,0,0,0,90.00000001 +305.43,50.30085681,-2.800090563,10500,0,200.0009685,0,0,0,90.00000001 +305.44,50.30085681,-2.800062537,10500,0,200.0009685,0,0,0,90.00000001 +305.45,50.30085681,-2.800034512,10500,0,199.9998535,0,0,0,90.00000001 +305.46,50.30085681,-2.800006487,10500,0,199.9991844,0,0,0,90.00000001 +305.47,50.30085681,-2.799978462,10500,0,199.9998535,0,0,0,90.00000001 +305.48,50.30085681,-2.799950437,10500,0,200.0009685,0,0,0,90.00000001 +305.49,50.30085681,-2.799922411,10500,0,200.0009685,0,0,0,90.00000001 +305.5,50.30085681,-2.799894386,10500,0,199.9998535,0,0,0,90.00000001 +305.51,50.30085681,-2.799866361,10500,0,199.9989614,0,0,0,90.00000001 +305.52,50.30085681,-2.799838336,10500,0,199.9989614,0,0,0,90.00000001 +305.53,50.30085681,-2.799810311,10500,0,199.9998535,0,0,0,90.00000001 +305.54,50.30085681,-2.799782286,10500,0,200.0009685,0,0,0,90.00000001 +305.55,50.30085681,-2.79975426,10500,0,200.0009685,0,0,0,90.00000001 +305.56,50.30085681,-2.799726235,10500,0,199.9998535,0,0,0,90.00000001 +305.57,50.30085681,-2.79969821,10500,0,199.9989614,0,0,0,90.00000001 +305.58,50.30085681,-2.799670185,10500,0,199.9987384,0,0,0,90.00000001 +305.59,50.30085681,-2.79964216,10500,0,199.9989614,0,0,0,90.00000001 +305.6,50.30085681,-2.799614135,10500,0,199.9998535,0,0,0,90.00000001 +305.61,50.30085681,-2.79958611,10500,0,200.0009685,0,0,0,90.00000001 +305.62,50.30085681,-2.799558084,10500,0,200.0009685,0,0,0,90.00000001 +305.63,50.30085681,-2.799530059,10500,0,199.9998535,0,0,0,90.00000001 +305.64,50.30085681,-2.799502034,10500,0,199.9989614,0,0,0,90.00000001 +305.65,50.30085681,-2.799474009,10500,0,199.9989614,0,0,0,90.00000001 +305.66,50.30085681,-2.799445984,10500,0,199.9998535,0,0,0,90.00000001 +305.67,50.30085681,-2.799417959,10500,0,200.0009685,0,0,0,90.00000001 +305.68,50.30085681,-2.799389933,10500,0,200.0009685,0,0,0,90.00000001 +305.69,50.30085681,-2.799361908,10500,0,199.9998535,0,0,0,90.00000001 +305.7,50.30085681,-2.799333883,10500,0,199.9989614,0,0,0,90.00000001 +305.71,50.30085681,-2.799305858,10500,0,199.9989614,0,0,0,90.00000001 +305.72,50.30085681,-2.799277833,10500,0,199.9998535,0,0,0,90.00000001 +305.73,50.30085681,-2.799249808,10500,0,200.0009685,0,0,0,90.00000001 +305.74,50.30085681,-2.799221782,10500,0,200.0009685,0,0,0,90.00000001 +305.75,50.30085681,-2.799193757,10500,0,199.9998535,0,0,0,90.00000001 +305.76,50.30085681,-2.799165732,10500,0,199.9989614,0,0,0,90.00000001 +305.77,50.30085681,-2.799137707,10500,0,199.9989614,0,0,0,90.00000001 +305.78,50.30085681,-2.799109682,10500,0,199.9998535,0,0,0,90.00000001 +305.79,50.30085681,-2.799081657,10500,0,200.0009685,0,0,0,90.00000001 +305.8,50.30085681,-2.799053631,10500,0,200.0009685,0,0,0,90.00000001 +305.81,50.30085681,-2.799025606,10500,0,199.9998535,0,0,0,90.00000001 +305.82,50.30085681,-2.798997581,10500,0,199.9989614,0,0,0,90.00000001 +305.83,50.30085681,-2.798969556,10500,0,199.9989614,0,0,0,90.00000001 +305.84,50.30085681,-2.798941531,10500,0,199.9998535,0,0,0,90.00000001 +305.85,50.30085681,-2.798913506,10500,0,200.0009685,0,0,0,90.00000001 +305.86,50.30085681,-2.79888548,10500,0,200.0009685,0,0,0,90.00000001 +305.87,50.30085681,-2.798857455,10500,0,199.9998535,0,0,0,90.00000001 +305.88,50.30085681,-2.79882943,10500,0,199.9991844,0,0,0,90.00000001 +305.89,50.30085681,-2.798801405,10500,0,199.9998535,0,0,0,90.00000001 +305.9,50.30085681,-2.79877338,10500,0,200.0009685,0,0,0,90.00000001 +305.91,50.30085681,-2.798745354,10500,0,200.0009685,0,0,0,90.00000001 +305.92,50.30085681,-2.798717329,10500,0,199.9998535,0,0,0,90.00000001 +305.93,50.30085681,-2.798689304,10500,0,199.9991844,0,0,0,90.00000001 +305.94,50.30085681,-2.798661279,10500,0,199.9998535,0,0,0,90.00000001 +305.95,50.30085681,-2.798633254,10500,0,200.0009685,0,0,0,90.00000001 +305.96,50.30085681,-2.798605228,10500,0,200.0009685,0,0,0,90.00000001 +305.97,50.30085681,-2.798577203,10500,0,199.9998535,0,0,0,90.00000001 +305.98,50.30085681,-2.798549178,10500,0,199.9991844,0,0,0,90.00000001 +305.99,50.30085681,-2.798521153,10500,0,199.9998535,0,0,0,90.00000001 +306,50.30085681,-2.798493128,10500,0,200.0009685,0,0,0,90.00000001 +306.01,50.30085681,-2.798465102,10500,0,200.0009685,0,0,0,90.00000001 +306.02,50.30085681,-2.798437077,10500,0,199.9998535,0,0,0,90.00000001 +306.03,50.30085681,-2.798409052,10500,0,199.9991844,0,0,0,90.00000001 +306.04,50.30085681,-2.798381027,10500,0,199.9998535,0,0,0,90.00000001 +306.05,50.30085681,-2.798353002,10500,0,200.0009685,0,0,0,90.00000001 +306.06,50.30085681,-2.798324976,10500,0,200.0009685,0,0,0,90.00000001 +306.07,50.30085681,-2.798296951,10500,0,199.9998535,0,0,0,90.00000001 +306.08,50.30085681,-2.798268926,10500,0,199.9991844,0,0,0,90.00000001 +306.09,50.30085681,-2.798240901,10500,0,199.9998535,0,0,0,90.00000001 +306.1,50.30085681,-2.798212876,10500,0,200.0009685,0,0,0,90.00000001 +306.11,50.30085681,-2.79818485,10500,0,200.0009685,0,0,0,90.00000001 +306.12,50.30085681,-2.798156825,10500,0,199.9998535,0,0,0,90.00000001 +306.13,50.30085681,-2.7981288,10500,0,199.9989614,0,0,0,90.00000001 +306.14,50.30085681,-2.798100775,10500,0,199.9987384,0,0,0,90.00000001 +306.15,50.30085681,-2.79807275,10500,0,199.9989614,0,0,0,90.00000001 +306.16,50.30085681,-2.798044725,10500,0,199.9998535,0,0,0,90.00000001 +306.17,50.30085681,-2.7980167,10500,0,200.0009685,0,0,0,90.00000001 +306.18,50.30085681,-2.797988674,10500,0,200.0009685,0,0,0,90.00000001 +306.19,50.30085681,-2.797960649,10500,0,199.9998535,0,0,0,90.00000001 +306.2,50.30085681,-2.797932624,10500,0,199.9989614,0,0,0,90.00000001 +306.21,50.30085681,-2.797904599,10500,0,199.9989614,0,0,0,90.00000001 +306.22,50.30085681,-2.797876574,10500,0,199.9998535,0,0,0,90.00000001 +306.23,50.30085681,-2.797848549,10500,0,200.0009685,0,0,0,90.00000001 +306.24,50.30085681,-2.797820523,10500,0,200.0009685,0,0,0,90.00000001 +306.25,50.30085681,-2.797792498,10500,0,199.9998535,0,0,0,90.00000001 +306.26,50.30085681,-2.797764473,10500,0,199.9989614,0,0,0,90.00000001 +306.27,50.30085681,-2.797736448,10500,0,199.9989614,0,0,0,90.00000001 +306.28,50.30085681,-2.797708423,10500,0,199.9998535,0,0,0,90.00000001 +306.29,50.30085681,-2.797680398,10500,0,200.0009685,0,0,0,90.00000001 +306.3,50.30085681,-2.797652372,10500,0,200.0009685,0,0,0,90.00000001 +306.31,50.30085681,-2.797624347,10500,0,199.9998535,0,0,0,90.00000001 +306.32,50.30085681,-2.797596322,10500,0,199.9989614,0,0,0,90.00000001 +306.33,50.30085681,-2.797568297,10500,0,199.9989614,0,0,0,90.00000001 +306.34,50.30085681,-2.797540272,10500,0,199.9998535,0,0,0,90.00000001 +306.35,50.30085681,-2.797512247,10500,0,200.0009685,0,0,0,90.00000001 +306.36,50.30085681,-2.797484221,10500,0,200.0009685,0,0,0,90.00000001 +306.37,50.30085681,-2.797456196,10500,0,199.9998535,0,0,0,90.00000001 +306.38,50.30085681,-2.797428171,10500,0,199.9989614,0,0,0,90.00000001 +306.39,50.30085681,-2.797400146,10500,0,199.9989614,0,0,0,90.00000001 +306.4,50.30085681,-2.797372121,10500,0,199.9998535,0,0,0,90.00000001 +306.41,50.30085681,-2.797344096,10500,0,200.0009685,0,0,0,90.00000001 +306.42,50.30085681,-2.79731607,10500,0,200.0009685,0,0,0,90.00000001 +306.43,50.30085681,-2.797288045,10500,0,199.9998535,0,0,0,90.00000001 +306.44,50.30085681,-2.79726002,10500,0,199.9989614,0,0,0,90.00000001 +306.45,50.30085681,-2.797231995,10500,0,199.9989614,0,0,0,90.00000001 +306.46,50.30085681,-2.79720397,10500,0,199.9998535,0,0,0,90.00000001 +306.47,50.30085681,-2.797175945,10500,0,200.0009685,0,0,0,90.00000001 +306.48,50.30085681,-2.797147919,10500,0,200.0009685,0,0,0,90.00000001 +306.49,50.30085681,-2.797119894,10500,0,199.9998535,0,0,0,90.00000001 +306.5,50.30085681,-2.797091869,10500,0,199.9991844,0,0,0,90.00000001 +306.51,50.30085681,-2.797063844,10500,0,199.9998535,0,0,0,90.00000001 +306.52,50.30085681,-2.797035819,10500,0,200.0009685,0,0,0,90.00000001 +306.53,50.30085681,-2.797007793,10500,0,200.0009685,0,0,0,90.00000001 +306.54,50.30085681,-2.796979768,10500,0,199.9998535,0,0,0,90.00000001 +306.55,50.30085681,-2.796951743,10500,0,199.9991844,0,0,0,90.00000001 +306.56,50.30085681,-2.796923718,10500,0,199.9998535,0,0,0,90.00000001 +306.57,50.30085681,-2.796895693,10500,0,200.0009685,0,0,0,90.00000001 +306.58,50.30085681,-2.796867667,10500,0,200.0009685,0,0,0,90.00000001 +306.59,50.30085681,-2.796839642,10500,0,199.9998535,0,0,0,90.00000001 +306.6,50.30085681,-2.796811617,10500,0,199.9991844,0,0,0,90.00000001 +306.61,50.30085681,-2.796783592,10500,0,199.9998535,0,0,0,90.00000001 +306.62,50.30085681,-2.796755567,10500,0,200.0009685,0,0,0,90.00000001 +306.63,50.30085681,-2.796727541,10500,0,200.0009685,0,0,0,90.00000001 +306.64,50.30085681,-2.796699516,10500,0,199.9998535,0,0,0,90.00000001 +306.65,50.30085681,-2.796671491,10500,0,199.9991844,0,0,0,90.00000001 +306.66,50.30085681,-2.796643466,10500,0,199.9998535,0,0,0,90.00000001 +306.67,50.30085681,-2.796615441,10500,0,200.0009685,0,0,0,90.00000001 +306.68,50.30085681,-2.796587415,10500,0,200.0009685,0,0,0,90.00000001 +306.69,50.30085681,-2.79655939,10500,0,199.9998535,0,0,0,90.00000001 +306.7,50.30085681,-2.796531365,10500,0,199.9989614,0,0,0,90.00000001 +306.71,50.30085681,-2.79650334,10500,0,199.9989614,0,0,0,90.00000001 +306.72,50.30085681,-2.796475315,10500,0,199.9998535,0,0,0,90.00000001 +306.73,50.30085681,-2.79644729,10500,0,200.0009685,0,0,0,90.00000001 +306.74,50.30085681,-2.796419264,10500,0,200.0009685,0,0,0,90.00000001 +306.75,50.30085681,-2.796391239,10500,0,199.9998535,0,0,0,90.00000001 +306.76,50.30085681,-2.796363214,10500,0,199.9989614,0,0,0,90.00000001 +306.77,50.30085681,-2.796335189,10500,0,199.9989614,0,0,0,90.00000001 +306.78,50.30085681,-2.796307164,10500,0,199.9998535,0,0,0,90.00000001 +306.79,50.30085681,-2.796279139,10500,0,200.0009685,0,0,0,90.00000001 +306.8,50.30085681,-2.796251113,10500,0,200.0009685,0,0,0,90.00000001 +306.81,50.30085681,-2.796223088,10500,0,199.9998535,0,0,0,90.00000001 +306.82,50.30085681,-2.796195063,10500,0,199.9989614,0,0,0,90.00000001 +306.83,50.30085681,-2.796167038,10500,0,199.9989614,0,0,0,90.00000001 +306.84,50.30085681,-2.796139013,10500,0,199.9998535,0,0,0,90.00000001 +306.85,50.30085681,-2.796110988,10500,0,200.0009685,0,0,0,90.00000001 +306.86,50.30085681,-2.796082962,10500,0,200.0009685,0,0,0,90.00000001 +306.87,50.30085681,-2.796054937,10500,0,199.9998535,0,0,0,90.00000001 +306.88,50.30085681,-2.796026912,10500,0,199.9989614,0,0,0,90.00000001 +306.89,50.30085681,-2.795998887,10500,0,199.9989614,0,0,0,90.00000001 +306.9,50.30085681,-2.795970862,10500,0,199.9998535,0,0,0,90.00000001 +306.91,50.30085681,-2.795942837,10500,0,200.0009685,0,0,0,90.00000001 +306.92,50.30085681,-2.795914811,10500,0,200.0009685,0,0,0,90.00000001 +306.93,50.30085681,-2.795886786,10500,0,199.9998535,0,0,0,90.00000001 +306.94,50.30085681,-2.795858761,10500,0,199.9989614,0,0,0,90.00000001 +306.95,50.30085681,-2.795830736,10500,0,199.9989614,0,0,0,90.00000001 +306.96,50.30085681,-2.795802711,10500,0,199.9998535,0,0,0,90.00000001 +306.97,50.30085681,-2.795774686,10500,0,200.0009685,0,0,0,90.00000001 +306.98,50.30085681,-2.79574666,10500,0,200.0009685,0,0,0,90.00000001 +306.99,50.30085681,-2.795718635,10500,0,199.9998535,0,0,0,90.00000001 +307,50.30085681,-2.79569061,10500,0,199.9989614,0,0,0,90.00000001 +307.01,50.30085681,-2.795662585,10500,0,199.9987384,0,0,0,90.00000001 +307.02,50.30085681,-2.79563456,10500,0,199.9989614,0,0,0,90.00000001 +307.03,50.30085681,-2.795606535,10500,0,199.9998535,0,0,0,90.00000001 +307.04,50.30085681,-2.79557851,10500,0,200.0009685,0,0,0,90.00000001 +307.05,50.30085681,-2.795550484,10500,0,200.0009685,0,0,0,90.00000001 +307.06,50.30085681,-2.795522459,10500,0,199.9998535,0,0,0,90.00000001 +307.07,50.30085681,-2.795494434,10500,0,199.9991844,0,0,0,90.00000001 +307.08,50.30085681,-2.795466409,10500,0,199.9998535,0,0,0,90.00000001 +307.09,50.30085681,-2.795438384,10500,0,200.0009685,0,0,0,90.00000001 +307.1,50.30085681,-2.795410358,10500,0,200.0009685,0,0,0,90.00000001 +307.11,50.30085681,-2.795382333,10500,0,199.9998535,0,0,0,90.00000001 +307.12,50.30085681,-2.795354308,10500,0,199.9991844,0,0,0,90.00000001 +307.13,50.30085681,-2.795326283,10500,0,199.9998535,0,0,0,90.00000001 +307.14,50.30085681,-2.795298258,10500,0,200.0009685,0,0,0,90.00000001 +307.15,50.30085681,-2.795270232,10500,0,200.0009685,0,0,0,90.00000001 +307.16,50.30085681,-2.795242207,10500,0,199.9998535,0,0,0,90.00000001 +307.17,50.30085681,-2.795214182,10500,0,199.9991844,0,0,0,90.00000001 +307.18,50.30085681,-2.795186157,10500,0,199.9998535,0,0,0,90.00000001 +307.19,50.30085681,-2.795158132,10500,0,200.0009685,0,0,0,90.00000001 +307.2,50.30085681,-2.795130106,10500,0,200.0009685,0,0,0,90.00000001 +307.21,50.30085681,-2.795102081,10500,0,199.9998535,0,0,0,90.00000001 +307.22,50.30085681,-2.795074056,10500,0,199.9989614,0,0,0,90.00000001 +307.23,50.30085681,-2.795046031,10500,0,199.9989614,0,0,0,90.00000001 +307.24,50.30085681,-2.795018006,10500,0,199.9998535,0,0,0,90.00000001 +307.25,50.30085681,-2.794989981,10500,0,200.0009685,0,0,0,90.00000001 +307.26,50.30085681,-2.794961955,10500,0,200.0009685,0,0,0,90.00000001 +307.27,50.30085681,-2.79493393,10500,0,199.9998535,0,0,0,90.00000001 +307.28,50.30085681,-2.794905905,10500,0,199.9991844,0,0,0,90.00000001 +307.29,50.30085681,-2.79487788,10500,0,199.9998535,0,0,0,90.00000001 +307.3,50.30085681,-2.794849855,10500,0,200.0009685,0,0,0,90.00000001 +307.31,50.30085681,-2.794821829,10500,0,200.0009685,0,0,0,90.00000001 +307.32,50.30085681,-2.794793804,10500,0,199.9998535,0,0,0,90.00000001 +307.33,50.30085681,-2.794765779,10500,0,199.9991844,0,0,0,90.00000001 +307.34,50.30085681,-2.794737754,10500,0,199.9998535,0,0,0,90.00000001 +307.35,50.30085681,-2.794709729,10500,0,200.0009685,0,0,0,90.00000001 +307.36,50.30085681,-2.794681703,10500,0,200.0009685,0,0,0,90.00000001 +307.37,50.30085681,-2.794653678,10500,0,199.9998535,0,0,0,90.00000001 +307.38,50.30085681,-2.794625653,10500,0,199.9989614,0,0,0,90.00000001 +307.39,50.30085681,-2.794597628,10500,0,199.9989614,0,0,0,90.00000001 +307.4,50.30085681,-2.794569603,10500,0,199.9998535,0,0,0,90.00000001 +307.41,50.30085681,-2.794541578,10500,0,200.0009685,0,0,0,90.00000001 +307.42,50.30085681,-2.794513552,10500,0,200.0009685,0,0,0,90.00000001 +307.43,50.30085681,-2.794485527,10500,0,199.9998535,0,0,0,90.00000001 +307.44,50.30085681,-2.794457502,10500,0,199.9989614,0,0,0,90.00000001 +307.45,50.30085681,-2.794429477,10500,0,199.9989614,0,0,0,90.00000001 +307.46,50.30085681,-2.794401452,10500,0,199.9998535,0,0,0,90.00000001 +307.47,50.30085681,-2.794373427,10500,0,200.0009685,0,0,0,90.00000001 +307.48,50.30085681,-2.794345401,10500,0,200.0009685,0,0,0,90.00000001 +307.49,50.30085681,-2.794317376,10500,0,199.9998535,0,0,0,90.00000001 +307.5,50.30085681,-2.794289351,10500,0,199.9989614,0,0,0,90.00000001 +307.51,50.30085681,-2.794261326,10500,0,199.9989614,0,0,0,90.00000001 +307.52,50.30085681,-2.794233301,10500,0,199.9998535,0,0,0,90.00000001 +307.53,50.30085681,-2.794205276,10500,0,200.0009685,0,0,0,90.00000001 +307.54,50.30085681,-2.79417725,10500,0,200.0009685,0,0,0,90.00000001 +307.55,50.30085681,-2.794149225,10500,0,199.9998535,0,0,0,90.00000001 +307.56,50.30085681,-2.7941212,10500,0,199.9989614,0,0,0,90.00000001 +307.57,50.30085681,-2.794093175,10500,0,199.9987384,0,0,0,90.00000001 +307.58,50.30085681,-2.79406515,10500,0,199.9989614,0,0,0,90.00000001 +307.59,50.30085681,-2.794037125,10500,0,199.9998535,0,0,0,90.00000001 +307.6,50.30085681,-2.7940091,10500,0,200.0009685,0,0,0,90.00000001 +307.61,50.30085681,-2.793981074,10500,0,200.0009685,0,0,0,90.00000001 +307.62,50.30085681,-2.793953049,10500,0,199.9998535,0,0,0,90.00000001 +307.63,50.30085681,-2.793925024,10500,0,199.9989614,0,0,0,90.00000001 +307.64,50.30085681,-2.793896999,10500,0,199.9989614,0,0,0,90.00000001 +307.65,50.30085681,-2.793868974,10500,0,199.9998535,0,0,0,90.00000001 +307.66,50.30085681,-2.793840949,10500,0,200.0009685,0,0,0,90.00000001 +307.67,50.30085681,-2.793812923,10500,0,200.0009685,0,0,0,90.00000001 +307.68,50.30085681,-2.793784898,10500,0,199.9998535,0,0,0,90.00000001 +307.69,50.30085681,-2.793756873,10500,0,199.9989614,0,0,0,90.00000001 +307.7,50.30085681,-2.793728848,10500,0,199.9989614,0,0,0,90.00000001 +307.71,50.30085681,-2.793700823,10500,0,199.9998535,0,0,0,90.00000001 +307.72,50.30085681,-2.793672798,10500,0,200.0009685,0,0,0,90.00000001 +307.73,50.30085681,-2.793644772,10500,0,200.0009685,0,0,0,90.00000001 +307.74,50.30085681,-2.793616747,10500,0,199.9998535,0,0,0,90.00000001 +307.75,50.30085681,-2.793588722,10500,0,199.9991844,0,0,0,90.00000001 +307.76,50.30085681,-2.793560697,10500,0,199.9998535,0,0,0,90.00000001 +307.77,50.30085681,-2.793532672,10500,0,200.0009685,0,0,0,90.00000001 +307.78,50.30085681,-2.793504646,10500,0,200.0009685,0,0,0,90.00000001 +307.79,50.30085681,-2.793476621,10500,0,199.9998535,0,0,0,90.00000001 +307.8,50.30085681,-2.793448596,10500,0,199.9991844,0,0,0,90.00000001 +307.81,50.30085681,-2.793420571,10500,0,199.9998535,0,0,0,90.00000001 +307.82,50.30085681,-2.793392546,10500,0,200.0009685,0,0,0,90.00000001 +307.83,50.30085681,-2.79336452,10500,0,200.0009685,0,0,0,90.00000001 +307.84,50.30085681,-2.793336495,10500,0,199.9998535,0,0,0,90.00000001 +307.85,50.30085681,-2.79330847,10500,0,199.9991844,0,0,0,90.00000001 +307.86,50.30085681,-2.793280445,10500,0,199.9998535,0,0,0,90.00000001 +307.87,50.30085681,-2.79325242,10500,0,200.0009685,0,0,0,90.00000001 +307.88,50.30085681,-2.793224394,10500,0,200.0009685,0,0,0,90.00000001 +307.89,50.30085681,-2.793196369,10500,0,199.9998535,0,0,0,90.00000001 +307.9,50.30085681,-2.793168344,10500,0,199.9991844,0,0,0,90.00000001 +307.91,50.30085681,-2.793140319,10500,0,199.9998535,0,0,0,90.00000001 +307.92,50.30085681,-2.793112294,10500,0,200.0009685,0,0,0,90.00000001 +307.93,50.30085681,-2.793084268,10500,0,200.0009685,0,0,0,90.00000001 +307.94,50.30085681,-2.793056243,10500,0,199.9998535,0,0,0,90.00000001 +307.95,50.30085681,-2.793028218,10500,0,199.9991844,0,0,0,90.00000001 +307.96,50.30085681,-2.793000193,10500,0,199.9998535,0,0,0,90.00000001 +307.97,50.30085681,-2.792972168,10500,0,200.0009685,0,0,0,90.00000001 +307.98,50.30085681,-2.792944142,10500,0,200.0009685,0,0,0,90.00000001 +307.99,50.30085681,-2.792916117,10500,0,199.9998535,0,0,0,90.00000001 +308,50.30085681,-2.792888092,10500,0,199.9989614,0,0,0,90.00000001 +308.01,50.30085681,-2.792860067,10500,0,199.9989614,0,0,0,90.00000001 +308.02,50.30085681,-2.792832042,10500,0,199.9998535,0,0,0,90.00000001 +308.03,50.30085681,-2.792804017,10500,0,200.0009685,0,0,0,90.00000001 +308.04,50.30085681,-2.792775991,10500,0,200.0009685,0,0,0,90.00000001 +308.05,50.30085681,-2.792747966,10500,0,199.9998535,0,0,0,90.00000001 +308.06,50.30085681,-2.792719941,10500,0,199.9989614,0,0,0,90.00000001 +308.07,50.30085681,-2.792691916,10500,0,199.9989614,0,0,0,90.00000001 +308.08,50.30085681,-2.792663891,10500,0,199.9998535,0,0,0,90.00000001 +308.09,50.30085681,-2.792635866,10500,0,200.0009685,0,0,0,90.00000001 +308.1,50.30085681,-2.79260784,10500,0,200.0009685,0,0,0,90.00000001 +308.11,50.30085681,-2.792579815,10500,0,199.9998535,0,0,0,90.00000001 +308.12,50.30085681,-2.79255179,10500,0,199.9989614,0,0,0,90.00000001 +308.13,50.30085681,-2.792523765,10500,0,199.9987384,0,0,0,90.00000001 +308.14,50.30085681,-2.79249574,10500,0,199.9989614,0,0,0,90.00000001 +308.15,50.30085681,-2.792467715,10500,0,199.9998535,0,0,0,90.00000001 +308.16,50.30085681,-2.79243969,10500,0,200.0009685,0,0,0,90.00000001 +308.17,50.30085681,-2.792411664,10500,0,200.0009685,0,0,0,90.00000001 +308.18,50.30085681,-2.792383639,10500,0,199.9998535,0,0,0,90.00000001 +308.19,50.30085681,-2.792355614,10500,0,199.9989614,0,0,0,90.00000001 +308.2,50.30085681,-2.792327589,10500,0,199.9989614,0,0,0,90.00000001 +308.21,50.30085681,-2.792299564,10500,0,199.9998535,0,0,0,90.00000001 +308.22,50.30085681,-2.792271539,10500,0,200.0009685,0,0,0,90.00000001 +308.23,50.30085681,-2.792243513,10500,0,200.0009685,0,0,0,90.00000001 +308.24,50.30085681,-2.792215488,10500,0,199.9998535,0,0,0,90.00000001 +308.25,50.30085681,-2.792187463,10500,0,199.9989614,0,0,0,90.00000001 +308.26,50.30085681,-2.792159438,10500,0,199.9989614,0,0,0,90.00000001 +308.27,50.30085681,-2.792131413,10500,0,199.9998535,0,0,0,90.00000001 +308.28,50.30085681,-2.792103388,10500,0,200.0009685,0,0,0,90.00000001 +308.29,50.30085681,-2.792075362,10500,0,200.0009685,0,0,0,90.00000001 +308.3,50.30085681,-2.792047337,10500,0,199.9998535,0,0,0,90.00000001 +308.31,50.30085681,-2.792019312,10500,0,199.9989614,0,0,0,90.00000001 +308.32,50.30085681,-2.791991287,10500,0,199.9989614,0,0,0,90.00000001 +308.33,50.30085681,-2.791963262,10500,0,199.9998535,0,0,0,90.00000001 +308.34,50.30085681,-2.791935237,10500,0,200.0009685,0,0,0,90.00000001 +308.35,50.30085681,-2.791907211,10500,0,200.0009685,0,0,0,90.00000001 +308.36,50.30085681,-2.791879186,10500,0,199.9998535,0,0,0,90.00000001 +308.37,50.30085681,-2.791851161,10500,0,199.9991844,0,0,0,90.00000001 +308.38,50.30085681,-2.791823136,10500,0,199.9998535,0,0,0,90.00000001 +308.39,50.30085681,-2.791795111,10500,0,200.0009685,0,0,0,90.00000001 +308.4,50.30085681,-2.791767085,10500,0,200.0009685,0,0,0,90.00000001 +308.41,50.30085681,-2.79173906,10500,0,199.9998535,0,0,0,90.00000001 +308.42,50.30085681,-2.791711035,10500,0,199.9991844,0,0,0,90.00000001 +308.43,50.30085681,-2.79168301,10500,0,199.9998535,0,0,0,90.00000001 +308.44,50.30085681,-2.791654985,10500,0,200.0009685,0,0,0,90.00000001 +308.45,50.30085681,-2.791626959,10500,0,200.0009685,0,0,0,90.00000001 +308.46,50.30085681,-2.791598934,10500,0,199.9998535,0,0,0,90.00000001 +308.47,50.30085681,-2.791570909,10500,0,199.9991844,0,0,0,90.00000001 +308.48,50.30085681,-2.791542884,10500,0,199.9998535,0,0,0,90.00000001 +308.49,50.30085681,-2.791514859,10500,0,200.0009685,0,0,0,90.00000001 +308.5,50.30085681,-2.791486833,10500,0,200.0009685,0,0,0,90.00000001 +308.51,50.30085681,-2.791458808,10500,0,199.9998535,0,0,0,90.00000001 +308.52,50.30085681,-2.791430783,10500,0,199.9991844,0,0,0,90.00000001 +308.53,50.30085681,-2.791402758,10500,0,199.9998535,0,0,0,90.00000001 +308.54,50.30085681,-2.791374733,10500,0,200.0009685,0,0,0,90.00000001 +308.55,50.30085681,-2.791346707,10500,0,200.0009685,0,0,0,90.00000001 +308.56,50.30085681,-2.791318682,10500,0,199.9998535,0,0,0,90.00000001 +308.57,50.30085681,-2.791290657,10500,0,199.9991844,0,0,0,90.00000001 +308.58,50.30085681,-2.791262632,10500,0,199.9998535,0,0,0,90.00000001 +308.59,50.30085681,-2.791234607,10500,0,200.0009685,0,0,0,90.00000001 +308.6,50.30085681,-2.791206581,10500,0,200.0009685,0,0,0,90.00000001 +308.61,50.30085681,-2.791178556,10500,0,199.9998535,0,0,0,90.00000001 +308.62,50.30085681,-2.791150531,10500,0,199.9989614,0,0,0,90.00000001 +308.63,50.30085681,-2.791122506,10500,0,199.9989614,0,0,0,90.00000001 +308.64,50.30085681,-2.791094481,10500,0,199.9998535,0,0,0,90.00000001 +308.65,50.30085681,-2.791066456,10500,0,200.0009685,0,0,0,90.00000001 +308.66,50.30085681,-2.79103843,10500,0,200.0009685,0,0,0,90.00000001 +308.67,50.30085681,-2.791010405,10500,0,199.9998535,0,0,0,90.00000001 +308.68,50.30085681,-2.79098238,10500,0,199.9989614,0,0,0,90.00000001 +308.69,50.30085681,-2.790954355,10500,0,199.9987384,0,0,0,90.00000001 +308.7,50.30085681,-2.79092633,10500,0,199.9989614,0,0,0,90.00000001 +308.71,50.30085681,-2.790898305,10500,0,199.9998535,0,0,0,90.00000001 +308.72,50.30085681,-2.79087028,10500,0,200.0009685,0,0,0,90.00000001 +308.73,50.30085681,-2.790842254,10500,0,200.0009685,0,0,0,90.00000001 +308.74,50.30085681,-2.790814229,10500,0,199.9998535,0,0,0,90.00000001 +308.75,50.30085681,-2.790786204,10500,0,199.9989614,0,0,0,90.00000001 +308.76,50.30085681,-2.790758179,10500,0,199.9989614,0,0,0,90.00000001 +308.77,50.30085681,-2.790730154,10500,0,199.9998535,0,0,0,90.00000001 +308.78,50.30085681,-2.790702129,10500,0,200.0009685,0,0,0,90.00000001 +308.79,50.30085681,-2.790674103,10500,0,200.0009685,0,0,0,90.00000001 +308.8,50.30085681,-2.790646078,10500,0,199.9998535,0,0,0,90.00000001 +308.81,50.30085681,-2.790618053,10500,0,199.9989614,0,0,0,90.00000001 +308.82,50.30085681,-2.790590028,10500,0,199.9989614,0,0,0,90.00000001 +308.83,50.30085681,-2.790562003,10500,0,199.9998535,0,0,0,90.00000001 +308.84,50.30085681,-2.790533978,10500,0,200.0009685,0,0,0,90.00000001 +308.85,50.30085681,-2.790505952,10500,0,200.0009685,0,0,0,90.00000001 +308.86,50.30085681,-2.790477927,10500,0,199.9998535,0,0,0,90.00000001 +308.87,50.30085681,-2.790449902,10500,0,199.9989614,0,0,0,90.00000001 +308.88,50.30085681,-2.790421877,10500,0,199.9989614,0,0,0,90.00000001 +308.89,50.30085681,-2.790393852,10500,0,199.9998535,0,0,0,90.00000001 +308.9,50.30085681,-2.790365827,10500,0,200.0009685,0,0,0,90.00000001 +308.91,50.30085681,-2.790337801,10500,0,200.0009685,0,0,0,90.00000001 +308.92,50.30085681,-2.790309776,10500,0,199.9998535,0,0,0,90.00000001 +308.93,50.30085681,-2.790281751,10500,0,199.9989614,0,0,0,90.00000001 +308.94,50.30085681,-2.790253726,10500,0,199.9989614,0,0,0,90.00000001 +308.95,50.30085681,-2.790225701,10500,0,199.9998535,0,0,0,90.00000001 +308.96,50.30085681,-2.790197676,10500,0,200.0009685,0,0,0,90.00000001 +308.97,50.30085681,-2.79016965,10500,0,200.0009685,0,0,0,90.00000001 +308.98,50.30085681,-2.790141625,10500,0,199.9998535,0,0,0,90.00000001 +308.99,50.30085681,-2.7901136,10500,0,199.9991844,0,0,0,90.00000001 +309,50.30085681,-2.790085575,10500,0,199.9998535,0,0,0,90.00000001 +309.01,50.30085681,-2.79005755,10500,0,200.0009685,0,0,0,90.00000001 +309.02,50.30085681,-2.790029524,10500,0,200.0009685,0,0,0,90.00000001 +309.03,50.30085681,-2.790001499,10500,0,199.9998535,0,0,0,90.00000001 +309.04,50.30085681,-2.789973474,10500,0,199.9991844,0,0,0,90.00000001 +309.05,50.30085681,-2.789945449,10500,0,199.9998535,0,0,0,90.00000001 +309.06,50.30085681,-2.789917424,10500,0,200.0009685,0,0,0,90.00000001 +309.07,50.30085681,-2.789889398,10500,0,200.0009685,0,0,0,90.00000001 +309.08,50.30085681,-2.789861373,10500,0,199.9998535,0,0,0,90.00000001 +309.09,50.30085681,-2.789833348,10500,0,199.9991844,0,0,0,90.00000001 +309.1,50.30085681,-2.789805323,10500,0,199.9998535,0,0,0,90.00000001 +309.11,50.30085681,-2.789777298,10500,0,200.0009685,0,0,0,90.00000001 +309.12,50.30085681,-2.789749272,10500,0,200.0009685,0,0,0,90.00000001 +309.13,50.30085681,-2.789721247,10500,0,199.9998535,0,0,0,90.00000001 +309.14,50.30085681,-2.789693222,10500,0,199.9991844,0,0,0,90.00000001 +309.15,50.30085681,-2.789665197,10500,0,199.9998535,0,0,0,90.00000001 +309.16,50.30085681,-2.789637172,10500,0,200.0009685,0,0,0,90.00000001 +309.17,50.30085681,-2.789609146,10500,0,200.0009685,0,0,0,90.00000001 +309.18,50.30085681,-2.789581121,10500,0,199.9998535,0,0,0,90.00000001 +309.19,50.30085681,-2.789553096,10500,0,199.9991844,0,0,0,90.00000001 +309.2,50.30085681,-2.789525071,10500,0,199.9998535,0,0,0,90.00000001 +309.21,50.30085681,-2.789497046,10500,0,200.0009685,0,0,0,90.00000001 +309.22,50.30085681,-2.78946902,10500,0,200.0009685,0,0,0,90.00000001 +309.23,50.30085681,-2.789440995,10500,0,199.9998535,0,0,0,90.00000001 +309.24,50.30085681,-2.78941297,10500,0,199.9989614,0,0,0,90.00000001 +309.25,50.30085681,-2.789384945,10500,0,199.9989614,0,0,0,90.00000001 +309.26,50.30085681,-2.78935692,10500,0,199.9998535,0,0,0,90.00000001 +309.27,50.30085681,-2.789328895,10500,0,200.0009685,0,0,0,90.00000001 +309.28,50.30085681,-2.789300869,10500,0,200.0009685,0,0,0,90.00000001 +309.29,50.30085681,-2.789272844,10500,0,199.9998535,0,0,0,90.00000001 +309.3,50.30085681,-2.789244819,10500,0,199.9989614,0,0,0,90.00000001 +309.31,50.30085681,-2.789216794,10500,0,199.9987384,0,0,0,90.00000001 +309.32,50.30085681,-2.789188769,10500,0,199.9989614,0,0,0,90.00000001 +309.33,50.30085681,-2.789160744,10500,0,199.9998535,0,0,0,90.00000001 +309.34,50.30085681,-2.789132719,10500,0,200.0009685,0,0,0,90.00000001 +309.35,50.30085681,-2.789104693,10500,0,200.0009685,0,0,0,90.00000001 +309.36,50.30085681,-2.789076668,10500,0,199.9998535,0,0,0,90.00000001 +309.37,50.30085681,-2.789048643,10500,0,199.9989614,0,0,0,90.00000001 +309.38,50.30085681,-2.789020618,10500,0,199.9989614,0,0,0,90.00000001 +309.39,50.30085681,-2.788992593,10500,0,199.9998535,0,0,0,90.00000001 +309.4,50.30085681,-2.788964568,10500,0,200.0009685,0,0,0,90.00000001 +309.41,50.30085681,-2.788936542,10500,0,200.0009685,0,0,0,90.00000001 +309.42,50.30085681,-2.788908517,10500,0,199.9998535,0,0,0,90.00000001 +309.43,50.30085681,-2.788880492,10500,0,199.9989614,0,0,0,90.00000001 +309.44,50.30085681,-2.788852467,10500,0,199.9989614,0,0,0,90.00000001 +309.45,50.30085681,-2.788824442,10500,0,199.9998535,0,0,0,90.00000001 +309.46,50.30085681,-2.788796417,10500,0,200.0009685,0,0,0,90.00000001 +309.47,50.30085681,-2.788768391,10500,0,200.0009685,0,0,0,90.00000001 +309.48,50.30085681,-2.788740366,10500,0,199.9998535,0,0,0,90.00000001 +309.49,50.30085681,-2.788712341,10500,0,199.9989614,0,0,0,90.00000001 +309.5,50.30085681,-2.788684316,10500,0,199.9989614,0,0,0,90.00000001 +309.51,50.30085681,-2.788656291,10500,0,199.9998535,0,0,0,90.00000001 +309.52,50.30085681,-2.788628266,10500,0,200.0009685,0,0,0,90.00000001 +309.53,50.30085681,-2.78860024,10500,0,200.0009685,0,0,0,90.00000001 +309.54,50.30085681,-2.788572215,10500,0,199.9998535,0,0,0,90.00000001 +309.55,50.30085681,-2.78854419,10500,0,199.9989614,0,0,0,90.00000001 +309.56,50.30085681,-2.788516165,10500,0,199.9989614,0,0,0,90.00000001 +309.57,50.30085681,-2.78848814,10500,0,199.9998535,0,0,0,90.00000001 +309.58,50.30085681,-2.788460115,10500,0,200.0009685,0,0,0,90.00000001 +309.59,50.30085681,-2.788432089,10500,0,200.0009685,0,0,0,90.00000001 +309.6,50.30085681,-2.788404064,10500,0,199.9998535,0,0,0,90.00000001 +309.61,50.30085681,-2.788376039,10500,0,199.9989614,0,0,0,90.00000001 +309.62,50.30085681,-2.788348014,10500,0,199.9989614,0,0,0,90.00000001 +309.63,50.30085681,-2.788319989,10500,0,199.9998535,0,0,0,90.00000001 +309.64,50.30085681,-2.788291964,10500,0,200.0009685,0,0,0,90.00000001 +309.65,50.30085681,-2.788263938,10500,0,200.0009685,0,0,0,90.00000001 +309.66,50.30085681,-2.788235913,10500,0,199.9998535,0,0,0,90.00000001 +309.67,50.30085681,-2.788207888,10500,0,199.9991844,0,0,0,90.00000001 +309.68,50.30085681,-2.788179863,10500,0,199.9998535,0,0,0,90.00000001 +309.69,50.30085681,-2.788151838,10500,0,200.0009685,0,0,0,90.00000001 +309.7,50.30085681,-2.788123812,10500,0,200.0009685,0,0,0,90.00000001 +309.71,50.30085681,-2.788095787,10500,0,199.9998535,0,0,0,90.00000001 +309.72,50.30085681,-2.788067762,10500,0,199.9991844,0,0,0,90.00000001 +309.73,50.30085681,-2.788039737,10500,0,199.9998535,0,0,0,90.00000001 +309.74,50.30085681,-2.788011712,10500,0,200.0009685,0,0,0,90.00000001 +309.75,50.30085681,-2.787983686,10500,0,200.0009685,0,0,0,90.00000001 +309.76,50.30085681,-2.787955661,10500,0,199.9998535,0,0,0,90.00000001 +309.77,50.30085681,-2.787927636,10500,0,199.9991844,0,0,0,90.00000001 +309.78,50.30085681,-2.787899611,10500,0,199.9998535,0,0,0,90.00000001 +309.79,50.30085681,-2.787871586,10500,0,200.0009685,0,0,0,90.00000001 +309.8,50.30085681,-2.78784356,10500,0,200.0009685,0,0,0,90.00000001 +309.81,50.30085681,-2.787815535,10500,0,199.9998535,0,0,0,90.00000001 +309.82,50.30085681,-2.78778751,10500,0,199.9991844,0,0,0,90.00000001 +309.83,50.30085681,-2.787759485,10500,0,199.9998535,0,0,0,90.00000001 +309.84,50.30085681,-2.78773146,10500,0,200.0009685,0,0,0,90.00000001 +309.85,50.30085681,-2.787703434,10500,0,200.0009685,0,0,0,90.00000001 +309.86,50.30085681,-2.787675409,10500,0,199.9998535,0,0,0,90.00000001 +309.87,50.30085681,-2.787647384,10500,0,199.9989614,0,0,0,90.00000001 +309.88,50.30085681,-2.787619359,10500,0,199.9989614,0,0,0,90.00000001 +309.89,50.30085681,-2.787591334,10500,0,199.9998535,0,0,0,90.00000001 +309.9,50.30085681,-2.787563309,10500,0,200.0009685,0,0,0,90.00000001 +309.91,50.30085681,-2.787535283,10500,0,200.0009685,0,0,0,90.00000001 +309.92,50.30085681,-2.787507258,10500,0,199.9998535,0,0,0,90.00000001 +309.93,50.30085681,-2.787479233,10500,0,199.9989614,0,0,0,90.00000001 +309.94,50.30085681,-2.787451208,10500,0,199.9989614,0,0,0,90.00000001 +309.95,50.30085681,-2.787423183,10500,0,199.9998535,0,0,0,90.00000001 +309.96,50.30085681,-2.787395158,10500,0,200.0009685,0,0,0,90.00000001 +309.97,50.30085681,-2.787367132,10500,0,200.0009685,0,0,0,90.00000001 +309.98,50.30085681,-2.787339107,10500,0,199.9998535,0,0,0,90.00000001 +309.99,50.30085681,-2.787311082,10500,0,199.9989614,0,0,0,90.00000001 +310,50.30085681,-2.787283057,10500,0,199.9989614,0,0,0,90.00000001 +310.01,50.30085681,-2.787255032,10500,0,199.9998535,0,0,0,90.00000001 +310.02,50.30085681,-2.787227007,10500,0,200.0009685,0,0,0,90.00000001 +310.03,50.30085681,-2.787198981,10500,0,200.0009685,0,0,0,90.00000001 +310.04,50.30085681,-2.787170956,10500,0,199.9998535,0,0,0,90.00000001 +310.05,50.30085681,-2.787142931,10500,0,199.9989614,0,0,0,90.00000001 +310.06,50.30085681,-2.787114906,10500,0,199.9989614,0,0,0,90.00000001 +310.07,50.30085681,-2.787086881,10500,0,199.9998535,0,0,0,90.00000001 +310.08,50.30085681,-2.787058856,10500,0,200.0009685,0,0,0,90.00000001 +310.09,50.30085681,-2.78703083,10500,0,200.0009685,0,0,0,90.00000001 +310.1,50.30085681,-2.787002805,10500,0,199.9998535,0,0,0,90.00000001 +310.11,50.30085681,-2.78697478,10500,0,199.9989614,0,0,0,90.00000001 +310.12,50.30085681,-2.786946755,10500,0,199.9987384,0,0,0,90.00000001 +310.13,50.30085681,-2.78691873,10500,0,199.9989614,0,0,0,90.00000001 +310.14,50.30085681,-2.786890705,10500,0,199.9998535,0,0,0,90.00000001 +310.15,50.30085681,-2.78686268,10500,0,200.0009685,0,0,0,90.00000001 +310.16,50.30085681,-2.786834654,10500,0,200.0009685,0,0,0,90.00000001 +310.17,50.30085681,-2.786806629,10500,0,199.9998535,0,0,0,90.00000001 +310.18,50.30085681,-2.786778604,10500,0,199.9989614,0,0,0,90.00000001 +310.19,50.30085681,-2.786750579,10500,0,199.9989614,0,0,0,90.00000001 +310.2,50.30085681,-2.786722554,10500,0,199.9998535,0,0,0,90.00000001 +310.21,50.30085681,-2.786694529,10500,0,200.0009685,0,0,0,90.00000001 +310.22,50.30085681,-2.786666503,10500,0,200.0009685,0,0,0,90.00000001 +310.23,50.30085681,-2.786638478,10500,0,199.9998535,0,0,0,90.00000001 +310.24,50.30085681,-2.786610453,10500,0,199.9991844,0,0,0,90.00000001 +310.25,50.30085681,-2.786582428,10500,0,199.9998535,0,0,0,90.00000001 +310.26,50.30085681,-2.786554403,10500,0,200.0009685,0,0,0,90.00000001 +310.27,50.30085681,-2.786526377,10500,0,200.0009685,0,0,0,90.00000001 +310.28,50.30085681,-2.786498352,10500,0,199.9998535,0,0,0,90.00000001 +310.29,50.30085681,-2.786470327,10500,0,199.9991844,0,0,0,90.00000001 +310.3,50.30085681,-2.786442302,10500,0,199.9998535,0,0,0,90.00000001 +310.31,50.30085681,-2.786414277,10500,0,200.0009685,0,0,0,90.00000001 +310.32,50.30085681,-2.786386251,10500,0,200.0009685,0,0,0,90.00000001 +310.33,50.30085681,-2.786358226,10500,0,199.9998535,0,0,0,90.00000001 +310.34,50.30085681,-2.786330201,10500,0,199.9991844,0,0,0,90.00000001 +310.35,50.30085681,-2.786302176,10500,0,199.9998535,0,0,0,90.00000001 +310.36,50.30085681,-2.786274151,10500,0,200.0009685,0,0,0,90.00000001 +310.37,50.30085681,-2.786246125,10500,0,200.0009685,0,0,0,90.00000001 +310.38,50.30085681,-2.7862181,10500,0,199.9998535,0,0,0,90.00000001 +310.39,50.30085681,-2.786190075,10500,0,199.9991844,0,0,0,90.00000001 +310.4,50.30085681,-2.78616205,10500,0,199.9998535,0,0,0,90.00000001 +310.41,50.30085681,-2.786134025,10500,0,200.0009685,0,0,0,90.00000001 +310.42,50.30085681,-2.786105999,10500,0,200.0009685,0,0,0,90.00000001 +310.43,50.30085681,-2.786077974,10500,0,199.9998535,0,0,0,90.00000001 +310.44,50.30085681,-2.786049949,10500,0,199.9991844,0,0,0,90.00000001 +310.45,50.30085681,-2.786021924,10500,0,199.9998535,0,0,0,90.00000001 +310.46,50.30085681,-2.785993899,10500,0,200.0009685,0,0,0,90.00000001 +310.47,50.30085681,-2.785965873,10500,0,200.0009685,0,0,0,90.00000001 +310.48,50.30085681,-2.785937848,10500,0,199.9998535,0,0,0,90.00000001 +310.49,50.30085681,-2.785909823,10500,0,199.9989614,0,0,0,90.00000001 +310.5,50.30085681,-2.785881798,10500,0,199.9989614,0,0,0,90.00000001 +310.51,50.30085681,-2.785853773,10500,0,199.9998535,0,0,0,90.00000001 +310.52,50.30085681,-2.785825748,10500,0,200.0009685,0,0,0,90.00000001 +310.53,50.30085681,-2.785797722,10500,0,200.0009685,0,0,0,90.00000001 +310.54,50.30085681,-2.785769697,10500,0,199.9998535,0,0,0,90.00000001 +310.55,50.30085681,-2.785741672,10500,0,199.9989614,0,0,0,90.00000001 +310.56,50.30085681,-2.785713647,10500,0,199.9989614,0,0,0,90.00000001 +310.57,50.30085681,-2.785685622,10500,0,199.9998535,0,0,0,90.00000001 +310.58,50.30085681,-2.785657597,10500,0,200.0009685,0,0,0,90.00000001 +310.59,50.30085681,-2.785629571,10500,0,200.0009685,0,0,0,90.00000001 +310.6,50.30085681,-2.785601546,10500,0,199.9998535,0,0,0,90.00000001 +310.61,50.30085681,-2.785573521,10500,0,199.9989614,0,0,0,90.00000001 +310.62,50.30085681,-2.785545496,10500,0,199.9989614,0,0,0,90.00000001 +310.63,50.30085681,-2.785517471,10500,0,199.9998535,0,0,0,90.00000001 +310.64,50.30085681,-2.785489446,10500,0,200.0009685,0,0,0,90.00000001 +310.65,50.30085681,-2.78546142,10500,0,200.0009685,0,0,0,90.00000001 +310.66,50.30085681,-2.785433395,10500,0,199.9998535,0,0,0,90.00000001 +310.67,50.30085681,-2.78540537,10500,0,199.9989614,0,0,0,90.00000001 +310.68,50.30085681,-2.785377345,10500,0,199.9989614,0,0,0,90.00000001 +310.69,50.30085681,-2.78534932,10500,0,199.9998535,0,0,0,90.00000001 +310.7,50.30085681,-2.785321295,10500,0,200.0009685,0,0,0,90.00000001 +310.71,50.30085681,-2.785293269,10500,0,200.0009685,0,0,0,90.00000001 +310.72,50.30085681,-2.785265244,10500,0,199.9998535,0,0,0,90.00000001 +310.73,50.30085681,-2.785237219,10500,0,199.9989614,0,0,0,90.00000001 +310.74,50.30085681,-2.785209194,10500,0,199.9987384,0,0,0,90.00000001 +310.75,50.30085681,-2.785181169,10500,0,199.9989614,0,0,0,90.00000001 +310.76,50.30085681,-2.785153144,10500,0,199.9998535,0,0,0,90.00000001 +310.77,50.30085681,-2.785125119,10500,0,200.0009685,0,0,0,90.00000001 +310.78,50.30085681,-2.785097093,10500,0,200.0009685,0,0,0,90.00000001 +310.79,50.30085681,-2.785069068,10500,0,199.9998535,0,0,0,90.00000001 +310.8,50.30085681,-2.785041043,10500,0,199.9989614,0,0,0,90.00000001 +310.81,50.30085681,-2.785013018,10500,0,199.9989614,0,0,0,90.00000001 +310.82,50.30085681,-2.784984993,10500,0,199.9998535,0,0,0,90.00000001 +310.83,50.30085681,-2.784956968,10500,0,200.0009685,0,0,0,90.00000001 +310.84,50.30085681,-2.784928942,10500,0,200.0009685,0,0,0,90.00000001 +310.85,50.30085681,-2.784900917,10500,0,199.9998535,0,0,0,90.00000001 +310.86,50.30085681,-2.784872892,10500,0,199.9991844,0,0,0,90.00000001 +310.87,50.30085681,-2.784844867,10500,0,199.9998535,0,0,0,90.00000001 +310.88,50.30085681,-2.784816842,10500,0,200.0009685,0,0,0,90.00000001 +310.89,50.30085681,-2.784788816,10500,0,200.0009685,0,0,0,90.00000001 +310.9,50.30085681,-2.784760791,10500,0,199.9998535,0,0,0,90.00000001 +310.91,50.30085681,-2.784732766,10500,0,199.9991844,0,0,0,90.00000001 +310.92,50.30085681,-2.784704741,10500,0,199.9998535,0,0,0,90.00000001 +310.93,50.30085681,-2.784676716,10500,0,200.0009685,0,0,0,90.00000001 +310.94,50.30085681,-2.78464869,10500,0,200.0009685,0,0,0,90.00000001 +310.95,50.30085681,-2.784620665,10500,0,199.9998535,0,0,0,90.00000001 +310.96,50.30085681,-2.78459264,10500,0,199.9991844,0,0,0,90.00000001 +310.97,50.30085681,-2.784564615,10500,0,199.9998535,0,0,0,90.00000001 +310.98,50.30085681,-2.78453659,10500,0,200.0009685,0,0,0,90.00000001 +310.99,50.30085681,-2.784508564,10500,0,200.0009685,0,0,0,90.00000001 +311,50.30085681,-2.784480539,10500,0,199.9998535,0,0,0,90.00000001 +311.01,50.30085681,-2.784452514,10500,0,199.9991844,0,0,0,90.00000001 +311.02,50.30085681,-2.784424489,10500,0,199.9998535,0,0,0,90.00000001 +311.03,50.30085681,-2.784396464,10500,0,200.0009685,0,0,0,90.00000001 +311.04,50.30085681,-2.784368438,10500,0,200.0009685,0,0,0,90.00000001 +311.05,50.30085681,-2.784340413,10500,0,199.9998535,0,0,0,90.00000001 +311.06,50.30085681,-2.784312388,10500,0,199.9991844,0,0,0,90.00000001 +311.07,50.30085681,-2.784284363,10500,0,199.9998535,0,0,0,90.00000001 +311.08,50.30085681,-2.784256338,10500,0,200.0009685,0,0,0,90.00000001 +311.09,50.30085681,-2.784228312,10500,0,200.0009685,0,0,0,90.00000001 +311.1,50.30085681,-2.784200287,10500,0,199.9998535,0,0,0,90.00000001 +311.11,50.30085681,-2.784172262,10500,0,199.9989614,0,0,0,90.00000001 +311.12,50.30085681,-2.784144237,10500,0,199.9989614,0,0,0,90.00000001 +311.13,50.30085681,-2.784116212,10500,0,199.9998535,0,0,0,90.00000001 +311.14,50.30085681,-2.784088187,10500,0,200.0009685,0,0,0,90.00000001 +311.15,50.30085681,-2.784060161,10500,0,200.0009685,0,0,0,90.00000001 +311.16,50.30085681,-2.784032136,10500,0,199.9998535,0,0,0,90.00000001 +311.17,50.30085681,-2.784004111,10500,0,199.9989614,0,0,0,90.00000001 +311.18,50.30085681,-2.783976086,10500,0,199.9989614,0,0,0,90.00000001 +311.19,50.30085681,-2.783948061,10500,0,199.9998535,0,0,0,90.00000001 +311.2,50.30085681,-2.783920036,10500,0,200.0009685,0,0,0,90.00000001 +311.21,50.30085681,-2.78389201,10500,0,200.0009685,0,0,0,90.00000001 +311.22,50.30085681,-2.783863985,10500,0,199.9998535,0,0,0,90.00000001 +311.23,50.30085681,-2.78383596,10500,0,199.9989614,0,0,0,90.00000001 +311.24,50.30085681,-2.783807935,10500,0,199.9989614,0,0,0,90.00000001 +311.25,50.30085681,-2.78377991,10500,0,199.9998535,0,0,0,90.00000001 +311.26,50.30085681,-2.783751885,10500,0,200.0009685,0,0,0,90.00000001 +311.27,50.30085681,-2.783723859,10500,0,200.0009685,0,0,0,90.00000001 +311.28,50.30085681,-2.783695834,10500,0,199.9998535,0,0,0,90.00000001 +311.29,50.30085681,-2.783667809,10500,0,199.9989614,0,0,0,90.00000001 +311.3,50.30085681,-2.783639784,10500,0,199.9987384,0,0,0,90.00000001 +311.31,50.30085681,-2.783611759,10500,0,199.9989614,0,0,0,90.00000001 +311.32,50.30085681,-2.783583734,10500,0,199.9998535,0,0,0,90.00000001 +311.33,50.30085681,-2.783555709,10500,0,200.0009685,0,0,0,90.00000001 +311.34,50.30085681,-2.783527683,10500,0,200.0009685,0,0,0,90.00000001 +311.35,50.30085681,-2.783499658,10500,0,199.9998535,0,0,0,90.00000001 +311.36,50.30085681,-2.783471633,10500,0,199.9989614,0,0,0,90.00000001 +311.37,50.30085681,-2.783443608,10500,0,199.9989614,0,0,0,90.00000001 +311.38,50.30085681,-2.783415583,10500,0,199.9998535,0,0,0,90.00000001 +311.39,50.30085681,-2.783387558,10500,0,200.0009685,0,0,0,90.00000001 +311.4,50.30085681,-2.783359532,10500,0,200.0009685,0,0,0,90.00000001 +311.41,50.30085681,-2.783331507,10500,0,199.9998535,0,0,0,90.00000001 +311.42,50.30085681,-2.783303482,10500,0,199.9989614,0,0,0,90.00000001 +311.43,50.30085681,-2.783275457,10500,0,199.9989614,0,0,0,90.00000001 +311.44,50.30085681,-2.783247432,10500,0,199.9998535,0,0,0,90.00000001 +311.45,50.30085681,-2.783219407,10500,0,200.0009685,0,0,0,90.00000001 +311.46,50.30085681,-2.783191381,10500,0,200.0009685,0,0,0,90.00000001 +311.47,50.30085681,-2.783163356,10500,0,199.9998535,0,0,0,90.00000001 +311.48,50.30085681,-2.783135331,10500,0,199.9991844,0,0,0,90.00000001 +311.49,50.30085681,-2.783107306,10500,0,199.9998535,0,0,0,90.00000001 +311.5,50.30085681,-2.783079281,10500,0,200.0009685,0,0,0,90.00000001 +311.51,50.30085681,-2.783051255,10500,0,200.0009685,0,0,0,90.00000001 +311.52,50.30085681,-2.78302323,10500,0,199.9998535,0,0,0,90.00000001 +311.53,50.30085681,-2.782995205,10500,0,199.9991844,0,0,0,90.00000001 +311.54,50.30085681,-2.78296718,10500,0,199.9998535,0,0,0,90.00000001 +311.55,50.30085681,-2.782939155,10500,0,200.0009685,0,0,0,90.00000001 +311.56,50.30085681,-2.782911129,10500,0,200.0009685,0,0,0,90.00000001 +311.57,50.30085681,-2.782883104,10500,0,199.9998535,0,0,0,90.00000001 +311.58,50.30085681,-2.782855079,10500,0,199.9991844,0,0,0,90.00000001 +311.59,50.30085681,-2.782827054,10500,0,199.9998535,0,0,0,90.00000001 +311.6,50.30085681,-2.782799029,10500,0,200.0009685,0,0,0,90.00000001 +311.61,50.30085681,-2.782771003,10500,0,200.0009685,0,0,0,90.00000001 +311.62,50.30085681,-2.782742978,10500,0,199.9998535,0,0,0,90.00000001 +311.63,50.30085681,-2.782714953,10500,0,199.9991844,0,0,0,90.00000001 +311.64,50.30085681,-2.782686928,10500,0,199.9998535,0,0,0,90.00000001 +311.65,50.30085681,-2.782658903,10500,0,200.0009685,0,0,0,90.00000001 +311.66,50.30085681,-2.782630877,10500,0,200.0009685,0,0,0,90.00000001 +311.67,50.30085681,-2.782602852,10500,0,199.9998535,0,0,0,90.00000001 +311.68,50.30085681,-2.782574827,10500,0,199.9989614,0,0,0,90.00000001 +311.69,50.30085681,-2.782546802,10500,0,199.9989614,0,0,0,90.00000001 +311.7,50.30085681,-2.782518777,10500,0,199.9998535,0,0,0,90.00000001 +311.71,50.30085681,-2.782490752,10500,0,200.0009685,0,0,0,90.00000001 +311.72,50.30085681,-2.782462726,10500,0,200.0009685,0,0,0,90.00000001 +311.73,50.30085681,-2.782434701,10500,0,199.9998535,0,0,0,90.00000001 +311.74,50.30085681,-2.782406676,10500,0,199.9991844,0,0,0,90.00000001 +311.75,50.30085681,-2.782378651,10500,0,199.9998535,0,0,0,90.00000001 +311.76,50.30085681,-2.782350626,10500,0,200.0009685,0,0,0,90.00000001 +311.77,50.30085681,-2.7823226,10500,0,200.0009685,0,0,0,90.00000001 +311.78,50.30085681,-2.782294575,10500,0,199.9998535,0,0,0,90.00000001 +311.79,50.30085681,-2.78226655,10500,0,199.9989614,0,0,0,90.00000001 +311.8,50.30085681,-2.782238525,10500,0,199.9989614,0,0,0,90.00000001 +311.81,50.30085681,-2.7822105,10500,0,199.9998535,0,0,0,90.00000001 +311.82,50.30085681,-2.782182475,10500,0,200.0009685,0,0,0,90.00000001 +311.83,50.30085681,-2.782154449,10500,0,200.0009685,0,0,0,90.00000001 +311.84,50.30085681,-2.782126424,10500,0,199.9998535,0,0,0,90.00000001 +311.85,50.30085681,-2.782098399,10500,0,199.9989614,0,0,0,90.00000001 +311.86,50.30085681,-2.782070374,10500,0,199.9987384,0,0,0,90.00000001 +311.87,50.30085681,-2.782042349,10500,0,199.9989614,0,0,0,90.00000001 +311.88,50.30085681,-2.782014324,10500,0,199.9998535,0,0,0,90.00000001 +311.89,50.30085681,-2.781986299,10500,0,200.0009685,0,0,0,90.00000001 +311.9,50.30085681,-2.781958273,10500,0,200.0009685,0,0,0,90.00000001 +311.91,50.30085681,-2.781930248,10500,0,199.9998535,0,0,0,90.00000001 +311.92,50.30085681,-2.781902223,10500,0,199.9989614,0,0,0,90.00000001 +311.93,50.30085681,-2.781874198,10500,0,199.9989614,0,0,0,90.00000001 +311.94,50.30085681,-2.781846173,10500,0,199.9998535,0,0,0,90.00000001 +311.95,50.30085681,-2.781818148,10500,0,200.0009685,0,0,0,90.00000001 +311.96,50.30085681,-2.781790122,10500,0,200.0009685,0,0,0,90.00000001 +311.97,50.30085681,-2.781762097,10500,0,199.9998535,0,0,0,90.00000001 +311.98,50.30085681,-2.781734072,10500,0,199.9989614,0,0,0,90.00000001 +311.99,50.30085681,-2.781706047,10500,0,199.9989614,0,0,0,90.00000001 +312,50.30085681,-2.781678022,10500,0,199.9998535,0,0,0,90.00000001 +312.01,50.30085681,-2.781649997,10500,0,200.0009685,0,0,0,90.00000001 +312.02,50.30085681,-2.781621971,10500,0,200.0009685,0,0,0,90.00000001 +312.03,50.30085681,-2.781593946,10500,0,199.9998535,0,0,0,90.00000001 +312.04,50.30085681,-2.781565921,10500,0,199.9989614,0,0,0,90.00000001 +312.05,50.30085681,-2.781537896,10500,0,199.9989614,0,0,0,90.00000001 +312.06,50.30085681,-2.781509871,10500,0,199.9998535,0,0,0,90.00000001 +312.07,50.30085681,-2.781481846,10500,0,200.0009685,0,0,0,90.00000001 +312.08,50.30085681,-2.78145382,10500,0,200.0009685,0,0,0,90.00000001 +312.09,50.30085681,-2.781425795,10500,0,199.9998535,0,0,0,90.00000001 +312.1,50.30085681,-2.78139777,10500,0,199.9989614,0,0,0,90.00000001 +312.11,50.30085681,-2.781369745,10500,0,199.9989614,0,0,0,90.00000001 +312.12,50.30085681,-2.78134172,10500,0,199.9998535,0,0,0,90.00000001 +312.13,50.30085681,-2.781313695,10500,0,200.0009685,0,0,0,90.00000001 +312.14,50.30085681,-2.781285669,10500,0,200.0009685,0,0,0,90.00000001 +312.15,50.30085681,-2.781257644,10500,0,199.9998535,0,0,0,90.00000001 +312.16,50.30085681,-2.781229619,10500,0,199.9991844,0,0,0,90.00000001 +312.17,50.30085681,-2.781201594,10500,0,199.9998535,0,0,0,90.00000001 +312.18,50.30085681,-2.781173569,10500,0,200.0009685,0,0,0,90.00000001 +312.19,50.30085681,-2.781145543,10500,0,200.0009685,0,0,0,90.00000001 +312.2,50.30085681,-2.781117518,10500,0,199.9998535,0,0,0,90.00000001 +312.21,50.30085681,-2.781089493,10500,0,199.9991844,0,0,0,90.00000001 +312.22,50.30085681,-2.781061468,10500,0,199.9998535,0,0,0,90.00000001 +312.23,50.30085681,-2.781033443,10500,0,200.0009685,0,0,0,90.00000001 +312.24,50.30085681,-2.781005417,10500,0,200.0009685,0,0,0,90.00000001 +312.25,50.30085681,-2.780977392,10500,0,199.9998535,0,0,0,90.00000001 +312.26,50.30085681,-2.780949367,10500,0,199.9991844,0,0,0,90.00000001 +312.27,50.30085681,-2.780921342,10500,0,199.9998535,0,0,0,90.00000001 +312.28,50.30085681,-2.780893317,10500,0,200.0009685,0,0,0,90.00000001 +312.29,50.30085681,-2.780865291,10500,0,200.0009685,0,0,0,90.00000001 +312.3,50.30085681,-2.780837266,10500,0,199.9998535,0,0,0,90.00000001 +312.31,50.30085681,-2.780809241,10500,0,199.9991844,0,0,0,90.00000001 +312.32,50.30085681,-2.780781216,10500,0,199.9998535,0,0,0,90.00000001 +312.33,50.30085681,-2.780753191,10500,0,200.0009685,0,0,0,90.00000001 +312.34,50.30085681,-2.780725165,10500,0,200.0009685,0,0,0,90.00000001 +312.35,50.30085681,-2.78069714,10500,0,199.9998535,0,0,0,90.00000001 +312.36,50.30085681,-2.780669115,10500,0,199.9991844,0,0,0,90.00000001 +312.37,50.30085681,-2.78064109,10500,0,199.9998535,0,0,0,90.00000001 +312.38,50.30085681,-2.780613065,10500,0,200.0009685,0,0,0,90.00000001 +312.39,50.30085681,-2.780585039,10500,0,200.0009685,0,0,0,90.00000001 +312.4,50.30085681,-2.780557014,10500,0,199.9998535,0,0,0,90.00000001 +312.41,50.30085681,-2.780528989,10500,0,199.9989614,0,0,0,90.00000001 +312.42,50.30085681,-2.780500964,10500,0,199.9987384,0,0,0,90.00000001 +312.43,50.30085681,-2.780472939,10500,0,199.9989614,0,0,0,90.00000001 +312.44,50.30085681,-2.780444914,10500,0,199.9998535,0,0,0,90.00000001 +312.45,50.30085681,-2.780416889,10500,0,200.0009685,0,0,0,90.00000001 +312.46,50.30085681,-2.780388863,10500,0,200.0009685,0,0,0,90.00000001 +312.47,50.30085681,-2.780360838,10500,0,199.9998535,0,0,0,90.00000001 +312.48,50.30085681,-2.780332813,10500,0,199.9989614,0,0,0,90.00000001 +312.49,50.30085681,-2.780304788,10500,0,199.9989614,0,0,0,90.00000001 +312.5,50.30085681,-2.780276763,10500,0,199.9998535,0,0,0,90.00000001 +312.51,50.30085681,-2.780248738,10500,0,200.0009685,0,0,0,90.00000001 +312.52,50.30085681,-2.780220712,10500,0,200.0009685,0,0,0,90.00000001 +312.53,50.30085681,-2.780192687,10500,0,199.9998535,0,0,0,90.00000001 +312.54,50.30085681,-2.780164662,10500,0,199.9989614,0,0,0,90.00000001 +312.55,50.30085681,-2.780136637,10500,0,199.9989614,0,0,0,90.00000001 +312.56,50.30085681,-2.780108612,10500,0,199.9998535,0,0,0,90.00000001 +312.57,50.30085681,-2.780080587,10500,0,200.0009685,0,0,0,90.00000001 +312.58,50.30085681,-2.780052561,10500,0,200.0009685,0,0,0,90.00000001 +312.59,50.30085681,-2.780024536,10500,0,199.9998535,0,0,0,90.00000001 +312.6,50.30085681,-2.779996511,10500,0,199.9989614,0,0,0,90.00000001 +312.61,50.30085681,-2.779968486,10500,0,199.9989614,0,0,0,90.00000001 +312.62,50.30085681,-2.779940461,10500,0,199.9998535,0,0,0,90.00000001 +312.63,50.30085681,-2.779912436,10500,0,200.0009685,0,0,0,90.00000001 +312.64,50.30085681,-2.77988441,10500,0,200.0009685,0,0,0,90.00000001 +312.65,50.30085681,-2.779856385,10500,0,199.9998535,0,0,0,90.00000001 +312.66,50.30085681,-2.77982836,10500,0,199.9989614,0,0,0,90.00000001 +312.67,50.30085681,-2.779800335,10500,0,199.9989614,0,0,0,90.00000001 +312.68,50.30085681,-2.77977231,10500,0,199.9998535,0,0,0,90.00000001 +312.69,50.30085681,-2.779744285,10500,0,200.0009685,0,0,0,90.00000001 +312.7,50.30085681,-2.779716259,10500,0,200.0009685,0,0,0,90.00000001 +312.71,50.30085681,-2.779688234,10500,0,199.9998535,0,0,0,90.00000001 +312.72,50.30085681,-2.779660209,10500,0,199.9989614,0,0,0,90.00000001 +312.73,50.30085681,-2.779632184,10500,0,199.9989614,0,0,0,90.00000001 +312.74,50.30085681,-2.779604159,10500,0,199.9998535,0,0,0,90.00000001 +312.75,50.30085681,-2.779576134,10500,0,200.0009685,0,0,0,90.00000001 +312.76,50.30085681,-2.779548108,10500,0,200.0009685,0,0,0,90.00000001 +312.77,50.30085681,-2.779520083,10500,0,199.9998535,0,0,0,90.00000001 +312.78,50.30085681,-2.779492058,10500,0,199.9991844,0,0,0,90.00000001 +312.79,50.30085681,-2.779464033,10500,0,199.9998535,0,0,0,90.00000001 +312.8,50.30085681,-2.779436008,10500,0,200.0009685,0,0,0,90.00000001 +312.81,50.30085681,-2.779407982,10500,0,200.0009685,0,0,0,90.00000001 +312.82,50.30085681,-2.779379957,10500,0,199.9998535,0,0,0,90.00000001 +312.83,50.30085681,-2.779351932,10500,0,199.9991844,0,0,0,90.00000001 +312.84,50.30085681,-2.779323907,10500,0,199.9998535,0,0,0,90.00000001 +312.85,50.30085681,-2.779295882,10500,0,200.0009685,0,0,0,90.00000001 +312.86,50.30085681,-2.779267856,10500,0,200.0009685,0,0,0,90.00000001 +312.87,50.30085681,-2.779239831,10500,0,199.9998535,0,0,0,90.00000001 +312.88,50.30085681,-2.779211806,10500,0,199.9991844,0,0,0,90.00000001 +312.89,50.30085681,-2.779183781,10500,0,199.9998535,0,0,0,90.00000001 +312.9,50.30085681,-2.779155756,10500,0,200.0009685,0,0,0,90.00000001 +312.91,50.30085681,-2.77912773,10500,0,200.0009685,0,0,0,90.00000001 +312.92,50.30085681,-2.779099705,10500,0,199.9998535,0,0,0,90.00000001 +312.93,50.30085681,-2.77907168,10500,0,199.9991844,0,0,0,90.00000001 +312.94,50.30085681,-2.779043655,10500,0,199.9998535,0,0,0,90.00000001 +312.95,50.30085681,-2.77901563,10500,0,200.0009685,0,0,0,90.00000001 +312.96,50.30085681,-2.778987604,10500,0,200.0009685,0,0,0,90.00000001 +312.97,50.30085681,-2.778959579,10500,0,199.9998535,0,0,0,90.00000001 +312.98,50.30085681,-2.778931554,10500,0,199.9989614,0,0,0,90.00000001 +312.99,50.30085681,-2.778903529,10500,0,199.9989614,0,0,0,90.00000001 +313,50.30085681,-2.778875504,10500,0,199.9998535,0,0,0,90.00000001 +313.01,50.30085681,-2.778847479,10500,0,200.0009685,0,0,0,90.00000001 +313.02,50.30085681,-2.778819453,10500,0,200.0009685,0,0,0,90.00000001 +313.03,50.30085681,-2.778791428,10500,0,199.9998535,0,0,0,90.00000001 +313.04,50.30085681,-2.778763403,10500,0,199.9989614,0,0,0,90.00000001 +313.05,50.30085681,-2.778735378,10500,0,199.9989614,0,0,0,90.00000001 +313.06,50.30085681,-2.778707353,10500,0,199.9998535,0,0,0,90.00000001 +313.07,50.30085681,-2.778679328,10500,0,200.0009685,0,0,0,90.00000001 +313.08,50.30085681,-2.778651302,10500,0,200.0009685,0,0,0,90.00000001 +313.09,50.30085681,-2.778623277,10500,0,199.9998535,0,0,0,90.00000001 +313.1,50.30085681,-2.778595252,10500,0,199.9989614,0,0,0,90.00000001 +313.11,50.30085681,-2.778567227,10500,0,199.9989614,0,0,0,90.00000001 +313.12,50.30085681,-2.778539202,10500,0,199.9998535,0,0,0,90.00000001 +313.13,50.30085681,-2.778511177,10500,0,200.0009685,0,0,0,90.00000001 +313.14,50.30085681,-2.778483151,10500,0,200.0009685,0,0,0,90.00000001 +313.15,50.30085681,-2.778455126,10500,0,199.9998535,0,0,0,90.00000001 +313.16,50.30085681,-2.778427101,10500,0,199.9989614,0,0,0,90.00000001 +313.17,50.30085681,-2.778399076,10500,0,199.9989614,0,0,0,90.00000001 +313.18,50.30085681,-2.778371051,10500,0,199.9998535,0,0,0,90.00000001 +313.19,50.30085681,-2.778343026,10500,0,200.0009685,0,0,0,90.00000001 +313.2,50.30085681,-2.778315,10500,0,200.0009685,0,0,0,90.00000001 +313.21,50.30085681,-2.778286975,10500,0,199.9998535,0,0,0,90.00000001 +313.22,50.30085681,-2.77825895,10500,0,199.9989614,0,0,0,90.00000001 +313.23,50.30085681,-2.778230925,10500,0,199.9989614,0,0,0,90.00000001 +313.24,50.30085681,-2.7782029,10500,0,199.9998535,0,0,0,90.00000001 +313.25,50.30085681,-2.778174875,10500,0,200.0009685,0,0,0,90.00000001 +313.26,50.30085681,-2.778146849,10500,0,200.0009685,0,0,0,90.00000001 +313.27,50.30085681,-2.778118824,10500,0,199.9998535,0,0,0,90.00000001 +313.28,50.30085681,-2.778090799,10500,0,199.9989614,0,0,0,90.00000001 +313.29,50.30085681,-2.778062774,10500,0,199.9987384,0,0,0,90.00000001 +313.3,50.30085681,-2.778034749,10500,0,199.9989614,0,0,0,90.00000001 +313.31,50.30085681,-2.778006724,10500,0,199.9998535,0,0,0,90.00000001 +313.32,50.30085681,-2.777978699,10500,0,200.0009685,0,0,0,90.00000001 +313.33,50.30085681,-2.777950673,10500,0,200.0009685,0,0,0,90.00000001 +313.34,50.30085681,-2.777922648,10500,0,199.9998535,0,0,0,90.00000001 +313.35,50.30085681,-2.777894623,10500,0,199.9991844,0,0,0,90.00000001 +313.36,50.30085681,-2.777866598,10500,0,199.9998535,0,0,0,90.00000001 +313.37,50.30085681,-2.777838573,10500,0,200.0009685,0,0,0,90.00000001 +313.38,50.30085681,-2.777810547,10500,0,200.0009685,0,0,0,90.00000001 +313.39,50.30085681,-2.777782522,10500,0,199.9998535,0,0,0,90.00000001 +313.4,50.30085681,-2.777754497,10500,0,199.9991844,0,0,0,90.00000001 +313.41,50.30085681,-2.777726472,10500,0,199.9998535,0,0,0,90.00000001 +313.42,50.30085681,-2.777698447,10500,0,200.0009685,0,0,0,90.00000001 +313.43,50.30085681,-2.777670421,10500,0,200.0009685,0,0,0,90.00000001 +313.44,50.30085681,-2.777642396,10500,0,199.9998535,0,0,0,90.00000001 +313.45,50.30085681,-2.777614371,10500,0,199.9991844,0,0,0,90.00000001 +313.46,50.30085681,-2.777586346,10500,0,199.9998535,0,0,0,90.00000001 +313.47,50.30085681,-2.777558321,10500,0,200.0009685,0,0,0,90.00000001 +313.48,50.30085681,-2.777530295,10500,0,200.0009685,0,0,0,90.00000001 +313.49,50.30085681,-2.77750227,10500,0,199.9998535,0,0,0,90.00000001 +313.5,50.30085681,-2.777474245,10500,0,199.9991844,0,0,0,90.00000001 +313.51,50.30085681,-2.77744622,10500,0,199.9998535,0,0,0,90.00000001 +313.52,50.30085681,-2.777418195,10500,0,200.0009685,0,0,0,90.00000001 +313.53,50.30085681,-2.777390169,10500,0,200.0009685,0,0,0,90.00000001 +313.54,50.30085681,-2.777362144,10500,0,199.9998535,0,0,0,90.00000001 +313.55,50.30085681,-2.777334119,10500,0,199.9991844,0,0,0,90.00000001 +313.56,50.30085681,-2.777306094,10500,0,199.9998535,0,0,0,90.00000001 +313.57,50.30085681,-2.777278069,10500,0,200.0009685,0,0,0,90.00000001 +313.58,50.30085681,-2.777250043,10500,0,200.0009685,0,0,0,90.00000001 +313.59,50.30085681,-2.777222018,10500,0,199.9998535,0,0,0,90.00000001 +313.6,50.30085681,-2.777193993,10500,0,199.9989614,0,0,0,90.00000001 +313.61,50.30085681,-2.777165968,10500,0,199.9989614,0,0,0,90.00000001 +313.62,50.30085681,-2.777137943,10500,0,199.9998535,0,0,0,90.00000001 +313.63,50.30085681,-2.777109918,10500,0,200.0009685,0,0,0,90.00000001 +313.64,50.30085681,-2.777081892,10500,0,200.0009685,0,0,0,90.00000001 +313.65,50.30085681,-2.777053867,10500,0,199.9998535,0,0,0,90.00000001 +313.66,50.30085681,-2.777025842,10500,0,199.9989614,0,0,0,90.00000001 +313.67,50.30085681,-2.776997817,10500,0,199.9989614,0,0,0,90.00000001 +313.68,50.30085681,-2.776969792,10500,0,199.9998535,0,0,0,90.00000001 +313.69,50.30085681,-2.776941767,10500,0,200.0009685,0,0,0,90.00000001 +313.7,50.30085681,-2.776913741,10500,0,200.0009685,0,0,0,90.00000001 +313.71,50.30085681,-2.776885716,10500,0,199.9998535,0,0,0,90.00000001 +313.72,50.30085681,-2.776857691,10500,0,199.9989614,0,0,0,90.00000001 +313.73,50.30085681,-2.776829666,10500,0,199.9989614,0,0,0,90.00000001 +313.74,50.30085681,-2.776801641,10500,0,199.9998535,0,0,0,90.00000001 +313.75,50.30085681,-2.776773616,10500,0,200.0009685,0,0,0,90.00000001 +313.76,50.30085681,-2.77674559,10500,0,200.0009685,0,0,0,90.00000001 +313.77,50.30085681,-2.776717565,10500,0,199.9998535,0,0,0,90.00000001 +313.78,50.30085681,-2.77668954,10500,0,199.9989614,0,0,0,90.00000001 +313.79,50.30085681,-2.776661515,10500,0,199.9989614,0,0,0,90.00000001 +313.8,50.30085681,-2.77663349,10500,0,199.9998535,0,0,0,90.00000001 +313.81,50.30085681,-2.776605465,10500,0,200.0009685,0,0,0,90.00000001 +313.82,50.30085681,-2.776577439,10500,0,200.0009685,0,0,0,90.00000001 +313.83,50.30085681,-2.776549414,10500,0,199.9998535,0,0,0,90.00000001 +313.84,50.30085681,-2.776521389,10500,0,199.9989614,0,0,0,90.00000001 +313.85,50.30085681,-2.776493364,10500,0,199.9987384,0,0,0,90.00000001 +313.86,50.30085681,-2.776465339,10500,0,199.9989614,0,0,0,90.00000001 +313.87,50.30085681,-2.776437314,10500,0,199.9998535,0,0,0,90.00000001 +313.88,50.30085681,-2.776409289,10500,0,200.0009685,0,0,0,90.00000001 +313.89,50.30085681,-2.776381263,10500,0,200.0009685,0,0,0,90.00000001 +313.9,50.30085681,-2.776353238,10500,0,199.9998535,0,0,0,90.00000001 +313.91,50.30085681,-2.776325213,10500,0,199.9989614,0,0,0,90.00000001 +313.92,50.30085681,-2.776297188,10500,0,199.9989614,0,0,0,90.00000001 +313.93,50.30085681,-2.776269163,10500,0,199.9998535,0,0,0,90.00000001 +313.94,50.30085681,-2.776241138,10500,0,200.0009685,0,0,0,90.00000001 +313.95,50.30085681,-2.776213112,10500,0,200.0009685,0,0,0,90.00000001 +313.96,50.30085681,-2.776185087,10500,0,199.9998535,0,0,0,90.00000001 +313.97,50.30085681,-2.776157062,10500,0,199.9991844,0,0,0,90.00000001 +313.98,50.30085681,-2.776129037,10500,0,199.9998535,0,0,0,90.00000001 +313.99,50.30085681,-2.776101012,10500,0,200.0009685,0,0,0,90.00000001 +314,50.30085681,-2.776072986,10500,0,200.0009685,0,0,0,90.00000001 +314.01,50.30085681,-2.776044961,10500,0,199.9998535,0,0,0,90.00000001 +314.02,50.30085681,-2.776016936,10500,0,199.9991844,0,0,0,90.00000001 +314.03,50.30085681,-2.775988911,10500,0,199.9998535,0,0,0,90.00000001 +314.04,50.30085681,-2.775960886,10500,0,200.0009685,0,0,0,90.00000001 +314.05,50.30085681,-2.77593286,10500,0,200.0009685,0,0,0,90.00000001 +314.06,50.30085681,-2.775904835,10500,0,199.9998535,0,0,0,90.00000001 +314.07,50.30085681,-2.77587681,10500,0,199.9989614,0,0,0,90.00000001 +314.08,50.30085681,-2.775848785,10500,0,199.9989614,0,0,0,90.00000001 +314.09,50.30085681,-2.77582076,10500,0,199.9998535,0,0,0,90.00000001 +314.1,50.30085681,-2.775792735,10500,0,200.0009685,0,0,0,90.00000001 +314.11,50.30085681,-2.775764709,10500,0,200.0009685,0,0,0,90.00000001 +314.12,50.30085681,-2.775736684,10500,0,199.9998535,0,0,0,90.00000001 +314.13,50.30085681,-2.775708659,10500,0,199.9991844,0,0,0,90.00000001 +314.14,50.30085681,-2.775680634,10500,0,199.9998535,0,0,0,90.00000001 +314.15,50.30085681,-2.775652609,10500,0,200.0009685,0,0,0,90.00000001 +314.16,50.30085681,-2.775624583,10500,0,200.0009685,0,0,0,90.00000001 +314.17,50.30085681,-2.775596558,10500,0,199.9998535,0,0,0,90.00000001 +314.18,50.30085681,-2.775568533,10500,0,199.9991844,0,0,0,90.00000001 +314.19,50.30085681,-2.775540508,10500,0,199.9998535,0,0,0,90.00000001 +314.2,50.30085681,-2.775512483,10500,0,200.0009685,0,0,0,90.00000001 +314.21,50.30085681,-2.775484457,10500,0,200.0009685,0,0,0,90.00000001 +314.22,50.30085681,-2.775456432,10500,0,199.9998535,0,0,0,90.00000001 +314.23,50.30085681,-2.775428407,10500,0,199.9991844,0,0,0,90.00000001 +314.24,50.30085681,-2.775400382,10500,0,199.9998535,0,0,0,90.00000001 +314.25,50.30085681,-2.775372357,10500,0,200.0009685,0,0,0,90.00000001 +314.26,50.30085681,-2.775344331,10500,0,200.0009685,0,0,0,90.00000001 +314.27,50.30085681,-2.775316306,10500,0,199.9998535,0,0,0,90.00000001 +314.28,50.30085681,-2.775288281,10500,0,199.9989614,0,0,0,90.00000001 +314.29,50.30085681,-2.775260256,10500,0,199.9989614,0,0,0,90.00000001 +314.3,50.30085681,-2.775232231,10500,0,199.9998535,0,0,0,90.00000001 +314.31,50.30085681,-2.775204206,10500,0,200.0009685,0,0,0,90.00000001 +314.32,50.30085681,-2.77517618,10500,0,200.0009685,0,0,0,90.00000001 +314.33,50.30085681,-2.775148155,10500,0,199.9998535,0,0,0,90.00000001 +314.34,50.30085681,-2.77512013,10500,0,199.9989614,0,0,0,90.00000001 +314.35,50.30085681,-2.775092105,10500,0,199.9989614,0,0,0,90.00000001 +314.36,50.30085681,-2.77506408,10500,0,199.9998535,0,0,0,90.00000001 +314.37,50.30085681,-2.775036055,10500,0,200.0009685,0,0,0,90.00000001 +314.38,50.30085681,-2.775008029,10500,0,200.0009685,0,0,0,90.00000001 +314.39,50.30085681,-2.774980004,10500,0,199.9998535,0,0,0,90.00000001 +314.4,50.30085681,-2.774951979,10500,0,199.9989614,0,0,0,90.00000001 +314.41,50.30085681,-2.774923954,10500,0,199.9987384,0,0,0,90.00000001 +314.42,50.30085681,-2.774895929,10500,0,199.9989614,0,0,0,90.00000001 +314.43,50.30085681,-2.774867904,10500,0,199.9998535,0,0,0,90.00000001 +314.44,50.30085681,-2.774839879,10500,0,200.0009685,0,0,0,90.00000001 +314.45,50.30085681,-2.774811853,10500,0,200.0009685,0,0,0,90.00000001 +314.46,50.30085681,-2.774783828,10500,0,199.9998535,0,0,0,90.00000001 +314.47,50.30085681,-2.774755803,10500,0,199.9989614,0,0,0,90.00000001 +314.48,50.30085681,-2.774727778,10500,0,199.9989614,0,0,0,90.00000001 +314.49,50.30085681,-2.774699753,10500,0,199.9998535,0,0,0,90.00000001 +314.5,50.30085681,-2.774671728,10500,0,200.0009685,0,0,0,90.00000001 +314.51,50.30085681,-2.774643702,10500,0,200.0009685,0,0,0,90.00000001 +314.52,50.30085681,-2.774615677,10500,0,199.9998535,0,0,0,90.00000001 +314.53,50.30085681,-2.774587652,10500,0,199.9989614,0,0,0,90.00000001 +314.54,50.30085681,-2.774559627,10500,0,199.9989614,0,0,0,90.00000001 +314.55,50.30085681,-2.774531602,10500,0,199.9998535,0,0,0,90.00000001 +314.56,50.30085681,-2.774503577,10500,0,200.0009685,0,0,0,90.00000001 +314.57,50.30085681,-2.774475551,10500,0,200.0009685,0,0,0,90.00000001 +314.58,50.30085681,-2.774447526,10500,0,199.9998535,0,0,0,90.00000001 +314.59,50.30085681,-2.774419501,10500,0,199.9989614,0,0,0,90.00000001 +314.6,50.30085681,-2.774391476,10500,0,199.9989614,0,0,0,90.00000001 +314.61,50.30085681,-2.774363451,10500,0,199.9998535,0,0,0,90.00000001 +314.62,50.30085681,-2.774335426,10500,0,200.0009685,0,0,0,90.00000001 +314.63,50.30085681,-2.7743074,10500,0,200.0009685,0,0,0,90.00000001 +314.64,50.30085681,-2.774279375,10500,0,199.9998535,0,0,0,90.00000001 +314.65,50.30085681,-2.77425135,10500,0,199.9991844,0,0,0,90.00000001 +314.66,50.30085681,-2.774223325,10500,0,199.9998535,0,0,0,90.00000001 +314.67,50.30085681,-2.7741953,10500,0,200.0009685,0,0,0,90.00000001 +314.68,50.30085681,-2.774167274,10500,0,200.0009685,0,0,0,90.00000001 +314.69,50.30085681,-2.774139249,10500,0,199.9998535,0,0,0,90.00000001 +314.7,50.30085681,-2.774111224,10500,0,199.9991844,0,0,0,90.00000001 +314.71,50.30085681,-2.774083199,10500,0,199.9998535,0,0,0,90.00000001 +314.72,50.30085681,-2.774055174,10500,0,200.0009685,0,0,0,90.00000001 +314.73,50.30085681,-2.774027148,10500,0,200.0009685,0,0,0,90.00000001 +314.74,50.30085681,-2.773999123,10500,0,199.9998535,0,0,0,90.00000001 +314.75,50.30085681,-2.773971098,10500,0,199.9991844,0,0,0,90.00000001 +314.76,50.30085681,-2.773943073,10500,0,199.9998535,0,0,0,90.00000001 +314.77,50.30085681,-2.773915048,10500,0,200.0009685,0,0,0,90.00000001 +314.78,50.30085681,-2.773887022,10500,0,200.0009685,0,0,0,90.00000001 +314.79,50.30085681,-2.773858997,10500,0,199.9998535,0,0,0,90.00000001 +314.8,50.30085681,-2.773830972,10500,0,199.9991844,0,0,0,90.00000001 +314.81,50.30085681,-2.773802947,10500,0,199.9998535,0,0,0,90.00000001 +314.82,50.30085681,-2.773774922,10500,0,200.0009685,0,0,0,90.00000001 +314.83,50.30085681,-2.773746896,10500,0,200.0009685,0,0,0,90.00000001 +314.84,50.30085681,-2.773718871,10500,0,199.9998535,0,0,0,90.00000001 +314.85,50.30085681,-2.773690846,10500,0,199.9991844,0,0,0,90.00000001 +314.86,50.30085681,-2.773662821,10500,0,199.9998535,0,0,0,90.00000001 +314.87,50.30085681,-2.773634796,10500,0,200.0009685,0,0,0,90.00000001 +314.88,50.30085681,-2.77360677,10500,0,200.0009685,0,0,0,90.00000001 +314.89,50.30085681,-2.773578745,10500,0,199.9998535,0,0,0,90.00000001 +314.9,50.30085681,-2.77355072,10500,0,199.9989614,0,0,0,90.00000001 +314.91,50.30085681,-2.773522695,10500,0,199.9989614,0,0,0,90.00000001 +314.92,50.30085681,-2.77349467,10500,0,199.9998535,0,0,0,90.00000001 +314.93,50.30085681,-2.773466645,10500,0,200.0009685,0,0,0,90.00000001 +314.94,50.30085681,-2.773438619,10500,0,200.0009685,0,0,0,90.00000001 +314.95,50.30085681,-2.773410594,10500,0,199.9998535,0,0,0,90.00000001 +314.96,50.30085681,-2.773382569,10500,0,199.9989614,0,0,0,90.00000001 +314.97,50.30085681,-2.773354544,10500,0,199.9989614,0,0,0,90.00000001 +314.98,50.30085681,-2.773326519,10500,0,199.9998535,0,0,0,90.00000001 +314.99,50.30085681,-2.773298494,10500,0,200.0009685,0,0,0,90.00000001 +315,50.30085681,-2.773270468,10500,0,200.0009685,0,0,0,90.00000001 +315.01,50.30085681,-2.773242443,10500,0,199.9998535,0,0,0,90.00000001 +315.02,50.30085681,-2.773214418,10500,0,199.9989614,0,0,0,90.00000001 +315.03,50.30085681,-2.773186393,10500,0,199.9987384,0,0,0,90.00000001 +315.04,50.30085681,-2.773158368,10500,0,199.9989614,0,0,0,90.00000001 +315.05,50.30085681,-2.773130343,10500,0,199.9998535,0,0,0,90.00000001 +315.06,50.30085681,-2.773102318,10500,0,200.0009685,0,0,0,90.00000001 +315.07,50.30085681,-2.773074292,10500,0,200.0009685,0,0,0,90.00000001 +315.08,50.30085681,-2.773046267,10500,0,199.9998535,0,0,0,90.00000001 +315.09,50.30085681,-2.773018242,10500,0,199.9989614,0,0,0,90.00000001 +315.1,50.30085681,-2.772990217,10500,0,199.9989614,0,0,0,90.00000001 +315.11,50.30085681,-2.772962192,10500,0,199.9998535,0,0,0,90.00000001 +315.12,50.30085681,-2.772934167,10500,0,200.0009685,0,0,0,90.00000001 +315.13,50.30085681,-2.772906141,10500,0,200.0009685,0,0,0,90.00000001 +315.14,50.30085681,-2.772878116,10500,0,199.9998535,0,0,0,90.00000001 +315.15,50.30085681,-2.772850091,10500,0,199.9989614,0,0,0,90.00000001 +315.16,50.30085681,-2.772822066,10500,0,199.9989614,0,0,0,90.00000001 +315.17,50.30085681,-2.772794041,10500,0,199.9998535,0,0,0,90.00000001 +315.18,50.30085681,-2.772766016,10500,0,200.0009685,0,0,0,90.00000001 +315.19,50.30085681,-2.77273799,10500,0,200.0009685,0,0,0,90.00000001 +315.2,50.30085681,-2.772709965,10500,0,199.9998535,0,0,0,90.00000001 +315.21,50.30085681,-2.77268194,10500,0,199.9989614,0,0,0,90.00000001 +315.22,50.30085681,-2.772653915,10500,0,199.9989614,0,0,0,90.00000001 +315.23,50.30085681,-2.77262589,10500,0,199.9998535,0,0,0,90.00000001 +315.24,50.30085681,-2.772597865,10500,0,200.0009685,0,0,0,90.00000001 +315.25,50.30085681,-2.772569839,10500,0,200.0009685,0,0,0,90.00000001 +315.26,50.30085681,-2.772541814,10500,0,199.9998535,0,0,0,90.00000001 +315.27,50.30085681,-2.772513789,10500,0,199.9991844,0,0,0,90.00000001 +315.28,50.30085681,-2.772485764,10500,0,199.9998535,0,0,0,90.00000001 +315.29,50.30085681,-2.772457739,10500,0,200.0009685,0,0,0,90.00000001 +315.3,50.30085681,-2.772429713,10500,0,200.0009685,0,0,0,90.00000001 +315.31,50.30085681,-2.772401688,10500,0,199.9998535,0,0,0,90.00000001 +315.32,50.30085681,-2.772373663,10500,0,199.9991844,0,0,0,90.00000001 +315.33,50.30085681,-2.772345638,10500,0,199.9998535,0,0,0,90.00000001 +315.34,50.30085681,-2.772317613,10500,0,200.0009685,0,0,0,90.00000001 +315.35,50.30085681,-2.772289587,10500,0,200.0009685,0,0,0,90.00000001 +315.36,50.30085681,-2.772261562,10500,0,199.9998535,0,0,0,90.00000001 +315.37,50.30085681,-2.772233537,10500,0,199.9991844,0,0,0,90.00000001 +315.38,50.30085681,-2.772205512,10500,0,199.9998535,0,0,0,90.00000001 +315.39,50.30085681,-2.772177487,10500,0,200.0009685,0,0,0,90.00000001 +315.4,50.30085681,-2.772149461,10500,0,200.0009685,0,0,0,90.00000001 +315.41,50.30085681,-2.772121436,10500,0,199.9998535,0,0,0,90.00000001 +315.42,50.30085681,-2.772093411,10500,0,199.9991844,0,0,0,90.00000001 +315.43,50.30085681,-2.772065386,10500,0,199.9998535,0,0,0,90.00000001 +315.44,50.30085681,-2.772037361,10500,0,200.0009685,0,0,0,90.00000001 +315.45,50.30085681,-2.772009335,10500,0,200.0009685,0,0,0,90.00000001 +315.46,50.30085681,-2.77198131,10500,0,199.9998535,0,0,0,90.00000001 +315.47,50.30085681,-2.771953285,10500,0,199.9991844,0,0,0,90.00000001 +315.48,50.30085681,-2.77192526,10500,0,199.9998535,0,0,0,90.00000001 +315.49,50.30085681,-2.771897235,10500,0,200.0009685,0,0,0,90.00000001 +315.5,50.30085681,-2.771869209,10500,0,200.0009685,0,0,0,90.00000001 +315.51,50.30085681,-2.771841184,10500,0,199.9998535,0,0,0,90.00000001 +315.52,50.30085681,-2.771813159,10500,0,199.9989614,0,0,0,90.00000001 +315.53,50.30085681,-2.771785134,10500,0,199.9989614,0,0,0,90.00000001 +315.54,50.30085681,-2.771757109,10500,0,199.9998535,0,0,0,90.00000001 +315.55,50.30085681,-2.771729084,10500,0,200.0009685,0,0,0,90.00000001 +315.56,50.30085681,-2.771701058,10500,0,200.0009685,0,0,0,90.00000001 +315.57,50.30085681,-2.771673033,10500,0,199.9998535,0,0,0,90.00000001 +315.58,50.30085681,-2.771645008,10500,0,199.9989614,0,0,0,90.00000001 +315.59,50.30085681,-2.771616983,10500,0,199.9987384,0,0,0,90.00000001 +315.6,50.30085681,-2.771588958,10500,0,199.9989614,0,0,0,90.00000001 +315.61,50.30085681,-2.771560933,10500,0,199.9998535,0,0,0,90.00000001 +315.62,50.30085681,-2.771532908,10500,0,200.0009685,0,0,0,90.00000001 +315.63,50.30085681,-2.771504882,10500,0,200.0009685,0,0,0,90.00000001 +315.64,50.30085681,-2.771476857,10500,0,199.9998535,0,0,0,90.00000001 +315.65,50.30085681,-2.771448832,10500,0,199.9989614,0,0,0,90.00000001 +315.66,50.30085681,-2.771420807,10500,0,199.9989614,0,0,0,90.00000001 +315.67,50.30085681,-2.771392782,10500,0,199.9998535,0,0,0,90.00000001 +315.68,50.30085681,-2.771364757,10500,0,200.0009685,0,0,0,90.00000001 +315.69,50.30085681,-2.771336731,10500,0,200.0009685,0,0,0,90.00000001 +315.7,50.30085681,-2.771308706,10500,0,199.9998535,0,0,0,90.00000001 +315.71,50.30085681,-2.771280681,10500,0,199.9989614,0,0,0,90.00000001 +315.72,50.30085681,-2.771252656,10500,0,199.9989614,0,0,0,90.00000001 +315.73,50.30085681,-2.771224631,10500,0,199.9998535,0,0,0,90.00000001 +315.74,50.30085681,-2.771196606,10500,0,200.0009685,0,0,0,90.00000001 +315.75,50.30085681,-2.77116858,10500,0,200.0009685,0,0,0,90.00000001 +315.76,50.30085681,-2.771140555,10500,0,199.9998535,0,0,0,90.00000001 +315.77,50.30085681,-2.77111253,10500,0,199.9989614,0,0,0,90.00000001 +315.78,50.30085681,-2.771084505,10500,0,199.9989614,0,0,0,90.00000001 +315.79,50.30085681,-2.77105648,10500,0,199.9998535,0,0,0,90.00000001 +315.8,50.30085681,-2.771028455,10500,0,200.0009685,0,0,0,90.00000001 +315.81,50.30085681,-2.771000429,10500,0,200.0009685,0,0,0,90.00000001 +315.82,50.30085681,-2.770972404,10500,0,199.9998535,0,0,0,90.00000001 +315.83,50.30085681,-2.770944379,10500,0,199.9989614,0,0,0,90.00000001 +315.84,50.30085681,-2.770916354,10500,0,199.9989614,0,0,0,90.00000001 +315.85,50.30085681,-2.770888329,10500,0,199.9998535,0,0,0,90.00000001 +315.86,50.30085681,-2.770860304,10500,0,200.0009685,0,0,0,90.00000001 +315.87,50.30085681,-2.770832278,10500,0,200.0009685,0,0,0,90.00000001 +315.88,50.30085681,-2.770804253,10500,0,199.9998535,0,0,0,90.00000001 +315.89,50.30085681,-2.770776228,10500,0,199.9991844,0,0,0,90.00000001 +315.9,50.30085681,-2.770748203,10500,0,199.9998535,0,0,0,90.00000001 +315.91,50.30085681,-2.770720178,10500,0,200.0009685,0,0,0,90.00000001 +315.92,50.30085681,-2.770692152,10500,0,200.0009685,0,0,0,90.00000001 +315.93,50.30085681,-2.770664127,10500,0,199.9998535,0,0,0,90.00000001 +315.94,50.30085681,-2.770636102,10500,0,199.9991844,0,0,0,90.00000001 +315.95,50.30085681,-2.770608077,10500,0,199.9998535,0,0,0,90.00000001 +315.96,50.30085681,-2.770580052,10500,0,200.0009685,0,0,0,90.00000001 +315.97,50.30085681,-2.770552026,10500,0,200.0009685,0,0,0,90.00000001 +315.98,50.30085681,-2.770524001,10500,0,199.9998535,0,0,0,90.00000001 +315.99,50.30085681,-2.770495976,10500,0,199.9991844,0,0,0,90.00000001 +316,50.30085681,-2.770467951,10500,0,199.9998535,0,0,0,90.00000001 +316.01,50.30085681,-2.770439926,10500,0,200.0009685,0,0,0,90.00000001 +316.02,50.30085681,-2.7704119,10500,0,200.0009685,0,0,0,90.00000001 +316.03,50.30085681,-2.770383875,10500,0,199.9998535,0,0,0,90.00000001 +316.04,50.30085681,-2.77035585,10500,0,199.9991844,0,0,0,90.00000001 +316.05,50.30085681,-2.770327825,10500,0,199.9998535,0,0,0,90.00000001 +316.06,50.30085681,-2.7702998,10500,0,200.0009685,0,0,0,90.00000001 +316.07,50.30085681,-2.770271774,10500,0,200.0009685,0,0,0,90.00000001 +316.08,50.30085681,-2.770243749,10500,0,199.9998535,0,0,0,90.00000001 +316.09,50.30085681,-2.770215724,10500,0,199.9991844,0,0,0,90.00000001 +316.1,50.30085681,-2.770187699,10500,0,199.9998535,0,0,0,90.00000001 +316.11,50.30085681,-2.770159674,10500,0,200.0009685,0,0,0,90.00000001 +316.12,50.30085681,-2.770131648,10500,0,200.0009685,0,0,0,90.00000001 +316.13,50.30085681,-2.770103623,10500,0,199.9998535,0,0,0,90.00000001 +316.14,50.30085681,-2.770075598,10500,0,199.9989614,0,0,0,90.00000001 +316.15,50.30085681,-2.770047573,10500,0,199.9987384,0,0,0,90.00000001 +316.16,50.30085681,-2.770019548,10500,0,199.9989614,0,0,0,90.00000001 +316.17,50.30085681,-2.769991523,10500,0,199.9998535,0,0,0,90.00000001 +316.18,50.30085681,-2.769963498,10500,0,200.0009685,0,0,0,90.00000001 +316.19,50.30085681,-2.769935472,10500,0,200.0009685,0,0,0,90.00000001 +316.2,50.30085681,-2.769907447,10500,0,199.9998535,0,0,0,90.00000001 +316.21,50.30085681,-2.769879422,10500,0,199.9989614,0,0,0,90.00000001 +316.22,50.30085681,-2.769851397,10500,0,199.9989614,0,0,0,90.00000001 +316.23,50.30085681,-2.769823372,10500,0,199.9998535,0,0,0,90.00000001 +316.24,50.30085681,-2.769795347,10500,0,200.0009685,0,0,0,90.00000001 +316.25,50.30085681,-2.769767321,10500,0,200.0009685,0,0,0,90.00000001 +316.26,50.30085681,-2.769739296,10500,0,199.9998535,0,0,0,90.00000001 +316.27,50.30085681,-2.769711271,10500,0,199.9989614,0,0,0,90.00000001 +316.28,50.30085681,-2.769683246,10500,0,199.9989614,0,0,0,90.00000001 +316.29,50.30085681,-2.769655221,10500,0,199.9998535,0,0,0,90.00000001 +316.3,50.30085681,-2.769627196,10500,0,200.0009685,0,0,0,90.00000001 +316.31,50.30085681,-2.76959917,10500,0,200.0009685,0,0,0,90.00000001 +316.32,50.30085681,-2.769571145,10500,0,199.9998535,0,0,0,90.00000001 +316.33,50.30085681,-2.76954312,10500,0,199.9989614,0,0,0,90.00000001 +316.34,50.30085681,-2.769515095,10500,0,199.9989614,0,0,0,90.00000001 +316.35,50.30085681,-2.76948707,10500,0,199.9998535,0,0,0,90.00000001 +316.36,50.30085681,-2.769459045,10500,0,200.0009685,0,0,0,90.00000001 +316.37,50.30085681,-2.769431019,10500,0,200.0009685,0,0,0,90.00000001 +316.38,50.30085681,-2.769402994,10500,0,199.9998535,0,0,0,90.00000001 +316.39,50.30085681,-2.769374969,10500,0,199.9989614,0,0,0,90.00000001 +316.4,50.30085681,-2.769346944,10500,0,199.9989614,0,0,0,90.00000001 +316.41,50.30085681,-2.769318919,10500,0,199.9998535,0,0,0,90.00000001 +316.42,50.30085681,-2.769290894,10500,0,200.0009685,0,0,0,90.00000001 +316.43,50.30085681,-2.769262868,10500,0,200.0009685,0,0,0,90.00000001 +316.44,50.30085681,-2.769234843,10500,0,199.9998535,0,0,0,90.00000001 +316.45,50.30085681,-2.769206818,10500,0,199.9989614,0,0,0,90.00000001 +316.46,50.30085681,-2.769178793,10500,0,199.9987384,0,0,0,90.00000001 +316.47,50.30085681,-2.769150768,10500,0,199.9989614,0,0,0,90.00000001 +316.48,50.30085681,-2.769122743,10500,0,199.9998535,0,0,0,90.00000001 +316.49,50.30085681,-2.769094718,10500,0,200.0009685,0,0,0,90.00000001 +316.5,50.30085681,-2.769066692,10500,0,200.0009685,0,0,0,90.00000001 +316.51,50.30085681,-2.769038667,10500,0,199.9998535,0,0,0,90.00000001 +316.52,50.30085681,-2.769010642,10500,0,199.9991844,0,0,0,90.00000001 +316.53,50.30085681,-2.768982617,10500,0,199.9998535,0,0,0,90.00000001 +316.54,50.30085681,-2.768954592,10500,0,200.0009685,0,0,0,90.00000001 +316.55,50.30085681,-2.768926566,10500,0,200.0009685,0,0,0,90.00000001 +316.56,50.30085681,-2.768898541,10500,0,199.9998535,0,0,0,90.00000001 +316.57,50.30085681,-2.768870516,10500,0,199.9991844,0,0,0,90.00000001 +316.58,50.30085681,-2.768842491,10500,0,199.9998535,0,0,0,90.00000001 +316.59,50.30085681,-2.768814466,10500,0,200.0009685,0,0,0,90.00000001 +316.6,50.30085681,-2.76878644,10500,0,200.0009685,0,0,0,90.00000001 +316.61,50.30085681,-2.768758415,10500,0,199.9998535,0,0,0,90.00000001 +316.62,50.30085681,-2.76873039,10500,0,199.9991844,0,0,0,90.00000001 +316.63,50.30085681,-2.768702365,10500,0,199.9998535,0,0,0,90.00000001 +316.64,50.30085681,-2.76867434,10500,0,200.0009685,0,0,0,90.00000001 +316.65,50.30085681,-2.768646314,10500,0,200.0009685,0,0,0,90.00000001 +316.66,50.30085681,-2.768618289,10500,0,199.9998535,0,0,0,90.00000001 +316.67,50.30085681,-2.768590264,10500,0,199.9991844,0,0,0,90.00000001 +316.68,50.30085681,-2.768562239,10500,0,199.9998535,0,0,0,90.00000001 +316.69,50.30085681,-2.768534214,10500,0,200.0009685,0,0,0,90.00000001 +316.7,50.30085681,-2.768506188,10500,0,200.0009685,0,0,0,90.00000001 +316.71,50.30085681,-2.768478163,10500,0,199.9998535,0,0,0,90.00000001 +316.72,50.30085681,-2.768450138,10500,0,199.9991844,0,0,0,90.00000001 +316.73,50.30085681,-2.768422113,10500,0,199.9998535,0,0,0,90.00000001 +316.74,50.30085681,-2.768394088,10500,0,200.0009685,0,0,0,90.00000001 +316.75,50.30085681,-2.768366062,10500,0,200.0009685,0,0,0,90.00000001 +316.76,50.30085681,-2.768338037,10500,0,199.9998535,0,0,0,90.00000001 +316.77,50.30085681,-2.768310012,10500,0,199.9989614,0,0,0,90.00000001 +316.78,50.30085681,-2.768281987,10500,0,199.9989614,0,0,0,90.00000001 +316.79,50.30085681,-2.768253962,10500,0,199.9998535,0,0,0,90.00000001 +316.8,50.30085681,-2.768225937,10500,0,200.0009685,0,0,0,90.00000001 +316.81,50.30085681,-2.768197911,10500,0,200.0009685,0,0,0,90.00000001 +316.82,50.30085681,-2.768169886,10500,0,199.9998535,0,0,0,90.00000001 +316.83,50.30085681,-2.768141861,10500,0,199.9989614,0,0,0,90.00000001 +316.84,50.30085681,-2.768113836,10500,0,199.9989614,0,0,0,90.00000001 +316.85,50.30085681,-2.768085811,10500,0,199.9998535,0,0,0,90.00000001 +316.86,50.30085681,-2.768057786,10500,0,200.0009685,0,0,0,90.00000001 +316.87,50.30085681,-2.76802976,10500,0,200.0009685,0,0,0,90.00000001 +316.88,50.30085681,-2.768001735,10500,0,199.9998535,0,0,0,90.00000001 +316.89,50.30085681,-2.76797371,10500,0,199.9989614,0,0,0,90.00000001 +316.9,50.30085681,-2.767945685,10500,0,199.9989614,0,0,0,90.00000001 +316.91,50.30085681,-2.76791766,10500,0,199.9998535,0,0,0,90.00000001 +316.92,50.30085681,-2.767889635,10500,0,200.0009685,0,0,0,90.00000001 +316.93,50.30085681,-2.767861609,10500,0,200.0009685,0,0,0,90.00000001 +316.94,50.30085681,-2.767833584,10500,0,199.9998535,0,0,0,90.00000001 +316.95,50.30085681,-2.767805559,10500,0,199.9989614,0,0,0,90.00000001 +316.96,50.30085681,-2.767777534,10500,0,199.9989614,0,0,0,90.00000001 +316.97,50.30085681,-2.767749509,10500,0,199.9998535,0,0,0,90.00000001 +316.98,50.30085681,-2.767721484,10500,0,200.0009685,0,0,0,90.00000001 +316.99,50.30085681,-2.767693458,10500,0,200.0009685,0,0,0,90.00000001 +317,50.30085681,-2.767665433,10500,0,199.9998535,0,0,0,90.00000001 +317.01,50.30085681,-2.767637408,10500,0,199.9989614,0,0,0,90.00000001 +317.02,50.30085681,-2.767609383,10500,0,199.9987384,0,0,0,90.00000001 +317.03,50.30085681,-2.767581358,10500,0,199.9989614,0,0,0,90.00000001 +317.04,50.30085681,-2.767553333,10500,0,199.9998535,0,0,0,90.00000001 +317.05,50.30085681,-2.767525308,10500,0,200.0009685,0,0,0,90.00000001 +317.06,50.30085681,-2.767497282,10500,0,200.0009685,0,0,0,90.00000001 +317.07,50.30085681,-2.767469257,10500,0,199.9998535,0,0,0,90.00000001 +317.08,50.30085681,-2.767441232,10500,0,199.9989614,0,0,0,90.00000001 +317.09,50.30085681,-2.767413207,10500,0,199.9989614,0,0,0,90.00000001 +317.1,50.30085681,-2.767385182,10500,0,199.9998535,0,0,0,90.00000001 +317.11,50.30085681,-2.767357157,10500,0,200.0009685,0,0,0,90.00000001 +317.12,50.30085681,-2.767329131,10500,0,200.0009685,0,0,0,90.00000001 +317.13,50.30085681,-2.767301106,10500,0,199.9998535,0,0,0,90.00000001 +317.14,50.30085681,-2.767273081,10500,0,199.9991844,0,0,0,90.00000001 +317.15,50.30085681,-2.767245056,10500,0,199.9998535,0,0,0,90.00000001 +317.16,50.30085681,-2.767217031,10500,0,200.0009685,0,0,0,90.00000001 +317.17,50.30085681,-2.767189005,10500,0,200.0009685,0,0,0,90.00000001 +317.18,50.30085681,-2.76716098,10500,0,199.9998535,0,0,0,90.00000001 +317.19,50.30085681,-2.767132955,10500,0,199.9991844,0,0,0,90.00000001 +317.2,50.30085681,-2.76710493,10500,0,199.9998535,0,0,0,90.00000001 +317.21,50.30085681,-2.767076905,10500,0,200.0009685,0,0,0,90.00000001 +317.22,50.30085681,-2.767048879,10500,0,200.0009685,0,0,0,90.00000001 +317.23,50.30085681,-2.767020854,10500,0,199.9998535,0,0,0,90.00000001 +317.24,50.30085681,-2.766992829,10500,0,199.9991844,0,0,0,90.00000001 +317.25,50.30085681,-2.766964804,10500,0,199.9998535,0,0,0,90.00000001 +317.26,50.30085681,-2.766936779,10500,0,200.0009685,0,0,0,90.00000001 +317.27,50.30085681,-2.766908753,10500,0,200.0009685,0,0,0,90.00000001 +317.28,50.30085681,-2.766880728,10500,0,199.9998535,0,0,0,90.00000001 +317.29,50.30085681,-2.766852703,10500,0,199.9991844,0,0,0,90.00000001 +317.3,50.30085681,-2.766824678,10500,0,199.9998535,0,0,0,90.00000001 +317.31,50.30085681,-2.766796653,10500,0,200.0009685,0,0,0,90.00000001 +317.32,50.30085681,-2.766768627,10500,0,200.0009685,0,0,0,90.00000001 +317.33,50.30085681,-2.766740602,10500,0,199.9998535,0,0,0,90.00000001 +317.34,50.30085681,-2.766712577,10500,0,199.9991844,0,0,0,90.00000001 +317.35,50.30085681,-2.766684552,10500,0,199.9998535,0,0,0,90.00000001 +317.36,50.30085681,-2.766656527,10500,0,200.0009685,0,0,0,90.00000001 +317.37,50.30085681,-2.766628501,10500,0,200.0009685,0,0,0,90.00000001 +317.38,50.30085681,-2.766600476,10500,0,199.9998535,0,0,0,90.00000001 +317.39,50.30085681,-2.766572451,10500,0,199.9989614,0,0,0,90.00000001 +317.4,50.30085681,-2.766544426,10500,0,199.9989614,0,0,0,90.00000001 +317.41,50.30085681,-2.766516401,10500,0,199.9998535,0,0,0,90.00000001 +317.42,50.30085681,-2.766488376,10500,0,200.0009685,0,0,0,90.00000001 +317.43,50.30085681,-2.76646035,10500,0,200.0009685,0,0,0,90.00000001 +317.44,50.30085681,-2.766432325,10500,0,199.9998535,0,0,0,90.00000001 +317.45,50.30085681,-2.7664043,10500,0,199.9989614,0,0,0,90.00000001 +317.46,50.30085681,-2.766376275,10500,0,199.9989614,0,0,0,90.00000001 +317.47,50.30085681,-2.76634825,10500,0,199.9998535,0,0,0,90.00000001 +317.48,50.30085681,-2.766320225,10500,0,200.0009685,0,0,0,90.00000001 +317.49,50.30085681,-2.766292199,10500,0,200.0009685,0,0,0,90.00000001 +317.5,50.30085681,-2.766264174,10500,0,199.9998535,0,0,0,90.00000001 +317.51,50.30085681,-2.766236149,10500,0,199.9989614,0,0,0,90.00000001 +317.52,50.30085681,-2.766208124,10500,0,199.9989614,0,0,0,90.00000001 +317.53,50.30085681,-2.766180099,10500,0,199.9998535,0,0,0,90.00000001 +317.54,50.30085681,-2.766152074,10500,0,200.0009685,0,0,0,90.00000001 +317.55,50.30085681,-2.766124048,10500,0,200.0009685,0,0,0,90.00000001 +317.56,50.30085681,-2.766096023,10500,0,199.9998535,0,0,0,90.00000001 +317.57,50.30085681,-2.766067998,10500,0,199.9989614,0,0,0,90.00000001 +317.58,50.30085681,-2.766039973,10500,0,199.9987384,0,0,0,90.00000001 +317.59,50.30085681,-2.766011948,10500,0,199.9989614,0,0,0,90.00000001 +317.6,50.30085681,-2.765983923,10500,0,199.9998535,0,0,0,90.00000001 +317.61,50.30085681,-2.765955898,10500,0,200.0009685,0,0,0,90.00000001 +317.62,50.30085681,-2.765927872,10500,0,200.0009685,0,0,0,90.00000001 +317.63,50.30085681,-2.765899847,10500,0,199.9998535,0,0,0,90.00000001 +317.64,50.30085681,-2.765871822,10500,0,199.9989614,0,0,0,90.00000001 +317.65,50.30085681,-2.765843797,10500,0,199.9989614,0,0,0,90.00000001 +317.66,50.30085681,-2.765815772,10500,0,199.9998535,0,0,0,90.00000001 +317.67,50.30085681,-2.765787747,10500,0,200.0009685,0,0,0,90.00000001 +317.68,50.30085681,-2.765759721,10500,0,200.0009685,0,0,0,90.00000001 +317.69,50.30085681,-2.765731696,10500,0,199.9998535,0,0,0,90.00000001 +317.7,50.30085681,-2.765703671,10500,0,199.9989614,0,0,0,90.00000001 +317.71,50.30085681,-2.765675646,10500,0,199.9989614,0,0,0,90.00000001 +317.72,50.30085681,-2.765647621,10500,0,199.9998535,0,0,0,90.00000001 +317.73,50.30085681,-2.765619596,10500,0,200.0009685,0,0,0,90.00000001 +317.74,50.30085681,-2.76559157,10500,0,200.0009685,0,0,0,90.00000001 +317.75,50.30085681,-2.765563545,10500,0,199.9998535,0,0,0,90.00000001 +317.76,50.30085681,-2.76553552,10500,0,199.9991844,0,0,0,90.00000001 +317.77,50.30085681,-2.765507495,10500,0,199.9998535,0,0,0,90.00000001 +317.78,50.30085681,-2.76547947,10500,0,200.0009685,0,0,0,90.00000001 +317.79,50.30085681,-2.765451444,10500,0,200.0009685,0,0,0,90.00000001 +317.8,50.30085681,-2.765423419,10500,0,199.9998535,0,0,0,90.00000001 +317.81,50.30085681,-2.765395394,10500,0,199.9991844,0,0,0,90.00000001 +317.82,50.30085681,-2.765367369,10500,0,199.9998535,0,0,0,90.00000001 +317.83,50.30085681,-2.765339344,10500,0,200.0009685,0,0,0,90.00000001 +317.84,50.30085681,-2.765311318,10500,0,200.0009685,0,0,0,90.00000001 +317.85,50.30085681,-2.765283293,10500,0,199.9998535,0,0,0,90.00000001 +317.86,50.30085681,-2.765255268,10500,0,199.9991844,0,0,0,90.00000001 +317.87,50.30085681,-2.765227243,10500,0,199.9998535,0,0,0,90.00000001 +317.88,50.30085681,-2.765199218,10500,0,200.0009685,0,0,0,90.00000001 +317.89,50.30085681,-2.765171192,10500,0,200.0009685,0,0,0,90.00000001 +317.9,50.30085681,-2.765143167,10500,0,199.9998535,0,0,0,90.00000001 +317.91,50.30085681,-2.765115142,10500,0,199.9991844,0,0,0,90.00000001 +317.92,50.30085681,-2.765087117,10500,0,199.9998535,0,0,0,90.00000001 +317.93,50.30085681,-2.765059092,10500,0,200.0009685,0,0,0,90.00000001 +317.94,50.30085681,-2.765031066,10500,0,200.0009685,0,0,0,90.00000001 +317.95,50.30085681,-2.765003041,10500,0,199.9998535,0,0,0,90.00000001 +317.96,50.30085681,-2.764975016,10500,0,199.9991844,0,0,0,90.00000001 +317.97,50.30085681,-2.764946991,10500,0,199.9998535,0,0,0,90.00000001 +317.98,50.30085681,-2.764918966,10500,0,200.0009685,0,0,0,90.00000001 +317.99,50.30085681,-2.76489094,10500,0,200.0009685,0,0,0,90.00000001 +318,50.30085681,-2.764862915,10500,0,199.9998535,0,0,0,90.00000001 +318.01,50.30085681,-2.76483489,10500,0,199.9989614,0,0,0,90.00000001 +318.02,50.30085681,-2.764806865,10500,0,199.9989614,0,0,0,90.00000001 +318.03,50.30085681,-2.76477884,10500,0,199.9998535,0,0,0,90.00000001 +318.04,50.30085681,-2.764750815,10500,0,200.0009685,0,0,0,90.00000001 +318.05,50.30085681,-2.764722789,10500,0,200.0009685,0,0,0,90.00000001 +318.06,50.30085681,-2.764694764,10500,0,199.9998535,0,0,0,90.00000001 +318.07,50.30085681,-2.764666739,10500,0,199.9989614,0,0,0,90.00000001 +318.08,50.30085681,-2.764638714,10500,0,199.9989614,0,0,0,90.00000001 +318.09,50.30085681,-2.764610689,10500,0,199.9998535,0,0,0,90.00000001 +318.1,50.30085681,-2.764582664,10500,0,200.0009685,0,0,0,90.00000001 +318.11,50.30085681,-2.764554638,10500,0,200.0009685,0,0,0,90.00000001 +318.12,50.30085681,-2.764526613,10500,0,199.9998535,0,0,0,90.00000001 +318.13,50.30085681,-2.764498588,10500,0,199.9989614,0,0,0,90.00000001 +318.14,50.30085681,-2.764470563,10500,0,199.9987384,0,0,0,90.00000001 +318.15,50.30085681,-2.764442538,10500,0,199.9989614,0,0,0,90.00000001 +318.16,50.30085681,-2.764414513,10500,0,199.9998535,0,0,0,90.00000001 +318.17,50.30085681,-2.764386488,10500,0,200.0009685,0,0,0,90.00000001 +318.18,50.30085681,-2.764358462,10500,0,200.0009685,0,0,0,90.00000001 +318.19,50.30085681,-2.764330437,10500,0,199.9998535,0,0,0,90.00000001 +318.2,50.30085681,-2.764302412,10500,0,199.9989614,0,0,0,90.00000001 +318.21,50.30085681,-2.764274387,10500,0,199.9989614,0,0,0,90.00000001 +318.22,50.30085681,-2.764246362,10500,0,199.9998535,0,0,0,90.00000001 +318.23,50.30085681,-2.764218337,10500,0,200.0009685,0,0,0,90.00000001 +318.24,50.30085681,-2.764190311,10500,0,200.0009685,0,0,0,90.00000001 +318.25,50.30085681,-2.764162286,10500,0,199.9998535,0,0,0,90.00000001 +318.26,50.30085681,-2.764134261,10500,0,199.9989614,0,0,0,90.00000001 +318.27,50.30085681,-2.764106236,10500,0,199.9989614,0,0,0,90.00000001 +318.28,50.30085681,-2.764078211,10500,0,199.9998535,0,0,0,90.00000001 +318.29,50.30085681,-2.764050186,10500,0,200.0009685,0,0,0,90.00000001 +318.3,50.30085681,-2.76402216,10500,0,200.0009685,0,0,0,90.00000001 +318.31,50.30085681,-2.763994135,10500,0,199.9998535,0,0,0,90.00000001 +318.32,50.30085681,-2.76396611,10500,0,199.9989614,0,0,0,90.00000001 +318.33,50.30085681,-2.763938085,10500,0,199.9989614,0,0,0,90.00000001 +318.34,50.30085681,-2.76391006,10500,0,199.9998535,0,0,0,90.00000001 +318.35,50.30085681,-2.763882035,10500,0,200.0009685,0,0,0,90.00000001 +318.36,50.30085681,-2.763854009,10500,0,200.0009685,0,0,0,90.00000001 +318.37,50.30085681,-2.763825984,10500,0,199.9998535,0,0,0,90.00000001 +318.38,50.30085681,-2.763797959,10500,0,199.9991844,0,0,0,90.00000001 +318.39,50.30085681,-2.763769934,10500,0,199.9998535,0,0,0,90.00000001 +318.4,50.30085681,-2.763741909,10500,0,200.0009685,0,0,0,90.00000001 +318.41,50.30085681,-2.763713883,10500,0,200.0009685,0,0,0,90.00000001 +318.42,50.30085681,-2.763685858,10500,0,199.9998535,0,0,0,90.00000001 +318.43,50.30085681,-2.763657833,10500,0,199.9991844,0,0,0,90.00000001 +318.44,50.30085681,-2.763629808,10500,0,199.9998535,0,0,0,90.00000001 +318.45,50.30085681,-2.763601783,10500,0,200.0009685,0,0,0,90.00000001 +318.46,50.30085681,-2.763573757,10500,0,200.0009685,0,0,0,90.00000001 +318.47,50.30085681,-2.763545732,10500,0,199.9998535,0,0,0,90.00000001 +318.48,50.30085681,-2.763517707,10500,0,199.9991844,0,0,0,90.00000001 +318.49,50.30085681,-2.763489682,10500,0,199.9998535,0,0,0,90.00000001 +318.5,50.30085681,-2.763461657,10500,0,200.0009685,0,0,0,90.00000001 +318.51,50.30085681,-2.763433631,10500,0,200.0009685,0,0,0,90.00000001 +318.52,50.30085681,-2.763405606,10500,0,199.9998535,0,0,0,90.00000001 +318.53,50.30085681,-2.763377581,10500,0,199.9989614,0,0,0,90.00000001 +318.54,50.30085681,-2.763349556,10500,0,199.9989614,0,0,0,90.00000001 +318.55,50.30085681,-2.763321531,10500,0,199.9998535,0,0,0,90.00000001 +318.56,50.30085681,-2.763293506,10500,0,200.0009685,0,0,0,90.00000001 +318.57,50.30085681,-2.76326548,10500,0,200.0009685,0,0,0,90.00000001 +318.58,50.30085681,-2.763237455,10500,0,199.9998535,0,0,0,90.00000001 +318.59,50.30085681,-2.76320943,10500,0,199.9991844,0,0,0,90.00000001 +318.6,50.30085681,-2.763181405,10500,0,199.9998535,0,0,0,90.00000001 +318.61,50.30085681,-2.76315338,10500,0,200.0009685,0,0,0,90.00000001 +318.62,50.30085681,-2.763125354,10500,0,200.0009685,0,0,0,90.00000001 +318.63,50.30085681,-2.763097329,10500,0,199.9998535,0,0,0,90.00000001 +318.64,50.30085681,-2.763069304,10500,0,199.9991844,0,0,0,90.00000001 +318.65,50.30085681,-2.763041279,10500,0,199.9998535,0,0,0,90.00000001 +318.66,50.30085681,-2.763013254,10500,0,200.0009685,0,0,0,90.00000001 +318.67,50.30085681,-2.762985228,10500,0,200.0009685,0,0,0,90.00000001 +318.68,50.30085681,-2.762957203,10500,0,199.9998535,0,0,0,90.00000001 +318.69,50.30085681,-2.762929178,10500,0,199.9989614,0,0,0,90.00000001 +318.7,50.30085681,-2.762901153,10500,0,199.9987384,0,0,0,90.00000001 +318.71,50.30085681,-2.762873128,10500,0,199.9989614,0,0,0,90.00000001 +318.72,50.30085681,-2.762845103,10500,0,199.9998535,0,0,0,90.00000001 +318.73,50.30085681,-2.762817078,10500,0,200.0009685,0,0,0,90.00000001 +318.74,50.30085681,-2.762789052,10500,0,200.0009685,0,0,0,90.00000001 +318.75,50.30085681,-2.762761027,10500,0,199.9998535,0,0,0,90.00000001 +318.76,50.30085681,-2.762733002,10500,0,199.9989614,0,0,0,90.00000001 +318.77,50.30085681,-2.762704977,10500,0,199.9989614,0,0,0,90.00000001 +318.78,50.30085681,-2.762676952,10500,0,199.9998535,0,0,0,90.00000001 +318.79,50.30085681,-2.762648927,10500,0,200.0009685,0,0,0,90.00000001 +318.8,50.30085681,-2.762620901,10500,0,200.0009685,0,0,0,90.00000001 +318.81,50.30085681,-2.762592876,10500,0,199.9998535,0,0,0,90.00000001 +318.82,50.30085681,-2.762564851,10500,0,199.9989614,0,0,0,90.00000001 +318.83,50.30085681,-2.762536826,10500,0,199.9989614,0,0,0,90.00000001 +318.84,50.30085681,-2.762508801,10500,0,199.9998535,0,0,0,90.00000001 +318.85,50.30085681,-2.762480776,10500,0,200.0009685,0,0,0,90.00000001 +318.86,50.30085681,-2.76245275,10500,0,200.0009685,0,0,0,90.00000001 +318.87,50.30085681,-2.762424725,10500,0,199.9998535,0,0,0,90.00000001 +318.88,50.30085681,-2.7623967,10500,0,199.9989614,0,0,0,90.00000001 +318.89,50.30085681,-2.762368675,10500,0,199.9989614,0,0,0,90.00000001 +318.9,50.30085681,-2.76234065,10500,0,199.9998535,0,0,0,90.00000001 +318.91,50.30085681,-2.762312625,10500,0,200.0009685,0,0,0,90.00000001 +318.92,50.30085681,-2.762284599,10500,0,200.0009685,0,0,0,90.00000001 +318.93,50.30085681,-2.762256574,10500,0,199.9998535,0,0,0,90.00000001 +318.94,50.30085681,-2.762228549,10500,0,199.9989614,0,0,0,90.00000001 +318.95,50.30085681,-2.762200524,10500,0,199.9989614,0,0,0,90.00000001 +318.96,50.30085681,-2.762172499,10500,0,199.9998535,0,0,0,90.00000001 +318.97,50.30085681,-2.762144474,10500,0,200.0009685,0,0,0,90.00000001 +318.98,50.30085681,-2.762116448,10500,0,200.0009685,0,0,0,90.00000001 +318.99,50.30085681,-2.762088423,10500,0,199.9998535,0,0,0,90.00000001 +319,50.30085681,-2.762060398,10500,0,199.9989614,0,0,0,90.00000001 +319.01,50.30085681,-2.762032373,10500,0,199.9989614,0,0,0,90.00000001 +319.02,50.30085681,-2.762004348,10500,0,199.9998535,0,0,0,90.00000001 +319.03,50.30085681,-2.761976323,10500,0,200.0009685,0,0,0,90.00000001 +319.04,50.30085681,-2.761948297,10500,0,200.0009685,0,0,0,90.00000001 +319.05,50.30085681,-2.761920272,10500,0,199.9998535,0,0,0,90.00000001 +319.06,50.30085681,-2.761892247,10500,0,199.9991844,0,0,0,90.00000001 +319.07,50.30085681,-2.761864222,10500,0,199.9998535,0,0,0,90.00000001 +319.08,50.30085681,-2.761836197,10500,0,200.0009685,0,0,0,90.00000001 +319.09,50.30085681,-2.761808171,10500,0,200.0009685,0,0,0,90.00000001 +319.1,50.30085681,-2.761780146,10500,0,199.9998535,0,0,0,90.00000001 +319.11,50.30085681,-2.761752121,10500,0,199.9991844,0,0,0,90.00000001 +319.12,50.30085681,-2.761724096,10500,0,199.9998535,0,0,0,90.00000001 +319.13,50.30085681,-2.761696071,10500,0,200.0009685,0,0,0,90.00000001 +319.14,50.30085681,-2.761668045,10500,0,200.0009685,0,0,0,90.00000001 +319.15,50.30085681,-2.76164002,10500,0,199.9998535,0,0,0,90.00000001 +319.16,50.30085681,-2.761611995,10500,0,199.9991844,0,0,0,90.00000001 +319.17,50.30085681,-2.76158397,10500,0,199.9998535,0,0,0,90.00000001 +319.18,50.30085681,-2.761555945,10500,0,200.0009685,0,0,0,90.00000001 +319.19,50.30085681,-2.761527919,10500,0,200.0009685,0,0,0,90.00000001 +319.2,50.30085681,-2.761499894,10500,0,199.9998535,0,0,0,90.00000001 +319.21,50.30085681,-2.761471869,10500,0,199.9991844,0,0,0,90.00000001 +319.22,50.30085681,-2.761443844,10500,0,199.9998535,0,0,0,90.00000001 +319.23,50.30085681,-2.761415819,10500,0,200.0009685,0,0,0,90.00000001 +319.24,50.30085681,-2.761387793,10500,0,200.0009685,0,0,0,90.00000001 +319.25,50.30085681,-2.761359768,10500,0,199.9998535,0,0,0,90.00000001 +319.26,50.30085681,-2.761331743,10500,0,199.9991844,0,0,0,90.00000001 +319.27,50.30085681,-2.761303718,10500,0,199.9998535,0,0,0,90.00000001 +319.28,50.30085681,-2.761275693,10500,0,200.0009685,0,0,0,90.00000001 +319.29,50.30085681,-2.761247667,10500,0,200.0009685,0,0,0,90.00000001 +319.3,50.30085681,-2.761219642,10500,0,199.9998535,0,0,0,90.00000001 +319.31,50.30085681,-2.761191617,10500,0,199.9989614,0,0,0,90.00000001 +319.32,50.30085681,-2.761163592,10500,0,199.9987384,0,0,0,90.00000001 +319.33,50.30085681,-2.761135567,10500,0,199.9989614,0,0,0,90.00000001 +319.34,50.30085681,-2.761107542,10500,0,199.9998535,0,0,0,90.00000001 +319.35,50.30085681,-2.761079517,10500,0,200.0009685,0,0,0,90.00000001 +319.36,50.30085681,-2.761051491,10500,0,200.0009685,0,0,0,90.00000001 +319.37,50.30085681,-2.761023466,10500,0,199.9998535,0,0,0,90.00000001 +319.38,50.30085681,-2.760995441,10500,0,199.9989614,0,0,0,90.00000001 +319.39,50.30085681,-2.760967416,10500,0,199.9989614,0,0,0,90.00000001 +319.4,50.30085681,-2.760939391,10500,0,199.9998535,0,0,0,90.00000001 +319.41,50.30085681,-2.760911366,10500,0,200.0009685,0,0,0,90.00000001 +319.42,50.30085681,-2.76088334,10500,0,200.0009685,0,0,0,90.00000001 +319.43,50.30085681,-2.760855315,10500,0,199.9998535,0,0,0,90.00000001 +319.44,50.30085681,-2.76082729,10500,0,199.9989614,0,0,0,90.00000001 +319.45,50.30085681,-2.760799265,10500,0,199.9989614,0,0,0,90.00000001 +319.46,50.30085681,-2.76077124,10500,0,199.9998535,0,0,0,90.00000001 +319.47,50.30085681,-2.760743215,10500,0,200.0009685,0,0,0,90.00000001 +319.48,50.30085681,-2.760715189,10500,0,200.0009685,0,0,0,90.00000001 +319.49,50.30085681,-2.760687164,10500,0,199.9998535,0,0,0,90.00000001 +319.5,50.30085681,-2.760659139,10500,0,199.9989614,0,0,0,90.00000001 +319.51,50.30085681,-2.760631114,10500,0,199.9989614,0,0,0,90.00000001 +319.52,50.30085681,-2.760603089,10500,0,199.9998535,0,0,0,90.00000001 +319.53,50.30085681,-2.760575064,10500,0,200.0009685,0,0,0,90.00000001 +319.54,50.30085681,-2.760547038,10500,0,200.0009685,0,0,0,90.00000001 +319.55,50.30085681,-2.760519013,10500,0,199.9998535,0,0,0,90.00000001 +319.56,50.30085681,-2.760490988,10500,0,199.9989614,0,0,0,90.00000001 +319.57,50.30085681,-2.760462963,10500,0,199.9987384,0,0,0,90.00000001 +319.58,50.30085681,-2.760434938,10500,0,199.9989614,0,0,0,90.00000001 +319.59,50.30085681,-2.760406913,10500,0,199.9998535,0,0,0,90.00000001 +319.6,50.30085681,-2.760378888,10500,0,200.0009685,0,0,0,90.00000001 +319.61,50.30085681,-2.760350862,10500,0,200.0009685,0,0,0,90.00000001 +319.62,50.30085681,-2.760322837,10500,0,199.9998535,0,0,0,90.00000001 +319.63,50.30085681,-2.760294812,10500,0,199.9991844,0,0,0,90.00000001 +319.64,50.30085681,-2.760266787,10500,0,199.9998535,0,0,0,90.00000001 +319.65,50.30085681,-2.760238762,10500,0,200.0009685,0,0,0,90.00000001 +319.66,50.30085681,-2.760210736,10500,0,200.0009685,0,0,0,90.00000001 +319.67,50.30085681,-2.760182711,10500,0,199.9998535,0,0,0,90.00000001 +319.68,50.30085681,-2.760154686,10500,0,199.9991844,0,0,0,90.00000001 +319.69,50.30085681,-2.760126661,10500,0,199.9998535,0,0,0,90.00000001 +319.7,50.30085681,-2.760098636,10500,0,200.0009685,0,0,0,90.00000001 +319.71,50.30085681,-2.76007061,10500,0,200.0009685,0,0,0,90.00000001 +319.72,50.30085681,-2.760042585,10500,0,199.9998535,0,0,0,90.00000001 +319.73,50.30085681,-2.76001456,10500,0,199.9991844,0,0,0,90.00000001 +319.74,50.30085681,-2.759986535,10500,0,199.9998535,0,0,0,90.00000001 +319.75,50.30085681,-2.75995851,10500,0,200.0009685,0,0,0,90.00000001 +319.76,50.30085681,-2.759930484,10500,0,200.0009685,0,0,0,90.00000001 +319.77,50.30085681,-2.759902459,10500,0,199.9998535,0,0,0,90.00000001 +319.78,50.30085681,-2.759874434,10500,0,199.9991844,0,0,0,90.00000001 +319.79,50.30085681,-2.759846409,10500,0,199.9998535,0,0,0,90.00000001 +319.8,50.30085681,-2.759818384,10500,0,200.0009685,0,0,0,90.00000001 +319.81,50.30085681,-2.759790358,10500,0,200.0009685,0,0,0,90.00000001 +319.82,50.30085681,-2.759762333,10500,0,199.9998535,0,0,0,90.00000001 +319.83,50.30085681,-2.759734308,10500,0,199.9991844,0,0,0,90.00000001 +319.84,50.30085681,-2.759706283,10500,0,199.9998535,0,0,0,90.00000001 +319.85,50.30085681,-2.759678258,10500,0,200.0009685,0,0,0,90.00000001 +319.86,50.30085681,-2.759650232,10500,0,200.0009685,0,0,0,90.00000001 +319.87,50.30085681,-2.759622207,10500,0,199.9998535,0,0,0,90.00000001 +319.88,50.30085681,-2.759594182,10500,0,199.9989614,0,0,0,90.00000001 +319.89,50.30085681,-2.759566157,10500,0,199.9989614,0,0,0,90.00000001 +319.9,50.30085681,-2.759538132,10500,0,199.9998535,0,0,0,90.00000001 +319.91,50.30085681,-2.759510107,10500,0,200.0009685,0,0,0,90.00000001 +319.92,50.30085681,-2.759482081,10500,0,200.0009685,0,0,0,90.00000001 +319.93,50.30085681,-2.759454056,10500,0,199.9998535,0,0,0,90.00000001 +319.94,50.30085681,-2.759426031,10500,0,199.9989614,0,0,0,90.00000001 +319.95,50.30085681,-2.759398006,10500,0,199.9989614,0,0,0,90.00000001 +319.96,50.30085681,-2.759369981,10500,0,199.9998535,0,0,0,90.00000001 +319.97,50.30085681,-2.759341956,10500,0,200.0009685,0,0,0,90.00000001 +319.98,50.30085681,-2.75931393,10500,0,200.0009685,0,0,0,90.00000001 +319.99,50.30085681,-2.759285905,10500,0,199.9998535,0,0,0,90.00000001 +320,50.30085681,-2.75925788,10500,0,199.9989614,0,0,0,90.00000001 +320.01,50.30085681,-2.759229855,10500,0,199.9989614,0,0,0,90.00000001 +320.02,50.30085681,-2.75920183,10500,0,199.9998535,0,0,0,90.00000001 +320.03,50.30085681,-2.759173805,10500,0,200.0009685,0,0,0,90.00000001 +320.04,50.30085681,-2.759145779,10500,0,200.0009685,0,0,0,90.00000001 +320.05,50.30085681,-2.759117754,10500,0,199.9998535,0,0,0,90.00000001 +320.06,50.30085681,-2.759089729,10500,0,199.9989614,0,0,0,90.00000001 +320.07,50.30085681,-2.759061704,10500,0,199.9989614,0,0,0,90.00000001 +320.08,50.30085681,-2.759033679,10500,0,199.9998535,0,0,0,90.00000001 +320.09,50.30085681,-2.759005654,10500,0,200.0009685,0,0,0,90.00000001 +320.1,50.30085681,-2.758977628,10500,0,200.0009685,0,0,0,90.00000001 +320.11,50.30085681,-2.758949603,10500,0,199.9998535,0,0,0,90.00000001 +320.12,50.30085681,-2.758921578,10500,0,199.9989614,0,0,0,90.00000001 +320.13,50.30085681,-2.758893553,10500,0,199.9987384,0,0,0,90.00000001 +320.14,50.30085681,-2.758865528,10500,0,199.9989614,0,0,0,90.00000001 +320.15,50.30085681,-2.758837503,10500,0,199.9998535,0,0,0,90.00000001 +320.16,50.30085681,-2.758809478,10500,0,200.0009685,0,0,0,90.00000001 +320.17,50.30085681,-2.758781452,10500,0,200.0009685,0,0,0,90.00000001 +320.18,50.30085681,-2.758753427,10500,0,199.9998535,0,0,0,90.00000001 +320.19,50.30085681,-2.758725402,10500,0,199.9989614,0,0,0,90.00000001 +320.2,50.30085681,-2.758697377,10500,0,199.9989614,0,0,0,90.00000001 +320.21,50.30085681,-2.758669352,10500,0,199.9998535,0,0,0,90.00000001 +320.22,50.30085681,-2.758641327,10500,0,200.0009685,0,0,0,90.00000001 +320.23,50.30085681,-2.758613301,10500,0,200.0009685,0,0,0,90.00000001 +320.24,50.30085681,-2.758585276,10500,0,199.9998535,0,0,0,90.00000001 +320.25,50.30085681,-2.758557251,10500,0,199.9991844,0,0,0,90.00000001 +320.26,50.30085681,-2.758529226,10500,0,199.9998535,0,0,0,90.00000001 +320.27,50.30085681,-2.758501201,10500,0,200.0009685,0,0,0,90.00000001 +320.28,50.30085681,-2.758473175,10500,0,200.0009685,0,0,0,90.00000001 +320.29,50.30085681,-2.75844515,10500,0,199.9998535,0,0,0,90.00000001 +320.3,50.30085681,-2.758417125,10500,0,199.9991844,0,0,0,90.00000001 +320.31,50.30085681,-2.7583891,10500,0,199.9998535,0,0,0,90.00000001 +320.32,50.30085681,-2.758361075,10500,0,200.0009685,0,0,0,90.00000001 +320.33,50.30085681,-2.758333049,10500,0,200.0009685,0,0,0,90.00000001 +320.34,50.30085681,-2.758305024,10500,0,199.9998535,0,0,0,90.00000001 +320.35,50.30085681,-2.758276999,10500,0,199.9991844,0,0,0,90.00000001 +320.36,50.30085681,-2.758248974,10500,0,199.9998535,0,0,0,90.00000001 +320.37,50.30085681,-2.758220949,10500,0,200.0009685,0,0,0,90.00000001 +320.38,50.30085681,-2.758192923,10500,0,200.0009685,0,0,0,90.00000001 +320.39,50.30085681,-2.758164898,10500,0,199.9998535,0,0,0,90.00000001 +320.4,50.30085681,-2.758136873,10500,0,199.9991844,0,0,0,90.00000001 +320.41,50.30085681,-2.758108848,10500,0,199.9998535,0,0,0,90.00000001 +320.42,50.30085681,-2.758080823,10500,0,200.0009685,0,0,0,90.00000001 +320.43,50.30085681,-2.758052797,10500,0,200.0009685,0,0,0,90.00000001 +320.44,50.30085681,-2.758024772,10500,0,199.9998535,0,0,0,90.00000001 +320.45,50.30085681,-2.757996747,10500,0,199.9991844,0,0,0,90.00000001 +320.46,50.30085681,-2.757968722,10500,0,199.9998535,0,0,0,90.00000001 +320.47,50.30085681,-2.757940697,10500,0,200.0009685,0,0,0,90.00000001 +320.48,50.30085681,-2.757912671,10500,0,200.0009685,0,0,0,90.00000001 +320.49,50.30085681,-2.757884646,10500,0,199.9998535,0,0,0,90.00000001 +320.5,50.30085681,-2.757856621,10500,0,199.9989614,0,0,0,90.00000001 +320.51,50.30085681,-2.757828596,10500,0,199.9989614,0,0,0,90.00000001 +320.52,50.30085681,-2.757800571,10500,0,199.9998535,0,0,0,90.00000001 +320.53,50.30085681,-2.757772546,10500,0,200.0009685,0,0,0,90.00000001 +320.54,50.30085681,-2.75774452,10500,0,200.0009685,0,0,0,90.00000001 +320.55,50.30085681,-2.757716495,10500,0,199.9998535,0,0,0,90.00000001 +320.56,50.30085681,-2.75768847,10500,0,199.9989614,0,0,0,90.00000001 +320.57,50.30085681,-2.757660445,10500,0,199.9989614,0,0,0,90.00000001 +320.58,50.30085681,-2.75763242,10500,0,199.9998535,0,0,0,90.00000001 +320.59,50.30085681,-2.757604395,10500,0,200.0009685,0,0,0,90.00000001 +320.6,50.30085681,-2.757576369,10500,0,200.0009685,0,0,0,90.00000001 +320.61,50.30085681,-2.757548344,10500,0,199.9998535,0,0,0,90.00000001 +320.62,50.30085681,-2.757520319,10500,0,199.9989614,0,0,0,90.00000001 +320.63,50.30085681,-2.757492294,10500,0,199.9989614,0,0,0,90.00000001 +320.64,50.30085681,-2.757464269,10500,0,199.9998535,0,0,0,90.00000001 +320.65,50.30085681,-2.757436244,10500,0,200.0009685,0,0,0,90.00000001 +320.66,50.30085681,-2.757408218,10500,0,200.0009685,0,0,0,90.00000001 +320.67,50.30085681,-2.757380193,10500,0,199.9998535,0,0,0,90.00000001 +320.68,50.30085681,-2.757352168,10500,0,199.9989614,0,0,0,90.00000001 +320.69,50.30085681,-2.757324143,10500,0,199.9989614,0,0,0,90.00000001 +320.7,50.30085681,-2.757296118,10500,0,199.9998535,0,0,0,90.00000001 +320.71,50.30085681,-2.757268093,10500,0,200.0009685,0,0,0,90.00000001 +320.72,50.30085681,-2.757240067,10500,0,200.0009685,0,0,0,90.00000001 +320.73,50.30085681,-2.757212042,10500,0,199.9998535,0,0,0,90.00000001 +320.74,50.30085681,-2.757184017,10500,0,199.9989614,0,0,0,90.00000001 +320.75,50.30085681,-2.757155992,10500,0,199.9987384,0,0,0,90.00000001 +320.76,50.30085681,-2.757127967,10500,0,199.9989614,0,0,0,90.00000001 +320.77,50.30085681,-2.757099942,10500,0,199.9998535,0,0,0,90.00000001 +320.78,50.30085681,-2.757071917,10500,0,200.0009685,0,0,0,90.00000001 +320.79,50.30085681,-2.757043891,10500,0,200.0009685,0,0,0,90.00000001 +320.8,50.30085681,-2.757015866,10500,0,199.9998535,0,0,0,90.00000001 +320.81,50.30085681,-2.756987841,10500,0,199.9989614,0,0,0,90.00000001 +320.82,50.30085681,-2.756959816,10500,0,199.9989614,0,0,0,90.00000001 +320.83,50.30085681,-2.756931791,10500,0,199.9998535,0,0,0,90.00000001 +320.84,50.30085681,-2.756903766,10500,0,200.0009685,0,0,0,90.00000001 +320.85,50.30085681,-2.75687574,10500,0,200.0009685,0,0,0,90.00000001 +320.86,50.30085681,-2.756847715,10500,0,199.9998535,0,0,0,90.00000001 +320.87,50.30085681,-2.75681969,10500,0,199.9991844,0,0,0,90.00000001 +320.88,50.30085681,-2.756791665,10500,0,199.9998535,0,0,0,90.00000001 +320.89,50.30085681,-2.75676364,10500,0,200.0009685,0,0,0,90.00000001 +320.9,50.30085681,-2.756735614,10500,0,200.0009685,0,0,0,90.00000001 +320.91,50.30085681,-2.756707589,10500,0,199.9998535,0,0,0,90.00000001 +320.92,50.30085681,-2.756679564,10500,0,199.9989614,0,0,0,90.00000001 +320.93,50.30085681,-2.756651539,10500,0,199.9989614,0,0,0,90.00000001 +320.94,50.30085681,-2.756623514,10500,0,199.9998535,0,0,0,90.00000001 +320.95,50.30085681,-2.756595489,10500,0,200.0009685,0,0,0,90.00000001 +320.96,50.30085681,-2.756567463,10500,0,200.0009685,0,0,0,90.00000001 +320.97,50.30085681,-2.756539438,10500,0,199.9998535,0,0,0,90.00000001 +320.98,50.30085681,-2.756511413,10500,0,199.9991844,0,0,0,90.00000001 +320.99,50.30085681,-2.756483388,10500,0,199.9998535,0,0,0,90.00000001 +321,50.30085681,-2.756455363,10500,0,200.0009685,0,0,0,90.00000001 +321.01,50.30085681,-2.756427337,10500,0,200.0009685,0,0,0,90.00000001 +321.02,50.30085681,-2.756399312,10500,0,199.9998535,0,0,0,90.00000001 +321.03,50.30085681,-2.756371287,10500,0,199.9991844,0,0,0,90.00000001 +321.04,50.30085681,-2.756343262,10500,0,199.9998535,0,0,0,90.00000001 +321.05,50.30085681,-2.756315237,10500,0,200.0009685,0,0,0,90.00000001 +321.06,50.30085681,-2.756287211,10500,0,200.0009685,0,0,0,90.00000001 +321.07,50.30085681,-2.756259186,10500,0,199.9998535,0,0,0,90.00000001 +321.08,50.30085681,-2.756231161,10500,0,199.9991844,0,0,0,90.00000001 +321.09,50.30085681,-2.756203136,10500,0,199.9998535,0,0,0,90.00000001 +321.1,50.30085681,-2.756175111,10500,0,200.0009685,0,0,0,90.00000001 +321.11,50.30085681,-2.756147085,10500,0,200.0009685,0,0,0,90.00000001 +321.12,50.30085681,-2.75611906,10500,0,199.9998535,0,0,0,90.00000001 +321.13,50.30085681,-2.756091035,10500,0,199.9991844,0,0,0,90.00000001 +321.14,50.30085681,-2.75606301,10500,0,199.9998535,0,0,0,90.00000001 +321.15,50.30085681,-2.756034985,10500,0,200.0009685,0,0,0,90.00000001 +321.16,50.30085681,-2.756006959,10500,0,200.0009685,0,0,0,90.00000001 +321.17,50.30085681,-2.755978934,10500,0,199.9998535,0,0,0,90.00000001 +321.18,50.30085681,-2.755950909,10500,0,199.9989614,0,0,0,90.00000001 +321.19,50.30085681,-2.755922884,10500,0,199.9989614,0,0,0,90.00000001 +321.2,50.30085681,-2.755894859,10500,0,199.9998535,0,0,0,90.00000001 +321.21,50.30085681,-2.755866834,10500,0,200.0009685,0,0,0,90.00000001 +321.22,50.30085681,-2.755838808,10500,0,200.0009685,0,0,0,90.00000001 +321.23,50.30085681,-2.755810783,10500,0,199.9998535,0,0,0,90.00000001 +321.24,50.30085681,-2.755782758,10500,0,199.9989614,0,0,0,90.00000001 +321.25,50.30085681,-2.755754733,10500,0,199.9989614,0,0,0,90.00000001 +321.26,50.30085681,-2.755726708,10500,0,199.9998535,0,0,0,90.00000001 +321.27,50.30085681,-2.755698683,10500,0,200.0009685,0,0,0,90.00000001 +321.28,50.30085681,-2.755670657,10500,0,200.0009685,0,0,0,90.00000001 +321.29,50.30085681,-2.755642632,10500,0,199.9998535,0,0,0,90.00000001 +321.3,50.30085681,-2.755614607,10500,0,199.9989614,0,0,0,90.00000001 +321.31,50.30085681,-2.755586582,10500,0,199.9987384,0,0,0,90.00000001 +321.32,50.30085681,-2.755558557,10500,0,199.9989614,0,0,0,90.00000001 +321.33,50.30085681,-2.755530532,10500,0,199.9998535,0,0,0,90.00000001 +321.34,50.30085681,-2.755502507,10500,0,200.0009685,0,0,0,90.00000001 +321.35,50.30085681,-2.755474481,10500,0,200.0009685,0,0,0,90.00000001 +321.36,50.30085681,-2.755446456,10500,0,199.9998535,0,0,0,90.00000001 +321.37,50.30085681,-2.755418431,10500,0,199.9989614,0,0,0,90.00000001 +321.38,50.30085681,-2.755390406,10500,0,199.9989614,0,0,0,90.00000001 +321.39,50.30085681,-2.755362381,10500,0,199.9998535,0,0,0,90.00000001 +321.4,50.30085681,-2.755334356,10500,0,200.0009685,0,0,0,90.00000001 +321.41,50.30085681,-2.75530633,10500,0,200.0009685,0,0,0,90.00000001 +321.42,50.30085681,-2.755278305,10500,0,199.9998535,0,0,0,90.00000001 +321.43,50.30085681,-2.75525028,10500,0,199.9989614,0,0,0,90.00000001 +321.44,50.30085681,-2.755222255,10500,0,199.9989614,0,0,0,90.00000001 +321.45,50.30085681,-2.75519423,10500,0,199.9998535,0,0,0,90.00000001 +321.46,50.30085681,-2.755166205,10500,0,200.0009685,0,0,0,90.00000001 +321.47,50.30085681,-2.755138179,10500,0,200.0009685,0,0,0,90.00000001 +321.48,50.30085681,-2.755110154,10500,0,199.9998535,0,0,0,90.00000001 +321.49,50.30085681,-2.755082129,10500,0,199.9989614,0,0,0,90.00000001 +321.5,50.30085681,-2.755054104,10500,0,199.9989614,0,0,0,90.00000001 +321.51,50.30085681,-2.755026079,10500,0,199.9998535,0,0,0,90.00000001 +321.52,50.30085681,-2.754998054,10500,0,200.0009685,0,0,0,90.00000001 +321.53,50.30085681,-2.754970028,10500,0,200.0009685,0,0,0,90.00000001 +321.54,50.30085681,-2.754942003,10500,0,199.9998535,0,0,0,90.00000001 +321.55,50.30085681,-2.754913978,10500,0,199.9991844,0,0,0,90.00000001 +321.56,50.30085681,-2.754885953,10500,0,199.9998535,0,0,0,90.00000001 +321.57,50.30085681,-2.754857928,10500,0,200.0009685,0,0,0,90.00000001 +321.58,50.30085681,-2.754829902,10500,0,200.0009685,0,0,0,90.00000001 +321.59,50.30085681,-2.754801877,10500,0,199.9998535,0,0,0,90.00000001 +321.6,50.30085681,-2.754773852,10500,0,199.9991844,0,0,0,90.00000001 +321.61,50.30085681,-2.754745827,10500,0,199.9998535,0,0,0,90.00000001 +321.62,50.30085681,-2.754717802,10500,0,200.0009685,0,0,0,90.00000001 +321.63,50.30085681,-2.754689776,10500,0,200.0009685,0,0,0,90.00000001 +321.64,50.30085681,-2.754661751,10500,0,199.9998535,0,0,0,90.00000001 +321.65,50.30085681,-2.754633726,10500,0,199.9991844,0,0,0,90.00000001 +321.66,50.30085681,-2.754605701,10500,0,199.9998535,0,0,0,90.00000001 +321.67,50.30085681,-2.754577676,10500,0,200.0009685,0,0,0,90.00000001 +321.68,50.30085681,-2.75454965,10500,0,200.0009685,0,0,0,90.00000001 +321.69,50.30085681,-2.754521625,10500,0,199.9998535,0,0,0,90.00000001 +321.7,50.30085681,-2.7544936,10500,0,199.9991844,0,0,0,90.00000001 +321.71,50.30085681,-2.754465575,10500,0,199.9998535,0,0,0,90.00000001 +321.72,50.30085681,-2.75443755,10500,0,200.0009685,0,0,0,90.00000001 +321.73,50.30085681,-2.754409524,10500,0,200.0009685,0,0,0,90.00000001 +321.74,50.30085681,-2.754381499,10500,0,199.9998535,0,0,0,90.00000001 +321.75,50.30085681,-2.754353474,10500,0,199.9991844,0,0,0,90.00000001 +321.76,50.30085681,-2.754325449,10500,0,199.9998535,0,0,0,90.00000001 +321.77,50.30085681,-2.754297424,10500,0,200.0009685,0,0,0,90.00000001 +321.78,50.30085681,-2.754269398,10500,0,200.0009685,0,0,0,90.00000001 +321.79,50.30085681,-2.754241373,10500,0,199.9998535,0,0,0,90.00000001 +321.8,50.30085681,-2.754213348,10500,0,199.9989614,0,0,0,90.00000001 +321.81,50.30085681,-2.754185323,10500,0,199.9989614,0,0,0,90.00000001 +321.82,50.30085681,-2.754157298,10500,0,199.9998535,0,0,0,90.00000001 +321.83,50.30085681,-2.754129273,10500,0,200.0009685,0,0,0,90.00000001 +321.84,50.30085681,-2.754101247,10500,0,200.0009685,0,0,0,90.00000001 +321.85,50.30085681,-2.754073222,10500,0,199.9998535,0,0,0,90.00000001 +321.86,50.30085681,-2.754045197,10500,0,199.9989614,0,0,0,90.00000001 +321.87,50.30085681,-2.754017172,10500,0,199.9987384,0,0,0,90.00000001 +321.88,50.30085681,-2.753989147,10500,0,199.9989614,0,0,0,90.00000001 +321.89,50.30085681,-2.753961122,10500,0,199.9998535,0,0,0,90.00000001 +321.9,50.30085681,-2.753933097,10500,0,200.0009685,0,0,0,90.00000001 +321.91,50.30085681,-2.753905071,10500,0,200.0009685,0,0,0,90.00000001 +321.92,50.30085681,-2.753877046,10500,0,199.9998535,0,0,0,90.00000001 +321.93,50.30085681,-2.753849021,10500,0,199.9989614,0,0,0,90.00000001 +321.94,50.30085681,-2.753820996,10500,0,199.9989614,0,0,0,90.00000001 +321.95,50.30085681,-2.753792971,10500,0,199.9998535,0,0,0,90.00000001 +321.96,50.30085681,-2.753764946,10500,0,200.0009685,0,0,0,90.00000001 +321.97,50.30085681,-2.75373692,10500,0,200.0009685,0,0,0,90.00000001 +321.98,50.30085681,-2.753708895,10500,0,199.9998535,0,0,0,90.00000001 +321.99,50.30085681,-2.75368087,10500,0,199.9989614,0,0,0,90.00000001 +322,50.30085681,-2.753652845,10500,0,199.9989614,0,0,0,90.00000001 +322.01,50.30085681,-2.75362482,10500,0,199.9998535,0,0,0,90.00000001 +322.02,50.30085681,-2.753596795,10500,0,200.0009685,0,0,0,90.00000001 +322.03,50.30085681,-2.753568769,10500,0,200.0009685,0,0,0,90.00000001 +322.04,50.30085681,-2.753540744,10500,0,199.9998535,0,0,0,90.00000001 +322.05,50.30085681,-2.753512719,10500,0,199.9989614,0,0,0,90.00000001 +322.06,50.30085681,-2.753484694,10500,0,199.9989614,0,0,0,90.00000001 +322.07,50.30085681,-2.753456669,10500,0,199.9998535,0,0,0,90.00000001 +322.08,50.30085681,-2.753428644,10500,0,200.0009685,0,0,0,90.00000001 +322.09,50.30085681,-2.753400618,10500,0,200.0009685,0,0,0,90.00000001 +322.1,50.30085681,-2.753372593,10500,0,199.9998535,0,0,0,90.00000001 +322.11,50.30085681,-2.753344568,10500,0,199.9989614,0,0,0,90.00000001 +322.12,50.30085681,-2.753316543,10500,0,199.9989614,0,0,0,90.00000001 +322.13,50.30085681,-2.753288518,10500,0,199.9998535,0,0,0,90.00000001 +322.14,50.30085681,-2.753260493,10500,0,200.0009685,0,0,0,90.00000001 +322.15,50.30085681,-2.753232467,10500,0,200.0009685,0,0,0,90.00000001 +322.16,50.30085681,-2.753204442,10500,0,199.9998535,0,0,0,90.00000001 +322.17,50.30085681,-2.753176417,10500,0,199.9991844,0,0,0,90.00000001 +322.18,50.30085681,-2.753148392,10500,0,199.9998535,0,0,0,90.00000001 +322.19,50.30085681,-2.753120367,10500,0,200.0009685,0,0,0,90.00000001 +322.2,50.30085681,-2.753092341,10500,0,200.0009685,0,0,0,90.00000001 +322.21,50.30085681,-2.753064316,10500,0,199.9998535,0,0,0,90.00000001 +322.22,50.30085681,-2.753036291,10500,0,199.9991844,0,0,0,90.00000001 +322.23,50.30085681,-2.753008266,10500,0,199.9998535,0,0,0,90.00000001 +322.24,50.30085681,-2.752980241,10500,0,200.0009685,0,0,0,90.00000001 +322.25,50.30085681,-2.752952215,10500,0,200.0009685,0,0,0,90.00000001 +322.26,50.30085681,-2.75292419,10500,0,199.9998535,0,0,0,90.00000001 +322.27,50.30085681,-2.752896165,10500,0,199.9991844,0,0,0,90.00000001 +322.28,50.30085681,-2.75286814,10500,0,199.9998535,0,0,0,90.00000001 +322.29,50.30085681,-2.752840115,10500,0,200.0009685,0,0,0,90.00000001 +322.3,50.30085681,-2.752812089,10500,0,200.0009685,0,0,0,90.00000001 +322.31,50.30085681,-2.752784064,10500,0,199.9998535,0,0,0,90.00000001 +322.32,50.30085681,-2.752756039,10500,0,199.9991844,0,0,0,90.00000001 +322.33,50.30085681,-2.752728014,10500,0,199.9998535,0,0,0,90.00000001 +322.34,50.30085681,-2.752699989,10500,0,200.0009685,0,0,0,90.00000001 +322.35,50.30085681,-2.752671963,10500,0,200.0009685,0,0,0,90.00000001 +322.36,50.30085681,-2.752643938,10500,0,199.9998535,0,0,0,90.00000001 +322.37,50.30085681,-2.752615913,10500,0,199.9991844,0,0,0,90.00000001 +322.38,50.30085681,-2.752587888,10500,0,199.9998535,0,0,0,90.00000001 +322.39,50.30085681,-2.752559863,10500,0,200.0009685,0,0,0,90.00000001 +322.4,50.30085681,-2.752531837,10500,0,200.0009685,0,0,0,90.00000001 +322.41,50.30085681,-2.752503812,10500,0,199.9998535,0,0,0,90.00000001 +322.42,50.30085681,-2.752475787,10500,0,199.9989614,0,0,0,90.00000001 +322.43,50.30085681,-2.752447762,10500,0,199.9987384,0,0,0,90.00000001 +322.44,50.30085681,-2.752419737,10500,0,199.9989614,0,0,0,90.00000001 +322.45,50.30085681,-2.752391712,10500,0,199.9998535,0,0,0,90.00000001 +322.46,50.30085681,-2.752363687,10500,0,200.0009685,0,0,0,90.00000001 +322.47,50.30085681,-2.752335661,10500,0,200.0009685,0,0,0,90.00000001 +322.48,50.30085681,-2.752307636,10500,0,199.9998535,0,0,0,90.00000001 +322.49,50.30085681,-2.752279611,10500,0,199.9989614,0,0,0,90.00000001 +322.5,50.30085681,-2.752251586,10500,0,199.9989614,0,0,0,90.00000001 +322.51,50.30085681,-2.752223561,10500,0,199.9998535,0,0,0,90.00000001 +322.52,50.30085681,-2.752195536,10500,0,200.0009685,0,0,0,90.00000001 +322.53,50.30085681,-2.75216751,10500,0,200.0009685,0,0,0,90.00000001 +322.54,50.30085681,-2.752139485,10500,0,199.9998535,0,0,0,90.00000001 +322.55,50.30085681,-2.75211146,10500,0,199.9989614,0,0,0,90.00000001 +322.56,50.30085681,-2.752083435,10500,0,199.9989614,0,0,0,90.00000001 +322.57,50.30085681,-2.75205541,10500,0,199.9998535,0,0,0,90.00000001 +322.58,50.30085681,-2.752027385,10500,0,200.0009685,0,0,0,90.00000001 +322.59,50.30085681,-2.751999359,10500,0,200.0009685,0,0,0,90.00000001 +322.6,50.30085681,-2.751971334,10500,0,199.9998535,0,0,0,90.00000001 +322.61,50.30085681,-2.751943309,10500,0,199.9989614,0,0,0,90.00000001 +322.62,50.30085681,-2.751915284,10500,0,199.9989614,0,0,0,90.00000001 +322.63,50.30085681,-2.751887259,10500,0,199.9998535,0,0,0,90.00000001 +322.64,50.30085681,-2.751859234,10500,0,200.0009685,0,0,0,90.00000001 +322.65,50.30085681,-2.751831208,10500,0,200.0009685,0,0,0,90.00000001 +322.66,50.30085681,-2.751803183,10500,0,199.9998535,0,0,0,90.00000001 +322.67,50.30085681,-2.751775158,10500,0,199.9989614,0,0,0,90.00000001 +322.68,50.30085681,-2.751747133,10500,0,199.9989614,0,0,0,90.00000001 +322.69,50.30085681,-2.751719108,10500,0,199.9998535,0,0,0,90.00000001 +322.7,50.30085681,-2.751691083,10500,0,200.0009685,0,0,0,90.00000001 +322.71,50.30085681,-2.751663057,10500,0,200.0009685,0,0,0,90.00000001 +322.72,50.30085681,-2.751635032,10500,0,199.9998535,0,0,0,90.00000001 +322.73,50.30085681,-2.751607007,10500,0,199.9989614,0,0,0,90.00000001 +322.74,50.30085681,-2.751578982,10500,0,199.9989614,0,0,0,90.00000001 +322.75,50.30085681,-2.751550957,10500,0,199.9998535,0,0,0,90.00000001 +322.76,50.30085681,-2.751522932,10500,0,200.0009685,0,0,0,90.00000001 +322.77,50.30085681,-2.751494906,10500,0,200.0009685,0,0,0,90.00000001 +322.78,50.30085681,-2.751466881,10500,0,199.9998535,0,0,0,90.00000001 +322.79,50.30085681,-2.751438856,10500,0,199.9991844,0,0,0,90.00000001 +322.8,50.30085681,-2.751410831,10500,0,199.9998535,0,0,0,90.00000001 +322.81,50.30085681,-2.751382806,10500,0,200.0009685,0,0,0,90.00000001 +322.82,50.30085681,-2.75135478,10500,0,200.0009685,0,0,0,90.00000001 +322.83,50.30085681,-2.751326755,10500,0,199.9998535,0,0,0,90.00000001 +322.84,50.30085681,-2.75129873,10500,0,199.9991844,0,0,0,90.00000001 +322.85,50.30085681,-2.751270705,10500,0,199.9998535,0,0,0,90.00000001 +322.86,50.30085681,-2.75124268,10500,0,200.0009685,0,0,0,90.00000001 +322.87,50.30085681,-2.751214654,10500,0,200.0009685,0,0,0,90.00000001 +322.88,50.30085681,-2.751186629,10500,0,199.9998535,0,0,0,90.00000001 +322.89,50.30085681,-2.751158604,10500,0,199.9991844,0,0,0,90.00000001 +322.9,50.30085681,-2.751130579,10500,0,199.9998535,0,0,0,90.00000001 +322.91,50.30085681,-2.751102554,10500,0,200.0009685,0,0,0,90.00000001 +322.92,50.30085681,-2.751074528,10500,0,200.0009685,0,0,0,90.00000001 +322.93,50.30085681,-2.751046503,10500,0,199.9998535,0,0,0,90.00000001 +322.94,50.30085681,-2.751018478,10500,0,199.9991844,0,0,0,90.00000001 +322.95,50.30085681,-2.750990453,10500,0,199.9998535,0,0,0,90.00000001 +322.96,50.30085681,-2.750962428,10500,0,200.0009685,0,0,0,90.00000001 +322.97,50.30085681,-2.750934402,10500,0,200.0009685,0,0,0,90.00000001 +322.98,50.30085681,-2.750906377,10500,0,199.9998535,0,0,0,90.00000001 +322.99,50.30085681,-2.750878352,10500,0,199.9989614,0,0,0,90.00000001 +323,50.30085681,-2.750850327,10500,0,199.9989614,0,0,0,90.00000001 +323.01,50.30085681,-2.750822302,10500,0,199.9998535,0,0,0,90.00000001 +323.02,50.30085681,-2.750794277,10500,0,200.0009685,0,0,0,90.00000001 +323.03,50.30085681,-2.750766251,10500,0,200.0009685,0,0,0,90.00000001 +323.04,50.30085681,-2.750738226,10500,0,199.9998535,0,0,0,90.00000001 +323.05,50.30085681,-2.750710201,10500,0,199.9989614,0,0,0,90.00000001 +323.06,50.30085681,-2.750682176,10500,0,199.9989614,0,0,0,90.00000001 +323.07,50.30085681,-2.750654151,10500,0,199.9998535,0,0,0,90.00000001 +323.08,50.30085681,-2.750626126,10500,0,200.0009685,0,0,0,90.00000001 +323.09,50.30085681,-2.7505981,10500,0,200.0009685,0,0,0,90.00000001 +323.1,50.30085681,-2.750570075,10500,0,199.9998535,0,0,0,90.00000001 +323.11,50.30085681,-2.75054205,10500,0,199.9989614,0,0,0,90.00000001 +323.12,50.30085681,-2.750514025,10500,0,199.9989614,0,0,0,90.00000001 +323.13,50.30085681,-2.750486,10500,0,199.9998535,0,0,0,90.00000001 +323.14,50.30085681,-2.750457975,10500,0,200.0009685,0,0,0,90.00000001 +323.15,50.30085681,-2.750429949,10500,0,200.0009685,0,0,0,90.00000001 +323.16,50.30085681,-2.750401924,10500,0,199.9998535,0,0,0,90.00000001 +323.17,50.30085681,-2.750373899,10500,0,199.9989614,0,0,0,90.00000001 +323.18,50.30085681,-2.750345874,10500,0,199.9989614,0,0,0,90.00000001 +323.19,50.30085681,-2.750317849,10500,0,199.9998535,0,0,0,90.00000001 +323.2,50.30085681,-2.750289824,10500,0,200.0009685,0,0,0,90.00000001 +323.21,50.30085681,-2.750261798,10500,0,200.0009685,0,0,0,90.00000001 +323.22,50.30085681,-2.750233773,10500,0,199.9998535,0,0,0,90.00000001 +323.23,50.30085681,-2.750205748,10500,0,199.9989614,0,0,0,90.00000001 +323.24,50.30085681,-2.750177723,10500,0,199.9989614,0,0,0,90.00000001 +323.25,50.30085681,-2.750149698,10500,0,199.9998535,0,0,0,90.00000001 +323.26,50.30085681,-2.750121673,10500,0,200.0009685,0,0,0,90.00000001 +323.27,50.30085681,-2.750093647,10500,0,200.0009685,0,0,0,90.00000001 +323.28,50.30085681,-2.750065622,10500,0,199.9998535,0,0,0,90.00000001 +323.29,50.30085681,-2.750037597,10500,0,199.9989614,0,0,0,90.00000001 +323.3,50.30085681,-2.750009572,10500,0,199.9987384,0,0,0,90.00000001 +323.31,50.30085681,-2.749981547,10500,0,199.9989614,0,0,0,90.00000001 +323.32,50.30085681,-2.749953522,10500,0,199.9998535,0,0,0,90.00000001 +323.33,50.30085681,-2.749925497,10500,0,200.0009685,0,0,0,90.00000001 +323.34,50.30085681,-2.749897471,10500,0,200.0009685,0,0,0,90.00000001 +323.35,50.30085681,-2.749869446,10500,0,199.9998535,0,0,0,90.00000001 +323.36,50.30085681,-2.749841421,10500,0,199.9989614,0,0,0,90.00000001 +323.37,50.30085681,-2.749813396,10500,0,199.9989614,0,0,0,90.00000001 +323.38,50.30085681,-2.749785371,10500,0,199.9998535,0,0,0,90.00000001 +323.39,50.30085681,-2.749757346,10500,0,200.0009685,0,0,0,90.00000001 +323.4,50.30085681,-2.74972932,10500,0,200.0009685,0,0,0,90.00000001 +323.41,50.30085681,-2.749701295,10500,0,199.9998535,0,0,0,90.00000001 +323.42,50.30085681,-2.74967327,10500,0,199.9991844,0,0,0,90.00000001 +323.43,50.30085681,-2.749645245,10500,0,199.9998535,0,0,0,90.00000001 +323.44,50.30085681,-2.74961722,10500,0,200.0009685,0,0,0,90.00000001 +323.45,50.30085681,-2.749589194,10500,0,200.0009685,0,0,0,90.00000001 +323.46,50.30085681,-2.749561169,10500,0,199.9998535,0,0,0,90.00000001 +323.47,50.30085681,-2.749533144,10500,0,199.9991844,0,0,0,90.00000001 +323.48,50.30085681,-2.749505119,10500,0,199.9998535,0,0,0,90.00000001 +323.49,50.30085681,-2.749477094,10500,0,200.0009685,0,0,0,90.00000001 +323.5,50.30085681,-2.749449068,10500,0,200.0009685,0,0,0,90.00000001 +323.51,50.30085681,-2.749421043,10500,0,199.9998535,0,0,0,90.00000001 +323.52,50.30085681,-2.749393018,10500,0,199.9991844,0,0,0,90.00000001 +323.53,50.30085681,-2.749364993,10500,0,199.9998535,0,0,0,90.00000001 +323.54,50.30085681,-2.749336968,10500,0,200.0009685,0,0,0,90.00000001 +323.55,50.30085681,-2.749308942,10500,0,200.0009685,0,0,0,90.00000001 +323.56,50.30085681,-2.749280917,10500,0,199.9998535,0,0,0,90.00000001 +323.57,50.30085681,-2.749252892,10500,0,199.9991844,0,0,0,90.00000001 +323.58,50.30085681,-2.749224867,10500,0,199.9998535,0,0,0,90.00000001 +323.59,50.30085681,-2.749196842,10500,0,200.0009685,0,0,0,90.00000001 +323.6,50.30085681,-2.749168816,10500,0,200.0009685,0,0,0,90.00000001 +323.61,50.30085681,-2.749140791,10500,0,199.9998535,0,0,0,90.00000001 +323.62,50.30085681,-2.749112766,10500,0,199.9991844,0,0,0,90.00000001 +323.63,50.30085681,-2.749084741,10500,0,199.9998535,0,0,0,90.00000001 +323.64,50.30085681,-2.749056716,10500,0,200.0009685,0,0,0,90.00000001 +323.65,50.30085681,-2.74902869,10500,0,200.0009685,0,0,0,90.00000001 +323.66,50.30085681,-2.749000665,10500,0,199.9998535,0,0,0,90.00000001 +323.67,50.30085681,-2.74897264,10500,0,199.9989614,0,0,0,90.00000001 +323.68,50.30085681,-2.748944615,10500,0,199.9989614,0,0,0,90.00000001 +323.69,50.30085681,-2.74891659,10500,0,199.9998535,0,0,0,90.00000001 +323.7,50.30085681,-2.748888565,10500,0,200.0009685,0,0,0,90.00000001 +323.71,50.30085681,-2.748860539,10500,0,200.0009685,0,0,0,90.00000001 +323.72,50.30085681,-2.748832514,10500,0,199.9998535,0,0,0,90.00000001 +323.73,50.30085681,-2.748804489,10500,0,199.9989614,0,0,0,90.00000001 +323.74,50.30085681,-2.748776464,10500,0,199.9989614,0,0,0,90.00000001 +323.75,50.30085681,-2.748748439,10500,0,199.9998535,0,0,0,90.00000001 +323.76,50.30085681,-2.748720414,10500,0,200.0009685,0,0,0,90.00000001 +323.77,50.30085681,-2.748692388,10500,0,200.0009685,0,0,0,90.00000001 +323.78,50.30085681,-2.748664363,10500,0,199.9998535,0,0,0,90.00000001 +323.79,50.30085681,-2.748636338,10500,0,199.9989614,0,0,0,90.00000001 +323.8,50.30085681,-2.748608313,10500,0,199.9989614,0,0,0,90.00000001 +323.81,50.30085681,-2.748580288,10500,0,199.9998535,0,0,0,90.00000001 +323.82,50.30085681,-2.748552263,10500,0,200.0009685,0,0,0,90.00000001 +323.83,50.30085681,-2.748524237,10500,0,200.0009685,0,0,0,90.00000001 +323.84,50.30085681,-2.748496212,10500,0,199.9998535,0,0,0,90.00000001 +323.85,50.30085681,-2.748468187,10500,0,199.9989614,0,0,0,90.00000001 +323.86,50.30085681,-2.748440162,10500,0,199.9987384,0,0,0,90.00000001 +323.87,50.30085681,-2.748412137,10500,0,199.9989614,0,0,0,90.00000001 +323.88,50.30085681,-2.748384112,10500,0,199.9998535,0,0,0,90.00000001 +323.89,50.30085681,-2.748356087,10500,0,200.0009685,0,0,0,90.00000001 +323.9,50.30085681,-2.748328061,10500,0,200.0009685,0,0,0,90.00000001 +323.91,50.30085681,-2.748300036,10500,0,199.9998535,0,0,0,90.00000001 +323.92,50.30085681,-2.748272011,10500,0,199.9989614,0,0,0,90.00000001 +323.93,50.30085681,-2.748243986,10500,0,199.9989614,0,0,0,90.00000001 +323.94,50.30085681,-2.748215961,10500,0,199.9998535,0,0,0,90.00000001 +323.95,50.30085681,-2.748187936,10500,0,200.0009685,0,0,0,90.00000001 +323.96,50.30085681,-2.74815991,10500,0,200.0009685,0,0,0,90.00000001 +323.97,50.30085681,-2.748131885,10500,0,199.9998535,0,0,0,90.00000001 +323.98,50.30085681,-2.74810386,10500,0,199.9989614,0,0,0,90.00000001 +323.99,50.30085681,-2.748075835,10500,0,199.9989614,0,0,0,90.00000001 +324,50.30085681,-2.74804781,10500,0,199.9998535,0,0,0,90.00000001 +324.01,50.30085681,-2.748019785,10500,0,200.0009685,0,0,0,90.00000001 +324.02,50.30085681,-2.747991759,10500,0,200.0009685,0,0,0,90.00000001 +324.03,50.30085681,-2.747963734,10500,0,199.9998535,0,0,0,90.00000001 +324.04,50.30085681,-2.747935709,10500,0,199.9991844,0,0,0,90.00000001 +324.05,50.30085681,-2.747907684,10500,0,199.9998535,0,0,0,90.00000001 +324.06,50.30085681,-2.747879659,10500,0,200.0009685,0,0,0,90.00000001 +324.07,50.30085681,-2.747851633,10500,0,200.0009685,0,0,0,90.00000001 +324.08,50.30085681,-2.747823608,10500,0,199.9998535,0,0,0,90.00000001 +324.09,50.30085681,-2.747795583,10500,0,199.9991844,0,0,0,90.00000001 +324.1,50.30085681,-2.747767558,10500,0,199.9998535,0,0,0,90.00000001 +324.11,50.30085681,-2.747739533,10500,0,200.0009685,0,0,0,90.00000001 +324.12,50.30085681,-2.747711507,10500,0,200.0009685,0,0,0,90.00000001 +324.13,50.30085681,-2.747683482,10500,0,199.9998535,0,0,0,90.00000001 +324.14,50.30085681,-2.747655457,10500,0,199.9991844,0,0,0,90.00000001 +324.15,50.30085681,-2.747627432,10500,0,199.9998535,0,0,0,90.00000001 +324.16,50.30085681,-2.747599407,10500,0,200.0009685,0,0,0,90.00000001 +324.17,50.30085681,-2.747571381,10500,0,200.0009685,0,0,0,90.00000001 +324.18,50.30085681,-2.747543356,10500,0,199.9998535,0,0,0,90.00000001 +324.19,50.30085681,-2.747515331,10500,0,199.9991844,0,0,0,90.00000001 +324.2,50.30085681,-2.747487306,10500,0,199.9998535,0,0,0,90.00000001 +324.21,50.30085681,-2.747459281,10500,0,200.0009685,0,0,0,90.00000001 +324.22,50.30085681,-2.747431255,10500,0,200.0009685,0,0,0,90.00000001 +324.23,50.30085681,-2.74740323,10500,0,199.9998535,0,0,0,90.00000001 +324.24,50.30085681,-2.747375205,10500,0,199.9991844,0,0,0,90.00000001 +324.25,50.30085681,-2.74734718,10500,0,199.9998535,0,0,0,90.00000001 +324.26,50.30085681,-2.747319155,10500,0,200.0009685,0,0,0,90.00000001 +324.27,50.30085681,-2.747291129,10500,0,200.0009685,0,0,0,90.00000001 +324.28,50.30085681,-2.747263104,10500,0,199.9998535,0,0,0,90.00000001 +324.29,50.30085681,-2.747235079,10500,0,199.9989614,0,0,0,90.00000001 +324.3,50.30085681,-2.747207054,10500,0,199.9989614,0,0,0,90.00000001 +324.31,50.30085681,-2.747179029,10500,0,199.9998535,0,0,0,90.00000001 +324.32,50.30085681,-2.747151004,10500,0,200.0009685,0,0,0,90.00000001 +324.33,50.30085681,-2.747122978,10500,0,200.0009685,0,0,0,90.00000001 +324.34,50.30085681,-2.747094953,10500,0,199.9998535,0,0,0,90.00000001 +324.35,50.30085681,-2.747066928,10500,0,199.9989614,0,0,0,90.00000001 +324.36,50.30085681,-2.747038903,10500,0,199.9989614,0,0,0,90.00000001 +324.37,50.30085681,-2.747010878,10500,0,199.9998535,0,0,0,90.00000001 +324.38,50.30085681,-2.746982853,10500,0,200.0009685,0,0,0,90.00000001 +324.39,50.30085681,-2.746954827,10500,0,200.0009685,0,0,0,90.00000001 +324.4,50.30085681,-2.746926802,10500,0,199.9998535,0,0,0,90.00000001 +324.41,50.30085681,-2.746898777,10500,0,199.9989614,0,0,0,90.00000001 +324.42,50.30085681,-2.746870752,10500,0,199.9987384,0,0,0,90.00000001 +324.43,50.30085681,-2.746842727,10500,0,199.9989614,0,0,0,90.00000001 +324.44,50.30085681,-2.746814702,10500,0,199.9998535,0,0,0,90.00000001 +324.45,50.30085681,-2.746786677,10500,0,200.0009685,0,0,0,90.00000001 +324.46,50.30085681,-2.746758651,10500,0,200.0009685,0,0,0,90.00000001 +324.47,50.30085681,-2.746730626,10500,0,199.9998535,0,0,0,90.00000001 +324.48,50.30085681,-2.746702601,10500,0,199.9989614,0,0,0,90.00000001 +324.49,50.30085681,-2.746674576,10500,0,199.9989614,0,0,0,90.00000001 +324.5,50.30085681,-2.746646551,10500,0,199.9998535,0,0,0,90.00000001 +324.51,50.30085681,-2.746618526,10500,0,200.0009685,0,0,0,90.00000001 +324.52,50.30085681,-2.7465905,10500,0,200.0009685,0,0,0,90.00000001 +324.53,50.30085681,-2.746562475,10500,0,199.9998535,0,0,0,90.00000001 +324.54,50.30085681,-2.74653445,10500,0,199.9989614,0,0,0,90.00000001 +324.55,50.30085681,-2.746506425,10500,0,199.9989614,0,0,0,90.00000001 +324.56,50.30085681,-2.7464784,10500,0,199.9998535,0,0,0,90.00000001 +324.57,50.30085681,-2.746450375,10500,0,200.0009685,0,0,0,90.00000001 +324.58,50.30085681,-2.746422349,10500,0,200.0009685,0,0,0,90.00000001 +324.59,50.30085681,-2.746394324,10500,0,199.9998535,0,0,0,90.00000001 +324.6,50.30085681,-2.746366299,10500,0,199.9989614,0,0,0,90.00000001 +324.61,50.30085681,-2.746338274,10500,0,199.9989614,0,0,0,90.00000001 +324.62,50.30085681,-2.746310249,10500,0,199.9998535,0,0,0,90.00000001 +324.63,50.30085681,-2.746282224,10500,0,200.0009685,0,0,0,90.00000001 +324.64,50.30085681,-2.746254198,10500,0,200.0009685,0,0,0,90.00000001 +324.65,50.30085681,-2.746226173,10500,0,199.9998535,0,0,0,90.00000001 +324.66,50.30085681,-2.746198148,10500,0,199.9991844,0,0,0,90.00000001 +324.67,50.30085681,-2.746170123,10500,0,199.9998535,0,0,0,90.00000001 +324.68,50.30085681,-2.746142098,10500,0,200.0009685,0,0,0,90.00000001 +324.69,50.30085681,-2.746114072,10500,0,200.0009685,0,0,0,90.00000001 +324.7,50.30085681,-2.746086047,10500,0,199.9998535,0,0,0,90.00000001 +324.71,50.30085681,-2.746058022,10500,0,199.9991844,0,0,0,90.00000001 +324.72,50.30085681,-2.746029997,10500,0,199.9998535,0,0,0,90.00000001 +324.73,50.30085681,-2.746001972,10500,0,200.0009685,0,0,0,90.00000001 +324.74,50.30085681,-2.745973946,10500,0,200.0009685,0,0,0,90.00000001 +324.75,50.30085681,-2.745945921,10500,0,199.9998535,0,0,0,90.00000001 +324.76,50.30085681,-2.745917896,10500,0,199.9991844,0,0,0,90.00000001 +324.77,50.30085681,-2.745889871,10500,0,199.9998535,0,0,0,90.00000001 +324.78,50.30085681,-2.745861846,10500,0,200.0009685,0,0,0,90.00000001 +324.79,50.30085681,-2.74583382,10500,0,200.0009685,0,0,0,90.00000001 +324.8,50.30085681,-2.745805795,10500,0,199.9998535,0,0,0,90.00000001 +324.81,50.30085681,-2.74577777,10500,0,199.9991844,0,0,0,90.00000001 +324.82,50.30085681,-2.745749745,10500,0,199.9998535,0,0,0,90.00000001 +324.83,50.30085681,-2.74572172,10500,0,200.0009685,0,0,0,90.00000001 +324.84,50.30085681,-2.745693694,10500,0,200.0009685,0,0,0,90.00000001 +324.85,50.30085681,-2.745665669,10500,0,199.9998535,0,0,0,90.00000001 +324.86,50.30085681,-2.745637644,10500,0,199.9991844,0,0,0,90.00000001 +324.87,50.30085681,-2.745609619,10500,0,199.9998535,0,0,0,90.00000001 +324.88,50.30085681,-2.745581594,10500,0,200.0009685,0,0,0,90.00000001 +324.89,50.30085681,-2.745553568,10500,0,200.0009685,0,0,0,90.00000001 +324.9,50.30085681,-2.745525543,10500,0,199.9998535,0,0,0,90.00000001 +324.91,50.30085681,-2.745497518,10500,0,199.9989614,0,0,0,90.00000001 +324.92,50.30085681,-2.745469493,10500,0,199.9989614,0,0,0,90.00000001 +324.93,50.30085681,-2.745441468,10500,0,199.9998535,0,0,0,90.00000001 +324.94,50.30085681,-2.745413443,10500,0,200.0009685,0,0,0,90.00000001 +324.95,50.30085681,-2.745385417,10500,0,200.0009685,0,0,0,90.00000001 +324.96,50.30085681,-2.745357392,10500,0,199.9998535,0,0,0,90.00000001 +324.97,50.30085681,-2.745329367,10500,0,199.9989614,0,0,0,90.00000001 +324.98,50.30085681,-2.745301342,10500,0,199.9989614,0,0,0,90.00000001 +324.99,50.30085681,-2.745273317,10500,0,199.9998535,0,0,0,90.00000001 +325,50.30085681,-2.745245292,10500,0,200.0009685,0,0,0,90.00000001 +325.01,50.30085681,-2.745217266,10500,0,200.0009685,0,0,0,90.00000001 +325.02,50.30085681,-2.745189241,10500,0,199.9998535,0,0,0,90.00000001 +325.03,50.30085681,-2.745161216,10500,0,199.9989614,0,0,0,90.00000001 +325.04,50.30085681,-2.745133191,10500,0,199.9987384,0,0,0,90.00000001 +325.05,50.30085681,-2.745105166,10500,0,199.9989614,0,0,0,90.00000001 +325.06,50.30085681,-2.745077141,10500,0,199.9998535,0,0,0,90.00000001 +325.07,50.30085681,-2.745049116,10500,0,200.0009685,0,0,0,90.00000001 +325.08,50.30085681,-2.74502109,10500,0,200.0009685,0,0,0,90.00000001 +325.09,50.30085681,-2.744993065,10500,0,199.9998535,0,0,0,90.00000001 +325.1,50.30085681,-2.74496504,10500,0,199.9989614,0,0,0,90.00000001 +325.11,50.30085681,-2.744937015,10500,0,199.9989614,0,0,0,90.00000001 +325.12,50.30085681,-2.74490899,10500,0,199.9998535,0,0,0,90.00000001 +325.13,50.30085681,-2.744880965,10500,0,200.0009685,0,0,0,90.00000001 +325.14,50.30085681,-2.744852939,10500,0,200.0009685,0,0,0,90.00000001 +325.15,50.30085681,-2.744824914,10500,0,199.9998535,0,0,0,90.00000001 +325.16,50.30085681,-2.744796889,10500,0,199.9989614,0,0,0,90.00000001 +325.17,50.30085681,-2.744768864,10500,0,199.9989614,0,0,0,90.00000001 +325.18,50.30085681,-2.744740839,10500,0,199.9998535,0,0,0,90.00000001 +325.19,50.30085681,-2.744712814,10500,0,200.0009685,0,0,0,90.00000001 +325.2,50.30085681,-2.744684788,10500,0,200.0009685,0,0,0,90.00000001 +325.21,50.30085681,-2.744656763,10500,0,199.9998535,0,0,0,90.00000001 +325.22,50.30085681,-2.744628738,10500,0,199.9989614,0,0,0,90.00000001 +325.23,50.30085681,-2.744600713,10500,0,199.9989614,0,0,0,90.00000001 +325.24,50.30085681,-2.744572688,10500,0,199.9998535,0,0,0,90.00000001 +325.25,50.30085681,-2.744544663,10500,0,200.0009685,0,0,0,90.00000001 +325.26,50.30085681,-2.744516637,10500,0,200.0009685,0,0,0,90.00000001 +325.27,50.30085681,-2.744488612,10500,0,199.9998535,0,0,0,90.00000001 +325.28,50.30085681,-2.744460587,10500,0,199.9991844,0,0,0,90.00000001 +325.29,50.30085681,-2.744432562,10500,0,199.9998535,0,0,0,90.00000001 +325.3,50.30085681,-2.744404537,10500,0,200.0009685,0,0,0,90.00000001 +325.31,50.30085681,-2.744376511,10500,0,200.0009685,0,0,0,90.00000001 +325.32,50.30085681,-2.744348486,10500,0,199.9998535,0,0,0,90.00000001 +325.33,50.30085681,-2.744320461,10500,0,199.9991844,0,0,0,90.00000001 +325.34,50.30085681,-2.744292436,10500,0,199.9998535,0,0,0,90.00000001 +325.35,50.30085681,-2.744264411,10500,0,200.0009685,0,0,0,90.00000001 +325.36,50.30085681,-2.744236385,10500,0,200.0009685,0,0,0,90.00000001 +325.37,50.30085681,-2.74420836,10500,0,199.9998535,0,0,0,90.00000001 +325.38,50.30085681,-2.744180335,10500,0,199.9989614,0,0,0,90.00000001 +325.39,50.30085681,-2.74415231,10500,0,199.9989614,0,0,0,90.00000001 +325.4,50.30085681,-2.744124285,10500,0,199.9998535,0,0,0,90.00000001 +325.41,50.30085681,-2.74409626,10500,0,200.0009685,0,0,0,90.00000001 +325.42,50.30085681,-2.744068234,10500,0,200.0009685,0,0,0,90.00000001 +325.43,50.30085681,-2.744040209,10500,0,199.9998535,0,0,0,90.00000001 +325.44,50.30085681,-2.744012184,10500,0,199.9991844,0,0,0,90.00000001 +325.45,50.30085681,-2.743984159,10500,0,199.9998535,0,0,0,90.00000001 +325.46,50.30085681,-2.743956134,10500,0,200.0009685,0,0,0,90.00000001 +325.47,50.30085681,-2.743928108,10500,0,200.0009685,0,0,0,90.00000001 +325.48,50.30085681,-2.743900083,10500,0,199.9998535,0,0,0,90.00000001 +325.49,50.30085681,-2.743872058,10500,0,199.9991844,0,0,0,90.00000001 +325.5,50.30085681,-2.743844033,10500,0,199.9998535,0,0,0,90.00000001 +325.51,50.30085681,-2.743816008,10500,0,200.0009685,0,0,0,90.00000001 +325.52,50.30085681,-2.743787982,10500,0,200.0009685,0,0,0,90.00000001 +325.53,50.30085681,-2.743759957,10500,0,199.9998535,0,0,0,90.00000001 +325.54,50.30085681,-2.743731932,10500,0,199.9991844,0,0,0,90.00000001 +325.55,50.30085681,-2.743703907,10500,0,199.9998535,0,0,0,90.00000001 +325.56,50.30085681,-2.743675882,10500,0,200.0009685,0,0,0,90.00000001 +325.57,50.30085681,-2.743647856,10500,0,200.0009685,0,0,0,90.00000001 +325.58,50.30085681,-2.743619831,10500,0,199.9998535,0,0,0,90.00000001 +325.59,50.30085681,-2.743591806,10500,0,199.9989614,0,0,0,90.00000001 +325.6,50.30085681,-2.743563781,10500,0,199.9987384,0,0,0,90.00000001 +325.61,50.30085681,-2.743535756,10500,0,199.9989614,0,0,0,90.00000001 +325.62,50.30085681,-2.743507731,10500,0,199.9998535,0,0,0,90.00000001 +325.63,50.30085681,-2.743479706,10500,0,200.0009685,0,0,0,90.00000001 +325.64,50.30085681,-2.74345168,10500,0,200.0009685,0,0,0,90.00000001 +325.65,50.30085681,-2.743423655,10500,0,199.9998535,0,0,0,90.00000001 +325.66,50.30085681,-2.74339563,10500,0,199.9989614,0,0,0,90.00000001 +325.67,50.30085681,-2.743367605,10500,0,199.9989614,0,0,0,90.00000001 +325.68,50.30085681,-2.74333958,10500,0,199.9998535,0,0,0,90.00000001 +325.69,50.30085681,-2.743311555,10500,0,200.0009685,0,0,0,90.00000001 +325.7,50.30085681,-2.743283529,10500,0,200.0009685,0,0,0,90.00000001 +325.71,50.30085681,-2.743255504,10500,0,199.9998535,0,0,0,90.00000001 +325.72,50.30085681,-2.743227479,10500,0,199.9989614,0,0,0,90.00000001 +325.73,50.30085681,-2.743199454,10500,0,199.9989614,0,0,0,90.00000001 +325.74,50.30085681,-2.743171429,10500,0,199.9998535,0,0,0,90.00000001 +325.75,50.30085681,-2.743143404,10500,0,200.0009685,0,0,0,90.00000001 +325.76,50.30085681,-2.743115378,10500,0,200.0009685,0,0,0,90.00000001 +325.77,50.30085681,-2.743087353,10500,0,199.9998535,0,0,0,90.00000001 +325.78,50.30085681,-2.743059328,10500,0,199.9989614,0,0,0,90.00000001 +325.79,50.30085681,-2.743031303,10500,0,199.9989614,0,0,0,90.00000001 +325.8,50.30085681,-2.743003278,10500,0,199.9998535,0,0,0,90.00000001 +325.81,50.30085681,-2.742975253,10500,0,200.0009685,0,0,0,90.00000001 +325.82,50.30085681,-2.742947227,10500,0,200.0009685,0,0,0,90.00000001 +325.83,50.30085681,-2.742919202,10500,0,199.9998535,0,0,0,90.00000001 +325.84,50.30085681,-2.742891177,10500,0,199.9989614,0,0,0,90.00000001 +325.85,50.30085681,-2.742863152,10500,0,199.9987384,0,0,0,90.00000001 +325.86,50.30085681,-2.742835127,10500,0,199.9989614,0,0,0,90.00000001 +325.87,50.30085681,-2.742807102,10500,0,199.9998535,0,0,0,90.00000001 +325.88,50.30085681,-2.742779077,10500,0,200.0009685,0,0,0,90.00000001 +325.89,50.30085681,-2.742751051,10500,0,200.0009685,0,0,0,90.00000001 +325.9,50.30085681,-2.742723026,10500,0,199.9998535,0,0,0,90.00000001 +325.91,50.30085681,-2.742695001,10500,0,199.9991844,0,0,0,90.00000001 +325.92,50.30085681,-2.742666976,10500,0,199.9998535,0,0,0,90.00000001 +325.93,50.30085681,-2.742638951,10500,0,200.0009685,0,0,0,90.00000001 +325.94,50.30085681,-2.742610925,10500,0,200.0009685,0,0,0,90.00000001 +325.95,50.30085681,-2.7425829,10500,0,199.9998535,0,0,0,90.00000001 +325.96,50.30085681,-2.742554875,10500,0,199.9991844,0,0,0,90.00000001 +325.97,50.30085681,-2.74252685,10500,0,199.9998535,0,0,0,90.00000001 +325.98,50.30085681,-2.742498825,10500,0,200.0009685,0,0,0,90.00000001 +325.99,50.30085681,-2.742470799,10500,0,200.0009685,0,0,0,90.00000001 +326,50.30085681,-2.742442774,10500,0,199.9998535,0,0,0,90.00000001 +326.01,50.30085681,-2.742414749,10500,0,199.9991844,0,0,0,90.00000001 +326.02,50.30085681,-2.742386724,10500,0,199.9998535,0,0,0,90.00000001 +326.03,50.30085681,-2.742358699,10500,0,200.0009685,0,0,0,90.00000001 +326.04,50.30085681,-2.742330673,10500,0,200.0009685,0,0,0,90.00000001 +326.05,50.30085681,-2.742302648,10500,0,199.9998535,0,0,0,90.00000001 +326.06,50.30085681,-2.742274623,10500,0,199.9991844,0,0,0,90.00000001 +326.07,50.30085681,-2.742246598,10500,0,199.9998535,0,0,0,90.00000001 +326.08,50.30085681,-2.742218573,10500,0,200.0009685,0,0,0,90.00000001 +326.09,50.30085681,-2.742190547,10500,0,200.0009685,0,0,0,90.00000001 +326.1,50.30085681,-2.742162522,10500,0,199.9998535,0,0,0,90.00000001 +326.11,50.30085681,-2.742134497,10500,0,199.9991844,0,0,0,90.00000001 +326.12,50.30085681,-2.742106472,10500,0,199.9998535,0,0,0,90.00000001 +326.13,50.30085681,-2.742078447,10500,0,200.0009685,0,0,0,90.00000001 +326.14,50.30085681,-2.742050421,10500,0,200.0009685,0,0,0,90.00000001 +326.15,50.30085681,-2.742022396,10500,0,199.9998535,0,0,0,90.00000001 +326.16,50.30085681,-2.741994371,10500,0,199.9989614,0,0,0,90.00000001 +326.17,50.30085681,-2.741966346,10500,0,199.9989614,0,0,0,90.00000001 +326.18,50.30085681,-2.741938321,10500,0,199.9998535,0,0,0,90.00000001 +326.19,50.30085681,-2.741910296,10500,0,200.0009685,0,0,0,90.00000001 +326.2,50.30085681,-2.74188227,10500,0,200.0009685,0,0,0,90.00000001 +326.21,50.30085681,-2.741854245,10500,0,199.9998535,0,0,0,90.00000001 +326.22,50.30085681,-2.74182622,10500,0,199.9989614,0,0,0,90.00000001 +326.23,50.30085681,-2.741798195,10500,0,199.9989614,0,0,0,90.00000001 +326.24,50.30085681,-2.74177017,10500,0,199.9998535,0,0,0,90.00000001 +326.25,50.30085681,-2.741742145,10500,0,200.0009685,0,0,0,90.00000001 +326.26,50.30085681,-2.741714119,10500,0,200.0009685,0,0,0,90.00000001 +326.27,50.30085681,-2.741686094,10500,0,199.9998535,0,0,0,90.00000001 +326.28,50.30085681,-2.741658069,10500,0,199.9989614,0,0,0,90.00000001 +326.29,50.30085681,-2.741630044,10500,0,199.9989614,0,0,0,90.00000001 +326.3,50.30085681,-2.741602019,10500,0,199.9998535,0,0,0,90.00000001 +326.31,50.30085681,-2.741573994,10500,0,200.0009685,0,0,0,90.00000001 +326.32,50.30085681,-2.741545968,10500,0,200.0009685,0,0,0,90.00000001 +326.33,50.30085681,-2.741517943,10500,0,199.9998535,0,0,0,90.00000001 +326.34,50.30085681,-2.741489918,10500,0,199.9989614,0,0,0,90.00000001 +326.35,50.30085681,-2.741461893,10500,0,199.9989614,0,0,0,90.00000001 +326.36,50.30085681,-2.741433868,10500,0,199.9998535,0,0,0,90.00000001 +326.37,50.30085681,-2.741405843,10500,0,200.0009685,0,0,0,90.00000001 +326.38,50.30085681,-2.741377817,10500,0,200.0009685,0,0,0,90.00000001 +326.39,50.30085681,-2.741349792,10500,0,199.9998535,0,0,0,90.00000001 +326.4,50.30085681,-2.741321767,10500,0,199.9989614,0,0,0,90.00000001 +326.41,50.30085681,-2.741293742,10500,0,199.9989614,0,0,0,90.00000001 +326.42,50.30085681,-2.741265717,10500,0,199.9998535,0,0,0,90.00000001 +326.43,50.30085681,-2.741237692,10500,0,200.0009685,0,0,0,90.00000001 +326.44,50.30085681,-2.741209666,10500,0,200.0009685,0,0,0,90.00000001 +326.45,50.30085681,-2.741181641,10500,0,199.9998535,0,0,0,90.00000001 +326.46,50.30085681,-2.741153616,10500,0,199.9989614,0,0,0,90.00000001 +326.47,50.30085681,-2.741125591,10500,0,199.9987384,0,0,0,90.00000001 +326.48,50.30085681,-2.741097566,10500,0,199.9989614,0,0,0,90.00000001 +326.49,50.30085681,-2.741069541,10500,0,199.9998535,0,0,0,90.00000001 +326.5,50.30085681,-2.741041516,10500,0,200.0009685,0,0,0,90.00000001 +326.51,50.30085681,-2.74101349,10500,0,200.0009685,0,0,0,90.00000001 +326.52,50.30085681,-2.740985465,10500,0,199.9998535,0,0,0,90.00000001 +326.53,50.30085681,-2.74095744,10500,0,199.9991844,0,0,0,90.00000001 +326.54,50.30085681,-2.740929415,10500,0,199.9998535,0,0,0,90.00000001 +326.55,50.30085681,-2.74090139,10500,0,200.0009685,0,0,0,90.00000001 +326.56,50.30085681,-2.740873364,10500,0,200.0009685,0,0,0,90.00000001 +326.57,50.30085681,-2.740845339,10500,0,199.9998535,0,0,0,90.00000001 +326.58,50.30085681,-2.740817314,10500,0,199.9991844,0,0,0,90.00000001 +326.59,50.30085681,-2.740789289,10500,0,199.9998535,0,0,0,90.00000001 +326.6,50.30085681,-2.740761264,10500,0,200.0009685,0,0,0,90.00000001 +326.61,50.30085681,-2.740733238,10500,0,200.0009685,0,0,0,90.00000001 +326.62,50.30085681,-2.740705213,10500,0,199.9998535,0,0,0,90.00000001 +326.63,50.30085681,-2.740677188,10500,0,199.9991844,0,0,0,90.00000001 +326.64,50.30085681,-2.740649163,10500,0,199.9998535,0,0,0,90.00000001 +326.65,50.30085681,-2.740621138,10500,0,200.0009685,0,0,0,90.00000001 +326.66,50.30085681,-2.740593112,10500,0,200.0009685,0,0,0,90.00000001 +326.67,50.30085681,-2.740565087,10500,0,199.9998535,0,0,0,90.00000001 +326.68,50.30085681,-2.740537062,10500,0,199.9991844,0,0,0,90.00000001 +326.69,50.30085681,-2.740509037,10500,0,199.9998535,0,0,0,90.00000001 +326.7,50.30085681,-2.740481012,10500,0,200.0009685,0,0,0,90.00000001 +326.71,50.30085681,-2.740452986,10500,0,200.0009685,0,0,0,90.00000001 +326.72,50.30085681,-2.740424961,10500,0,199.9998535,0,0,0,90.00000001 +326.73,50.30085681,-2.740396936,10500,0,199.9991844,0,0,0,90.00000001 +326.74,50.30085681,-2.740368911,10500,0,199.9998535,0,0,0,90.00000001 +326.75,50.30085681,-2.740340886,10500,0,200.0009685,0,0,0,90.00000001 +326.76,50.30085681,-2.74031286,10500,0,200.0009685,0,0,0,90.00000001 +326.77,50.30085681,-2.740284835,10500,0,199.9998535,0,0,0,90.00000001 +326.78,50.30085681,-2.74025681,10500,0,199.9989614,0,0,0,90.00000001 +326.79,50.30085681,-2.740228785,10500,0,199.9989614,0,0,0,90.00000001 +326.8,50.30085681,-2.74020076,10500,0,199.9998535,0,0,0,90.00000001 +326.81,50.30085681,-2.740172735,10500,0,200.0009685,0,0,0,90.00000001 +326.82,50.30085681,-2.740144709,10500,0,200.0009685,0,0,0,90.00000001 +326.83,50.30085681,-2.740116684,10500,0,199.9998535,0,0,0,90.00000001 +326.84,50.30085681,-2.740088659,10500,0,199.9989614,0,0,0,90.00000001 +326.85,50.30085681,-2.740060634,10500,0,199.9989614,0,0,0,90.00000001 +326.86,50.30085681,-2.740032609,10500,0,199.9998535,0,0,0,90.00000001 +326.87,50.30085681,-2.740004584,10500,0,200.0009685,0,0,0,90.00000001 +326.88,50.30085681,-2.739976558,10500,0,200.0009685,0,0,0,90.00000001 +326.89,50.30085681,-2.739948533,10500,0,199.9998535,0,0,0,90.00000001 +326.9,50.30085681,-2.739920508,10500,0,199.9989614,0,0,0,90.00000001 +326.91,50.30085681,-2.739892483,10500,0,199.9989614,0,0,0,90.00000001 +326.92,50.30085681,-2.739864458,10500,0,199.9998535,0,0,0,90.00000001 +326.93,50.30085681,-2.739836433,10500,0,200.0009685,0,0,0,90.00000001 +326.94,50.30085681,-2.739808407,10500,0,200.0009685,0,0,0,90.00000001 +326.95,50.30085681,-2.739780382,10500,0,199.9998535,0,0,0,90.00000001 +326.96,50.30085681,-2.739752357,10500,0,199.9989614,0,0,0,90.00000001 +326.97,50.30085681,-2.739724332,10500,0,199.9989614,0,0,0,90.00000001 +326.98,50.30085681,-2.739696307,10500,0,199.9998535,0,0,0,90.00000001 +326.99,50.30085681,-2.739668282,10500,0,200.0009685,0,0,0,90.00000001 +327,50.30085681,-2.739640256,10500,0,200.0009685,0,0,0,90.00000001 +327.01,50.30085681,-2.739612231,10500,0,199.9998535,0,0,0,90.00000001 +327.02,50.30085681,-2.739584206,10500,0,199.9989614,0,0,0,90.00000001 +327.03,50.30085681,-2.739556181,10500,0,199.9987384,0,0,0,90.00000001 +327.04,50.30085681,-2.739528156,10500,0,199.9989614,0,0,0,90.00000001 +327.05,50.30085681,-2.739500131,10500,0,199.9998535,0,0,0,90.00000001 +327.06,50.30085681,-2.739472106,10500,0,200.0009685,0,0,0,90.00000001 +327.07,50.30085681,-2.73944408,10500,0,200.0009685,0,0,0,90.00000001 +327.08,50.30085681,-2.739416055,10500,0,199.9998535,0,0,0,90.00000001 +327.09,50.30085681,-2.73938803,10500,0,199.9989614,0,0,0,90.00000001 +327.1,50.30085681,-2.739360005,10500,0,199.9989614,0,0,0,90.00000001 +327.11,50.30085681,-2.73933198,10500,0,199.9998535,0,0,0,90.00000001 +327.12,50.30085681,-2.739303955,10500,0,200.0009685,0,0,0,90.00000001 +327.13,50.30085681,-2.739275929,10500,0,200.0009685,0,0,0,90.00000001 +327.14,50.30085681,-2.739247904,10500,0,199.9998535,0,0,0,90.00000001 +327.15,50.30085681,-2.739219879,10500,0,199.9991844,0,0,0,90.00000001 +327.16,50.30085681,-2.739191854,10500,0,199.9998535,0,0,0,90.00000001 +327.17,50.30085681,-2.739163829,10500,0,200.0009685,0,0,0,90.00000001 +327.18,50.30085681,-2.739135803,10500,0,200.0009685,0,0,0,90.00000001 +327.19,50.30085681,-2.739107778,10500,0,199.9998535,0,0,0,90.00000001 +327.2,50.30085681,-2.739079753,10500,0,199.9991844,0,0,0,90.00000001 +327.21,50.30085681,-2.739051728,10500,0,199.9998535,0,0,0,90.00000001 +327.22,50.30085681,-2.739023703,10500,0,200.0009685,0,0,0,90.00000001 +327.23,50.30085681,-2.738995677,10500,0,200.0009685,0,0,0,90.00000001 +327.24,50.30085681,-2.738967652,10500,0,199.9998535,0,0,0,90.00000001 +327.25,50.30085681,-2.738939627,10500,0,199.9991844,0,0,0,90.00000001 +327.26,50.30085681,-2.738911602,10500,0,199.9998535,0,0,0,90.00000001 +327.27,50.30085681,-2.738883577,10500,0,200.0009685,0,0,0,90.00000001 +327.28,50.30085681,-2.738855551,10500,0,200.0009685,0,0,0,90.00000001 +327.29,50.30085681,-2.738827526,10500,0,199.9998535,0,0,0,90.00000001 +327.3,50.30085681,-2.738799501,10500,0,199.9991844,0,0,0,90.00000001 +327.31,50.30085681,-2.738771476,10500,0,199.9998535,0,0,0,90.00000001 +327.32,50.30085681,-2.738743451,10500,0,200.0009685,0,0,0,90.00000001 +327.33,50.30085681,-2.738715425,10500,0,200.0009685,0,0,0,90.00000001 +327.34,50.30085681,-2.7386874,10500,0,199.9998535,0,0,0,90.00000001 +327.35,50.30085681,-2.738659375,10500,0,199.9991844,0,0,0,90.00000001 +327.36,50.30085681,-2.73863135,10500,0,199.9998535,0,0,0,90.00000001 +327.37,50.30085681,-2.738603325,10500,0,200.0009685,0,0,0,90.00000001 +327.38,50.30085681,-2.738575299,10500,0,200.0009685,0,0,0,90.00000001 +327.39,50.30085681,-2.738547274,10500,0,199.9998535,0,0,0,90.00000001 +327.4,50.30085681,-2.738519249,10500,0,199.9989614,0,0,0,90.00000001 +327.41,50.30085681,-2.738491224,10500,0,199.9989614,0,0,0,90.00000001 +327.42,50.30085681,-2.738463199,10500,0,199.9998535,0,0,0,90.00000001 +327.43,50.30085681,-2.738435174,10500,0,200.0009685,0,0,0,90.00000001 +327.44,50.30085681,-2.738407148,10500,0,200.0009685,0,0,0,90.00000001 +327.45,50.30085681,-2.738379123,10500,0,199.9998535,0,0,0,90.00000001 +327.46,50.30085681,-2.738351098,10500,0,199.9989614,0,0,0,90.00000001 +327.47,50.30085681,-2.738323073,10500,0,199.9989614,0,0,0,90.00000001 +327.48,50.30085681,-2.738295048,10500,0,199.9998535,0,0,0,90.00000001 +327.49,50.30085681,-2.738267023,10500,0,200.0009685,0,0,0,90.00000001 +327.5,50.30085681,-2.738238997,10500,0,200.0009685,0,0,0,90.00000001 +327.51,50.30085681,-2.738210972,10500,0,199.9998535,0,0,0,90.00000001 +327.52,50.30085681,-2.738182947,10500,0,199.9989614,0,0,0,90.00000001 +327.53,50.30085681,-2.738154922,10500,0,199.9989614,0,0,0,90.00000001 +327.54,50.30085681,-2.738126897,10500,0,199.9998535,0,0,0,90.00000001 +327.55,50.30085681,-2.738098872,10500,0,200.0009685,0,0,0,90.00000001 +327.56,50.30085681,-2.738070846,10500,0,200.0009685,0,0,0,90.00000001 +327.57,50.30085681,-2.738042821,10500,0,199.9998535,0,0,0,90.00000001 +327.58,50.30085681,-2.738014796,10500,0,199.9989614,0,0,0,90.00000001 +327.59,50.30085681,-2.737986771,10500,0,199.9987384,0,0,0,90.00000001 +327.6,50.30085681,-2.737958746,10500,0,199.9989614,0,0,0,90.00000001 +327.61,50.30085681,-2.737930721,10500,0,199.9998535,0,0,0,90.00000001 +327.62,50.30085681,-2.737902696,10500,0,200.0009685,0,0,0,90.00000001 +327.63,50.30085681,-2.73787467,10500,0,200.0009685,0,0,0,90.00000001 +327.64,50.30085681,-2.737846645,10500,0,199.9998535,0,0,0,90.00000001 +327.65,50.30085681,-2.73781862,10500,0,199.9989614,0,0,0,90.00000001 +327.66,50.30085681,-2.737790595,10500,0,199.9989614,0,0,0,90.00000001 +327.67,50.30085681,-2.73776257,10500,0,199.9998535,0,0,0,90.00000001 +327.68,50.30085681,-2.737734545,10500,0,200.0009685,0,0,0,90.00000001 +327.69,50.30085681,-2.737706519,10500,0,200.0009685,0,0,0,90.00000001 +327.7,50.30085681,-2.737678494,10500,0,199.9998535,0,0,0,90.00000001 +327.71,50.30085681,-2.737650469,10500,0,199.9989614,0,0,0,90.00000001 +327.72,50.30085681,-2.737622444,10500,0,199.9989614,0,0,0,90.00000001 +327.73,50.30085681,-2.737594419,10500,0,199.9998535,0,0,0,90.00000001 +327.74,50.30085681,-2.737566394,10500,0,200.0009685,0,0,0,90.00000001 +327.75,50.30085681,-2.737538368,10500,0,200.0009685,0,0,0,90.00000001 +327.76,50.30085681,-2.737510343,10500,0,199.9998535,0,0,0,90.00000001 +327.77,50.30085681,-2.737482318,10500,0,199.9989614,0,0,0,90.00000001 +327.78,50.30085681,-2.737454293,10500,0,199.9989614,0,0,0,90.00000001 +327.79,50.30085681,-2.737426268,10500,0,199.9998535,0,0,0,90.00000001 +327.8,50.30085681,-2.737398243,10500,0,200.0009685,0,0,0,90.00000001 +327.81,50.30085681,-2.737370217,10500,0,200.0009685,0,0,0,90.00000001 +327.82,50.30085681,-2.737342192,10500,0,199.9998535,0,0,0,90.00000001 +327.83,50.30085681,-2.737314167,10500,0,199.9991844,0,0,0,90.00000001 +327.84,50.30085681,-2.737286142,10500,0,199.9998535,0,0,0,90.00000001 +327.85,50.30085681,-2.737258117,10500,0,200.0009685,0,0,0,90.00000001 +327.86,50.30085681,-2.737230091,10500,0,200.0009685,0,0,0,90.00000001 +327.87,50.30085681,-2.737202066,10500,0,199.9998535,0,0,0,90.00000001 +327.88,50.30085681,-2.737174041,10500,0,199.9991844,0,0,0,90.00000001 +327.89,50.30085681,-2.737146016,10500,0,199.9998535,0,0,0,90.00000001 +327.9,50.30085681,-2.737117991,10500,0,200.0009685,0,0,0,90.00000001 +327.91,50.30085681,-2.737089965,10500,0,200.0009685,0,0,0,90.00000001 +327.92,50.30085681,-2.73706194,10500,0,199.9998535,0,0,0,90.00000001 +327.93,50.30085681,-2.737033915,10500,0,199.9991844,0,0,0,90.00000001 +327.94,50.30085681,-2.73700589,10500,0,199.9998535,0,0,0,90.00000001 +327.95,50.30085681,-2.736977865,10500,0,200.0009685,0,0,0,90.00000001 +327.96,50.30085681,-2.736949839,10500,0,200.0009685,0,0,0,90.00000001 +327.97,50.30085681,-2.736921814,10500,0,199.9998535,0,0,0,90.00000001 +327.98,50.30085681,-2.736893789,10500,0,199.9991844,0,0,0,90.00000001 +327.99,50.30085681,-2.736865764,10500,0,199.9998535,0,0,0,90.00000001 +328,50.30085681,-2.736837739,10500,0,200.0009685,0,0,0,90.00000001 +328.01,50.30085681,-2.736809713,10500,0,200.0009685,0,0,0,90.00000001 +328.02,50.30085681,-2.736781688,10500,0,199.9998535,0,0,0,90.00000001 +328.03,50.30085681,-2.736753663,10500,0,199.9991844,0,0,0,90.00000001 +328.04,50.30085681,-2.736725638,10500,0,199.9998535,0,0,0,90.00000001 +328.05,50.30085681,-2.736697613,10500,0,200.0009685,0,0,0,90.00000001 +328.06,50.30085681,-2.736669587,10500,0,200.0009685,0,0,0,90.00000001 +328.07,50.30085681,-2.736641562,10500,0,199.9998535,0,0,0,90.00000001 +328.08,50.30085681,-2.736613537,10500,0,199.9989614,0,0,0,90.00000001 +328.09,50.30085681,-2.736585512,10500,0,199.9989614,0,0,0,90.00000001 +328.1,50.30085681,-2.736557487,10500,0,199.9998535,0,0,0,90.00000001 +328.11,50.30085681,-2.736529462,10500,0,200.0009685,0,0,0,90.00000001 +328.12,50.30085681,-2.736501436,10500,0,200.0009685,0,0,0,90.00000001 +328.13,50.30085681,-2.736473411,10500,0,199.9998535,0,0,0,90.00000001 +328.14,50.30085681,-2.736445386,10500,0,199.9989614,0,0,0,90.00000001 +328.15,50.30085681,-2.736417361,10500,0,199.9987384,0,0,0,90.00000001 +328.16,50.30085681,-2.736389336,10500,0,199.9989614,0,0,0,90.00000001 +328.17,50.30085681,-2.736361311,10500,0,199.9998535,0,0,0,90.00000001 +328.18,50.30085681,-2.736333286,10500,0,200.0009685,0,0,0,90.00000001 +328.19,50.30085681,-2.73630526,10500,0,200.0009685,0,0,0,90.00000001 +328.2,50.30085681,-2.736277235,10500,0,199.9998535,0,0,0,90.00000001 +328.21,50.30085681,-2.73624921,10500,0,199.9989614,0,0,0,90.00000001 +328.22,50.30085681,-2.736221185,10500,0,199.9989614,0,0,0,90.00000001 +328.23,50.30085681,-2.73619316,10500,0,199.9998535,0,0,0,90.00000001 +328.24,50.30085681,-2.736165135,10500,0,200.0009685,0,0,0,90.00000001 +328.25,50.30085681,-2.736137109,10500,0,200.0009685,0,0,0,90.00000001 +328.26,50.30085681,-2.736109084,10500,0,199.9998535,0,0,0,90.00000001 +328.27,50.30085681,-2.736081059,10500,0,199.9989614,0,0,0,90.00000001 +328.28,50.30085681,-2.736053034,10500,0,199.9989614,0,0,0,90.00000001 +328.29,50.30085681,-2.736025009,10500,0,199.9998535,0,0,0,90.00000001 +328.3,50.30085681,-2.735996984,10500,0,200.0009685,0,0,0,90.00000001 +328.31,50.30085681,-2.735968958,10500,0,200.0009685,0,0,0,90.00000001 +328.32,50.30085681,-2.735940933,10500,0,199.9998535,0,0,0,90.00000001 +328.33,50.30085681,-2.735912908,10500,0,199.9989614,0,0,0,90.00000001 +328.34,50.30085681,-2.735884883,10500,0,199.9989614,0,0,0,90.00000001 +328.35,50.30085681,-2.735856858,10500,0,199.9998535,0,0,0,90.00000001 +328.36,50.30085681,-2.735828833,10500,0,200.0009685,0,0,0,90.00000001 +328.37,50.30085681,-2.735800807,10500,0,200.0009685,0,0,0,90.00000001 +328.38,50.30085681,-2.735772782,10500,0,199.9998535,0,0,0,90.00000001 +328.39,50.30085681,-2.735744757,10500,0,199.9989614,0,0,0,90.00000001 +328.4,50.30085681,-2.735716732,10500,0,199.9989614,0,0,0,90.00000001 +328.41,50.30085681,-2.735688707,10500,0,199.9998535,0,0,0,90.00000001 +328.42,50.30085681,-2.735660682,10500,0,200.0009685,0,0,0,90.00000001 +328.43,50.30085681,-2.735632656,10500,0,200.0009685,0,0,0,90.00000001 +328.44,50.30085681,-2.735604631,10500,0,199.9998535,0,0,0,90.00000001 +328.45,50.30085681,-2.735576606,10500,0,199.9991844,0,0,0,90.00000001 +328.46,50.30085681,-2.735548581,10500,0,199.9998535,0,0,0,90.00000001 +328.47,50.30085681,-2.735520556,10500,0,200.0009685,0,0,0,90.00000001 +328.48,50.30085681,-2.73549253,10500,0,200.0009685,0,0,0,90.00000001 +328.49,50.30085681,-2.735464505,10500,0,199.9998535,0,0,0,90.00000001 +328.5,50.30085681,-2.73543648,10500,0,199.9991844,0,0,0,90.00000001 +328.51,50.30085681,-2.735408455,10500,0,199.9998535,0,0,0,90.00000001 +328.52,50.30085681,-2.73538043,10500,0,200.0009685,0,0,0,90.00000001 +328.53,50.30085681,-2.735352404,10500,0,200.0009685,0,0,0,90.00000001 +328.54,50.30085681,-2.735324379,10500,0,199.9998535,0,0,0,90.00000001 +328.55,50.30085681,-2.735296354,10500,0,199.9991844,0,0,0,90.00000001 +328.56,50.30085681,-2.735268329,10500,0,199.9998535,0,0,0,90.00000001 +328.57,50.30085681,-2.735240304,10500,0,200.0009685,0,0,0,90.00000001 +328.58,50.30085681,-2.735212278,10500,0,200.0009685,0,0,0,90.00000001 +328.59,50.30085681,-2.735184253,10500,0,199.9998535,0,0,0,90.00000001 +328.6,50.30085681,-2.735156228,10500,0,199.9991844,0,0,0,90.00000001 +328.61,50.30085681,-2.735128203,10500,0,199.9998535,0,0,0,90.00000001 +328.62,50.30085681,-2.735100178,10500,0,200.0009685,0,0,0,90.00000001 +328.63,50.30085681,-2.735072152,10500,0,200.0009685,0,0,0,90.00000001 +328.64,50.30085681,-2.735044127,10500,0,199.9998535,0,0,0,90.00000001 +328.65,50.30085681,-2.735016102,10500,0,199.9991844,0,0,0,90.00000001 +328.66,50.30085681,-2.734988077,10500,0,199.9998535,0,0,0,90.00000001 +328.67,50.30085681,-2.734960052,10500,0,200.0009685,0,0,0,90.00000001 +328.68,50.30085681,-2.734932026,10500,0,200.0009685,0,0,0,90.00000001 +328.69,50.30085681,-2.734904001,10500,0,199.9998535,0,0,0,90.00000001 +328.7,50.30085681,-2.734875976,10500,0,199.9989614,0,0,0,90.00000001 +328.71,50.30085681,-2.734847951,10500,0,199.9987384,0,0,0,90.00000001 +328.72,50.30085681,-2.734819926,10500,0,199.9989614,0,0,0,90.00000001 +328.73,50.30085681,-2.734791901,10500,0,199.9998535,0,0,0,90.00000001 +328.74,50.30085681,-2.734763876,10500,0,200.0009685,0,0,0,90.00000001 +328.75,50.30085681,-2.73473585,10500,0,200.0009685,0,0,0,90.00000001 +328.76,50.30085681,-2.734707825,10500,0,199.9998535,0,0,0,90.00000001 +328.77,50.30085681,-2.7346798,10500,0,199.9989614,0,0,0,90.00000001 +328.78,50.30085681,-2.734651775,10500,0,199.9989614,0,0,0,90.00000001 +328.79,50.30085681,-2.73462375,10500,0,199.9998535,0,0,0,90.00000001 +328.8,50.30085681,-2.734595725,10500,0,200.0009685,0,0,0,90.00000001 +328.81,50.30085681,-2.734567699,10500,0,200.0009685,0,0,0,90.00000001 +328.82,50.30085681,-2.734539674,10500,0,199.9998535,0,0,0,90.00000001 +328.83,50.30085681,-2.734511649,10500,0,199.9989614,0,0,0,90.00000001 +328.84,50.30085681,-2.734483624,10500,0,199.9989614,0,0,0,90.00000001 +328.85,50.30085681,-2.734455599,10500,0,199.9998535,0,0,0,90.00000001 +328.86,50.30085681,-2.734427574,10500,0,200.0009685,0,0,0,90.00000001 +328.87,50.30085681,-2.734399548,10500,0,200.0009685,0,0,0,90.00000001 +328.88,50.30085681,-2.734371523,10500,0,199.9998535,0,0,0,90.00000001 +328.89,50.30085681,-2.734343498,10500,0,199.9989614,0,0,0,90.00000001 +328.9,50.30085681,-2.734315473,10500,0,199.9989614,0,0,0,90.00000001 +328.91,50.30085681,-2.734287448,10500,0,199.9998535,0,0,0,90.00000001 +328.92,50.30085681,-2.734259423,10500,0,200.0009685,0,0,0,90.00000001 +328.93,50.30085681,-2.734231397,10500,0,200.0009685,0,0,0,90.00000001 +328.94,50.30085681,-2.734203372,10500,0,199.9998535,0,0,0,90.00000001 +328.95,50.30085681,-2.734175347,10500,0,199.9989614,0,0,0,90.00000001 +328.96,50.30085681,-2.734147322,10500,0,199.9989614,0,0,0,90.00000001 +328.97,50.30085681,-2.734119297,10500,0,199.9998535,0,0,0,90.00000001 +328.98,50.30085681,-2.734091272,10500,0,200.0009685,0,0,0,90.00000001 +328.99,50.30085681,-2.734063246,10500,0,200.0009685,0,0,0,90.00000001 +329,50.30085681,-2.734035221,10500,0,199.9998535,0,0,0,90.00000001 +329.01,50.30085681,-2.734007196,10500,0,199.9989614,0,0,0,90.00000001 +329.02,50.30085681,-2.733979171,10500,0,199.9989614,0,0,0,90.00000001 +329.03,50.30085681,-2.733951146,10500,0,199.9998535,0,0,0,90.00000001 +329.04,50.30085681,-2.733923121,10500,0,200.0009685,0,0,0,90.00000001 +329.05,50.30085681,-2.733895095,10500,0,200.0009685,0,0,0,90.00000001 +329.06,50.30085681,-2.73386707,10500,0,199.9998535,0,0,0,90.00000001 +329.07,50.30085681,-2.733839045,10500,0,199.9991844,0,0,0,90.00000001 +329.08,50.30085681,-2.73381102,10500,0,199.9998535,0,0,0,90.00000001 +329.09,50.30085681,-2.733782995,10500,0,200.0009685,0,0,0,90.00000001 +329.1,50.30085681,-2.733754969,10500,0,200.0009685,0,0,0,90.00000001 +329.11,50.30085681,-2.733726944,10500,0,199.9998535,0,0,0,90.00000001 +329.12,50.30085681,-2.733698919,10500,0,199.9991844,0,0,0,90.00000001 +329.13,50.30085681,-2.733670894,10500,0,199.9998535,0,0,0,90.00000001 +329.14,50.30085681,-2.733642869,10500,0,200.0009685,0,0,0,90.00000001 +329.15,50.30085681,-2.733614843,10500,0,200.0009685,0,0,0,90.00000001 +329.16,50.30085681,-2.733586818,10500,0,199.9998535,0,0,0,90.00000001 +329.17,50.30085681,-2.733558793,10500,0,199.9991844,0,0,0,90.00000001 +329.18,50.30085681,-2.733530768,10500,0,199.9998535,0,0,0,90.00000001 +329.19,50.30085681,-2.733502743,10500,0,200.0009685,0,0,0,90.00000001 +329.2,50.30085681,-2.733474717,10500,0,200.0009685,0,0,0,90.00000001 +329.21,50.30085681,-2.733446692,10500,0,199.9998535,0,0,0,90.00000001 +329.22,50.30085681,-2.733418667,10500,0,199.9991844,0,0,0,90.00000001 +329.23,50.30085681,-2.733390642,10500,0,199.9998535,0,0,0,90.00000001 +329.24,50.30085681,-2.733362617,10500,0,200.0009685,0,0,0,90.00000001 +329.25,50.30085681,-2.733334591,10500,0,200.0009685,0,0,0,90.00000001 +329.26,50.30085681,-2.733306566,10500,0,199.9998535,0,0,0,90.00000001 +329.27,50.30085681,-2.733278541,10500,0,199.9991844,0,0,0,90.00000001 +329.28,50.30085681,-2.733250516,10500,0,199.9998535,0,0,0,90.00000001 +329.29,50.30085681,-2.733222491,10500,0,200.0009685,0,0,0,90.00000001 +329.3,50.30085681,-2.733194465,10500,0,200.0009685,0,0,0,90.00000001 +329.31,50.30085681,-2.73316644,10500,0,199.9998535,0,0,0,90.00000001 +329.32,50.30085681,-2.733138415,10500,0,199.9989614,0,0,0,90.00000001 +329.33,50.30085681,-2.73311039,10500,0,199.9987384,0,0,0,90.00000001 +329.34,50.30085681,-2.733082365,10500,0,199.9989614,0,0,0,90.00000001 +329.35,50.30085681,-2.73305434,10500,0,199.9998535,0,0,0,90.00000001 +329.36,50.30085681,-2.733026315,10500,0,200.0009685,0,0,0,90.00000001 +329.37,50.30085681,-2.732998289,10500,0,200.0009685,0,0,0,90.00000001 +329.38,50.30085681,-2.732970264,10500,0,199.9998535,0,0,0,90.00000001 +329.39,50.30085681,-2.732942239,10500,0,199.9989614,0,0,0,90.00000001 +329.4,50.30085681,-2.732914214,10500,0,199.9989614,0,0,0,90.00000001 +329.41,50.30085681,-2.732886189,10500,0,199.9998535,0,0,0,90.00000001 +329.42,50.30085681,-2.732858164,10500,0,200.0009685,0,0,0,90.00000001 +329.43,50.30085681,-2.732830138,10500,0,200.0009685,0,0,0,90.00000001 +329.44,50.30085681,-2.732802113,10500,0,199.9998535,0,0,0,90.00000001 +329.45,50.30085681,-2.732774088,10500,0,199.9989614,0,0,0,90.00000001 +329.46,50.30085681,-2.732746063,10500,0,199.9989614,0,0,0,90.00000001 +329.47,50.30085681,-2.732718038,10500,0,199.9998535,0,0,0,90.00000001 +329.48,50.30085681,-2.732690013,10500,0,200.0009685,0,0,0,90.00000001 +329.49,50.30085681,-2.732661987,10500,0,200.0009685,0,0,0,90.00000001 +329.5,50.30085681,-2.732633962,10500,0,199.9998535,0,0,0,90.00000001 +329.51,50.30085681,-2.732605937,10500,0,199.9989614,0,0,0,90.00000001 +329.52,50.30085681,-2.732577912,10500,0,199.9989614,0,0,0,90.00000001 +329.53,50.30085681,-2.732549887,10500,0,199.9998535,0,0,0,90.00000001 +329.54,50.30085681,-2.732521862,10500,0,200.0009685,0,0,0,90.00000001 +329.55,50.30085681,-2.732493836,10500,0,200.0009685,0,0,0,90.00000001 +329.56,50.30085681,-2.732465811,10500,0,199.9998535,0,0,0,90.00000001 +329.57,50.30085681,-2.732437786,10500,0,199.9989614,0,0,0,90.00000001 +329.58,50.30085681,-2.732409761,10500,0,199.9987384,0,0,0,90.00000001 +329.59,50.30085681,-2.732381736,10500,0,199.9989614,0,0,0,90.00000001 +329.6,50.30085681,-2.732353711,10500,0,199.9998535,0,0,0,90.00000001 +329.61,50.30085681,-2.732325686,10500,0,200.0009685,0,0,0,90.00000001 +329.62,50.30085681,-2.73229766,10500,0,200.0009685,0,0,0,90.00000001 +329.63,50.30085681,-2.732269635,10500,0,199.9998535,0,0,0,90.00000001 +329.64,50.30085681,-2.73224161,10500,0,199.9991844,0,0,0,90.00000001 +329.65,50.30085681,-2.732213585,10500,0,199.9998535,0,0,0,90.00000001 +329.66,50.30085681,-2.73218556,10500,0,200.0009685,0,0,0,90.00000001 +329.67,50.30085681,-2.732157534,10500,0,200.0009685,0,0,0,90.00000001 +329.68,50.30085681,-2.732129509,10500,0,199.9998535,0,0,0,90.00000001 +329.69,50.30085681,-2.732101484,10500,0,199.9991844,0,0,0,90.00000001 +329.7,50.30085681,-2.732073459,10500,0,199.9998535,0,0,0,90.00000001 +329.71,50.30085681,-2.732045434,10500,0,200.0009685,0,0,0,90.00000001 +329.72,50.30085681,-2.732017408,10500,0,200.0009685,0,0,0,90.00000001 +329.73,50.30085681,-2.731989383,10500,0,199.9998535,0,0,0,90.00000001 +329.74,50.30085681,-2.731961358,10500,0,199.9991844,0,0,0,90.00000001 +329.75,50.30085681,-2.731933333,10500,0,199.9998535,0,0,0,90.00000001 +329.76,50.30085681,-2.731905308,10500,0,200.0009685,0,0,0,90.00000001 +329.77,50.30085681,-2.731877282,10500,0,200.0009685,0,0,0,90.00000001 +329.78,50.30085681,-2.731849257,10500,0,199.9998535,0,0,0,90.00000001 +329.79,50.30085681,-2.731821232,10500,0,199.9989614,0,0,0,90.00000001 +329.8,50.30085681,-2.731793207,10500,0,199.9989614,0,0,0,90.00000001 +329.81,50.30085681,-2.731765182,10500,0,199.9998535,0,0,0,90.00000001 +329.82,50.30085681,-2.731737157,10500,0,200.0009685,0,0,0,90.00000001 +329.83,50.30085681,-2.731709131,10500,0,200.0009685,0,0,0,90.00000001 +329.84,50.30085681,-2.731681106,10500,0,199.9998535,0,0,0,90.00000001 +329.85,50.30085681,-2.731653081,10500,0,199.9991844,0,0,0,90.00000001 +329.86,50.30085681,-2.731625056,10500,0,199.9998535,0,0,0,90.00000001 +329.87,50.30085681,-2.731597031,10500,0,200.0009685,0,0,0,90.00000001 +329.88,50.30085681,-2.731569005,10500,0,200.0009685,0,0,0,90.00000001 +329.89,50.30085681,-2.73154098,10500,0,199.9998535,0,0,0,90.00000001 +329.9,50.30085681,-2.731512955,10500,0,199.9991844,0,0,0,90.00000001 +329.91,50.30085681,-2.73148493,10500,0,199.9998535,0,0,0,90.00000001 +329.92,50.30085681,-2.731456905,10500,0,200.0009685,0,0,0,90.00000001 +329.93,50.30085681,-2.731428879,10500,0,200.0009685,0,0,0,90.00000001 +329.94,50.30085681,-2.731400854,10500,0,199.9998535,0,0,0,90.00000001 +329.95,50.30085681,-2.731372829,10500,0,199.9989614,0,0,0,90.00000001 +329.96,50.30085681,-2.731344804,10500,0,199.9989614,0,0,0,90.00000001 +329.97,50.30085681,-2.731316779,10500,0,199.9998535,0,0,0,90.00000001 +329.98,50.30085681,-2.731288754,10500,0,200.0009685,0,0,0,90.00000001 +329.99,50.30085681,-2.731260728,10500,0,200.0009685,0,0,0,90.00000001 +330,50.30085681,-2.731232703,10500,0,199.9998535,0,0,0,90.00000001 +330.01,50.30085681,-2.731204678,10500,0,199.9989614,0,0,0,90.00000001 +330.02,50.30085681,-2.731176653,10500,0,199.9989614,0,0,0,90.00000001 +330.03,50.30085681,-2.731148628,10500,0,199.9998535,0,0,0,90.00000001 +330.04,50.30085681,-2.731120603,10500,0,200.0009685,0,0,0,90.00000001 +330.05,50.30085681,-2.731092577,10500,0,200.0009685,0,0,0,90.00000001 +330.06,50.30085681,-2.731064552,10500,0,199.9998535,0,0,0,90.00000001 +330.07,50.30085681,-2.731036527,10500,0,199.9989614,0,0,0,90.00000001 +330.08,50.30085681,-2.731008502,10500,0,199.9989614,0,0,0,90.00000001 +330.09,50.30085681,-2.730980477,10500,0,199.9998535,0,0,0,90.00000001 +330.1,50.30085681,-2.730952452,10500,0,200.0009685,0,0,0,90.00000001 +330.11,50.30085681,-2.730924426,10500,0,200.0009685,0,0,0,90.00000001 +330.12,50.30085681,-2.730896401,10500,0,199.9998535,0,0,0,90.00000001 +330.13,50.30085681,-2.730868376,10500,0,199.9989614,0,0,0,90.00000001 +330.14,50.30085681,-2.730840351,10500,0,199.9987384,0,0,0,90.00000001 +330.15,50.30085681,-2.730812326,10500,0,199.9989614,0,0,0,90.00000001 +330.16,50.30085681,-2.730784301,10500,0,199.9998535,0,0,0,90.00000001 +330.17,50.30085681,-2.730756276,10500,0,200.0009685,0,0,0,90.00000001 +330.18,50.30085681,-2.73072825,10500,0,200.0009685,0,0,0,90.00000001 +330.19,50.30085681,-2.730700225,10500,0,199.9998535,0,0,0,90.00000001 +330.2,50.30085681,-2.7306722,10500,0,199.9989614,0,0,0,90.00000001 +330.21,50.30085681,-2.730644175,10500,0,199.9989614,0,0,0,90.00000001 +330.22,50.30085681,-2.73061615,10500,0,199.9998535,0,0,0,90.00000001 +330.23,50.30085681,-2.730588125,10500,0,200.0009685,0,0,0,90.00000001 +330.24,50.30085681,-2.730560099,10500,0,200.0009685,0,0,0,90.00000001 +330.25,50.30085681,-2.730532074,10500,0,199.9998535,0,0,0,90.00000001 +330.26,50.30085681,-2.730504049,10500,0,199.9989614,0,0,0,90.00000001 +330.27,50.30085681,-2.730476024,10500,0,199.9989614,0,0,0,90.00000001 +330.28,50.30085681,-2.730447999,10500,0,199.9998535,0,0,0,90.00000001 +330.29,50.30085681,-2.730419974,10500,0,200.0009685,0,0,0,90.00000001 +330.3,50.30085681,-2.730391948,10500,0,200.0009685,0,0,0,90.00000001 +330.31,50.30085681,-2.730363923,10500,0,199.9998535,0,0,0,90.00000001 +330.32,50.30085681,-2.730335898,10500,0,199.9991844,0,0,0,90.00000001 +330.33,50.30085681,-2.730307873,10500,0,199.9998535,0,0,0,90.00000001 +330.34,50.30085681,-2.730279848,10500,0,200.0009685,0,0,0,90.00000001 +330.35,50.30085681,-2.730251822,10500,0,200.0009685,0,0,0,90.00000001 +330.36,50.30085681,-2.730223797,10500,0,199.9998535,0,0,0,90.00000001 +330.37,50.30085681,-2.730195772,10500,0,199.9991844,0,0,0,90.00000001 +330.38,50.30085681,-2.730167747,10500,0,199.9998535,0,0,0,90.00000001 +330.39,50.30085681,-2.730139722,10500,0,200.0009685,0,0,0,90.00000001 +330.4,50.30085681,-2.730111696,10500,0,200.0009685,0,0,0,90.00000001 +330.41,50.30085681,-2.730083671,10500,0,199.9998535,0,0,0,90.00000001 +330.42,50.30085681,-2.730055646,10500,0,199.9991844,0,0,0,90.00000001 +330.43,50.30085681,-2.730027621,10500,0,199.9998535,0,0,0,90.00000001 +330.44,50.30085681,-2.729999596,10500,0,200.0009685,0,0,0,90.00000001 +330.45,50.30085681,-2.72997157,10500,0,200.0009685,0,0,0,90.00000001 +330.46,50.30085681,-2.729943545,10500,0,199.9998535,0,0,0,90.00000001 +330.47,50.30085681,-2.72991552,10500,0,199.9991844,0,0,0,90.00000001 +330.48,50.30085681,-2.729887495,10500,0,199.9998535,0,0,0,90.00000001 +330.49,50.30085681,-2.72985947,10500,0,200.0009685,0,0,0,90.00000001 +330.5,50.30085681,-2.729831444,10500,0,200.0009685,0,0,0,90.00000001 +330.51,50.30085681,-2.729803419,10500,0,199.9998535,0,0,0,90.00000001 +330.52,50.30085681,-2.729775394,10500,0,199.9991844,0,0,0,90.00000001 +330.53,50.30085681,-2.729747369,10500,0,199.9998535,0,0,0,90.00000001 +330.54,50.30085681,-2.729719344,10500,0,200.0009685,0,0,0,90.00000001 +330.55,50.30085681,-2.729691318,10500,0,200.0009685,0,0,0,90.00000001 +330.56,50.30085681,-2.729663293,10500,0,199.9998535,0,0,0,90.00000001 +330.57,50.30085681,-2.729635268,10500,0,199.9989614,0,0,0,90.00000001 +330.58,50.30085681,-2.729607243,10500,0,199.9989614,0,0,0,90.00000001 +330.59,50.30085681,-2.729579218,10500,0,199.9998535,0,0,0,90.00000001 +330.6,50.30085681,-2.729551193,10500,0,200.0009685,0,0,0,90.00000001 +330.61,50.30085681,-2.729523167,10500,0,200.0009685,0,0,0,90.00000001 +330.62,50.30085681,-2.729495142,10500,0,199.9998535,0,0,0,90.00000001 +330.63,50.30085681,-2.729467117,10500,0,199.9989614,0,0,0,90.00000001 +330.64,50.30085681,-2.729439092,10500,0,199.9989614,0,0,0,90.00000001 +330.65,50.30085681,-2.729411067,10500,0,199.9998535,0,0,0,90.00000001 +330.66,50.30085681,-2.729383042,10500,0,200.0009685,0,0,0,90.00000001 +330.67,50.30085681,-2.729355016,10500,0,200.0009685,0,0,0,90.00000001 +330.68,50.30085681,-2.729326991,10500,0,199.9998535,0,0,0,90.00000001 +330.69,50.30085681,-2.729298966,10500,0,199.9989614,0,0,0,90.00000001 +330.7,50.30085681,-2.729270941,10500,0,199.9989614,0,0,0,90.00000001 +330.71,50.30085681,-2.729242916,10500,0,199.9998535,0,0,0,90.00000001 +330.72,50.30085681,-2.729214891,10500,0,200.0009685,0,0,0,90.00000001 +330.73,50.30085681,-2.729186865,10500,0,200.0009685,0,0,0,90.00000001 +330.74,50.30085681,-2.72915884,10500,0,199.9998535,0,0,0,90.00000001 +330.75,50.30085681,-2.729130815,10500,0,199.9989614,0,0,0,90.00000001 +330.76,50.30085681,-2.72910279,10500,0,199.9987384,0,0,0,90.00000001 +330.77,50.30085681,-2.729074765,10500,0,199.9989614,0,0,0,90.00000001 +330.78,50.30085681,-2.72904674,10500,0,199.9998535,0,0,0,90.00000001 +330.79,50.30085681,-2.729018715,10500,0,200.0009685,0,0,0,90.00000001 +330.8,50.30085681,-2.728990689,10500,0,200.0009685,0,0,0,90.00000001 +330.81,50.30085681,-2.728962664,10500,0,199.9998535,0,0,0,90.00000001 +330.82,50.30085681,-2.728934639,10500,0,199.9989614,0,0,0,90.00000001 +330.83,50.30085681,-2.728906614,10500,0,199.9989614,0,0,0,90.00000001 +330.84,50.30085681,-2.728878589,10500,0,199.9998535,0,0,0,90.00000001 +330.85,50.30085681,-2.728850564,10500,0,200.0009685,0,0,0,90.00000001 +330.86,50.30085681,-2.728822538,10500,0,200.0009685,0,0,0,90.00000001 +330.87,50.30085681,-2.728794513,10500,0,199.9998535,0,0,0,90.00000001 +330.88,50.30085681,-2.728766488,10500,0,199.9989614,0,0,0,90.00000001 +330.89,50.30085681,-2.728738463,10500,0,199.9989614,0,0,0,90.00000001 +330.9,50.30085681,-2.728710438,10500,0,199.9998535,0,0,0,90.00000001 +330.91,50.30085681,-2.728682413,10500,0,200.0009685,0,0,0,90.00000001 +330.92,50.30085681,-2.728654387,10500,0,200.0009685,0,0,0,90.00000001 +330.93,50.30085681,-2.728626362,10500,0,199.9998535,0,0,0,90.00000001 +330.94,50.30085681,-2.728598337,10500,0,199.9991844,0,0,0,90.00000001 +330.95,50.30085681,-2.728570312,10500,0,199.9998535,0,0,0,90.00000001 +330.96,50.30085681,-2.728542287,10500,0,200.0009685,0,0,0,90.00000001 +330.97,50.30085681,-2.728514261,10500,0,200.0009685,0,0,0,90.00000001 +330.98,50.30085681,-2.728486236,10500,0,199.9998535,0,0,0,90.00000001 +330.99,50.30085681,-2.728458211,10500,0,199.9991844,0,0,0,90.00000001 +331,50.30085681,-2.728430186,10500,0,199.9998535,0,0,0,90.00000001 +331.01,50.30085681,-2.728402161,10500,0,200.0009685,0,0,0,90.00000001 +331.02,50.30085681,-2.728374135,10500,0,200.0009685,0,0,0,90.00000001 +331.03,50.30085681,-2.72834611,10500,0,199.9998535,0,0,0,90.00000001 +331.04,50.30085681,-2.728318085,10500,0,199.9991844,0,0,0,90.00000001 +331.05,50.30085681,-2.72829006,10500,0,199.9998535,0,0,0,90.00000001 +331.06,50.30085681,-2.728262035,10500,0,200.0009685,0,0,0,90.00000001 +331.07,50.30085681,-2.728234009,10500,0,200.0009685,0,0,0,90.00000001 +331.08,50.30085681,-2.728205984,10500,0,199.9998535,0,0,0,90.00000001 +331.09,50.30085681,-2.728177959,10500,0,199.9991844,0,0,0,90.00000001 +331.1,50.30085681,-2.728149934,10500,0,199.9998535,0,0,0,90.00000001 +331.11,50.30085681,-2.728121909,10500,0,200.0009685,0,0,0,90.00000001 +331.12,50.30085681,-2.728093883,10500,0,200.0009685,0,0,0,90.00000001 +331.13,50.30085681,-2.728065858,10500,0,199.9998535,0,0,0,90.00000001 +331.14,50.30085681,-2.728037833,10500,0,199.9991844,0,0,0,90.00000001 +331.15,50.30085681,-2.728009808,10500,0,199.9998535,0,0,0,90.00000001 +331.16,50.30085681,-2.727981783,10500,0,200.0009685,0,0,0,90.00000001 +331.17,50.30085681,-2.727953757,10500,0,200.0009685,0,0,0,90.00000001 +331.18,50.30085681,-2.727925732,10500,0,199.9998535,0,0,0,90.00000001 +331.19,50.30085681,-2.727897707,10500,0,199.9989614,0,0,0,90.00000001 +331.2,50.30085681,-2.727869682,10500,0,199.9989614,0,0,0,90.00000001 +331.21,50.30085681,-2.727841657,10500,0,199.9998535,0,0,0,90.00000001 +331.22,50.30085681,-2.727813632,10500,0,200.0009685,0,0,0,90.00000001 +331.23,50.30085681,-2.727785606,10500,0,200.0009685,0,0,0,90.00000001 +331.24,50.30085681,-2.727757581,10500,0,199.9998535,0,0,0,90.00000001 +331.25,50.30085681,-2.727729556,10500,0,199.9989614,0,0,0,90.00000001 +331.26,50.30085681,-2.727701531,10500,0,199.9989614,0,0,0,90.00000001 +331.27,50.30085681,-2.727673506,10500,0,199.9998535,0,0,0,90.00000001 +331.28,50.30085681,-2.727645481,10500,0,200.0009685,0,0,0,90.00000001 +331.29,50.30085681,-2.727617455,10500,0,200.0009685,0,0,0,90.00000001 +331.3,50.30085681,-2.72758943,10500,0,199.9998535,0,0,0,90.00000001 +331.31,50.30085681,-2.727561405,10500,0,199.9989614,0,0,0,90.00000001 +331.32,50.30085681,-2.72753338,10500,0,199.9987384,0,0,0,90.00000001 +331.33,50.30085681,-2.727505355,10500,0,199.9989614,0,0,0,90.00000001 +331.34,50.30085681,-2.72747733,10500,0,199.9998535,0,0,0,90.00000001 +331.35,50.30085681,-2.727449305,10500,0,200.0009685,0,0,0,90.00000001 +331.36,50.30085681,-2.727421279,10500,0,200.0009685,0,0,0,90.00000001 +331.37,50.30085681,-2.727393254,10500,0,199.9998535,0,0,0,90.00000001 +331.38,50.30085681,-2.727365229,10500,0,199.9989614,0,0,0,90.00000001 +331.39,50.30085681,-2.727337204,10500,0,199.9989614,0,0,0,90.00000001 +331.4,50.30085681,-2.727309179,10500,0,199.9998535,0,0,0,90.00000001 +331.41,50.30085681,-2.727281154,10500,0,200.0009685,0,0,0,90.00000001 +331.42,50.30085681,-2.727253128,10500,0,200.0009685,0,0,0,90.00000001 +331.43,50.30085681,-2.727225103,10500,0,199.9998535,0,0,0,90.00000001 +331.44,50.30085681,-2.727197078,10500,0,199.9989614,0,0,0,90.00000001 +331.45,50.30085681,-2.727169053,10500,0,199.9989614,0,0,0,90.00000001 +331.46,50.30085681,-2.727141028,10500,0,199.9998535,0,0,0,90.00000001 +331.47,50.30085681,-2.727113003,10500,0,200.0009685,0,0,0,90.00000001 +331.48,50.30085681,-2.727084977,10500,0,200.0009685,0,0,0,90.00000001 +331.49,50.30085681,-2.727056952,10500,0,199.9998535,0,0,0,90.00000001 +331.5,50.30085681,-2.727028927,10500,0,199.9989614,0,0,0,90.00000001 +331.51,50.30085681,-2.727000902,10500,0,199.9989614,0,0,0,90.00000001 +331.52,50.30085681,-2.726972877,10500,0,199.9998535,0,0,0,90.00000001 +331.53,50.30085681,-2.726944852,10500,0,200.0009685,0,0,0,90.00000001 +331.54,50.30085681,-2.726916826,10500,0,200.0009685,0,0,0,90.00000001 +331.55,50.30085681,-2.726888801,10500,0,199.9998535,0,0,0,90.00000001 +331.56,50.30085681,-2.726860776,10500,0,199.9991844,0,0,0,90.00000001 +331.57,50.30085681,-2.726832751,10500,0,199.9998535,0,0,0,90.00000001 +331.58,50.30085681,-2.726804726,10500,0,200.0009685,0,0,0,90.00000001 +331.59,50.30085681,-2.7267767,10500,0,200.0009685,0,0,0,90.00000001 +331.6,50.30085681,-2.726748675,10500,0,199.9998535,0,0,0,90.00000001 +331.61,50.30085681,-2.72672065,10500,0,199.9991844,0,0,0,90.00000001 +331.62,50.30085681,-2.726692625,10500,0,199.9998535,0,0,0,90.00000001 +331.63,50.30085681,-2.7266646,10500,0,200.0009685,0,0,0,90.00000001 +331.64,50.30085681,-2.726636574,10500,0,200.0009685,0,0,0,90.00000001 +331.65,50.30085681,-2.726608549,10500,0,199.9998535,0,0,0,90.00000001 +331.66,50.30085681,-2.726580524,10500,0,199.9991844,0,0,0,90.00000001 +331.67,50.30085681,-2.726552499,10500,0,199.9998535,0,0,0,90.00000001 +331.68,50.30085681,-2.726524474,10500,0,200.0009685,0,0,0,90.00000001 +331.69,50.30085681,-2.726496448,10500,0,200.0009685,0,0,0,90.00000001 +331.7,50.30085681,-2.726468423,10500,0,199.9998535,0,0,0,90.00000001 +331.71,50.30085681,-2.726440398,10500,0,199.9991844,0,0,0,90.00000001 +331.72,50.30085681,-2.726412373,10500,0,199.9998535,0,0,0,90.00000001 +331.73,50.30085681,-2.726384348,10500,0,200.0009685,0,0,0,90.00000001 +331.74,50.30085681,-2.726356322,10500,0,200.0009685,0,0,0,90.00000001 +331.75,50.30085681,-2.726328297,10500,0,199.9998535,0,0,0,90.00000001 +331.76,50.30085681,-2.726300272,10500,0,199.9991844,0,0,0,90.00000001 +331.77,50.30085681,-2.726272247,10500,0,199.9998535,0,0,0,90.00000001 +331.78,50.30085681,-2.726244222,10500,0,200.0009685,0,0,0,90.00000001 +331.79,50.30085681,-2.726216196,10500,0,200.0009685,0,0,0,90.00000001 +331.8,50.30085681,-2.726188171,10500,0,199.9998535,0,0,0,90.00000001 +331.81,50.30085681,-2.726160146,10500,0,199.9989614,0,0,0,90.00000001 +331.82,50.30085681,-2.726132121,10500,0,199.9989614,0,0,0,90.00000001 +331.83,50.30085681,-2.726104096,10500,0,199.9998535,0,0,0,90.00000001 +331.84,50.30085681,-2.726076071,10500,0,200.0009685,0,0,0,90.00000001 +331.85,50.30085681,-2.726048045,10500,0,200.0009685,0,0,0,90.00000001 +331.86,50.30085681,-2.72602002,10500,0,199.9998535,0,0,0,90.00000001 +331.87,50.30085681,-2.725991995,10500,0,199.9989614,0,0,0,90.00000001 +331.88,50.30085681,-2.72596397,10500,0,199.9987384,0,0,0,90.00000001 +331.89,50.30085681,-2.725935945,10500,0,199.9989614,0,0,0,90.00000001 +331.9,50.30085681,-2.72590792,10500,0,199.9998535,0,0,0,90.00000001 +331.91,50.30085681,-2.725879895,10500,0,200.0009685,0,0,0,90.00000001 +331.92,50.30085681,-2.725851869,10500,0,200.0009685,0,0,0,90.00000001 +331.93,50.30085681,-2.725823844,10500,0,199.9998535,0,0,0,90.00000001 +331.94,50.30085681,-2.725795819,10500,0,199.9989614,0,0,0,90.00000001 +331.95,50.30085681,-2.725767794,10500,0,199.9989614,0,0,0,90.00000001 +331.96,50.30085681,-2.725739769,10500,0,199.9998535,0,0,0,90.00000001 +331.97,50.30085681,-2.725711744,10500,0,200.0009685,0,0,0,90.00000001 +331.98,50.30085681,-2.725683718,10500,0,200.0009685,0,0,0,90.00000001 +331.99,50.30085681,-2.725655693,10500,0,199.9998535,0,0,0,90.00000001 +332,50.30085681,-2.725627668,10500,0,199.9989614,0,0,0,90.00000001 +332.01,50.30085681,-2.725599643,10500,0,199.9989614,0,0,0,90.00000001 +332.02,50.30085681,-2.725571618,10500,0,199.9998535,0,0,0,90.00000001 +332.03,50.30085681,-2.725543593,10500,0,200.0009685,0,0,0,90.00000001 +332.04,50.30085681,-2.725515567,10500,0,200.0009685,0,0,0,90.00000001 +332.05,50.30085681,-2.725487542,10500,0,199.9998535,0,0,0,90.00000001 +332.06,50.30085681,-2.725459517,10500,0,199.9989614,0,0,0,90.00000001 +332.07,50.30085681,-2.725431492,10500,0,199.9989614,0,0,0,90.00000001 +332.08,50.30085681,-2.725403467,10500,0,199.9998535,0,0,0,90.00000001 +332.09,50.30085681,-2.725375442,10500,0,200.0009685,0,0,0,90.00000001 +332.1,50.30085681,-2.725347416,10500,0,200.0009685,0,0,0,90.00000001 +332.11,50.30085681,-2.725319391,10500,0,199.9998535,0,0,0,90.00000001 +332.12,50.30085681,-2.725291366,10500,0,199.9989614,0,0,0,90.00000001 +332.13,50.30085681,-2.725263341,10500,0,199.9989614,0,0,0,90.00000001 +332.14,50.30085681,-2.725235316,10500,0,199.9998535,0,0,0,90.00000001 +332.15,50.30085681,-2.725207291,10500,0,200.0009685,0,0,0,90.00000001 +332.16,50.30085681,-2.725179265,10500,0,200.0009685,0,0,0,90.00000001 +332.17,50.30085681,-2.72515124,10500,0,199.9998535,0,0,0,90.00000001 +332.18,50.30085681,-2.725123215,10500,0,199.9989614,0,0,0,90.00000001 +332.19,50.30085681,-2.72509519,10500,0,199.9989614,0,0,0,90.00000001 +332.2,50.30085681,-2.725067165,10500,0,199.9998535,0,0,0,90.00000001 +332.21,50.30085681,-2.72503914,10500,0,200.0009685,0,0,0,90.00000001 +332.22,50.30085681,-2.725011114,10500,0,200.0009685,0,0,0,90.00000001 +332.23,50.30085681,-2.724983089,10500,0,199.9998535,0,0,0,90.00000001 +332.24,50.30085681,-2.724955064,10500,0,199.9991844,0,0,0,90.00000001 +332.25,50.30085681,-2.724927039,10500,0,199.9998535,0,0,0,90.00000001 +332.26,50.30085681,-2.724899014,10500,0,200.0009685,0,0,0,90.00000001 +332.27,50.30085681,-2.724870988,10500,0,200.0009685,0,0,0,90.00000001 +332.28,50.30085681,-2.724842963,10500,0,199.9998535,0,0,0,90.00000001 +332.29,50.30085681,-2.724814938,10500,0,199.9991844,0,0,0,90.00000001 +332.3,50.30085681,-2.724786913,10500,0,199.9998535,0,0,0,90.00000001 +332.31,50.30085681,-2.724758888,10500,0,200.0009685,0,0,0,90.00000001 +332.32,50.30085681,-2.724730862,10500,0,200.0009685,0,0,0,90.00000001 +332.33,50.30085681,-2.724702837,10500,0,199.9998535,0,0,0,90.00000001 +332.34,50.30085681,-2.724674812,10500,0,199.9991844,0,0,0,90.00000001 +332.35,50.30085681,-2.724646787,10500,0,199.9998535,0,0,0,90.00000001 +332.36,50.30085681,-2.724618762,10500,0,200.0009685,0,0,0,90.00000001 +332.37,50.30085681,-2.724590736,10500,0,200.0009685,0,0,0,90.00000001 +332.38,50.30085681,-2.724562711,10500,0,199.9998535,0,0,0,90.00000001 +332.39,50.30085681,-2.724534686,10500,0,199.9991844,0,0,0,90.00000001 +332.4,50.30085681,-2.724506661,10500,0,199.9998535,0,0,0,90.00000001 +332.41,50.30085681,-2.724478636,10500,0,200.0009685,0,0,0,90.00000001 +332.42,50.30085681,-2.72445061,10500,0,200.0009685,0,0,0,90.00000001 +332.43,50.30085681,-2.724422585,10500,0,199.9998535,0,0,0,90.00000001 +332.44,50.30085681,-2.72439456,10500,0,199.9989614,0,0,0,90.00000001 +332.45,50.30085681,-2.724366535,10500,0,199.9989614,0,0,0,90.00000001 +332.46,50.30085681,-2.72433851,10500,0,199.9998535,0,0,0,90.00000001 +332.47,50.30085681,-2.724310485,10500,0,200.0009685,0,0,0,90.00000001 +332.48,50.30085681,-2.724282459,10500,0,200.0009685,0,0,0,90.00000001 +332.49,50.30085681,-2.724254434,10500,0,199.9998535,0,0,0,90.00000001 +332.5,50.30085681,-2.724226409,10500,0,199.9989614,0,0,0,90.00000001 +332.51,50.30085681,-2.724198384,10500,0,199.9989614,0,0,0,90.00000001 +332.52,50.30085681,-2.724170359,10500,0,199.9998535,0,0,0,90.00000001 +332.53,50.30085681,-2.724142334,10500,0,200.0009685,0,0,0,90.00000001 +332.54,50.30085681,-2.724114308,10500,0,200.0009685,0,0,0,90.00000001 +332.55,50.30085681,-2.724086283,10500,0,199.9998535,0,0,0,90.00000001 +332.56,50.30085681,-2.724058258,10500,0,199.9989614,0,0,0,90.00000001 +332.57,50.30085681,-2.724030233,10500,0,199.9989614,0,0,0,90.00000001 +332.58,50.30085681,-2.724002208,10500,0,199.9998535,0,0,0,90.00000001 +332.59,50.30085681,-2.723974183,10500,0,200.0009685,0,0,0,90.00000001 +332.6,50.30085681,-2.723946157,10500,0,200.0009685,0,0,0,90.00000001 +332.61,50.30085681,-2.723918132,10500,0,199.9998535,0,0,0,90.00000001 +332.62,50.30085681,-2.723890107,10500,0,199.9989614,0,0,0,90.00000001 +332.63,50.30085681,-2.723862082,10500,0,199.9989614,0,0,0,90.00000001 +332.64,50.30085681,-2.723834057,10500,0,199.9998535,0,0,0,90.00000001 +332.65,50.30085681,-2.723806032,10500,0,200.0009685,0,0,0,90.00000001 +332.66,50.30085681,-2.723778006,10500,0,200.0009685,0,0,0,90.00000001 +332.67,50.30085681,-2.723749981,10500,0,199.9998535,0,0,0,90.00000001 +332.68,50.30085681,-2.723721956,10500,0,199.9989614,0,0,0,90.00000001 +332.69,50.30085681,-2.723693931,10500,0,199.9989614,0,0,0,90.00000001 +332.7,50.30085681,-2.723665906,10500,0,199.9998535,0,0,0,90.00000001 +332.71,50.30085681,-2.723637881,10500,0,200.0009685,0,0,0,90.00000001 +332.72,50.30085681,-2.723609855,10500,0,200.0009685,0,0,0,90.00000001 +332.73,50.30085681,-2.72358183,10500,0,199.9998535,0,0,0,90.00000001 +332.74,50.30085681,-2.723553805,10500,0,199.9989614,0,0,0,90.00000001 +332.75,50.30085681,-2.72352578,10500,0,199.9987384,0,0,0,90.00000001 +332.76,50.30085681,-2.723497755,10500,0,199.9989614,0,0,0,90.00000001 +332.77,50.30085681,-2.72346973,10500,0,199.9998535,0,0,0,90.00000001 +332.78,50.30085681,-2.723441705,10500,0,200.0009685,0,0,0,90.00000001 +332.79,50.30085681,-2.723413679,10500,0,200.0009685,0,0,0,90.00000001 +332.8,50.30085681,-2.723385654,10500,0,199.9998535,0,0,0,90.00000001 +332.81,50.30085681,-2.723357629,10500,0,199.9991844,0,0,0,90.00000001 +332.82,50.30085681,-2.723329604,10500,0,199.9998535,0,0,0,90.00000001 +332.83,50.30085681,-2.723301579,10500,0,200.0009685,0,0,0,90.00000001 +332.84,50.30085681,-2.723273553,10500,0,200.0009685,0,0,0,90.00000001 +332.85,50.30085681,-2.723245528,10500,0,199.9998535,0,0,0,90.00000001 +332.86,50.30085681,-2.723217503,10500,0,199.9991844,0,0,0,90.00000001 +332.87,50.30085681,-2.723189478,10500,0,199.9998535,0,0,0,90.00000001 +332.88,50.30085681,-2.723161453,10500,0,200.0009685,0,0,0,90.00000001 +332.89,50.30085681,-2.723133427,10500,0,200.0009685,0,0,0,90.00000001 +332.9,50.30085681,-2.723105402,10500,0,199.9998535,0,0,0,90.00000001 +332.91,50.30085681,-2.723077377,10500,0,199.9991844,0,0,0,90.00000001 +332.92,50.30085681,-2.723049352,10500,0,199.9998535,0,0,0,90.00000001 +332.93,50.30085681,-2.723021327,10500,0,200.0009685,0,0,0,90.00000001 +332.94,50.30085681,-2.722993301,10500,0,200.0009685,0,0,0,90.00000001 +332.95,50.30085681,-2.722965276,10500,0,199.9998535,0,0,0,90.00000001 +332.96,50.30085681,-2.722937251,10500,0,199.9991844,0,0,0,90.00000001 +332.97,50.30085681,-2.722909226,10500,0,199.9998535,0,0,0,90.00000001 +332.98,50.30085681,-2.722881201,10500,0,200.0009685,0,0,0,90.00000001 +332.99,50.30085681,-2.722853175,10500,0,200.0009685,0,0,0,90.00000001 +333,50.30085681,-2.72282515,10500,0,199.9998535,0,0,0,90.00000001 +333.01,50.30085681,-2.722797125,10500,0,199.9991844,0,0,0,90.00000001 +333.02,50.30085681,-2.7227691,10500,0,199.9998535,0,0,0,90.00000001 +333.03,50.30085681,-2.722741075,10500,0,200.0009685,0,0,0,90.00000001 +333.04,50.30085681,-2.722713049,10500,0,200.0009685,0,0,0,90.00000001 +333.05,50.30085681,-2.722685024,10500,0,199.9998535,0,0,0,90.00000001 +333.06,50.30085681,-2.722656999,10500,0,199.9989614,0,0,0,90.00000001 +333.07,50.30085681,-2.722628974,10500,0,199.9989614,0,0,0,90.00000001 +333.08,50.30085681,-2.722600949,10500,0,199.9998535,0,0,0,90.00000001 +333.09,50.30085681,-2.722572924,10500,0,200.0009685,0,0,0,90.00000001 +333.1,50.30085681,-2.722544898,10500,0,200.0009685,0,0,0,90.00000001 +333.11,50.30085681,-2.722516873,10500,0,199.9998535,0,0,0,90.00000001 +333.12,50.30085681,-2.722488848,10500,0,199.9989614,0,0,0,90.00000001 +333.13,50.30085681,-2.722460823,10500,0,199.9989614,0,0,0,90.00000001 +333.14,50.30085681,-2.722432798,10500,0,199.9998535,0,0,0,90.00000001 +333.15,50.30085681,-2.722404773,10500,0,200.0009685,0,0,0,90.00000001 +333.16,50.30085681,-2.722376747,10500,0,200.0009685,0,0,0,90.00000001 +333.17,50.30085681,-2.722348722,10500,0,199.9998535,0,0,0,90.00000001 +333.18,50.30085681,-2.722320697,10500,0,199.9989614,0,0,0,90.00000001 +333.19,50.30085681,-2.722292672,10500,0,199.9989614,0,0,0,90.00000001 +333.2,50.30085681,-2.722264647,10500,0,199.9998535,0,0,0,90.00000001 +333.21,50.30085681,-2.722236622,10500,0,200.0009685,0,0,0,90.00000001 +333.22,50.30085681,-2.722208596,10500,0,200.0009685,0,0,0,90.00000001 +333.23,50.30085681,-2.722180571,10500,0,199.9998535,0,0,0,90.00000001 +333.24,50.30085681,-2.722152546,10500,0,199.9989614,0,0,0,90.00000001 +333.25,50.30085681,-2.722124521,10500,0,199.9989614,0,0,0,90.00000001 +333.26,50.30085681,-2.722096496,10500,0,199.9998535,0,0,0,90.00000001 +333.27,50.30085681,-2.722068471,10500,0,200.0009685,0,0,0,90.00000001 +333.28,50.30085681,-2.722040445,10500,0,200.0009685,0,0,0,90.00000001 +333.29,50.30085681,-2.72201242,10500,0,199.9998535,0,0,0,90.00000001 +333.3,50.30085681,-2.721984395,10500,0,199.9989614,0,0,0,90.00000001 +333.31,50.30085681,-2.72195637,10500,0,199.9987384,0,0,0,90.00000001 +333.32,50.30085681,-2.721928345,10500,0,199.9989614,0,0,0,90.00000001 +333.33,50.30085681,-2.72190032,10500,0,199.9998535,0,0,0,90.00000001 +333.34,50.30085681,-2.721872295,10500,0,200.0009685,0,0,0,90.00000001 +333.35,50.30085681,-2.721844269,10500,0,200.0009685,0,0,0,90.00000001 +333.36,50.30085681,-2.721816244,10500,0,199.9998535,0,0,0,90.00000001 +333.37,50.30085681,-2.721788219,10500,0,199.9989614,0,0,0,90.00000001 +333.38,50.30085681,-2.721760194,10500,0,199.9989614,0,0,0,90.00000001 +333.39,50.30085681,-2.721732169,10500,0,199.9998535,0,0,0,90.00000001 +333.4,50.30085681,-2.721704144,10500,0,200.0009685,0,0,0,90.00000001 +333.41,50.30085681,-2.721676118,10500,0,200.0009685,0,0,0,90.00000001 +333.42,50.30085681,-2.721648093,10500,0,199.9998535,0,0,0,90.00000001 +333.43,50.30085681,-2.721620068,10500,0,199.9991844,0,0,0,90.00000001 +333.44,50.30085681,-2.721592043,10500,0,199.9998535,0,0,0,90.00000001 +333.45,50.30085681,-2.721564018,10500,0,200.0009685,0,0,0,90.00000001 +333.46,50.30085681,-2.721535992,10500,0,200.0009685,0,0,0,90.00000001 +333.47,50.30085681,-2.721507967,10500,0,199.9998535,0,0,0,90.00000001 +333.48,50.30085681,-2.721479942,10500,0,199.9991844,0,0,0,90.00000001 +333.49,50.30085681,-2.721451917,10500,0,199.9998535,0,0,0,90.00000001 +333.5,50.30085681,-2.721423892,10500,0,200.0009685,0,0,0,90.00000001 +333.51,50.30085681,-2.721395866,10500,0,200.0009685,0,0,0,90.00000001 +333.52,50.30085681,-2.721367841,10500,0,199.9998535,0,0,0,90.00000001 +333.53,50.30085681,-2.721339816,10500,0,199.9991844,0,0,0,90.00000001 +333.54,50.30085681,-2.721311791,10500,0,199.9998535,0,0,0,90.00000001 +333.55,50.30085681,-2.721283766,10500,0,200.0009685,0,0,0,90.00000001 +333.56,50.30085681,-2.72125574,10500,0,200.0009685,0,0,0,90.00000001 +333.57,50.30085681,-2.721227715,10500,0,199.9998535,0,0,0,90.00000001 +333.58,50.30085681,-2.72119969,10500,0,199.9991844,0,0,0,90.00000001 +333.59,50.30085681,-2.721171665,10500,0,199.9998535,0,0,0,90.00000001 +333.6,50.30085681,-2.72114364,10500,0,200.0009685,0,0,0,90.00000001 +333.61,50.30085681,-2.721115614,10500,0,200.0009685,0,0,0,90.00000001 +333.62,50.30085681,-2.721087589,10500,0,199.9998535,0,0,0,90.00000001 +333.63,50.30085681,-2.721059564,10500,0,199.9991844,0,0,0,90.00000001 +333.64,50.30085681,-2.721031539,10500,0,199.9998535,0,0,0,90.00000001 +333.65,50.30085681,-2.721003514,10500,0,200.0009685,0,0,0,90.00000001 +333.66,50.30085681,-2.720975488,10500,0,200.0009685,0,0,0,90.00000001 +333.67,50.30085681,-2.720947463,10500,0,199.9998535,0,0,0,90.00000001 +333.68,50.30085681,-2.720919438,10500,0,199.9989614,0,0,0,90.00000001 +333.69,50.30085681,-2.720891413,10500,0,199.9989614,0,0,0,90.00000001 +333.7,50.30085681,-2.720863388,10500,0,199.9998535,0,0,0,90.00000001 +333.71,50.30085681,-2.720835363,10500,0,200.0009685,0,0,0,90.00000001 +333.72,50.30085681,-2.720807337,10500,0,200.0009685,0,0,0,90.00000001 +333.73,50.30085681,-2.720779312,10500,0,199.9998535,0,0,0,90.00000001 +333.74,50.30085681,-2.720751287,10500,0,199.9989614,0,0,0,90.00000001 +333.75,50.30085681,-2.720723262,10500,0,199.9989614,0,0,0,90.00000001 +333.76,50.30085681,-2.720695237,10500,0,199.9998535,0,0,0,90.00000001 +333.77,50.30085681,-2.720667212,10500,0,200.0009685,0,0,0,90.00000001 +333.78,50.30085681,-2.720639186,10500,0,200.0009685,0,0,0,90.00000001 +333.79,50.30085681,-2.720611161,10500,0,199.9998535,0,0,0,90.00000001 +333.8,50.30085681,-2.720583136,10500,0,199.9989614,0,0,0,90.00000001 +333.81,50.30085681,-2.720555111,10500,0,199.9989614,0,0,0,90.00000001 +333.82,50.30085681,-2.720527086,10500,0,199.9998535,0,0,0,90.00000001 +333.83,50.30085681,-2.720499061,10500,0,200.0009685,0,0,0,90.00000001 +333.84,50.30085681,-2.720471035,10500,0,200.0009685,0,0,0,90.00000001 +333.85,50.30085681,-2.72044301,10500,0,199.9998535,0,0,0,90.00000001 +333.86,50.30085681,-2.720414985,10500,0,199.9989614,0,0,0,90.00000001 +333.87,50.30085681,-2.72038696,10500,0,199.9987384,0,0,0,90.00000001 +333.88,50.30085681,-2.720358935,10500,0,199.9989614,0,0,0,90.00000001 +333.89,50.30085681,-2.72033091,10500,0,199.9998535,0,0,0,90.00000001 +333.9,50.30085681,-2.720302885,10500,0,200.0009685,0,0,0,90.00000001 +333.91,50.30085681,-2.720274859,10500,0,200.0009685,0,0,0,90.00000001 +333.92,50.30085681,-2.720246834,10500,0,199.9998535,0,0,0,90.00000001 +333.93,50.30085681,-2.720218809,10500,0,199.9989614,0,0,0,90.00000001 +333.94,50.30085681,-2.720190784,10500,0,199.9989614,0,0,0,90.00000001 +333.95,50.30085681,-2.720162759,10500,0,199.9998535,0,0,0,90.00000001 +333.96,50.30085681,-2.720134734,10500,0,200.0009685,0,0,0,90.00000001 +333.97,50.30085681,-2.720106708,10500,0,200.0009685,0,0,0,90.00000001 +333.98,50.30085681,-2.720078683,10500,0,199.9998535,0,0,0,90.00000001 +333.99,50.30085681,-2.720050658,10500,0,199.9989614,0,0,0,90.00000001 +334,50.30085681,-2.720022633,10500,0,199.9989614,0,0,0,90.00000001 +334.01,50.30085681,-2.719994608,10500,0,199.9998535,0,0,0,90.00000001 +334.02,50.30085681,-2.719966583,10500,0,200.0009685,0,0,0,90.00000001 +334.03,50.30085681,-2.719938557,10500,0,200.0009685,0,0,0,90.00000001 +334.04,50.30085681,-2.719910532,10500,0,199.9998535,0,0,0,90.00000001 +334.05,50.30085681,-2.719882507,10500,0,199.9991844,0,0,0,90.00000001 +334.06,50.30085681,-2.719854482,10500,0,199.9998535,0,0,0,90.00000001 +334.07,50.30085681,-2.719826457,10500,0,200.0009685,0,0,0,90.00000001 +334.08,50.30085681,-2.719798431,10500,0,200.0009685,0,0,0,90.00000001 +334.09,50.30085681,-2.719770406,10500,0,199.9998535,0,0,0,90.00000001 +334.1,50.30085681,-2.719742381,10500,0,199.9991844,0,0,0,90.00000001 +334.11,50.30085681,-2.719714356,10500,0,199.9998535,0,0,0,90.00000001 +334.12,50.30085681,-2.719686331,10500,0,200.0009685,0,0,0,90.00000001 +334.13,50.30085681,-2.719658305,10500,0,200.0009685,0,0,0,90.00000001 +334.14,50.30085681,-2.71963028,10500,0,199.9998535,0,0,0,90.00000001 +334.15,50.30085681,-2.719602255,10500,0,199.9991844,0,0,0,90.00000001 +334.16,50.30085681,-2.71957423,10500,0,199.9998535,0,0,0,90.00000001 +334.17,50.30085681,-2.719546205,10500,0,200.0009685,0,0,0,90.00000001 +334.18,50.30085681,-2.719518179,10500,0,200.0009685,0,0,0,90.00000001 +334.19,50.30085681,-2.719490154,10500,0,199.9998535,0,0,0,90.00000001 +334.2,50.30085681,-2.719462129,10500,0,199.9991844,0,0,0,90.00000001 +334.21,50.30085681,-2.719434104,10500,0,199.9998535,0,0,0,90.00000001 +334.22,50.30085681,-2.719406079,10500,0,200.0009685,0,0,0,90.00000001 +334.23,50.30085681,-2.719378053,10500,0,200.0009685,0,0,0,90.00000001 +334.24,50.30085681,-2.719350028,10500,0,199.9998535,0,0,0,90.00000001 +334.25,50.30085681,-2.719322003,10500,0,199.9989614,0,0,0,90.00000001 +334.26,50.30085681,-2.719293978,10500,0,199.9989614,0,0,0,90.00000001 +334.27,50.30085681,-2.719265953,10500,0,199.9998535,0,0,0,90.00000001 +334.28,50.30085681,-2.719237928,10500,0,200.0009685,0,0,0,90.00000001 +334.29,50.30085681,-2.719209902,10500,0,200.0009685,0,0,0,90.00000001 +334.3,50.30085681,-2.719181877,10500,0,199.9998535,0,0,0,90.00000001 +334.31,50.30085681,-2.719153852,10500,0,199.9991844,0,0,0,90.00000001 +334.32,50.30085681,-2.719125827,10500,0,199.9998535,0,0,0,90.00000001 +334.33,50.30085681,-2.719097802,10500,0,200.0009685,0,0,0,90.00000001 +334.34,50.30085681,-2.719069776,10500,0,200.0009685,0,0,0,90.00000001 +334.35,50.30085681,-2.719041751,10500,0,199.9998535,0,0,0,90.00000001 +334.36,50.30085681,-2.719013726,10500,0,199.9989614,0,0,0,90.00000001 +334.37,50.30085681,-2.718985701,10500,0,199.9989614,0,0,0,90.00000001 +334.38,50.30085681,-2.718957676,10500,0,199.9998535,0,0,0,90.00000001 +334.39,50.30085681,-2.718929651,10500,0,200.0009685,0,0,0,90.00000001 +334.4,50.30085681,-2.718901625,10500,0,200.0009685,0,0,0,90.00000001 +334.41,50.30085681,-2.7188736,10500,0,199.9998535,0,0,0,90.00000001 +334.42,50.30085681,-2.718845575,10500,0,199.9989614,0,0,0,90.00000001 +334.43,50.30085681,-2.71881755,10500,0,199.9987384,0,0,0,90.00000001 +334.44,50.30085681,-2.718789525,10500,0,199.9989614,0,0,0,90.00000001 +334.45,50.30085681,-2.7187615,10500,0,199.9998535,0,0,0,90.00000001 +334.46,50.30085681,-2.718733475,10500,0,200.0009685,0,0,0,90.00000001 +334.47,50.30085681,-2.718705449,10500,0,200.0009685,0,0,0,90.00000001 +334.48,50.30085681,-2.718677424,10500,0,199.9998535,0,0,0,90.00000001 +334.49,50.30085681,-2.718649399,10500,0,199.9989614,0,0,0,90.00000001 +334.5,50.30085681,-2.718621374,10500,0,199.9989614,0,0,0,90.00000001 +334.51,50.30085681,-2.718593349,10500,0,199.9998535,0,0,0,90.00000001 +334.52,50.30085681,-2.718565324,10500,0,200.0009685,0,0,0,90.00000001 +334.53,50.30085681,-2.718537298,10500,0,200.0009685,0,0,0,90.00000001 +334.54,50.30085681,-2.718509273,10500,0,199.9998535,0,0,0,90.00000001 +334.55,50.30085681,-2.718481248,10500,0,199.9989614,0,0,0,90.00000001 +334.56,50.30085681,-2.718453223,10500,0,199.9989614,0,0,0,90.00000001 +334.57,50.30085681,-2.718425198,10500,0,199.9998535,0,0,0,90.00000001 +334.58,50.30085681,-2.718397173,10500,0,200.0009685,0,0,0,90.00000001 +334.59,50.30085681,-2.718369147,10500,0,200.0009685,0,0,0,90.00000001 +334.6,50.30085681,-2.718341122,10500,0,199.9998535,0,0,0,90.00000001 +334.61,50.30085681,-2.718313097,10500,0,199.9989614,0,0,0,90.00000001 +334.62,50.30085681,-2.718285072,10500,0,199.9989614,0,0,0,90.00000001 +334.63,50.30085681,-2.718257047,10500,0,199.9998535,0,0,0,90.00000001 +334.64,50.30085681,-2.718229022,10500,0,200.0009685,0,0,0,90.00000001 +334.65,50.30085681,-2.718200996,10500,0,200.0009685,0,0,0,90.00000001 +334.66,50.30085681,-2.718172971,10500,0,199.9998535,0,0,0,90.00000001 +334.67,50.30085681,-2.718144946,10500,0,199.9989614,0,0,0,90.00000001 +334.68,50.30085681,-2.718116921,10500,0,199.9989614,0,0,0,90.00000001 +334.69,50.30085681,-2.718088896,10500,0,199.9998535,0,0,0,90.00000001 +334.7,50.30085681,-2.718060871,10500,0,200.0009685,0,0,0,90.00000001 +334.71,50.30085681,-2.718032845,10500,0,200.0009685,0,0,0,90.00000001 +334.72,50.30085681,-2.71800482,10500,0,199.9998535,0,0,0,90.00000001 +334.73,50.30085681,-2.717976795,10500,0,199.9991844,0,0,0,90.00000001 +334.74,50.30085681,-2.71794877,10500,0,199.9998535,0,0,0,90.00000001 +334.75,50.30085681,-2.717920745,10500,0,200.0009685,0,0,0,90.00000001 +334.76,50.30085681,-2.717892719,10500,0,200.0009685,0,0,0,90.00000001 +334.77,50.30085681,-2.717864694,10500,0,199.9998535,0,0,0,90.00000001 +334.78,50.30085681,-2.717836669,10500,0,199.9991844,0,0,0,90.00000001 +334.79,50.30085681,-2.717808644,10500,0,199.9998535,0,0,0,90.00000001 +334.8,50.30085681,-2.717780619,10500,0,200.0009685,0,0,0,90.00000001 +334.81,50.30085681,-2.717752593,10500,0,200.0009685,0,0,0,90.00000001 +334.82,50.30085681,-2.717724568,10500,0,199.9998535,0,0,0,90.00000001 +334.83,50.30085681,-2.717696543,10500,0,199.9991844,0,0,0,90.00000001 +334.84,50.30085681,-2.717668518,10500,0,199.9998535,0,0,0,90.00000001 +334.85,50.30085681,-2.717640493,10500,0,200.0009685,0,0,0,90.00000001 +334.86,50.30085681,-2.717612467,10500,0,200.0009685,0,0,0,90.00000001 +334.87,50.30085681,-2.717584442,10500,0,199.9998535,0,0,0,90.00000001 +334.88,50.30085681,-2.717556417,10500,0,199.9991844,0,0,0,90.00000001 +334.89,50.30085681,-2.717528392,10500,0,199.9998535,0,0,0,90.00000001 +334.9,50.30085681,-2.717500367,10500,0,200.0009685,0,0,0,90.00000001 +334.91,50.30085681,-2.717472341,10500,0,200.0009685,0,0,0,90.00000001 +334.92,50.30085681,-2.717444316,10500,0,199.9998535,0,0,0,90.00000001 +334.93,50.30085681,-2.717416291,10500,0,199.9991844,0,0,0,90.00000001 +334.94,50.30085681,-2.717388266,10500,0,199.9998535,0,0,0,90.00000001 +334.95,50.30085681,-2.717360241,10500,0,200.0009685,0,0,0,90.00000001 +334.96,50.30085681,-2.717332215,10500,0,200.0009685,0,0,0,90.00000001 +334.97,50.30085681,-2.71730419,10500,0,199.9998535,0,0,0,90.00000001 +334.98,50.30085681,-2.717276165,10500,0,199.9989614,0,0,0,90.00000001 +334.99,50.30085681,-2.71724814,10500,0,199.9989614,0,0,0,90.00000001 +335,50.30085681,-2.717220115,10500,0,199.9998535,0,0,0,90.00000001 +335.01,50.30085681,-2.71719209,10500,0,200.0009685,0,0,0,90.00000001 +335.02,50.30085681,-2.717164064,10500,0,200.0009685,0,0,0,90.00000001 +335.03,50.30085681,-2.717136039,10500,0,199.9998535,0,0,0,90.00000001 +335.04,50.30085681,-2.717108014,10500,0,199.9989614,0,0,0,90.00000001 +335.05,50.30085681,-2.717079989,10500,0,199.9987384,0,0,0,90.00000001 +335.06,50.30085681,-2.717051964,10500,0,199.9989614,0,0,0,90.00000001 +335.07,50.30085681,-2.717023939,10500,0,199.9998535,0,0,0,90.00000001 +335.08,50.30085681,-2.716995914,10500,0,200.0009685,0,0,0,90.00000001 +335.09,50.30085681,-2.716967888,10500,0,200.0009685,0,0,0,90.00000001 +335.1,50.30085681,-2.716939863,10500,0,199.9998535,0,0,0,90.00000001 +335.11,50.30085681,-2.716911838,10500,0,199.9989614,0,0,0,90.00000001 +335.12,50.30085681,-2.716883813,10500,0,199.9989614,0,0,0,90.00000001 +335.13,50.30085681,-2.716855788,10500,0,199.9998535,0,0,0,90.00000001 +335.14,50.30085681,-2.716827763,10500,0,200.0009685,0,0,0,90.00000001 +335.15,50.30085681,-2.716799737,10500,0,200.0009685,0,0,0,90.00000001 +335.16,50.30085681,-2.716771712,10500,0,199.9998535,0,0,0,90.00000001 +335.17,50.30085681,-2.716743687,10500,0,199.9989614,0,0,0,90.00000001 +335.18,50.30085681,-2.716715662,10500,0,199.9989614,0,0,0,90.00000001 +335.19,50.30085681,-2.716687637,10500,0,199.9998535,0,0,0,90.00000001 +335.2,50.30085681,-2.716659612,10500,0,200.0009685,0,0,0,90.00000001 +335.21,50.30085681,-2.716631586,10500,0,200.0009685,0,0,0,90.00000001 +335.22,50.30085681,-2.716603561,10500,0,199.9998535,0,0,0,90.00000001 +335.23,50.30085681,-2.716575536,10500,0,199.9989614,0,0,0,90.00000001 +335.24,50.30085681,-2.716547511,10500,0,199.9989614,0,0,0,90.00000001 +335.25,50.30085681,-2.716519486,10500,0,199.9998535,0,0,0,90.00000001 +335.26,50.30085681,-2.716491461,10500,0,200.0009685,0,0,0,90.00000001 +335.27,50.30085681,-2.716463435,10500,0,200.0009685,0,0,0,90.00000001 +335.28,50.30085681,-2.71643541,10500,0,199.9998535,0,0,0,90.00000001 +335.29,50.30085681,-2.716407385,10500,0,199.9989614,0,0,0,90.00000001 +335.3,50.30085681,-2.71637936,10500,0,199.9989614,0,0,0,90.00000001 +335.31,50.30085681,-2.716351335,10500,0,199.9998535,0,0,0,90.00000001 +335.32,50.30085681,-2.71632331,10500,0,200.0009685,0,0,0,90.00000001 +335.33,50.30085681,-2.716295284,10500,0,200.0009685,0,0,0,90.00000001 +335.34,50.30085681,-2.716267259,10500,0,199.9998535,0,0,0,90.00000001 +335.35,50.30085681,-2.716239234,10500,0,199.9991844,0,0,0,90.00000001 +335.36,50.30085681,-2.716211209,10500,0,199.9998535,0,0,0,90.00000001 +335.37,50.30085681,-2.716183184,10500,0,200.0009685,0,0,0,90.00000001 +335.38,50.30085681,-2.716155158,10500,0,200.0009685,0,0,0,90.00000001 +335.39,50.30085681,-2.716127133,10500,0,199.9998535,0,0,0,90.00000001 +335.4,50.30085681,-2.716099108,10500,0,199.9991844,0,0,0,90.00000001 +335.41,50.30085681,-2.716071083,10500,0,199.9998535,0,0,0,90.00000001 +335.42,50.30085681,-2.716043058,10500,0,200.0009685,0,0,0,90.00000001 +335.43,50.30085681,-2.716015032,10500,0,200.0009685,0,0,0,90.00000001 +335.44,50.30085681,-2.715987007,10500,0,199.9998535,0,0,0,90.00000001 +335.45,50.30085681,-2.715958982,10500,0,199.9991844,0,0,0,90.00000001 +335.46,50.30085681,-2.715930957,10500,0,199.9998535,0,0,0,90.00000001 +335.47,50.30085681,-2.715902932,10500,0,200.0009685,0,0,0,90.00000001 +335.48,50.30085681,-2.715874906,10500,0,200.0009685,0,0,0,90.00000001 +335.49,50.30085681,-2.715846881,10500,0,199.9998535,0,0,0,90.00000001 +335.5,50.30085681,-2.715818856,10500,0,199.9991844,0,0,0,90.00000001 +335.51,50.30085681,-2.715790831,10500,0,199.9998535,0,0,0,90.00000001 +335.52,50.30085681,-2.715762806,10500,0,200.0009685,0,0,0,90.00000001 +335.53,50.30085681,-2.71573478,10500,0,200.0009685,0,0,0,90.00000001 +335.54,50.30085681,-2.715706755,10500,0,199.9998535,0,0,0,90.00000001 +335.55,50.30085681,-2.71567873,10500,0,199.9991844,0,0,0,90.00000001 +335.56,50.30085681,-2.715650705,10500,0,199.9998535,0,0,0,90.00000001 +335.57,50.30085681,-2.71562268,10500,0,200.0009685,0,0,0,90.00000001 +335.58,50.30085681,-2.715594654,10500,0,200.0009685,0,0,0,90.00000001 +335.59,50.30085681,-2.715566629,10500,0,199.9998535,0,0,0,90.00000001 +335.6,50.30085681,-2.715538604,10500,0,199.9989614,0,0,0,90.00000001 +335.61,50.30085681,-2.715510579,10500,0,199.9987384,0,0,0,90.00000001 +335.62,50.30085681,-2.715482554,10500,0,199.9989614,0,0,0,90.00000001 +335.63,50.30085681,-2.715454529,10500,0,199.9998535,0,0,0,90.00000001 +335.64,50.30085681,-2.715426504,10500,0,200.0009685,0,0,0,90.00000001 +335.65,50.30085681,-2.715398478,10500,0,200.0009685,0,0,0,90.00000001 +335.66,50.30085681,-2.715370453,10500,0,199.9998535,0,0,0,90.00000001 +335.67,50.30085681,-2.715342428,10500,0,199.9989614,0,0,0,90.00000001 +335.68,50.30085681,-2.715314403,10500,0,199.9989614,0,0,0,90.00000001 +335.69,50.30085681,-2.715286378,10500,0,199.9998535,0,0,0,90.00000001 +335.7,50.30085681,-2.715258353,10500,0,200.0009685,0,0,0,90.00000001 +335.71,50.30085681,-2.715230327,10500,0,200.0009685,0,0,0,90.00000001 +335.72,50.30085681,-2.715202302,10500,0,199.9998535,0,0,0,90.00000001 +335.73,50.30085681,-2.715174277,10500,0,199.9989614,0,0,0,90.00000001 +335.74,50.30085681,-2.715146252,10500,0,199.9989614,0,0,0,90.00000001 +335.75,50.30085681,-2.715118227,10500,0,199.9998535,0,0,0,90.00000001 +335.76,50.30085681,-2.715090202,10500,0,200.0009685,0,0,0,90.00000001 +335.77,50.30085681,-2.715062176,10500,0,200.0009685,0,0,0,90.00000001 +335.78,50.30085681,-2.715034151,10500,0,199.9998535,0,0,0,90.00000001 +335.79,50.30085681,-2.715006126,10500,0,199.9989614,0,0,0,90.00000001 +335.8,50.30085681,-2.714978101,10500,0,199.9989614,0,0,0,90.00000001 +335.81,50.30085681,-2.714950076,10500,0,199.9998535,0,0,0,90.00000001 +335.82,50.30085681,-2.714922051,10500,0,200.0009685,0,0,0,90.00000001 +335.83,50.30085681,-2.714894025,10500,0,200.0009685,0,0,0,90.00000001 +335.84,50.30085681,-2.714866,10500,0,199.9998535,0,0,0,90.00000001 +335.85,50.30085681,-2.714837975,10500,0,199.9989614,0,0,0,90.00000001 +335.86,50.30085681,-2.71480995,10500,0,199.9987384,0,0,0,90.00000001 +335.87,50.30085681,-2.714781925,10500,0,199.9989614,0,0,0,90.00000001 +335.88,50.30085681,-2.7147539,10500,0,199.9998535,0,0,0,90.00000001 +335.89,50.30085681,-2.714725875,10500,0,200.0009685,0,0,0,90.00000001 +335.9,50.30085681,-2.714697849,10500,0,200.0009685,0,0,0,90.00000001 +335.91,50.30085681,-2.714669824,10500,0,199.9998535,0,0,0,90.00000001 +335.92,50.30085681,-2.714641799,10500,0,199.9991844,0,0,0,90.00000001 +335.93,50.30085681,-2.714613774,10500,0,199.9998535,0,0,0,90.00000001 +335.94,50.30085681,-2.714585749,10500,0,200.0009685,0,0,0,90.00000001 +335.95,50.30085681,-2.714557723,10500,0,200.0009685,0,0,0,90.00000001 +335.96,50.30085681,-2.714529698,10500,0,199.9998535,0,0,0,90.00000001 +335.97,50.30085681,-2.714501673,10500,0,199.9991844,0,0,0,90.00000001 +335.98,50.30085681,-2.714473648,10500,0,199.9998535,0,0,0,90.00000001 +335.99,50.30085681,-2.714445623,10500,0,200.0009685,0,0,0,90.00000001 +336,50.30085681,-2.714417597,10500,0,200.0009685,0,0,0,90.00000001 +336.01,50.30085681,-2.714389572,10500,0,199.9998535,0,0,0,90.00000001 +336.02,50.30085681,-2.714361547,10500,0,199.9991844,0,0,0,90.00000001 +336.03,50.30085681,-2.714333522,10500,0,199.9998535,0,0,0,90.00000001 +336.04,50.30085681,-2.714305497,10500,0,200.0009685,0,0,0,90.00000001 +336.05,50.30085681,-2.714277471,10500,0,200.0009685,0,0,0,90.00000001 +336.06,50.30085681,-2.714249446,10500,0,199.9998535,0,0,0,90.00000001 +336.07,50.30085681,-2.714221421,10500,0,199.9991844,0,0,0,90.00000001 +336.08,50.30085681,-2.714193396,10500,0,199.9998535,0,0,0,90.00000001 +336.09,50.30085681,-2.714165371,10500,0,200.0009685,0,0,0,90.00000001 +336.1,50.30085681,-2.714137345,10500,0,200.0009685,0,0,0,90.00000001 +336.11,50.30085681,-2.71410932,10500,0,199.9998535,0,0,0,90.00000001 +336.12,50.30085681,-2.714081295,10500,0,199.9991844,0,0,0,90.00000001 +336.13,50.30085681,-2.71405327,10500,0,199.9998535,0,0,0,90.00000001 +336.14,50.30085681,-2.714025245,10500,0,200.0009685,0,0,0,90.00000001 +336.15,50.30085681,-2.713997219,10500,0,200.0009685,0,0,0,90.00000001 +336.16,50.30085681,-2.713969194,10500,0,199.9998535,0,0,0,90.00000001 +336.17,50.30085681,-2.713941169,10500,0,199.9989614,0,0,0,90.00000001 +336.18,50.30085681,-2.713913144,10500,0,199.9989614,0,0,0,90.00000001 +336.19,50.30085681,-2.713885119,10500,0,199.9998535,0,0,0,90.00000001 +336.2,50.30085681,-2.713857094,10500,0,200.0009685,0,0,0,90.00000001 +336.21,50.30085681,-2.713829068,10500,0,200.0009685,0,0,0,90.00000001 +336.22,50.30085681,-2.713801043,10500,0,199.9998535,0,0,0,90.00000001 +336.23,50.30085681,-2.713773018,10500,0,199.9989614,0,0,0,90.00000001 +336.24,50.30085681,-2.713744993,10500,0,199.9989614,0,0,0,90.00000001 +336.25,50.30085681,-2.713716968,10500,0,199.9998535,0,0,0,90.00000001 +336.26,50.30085681,-2.713688943,10500,0,200.0009685,0,0,0,90.00000001 +336.27,50.30085681,-2.713660917,10500,0,200.0009685,0,0,0,90.00000001 +336.28,50.30085681,-2.713632892,10500,0,199.9998535,0,0,0,90.00000001 +336.29,50.30085681,-2.713604867,10500,0,199.9989614,0,0,0,90.00000001 +336.3,50.30085681,-2.713576842,10500,0,199.9989614,0,0,0,90.00000001 +336.31,50.30085681,-2.713548817,10500,0,199.9998535,0,0,0,90.00000001 +336.32,50.30085681,-2.713520792,10500,0,200.0009685,0,0,0,90.00000001 +336.33,50.30085681,-2.713492766,10500,0,200.0009685,0,0,0,90.00000001 +336.34,50.30085681,-2.713464741,10500,0,199.9998535,0,0,0,90.00000001 +336.35,50.30085681,-2.713436716,10500,0,199.9989614,0,0,0,90.00000001 +336.36,50.30085681,-2.713408691,10500,0,199.9989614,0,0,0,90.00000001 +336.37,50.30085681,-2.713380666,10500,0,199.9998535,0,0,0,90.00000001 +336.38,50.30085681,-2.713352641,10500,0,200.0009685,0,0,0,90.00000001 +336.39,50.30085681,-2.713324615,10500,0,200.0009685,0,0,0,90.00000001 +336.4,50.30085681,-2.71329659,10500,0,199.9998535,0,0,0,90.00000001 +336.41,50.30085681,-2.713268565,10500,0,199.9989614,0,0,0,90.00000001 +336.42,50.30085681,-2.71324054,10500,0,199.9989614,0,0,0,90.00000001 +336.43,50.30085681,-2.713212515,10500,0,199.9998535,0,0,0,90.00000001 +336.44,50.30085681,-2.71318449,10500,0,200.0009685,0,0,0,90.00000001 +336.45,50.30085681,-2.713156464,10500,0,200.0009685,0,0,0,90.00000001 +336.46,50.30085681,-2.713128439,10500,0,199.9998535,0,0,0,90.00000001 +336.47,50.30085681,-2.713100414,10500,0,199.9989614,0,0,0,90.00000001 +336.48,50.30085681,-2.713072389,10500,0,199.9987384,0,0,0,90.00000001 +336.49,50.30085681,-2.713044364,10500,0,199.9989614,0,0,0,90.00000001 +336.5,50.30085681,-2.713016339,10500,0,199.9998535,0,0,0,90.00000001 +336.51,50.30085681,-2.712988314,10500,0,200.0009685,0,0,0,90.00000001 +336.52,50.30085681,-2.712960288,10500,0,200.0009685,0,0,0,90.00000001 +336.53,50.30085681,-2.712932263,10500,0,199.9998535,0,0,0,90.00000001 +336.54,50.30085681,-2.712904238,10500,0,199.9991844,0,0,0,90.00000001 +336.55,50.30085681,-2.712876213,10500,0,199.9998535,0,0,0,90.00000001 +336.56,50.30085681,-2.712848188,10500,0,200.0009685,0,0,0,90.00000001 +336.57,50.30085681,-2.712820162,10500,0,200.0009685,0,0,0,90.00000001 +336.58,50.30085681,-2.712792137,10500,0,199.9998535,0,0,0,90.00000001 +336.59,50.30085681,-2.712764112,10500,0,199.9991844,0,0,0,90.00000001 +336.6,50.30085681,-2.712736087,10500,0,199.9998535,0,0,0,90.00000001 +336.61,50.30085681,-2.712708062,10500,0,200.0009685,0,0,0,90.00000001 +336.62,50.30085681,-2.712680036,10500,0,200.0009685,0,0,0,90.00000001 +336.63,50.30085681,-2.712652011,10500,0,199.9998535,0,0,0,90.00000001 +336.64,50.30085681,-2.712623986,10500,0,199.9989614,0,0,0,90.00000001 +336.65,50.30085681,-2.712595961,10500,0,199.9989614,0,0,0,90.00000001 +336.66,50.30085681,-2.712567936,10500,0,199.9998535,0,0,0,90.00000001 +336.67,50.30085681,-2.712539911,10500,0,200.0009685,0,0,0,90.00000001 +336.68,50.30085681,-2.712511885,10500,0,200.0009685,0,0,0,90.00000001 +336.69,50.30085681,-2.71248386,10500,0,199.9998535,0,0,0,90.00000001 +336.7,50.30085681,-2.712455835,10500,0,199.9991844,0,0,0,90.00000001 +336.71,50.30085681,-2.71242781,10500,0,199.9998535,0,0,0,90.00000001 +336.72,50.30085681,-2.712399785,10500,0,200.0009685,0,0,0,90.00000001 +336.73,50.30085681,-2.712371759,10500,0,200.0009685,0,0,0,90.00000001 +336.74,50.30085681,-2.712343734,10500,0,199.9998535,0,0,0,90.00000001 +336.75,50.30085681,-2.712315709,10500,0,199.9991844,0,0,0,90.00000001 +336.76,50.30085681,-2.712287684,10500,0,199.9998535,0,0,0,90.00000001 +336.77,50.30085681,-2.712259659,10500,0,200.0009685,0,0,0,90.00000001 +336.78,50.30085681,-2.712231633,10500,0,200.0009685,0,0,0,90.00000001 +336.79,50.30085681,-2.712203608,10500,0,199.9998535,0,0,0,90.00000001 +336.8,50.30085681,-2.712175583,10500,0,199.9991844,0,0,0,90.00000001 +336.81,50.30085681,-2.712147558,10500,0,199.9998535,0,0,0,90.00000001 +336.82,50.30085681,-2.712119533,10500,0,200.0009685,0,0,0,90.00000001 +336.83,50.30085681,-2.712091507,10500,0,200.0009685,0,0,0,90.00000001 +336.84,50.30085681,-2.712063482,10500,0,199.9998535,0,0,0,90.00000001 +336.85,50.30085681,-2.712035457,10500,0,199.9989614,0,0,0,90.00000001 +336.86,50.30085681,-2.712007432,10500,0,199.9989614,0,0,0,90.00000001 +336.87,50.30085681,-2.711979407,10500,0,199.9998535,0,0,0,90.00000001 +336.88,50.30085681,-2.711951382,10500,0,200.0009685,0,0,0,90.00000001 +336.89,50.30085681,-2.711923356,10500,0,200.0009685,0,0,0,90.00000001 +336.9,50.30085681,-2.711895331,10500,0,199.9998535,0,0,0,90.00000001 +336.91,50.30085681,-2.711867306,10500,0,199.9989614,0,0,0,90.00000001 +336.92,50.30085681,-2.711839281,10500,0,199.9989614,0,0,0,90.00000001 +336.93,50.30085681,-2.711811256,10500,0,199.9998535,0,0,0,90.00000001 +336.94,50.30085681,-2.711783231,10500,0,200.0009685,0,0,0,90.00000001 +336.95,50.30085681,-2.711755205,10500,0,200.0009685,0,0,0,90.00000001 +336.96,50.30085681,-2.71172718,10500,0,199.9998535,0,0,0,90.00000001 +336.97,50.30085681,-2.711699155,10500,0,199.9989614,0,0,0,90.00000001 +336.98,50.30085681,-2.71167113,10500,0,199.9989614,0,0,0,90.00000001 +336.99,50.30085681,-2.711643105,10500,0,199.9998535,0,0,0,90.00000001 +337,50.30085681,-2.71161508,10500,0,200.0009685,0,0,0,90.00000001 +337.01,50.30085681,-2.711587054,10500,0,200.0009685,0,0,0,90.00000001 +337.02,50.30085681,-2.711559029,10500,0,199.9998535,0,0,0,90.00000001 +337.03,50.30085681,-2.711531004,10500,0,199.9989614,0,0,0,90.00000001 +337.04,50.30085681,-2.711502979,10500,0,199.9987384,0,0,0,90.00000001 +337.05,50.30085681,-2.711474954,10500,0,199.9989614,0,0,0,90.00000001 +337.06,50.30085681,-2.711446929,10500,0,199.9998535,0,0,0,90.00000001 +337.07,50.30085681,-2.711418904,10500,0,200.0009685,0,0,0,90.00000001 +337.08,50.30085681,-2.711390878,10500,0,200.0009685,0,0,0,90.00000001 +337.09,50.30085681,-2.711362853,10500,0,199.9998535,0,0,0,90.00000001 +337.1,50.30085681,-2.711334828,10500,0,199.9989614,0,0,0,90.00000001 +337.11,50.30085681,-2.711306803,10500,0,199.9989614,0,0,0,90.00000001 +337.12,50.30085681,-2.711278778,10500,0,199.9998535,0,0,0,90.00000001 +337.13,50.30085681,-2.711250753,10500,0,200.0009685,0,0,0,90.00000001 +337.14,50.30085681,-2.711222727,10500,0,200.0009685,0,0,0,90.00000001 +337.15,50.30085681,-2.711194702,10500,0,199.9998535,0,0,0,90.00000001 +337.16,50.30085681,-2.711166677,10500,0,199.9989614,0,0,0,90.00000001 +337.17,50.30085681,-2.711138652,10500,0,199.9989614,0,0,0,90.00000001 +337.18,50.30085681,-2.711110627,10500,0,199.9998535,0,0,0,90.00000001 +337.19,50.30085681,-2.711082602,10500,0,200.0009685,0,0,0,90.00000001 +337.2,50.30085681,-2.711054576,10500,0,200.0009685,0,0,0,90.00000001 +337.21,50.30085681,-2.711026551,10500,0,199.9998535,0,0,0,90.00000001 +337.22,50.30085681,-2.710998526,10500,0,199.9991844,0,0,0,90.00000001 +337.23,50.30085681,-2.710970501,10500,0,199.9998535,0,0,0,90.00000001 +337.24,50.30085681,-2.710942476,10500,0,200.0009685,0,0,0,90.00000001 +337.25,50.30085681,-2.71091445,10500,0,200.0009685,0,0,0,90.00000001 +337.26,50.30085681,-2.710886425,10500,0,199.9998535,0,0,0,90.00000001 +337.27,50.30085681,-2.7108584,10500,0,199.9991844,0,0,0,90.00000001 +337.28,50.30085681,-2.710830375,10500,0,199.9998535,0,0,0,90.00000001 +337.29,50.30085681,-2.71080235,10500,0,200.0009685,0,0,0,90.00000001 +337.3,50.30085681,-2.710774324,10500,0,200.0009685,0,0,0,90.00000001 +337.31,50.30085681,-2.710746299,10500,0,199.9998535,0,0,0,90.00000001 +337.32,50.30085681,-2.710718274,10500,0,199.9991844,0,0,0,90.00000001 +337.33,50.30085681,-2.710690249,10500,0,199.9998535,0,0,0,90.00000001 +337.34,50.30085681,-2.710662224,10500,0,200.0009685,0,0,0,90.00000001 +337.35,50.30085681,-2.710634198,10500,0,200.0009685,0,0,0,90.00000001 +337.36,50.30085681,-2.710606173,10500,0,199.9998535,0,0,0,90.00000001 +337.37,50.30085681,-2.710578148,10500,0,199.9991844,0,0,0,90.00000001 +337.38,50.30085681,-2.710550123,10500,0,199.9998535,0,0,0,90.00000001 +337.39,50.30085681,-2.710522098,10500,0,200.0009685,0,0,0,90.00000001 +337.4,50.30085681,-2.710494072,10500,0,200.0009685,0,0,0,90.00000001 +337.41,50.30085681,-2.710466047,10500,0,199.9998535,0,0,0,90.00000001 +337.42,50.30085681,-2.710438022,10500,0,199.9991844,0,0,0,90.00000001 +337.43,50.30085681,-2.710409997,10500,0,199.9998535,0,0,0,90.00000001 +337.44,50.30085681,-2.710381972,10500,0,200.0009685,0,0,0,90.00000001 +337.45,50.30085681,-2.710353946,10500,0,200.0009685,0,0,0,90.00000001 +337.46,50.30085681,-2.710325921,10500,0,199.9998535,0,0,0,90.00000001 +337.47,50.30085681,-2.710297896,10500,0,199.9989614,0,0,0,90.00000001 +337.48,50.30085681,-2.710269871,10500,0,199.9989614,0,0,0,90.00000001 +337.49,50.30085681,-2.710241846,10500,0,199.9998535,0,0,0,90.00000001 +337.5,50.30085681,-2.710213821,10500,0,200.0009685,0,0,0,90.00000001 +337.51,50.30085681,-2.710185795,10500,0,200.0009685,0,0,0,90.00000001 +337.52,50.30085681,-2.71015777,10500,0,199.9998535,0,0,0,90.00000001 +337.53,50.30085681,-2.710129745,10500,0,199.9989614,0,0,0,90.00000001 +337.54,50.30085681,-2.71010172,10500,0,199.9989614,0,0,0,90.00000001 +337.55,50.30085681,-2.710073695,10500,0,199.9998535,0,0,0,90.00000001 +337.56,50.30085681,-2.71004567,10500,0,200.0009685,0,0,0,90.00000001 +337.57,50.30085681,-2.710017644,10500,0,200.0009685,0,0,0,90.00000001 +337.58,50.30085681,-2.709989619,10500,0,199.9998535,0,0,0,90.00000001 +337.59,50.30085681,-2.709961594,10500,0,199.9989614,0,0,0,90.00000001 +337.6,50.30085681,-2.709933569,10500,0,199.9987384,0,0,0,90.00000001 +337.61,50.30085681,-2.709905544,10500,0,199.9989614,0,0,0,90.00000001 +337.62,50.30085681,-2.709877519,10500,0,199.9998535,0,0,0,90.00000001 +337.63,50.30085681,-2.709849494,10500,0,200.0009685,0,0,0,90.00000001 +337.64,50.30085681,-2.709821468,10500,0,200.0009685,0,0,0,90.00000001 +337.65,50.30085681,-2.709793443,10500,0,199.9998535,0,0,0,90.00000001 +337.66,50.30085681,-2.709765418,10500,0,199.9989614,0,0,0,90.00000001 +337.67,50.30085681,-2.709737393,10500,0,199.9989614,0,0,0,90.00000001 +337.68,50.30085681,-2.709709368,10500,0,199.9998535,0,0,0,90.00000001 +337.69,50.30085681,-2.709681343,10500,0,200.0009685,0,0,0,90.00000001 +337.7,50.30085681,-2.709653317,10500,0,200.0009685,0,0,0,90.00000001 +337.71,50.30085681,-2.709625292,10500,0,199.9998535,0,0,0,90.00000001 +337.72,50.30085681,-2.709597267,10500,0,199.9989614,0,0,0,90.00000001 +337.73,50.30085681,-2.709569242,10500,0,199.9989614,0,0,0,90.00000001 +337.74,50.30085681,-2.709541217,10500,0,199.9998535,0,0,0,90.00000001 +337.75,50.30085681,-2.709513192,10500,0,200.0009685,0,0,0,90.00000001 +337.76,50.30085681,-2.709485166,10500,0,200.0009685,0,0,0,90.00000001 +337.77,50.30085681,-2.709457141,10500,0,199.9998535,0,0,0,90.00000001 +337.78,50.30085681,-2.709429116,10500,0,199.9989614,0,0,0,90.00000001 +337.79,50.30085681,-2.709401091,10500,0,199.9989614,0,0,0,90.00000001 +337.8,50.30085681,-2.709373066,10500,0,199.9998535,0,0,0,90.00000001 +337.81,50.30085681,-2.709345041,10500,0,200.0009685,0,0,0,90.00000001 +337.82,50.30085681,-2.709317015,10500,0,200.0009685,0,0,0,90.00000001 +337.83,50.30085681,-2.70928899,10500,0,199.9998535,0,0,0,90.00000001 +337.84,50.30085681,-2.709260965,10500,0,199.9991844,0,0,0,90.00000001 +337.85,50.30085681,-2.70923294,10500,0,199.9998535,0,0,0,90.00000001 +337.86,50.30085681,-2.709204915,10500,0,200.0009685,0,0,0,90.00000001 +337.87,50.30085681,-2.709176889,10500,0,200.0009685,0,0,0,90.00000001 +337.88,50.30085681,-2.709148864,10500,0,199.9998535,0,0,0,90.00000001 +337.89,50.30085681,-2.709120839,10500,0,199.9991844,0,0,0,90.00000001 +337.9,50.30085681,-2.709092814,10500,0,199.9998535,0,0,0,90.00000001 +337.91,50.30085681,-2.709064789,10500,0,200.0009685,0,0,0,90.00000001 +337.92,50.30085681,-2.709036763,10500,0,200.0009685,0,0,0,90.00000001 +337.93,50.30085681,-2.709008738,10500,0,199.9998535,0,0,0,90.00000001 +337.94,50.30085681,-2.708980713,10500,0,199.9991844,0,0,0,90.00000001 +337.95,50.30085681,-2.708952688,10500,0,199.9998535,0,0,0,90.00000001 +337.96,50.30085681,-2.708924663,10500,0,200.0009685,0,0,0,90.00000001 +337.97,50.30085681,-2.708896637,10500,0,200.0009685,0,0,0,90.00000001 +337.98,50.30085681,-2.708868612,10500,0,199.9998535,0,0,0,90.00000001 +337.99,50.30085681,-2.708840587,10500,0,199.9991844,0,0,0,90.00000001 +338,50.30085681,-2.708812562,10500,0,199.9998535,0,0,0,90.00000001 +338.01,50.30085681,-2.708784537,10500,0,200.0009685,0,0,0,90.00000001 +338.02,50.30085681,-2.708756511,10500,0,200.0009685,0,0,0,90.00000001 +338.03,50.30085681,-2.708728486,10500,0,199.9998535,0,0,0,90.00000001 +338.04,50.30085681,-2.708700461,10500,0,199.9991844,0,0,0,90.00000001 +338.05,50.30085681,-2.708672436,10500,0,199.9998535,0,0,0,90.00000001 +338.06,50.30085681,-2.708644411,10500,0,200.0009685,0,0,0,90.00000001 +338.07,50.30085681,-2.708616385,10500,0,200.0009685,0,0,0,90.00000001 +338.08,50.30085681,-2.70858836,10500,0,199.9998535,0,0,0,90.00000001 +338.09,50.30085681,-2.708560335,10500,0,199.9989614,0,0,0,90.00000001 +338.1,50.30085681,-2.70853231,10500,0,199.9989614,0,0,0,90.00000001 +338.11,50.30085681,-2.708504285,10500,0,199.9998535,0,0,0,90.00000001 +338.12,50.30085681,-2.70847626,10500,0,200.0009685,0,0,0,90.00000001 +338.13,50.30085681,-2.708448234,10500,0,200.0009685,0,0,0,90.00000001 +338.14,50.30085681,-2.708420209,10500,0,199.9998535,0,0,0,90.00000001 +338.15,50.30085681,-2.708392184,10500,0,199.9989614,0,0,0,90.00000001 +338.16,50.30085681,-2.708364159,10500,0,199.9987384,0,0,0,90.00000001 +338.17,50.30085681,-2.708336134,10500,0,199.9989614,0,0,0,90.00000001 +338.18,50.30085681,-2.708308109,10500,0,199.9998535,0,0,0,90.00000001 +338.19,50.30085681,-2.708280084,10500,0,200.0009685,0,0,0,90.00000001 +338.2,50.30085681,-2.708252058,10500,0,200.0009685,0,0,0,90.00000001 +338.21,50.30085681,-2.708224033,10500,0,199.9998535,0,0,0,90.00000001 +338.22,50.30085681,-2.708196008,10500,0,199.9989614,0,0,0,90.00000001 +338.23,50.30085681,-2.708167983,10500,0,199.9989614,0,0,0,90.00000001 +338.24,50.30085681,-2.708139958,10500,0,199.9998535,0,0,0,90.00000001 +338.25,50.30085681,-2.708111933,10500,0,200.0009685,0,0,0,90.00000001 +338.26,50.30085681,-2.708083907,10500,0,200.0009685,0,0,0,90.00000001 +338.27,50.30085681,-2.708055882,10500,0,199.9998535,0,0,0,90.00000001 +338.28,50.30085681,-2.708027857,10500,0,199.9989614,0,0,0,90.00000001 +338.29,50.30085681,-2.707999832,10500,0,199.9989614,0,0,0,90.00000001 +338.3,50.30085681,-2.707971807,10500,0,199.9998535,0,0,0,90.00000001 +338.31,50.30085681,-2.707943782,10500,0,200.0009685,0,0,0,90.00000001 +338.32,50.30085681,-2.707915756,10500,0,200.0009685,0,0,0,90.00000001 +338.33,50.30085681,-2.707887731,10500,0,199.9998535,0,0,0,90.00000001 +338.34,50.30085681,-2.707859706,10500,0,199.9989614,0,0,0,90.00000001 +338.35,50.30085681,-2.707831681,10500,0,199.9989614,0,0,0,90.00000001 +338.36,50.30085681,-2.707803656,10500,0,199.9998535,0,0,0,90.00000001 +338.37,50.30085681,-2.707775631,10500,0,200.0009685,0,0,0,90.00000001 +338.38,50.30085681,-2.707747605,10500,0,200.0009685,0,0,0,90.00000001 +338.39,50.30085681,-2.70771958,10500,0,199.9998535,0,0,0,90.00000001 +338.4,50.30085681,-2.707691555,10500,0,199.9989614,0,0,0,90.00000001 +338.41,50.30085681,-2.70766353,10500,0,199.9989614,0,0,0,90.00000001 +338.42,50.30085681,-2.707635505,10500,0,199.9998535,0,0,0,90.00000001 +338.43,50.30085681,-2.70760748,10500,0,200.0009685,0,0,0,90.00000001 +338.44,50.30085681,-2.707579454,10500,0,200.0009685,0,0,0,90.00000001 +338.45,50.30085681,-2.707551429,10500,0,199.9998535,0,0,0,90.00000001 +338.46,50.30085681,-2.707523404,10500,0,199.9991844,0,0,0,90.00000001 +338.47,50.30085681,-2.707495379,10500,0,199.9998535,0,0,0,90.00000001 +338.48,50.30085681,-2.707467354,10500,0,200.0009685,0,0,0,90.00000001 +338.49,50.30085681,-2.707439328,10500,0,200.0009685,0,0,0,90.00000001 +338.5,50.30085681,-2.707411303,10500,0,199.9998535,0,0,0,90.00000001 +338.51,50.30085681,-2.707383278,10500,0,199.9991844,0,0,0,90.00000001 +338.52,50.30085681,-2.707355253,10500,0,199.9998535,0,0,0,90.00000001 +338.53,50.30085681,-2.707327228,10500,0,200.0009685,0,0,0,90.00000001 +338.54,50.30085681,-2.707299202,10500,0,200.0009685,0,0,0,90.00000001 +338.55,50.30085681,-2.707271177,10500,0,199.9998535,0,0,0,90.00000001 +338.56,50.30085681,-2.707243152,10500,0,199.9991844,0,0,0,90.00000001 +338.57,50.30085681,-2.707215127,10500,0,199.9998535,0,0,0,90.00000001 +338.58,50.30085681,-2.707187102,10500,0,200.0009685,0,0,0,90.00000001 +338.59,50.30085681,-2.707159076,10500,0,200.0009685,0,0,0,90.00000001 +338.6,50.30085681,-2.707131051,10500,0,199.9998535,0,0,0,90.00000001 +338.61,50.30085681,-2.707103026,10500,0,199.9991844,0,0,0,90.00000001 +338.62,50.30085681,-2.707075001,10500,0,199.9998535,0,0,0,90.00000001 +338.63,50.30085681,-2.707046976,10500,0,200.0009685,0,0,0,90.00000001 +338.64,50.30085681,-2.70701895,10500,0,200.0009685,0,0,0,90.00000001 +338.65,50.30085681,-2.706990925,10500,0,199.9998535,0,0,0,90.00000001 +338.66,50.30085681,-2.7069629,10500,0,199.9991844,0,0,0,90.00000001 +338.67,50.30085681,-2.706934875,10500,0,199.9998535,0,0,0,90.00000001 +338.68,50.30085681,-2.70690685,10500,0,200.0009685,0,0,0,90.00000001 +338.69,50.30085681,-2.706878824,10500,0,200.0009685,0,0,0,90.00000001 +338.7,50.30085681,-2.706850799,10500,0,199.9998535,0,0,0,90.00000001 +338.71,50.30085681,-2.706822774,10500,0,199.9989614,0,0,0,90.00000001 +338.72,50.30085681,-2.706794749,10500,0,199.9987384,0,0,0,90.00000001 +338.73,50.30085681,-2.706766724,10500,0,199.9989614,0,0,0,90.00000001 +338.74,50.30085681,-2.706738699,10500,0,199.9998535,0,0,0,90.00000001 +338.75,50.30085681,-2.706710674,10500,0,200.0009685,0,0,0,90.00000001 +338.76,50.30085681,-2.706682648,10500,0,200.0009685,0,0,0,90.00000001 +338.77,50.30085681,-2.706654623,10500,0,199.9998535,0,0,0,90.00000001 +338.78,50.30085681,-2.706626598,10500,0,199.9989614,0,0,0,90.00000001 +338.79,50.30085681,-2.706598573,10500,0,199.9989614,0,0,0,90.00000001 +338.8,50.30085681,-2.706570548,10500,0,199.9998535,0,0,0,90.00000001 +338.81,50.30085681,-2.706542523,10500,0,200.0009685,0,0,0,90.00000001 +338.82,50.30085681,-2.706514497,10500,0,200.0009685,0,0,0,90.00000001 +338.83,50.30085681,-2.706486472,10500,0,199.9998535,0,0,0,90.00000001 +338.84,50.30085681,-2.706458447,10500,0,199.9989614,0,0,0,90.00000001 +338.85,50.30085681,-2.706430422,10500,0,199.9989614,0,0,0,90.00000001 +338.86,50.30085681,-2.706402397,10500,0,199.9998535,0,0,0,90.00000001 +338.87,50.30085681,-2.706374372,10500,0,200.0009685,0,0,0,90.00000001 +338.88,50.30085681,-2.706346346,10500,0,200.0009685,0,0,0,90.00000001 +338.89,50.30085681,-2.706318321,10500,0,199.9998535,0,0,0,90.00000001 +338.9,50.30085681,-2.706290296,10500,0,199.9989614,0,0,0,90.00000001 +338.91,50.30085681,-2.706262271,10500,0,199.9989614,0,0,0,90.00000001 +338.92,50.30085681,-2.706234246,10500,0,199.9998535,0,0,0,90.00000001 +338.93,50.30085681,-2.706206221,10500,0,200.0009685,0,0,0,90.00000001 +338.94,50.30085681,-2.706178195,10500,0,200.0009685,0,0,0,90.00000001 +338.95,50.30085681,-2.70615017,10500,0,199.9998535,0,0,0,90.00000001 +338.96,50.30085681,-2.706122145,10500,0,199.9989614,0,0,0,90.00000001 +338.97,50.30085681,-2.70609412,10500,0,199.9989614,0,0,0,90.00000001 +338.98,50.30085681,-2.706066095,10500,0,199.9998535,0,0,0,90.00000001 +338.99,50.30085681,-2.70603807,10500,0,200.0009685,0,0,0,90.00000001 +339,50.30085681,-2.706010044,10500,0,200.0009685,0,0,0,90.00000001 +339.01,50.30085681,-2.705982019,10500,0,199.9998535,0,0,0,90.00000001 +339.02,50.30085681,-2.705953994,10500,0,199.9989614,0,0,0,90.00000001 +339.03,50.30085681,-2.705925969,10500,0,199.9987384,0,0,0,90.00000001 +339.04,50.30085681,-2.705897944,10500,0,199.9989614,0,0,0,90.00000001 +339.05,50.30085681,-2.705869919,10500,0,199.9998535,0,0,0,90.00000001 +339.06,50.30085681,-2.705841894,10500,0,200.0009685,0,0,0,90.00000001 +339.07,50.30085681,-2.705813868,10500,0,200.0009685,0,0,0,90.00000001 +339.08,50.30085681,-2.705785843,10500,0,199.9998535,0,0,0,90.00000001 +339.09,50.30085681,-2.705757818,10500,0,199.9991844,0,0,0,90.00000001 +339.1,50.30085681,-2.705729793,10500,0,199.9998535,0,0,0,90.00000001 +339.11,50.30085681,-2.705701768,10500,0,200.0009685,0,0,0,90.00000001 +339.12,50.30085681,-2.705673742,10500,0,200.0009685,0,0,0,90.00000001 +339.13,50.30085681,-2.705645717,10500,0,199.9998535,0,0,0,90.00000001 +339.14,50.30085681,-2.705617692,10500,0,199.9991844,0,0,0,90.00000001 +339.15,50.30085681,-2.705589667,10500,0,199.9998535,0,0,0,90.00000001 +339.16,50.30085681,-2.705561642,10500,0,200.0009685,0,0,0,90.00000001 +339.17,50.30085681,-2.705533616,10500,0,200.0009685,0,0,0,90.00000001 +339.18,50.30085681,-2.705505591,10500,0,199.9998535,0,0,0,90.00000001 +339.19,50.30085681,-2.705477566,10500,0,199.9991844,0,0,0,90.00000001 +339.2,50.30085681,-2.705449541,10500,0,199.9998535,0,0,0,90.00000001 +339.21,50.30085681,-2.705421516,10500,0,200.0009685,0,0,0,90.00000001 +339.22,50.30085681,-2.70539349,10500,0,200.0009685,0,0,0,90.00000001 +339.23,50.30085681,-2.705365465,10500,0,199.9998535,0,0,0,90.00000001 +339.24,50.30085681,-2.70533744,10500,0,199.9991844,0,0,0,90.00000001 +339.25,50.30085681,-2.705309415,10500,0,199.9998535,0,0,0,90.00000001 +339.26,50.30085681,-2.70528139,10500,0,200.0009685,0,0,0,90.00000001 +339.27,50.30085681,-2.705253364,10500,0,200.0009685,0,0,0,90.00000001 +339.28,50.30085681,-2.705225339,10500,0,199.9998535,0,0,0,90.00000001 +339.29,50.30085681,-2.705197314,10500,0,199.9991844,0,0,0,90.00000001 +339.3,50.30085681,-2.705169289,10500,0,199.9998535,0,0,0,90.00000001 +339.31,50.30085681,-2.705141264,10500,0,200.0009685,0,0,0,90.00000001 +339.32,50.30085681,-2.705113238,10500,0,200.0009685,0,0,0,90.00000001 +339.33,50.30085681,-2.705085213,10500,0,199.9998535,0,0,0,90.00000001 +339.34,50.30085681,-2.705057188,10500,0,199.9989614,0,0,0,90.00000001 +339.35,50.30085681,-2.705029163,10500,0,199.9989614,0,0,0,90.00000001 +339.36,50.30085681,-2.705001138,10500,0,199.9998535,0,0,0,90.00000001 +339.37,50.30085681,-2.704973113,10500,0,200.0009685,0,0,0,90.00000001 +339.38,50.30085681,-2.704945087,10500,0,200.0009685,0,0,0,90.00000001 +339.39,50.30085681,-2.704917062,10500,0,199.9998535,0,0,0,90.00000001 +339.4,50.30085681,-2.704889037,10500,0,199.9989614,0,0,0,90.00000001 +339.41,50.30085681,-2.704861012,10500,0,199.9989614,0,0,0,90.00000001 +339.42,50.30085681,-2.704832987,10500,0,199.9998535,0,0,0,90.00000001 +339.43,50.30085681,-2.704804962,10500,0,200.0009685,0,0,0,90.00000001 +339.44,50.30085681,-2.704776936,10500,0,200.0009685,0,0,0,90.00000001 +339.45,50.30085681,-2.704748911,10500,0,199.9998535,0,0,0,90.00000001 +339.46,50.30085681,-2.704720886,10500,0,199.9989614,0,0,0,90.00000001 +339.47,50.30085681,-2.704692861,10500,0,199.9989614,0,0,0,90.00000001 +339.48,50.30085681,-2.704664836,10500,0,199.9998535,0,0,0,90.00000001 +339.49,50.30085681,-2.704636811,10500,0,200.0009685,0,0,0,90.00000001 +339.5,50.30085681,-2.704608785,10500,0,200.0009685,0,0,0,90.00000001 +339.51,50.30085681,-2.70458076,10500,0,199.9998535,0,0,0,90.00000001 +339.52,50.30085681,-2.704552735,10500,0,199.9989614,0,0,0,90.00000001 +339.53,50.30085681,-2.70452471,10500,0,199.9989614,0,0,0,90.00000001 +339.54,50.30085681,-2.704496685,10500,0,199.9998535,0,0,0,90.00000001 +339.55,50.30085681,-2.70446866,10500,0,200.0009685,0,0,0,90.00000001 +339.56,50.30085681,-2.704440634,10500,0,200.0009685,0,0,0,90.00000001 +339.57,50.30085681,-2.704412609,10500,0,199.9998535,0,0,0,90.00000001 +339.58,50.30085681,-2.704384584,10500,0,199.9989614,0,0,0,90.00000001 +339.59,50.30085681,-2.704356559,10500,0,199.9987384,0,0,0,90.00000001 +339.6,50.30085681,-2.704328534,10500,0,199.9989614,0,0,0,90.00000001 +339.61,50.30085681,-2.704300509,10500,0,199.9998535,0,0,0,90.00000001 +339.62,50.30085681,-2.704272484,10500,0,200.0009685,0,0,0,90.00000001 +339.63,50.30085681,-2.704244458,10500,0,200.0009685,0,0,0,90.00000001 +339.64,50.30085681,-2.704216433,10500,0,199.9998535,0,0,0,90.00000001 +339.65,50.30085681,-2.704188408,10500,0,199.9989614,0,0,0,90.00000001 +339.66,50.30085681,-2.704160383,10500,0,199.9989614,0,0,0,90.00000001 +339.67,50.30085681,-2.704132358,10500,0,199.9998535,0,0,0,90.00000001 +339.68,50.30085681,-2.704104333,10500,0,200.0009685,0,0,0,90.00000001 +339.69,50.30085681,-2.704076307,10500,0,200.0009685,0,0,0,90.00000001 +339.7,50.30085681,-2.704048282,10500,0,199.9998535,0,0,0,90.00000001 +339.71,50.30085681,-2.704020257,10500,0,199.9991844,0,0,0,90.00000001 +339.72,50.30085681,-2.703992232,10500,0,199.9998535,0,0,0,90.00000001 +339.73,50.30085681,-2.703964207,10500,0,200.0009685,0,0,0,90.00000001 +339.74,50.30085681,-2.703936181,10500,0,200.0009685,0,0,0,90.00000001 +339.75,50.30085681,-2.703908156,10500,0,199.9998535,0,0,0,90.00000001 +339.76,50.30085681,-2.703880131,10500,0,199.9991844,0,0,0,90.00000001 +339.77,50.30085681,-2.703852106,10500,0,199.9998535,0,0,0,90.00000001 +339.78,50.30085681,-2.703824081,10500,0,200.0009685,0,0,0,90.00000001 +339.79,50.30085681,-2.703796055,10500,0,200.0009685,0,0,0,90.00000001 +339.8,50.30085681,-2.70376803,10500,0,199.9998535,0,0,0,90.00000001 +339.81,50.30085681,-2.703740005,10500,0,199.9991844,0,0,0,90.00000001 +339.82,50.30085681,-2.70371198,10500,0,199.9998535,0,0,0,90.00000001 +339.83,50.30085681,-2.703683955,10500,0,200.0009685,0,0,0,90.00000001 +339.84,50.30085681,-2.703655929,10500,0,200.0009685,0,0,0,90.00000001 +339.85,50.30085681,-2.703627904,10500,0,199.9998535,0,0,0,90.00000001 +339.86,50.30085681,-2.703599879,10500,0,199.9991844,0,0,0,90.00000001 +339.87,50.30085681,-2.703571854,10500,0,199.9998535,0,0,0,90.00000001 +339.88,50.30085681,-2.703543829,10500,0,200.0009685,0,0,0,90.00000001 +339.89,50.30085681,-2.703515803,10500,0,200.0009685,0,0,0,90.00000001 +339.9,50.30085681,-2.703487778,10500,0,199.9998535,0,0,0,90.00000001 +339.91,50.30085681,-2.703459753,10500,0,199.9991844,0,0,0,90.00000001 +339.92,50.30085681,-2.703431728,10500,0,199.9998535,0,0,0,90.00000001 +339.93,50.30085681,-2.703403703,10500,0,200.0009685,0,0,0,90.00000001 +339.94,50.30085681,-2.703375677,10500,0,200.0009685,0,0,0,90.00000001 +339.95,50.30085681,-2.703347652,10500,0,199.9998535,0,0,0,90.00000001 +339.96,50.30085681,-2.703319627,10500,0,199.9989614,0,0,0,90.00000001 +339.97,50.30085681,-2.703291602,10500,0,199.9989614,0,0,0,90.00000001 +339.98,50.30085681,-2.703263577,10500,0,199.9998535,0,0,0,90.00000001 +339.99,50.30085681,-2.703235552,10500,0,200.0009685,0,0,0,90.00000001 +340,50.30085681,-2.703207526,10500,0,200.0009685,0,0,0,90.00000001 +340.01,50.30085681,-2.703179501,10500,0,199.9998535,0,0,0,90.00000001 +340.02,50.30085681,-2.703151476,10500,0,199.9989614,0,0,0,90.00000001 +340.03,50.30085681,-2.703123451,10500,0,199.9989614,0,0,0,90.00000001 +340.04,50.30085681,-2.703095426,10500,0,199.9998535,0,0,0,90.00000001 +340.05,50.30085681,-2.703067401,10500,0,200.0009685,0,0,0,90.00000001 +340.06,50.30085681,-2.703039375,10500,0,200.0009685,0,0,0,90.00000001 +340.07,50.30085681,-2.70301135,10500,0,199.9998535,0,0,0,90.00000001 +340.08,50.30085681,-2.702983325,10500,0,199.9989614,0,0,0,90.00000001 +340.09,50.30085681,-2.7029553,10500,0,199.9989614,0,0,0,90.00000001 +340.1,50.30085681,-2.702927275,10500,0,199.9998535,0,0,0,90.00000001 +340.11,50.30085681,-2.70289925,10500,0,200.0009685,0,0,0,90.00000001 +340.12,50.30085681,-2.702871224,10500,0,200.0009685,0,0,0,90.00000001 +340.13,50.30085681,-2.702843199,10500,0,199.9998535,0,0,0,90.00000001 +340.14,50.30085681,-2.702815174,10500,0,199.9989614,0,0,0,90.00000001 +340.15,50.30085681,-2.702787149,10500,0,199.9987384,0,0,0,90.00000001 +340.16,50.30085681,-2.702759124,10500,0,199.9989614,0,0,0,90.00000001 +340.17,50.30085681,-2.702731099,10500,0,199.9998535,0,0,0,90.00000001 +340.18,50.30085681,-2.702703074,10500,0,200.0009685,0,0,0,90.00000001 +340.19,50.30085681,-2.702675048,10500,0,200.0009685,0,0,0,90.00000001 +340.2,50.30085681,-2.702647023,10500,0,199.9998535,0,0,0,90.00000001 +340.21,50.30085681,-2.702618998,10500,0,199.9989614,0,0,0,90.00000001 +340.22,50.30085681,-2.702590973,10500,0,199.9989614,0,0,0,90.00000001 +340.23,50.30085681,-2.702562948,10500,0,199.9998535,0,0,0,90.00000001 +340.24,50.30085681,-2.702534923,10500,0,200.0009685,0,0,0,90.00000001 +340.25,50.30085681,-2.702506897,10500,0,200.0009685,0,0,0,90.00000001 +340.26,50.30085681,-2.702478872,10500,0,199.9998535,0,0,0,90.00000001 +340.27,50.30085681,-2.702450847,10500,0,199.9989614,0,0,0,90.00000001 +340.28,50.30085681,-2.702422822,10500,0,199.9989614,0,0,0,90.00000001 +340.29,50.30085681,-2.702394797,10500,0,199.9998535,0,0,0,90.00000001 +340.3,50.30085681,-2.702366772,10500,0,200.0009685,0,0,0,90.00000001 +340.31,50.30085681,-2.702338746,10500,0,200.0009685,0,0,0,90.00000001 +340.32,50.30085681,-2.702310721,10500,0,199.9998535,0,0,0,90.00000001 +340.33,50.30085681,-2.702282696,10500,0,199.9991844,0,0,0,90.00000001 +340.34,50.30085681,-2.702254671,10500,0,199.9998535,0,0,0,90.00000001 +340.35,50.30085681,-2.702226646,10500,0,200.0009685,0,0,0,90.00000001 +340.36,50.30085681,-2.70219862,10500,0,200.0009685,0,0,0,90.00000001 +340.37,50.30085681,-2.702170595,10500,0,199.9998535,0,0,0,90.00000001 +340.38,50.30085681,-2.70214257,10500,0,199.9991844,0,0,0,90.00000001 +340.39,50.30085681,-2.702114545,10500,0,199.9998535,0,0,0,90.00000001 +340.4,50.30085681,-2.70208652,10500,0,200.0009685,0,0,0,90.00000001 +340.41,50.30085681,-2.702058494,10500,0,200.0009685,0,0,0,90.00000001 +340.42,50.30085681,-2.702030469,10500,0,199.9998535,0,0,0,90.00000001 +340.43,50.30085681,-2.702002444,10500,0,199.9991844,0,0,0,90.00000001 +340.44,50.30085681,-2.701974419,10500,0,199.9998535,0,0,0,90.00000001 +340.45,50.30085681,-2.701946394,10500,0,200.0009685,0,0,0,90.00000001 +340.46,50.30085681,-2.701918368,10500,0,200.0009685,0,0,0,90.00000001 +340.47,50.30085681,-2.701890343,10500,0,199.9998535,0,0,0,90.00000001 +340.48,50.30085681,-2.701862318,10500,0,199.9991844,0,0,0,90.00000001 +340.49,50.30085681,-2.701834293,10500,0,199.9998535,0,0,0,90.00000001 +340.5,50.30085681,-2.701806268,10500,0,200.0009685,0,0,0,90.00000001 +340.51,50.30085681,-2.701778242,10500,0,200.0009685,0,0,0,90.00000001 +340.52,50.30085681,-2.701750217,10500,0,199.9998535,0,0,0,90.00000001 +340.53,50.30085681,-2.701722192,10500,0,199.9991844,0,0,0,90.00000001 +340.54,50.30085681,-2.701694167,10500,0,199.9998535,0,0,0,90.00000001 +340.55,50.30085681,-2.701666142,10500,0,200.0009685,0,0,0,90.00000001 +340.56,50.30085681,-2.701638116,10500,0,200.0009685,0,0,0,90.00000001 +340.57,50.30085681,-2.701610091,10500,0,199.9998535,0,0,0,90.00000001 +340.58,50.30085681,-2.701582066,10500,0,199.9989614,0,0,0,90.00000001 +340.59,50.30085681,-2.701554041,10500,0,199.9989614,0,0,0,90.00000001 +340.6,50.30085681,-2.701526016,10500,0,199.9998535,0,0,0,90.00000001 +340.61,50.30085681,-2.701497991,10500,0,200.0009685,0,0,0,90.00000001 +340.62,50.30085681,-2.701469965,10500,0,200.0009685,0,0,0,90.00000001 +340.63,50.30085681,-2.70144194,10500,0,199.9998535,0,0,0,90.00000001 +340.64,50.30085681,-2.701413915,10500,0,199.9989614,0,0,0,90.00000001 +340.65,50.30085681,-2.70138589,10500,0,199.9989614,0,0,0,90.00000001 +340.66,50.30085681,-2.701357865,10500,0,199.9998535,0,0,0,90.00000001 +340.67,50.30085681,-2.70132984,10500,0,200.0009685,0,0,0,90.00000001 +340.68,50.30085681,-2.701301814,10500,0,200.0009685,0,0,0,90.00000001 +340.69,50.30085681,-2.701273789,10500,0,199.9998535,0,0,0,90.00000001 +340.7,50.30085681,-2.701245764,10500,0,199.9989614,0,0,0,90.00000001 +340.71,50.30085681,-2.701217739,10500,0,199.9989614,0,0,0,90.00000001 +340.72,50.30085681,-2.701189714,10500,0,199.9998535,0,0,0,90.00000001 +340.73,50.30085681,-2.701161689,10500,0,200.0009685,0,0,0,90.00000001 +340.74,50.30085681,-2.701133663,10500,0,200.0009685,0,0,0,90.00000001 +340.75,50.30085681,-2.701105638,10500,0,199.9998535,0,0,0,90.00000001 +340.76,50.30085681,-2.701077613,10500,0,199.9989614,0,0,0,90.00000001 +340.77,50.30085681,-2.701049588,10500,0,199.9987384,0,0,0,90.00000001 +340.78,50.30085681,-2.701021563,10500,0,199.9989614,0,0,0,90.00000001 +340.79,50.30085681,-2.700993538,10500,0,199.9998535,0,0,0,90.00000001 +340.8,50.30085681,-2.700965513,10500,0,200.0009685,0,0,0,90.00000001 +340.81,50.30085681,-2.700937487,10500,0,200.0009685,0,0,0,90.00000001 +340.82,50.30085681,-2.700909462,10500,0,199.9998535,0,0,0,90.00000001 +340.83,50.30085681,-2.700881437,10500,0,199.9989614,0,0,0,90.00000001 +340.84,50.30085681,-2.700853412,10500,0,199.9989614,0,0,0,90.00000001 +340.85,50.30085681,-2.700825387,10500,0,199.9998535,0,0,0,90.00000001 +340.86,50.30085681,-2.700797362,10500,0,200.0009685,0,0,0,90.00000001 +340.87,50.30085681,-2.700769336,10500,0,200.0009685,0,0,0,90.00000001 +340.88,50.30085681,-2.700741311,10500,0,199.9998535,0,0,0,90.00000001 +340.89,50.30085681,-2.700713286,10500,0,199.9989614,0,0,0,90.00000001 +340.9,50.30085681,-2.700685261,10500,0,199.9989614,0,0,0,90.00000001 +340.91,50.30085681,-2.700657236,10500,0,199.9998535,0,0,0,90.00000001 +340.92,50.30085681,-2.700629211,10500,0,200.0009685,0,0,0,90.00000001 +340.93,50.30085681,-2.700601185,10500,0,200.0009685,0,0,0,90.00000001 +340.94,50.30085681,-2.70057316,10500,0,199.9998535,0,0,0,90.00000001 +340.95,50.30085681,-2.700545135,10500,0,199.9991844,0,0,0,90.00000001 +340.96,50.30085681,-2.70051711,10500,0,199.9998535,0,0,0,90.00000001 +340.97,50.30085681,-2.700489085,10500,0,200.0009685,0,0,0,90.00000001 +340.98,50.30085681,-2.700461059,10500,0,200.0009685,0,0,0,90.00000001 +340.99,50.30085681,-2.700433034,10500,0,199.9998535,0,0,0,90.00000001 +341,50.30085681,-2.700405009,10500,0,199.9991844,0,0,0,90.00000001 +341.01,50.30085681,-2.700376984,10500,0,199.9998535,0,0,0,90.00000001 +341.02,50.30085681,-2.700348959,10500,0,200.0009685,0,0,0,90.00000001 +341.03,50.30085681,-2.700320933,10500,0,200.0009685,0,0,0,90.00000001 +341.04,50.30085681,-2.700292908,10500,0,199.9998535,0,0,0,90.00000001 +341.05,50.30085681,-2.700264883,10500,0,199.9991844,0,0,0,90.00000001 +341.06,50.30085681,-2.700236858,10500,0,199.9998535,0,0,0,90.00000001 +341.07,50.30085681,-2.700208833,10500,0,200.0009685,0,0,0,90.00000001 +341.08,50.30085681,-2.700180807,10500,0,200.0009685,0,0,0,90.00000001 +341.09,50.30085681,-2.700152782,10500,0,199.9998535,0,0,0,90.00000001 +341.1,50.30085681,-2.700124757,10500,0,199.9989614,0,0,0,90.00000001 +341.11,50.30085681,-2.700096732,10500,0,199.9989614,0,0,0,90.00000001 +341.12,50.30085681,-2.700068707,10500,0,199.9998535,0,0,0,90.00000001 +341.13,50.30085681,-2.700040682,10500,0,200.0009685,0,0,0,90.00000001 +341.14,50.30085681,-2.700012656,10500,0,200.0009685,0,0,0,90.00000001 +341.15,50.30085681,-2.699984631,10500,0,199.9998535,0,0,0,90.00000001 +341.16,50.30085681,-2.699956606,10500,0,199.9991844,0,0,0,90.00000001 +341.17,50.30085681,-2.699928581,10500,0,199.9998535,0,0,0,90.00000001 +341.18,50.30085681,-2.699900556,10500,0,200.0009685,0,0,0,90.00000001 +341.19,50.30085681,-2.69987253,10500,0,200.0009685,0,0,0,90.00000001 +341.2,50.30085681,-2.699844505,10500,0,199.9998535,0,0,0,90.00000001 +341.21,50.30085681,-2.69981648,10500,0,199.9991844,0,0,0,90.00000001 +341.22,50.30085681,-2.699788455,10500,0,199.9998535,0,0,0,90.00000001 +341.23,50.30085681,-2.69976043,10500,0,200.0009685,0,0,0,90.00000001 +341.24,50.30085681,-2.699732404,10500,0,200.0009685,0,0,0,90.00000001 +341.25,50.30085681,-2.699704379,10500,0,199.9998535,0,0,0,90.00000001 +341.26,50.30085681,-2.699676354,10500,0,199.9989614,0,0,0,90.00000001 +341.27,50.30085681,-2.699648329,10500,0,199.9989614,0,0,0,90.00000001 +341.28,50.30085681,-2.699620304,10500,0,199.9998535,0,0,0,90.00000001 +341.29,50.30085681,-2.699592279,10500,0,200.0009685,0,0,0,90.00000001 +341.3,50.30085681,-2.699564253,10500,0,200.0009685,0,0,0,90.00000001 +341.31,50.30085681,-2.699536228,10500,0,199.9998535,0,0,0,90.00000001 +341.32,50.30085681,-2.699508203,10500,0,199.9989614,0,0,0,90.00000001 +341.33,50.30085681,-2.699480178,10500,0,199.9987384,0,0,0,90.00000001 +341.34,50.30085681,-2.699452153,10500,0,199.9989614,0,0,0,90.00000001 +341.35,50.30085681,-2.699424128,10500,0,199.9998535,0,0,0,90.00000001 +341.36,50.30085681,-2.699396103,10500,0,200.0009685,0,0,0,90.00000001 +341.37,50.30085681,-2.699368077,10500,0,200.0009685,0,0,0,90.00000001 +341.38,50.30085681,-2.699340052,10500,0,199.9998535,0,0,0,90.00000001 +341.39,50.30085681,-2.699312027,10500,0,199.9989614,0,0,0,90.00000001 +341.4,50.30085681,-2.699284002,10500,0,199.9989614,0,0,0,90.00000001 +341.41,50.30085681,-2.699255977,10500,0,199.9998535,0,0,0,90.00000001 +341.42,50.30085681,-2.699227952,10500,0,200.0009685,0,0,0,90.00000001 +341.43,50.30085681,-2.699199926,10500,0,200.0009685,0,0,0,90.00000001 +341.44,50.30085681,-2.699171901,10500,0,199.9998535,0,0,0,90.00000001 +341.45,50.30085681,-2.699143876,10500,0,199.9989614,0,0,0,90.00000001 +341.46,50.30085681,-2.699115851,10500,0,199.9989614,0,0,0,90.00000001 +341.47,50.30085681,-2.699087826,10500,0,199.9998535,0,0,0,90.00000001 +341.48,50.30085681,-2.699059801,10500,0,200.0009685,0,0,0,90.00000001 +341.49,50.30085681,-2.699031775,10500,0,200.0009685,0,0,0,90.00000001 +341.5,50.30085681,-2.69900375,10500,0,199.9998535,0,0,0,90.00000001 +341.51,50.30085681,-2.698975725,10500,0,199.9989614,0,0,0,90.00000001 +341.52,50.30085681,-2.6989477,10500,0,199.9989614,0,0,0,90.00000001 +341.53,50.30085681,-2.698919675,10500,0,199.9998535,0,0,0,90.00000001 +341.54,50.30085681,-2.69889165,10500,0,200.0009685,0,0,0,90.00000001 +341.55,50.30085681,-2.698863624,10500,0,200.0009685,0,0,0,90.00000001 +341.56,50.30085681,-2.698835599,10500,0,199.9998535,0,0,0,90.00000001 +341.57,50.30085681,-2.698807574,10500,0,199.9989614,0,0,0,90.00000001 +341.58,50.30085681,-2.698779549,10500,0,199.9989614,0,0,0,90.00000001 +341.59,50.30085681,-2.698751524,10500,0,199.9998535,0,0,0,90.00000001 +341.6,50.30085681,-2.698723499,10500,0,200.0009685,0,0,0,90.00000001 +341.61,50.30085681,-2.698695473,10500,0,200.0009685,0,0,0,90.00000001 +341.62,50.30085681,-2.698667448,10500,0,199.9998535,0,0,0,90.00000001 +341.63,50.30085681,-2.698639423,10500,0,199.9991844,0,0,0,90.00000001 +341.64,50.30085681,-2.698611398,10500,0,199.9998535,0,0,0,90.00000001 +341.65,50.30085681,-2.698583373,10500,0,200.0009685,0,0,0,90.00000001 +341.66,50.30085681,-2.698555347,10500,0,200.0009685,0,0,0,90.00000001 +341.67,50.30085681,-2.698527322,10500,0,199.9998535,0,0,0,90.00000001 +341.68,50.30085681,-2.698499297,10500,0,199.9991844,0,0,0,90.00000001 +341.69,50.30085681,-2.698471272,10500,0,199.9998535,0,0,0,90.00000001 +341.7,50.30085681,-2.698443247,10500,0,200.0009685,0,0,0,90.00000001 +341.71,50.30085681,-2.698415221,10500,0,200.0009685,0,0,0,90.00000001 +341.72,50.30085681,-2.698387196,10500,0,199.9998535,0,0,0,90.00000001 +341.73,50.30085681,-2.698359171,10500,0,199.9991844,0,0,0,90.00000001 +341.74,50.30085681,-2.698331146,10500,0,199.9998535,0,0,0,90.00000001 +341.75,50.30085681,-2.698303121,10500,0,200.0009685,0,0,0,90.00000001 +341.76,50.30085681,-2.698275095,10500,0,200.0009685,0,0,0,90.00000001 +341.77,50.30085681,-2.69824707,10500,0,199.9998535,0,0,0,90.00000001 +341.78,50.30085681,-2.698219045,10500,0,199.9991844,0,0,0,90.00000001 +341.79,50.30085681,-2.69819102,10500,0,199.9998535,0,0,0,90.00000001 +341.8,50.30085681,-2.698162995,10500,0,200.0009685,0,0,0,90.00000001 +341.81,50.30085681,-2.698134969,10500,0,200.0009685,0,0,0,90.00000001 +341.82,50.30085681,-2.698106944,10500,0,199.9998535,0,0,0,90.00000001 +341.83,50.30085681,-2.698078919,10500,0,199.9991844,0,0,0,90.00000001 +341.84,50.30085681,-2.698050894,10500,0,199.9998535,0,0,0,90.00000001 +341.85,50.30085681,-2.698022869,10500,0,200.0009685,0,0,0,90.00000001 +341.86,50.30085681,-2.697994843,10500,0,200.0009685,0,0,0,90.00000001 +341.87,50.30085681,-2.697966818,10500,0,199.9998535,0,0,0,90.00000001 +341.88,50.30085681,-2.697938793,10500,0,199.9989614,0,0,0,90.00000001 +341.89,50.30085681,-2.697910768,10500,0,199.9987384,0,0,0,90.00000001 +341.9,50.30085681,-2.697882743,10500,0,199.9989614,0,0,0,90.00000001 +341.91,50.30085681,-2.697854718,10500,0,199.9998535,0,0,0,90.00000001 +341.92,50.30085681,-2.697826693,10500,0,200.0009685,0,0,0,90.00000001 +341.93,50.30085681,-2.697798667,10500,0,200.0009685,0,0,0,90.00000001 +341.94,50.30085681,-2.697770642,10500,0,199.9998535,0,0,0,90.00000001 +341.95,50.30085681,-2.697742617,10500,0,199.9989614,0,0,0,90.00000001 +341.96,50.30085681,-2.697714592,10500,0,199.9989614,0,0,0,90.00000001 +341.97,50.30085681,-2.697686567,10500,0,199.9998535,0,0,0,90.00000001 +341.98,50.30085681,-2.697658542,10500,0,200.0009685,0,0,0,90.00000001 +341.99,50.30085681,-2.697630516,10500,0,200.0009685,0,0,0,90.00000001 +342,50.30085681,-2.697602491,10500,0,199.9998535,0,0,0,90.00000001 +342.01,50.30085681,-2.697574466,10500,0,199.9989614,0,0,0,90.00000001 +342.02,50.30085681,-2.697546441,10500,0,199.9989614,0,0,0,90.00000001 +342.03,50.30085681,-2.697518416,10500,0,199.9998535,0,0,0,90.00000001 +342.04,50.30085681,-2.697490391,10500,0,200.0009685,0,0,0,90.00000001 +342.05,50.30085681,-2.697462365,10500,0,200.0009685,0,0,0,90.00000001 +342.06,50.30085681,-2.69743434,10500,0,199.9998535,0,0,0,90.00000001 +342.07,50.30085681,-2.697406315,10500,0,199.9989614,0,0,0,90.00000001 +342.08,50.30085681,-2.69737829,10500,0,199.9989614,0,0,0,90.00000001 +342.09,50.30085681,-2.697350265,10500,0,199.9998535,0,0,0,90.00000001 +342.1,50.30085681,-2.69732224,10500,0,200.0009685,0,0,0,90.00000001 +342.11,50.30085681,-2.697294214,10500,0,200.0009685,0,0,0,90.00000001 +342.12,50.30085681,-2.697266189,10500,0,199.9998535,0,0,0,90.00000001 +342.13,50.30085681,-2.697238164,10500,0,199.9989614,0,0,0,90.00000001 +342.14,50.30085681,-2.697210139,10500,0,199.9989614,0,0,0,90.00000001 +342.15,50.30085681,-2.697182114,10500,0,199.9998535,0,0,0,90.00000001 +342.16,50.30085681,-2.697154089,10500,0,200.0009685,0,0,0,90.00000001 +342.17,50.30085681,-2.697126063,10500,0,200.0009685,0,0,0,90.00000001 +342.18,50.30085681,-2.697098038,10500,0,199.9998535,0,0,0,90.00000001 +342.19,50.30085681,-2.697070013,10500,0,199.9989614,0,0,0,90.00000001 +342.2,50.30085681,-2.697041988,10500,0,199.9989614,0,0,0,90.00000001 +342.21,50.30085681,-2.697013963,10500,0,199.9998535,0,0,0,90.00000001 +342.22,50.30085681,-2.696985938,10500,0,200.0009685,0,0,0,90.00000001 +342.23,50.30085681,-2.696957912,10500,0,200.0009685,0,0,0,90.00000001 +342.24,50.30085681,-2.696929887,10500,0,199.9998535,0,0,0,90.00000001 +342.25,50.30085681,-2.696901862,10500,0,199.9991844,0,0,0,90.00000001 +342.26,50.30085681,-2.696873837,10500,0,199.9998535,0,0,0,90.00000001 +342.27,50.30085681,-2.696845812,10500,0,200.0009685,0,0,0,90.00000001 +342.28,50.30085681,-2.696817786,10500,0,200.0009685,0,0,0,90.00000001 +342.29,50.30085681,-2.696789761,10500,0,199.9998535,0,0,0,90.00000001 +342.3,50.30085681,-2.696761736,10500,0,199.9991844,0,0,0,90.00000001 +342.31,50.30085681,-2.696733711,10500,0,199.9998535,0,0,0,90.00000001 +342.32,50.30085681,-2.696705686,10500,0,200.0009685,0,0,0,90.00000001 +342.33,50.30085681,-2.69667766,10500,0,200.0009685,0,0,0,90.00000001 +342.34,50.30085681,-2.696649635,10500,0,199.9998535,0,0,0,90.00000001 +342.35,50.30085681,-2.69662161,10500,0,199.9991844,0,0,0,90.00000001 +342.36,50.30085681,-2.696593585,10500,0,199.9998535,0,0,0,90.00000001 +342.37,50.30085681,-2.69656556,10500,0,200.0009685,0,0,0,90.00000001 +342.38,50.30085681,-2.696537534,10500,0,200.0009685,0,0,0,90.00000001 +342.39,50.30085681,-2.696509509,10500,0,199.9998535,0,0,0,90.00000001 +342.4,50.30085681,-2.696481484,10500,0,199.9991844,0,0,0,90.00000001 +342.41,50.30085681,-2.696453459,10500,0,199.9998535,0,0,0,90.00000001 +342.42,50.30085681,-2.696425434,10500,0,200.0009685,0,0,0,90.00000001 +342.43,50.30085681,-2.696397408,10500,0,200.0009685,0,0,0,90.00000001 +342.44,50.30085681,-2.696369383,10500,0,199.9998535,0,0,0,90.00000001 +342.45,50.30085681,-2.696341358,10500,0,199.9989614,0,0,0,90.00000001 +342.46,50.30085681,-2.696313333,10500,0,199.9989614,0,0,0,90.00000001 +342.47,50.30085681,-2.696285308,10500,0,199.9998535,0,0,0,90.00000001 +342.48,50.30085681,-2.696257283,10500,0,200.0009685,0,0,0,90.00000001 +342.49,50.30085681,-2.696229257,10500,0,200.0009685,0,0,0,90.00000001 +342.5,50.30085681,-2.696201232,10500,0,199.9998535,0,0,0,90.00000001 +342.51,50.30085681,-2.696173207,10500,0,199.9989614,0,0,0,90.00000001 +342.52,50.30085681,-2.696145182,10500,0,199.9989614,0,0,0,90.00000001 +342.53,50.30085681,-2.696117157,10500,0,199.9998535,0,0,0,90.00000001 +342.54,50.30085681,-2.696089132,10500,0,200.0009685,0,0,0,90.00000001 +342.55,50.30085681,-2.696061106,10500,0,200.0009685,0,0,0,90.00000001 +342.56,50.30085681,-2.696033081,10500,0,199.9998535,0,0,0,90.00000001 +342.57,50.30085681,-2.696005056,10500,0,199.9989614,0,0,0,90.00000001 +342.58,50.30085681,-2.695977031,10500,0,199.9989614,0,0,0,90.00000001 +342.59,50.30085681,-2.695949006,10500,0,199.9998535,0,0,0,90.00000001 +342.6,50.30085681,-2.695920981,10500,0,200.0009685,0,0,0,90.00000001 +342.61,50.30085681,-2.695892955,10500,0,200.0009685,0,0,0,90.00000001 +342.62,50.30085681,-2.69586493,10500,0,199.9998535,0,0,0,90.00000001 +342.63,50.30085681,-2.695836905,10500,0,199.9989614,0,0,0,90.00000001 +342.64,50.30085681,-2.69580888,10500,0,199.9989614,0,0,0,90.00000001 +342.65,50.30085681,-2.695780855,10500,0,199.9998535,0,0,0,90.00000001 +342.66,50.30085681,-2.69575283,10500,0,200.0009685,0,0,0,90.00000001 +342.67,50.30085681,-2.695724804,10500,0,200.0009685,0,0,0,90.00000001 +342.68,50.30085681,-2.695696779,10500,0,199.9998535,0,0,0,90.00000001 +342.69,50.30085681,-2.695668754,10500,0,199.9989614,0,0,0,90.00000001 +342.7,50.30085681,-2.695640729,10500,0,199.9989614,0,0,0,90.00000001 +342.71,50.30085681,-2.695612704,10500,0,199.9998535,0,0,0,90.00000001 +342.72,50.30085681,-2.695584679,10500,0,200.0009685,0,0,0,90.00000001 +342.73,50.30085681,-2.695556653,10500,0,200.0009685,0,0,0,90.00000001 +342.74,50.30085681,-2.695528628,10500,0,199.9998535,0,0,0,90.00000001 +342.75,50.30085681,-2.695500603,10500,0,199.9989614,0,0,0,90.00000001 +342.76,50.30085681,-2.695472578,10500,0,199.9987384,0,0,0,90.00000001 +342.77,50.30085681,-2.695444553,10500,0,199.9989614,0,0,0,90.00000001 +342.78,50.30085681,-2.695416528,10500,0,199.9998535,0,0,0,90.00000001 +342.79,50.30085681,-2.695388503,10500,0,200.0009685,0,0,0,90.00000001 +342.8,50.30085681,-2.695360477,10500,0,200.0009685,0,0,0,90.00000001 +342.81,50.30085681,-2.695332452,10500,0,199.9998535,0,0,0,90.00000001 +342.82,50.30085681,-2.695304427,10500,0,199.9991844,0,0,0,90.00000001 +342.83,50.30085681,-2.695276402,10500,0,199.9998535,0,0,0,90.00000001 +342.84,50.30085681,-2.695248377,10500,0,200.0009685,0,0,0,90.00000001 +342.85,50.30085681,-2.695220351,10500,0,200.0009685,0,0,0,90.00000001 +342.86,50.30085681,-2.695192326,10500,0,199.9998535,0,0,0,90.00000001 +342.87,50.30085681,-2.695164301,10500,0,199.9991844,0,0,0,90.00000001 +342.88,50.30085681,-2.695136276,10500,0,199.9998535,0,0,0,90.00000001 +342.89,50.30085681,-2.695108251,10500,0,200.0009685,0,0,0,90.00000001 +342.9,50.30085681,-2.695080225,10500,0,200.0009685,0,0,0,90.00000001 +342.91,50.30085681,-2.6950522,10500,0,199.9998535,0,0,0,90.00000001 +342.92,50.30085681,-2.695024175,10500,0,199.9991844,0,0,0,90.00000001 +342.93,50.30085681,-2.69499615,10500,0,199.9998535,0,0,0,90.00000001 +342.94,50.30085681,-2.694968125,10500,0,200.0009685,0,0,0,90.00000001 +342.95,50.30085681,-2.694940099,10500,0,200.0009685,0,0,0,90.00000001 +342.96,50.30085681,-2.694912074,10500,0,199.9998535,0,0,0,90.00000001 +342.97,50.30085681,-2.694884049,10500,0,199.9991844,0,0,0,90.00000001 +342.98,50.30085681,-2.694856024,10500,0,199.9998535,0,0,0,90.00000001 +342.99,50.30085681,-2.694827999,10500,0,200.0009685,0,0,0,90.00000001 +343,50.30085681,-2.694799973,10500,0,200.0009685,0,0,0,90.00000001 +343.01,50.30085681,-2.694771948,10500,0,199.9998535,0,0,0,90.00000001 +343.02,50.30085681,-2.694743923,10500,0,199.9991844,0,0,0,90.00000001 +343.03,50.30085681,-2.694715898,10500,0,199.9998535,0,0,0,90.00000001 +343.04,50.30085681,-2.694687873,10500,0,200.0009685,0,0,0,90.00000001 +343.05,50.30085681,-2.694659847,10500,0,200.0009685,0,0,0,90.00000001 +343.06,50.30085681,-2.694631822,10500,0,199.9998535,0,0,0,90.00000001 +343.07,50.30085681,-2.694603797,10500,0,199.9989614,0,0,0,90.00000001 +343.08,50.30085681,-2.694575772,10500,0,199.9989614,0,0,0,90.00000001 +343.09,50.30085681,-2.694547747,10500,0,199.9998535,0,0,0,90.00000001 +343.1,50.30085681,-2.694519722,10500,0,200.0009685,0,0,0,90.00000001 +343.11,50.30085681,-2.694491696,10500,0,200.0009685,0,0,0,90.00000001 +343.12,50.30085681,-2.694463671,10500,0,199.9998535,0,0,0,90.00000001 +343.13,50.30085681,-2.694435646,10500,0,199.9989614,0,0,0,90.00000001 +343.14,50.30085681,-2.694407621,10500,0,199.9989614,0,0,0,90.00000001 +343.15,50.30085681,-2.694379596,10500,0,199.9998535,0,0,0,90.00000001 +343.16,50.30085681,-2.694351571,10500,0,200.0009685,0,0,0,90.00000001 +343.17,50.30085681,-2.694323545,10500,0,200.0009685,0,0,0,90.00000001 +343.18,50.30085681,-2.69429552,10500,0,199.9998535,0,0,0,90.00000001 +343.19,50.30085681,-2.694267495,10500,0,199.9989614,0,0,0,90.00000001 +343.2,50.30085681,-2.69423947,10500,0,199.9989614,0,0,0,90.00000001 +343.21,50.30085681,-2.694211445,10500,0,199.9998535,0,0,0,90.00000001 +343.22,50.30085681,-2.69418342,10500,0,200.0009685,0,0,0,90.00000001 +343.23,50.30085681,-2.694155394,10500,0,200.0009685,0,0,0,90.00000001 +343.24,50.30085681,-2.694127369,10500,0,199.9998535,0,0,0,90.00000001 +343.25,50.30085681,-2.694099344,10500,0,199.9989614,0,0,0,90.00000001 +343.26,50.30085681,-2.694071319,10500,0,199.9989614,0,0,0,90.00000001 +343.27,50.30085681,-2.694043294,10500,0,199.9998535,0,0,0,90.00000001 +343.28,50.30085681,-2.694015269,10500,0,200.0009685,0,0,0,90.00000001 +343.29,50.30085681,-2.693987243,10500,0,200.0009685,0,0,0,90.00000001 +343.3,50.30085681,-2.693959218,10500,0,199.9998535,0,0,0,90.00000001 +343.31,50.30085681,-2.693931193,10500,0,199.9989614,0,0,0,90.00000001 +343.32,50.30085681,-2.693903168,10500,0,199.9987384,0,0,0,90.00000001 +343.33,50.30085681,-2.693875143,10500,0,199.9989614,0,0,0,90.00000001 +343.34,50.30085681,-2.693847118,10500,0,199.9998535,0,0,0,90.00000001 +343.35,50.30085681,-2.693819093,10500,0,200.0009685,0,0,0,90.00000001 +343.36,50.30085681,-2.693791067,10500,0,200.0009685,0,0,0,90.00000001 +343.37,50.30085681,-2.693763042,10500,0,199.9998535,0,0,0,90.00000001 +343.38,50.30085681,-2.693735017,10500,0,199.9989614,0,0,0,90.00000001 +343.39,50.30085681,-2.693706992,10500,0,199.9989614,0,0,0,90.00000001 +343.4,50.30085681,-2.693678967,10500,0,199.9998535,0,0,0,90.00000001 +343.41,50.30085681,-2.693650942,10500,0,200.0009685,0,0,0,90.00000001 +343.42,50.30085681,-2.693622916,10500,0,200.0009685,0,0,0,90.00000001 +343.43,50.30085681,-2.693594891,10500,0,199.9998535,0,0,0,90.00000001 +343.44,50.30085681,-2.693566866,10500,0,199.9991844,0,0,0,90.00000001 +343.45,50.30085681,-2.693538841,10500,0,199.9998535,0,0,0,90.00000001 +343.46,50.30085681,-2.693510816,10500,0,200.0009685,0,0,0,90.00000001 +343.47,50.30085681,-2.69348279,10500,0,200.0009685,0,0,0,90.00000001 +343.48,50.30085681,-2.693454765,10500,0,199.9998535,0,0,0,90.00000001 +343.49,50.30085681,-2.69342674,10500,0,199.9989614,0,0,0,90.00000001 +343.5,50.30085681,-2.693398715,10500,0,199.9989614,0,0,0,90.00000001 +343.51,50.30085681,-2.69337069,10500,0,199.9998535,0,0,0,90.00000001 +343.52,50.30085681,-2.693342665,10500,0,200.0009685,0,0,0,90.00000001 +343.53,50.30085681,-2.693314639,10500,0,200.0009685,0,0,0,90.00000001 +343.54,50.30085681,-2.693286614,10500,0,199.9998535,0,0,0,90.00000001 +343.55,50.30085681,-2.693258589,10500,0,199.9991844,0,0,0,90.00000001 +343.56,50.30085681,-2.693230564,10500,0,199.9998535,0,0,0,90.00000001 +343.57,50.30085681,-2.693202539,10500,0,200.0009685,0,0,0,90.00000001 +343.58,50.30085681,-2.693174513,10500,0,200.0009685,0,0,0,90.00000001 +343.59,50.30085681,-2.693146488,10500,0,199.9998535,0,0,0,90.00000001 +343.6,50.30085681,-2.693118463,10500,0,199.9991844,0,0,0,90.00000001 +343.61,50.30085681,-2.693090438,10500,0,199.9998535,0,0,0,90.00000001 +343.62,50.30085681,-2.693062413,10500,0,200.0009685,0,0,0,90.00000001 +343.63,50.30085681,-2.693034387,10500,0,200.0009685,0,0,0,90.00000001 +343.64,50.30085681,-2.693006362,10500,0,199.9998535,0,0,0,90.00000001 +343.65,50.30085681,-2.692978337,10500,0,199.9991844,0,0,0,90.00000001 +343.66,50.30085681,-2.692950312,10500,0,199.9998535,0,0,0,90.00000001 +343.67,50.30085681,-2.692922287,10500,0,200.0009685,0,0,0,90.00000001 +343.68,50.30085681,-2.692894261,10500,0,200.0009685,0,0,0,90.00000001 +343.69,50.30085681,-2.692866236,10500,0,199.9998535,0,0,0,90.00000001 +343.7,50.30085681,-2.692838211,10500,0,199.9991844,0,0,0,90.00000001 +343.71,50.30085681,-2.692810186,10500,0,199.9998535,0,0,0,90.00000001 +343.72,50.30085681,-2.692782161,10500,0,200.0009685,0,0,0,90.00000001 +343.73,50.30085681,-2.692754135,10500,0,200.0009685,0,0,0,90.00000001 +343.74,50.30085681,-2.69272611,10500,0,199.9998535,0,0,0,90.00000001 +343.75,50.30085681,-2.692698085,10500,0,199.9989614,0,0,0,90.00000001 +343.76,50.30085681,-2.69267006,10500,0,199.9989614,0,0,0,90.00000001 +343.77,50.30085681,-2.692642035,10500,0,199.9998535,0,0,0,90.00000001 +343.78,50.30085681,-2.69261401,10500,0,200.0009685,0,0,0,90.00000001 +343.79,50.30085681,-2.692585984,10500,0,200.0009685,0,0,0,90.00000001 +343.8,50.30085681,-2.692557959,10500,0,199.9998535,0,0,0,90.00000001 +343.81,50.30085681,-2.692529934,10500,0,199.9989614,0,0,0,90.00000001 +343.82,50.30085681,-2.692501909,10500,0,199.9989614,0,0,0,90.00000001 +343.83,50.30085681,-2.692473884,10500,0,199.9998535,0,0,0,90.00000001 +343.84,50.30085681,-2.692445859,10500,0,200.0009685,0,0,0,90.00000001 +343.85,50.30085681,-2.692417833,10500,0,200.0009685,0,0,0,90.00000001 +343.86,50.30085681,-2.692389808,10500,0,199.9998535,0,0,0,90.00000001 +343.87,50.30085681,-2.692361783,10500,0,199.9989614,0,0,0,90.00000001 +343.88,50.30085681,-2.692333758,10500,0,199.9987384,0,0,0,90.00000001 +343.89,50.30085681,-2.692305733,10500,0,199.9989614,0,0,0,90.00000001 +343.9,50.30085681,-2.692277708,10500,0,199.9998535,0,0,0,90.00000001 +343.91,50.30085681,-2.692249683,10500,0,200.0009685,0,0,0,90.00000001 +343.92,50.30085681,-2.692221657,10500,0,200.0009685,0,0,0,90.00000001 +343.93,50.30085681,-2.692193632,10500,0,199.9998535,0,0,0,90.00000001 +343.94,50.30085681,-2.692165607,10500,0,199.9989614,0,0,0,90.00000001 +343.95,50.30085681,-2.692137582,10500,0,199.9989614,0,0,0,90.00000001 +343.96,50.30085681,-2.692109557,10500,0,199.9998535,0,0,0,90.00000001 +343.97,50.30085681,-2.692081532,10500,0,200.0009685,0,0,0,90.00000001 +343.98,50.30085681,-2.692053506,10500,0,200.0009685,0,0,0,90.00000001 +343.99,50.30085681,-2.692025481,10500,0,199.9998535,0,0,0,90.00000001 +344,50.30085681,-2.691997456,10500,0,199.9989614,0,0,0,90.00000001 +344.01,50.30085681,-2.691969431,10500,0,199.9989614,0,0,0,90.00000001 +344.02,50.30085681,-2.691941406,10500,0,199.9998535,0,0,0,90.00000001 +344.03,50.30085681,-2.691913381,10500,0,200.0009685,0,0,0,90.00000001 +344.04,50.30085681,-2.691885355,10500,0,200.0009685,0,0,0,90.00000001 +344.05,50.30085681,-2.69185733,10500,0,199.9998535,0,0,0,90.00000001 +344.06,50.30085681,-2.691829305,10500,0,199.9989614,0,0,0,90.00000001 +344.07,50.30085681,-2.69180128,10500,0,199.9989614,0,0,0,90.00000001 +344.08,50.30085681,-2.691773255,10500,0,199.9998535,0,0,0,90.00000001 +344.09,50.30085681,-2.69174523,10500,0,200.0009685,0,0,0,90.00000001 +344.1,50.30085681,-2.691717204,10500,0,200.0009685,0,0,0,90.00000001 +344.11,50.30085681,-2.691689179,10500,0,199.9998535,0,0,0,90.00000001 +344.12,50.30085681,-2.691661154,10500,0,199.9991844,0,0,0,90.00000001 +344.13,50.30085681,-2.691633129,10500,0,199.9998535,0,0,0,90.00000001 +344.14,50.30085681,-2.691605104,10500,0,200.0009685,0,0,0,90.00000001 +344.15,50.30085681,-2.691577078,10500,0,200.0009685,0,0,0,90.00000001 +344.16,50.30085681,-2.691549053,10500,0,199.9998535,0,0,0,90.00000001 +344.17,50.30085681,-2.691521028,10500,0,199.9991844,0,0,0,90.00000001 +344.18,50.30085681,-2.691493003,10500,0,199.9998535,0,0,0,90.00000001 +344.19,50.30085681,-2.691464978,10500,0,200.0009685,0,0,0,90.00000001 +344.2,50.30085681,-2.691436952,10500,0,200.0009685,0,0,0,90.00000001 +344.21,50.30085681,-2.691408927,10500,0,199.9998535,0,0,0,90.00000001 +344.22,50.30085681,-2.691380902,10500,0,199.9991844,0,0,0,90.00000001 +344.23,50.30085681,-2.691352877,10500,0,199.9998535,0,0,0,90.00000001 +344.24,50.30085681,-2.691324852,10500,0,200.0009685,0,0,0,90.00000001 +344.25,50.30085681,-2.691296826,10500,0,200.0009685,0,0,0,90.00000001 +344.26,50.30085681,-2.691268801,10500,0,199.9998535,0,0,0,90.00000001 +344.27,50.30085681,-2.691240776,10500,0,199.9991844,0,0,0,90.00000001 +344.28,50.30085681,-2.691212751,10500,0,199.9998535,0,0,0,90.00000001 +344.29,50.30085681,-2.691184726,10500,0,200.0009685,0,0,0,90.00000001 +344.3,50.30085681,-2.6911567,10500,0,200.0009685,0,0,0,90.00000001 +344.31,50.30085681,-2.691128675,10500,0,199.9998535,0,0,0,90.00000001 +344.32,50.30085681,-2.69110065,10500,0,199.9991844,0,0,0,90.00000001 +344.33,50.30085681,-2.691072625,10500,0,199.9998535,0,0,0,90.00000001 +344.34,50.30085681,-2.6910446,10500,0,200.0009685,0,0,0,90.00000001 +344.35,50.30085681,-2.691016574,10500,0,200.0009685,0,0,0,90.00000001 +344.36,50.30085681,-2.690988549,10500,0,199.9998535,0,0,0,90.00000001 +344.37,50.30085681,-2.690960524,10500,0,199.9989614,0,0,0,90.00000001 +344.38,50.30085681,-2.690932499,10500,0,199.9989614,0,0,0,90.00000001 +344.39,50.30085681,-2.690904474,10500,0,199.9998535,0,0,0,90.00000001 +344.4,50.30085681,-2.690876449,10500,0,200.0009685,0,0,0,90.00000001 +344.41,50.30085681,-2.690848423,10500,0,200.0009685,0,0,0,90.00000001 +344.42,50.30085681,-2.690820398,10500,0,199.9998535,0,0,0,90.00000001 +344.43,50.30085681,-2.690792373,10500,0,199.9989614,0,0,0,90.00000001 +344.44,50.30085681,-2.690764348,10500,0,199.9987384,0,0,0,90.00000001 +344.45,50.30085681,-2.690736323,10500,0,199.9989614,0,0,0,90.00000001 +344.46,50.30085681,-2.690708298,10500,0,199.9998535,0,0,0,90.00000001 +344.47,50.30085681,-2.690680273,10500,0,200.0009685,0,0,0,90.00000001 +344.48,50.30085681,-2.690652247,10500,0,200.0009685,0,0,0,90.00000001 +344.49,50.30085681,-2.690624222,10500,0,199.9998535,0,0,0,90.00000001 +344.5,50.30085681,-2.690596197,10500,0,199.9989614,0,0,0,90.00000001 +344.51,50.30085681,-2.690568172,10500,0,199.9989614,0,0,0,90.00000001 +344.52,50.30085681,-2.690540147,10500,0,199.9998535,0,0,0,90.00000001 +344.53,50.30085681,-2.690512122,10500,0,200.0009685,0,0,0,90.00000001 +344.54,50.30085681,-2.690484096,10500,0,200.0009685,0,0,0,90.00000001 +344.55,50.30085681,-2.690456071,10500,0,199.9998535,0,0,0,90.00000001 +344.56,50.30085681,-2.690428046,10500,0,199.9989614,0,0,0,90.00000001 +344.57,50.30085681,-2.690400021,10500,0,199.9989614,0,0,0,90.00000001 +344.58,50.30085681,-2.690371996,10500,0,199.9998535,0,0,0,90.00000001 +344.59,50.30085681,-2.690343971,10500,0,200.0009685,0,0,0,90.00000001 +344.6,50.30085681,-2.690315945,10500,0,200.0009685,0,0,0,90.00000001 +344.61,50.30085681,-2.69028792,10500,0,199.9998535,0,0,0,90.00000001 +344.62,50.30085681,-2.690259895,10500,0,199.9989614,0,0,0,90.00000001 +344.63,50.30085681,-2.69023187,10500,0,199.9989614,0,0,0,90.00000001 +344.64,50.30085681,-2.690203845,10500,0,199.9998535,0,0,0,90.00000001 +344.65,50.30085681,-2.69017582,10500,0,200.0009685,0,0,0,90.00000001 +344.66,50.30085681,-2.690147794,10500,0,200.0009685,0,0,0,90.00000001 +344.67,50.30085681,-2.690119769,10500,0,199.9998535,0,0,0,90.00000001 +344.68,50.30085681,-2.690091744,10500,0,199.9989614,0,0,0,90.00000001 +344.69,50.30085681,-2.690063719,10500,0,199.9989614,0,0,0,90.00000001 +344.7,50.30085681,-2.690035694,10500,0,199.9998535,0,0,0,90.00000001 +344.71,50.30085681,-2.690007669,10500,0,200.0009685,0,0,0,90.00000001 +344.72,50.30085681,-2.689979643,10500,0,200.0009685,0,0,0,90.00000001 +344.73,50.30085681,-2.689951618,10500,0,199.9998535,0,0,0,90.00000001 +344.74,50.30085681,-2.689923593,10500,0,199.9991844,0,0,0,90.00000001 +344.75,50.30085681,-2.689895568,10500,0,199.9998535,0,0,0,90.00000001 +344.76,50.30085681,-2.689867543,10500,0,200.0009685,0,0,0,90.00000001 +344.77,50.30085681,-2.689839517,10500,0,200.0009685,0,0,0,90.00000001 +344.78,50.30085681,-2.689811492,10500,0,199.9998535,0,0,0,90.00000001 +344.79,50.30085681,-2.689783467,10500,0,199.9991844,0,0,0,90.00000001 +344.8,50.30085681,-2.689755442,10500,0,199.9998535,0,0,0,90.00000001 +344.81,50.30085681,-2.689727417,10500,0,200.0009685,0,0,0,90.00000001 +344.82,50.30085681,-2.689699391,10500,0,200.0009685,0,0,0,90.00000001 +344.83,50.30085681,-2.689671366,10500,0,199.9998535,0,0,0,90.00000001 +344.84,50.30085681,-2.689643341,10500,0,199.9991844,0,0,0,90.00000001 +344.85,50.30085681,-2.689615316,10500,0,199.9998535,0,0,0,90.00000001 +344.86,50.30085681,-2.689587291,10500,0,200.0009685,0,0,0,90.00000001 +344.87,50.30085681,-2.689559265,10500,0,200.0009685,0,0,0,90.00000001 +344.88,50.30085681,-2.68953124,10500,0,199.9998535,0,0,0,90.00000001 +344.89,50.30085681,-2.689503215,10500,0,199.9991844,0,0,0,90.00000001 +344.9,50.30085681,-2.68947519,10500,0,199.9998535,0,0,0,90.00000001 +344.91,50.30085681,-2.689447165,10500,0,200.0009685,0,0,0,90.00000001 +344.92,50.30085681,-2.689419139,10500,0,200.0009685,0,0,0,90.00000001 +344.93,50.30085681,-2.689391114,10500,0,199.9998535,0,0,0,90.00000001 +344.94,50.30085681,-2.689363089,10500,0,199.9991844,0,0,0,90.00000001 +344.95,50.30085681,-2.689335064,10500,0,199.9998535,0,0,0,90.00000001 +344.96,50.30085681,-2.689307039,10500,0,200.0009685,0,0,0,90.00000001 +344.97,50.30085681,-2.689279013,10500,0,200.0009685,0,0,0,90.00000001 +344.98,50.30085681,-2.689250988,10500,0,199.9998535,0,0,0,90.00000001 +344.99,50.30085681,-2.689222963,10500,0,199.9989614,0,0,0,90.00000001 +345,50.30085681,-2.689194938,10500,0,199.9989614,0,0,0,90.00000001 +345.01,50.30085681,-2.689166913,10500,0,199.9998535,0,0,0,90.00000001 +345.02,50.30085681,-2.689138888,10500,0,200.0009685,0,0,0,90.00000001 +345.03,50.30085681,-2.689110862,10500,0,200.0009685,0,0,0,90.00000001 +345.04,50.30085681,-2.689082837,10500,0,199.9998535,0,0,0,90.00000001 +345.05,50.30085681,-2.689054812,10500,0,199.9989614,0,0,0,90.00000001 +345.06,50.30085681,-2.689026787,10500,0,199.9987384,0,0,0,90.00000001 +345.07,50.30085681,-2.688998762,10500,0,199.9989614,0,0,0,90.00000001 +345.08,50.30085681,-2.688970737,10500,0,199.9998535,0,0,0,90.00000001 +345.09,50.30085681,-2.688942712,10500,0,200.0009685,0,0,0,90.00000001 +345.1,50.30085681,-2.688914686,10500,0,200.0009685,0,0,0,90.00000001 +345.11,50.30085681,-2.688886661,10500,0,199.9998535,0,0,0,90.00000001 +345.12,50.30085681,-2.688858636,10500,0,199.9989614,0,0,0,90.00000001 +345.13,50.30085681,-2.688830611,10500,0,199.9989614,0,0,0,90.00000001 +345.14,50.30085681,-2.688802586,10500,0,199.9998535,0,0,0,90.00000001 +345.15,50.30085681,-2.688774561,10500,0,200.0009685,0,0,0,90.00000001 +345.16,50.30085681,-2.688746535,10500,0,200.0009685,0,0,0,90.00000001 +345.17,50.30085681,-2.68871851,10500,0,199.9998535,0,0,0,90.00000001 +345.18,50.30085681,-2.688690485,10500,0,199.9989614,0,0,0,90.00000001 +345.19,50.30085681,-2.68866246,10500,0,199.9989614,0,0,0,90.00000001 +345.2,50.30085681,-2.688634435,10500,0,199.9998535,0,0,0,90.00000001 +345.21,50.30085681,-2.68860641,10500,0,200.0009685,0,0,0,90.00000001 +345.22,50.30085681,-2.688578384,10500,0,200.0009685,0,0,0,90.00000001 +345.23,50.30085681,-2.688550359,10500,0,199.9998535,0,0,0,90.00000001 +345.24,50.30085681,-2.688522334,10500,0,199.9989614,0,0,0,90.00000001 +345.25,50.30085681,-2.688494309,10500,0,199.9989614,0,0,0,90.00000001 +345.26,50.30085681,-2.688466284,10500,0,199.9998535,0,0,0,90.00000001 +345.27,50.30085681,-2.688438259,10500,0,200.0009685,0,0,0,90.00000001 +345.28,50.30085681,-2.688410233,10500,0,200.0009685,0,0,0,90.00000001 +345.29,50.30085681,-2.688382208,10500,0,199.9998535,0,0,0,90.00000001 +345.3,50.30085681,-2.688354183,10500,0,199.9989614,0,0,0,90.00000001 +345.31,50.30085681,-2.688326158,10500,0,199.9989614,0,0,0,90.00000001 +345.32,50.30085681,-2.688298133,10500,0,199.9998535,0,0,0,90.00000001 +345.33,50.30085681,-2.688270108,10500,0,200.0009685,0,0,0,90.00000001 +345.34,50.30085681,-2.688242082,10500,0,200.0009685,0,0,0,90.00000001 +345.35,50.30085681,-2.688214057,10500,0,199.9998535,0,0,0,90.00000001 +345.36,50.30085681,-2.688186032,10500,0,199.9991844,0,0,0,90.00000001 +345.37,50.30085681,-2.688158007,10500,0,199.9998535,0,0,0,90.00000001 +345.38,50.30085681,-2.688129982,10500,0,200.0009685,0,0,0,90.00000001 +345.39,50.30085681,-2.688101956,10500,0,200.0009685,0,0,0,90.00000001 +345.4,50.30085681,-2.688073931,10500,0,199.9998535,0,0,0,90.00000001 +345.41,50.30085681,-2.688045906,10500,0,199.9991844,0,0,0,90.00000001 +345.42,50.30085681,-2.688017881,10500,0,199.9998535,0,0,0,90.00000001 +345.43,50.30085681,-2.687989856,10500,0,200.0009685,0,0,0,90.00000001 +345.44,50.30085681,-2.68796183,10500,0,200.0009685,0,0,0,90.00000001 +345.45,50.30085681,-2.687933805,10500,0,199.9998535,0,0,0,90.00000001 +345.46,50.30085681,-2.68790578,10500,0,199.9991844,0,0,0,90.00000001 +345.47,50.30085681,-2.687877755,10500,0,199.9998535,0,0,0,90.00000001 +345.48,50.30085681,-2.68784973,10500,0,200.0009685,0,0,0,90.00000001 +345.49,50.30085681,-2.687821704,10500,0,200.0009685,0,0,0,90.00000001 +345.5,50.30085681,-2.687793679,10500,0,199.9998535,0,0,0,90.00000001 +345.51,50.30085681,-2.687765654,10500,0,199.9991844,0,0,0,90.00000001 +345.52,50.30085681,-2.687737629,10500,0,199.9998535,0,0,0,90.00000001 +345.53,50.30085681,-2.687709604,10500,0,200.0009685,0,0,0,90.00000001 +345.54,50.30085681,-2.687681578,10500,0,200.0009685,0,0,0,90.00000001 +345.55,50.30085681,-2.687653553,10500,0,199.9998535,0,0,0,90.00000001 +345.56,50.30085681,-2.687625528,10500,0,199.9989614,0,0,0,90.00000001 +345.57,50.30085681,-2.687597503,10500,0,199.9989614,0,0,0,90.00000001 +345.58,50.30085681,-2.687569478,10500,0,199.9998535,0,0,0,90.00000001 +345.59,50.30085681,-2.687541453,10500,0,200.0009685,0,0,0,90.00000001 +345.6,50.30085681,-2.687513427,10500,0,200.0009685,0,0,0,90.00000001 +345.61,50.30085681,-2.687485402,10500,0,199.9998535,0,0,0,90.00000001 +345.62,50.30085681,-2.687457377,10500,0,199.9989614,0,0,0,90.00000001 +345.63,50.30085681,-2.687429352,10500,0,199.9989614,0,0,0,90.00000001 +345.64,50.30085681,-2.687401327,10500,0,199.9998535,0,0,0,90.00000001 +345.65,50.30085681,-2.687373302,10500,0,200.0009685,0,0,0,90.00000001 +345.66,50.30085681,-2.687345276,10500,0,200.0009685,0,0,0,90.00000001 +345.67,50.30085681,-2.687317251,10500,0,199.9998535,0,0,0,90.00000001 +345.68,50.30085681,-2.687289226,10500,0,199.9989614,0,0,0,90.00000001 +345.69,50.30085681,-2.687261201,10500,0,199.9989614,0,0,0,90.00000001 +345.7,50.30085681,-2.687233176,10500,0,199.9998535,0,0,0,90.00000001 +345.71,50.30085681,-2.687205151,10500,0,200.0009685,0,0,0,90.00000001 +345.72,50.30085681,-2.687177125,10500,0,200.0009685,0,0,0,90.00000001 +345.73,50.30085681,-2.6871491,10500,0,199.9998535,0,0,0,90.00000001 +345.74,50.30085681,-2.687121075,10500,0,199.9989614,0,0,0,90.00000001 +345.75,50.30085681,-2.68709305,10500,0,199.9989614,0,0,0,90.00000001 +345.76,50.30085681,-2.687065025,10500,0,199.9998535,0,0,0,90.00000001 +345.77,50.30085681,-2.687037,10500,0,200.0009685,0,0,0,90.00000001 +345.78,50.30085681,-2.687008974,10500,0,200.0009685,0,0,0,90.00000001 +345.79,50.30085681,-2.686980949,10500,0,199.9998535,0,0,0,90.00000001 +345.8,50.30085681,-2.686952924,10500,0,199.9989614,0,0,0,90.00000001 +345.81,50.30085681,-2.686924899,10500,0,199.9989614,0,0,0,90.00000001 +345.82,50.30085681,-2.686896874,10500,0,199.9998535,0,0,0,90.00000001 +345.83,50.30085681,-2.686868849,10500,0,200.0009685,0,0,0,90.00000001 +345.84,50.30085681,-2.686840823,10500,0,200.0009685,0,0,0,90.00000001 +345.85,50.30085681,-2.686812798,10500,0,199.9998535,0,0,0,90.00000001 +345.86,50.30085681,-2.686784773,10500,0,199.9989614,0,0,0,90.00000001 +345.87,50.30085681,-2.686756748,10500,0,199.9987384,0,0,0,90.00000001 +345.88,50.30085681,-2.686728723,10500,0,199.9989614,0,0,0,90.00000001 +345.89,50.30085681,-2.686700698,10500,0,199.9998535,0,0,0,90.00000001 +345.9,50.30085681,-2.686672673,10500,0,200.0009685,0,0,0,90.00000001 +345.91,50.30085681,-2.686644647,10500,0,200.0009685,0,0,0,90.00000001 +345.92,50.30085681,-2.686616622,10500,0,199.9998535,0,0,0,90.00000001 +345.93,50.30085681,-2.686588597,10500,0,199.9989614,0,0,0,90.00000001 +345.94,50.30085681,-2.686560572,10500,0,199.9989614,0,0,0,90.00000001 +345.95,50.30085681,-2.686532547,10500,0,199.9998535,0,0,0,90.00000001 +345.96,50.30085681,-2.686504522,10500,0,200.0009685,0,0,0,90.00000001 +345.97,50.30085681,-2.686476496,10500,0,200.0009685,0,0,0,90.00000001 +345.98,50.30085681,-2.686448471,10500,0,199.9998535,0,0,0,90.00000001 +345.99,50.30085681,-2.686420446,10500,0,199.9991844,0,0,0,90.00000001 +346,50.30085681,-2.686392421,10500,0,199.9998535,0,0,0,90.00000001 +346.01,50.30085681,-2.686364396,10500,0,200.0009685,0,0,0,90.00000001 +346.02,50.30085681,-2.68633637,10500,0,200.0009685,0,0,0,90.00000001 +346.03,50.30085681,-2.686308345,10500,0,199.9998535,0,0,0,90.00000001 +346.04,50.30085681,-2.68628032,10500,0,199.9991844,0,0,0,90.00000001 +346.05,50.30085681,-2.686252295,10500,0,199.9998535,0,0,0,90.00000001 +346.06,50.30085681,-2.68622427,10500,0,200.0009685,0,0,0,90.00000001 +346.07,50.30085681,-2.686196244,10500,0,200.0009685,0,0,0,90.00000001 +346.08,50.30085681,-2.686168219,10500,0,199.9998535,0,0,0,90.00000001 +346.09,50.30085681,-2.686140194,10500,0,199.9991844,0,0,0,90.00000001 +346.1,50.30085681,-2.686112169,10500,0,199.9998535,0,0,0,90.00000001 +346.11,50.30085681,-2.686084144,10500,0,200.0009685,0,0,0,90.00000001 +346.12,50.30085681,-2.686056118,10500,0,200.0009685,0,0,0,90.00000001 +346.13,50.30085681,-2.686028093,10500,0,199.9998535,0,0,0,90.00000001 +346.14,50.30085681,-2.686000068,10500,0,199.9991844,0,0,0,90.00000001 +346.15,50.30085681,-2.685972043,10500,0,199.9998535,0,0,0,90.00000001 +346.16,50.30085681,-2.685944018,10500,0,200.0009685,0,0,0,90.00000001 +346.17,50.30085681,-2.685915992,10500,0,200.0009685,0,0,0,90.00000001 +346.18,50.30085681,-2.685887967,10500,0,199.9998535,0,0,0,90.00000001 +346.19,50.30085681,-2.685859942,10500,0,199.9991844,0,0,0,90.00000001 +346.2,50.30085681,-2.685831917,10500,0,199.9998535,0,0,0,90.00000001 +346.21,50.30085681,-2.685803892,10500,0,200.0009685,0,0,0,90.00000001 +346.22,50.30085681,-2.685775866,10500,0,200.0009685,0,0,0,90.00000001 +346.23,50.30085681,-2.685747841,10500,0,199.9998535,0,0,0,90.00000001 +346.24,50.30085681,-2.685719816,10500,0,199.9989614,0,0,0,90.00000001 +346.25,50.30085681,-2.685691791,10500,0,199.9989614,0,0,0,90.00000001 +346.26,50.30085681,-2.685663766,10500,0,199.9998535,0,0,0,90.00000001 +346.27,50.30085681,-2.685635741,10500,0,200.0009685,0,0,0,90.00000001 +346.28,50.30085681,-2.685607715,10500,0,200.0009685,0,0,0,90.00000001 +346.29,50.30085681,-2.68557969,10500,0,199.9998535,0,0,0,90.00000001 +346.3,50.30085681,-2.685551665,10500,0,199.9989614,0,0,0,90.00000001 +346.31,50.30085681,-2.68552364,10500,0,199.9989614,0,0,0,90.00000001 +346.32,50.30085681,-2.685495615,10500,0,199.9998535,0,0,0,90.00000001 +346.33,50.30085681,-2.68546759,10500,0,200.0009685,0,0,0,90.00000001 +346.34,50.30085681,-2.685439564,10500,0,200.0009685,0,0,0,90.00000001 +346.35,50.30085681,-2.685411539,10500,0,199.9998535,0,0,0,90.00000001 +346.36,50.30085681,-2.685383514,10500,0,199.9989614,0,0,0,90.00000001 +346.37,50.30085681,-2.685355489,10500,0,199.9989614,0,0,0,90.00000001 +346.38,50.30085681,-2.685327464,10500,0,199.9998535,0,0,0,90.00000001 +346.39,50.30085681,-2.685299439,10500,0,200.0009685,0,0,0,90.00000001 +346.4,50.30085681,-2.685271413,10500,0,200.0009685,0,0,0,90.00000001 +346.41,50.30085681,-2.685243388,10500,0,199.9998535,0,0,0,90.00000001 +346.42,50.30085681,-2.685215363,10500,0,199.9989614,0,0,0,90.00000001 +346.43,50.30085681,-2.685187338,10500,0,199.9989614,0,0,0,90.00000001 +346.44,50.30085681,-2.685159313,10500,0,199.9998535,0,0,0,90.00000001 +346.45,50.30085681,-2.685131288,10500,0,200.0009685,0,0,0,90.00000001 +346.46,50.30085681,-2.685103262,10500,0,200.0009685,0,0,0,90.00000001 +346.47,50.30085681,-2.685075237,10500,0,199.9998535,0,0,0,90.00000001 +346.48,50.30085681,-2.685047212,10500,0,199.9989614,0,0,0,90.00000001 +346.49,50.30085681,-2.685019187,10500,0,199.9987384,0,0,0,90.00000001 +346.5,50.30085681,-2.684991162,10500,0,199.9989614,0,0,0,90.00000001 +346.51,50.30085681,-2.684963137,10500,0,199.9998535,0,0,0,90.00000001 +346.52,50.30085681,-2.684935112,10500,0,200.0009685,0,0,0,90.00000001 +346.53,50.30085681,-2.684907086,10500,0,200.0009685,0,0,0,90.00000001 +346.54,50.30085681,-2.684879061,10500,0,199.9998535,0,0,0,90.00000001 +346.55,50.30085681,-2.684851036,10500,0,199.9989614,0,0,0,90.00000001 +346.56,50.30085681,-2.684823011,10500,0,199.9989614,0,0,0,90.00000001 +346.57,50.30085681,-2.684794986,10500,0,199.9998535,0,0,0,90.00000001 +346.58,50.30085681,-2.684766961,10500,0,200.0009685,0,0,0,90.00000001 +346.59,50.30085681,-2.684738935,10500,0,200.0009685,0,0,0,90.00000001 +346.6,50.30085681,-2.68471091,10500,0,199.9998535,0,0,0,90.00000001 +346.61,50.30085681,-2.684682885,10500,0,199.9991844,0,0,0,90.00000001 +346.62,50.30085681,-2.68465486,10500,0,199.9998535,0,0,0,90.00000001 +346.63,50.30085681,-2.684626835,10500,0,200.0009685,0,0,0,90.00000001 +346.64,50.30085681,-2.684598809,10500,0,200.0009685,0,0,0,90.00000001 +346.65,50.30085681,-2.684570784,10500,0,199.9998535,0,0,0,90.00000001 +346.66,50.30085681,-2.684542759,10500,0,199.9991844,0,0,0,90.00000001 +346.67,50.30085681,-2.684514734,10500,0,199.9998535,0,0,0,90.00000001 +346.68,50.30085681,-2.684486709,10500,0,200.0009685,0,0,0,90.00000001 +346.69,50.30085681,-2.684458683,10500,0,200.0009685,0,0,0,90.00000001 +346.7,50.30085681,-2.684430658,10500,0,199.9998535,0,0,0,90.00000001 +346.71,50.30085681,-2.684402633,10500,0,199.9991844,0,0,0,90.00000001 +346.72,50.30085681,-2.684374608,10500,0,199.9998535,0,0,0,90.00000001 +346.73,50.30085681,-2.684346583,10500,0,200.0009685,0,0,0,90.00000001 +346.74,50.30085681,-2.684318557,10500,0,200.0009685,0,0,0,90.00000001 +346.75,50.30085681,-2.684290532,10500,0,199.9998535,0,0,0,90.00000001 +346.76,50.30085681,-2.684262507,10500,0,199.9991844,0,0,0,90.00000001 +346.77,50.30085681,-2.684234482,10500,0,199.9998535,0,0,0,90.00000001 +346.78,50.30085681,-2.684206457,10500,0,200.0009685,0,0,0,90.00000001 +346.79,50.30085681,-2.684178431,10500,0,200.0009685,0,0,0,90.00000001 +346.8,50.30085681,-2.684150406,10500,0,199.9998535,0,0,0,90.00000001 +346.81,50.30085681,-2.684122381,10500,0,199.9991844,0,0,0,90.00000001 +346.82,50.30085681,-2.684094356,10500,0,199.9998535,0,0,0,90.00000001 +346.83,50.30085681,-2.684066331,10500,0,200.0009685,0,0,0,90.00000001 +346.84,50.30085681,-2.684038305,10500,0,200.0009685,0,0,0,90.00000001 +346.85,50.30085681,-2.68401028,10500,0,199.9998535,0,0,0,90.00000001 +346.86,50.30085681,-2.683982255,10500,0,199.9989614,0,0,0,90.00000001 +346.87,50.30085681,-2.68395423,10500,0,199.9989614,0,0,0,90.00000001 +346.88,50.30085681,-2.683926205,10500,0,199.9998535,0,0,0,90.00000001 +346.89,50.30085681,-2.68389818,10500,0,200.0009685,0,0,0,90.00000001 +346.9,50.30085681,-2.683870154,10500,0,200.0009685,0,0,0,90.00000001 +346.91,50.30085681,-2.683842129,10500,0,199.9998535,0,0,0,90.00000001 +346.92,50.30085681,-2.683814104,10500,0,199.9989614,0,0,0,90.00000001 +346.93,50.30085681,-2.683786079,10500,0,199.9989614,0,0,0,90.00000001 +346.94,50.30085681,-2.683758054,10500,0,199.9998535,0,0,0,90.00000001 +346.95,50.30085681,-2.683730029,10500,0,200.0009685,0,0,0,90.00000001 +346.96,50.30085681,-2.683702003,10500,0,200.0009685,0,0,0,90.00000001 +346.97,50.30085681,-2.683673978,10500,0,199.9998535,0,0,0,90.00000001 +346.98,50.30085681,-2.683645953,10500,0,199.9989614,0,0,0,90.00000001 +346.99,50.30085681,-2.683617928,10500,0,199.9989614,0,0,0,90.00000001 +347,50.30085681,-2.683589903,10500,0,199.9998535,0,0,0,90.00000001 +347.01,50.30085681,-2.683561878,10500,0,200.0009685,0,0,0,90.00000001 +347.02,50.30085681,-2.683533852,10500,0,200.0009685,0,0,0,90.00000001 +347.03,50.30085681,-2.683505827,10500,0,199.9998535,0,0,0,90.00000001 +347.04,50.30085681,-2.683477802,10500,0,199.9989614,0,0,0,90.00000001 +347.05,50.30085681,-2.683449777,10500,0,199.9987384,0,0,0,90.00000001 +347.06,50.30085681,-2.683421752,10500,0,199.9989614,0,0,0,90.00000001 +347.07,50.30085681,-2.683393727,10500,0,199.9998535,0,0,0,90.00000001 +347.08,50.30085681,-2.683365702,10500,0,200.0009685,0,0,0,90.00000001 +347.09,50.30085681,-2.683337676,10500,0,200.0009685,0,0,0,90.00000001 +347.1,50.30085681,-2.683309651,10500,0,199.9998535,0,0,0,90.00000001 +347.11,50.30085681,-2.683281626,10500,0,199.9989614,0,0,0,90.00000001 +347.12,50.30085681,-2.683253601,10500,0,199.9989614,0,0,0,90.00000001 +347.13,50.30085681,-2.683225576,10500,0,199.9998535,0,0,0,90.00000001 +347.14,50.30085681,-2.683197551,10500,0,200.0009685,0,0,0,90.00000001 +347.15,50.30085681,-2.683169525,10500,0,200.0009685,0,0,0,90.00000001 +347.16,50.30085681,-2.6831415,10500,0,199.9998535,0,0,0,90.00000001 +347.17,50.30085681,-2.683113475,10500,0,199.9989614,0,0,0,90.00000001 +347.18,50.30085681,-2.68308545,10500,0,199.9989614,0,0,0,90.00000001 +347.19,50.30085681,-2.683057425,10500,0,199.9998535,0,0,0,90.00000001 +347.2,50.30085681,-2.6830294,10500,0,200.0009685,0,0,0,90.00000001 +347.21,50.30085681,-2.683001374,10500,0,200.0009685,0,0,0,90.00000001 +347.22,50.30085681,-2.682973349,10500,0,199.9998535,0,0,0,90.00000001 +347.23,50.30085681,-2.682945324,10500,0,199.9991844,0,0,0,90.00000001 +347.24,50.30085681,-2.682917299,10500,0,199.9998535,0,0,0,90.00000001 +347.25,50.30085681,-2.682889274,10500,0,200.0009685,0,0,0,90.00000001 +347.26,50.30085681,-2.682861248,10500,0,200.0009685,0,0,0,90.00000001 +347.27,50.30085681,-2.682833223,10500,0,199.9998535,0,0,0,90.00000001 +347.28,50.30085681,-2.682805198,10500,0,199.9991844,0,0,0,90.00000001 +347.29,50.30085681,-2.682777173,10500,0,199.9998535,0,0,0,90.00000001 +347.3,50.30085681,-2.682749148,10500,0,200.0009685,0,0,0,90.00000001 +347.31,50.30085681,-2.682721122,10500,0,200.0009685,0,0,0,90.00000001 +347.32,50.30085681,-2.682693097,10500,0,199.9998535,0,0,0,90.00000001 +347.33,50.30085681,-2.682665072,10500,0,199.9991844,0,0,0,90.00000001 +347.34,50.30085681,-2.682637047,10500,0,199.9998535,0,0,0,90.00000001 +347.35,50.30085681,-2.682609022,10500,0,200.0009685,0,0,0,90.00000001 +347.36,50.30085681,-2.682580996,10500,0,200.0009685,0,0,0,90.00000001 +347.37,50.30085681,-2.682552971,10500,0,199.9998535,0,0,0,90.00000001 +347.38,50.30085681,-2.682524946,10500,0,199.9991844,0,0,0,90.00000001 +347.39,50.30085681,-2.682496921,10500,0,199.9998535,0,0,0,90.00000001 +347.4,50.30085681,-2.682468896,10500,0,200.0009685,0,0,0,90.00000001 +347.41,50.30085681,-2.68244087,10500,0,200.0009685,0,0,0,90.00000001 +347.42,50.30085681,-2.682412845,10500,0,199.9998535,0,0,0,90.00000001 +347.43,50.30085681,-2.68238482,10500,0,199.9991844,0,0,0,90.00000001 +347.44,50.30085681,-2.682356795,10500,0,199.9998535,0,0,0,90.00000001 +347.45,50.30085681,-2.68232877,10500,0,200.0009685,0,0,0,90.00000001 +347.46,50.30085681,-2.682300744,10500,0,200.0009685,0,0,0,90.00000001 +347.47,50.30085681,-2.682272719,10500,0,199.9998535,0,0,0,90.00000001 +347.48,50.30085681,-2.682244694,10500,0,199.9989614,0,0,0,90.00000001 +347.49,50.30085681,-2.682216669,10500,0,199.9989614,0,0,0,90.00000001 +347.5,50.30085681,-2.682188644,10500,0,199.9998535,0,0,0,90.00000001 +347.51,50.30085681,-2.682160619,10500,0,200.0009685,0,0,0,90.00000001 +347.52,50.30085681,-2.682132593,10500,0,200.0009685,0,0,0,90.00000001 +347.53,50.30085681,-2.682104568,10500,0,199.9998535,0,0,0,90.00000001 +347.54,50.30085681,-2.682076543,10500,0,199.9989614,0,0,0,90.00000001 +347.55,50.30085681,-2.682048518,10500,0,199.9989614,0,0,0,90.00000001 +347.56,50.30085681,-2.682020493,10500,0,199.9998535,0,0,0,90.00000001 +347.57,50.30085681,-2.681992468,10500,0,200.0009685,0,0,0,90.00000001 +347.58,50.30085681,-2.681964442,10500,0,200.0009685,0,0,0,90.00000001 +347.59,50.30085681,-2.681936417,10500,0,199.9998535,0,0,0,90.00000001 +347.6,50.30085681,-2.681908392,10500,0,199.9989614,0,0,0,90.00000001 +347.61,50.30085681,-2.681880367,10500,0,199.9987384,0,0,0,90.00000001 +347.62,50.30085681,-2.681852342,10500,0,199.9989614,0,0,0,90.00000001 +347.63,50.30085681,-2.681824317,10500,0,199.9998535,0,0,0,90.00000001 +347.64,50.30085681,-2.681796292,10500,0,200.0009685,0,0,0,90.00000001 +347.65,50.30085681,-2.681768266,10500,0,200.0009685,0,0,0,90.00000001 +347.66,50.30085681,-2.681740241,10500,0,199.9998535,0,0,0,90.00000001 +347.67,50.30085681,-2.681712216,10500,0,199.9989614,0,0,0,90.00000001 +347.68,50.30085681,-2.681684191,10500,0,199.9989614,0,0,0,90.00000001 +347.69,50.30085681,-2.681656166,10500,0,199.9998535,0,0,0,90.00000001 +347.7,50.30085681,-2.681628141,10500,0,200.0009685,0,0,0,90.00000001 +347.71,50.30085681,-2.681600115,10500,0,200.0009685,0,0,0,90.00000001 +347.72,50.30085681,-2.68157209,10500,0,199.9998535,0,0,0,90.00000001 +347.73,50.30085681,-2.681544065,10500,0,199.9989614,0,0,0,90.00000001 +347.74,50.30085681,-2.68151604,10500,0,199.9989614,0,0,0,90.00000001 +347.75,50.30085681,-2.681488015,10500,0,199.9998535,0,0,0,90.00000001 +347.76,50.30085681,-2.68145999,10500,0,200.0009685,0,0,0,90.00000001 +347.77,50.30085681,-2.681431964,10500,0,200.0009685,0,0,0,90.00000001 +347.78,50.30085681,-2.681403939,10500,0,199.9998535,0,0,0,90.00000001 +347.79,50.30085681,-2.681375914,10500,0,199.9989614,0,0,0,90.00000001 +347.8,50.30085681,-2.681347889,10500,0,199.9989614,0,0,0,90.00000001 +347.81,50.30085681,-2.681319864,10500,0,199.9998535,0,0,0,90.00000001 +347.82,50.30085681,-2.681291839,10500,0,200.0009685,0,0,0,90.00000001 +347.83,50.30085681,-2.681263813,10500,0,200.0009685,0,0,0,90.00000001 +347.84,50.30085681,-2.681235788,10500,0,199.9998535,0,0,0,90.00000001 +347.85,50.30085681,-2.681207763,10500,0,199.9991844,0,0,0,90.00000001 +347.86,50.30085681,-2.681179738,10500,0,199.9998535,0,0,0,90.00000001 +347.87,50.30085681,-2.681151713,10500,0,200.0009685,0,0,0,90.00000001 +347.88,50.30085681,-2.681123687,10500,0,200.0009685,0,0,0,90.00000001 +347.89,50.30085681,-2.681095662,10500,0,199.9998535,0,0,0,90.00000001 +347.9,50.30085681,-2.681067637,10500,0,199.9991844,0,0,0,90.00000001 +347.91,50.30085681,-2.681039612,10500,0,199.9998535,0,0,0,90.00000001 +347.92,50.30085681,-2.681011587,10500,0,200.0009685,0,0,0,90.00000001 +347.93,50.30085681,-2.680983561,10500,0,200.0009685,0,0,0,90.00000001 +347.94,50.30085681,-2.680955536,10500,0,199.9998535,0,0,0,90.00000001 +347.95,50.30085681,-2.680927511,10500,0,199.9989614,0,0,0,90.00000001 +347.96,50.30085681,-2.680899486,10500,0,199.9989614,0,0,0,90.00000001 +347.97,50.30085681,-2.680871461,10500,0,199.9998535,0,0,0,90.00000001 +347.98,50.30085681,-2.680843436,10500,0,200.0009685,0,0,0,90.00000001 +347.99,50.30085681,-2.68081541,10500,0,200.0009685,0,0,0,90.00000001 +348,50.30085681,-2.680787385,10500,0,199.9998535,0,0,0,90.00000001 +348.01,50.30085681,-2.68075936,10500,0,199.9991844,0,0,0,90.00000001 +348.02,50.30085681,-2.680731335,10500,0,199.9998535,0,0,0,90.00000001 +348.03,50.30085681,-2.68070331,10500,0,200.0009685,0,0,0,90.00000001 +348.04,50.30085681,-2.680675284,10500,0,200.0009685,0,0,0,90.00000001 +348.05,50.30085681,-2.680647259,10500,0,199.9998535,0,0,0,90.00000001 +348.06,50.30085681,-2.680619234,10500,0,199.9991844,0,0,0,90.00000001 +348.07,50.30085681,-2.680591209,10500,0,199.9998535,0,0,0,90.00000001 +348.08,50.30085681,-2.680563184,10500,0,200.0009685,0,0,0,90.00000001 +348.09,50.30085681,-2.680535158,10500,0,200.0009685,0,0,0,90.00000001 +348.1,50.30085681,-2.680507133,10500,0,199.9998535,0,0,0,90.00000001 +348.11,50.30085681,-2.680479108,10500,0,199.9991844,0,0,0,90.00000001 +348.12,50.30085681,-2.680451083,10500,0,199.9998535,0,0,0,90.00000001 +348.13,50.30085681,-2.680423058,10500,0,200.0009685,0,0,0,90.00000001 +348.14,50.30085681,-2.680395032,10500,0,200.0009685,0,0,0,90.00000001 +348.15,50.30085681,-2.680367007,10500,0,199.9998535,0,0,0,90.00000001 +348.16,50.30085681,-2.680338982,10500,0,199.9989614,0,0,0,90.00000001 +348.17,50.30085681,-2.680310957,10500,0,199.9987384,0,0,0,90.00000001 +348.18,50.30085681,-2.680282932,10500,0,199.9989614,0,0,0,90.00000001 +348.19,50.30085681,-2.680254907,10500,0,199.9998535,0,0,0,90.00000001 +348.2,50.30085681,-2.680226882,10500,0,200.0009685,0,0,0,90.00000001 +348.21,50.30085681,-2.680198856,10500,0,200.0009685,0,0,0,90.00000001 +348.22,50.30085681,-2.680170831,10500,0,199.9998535,0,0,0,90.00000001 +348.23,50.30085681,-2.680142806,10500,0,199.9989614,0,0,0,90.00000001 +348.24,50.30085681,-2.680114781,10500,0,199.9989614,0,0,0,90.00000001 +348.25,50.30085681,-2.680086756,10500,0,199.9998535,0,0,0,90.00000001 +348.26,50.30085681,-2.680058731,10500,0,200.0009685,0,0,0,90.00000001 +348.27,50.30085681,-2.680030705,10500,0,200.0009685,0,0,0,90.00000001 +348.28,50.30085681,-2.68000268,10500,0,199.9998535,0,0,0,90.00000001 +348.29,50.30085681,-2.679974655,10500,0,199.9989614,0,0,0,90.00000001 +348.3,50.30085681,-2.67994663,10500,0,199.9989614,0,0,0,90.00000001 +348.31,50.30085681,-2.679918605,10500,0,199.9998535,0,0,0,90.00000001 +348.32,50.30085681,-2.67989058,10500,0,200.0009685,0,0,0,90.00000001 +348.33,50.30085681,-2.679862554,10500,0,200.0009685,0,0,0,90.00000001 +348.34,50.30085681,-2.679834529,10500,0,199.9998535,0,0,0,90.00000001 +348.35,50.30085681,-2.679806504,10500,0,199.9989614,0,0,0,90.00000001 +348.36,50.30085681,-2.679778479,10500,0,199.9989614,0,0,0,90.00000001 +348.37,50.30085681,-2.679750454,10500,0,199.9998535,0,0,0,90.00000001 +348.38,50.30085681,-2.679722429,10500,0,200.0009685,0,0,0,90.00000001 +348.39,50.30085681,-2.679694403,10500,0,200.0009685,0,0,0,90.00000001 +348.4,50.30085681,-2.679666378,10500,0,199.9998535,0,0,0,90.00000001 +348.41,50.30085681,-2.679638353,10500,0,199.9989614,0,0,0,90.00000001 +348.42,50.30085681,-2.679610328,10500,0,199.9989614,0,0,0,90.00000001 +348.43,50.30085681,-2.679582303,10500,0,199.9998535,0,0,0,90.00000001 +348.44,50.30085681,-2.679554278,10500,0,200.0009685,0,0,0,90.00000001 +348.45,50.30085681,-2.679526252,10500,0,200.0009685,0,0,0,90.00000001 +348.46,50.30085681,-2.679498227,10500,0,199.9998535,0,0,0,90.00000001 +348.47,50.30085681,-2.679470202,10500,0,199.9989614,0,0,0,90.00000001 +348.48,50.30085681,-2.679442177,10500,0,199.9989614,0,0,0,90.00000001 +348.49,50.30085681,-2.679414152,10500,0,199.9998535,0,0,0,90.00000001 +348.5,50.30085681,-2.679386127,10500,0,200.0009685,0,0,0,90.00000001 +348.51,50.30085681,-2.679358101,10500,0,200.0009685,0,0,0,90.00000001 +348.52,50.30085681,-2.679330076,10500,0,199.9998535,0,0,0,90.00000001 +348.53,50.30085681,-2.679302051,10500,0,199.9991844,0,0,0,90.00000001 +348.54,50.30085681,-2.679274026,10500,0,199.9998535,0,0,0,90.00000001 +348.55,50.30085681,-2.679246001,10500,0,200.0009685,0,0,0,90.00000001 +348.56,50.30085681,-2.679217975,10500,0,200.0009685,0,0,0,90.00000001 +348.57,50.30085681,-2.67918995,10500,0,199.9998535,0,0,0,90.00000001 +348.58,50.30085681,-2.679161925,10500,0,199.9991844,0,0,0,90.00000001 +348.59,50.30085681,-2.6791339,10500,0,199.9998535,0,0,0,90.00000001 +348.6,50.30085681,-2.679105875,10500,0,200.0009685,0,0,0,90.00000001 +348.61,50.30085681,-2.679077849,10500,0,200.0009685,0,0,0,90.00000001 +348.62,50.30085681,-2.679049824,10500,0,199.9998535,0,0,0,90.00000001 +348.63,50.30085681,-2.679021799,10500,0,199.9991844,0,0,0,90.00000001 +348.64,50.30085681,-2.678993774,10500,0,199.9998535,0,0,0,90.00000001 +348.65,50.30085681,-2.678965749,10500,0,200.0009685,0,0,0,90.00000001 +348.66,50.30085681,-2.678937723,10500,0,200.0009685,0,0,0,90.00000001 +348.67,50.30085681,-2.678909698,10500,0,199.9998535,0,0,0,90.00000001 +348.68,50.30085681,-2.678881673,10500,0,199.9991844,0,0,0,90.00000001 +348.69,50.30085681,-2.678853648,10500,0,199.9998535,0,0,0,90.00000001 +348.7,50.30085681,-2.678825623,10500,0,200.0009685,0,0,0,90.00000001 +348.71,50.30085681,-2.678797597,10500,0,200.0009685,0,0,0,90.00000001 +348.72,50.30085681,-2.678769572,10500,0,199.9998535,0,0,0,90.00000001 +348.73,50.30085681,-2.678741547,10500,0,199.9989614,0,0,0,90.00000001 +348.74,50.30085681,-2.678713522,10500,0,199.9989614,0,0,0,90.00000001 +348.75,50.30085681,-2.678685497,10500,0,199.9998535,0,0,0,90.00000001 +348.76,50.30085681,-2.678657472,10500,0,200.0009685,0,0,0,90.00000001 +348.77,50.30085681,-2.678629446,10500,0,200.0009685,0,0,0,90.00000001 +348.78,50.30085681,-2.678601421,10500,0,199.9998535,0,0,0,90.00000001 +348.79,50.30085681,-2.678573396,10500,0,199.9989614,0,0,0,90.00000001 +348.8,50.30085681,-2.678545371,10500,0,199.9989614,0,0,0,90.00000001 +348.81,50.30085681,-2.678517346,10500,0,199.9998535,0,0,0,90.00000001 +348.82,50.30085681,-2.678489321,10500,0,200.0009685,0,0,0,90.00000001 +348.83,50.30085681,-2.678461295,10500,0,200.0009685,0,0,0,90.00000001 +348.84,50.30085681,-2.67843327,10500,0,199.9998535,0,0,0,90.00000001 +348.85,50.30085681,-2.678405245,10500,0,199.9989614,0,0,0,90.00000001 +348.86,50.30085681,-2.67837722,10500,0,199.9989614,0,0,0,90.00000001 +348.87,50.30085681,-2.678349195,10500,0,199.9998535,0,0,0,90.00000001 +348.88,50.30085681,-2.67832117,10500,0,200.0009685,0,0,0,90.00000001 +348.89,50.30085681,-2.678293144,10500,0,200.0009685,0,0,0,90.00000001 +348.9,50.30085681,-2.678265119,10500,0,199.9998535,0,0,0,90.00000001 +348.91,50.30085681,-2.678237094,10500,0,199.9989614,0,0,0,90.00000001 +348.92,50.30085681,-2.678209069,10500,0,199.9989614,0,0,0,90.00000001 +348.93,50.30085681,-2.678181044,10500,0,199.9998535,0,0,0,90.00000001 +348.94,50.30085681,-2.678153019,10500,0,200.0009685,0,0,0,90.00000001 +348.95,50.30085681,-2.678124993,10500,0,200.0009685,0,0,0,90.00000001 +348.96,50.30085681,-2.678096968,10500,0,199.9998535,0,0,0,90.00000001 +348.97,50.30085681,-2.678068943,10500,0,199.9989614,0,0,0,90.00000001 +348.98,50.30085681,-2.678040918,10500,0,199.9989614,0,0,0,90.00000001 +348.99,50.30085681,-2.678012893,10500,0,199.9998535,0,0,0,90.00000001 +349,50.30085681,-2.677984868,10500,0,200.0009685,0,0,0,90.00000001 +349.01,50.30085681,-2.677956842,10500,0,200.0009685,0,0,0,90.00000001 +349.02,50.30085681,-2.677928817,10500,0,199.9998535,0,0,0,90.00000001 +349.03,50.30085681,-2.677900792,10500,0,199.9989614,0,0,0,90.00000001 +349.04,50.30085681,-2.677872767,10500,0,199.9987384,0,0,0,90.00000001 +349.05,50.30085681,-2.677844742,10500,0,199.9989614,0,0,0,90.00000001 +349.06,50.30085681,-2.677816717,10500,0,199.9998535,0,0,0,90.00000001 +349.07,50.30085681,-2.677788692,10500,0,200.0009685,0,0,0,90.00000001 +349.08,50.30085681,-2.677760666,10500,0,200.0009685,0,0,0,90.00000001 +349.09,50.30085681,-2.677732641,10500,0,199.9998535,0,0,0,90.00000001 +349.1,50.30085681,-2.677704616,10500,0,199.9991844,0,0,0,90.00000001 +349.11,50.30085681,-2.677676591,10500,0,199.9998535,0,0,0,90.00000001 +349.12,50.30085681,-2.677648566,10500,0,200.0009685,0,0,0,90.00000001 +349.13,50.30085681,-2.67762054,10500,0,200.0009685,0,0,0,90.00000001 +349.14,50.30085681,-2.677592515,10500,0,199.9998535,0,0,0,90.00000001 +349.15,50.30085681,-2.67756449,10500,0,199.9991844,0,0,0,90.00000001 +349.16,50.30085681,-2.677536465,10500,0,199.9998535,0,0,0,90.00000001 +349.17,50.30085681,-2.67750844,10500,0,200.0009685,0,0,0,90.00000001 +349.18,50.30085681,-2.677480414,10500,0,200.0009685,0,0,0,90.00000001 +349.19,50.30085681,-2.677452389,10500,0,199.9998535,0,0,0,90.00000001 +349.2,50.30085681,-2.677424364,10500,0,199.9991844,0,0,0,90.00000001 +349.21,50.30085681,-2.677396339,10500,0,199.9998535,0,0,0,90.00000001 +349.22,50.30085681,-2.677368314,10500,0,200.0009685,0,0,0,90.00000001 +349.23,50.30085681,-2.677340288,10500,0,200.0009685,0,0,0,90.00000001 +349.24,50.30085681,-2.677312263,10500,0,199.9998535,0,0,0,90.00000001 +349.25,50.30085681,-2.677284238,10500,0,199.9991844,0,0,0,90.00000001 +349.26,50.30085681,-2.677256213,10500,0,199.9998535,0,0,0,90.00000001 +349.27,50.30085681,-2.677228188,10500,0,200.0009685,0,0,0,90.00000001 +349.28,50.30085681,-2.677200162,10500,0,200.0009685,0,0,0,90.00000001 +349.29,50.30085681,-2.677172137,10500,0,199.9998535,0,0,0,90.00000001 +349.3,50.30085681,-2.677144112,10500,0,199.9991844,0,0,0,90.00000001 +349.31,50.30085681,-2.677116087,10500,0,199.9998535,0,0,0,90.00000001 +349.32,50.30085681,-2.677088062,10500,0,200.0009685,0,0,0,90.00000001 +349.33,50.30085681,-2.677060036,10500,0,200.0009685,0,0,0,90.00000001 +349.34,50.30085681,-2.677032011,10500,0,199.9998535,0,0,0,90.00000001 +349.35,50.30085681,-2.677003986,10500,0,199.9989614,0,0,0,90.00000001 +349.36,50.30085681,-2.676975961,10500,0,199.9989614,0,0,0,90.00000001 +349.37,50.30085681,-2.676947936,10500,0,199.9998535,0,0,0,90.00000001 +349.38,50.30085681,-2.676919911,10500,0,200.0009685,0,0,0,90.00000001 +349.39,50.30085681,-2.676891885,10500,0,200.0009685,0,0,0,90.00000001 +349.4,50.30085681,-2.67686386,10500,0,199.9998535,0,0,0,90.00000001 +349.41,50.30085681,-2.676835835,10500,0,199.9989614,0,0,0,90.00000001 +349.42,50.30085681,-2.67680781,10500,0,199.9989614,0,0,0,90.00000001 +349.43,50.30085681,-2.676779785,10500,0,199.9998535,0,0,0,90.00000001 +349.44,50.30085681,-2.67675176,10500,0,200.0009685,0,0,0,90.00000001 +349.45,50.30085681,-2.676723734,10500,0,200.0009685,0,0,0,90.00000001 +349.46,50.30085681,-2.676695709,10500,0,199.9998535,0,0,0,90.00000001 +349.47,50.30085681,-2.676667684,10500,0,199.9989614,0,0,0,90.00000001 +349.48,50.30085681,-2.676639659,10500,0,199.9989614,0,0,0,90.00000001 +349.49,50.30085681,-2.676611634,10500,0,199.9998535,0,0,0,90.00000001 +349.5,50.30085681,-2.676583609,10500,0,200.0009685,0,0,0,90.00000001 +349.51,50.30085681,-2.676555583,10500,0,200.0009685,0,0,0,90.00000001 +349.52,50.30085681,-2.676527558,10500,0,199.9998535,0,0,0,90.00000001 +349.53,50.30085681,-2.676499533,10500,0,199.9989614,0,0,0,90.00000001 +349.54,50.30085681,-2.676471508,10500,0,199.9989614,0,0,0,90.00000001 +349.55,50.30085681,-2.676443483,10500,0,199.9998535,0,0,0,90.00000001 +349.56,50.30085681,-2.676415458,10500,0,200.0009685,0,0,0,90.00000001 +349.57,50.30085681,-2.676387432,10500,0,200.0009685,0,0,0,90.00000001 +349.58,50.30085681,-2.676359407,10500,0,199.9998535,0,0,0,90.00000001 +349.59,50.30085681,-2.676331382,10500,0,199.9989614,0,0,0,90.00000001 +349.6,50.30085681,-2.676303357,10500,0,199.9987384,0,0,0,90.00000001 +349.61,50.30085681,-2.676275332,10500,0,199.9989614,0,0,0,90.00000001 +349.62,50.30085681,-2.676247307,10500,0,199.9998535,0,0,0,90.00000001 +349.63,50.30085681,-2.676219282,10500,0,200.0009685,0,0,0,90.00000001 +349.64,50.30085681,-2.676191256,10500,0,200.0009685,0,0,0,90.00000001 +349.65,50.30085681,-2.676163231,10500,0,199.9998535,0,0,0,90.00000001 +349.66,50.30085681,-2.676135206,10500,0,199.9989614,0,0,0,90.00000001 +349.67,50.30085681,-2.676107181,10500,0,199.9989614,0,0,0,90.00000001 +349.68,50.30085681,-2.676079156,10500,0,199.9998535,0,0,0,90.00000001 +349.69,50.30085681,-2.676051131,10500,0,200.0009685,0,0,0,90.00000001 +349.7,50.30085681,-2.676023105,10500,0,200.0009685,0,0,0,90.00000001 +349.71,50.30085681,-2.67599508,10500,0,199.9998535,0,0,0,90.00000001 +349.72,50.30085681,-2.675967055,10500,0,199.9991844,0,0,0,90.00000001 +349.73,50.30085681,-2.67593903,10500,0,199.9998535,0,0,0,90.00000001 +349.74,50.30085681,-2.675911005,10500,0,200.0009685,0,0,0,90.00000001 +349.75,50.30085681,-2.675882979,10500,0,200.0009685,0,0,0,90.00000001 +349.76,50.30085681,-2.675854954,10500,0,199.9998535,0,0,0,90.00000001 +349.77,50.30085681,-2.675826929,10500,0,199.9991844,0,0,0,90.00000001 +349.78,50.30085681,-2.675798904,10500,0,199.9998535,0,0,0,90.00000001 +349.79,50.30085681,-2.675770879,10500,0,200.0009685,0,0,0,90.00000001 +349.8,50.30085681,-2.675742853,10500,0,200.0009685,0,0,0,90.00000001 +349.81,50.30085681,-2.675714828,10500,0,199.9998535,0,0,0,90.00000001 +349.82,50.30085681,-2.675686803,10500,0,199.9991844,0,0,0,90.00000001 +349.83,50.30085681,-2.675658778,10500,0,199.9998535,0,0,0,90.00000001 +349.84,50.30085681,-2.675630753,10500,0,200.0009685,0,0,0,90.00000001 +349.85,50.30085681,-2.675602727,10500,0,200.0009685,0,0,0,90.00000001 +349.86,50.30085681,-2.675574702,10500,0,199.9998535,0,0,0,90.00000001 +349.87,50.30085681,-2.675546677,10500,0,199.9991844,0,0,0,90.00000001 +349.88,50.30085681,-2.675518652,10500,0,199.9998535,0,0,0,90.00000001 +349.89,50.30085681,-2.675490627,10500,0,200.0009685,0,0,0,90.00000001 +349.9,50.30085681,-2.675462601,10500,0,200.0009685,0,0,0,90.00000001 +349.91,50.30085681,-2.675434576,10500,0,199.9998535,0,0,0,90.00000001 +349.92,50.30085681,-2.675406551,10500,0,199.9991844,0,0,0,90.00000001 +349.93,50.30085681,-2.675378526,10500,0,199.9998535,0,0,0,90.00000001 +349.94,50.30085681,-2.675350501,10500,0,200.0009685,0,0,0,90.00000001 +349.95,50.30085681,-2.675322475,10500,0,200.0009685,0,0,0,90.00000001 +349.96,50.30085681,-2.67529445,10500,0,199.9998535,0,0,0,90.00000001 +349.97,50.30085681,-2.675266425,10500,0,199.9989614,0,0,0,90.00000001 +349.98,50.30085681,-2.6752384,10500,0,199.9989614,0,0,0,90.00000001 +349.99,50.30085681,-2.675210375,10500,0,199.9998535,0,0,0,90.00000001 +350,50.30085681,-2.67518235,10500,0,200.0009685,0,0,0,90.00000001 +350.01,50.30085681,-2.675154324,10500,0,200.0009685,0,0,0,90.00000001 +350.02,50.30085681,-2.675126299,10500,0,199.9998535,0,0,0,90.00000001 +350.03,50.30085681,-2.675098274,10500,0,199.9989614,0,0,0,90.00000001 +350.04,50.30085681,-2.675070249,10500,0,199.9989614,0,0,0,90.00000001 +350.05,50.30085681,-2.675042224,10500,0,199.9998535,0,0,0,90.00000001 +350.06,50.30085681,-2.675014199,10500,0,200.0009685,0,0,0,90.00000001 +350.07,50.30085681,-2.674986173,10500,0,200.0009685,0,0,0,90.00000001 +350.08,50.30085681,-2.674958148,10500,0,199.9998535,0,0,0,90.00000001 +350.09,50.30085681,-2.674930123,10500,0,199.9989614,0,0,0,90.00000001 +350.1,50.30085681,-2.674902098,10500,0,199.9989614,0,0,0,90.00000001 +350.11,50.30085681,-2.674874073,10500,0,199.9998535,0,0,0,90.00000001 +350.12,50.30085681,-2.674846048,10500,0,200.0009685,0,0,0,90.00000001 +350.13,50.30085681,-2.674818022,10500,0,200.0009685,0,0,0,90.00000001 +350.14,50.30085681,-2.674789997,10500,0,199.9998535,0,0,0,90.00000001 +350.15,50.30085681,-2.674761972,10500,0,199.9989614,0,0,0,90.00000001 +350.16,50.30085681,-2.674733947,10500,0,199.9987384,0,0,0,90.00000001 +350.17,50.30085681,-2.674705922,10500,0,199.9989614,0,0,0,90.00000001 +350.18,50.30085681,-2.674677897,10500,0,199.9998535,0,0,0,90.00000001 +350.19,50.30085681,-2.674649872,10500,0,200.0009685,0,0,0,90.00000001 +350.2,50.30085681,-2.674621846,10500,0,200.0009685,0,0,0,90.00000001 +350.21,50.30085681,-2.674593821,10500,0,199.9998535,0,0,0,90.00000001 +350.22,50.30085681,-2.674565796,10500,0,199.9989614,0,0,0,90.00000001 +350.23,50.30085681,-2.674537771,10500,0,199.9989614,0,0,0,90.00000001 +350.24,50.30085681,-2.674509746,10500,0,199.9998535,0,0,0,90.00000001 +350.25,50.30085681,-2.674481721,10500,0,200.0009685,0,0,0,90.00000001 +350.26,50.30085681,-2.674453695,10500,0,200.0009685,0,0,0,90.00000001 +350.27,50.30085681,-2.67442567,10500,0,199.9998535,0,0,0,90.00000001 +350.28,50.30085681,-2.674397645,10500,0,199.9989614,0,0,0,90.00000001 +350.29,50.30085681,-2.67436962,10500,0,199.9989614,0,0,0,90.00000001 +350.3,50.30085681,-2.674341595,10500,0,199.9998535,0,0,0,90.00000001 +350.31,50.30085681,-2.67431357,10500,0,200.0009685,0,0,0,90.00000001 +350.32,50.30085681,-2.674285544,10500,0,200.0009685,0,0,0,90.00000001 +350.33,50.30085681,-2.674257519,10500,0,199.9998535,0,0,0,90.00000001 +350.34,50.30085681,-2.674229494,10500,0,199.9989614,0,0,0,90.00000001 +350.35,50.30085681,-2.674201469,10500,0,199.9989614,0,0,0,90.00000001 +350.36,50.30085681,-2.674173444,10500,0,199.9998535,0,0,0,90.00000001 +350.37,50.30085681,-2.674145419,10500,0,200.0009685,0,0,0,90.00000001 +350.38,50.30085681,-2.674117393,10500,0,200.0009685,0,0,0,90.00000001 +350.39,50.30085681,-2.674089368,10500,0,199.9998535,0,0,0,90.00000001 +350.4,50.30085681,-2.674061343,10500,0,199.9991844,0,0,0,90.00000001 +350.41,50.30085681,-2.674033318,10500,0,199.9998535,0,0,0,90.00000001 +350.42,50.30085681,-2.674005293,10500,0,200.0009685,0,0,0,90.00000001 +350.43,50.30085681,-2.673977267,10500,0,200.0009685,0,0,0,90.00000001 +350.44,50.30085681,-2.673949242,10500,0,199.9998535,0,0,0,90.00000001 +350.45,50.30085681,-2.673921217,10500,0,199.9991844,0,0,0,90.00000001 +350.46,50.30085681,-2.673893192,10500,0,199.9998535,0,0,0,90.00000001 +350.47,50.30085681,-2.673865167,10500,0,200.0009685,0,0,0,90.00000001 +350.48,50.30085681,-2.673837141,10500,0,200.0009685,0,0,0,90.00000001 +350.49,50.30085681,-2.673809116,10500,0,199.9998535,0,0,0,90.00000001 +350.5,50.30085681,-2.673781091,10500,0,199.9991844,0,0,0,90.00000001 +350.51,50.30085681,-2.673753066,10500,0,199.9998535,0,0,0,90.00000001 +350.52,50.30085681,-2.673725041,10500,0,200.0009685,0,0,0,90.00000001 +350.53,50.30085681,-2.673697015,10500,0,200.0009685,0,0,0,90.00000001 +350.54,50.30085681,-2.67366899,10500,0,199.9998535,0,0,0,90.00000001 +350.55,50.30085681,-2.673640965,10500,0,199.9991844,0,0,0,90.00000001 +350.56,50.30085681,-2.67361294,10500,0,199.9998535,0,0,0,90.00000001 +350.57,50.30085681,-2.673584915,10500,0,200.0009685,0,0,0,90.00000001 +350.58,50.30085681,-2.673556889,10500,0,200.0009685,0,0,0,90.00000001 +350.59,50.30085681,-2.673528864,10500,0,199.9998535,0,0,0,90.00000001 +350.6,50.30085681,-2.673500839,10500,0,199.9991844,0,0,0,90.00000001 +350.61,50.30085681,-2.673472814,10500,0,199.9998535,0,0,0,90.00000001 +350.62,50.30085681,-2.673444789,10500,0,200.0009685,0,0,0,90.00000001 +350.63,50.30085681,-2.673416763,10500,0,200.0009685,0,0,0,90.00000001 +350.64,50.30085681,-2.673388738,10500,0,199.9998535,0,0,0,90.00000001 +350.65,50.30085681,-2.673360713,10500,0,199.9989614,0,0,0,90.00000001 +350.66,50.30085681,-2.673332688,10500,0,199.9989614,0,0,0,90.00000001 +350.67,50.30085681,-2.673304663,10500,0,199.9998535,0,0,0,90.00000001 +350.68,50.30085681,-2.673276638,10500,0,200.0009685,0,0,0,90.00000001 +350.69,50.30085681,-2.673248612,10500,0,200.0009685,0,0,0,90.00000001 +350.7,50.30085681,-2.673220587,10500,0,199.9998535,0,0,0,90.00000001 +350.71,50.30085681,-2.673192562,10500,0,199.9989614,0,0,0,90.00000001 +350.72,50.30085681,-2.673164537,10500,0,199.9989614,0,0,0,90.00000001 +350.73,50.30085681,-2.673136512,10500,0,199.9998535,0,0,0,90.00000001 +350.74,50.30085681,-2.673108487,10500,0,200.0009685,0,0,0,90.00000001 +350.75,50.30085681,-2.673080461,10500,0,200.0009685,0,0,0,90.00000001 +350.76,50.30085681,-2.673052436,10500,0,199.9998535,0,0,0,90.00000001 +350.77,50.30085681,-2.673024411,10500,0,199.9989614,0,0,0,90.00000001 +350.78,50.30085681,-2.672996386,10500,0,199.9987384,0,0,0,90.00000001 +350.79,50.30085681,-2.672968361,10500,0,199.9989614,0,0,0,90.00000001 +350.8,50.30085681,-2.672940336,10500,0,199.9998535,0,0,0,90.00000001 +350.81,50.30085681,-2.672912311,10500,0,200.0009685,0,0,0,90.00000001 +350.82,50.30085681,-2.672884285,10500,0,200.0009685,0,0,0,90.00000001 +350.83,50.30085681,-2.67285626,10500,0,199.9998535,0,0,0,90.00000001 +350.84,50.30085681,-2.672828235,10500,0,199.9989614,0,0,0,90.00000001 +350.85,50.30085681,-2.67280021,10500,0,199.9989614,0,0,0,90.00000001 +350.86,50.30085681,-2.672772185,10500,0,199.9998535,0,0,0,90.00000001 +350.87,50.30085681,-2.67274416,10500,0,200.0009685,0,0,0,90.00000001 +350.88,50.30085681,-2.672716134,10500,0,200.0009685,0,0,0,90.00000001 +350.89,50.30085681,-2.672688109,10500,0,199.9998535,0,0,0,90.00000001 +350.9,50.30085681,-2.672660084,10500,0,199.9989614,0,0,0,90.00000001 +350.91,50.30085681,-2.672632059,10500,0,199.9989614,0,0,0,90.00000001 +350.92,50.30085681,-2.672604034,10500,0,199.9998535,0,0,0,90.00000001 +350.93,50.30085681,-2.672576009,10500,0,200.0009685,0,0,0,90.00000001 +350.94,50.30085681,-2.672547983,10500,0,200.0009685,0,0,0,90.00000001 +350.95,50.30085681,-2.672519958,10500,0,199.9998535,0,0,0,90.00000001 +350.96,50.30085681,-2.672491933,10500,0,199.9989614,0,0,0,90.00000001 +350.97,50.30085681,-2.672463908,10500,0,199.9989614,0,0,0,90.00000001 +350.98,50.30085681,-2.672435883,10500,0,199.9998535,0,0,0,90.00000001 +350.99,50.30085681,-2.672407858,10500,0,200.0009685,0,0,0,90.00000001 +351,50.30085681,-2.672379832,10500,0,200.0009685,0,0,0,90.00000001 +351.01,50.30085681,-2.672351807,10500,0,199.9998535,0,0,0,90.00000001 +351.02,50.30085681,-2.672323782,10500,0,199.9991844,0,0,0,90.00000001 +351.03,50.30085681,-2.672295757,10500,0,199.9998535,0,0,0,90.00000001 +351.04,50.30085681,-2.672267732,10500,0,200.0009685,0,0,0,90.00000001 +351.05,50.30085681,-2.672239706,10500,0,200.0009685,0,0,0,90.00000001 +351.06,50.30085681,-2.672211681,10500,0,199.9998535,0,0,0,90.00000001 +351.07,50.30085681,-2.672183656,10500,0,199.9991844,0,0,0,90.00000001 +351.08,50.30085681,-2.672155631,10500,0,199.9998535,0,0,0,90.00000001 +351.09,50.30085681,-2.672127606,10500,0,200.0009685,0,0,0,90.00000001 +351.1,50.30085681,-2.67209958,10500,0,200.0009685,0,0,0,90.00000001 +351.11,50.30085681,-2.672071555,10500,0,199.9998535,0,0,0,90.00000001 +351.12,50.30085681,-2.67204353,10500,0,199.9991844,0,0,0,90.00000001 +351.13,50.30085681,-2.672015505,10500,0,199.9998535,0,0,0,90.00000001 +351.14,50.30085681,-2.67198748,10500,0,200.0009685,0,0,0,90.00000001 +351.15,50.30085681,-2.671959454,10500,0,200.0009685,0,0,0,90.00000001 +351.16,50.30085681,-2.671931429,10500,0,199.9998535,0,0,0,90.00000001 +351.17,50.30085681,-2.671903404,10500,0,199.9991844,0,0,0,90.00000001 +351.18,50.30085681,-2.671875379,10500,0,199.9998535,0,0,0,90.00000001 +351.19,50.30085681,-2.671847354,10500,0,200.0009685,0,0,0,90.00000001 +351.2,50.30085681,-2.671819328,10500,0,200.0009685,0,0,0,90.00000001 +351.21,50.30085681,-2.671791303,10500,0,199.9998535,0,0,0,90.00000001 +351.22,50.30085681,-2.671763278,10500,0,199.9991844,0,0,0,90.00000001 +351.23,50.30085681,-2.671735253,10500,0,199.9998535,0,0,0,90.00000001 +351.24,50.30085681,-2.671707228,10500,0,200.0009685,0,0,0,90.00000001 +351.25,50.30085681,-2.671679202,10500,0,200.0009685,0,0,0,90.00000001 +351.26,50.30085681,-2.671651177,10500,0,199.9998535,0,0,0,90.00000001 +351.27,50.30085681,-2.671623152,10500,0,199.9989614,0,0,0,90.00000001 +351.28,50.30085681,-2.671595127,10500,0,199.9989614,0,0,0,90.00000001 +351.29,50.30085681,-2.671567102,10500,0,199.9998535,0,0,0,90.00000001 +351.3,50.30085681,-2.671539077,10500,0,200.0009685,0,0,0,90.00000001 +351.31,50.30085681,-2.671511051,10500,0,200.0009685,0,0,0,90.00000001 +351.32,50.30085681,-2.671483026,10500,0,199.9998535,0,0,0,90.00000001 +351.33,50.30085681,-2.671455001,10500,0,199.9989614,0,0,0,90.00000001 +351.34,50.30085681,-2.671426976,10500,0,199.9987384,0,0,0,90.00000001 +351.35,50.30085681,-2.671398951,10500,0,199.9989614,0,0,0,90.00000001 +351.36,50.30085681,-2.671370926,10500,0,199.9998535,0,0,0,90.00000001 +351.37,50.30085681,-2.671342901,10500,0,200.0009685,0,0,0,90.00000001 +351.38,50.30085681,-2.671314875,10500,0,200.0009685,0,0,0,90.00000001 +351.39,50.30085681,-2.67128685,10500,0,199.9998535,0,0,0,90.00000001 +351.4,50.30085681,-2.671258825,10500,0,199.9989614,0,0,0,90.00000001 +351.41,50.30085681,-2.6712308,10500,0,199.9989614,0,0,0,90.00000001 +351.42,50.30085681,-2.671202775,10500,0,199.9998535,0,0,0,90.00000001 +351.43,50.30085681,-2.67117475,10500,0,200.0009685,0,0,0,90.00000001 +351.44,50.30085681,-2.671146724,10500,0,200.0009685,0,0,0,90.00000001 +351.45,50.30085681,-2.671118699,10500,0,199.9998535,0,0,0,90.00000001 +351.46,50.30085681,-2.671090674,10500,0,199.9989614,0,0,0,90.00000001 +351.47,50.30085681,-2.671062649,10500,0,199.9989614,0,0,0,90.00000001 +351.48,50.30085681,-2.671034624,10500,0,199.9998535,0,0,0,90.00000001 +351.49,50.30085681,-2.671006599,10500,0,200.0009685,0,0,0,90.00000001 +351.5,50.30085681,-2.670978573,10500,0,200.0009685,0,0,0,90.00000001 +351.51,50.30085681,-2.670950548,10500,0,199.9998535,0,0,0,90.00000001 +351.52,50.30085681,-2.670922523,10500,0,199.9989614,0,0,0,90.00000001 +351.53,50.30085681,-2.670894498,10500,0,199.9989614,0,0,0,90.00000001 +351.54,50.30085681,-2.670866473,10500,0,199.9998535,0,0,0,90.00000001 +351.55,50.30085681,-2.670838448,10500,0,200.0009685,0,0,0,90.00000001 +351.56,50.30085681,-2.670810422,10500,0,200.0009685,0,0,0,90.00000001 +351.57,50.30085681,-2.670782397,10500,0,199.9998535,0,0,0,90.00000001 +351.58,50.30085681,-2.670754372,10500,0,199.9989614,0,0,0,90.00000001 +351.59,50.30085681,-2.670726347,10500,0,199.9989614,0,0,0,90.00000001 +351.6,50.30085681,-2.670698322,10500,0,199.9998535,0,0,0,90.00000001 +351.61,50.30085681,-2.670670297,10500,0,200.0009685,0,0,0,90.00000001 +351.62,50.30085681,-2.670642271,10500,0,200.0009685,0,0,0,90.00000001 +351.63,50.30085681,-2.670614246,10500,0,199.9998535,0,0,0,90.00000001 +351.64,50.30085681,-2.670586221,10500,0,199.9991844,0,0,0,90.00000001 +351.65,50.30085681,-2.670558196,10500,0,199.9998535,0,0,0,90.00000001 +351.66,50.30085681,-2.670530171,10500,0,200.0009685,0,0,0,90.00000001 +351.67,50.30085681,-2.670502145,10500,0,200.0009685,0,0,0,90.00000001 +351.68,50.30085681,-2.67047412,10500,0,199.9998535,0,0,0,90.00000001 +351.69,50.30085681,-2.670446095,10500,0,199.9991844,0,0,0,90.00000001 +351.7,50.30085681,-2.67041807,10500,0,199.9998535,0,0,0,90.00000001 +351.71,50.30085681,-2.670390045,10500,0,200.0009685,0,0,0,90.00000001 +351.72,50.30085681,-2.670362019,10500,0,200.0009685,0,0,0,90.00000001 +351.73,50.30085681,-2.670333994,10500,0,199.9998535,0,0,0,90.00000001 +351.74,50.30085681,-2.670305969,10500,0,199.9991844,0,0,0,90.00000001 +351.75,50.30085681,-2.670277944,10500,0,199.9998535,0,0,0,90.00000001 +351.76,50.30085681,-2.670249919,10500,0,200.0009685,0,0,0,90.00000001 +351.77,50.30085681,-2.670221893,10500,0,200.0009685,0,0,0,90.00000001 +351.78,50.30085681,-2.670193868,10500,0,199.9998535,0,0,0,90.00000001 +351.79,50.30085681,-2.670165843,10500,0,199.9991844,0,0,0,90.00000001 +351.8,50.30085681,-2.670137818,10500,0,199.9998535,0,0,0,90.00000001 +351.81,50.30085681,-2.670109793,10500,0,200.0009685,0,0,0,90.00000001 +351.82,50.30085681,-2.670081767,10500,0,200.0009685,0,0,0,90.00000001 +351.83,50.30085681,-2.670053742,10500,0,199.9998535,0,0,0,90.00000001 +351.84,50.30085681,-2.670025717,10500,0,199.9991844,0,0,0,90.00000001 +351.85,50.30085681,-2.669997692,10500,0,199.9998535,0,0,0,90.00000001 +351.86,50.30085681,-2.669969667,10500,0,200.0009685,0,0,0,90.00000001 +351.87,50.30085681,-2.669941641,10500,0,200.0009685,0,0,0,90.00000001 +351.88,50.30085681,-2.669913616,10500,0,199.9998535,0,0,0,90.00000001 +351.89,50.30085681,-2.669885591,10500,0,199.9989614,0,0,0,90.00000001 +351.9,50.30085681,-2.669857566,10500,0,199.9987384,0,0,0,90.00000001 +351.91,50.30085681,-2.669829541,10500,0,199.9989614,0,0,0,90.00000001 +351.92,50.30085681,-2.669801516,10500,0,199.9998535,0,0,0,90.00000001 +351.93,50.30085681,-2.669773491,10500,0,200.0009685,0,0,0,90.00000001 +351.94,50.30085681,-2.669745465,10500,0,200.0009685,0,0,0,90.00000001 +351.95,50.30085681,-2.66971744,10500,0,199.9998535,0,0,0,90.00000001 +351.96,50.30085681,-2.669689415,10500,0,199.9989614,0,0,0,90.00000001 +351.97,50.30085681,-2.66966139,10500,0,199.9989614,0,0,0,90.00000001 +351.98,50.30085681,-2.669633365,10500,0,199.9998535,0,0,0,90.00000001 +351.99,50.30085681,-2.66960534,10500,0,200.0009685,0,0,0,90.00000001 +352,50.30085681,-2.669577314,10500,0,200.0009685,0,0,0,90.00000001 +352.01,50.30085681,-2.669549289,10500,0,199.9998535,0,0,0,90.00000001 +352.02,50.30085681,-2.669521264,10500,0,199.9989614,0,0,0,90.00000001 +352.03,50.30085681,-2.669493239,10500,0,199.9989614,0,0,0,90.00000001 +352.04,50.30085681,-2.669465214,10500,0,199.9998535,0,0,0,90.00000001 +352.05,50.30085681,-2.669437189,10500,0,200.0009685,0,0,0,90.00000001 +352.06,50.30085681,-2.669409163,10500,0,200.0009685,0,0,0,90.00000001 +352.07,50.30085681,-2.669381138,10500,0,199.9998535,0,0,0,90.00000001 +352.08,50.30085681,-2.669353113,10500,0,199.9989614,0,0,0,90.00000001 +352.09,50.30085681,-2.669325088,10500,0,199.9989614,0,0,0,90.00000001 +352.1,50.30085681,-2.669297063,10500,0,199.9998535,0,0,0,90.00000001 +352.11,50.30085681,-2.669269038,10500,0,200.0009685,0,0,0,90.00000001 +352.12,50.30085681,-2.669241012,10500,0,200.0009685,0,0,0,90.00000001 +352.13,50.30085681,-2.669212987,10500,0,199.9998535,0,0,0,90.00000001 +352.14,50.30085681,-2.669184962,10500,0,199.9989614,0,0,0,90.00000001 +352.15,50.30085681,-2.669156937,10500,0,199.9989614,0,0,0,90.00000001 +352.16,50.30085681,-2.669128912,10500,0,199.9998535,0,0,0,90.00000001 +352.17,50.30085681,-2.669100887,10500,0,200.0009685,0,0,0,90.00000001 +352.18,50.30085681,-2.669072861,10500,0,200.0009685,0,0,0,90.00000001 +352.19,50.30085681,-2.669044836,10500,0,199.9998535,0,0,0,90.00000001 +352.2,50.30085681,-2.669016811,10500,0,199.9989614,0,0,0,90.00000001 +352.21,50.30085681,-2.668988786,10500,0,199.9989614,0,0,0,90.00000001 +352.22,50.30085681,-2.668960761,10500,0,199.9998535,0,0,0,90.00000001 +352.23,50.30085681,-2.668932736,10500,0,200.0009685,0,0,0,90.00000001 +352.24,50.30085681,-2.66890471,10500,0,200.0009685,0,0,0,90.00000001 +352.25,50.30085681,-2.668876685,10500,0,199.9998535,0,0,0,90.00000001 +352.26,50.30085681,-2.66884866,10500,0,199.9991844,0,0,0,90.00000001 +352.27,50.30085681,-2.668820635,10500,0,199.9998535,0,0,0,90.00000001 +352.28,50.30085681,-2.66879261,10500,0,200.0009685,0,0,0,90.00000001 +352.29,50.30085681,-2.668764584,10500,0,200.0009685,0,0,0,90.00000001 +352.3,50.30085681,-2.668736559,10500,0,199.9998535,0,0,0,90.00000001 +352.31,50.30085681,-2.668708534,10500,0,199.9991844,0,0,0,90.00000001 +352.32,50.30085681,-2.668680509,10500,0,199.9998535,0,0,0,90.00000001 +352.33,50.30085681,-2.668652484,10500,0,200.0009685,0,0,0,90.00000001 +352.34,50.30085681,-2.668624458,10500,0,200.0009685,0,0,0,90.00000001 +352.35,50.30085681,-2.668596433,10500,0,199.9998535,0,0,0,90.00000001 +352.36,50.30085681,-2.668568408,10500,0,199.9991844,0,0,0,90.00000001 +352.37,50.30085681,-2.668540383,10500,0,199.9998535,0,0,0,90.00000001 +352.38,50.30085681,-2.668512358,10500,0,200.0009685,0,0,0,90.00000001 +352.39,50.30085681,-2.668484332,10500,0,200.0009685,0,0,0,90.00000001 +352.4,50.30085681,-2.668456307,10500,0,199.9998535,0,0,0,90.00000001 +352.41,50.30085681,-2.668428282,10500,0,199.9989614,0,0,0,90.00000001 +352.42,50.30085681,-2.668400257,10500,0,199.9989614,0,0,0,90.00000001 +352.43,50.30085681,-2.668372232,10500,0,199.9998535,0,0,0,90.00000001 +352.44,50.30085681,-2.668344207,10500,0,200.0009685,0,0,0,90.00000001 +352.45,50.30085681,-2.668316181,10500,0,200.0009685,0,0,0,90.00000001 +352.46,50.30085681,-2.668288156,10500,0,199.9998535,0,0,0,90.00000001 +352.47,50.30085681,-2.668260131,10500,0,199.9991844,0,0,0,90.00000001 +352.48,50.30085681,-2.668232106,10500,0,199.9998535,0,0,0,90.00000001 +352.49,50.30085681,-2.668204081,10500,0,200.0009685,0,0,0,90.00000001 +352.5,50.30085681,-2.668176055,10500,0,200.0009685,0,0,0,90.00000001 +352.51,50.30085681,-2.66814803,10500,0,199.9998535,0,0,0,90.00000001 +352.52,50.30085681,-2.668120005,10500,0,199.9989614,0,0,0,90.00000001 +352.53,50.30085681,-2.66809198,10500,0,199.9989614,0,0,0,90.00000001 +352.54,50.30085681,-2.668063955,10500,0,199.9998535,0,0,0,90.00000001 +352.55,50.30085681,-2.66803593,10500,0,200.0009685,0,0,0,90.00000001 +352.56,50.30085681,-2.668007904,10500,0,200.0009685,0,0,0,90.00000001 +352.57,50.30085681,-2.667979879,10500,0,199.9998535,0,0,0,90.00000001 +352.58,50.30085681,-2.667951854,10500,0,199.9989614,0,0,0,90.00000001 +352.59,50.30085681,-2.667923829,10500,0,199.9989614,0,0,0,90.00000001 +352.6,50.30085681,-2.667895804,10500,0,199.9998535,0,0,0,90.00000001 +352.61,50.30085681,-2.667867779,10500,0,200.0009685,0,0,0,90.00000001 +352.62,50.30085681,-2.667839753,10500,0,200.0009685,0,0,0,90.00000001 +352.63,50.30085681,-2.667811728,10500,0,199.9998535,0,0,0,90.00000001 +352.64,50.30085681,-2.667783703,10500,0,199.9989614,0,0,0,90.00000001 +352.65,50.30085681,-2.667755678,10500,0,199.9989614,0,0,0,90.00000001 +352.66,50.30085681,-2.667727653,10500,0,199.9998535,0,0,0,90.00000001 +352.67,50.30085681,-2.667699628,10500,0,200.0009685,0,0,0,90.00000001 +352.68,50.30085681,-2.667671602,10500,0,200.0009685,0,0,0,90.00000001 +352.69,50.30085681,-2.667643577,10500,0,199.9998535,0,0,0,90.00000001 +352.7,50.30085681,-2.667615552,10500,0,199.9989614,0,0,0,90.00000001 +352.71,50.30085681,-2.667587527,10500,0,199.9989614,0,0,0,90.00000001 +352.72,50.30085681,-2.667559502,10500,0,199.9998535,0,0,0,90.00000001 +352.73,50.30085681,-2.667531477,10500,0,200.0009685,0,0,0,90.00000001 +352.74,50.30085681,-2.667503451,10500,0,200.0009685,0,0,0,90.00000001 +352.75,50.30085681,-2.667475426,10500,0,199.9998535,0,0,0,90.00000001 +352.76,50.30085681,-2.667447401,10500,0,199.9989614,0,0,0,90.00000001 +352.77,50.30085681,-2.667419376,10500,0,199.9987384,0,0,0,90.00000001 +352.78,50.30085681,-2.667391351,10500,0,199.9989614,0,0,0,90.00000001 +352.79,50.30085681,-2.667363326,10500,0,199.9998535,0,0,0,90.00000001 +352.8,50.30085681,-2.667335301,10500,0,200.0009685,0,0,0,90.00000001 +352.81,50.30085681,-2.667307275,10500,0,200.0009685,0,0,0,90.00000001 +352.82,50.30085681,-2.66727925,10500,0,199.9998535,0,0,0,90.00000001 +352.83,50.30085681,-2.667251225,10500,0,199.9989614,0,0,0,90.00000001 +352.84,50.30085681,-2.6672232,10500,0,199.9989614,0,0,0,90.00000001 +352.85,50.30085681,-2.667195175,10500,0,199.9998535,0,0,0,90.00000001 +352.86,50.30085681,-2.66716715,10500,0,200.0009685,0,0,0,90.00000001 +352.87,50.30085681,-2.667139124,10500,0,200.0009685,0,0,0,90.00000001 +352.88,50.30085681,-2.667111099,10500,0,199.9998535,0,0,0,90.00000001 +352.89,50.30085681,-2.667083074,10500,0,199.9991844,0,0,0,90.00000001 +352.9,50.30085681,-2.667055049,10500,0,199.9998535,0,0,0,90.00000001 +352.91,50.30085681,-2.667027024,10500,0,200.0009685,0,0,0,90.00000001 +352.92,50.30085681,-2.666998998,10500,0,200.0009685,0,0,0,90.00000001 +352.93,50.30085681,-2.666970973,10500,0,199.9998535,0,0,0,90.00000001 +352.94,50.30085681,-2.666942948,10500,0,199.9991844,0,0,0,90.00000001 +352.95,50.30085681,-2.666914923,10500,0,199.9998535,0,0,0,90.00000001 +352.96,50.30085681,-2.666886898,10500,0,200.0009685,0,0,0,90.00000001 +352.97,50.30085681,-2.666858872,10500,0,200.0009685,0,0,0,90.00000001 +352.98,50.30085681,-2.666830847,10500,0,199.9998535,0,0,0,90.00000001 +352.99,50.30085681,-2.666802822,10500,0,199.9991844,0,0,0,90.00000001 +353,50.30085681,-2.666774797,10500,0,199.9998535,0,0,0,90.00000001 +353.01,50.30085681,-2.666746772,10500,0,200.0009685,0,0,0,90.00000001 +353.02,50.30085681,-2.666718746,10500,0,200.0009685,0,0,0,90.00000001 +353.03,50.30085681,-2.666690721,10500,0,199.9998535,0,0,0,90.00000001 +353.04,50.30085681,-2.666662696,10500,0,199.9991844,0,0,0,90.00000001 +353.05,50.30085681,-2.666634671,10500,0,199.9998535,0,0,0,90.00000001 +353.06,50.30085681,-2.666606646,10500,0,200.0009685,0,0,0,90.00000001 +353.07,50.30085681,-2.66657862,10500,0,200.0009685,0,0,0,90.00000001 +353.08,50.30085681,-2.666550595,10500,0,199.9998535,0,0,0,90.00000001 +353.09,50.30085681,-2.66652257,10500,0,199.9991844,0,0,0,90.00000001 +353.1,50.30085681,-2.666494545,10500,0,199.9998535,0,0,0,90.00000001 +353.11,50.30085681,-2.66646652,10500,0,200.0009685,0,0,0,90.00000001 +353.12,50.30085681,-2.666438494,10500,0,200.0009685,0,0,0,90.00000001 +353.13,50.30085681,-2.666410469,10500,0,199.9998535,0,0,0,90.00000001 +353.14,50.30085681,-2.666382444,10500,0,199.9989614,0,0,0,90.00000001 +353.15,50.30085681,-2.666354419,10500,0,199.9989614,0,0,0,90.00000001 +353.16,50.30085681,-2.666326394,10500,0,199.9998535,0,0,0,90.00000001 +353.17,50.30085681,-2.666298369,10500,0,200.0009685,0,0,0,90.00000001 +353.18,50.30085681,-2.666270343,10500,0,200.0009685,0,0,0,90.00000001 +353.19,50.30085681,-2.666242318,10500,0,199.9998535,0,0,0,90.00000001 +353.2,50.30085681,-2.666214293,10500,0,199.9989614,0,0,0,90.00000001 +353.21,50.30085681,-2.666186268,10500,0,199.9989614,0,0,0,90.00000001 +353.22,50.30085681,-2.666158243,10500,0,199.9998535,0,0,0,90.00000001 +353.23,50.30085681,-2.666130218,10500,0,200.0009685,0,0,0,90.00000001 +353.24,50.30085681,-2.666102192,10500,0,200.0009685,0,0,0,90.00000001 +353.25,50.30085681,-2.666074167,10500,0,199.9998535,0,0,0,90.00000001 +353.26,50.30085681,-2.666046142,10500,0,199.9989614,0,0,0,90.00000001 +353.27,50.30085681,-2.666018117,10500,0,199.9989614,0,0,0,90.00000001 +353.28,50.30085681,-2.665990092,10500,0,199.9998535,0,0,0,90.00000001 +353.29,50.30085681,-2.665962067,10500,0,200.0009685,0,0,0,90.00000001 +353.3,50.30085681,-2.665934041,10500,0,200.0009685,0,0,0,90.00000001 +353.31,50.30085681,-2.665906016,10500,0,199.9998535,0,0,0,90.00000001 +353.32,50.30085681,-2.665877991,10500,0,199.9989614,0,0,0,90.00000001 +353.33,50.30085681,-2.665849966,10500,0,199.9987384,0,0,0,90.00000001 +353.34,50.30085681,-2.665821941,10500,0,199.9989614,0,0,0,90.00000001 +353.35,50.30085681,-2.665793916,10500,0,199.9998535,0,0,0,90.00000001 +353.36,50.30085681,-2.665765891,10500,0,200.0009685,0,0,0,90.00000001 +353.37,50.30085681,-2.665737865,10500,0,200.0009685,0,0,0,90.00000001 +353.38,50.30085681,-2.66570984,10500,0,199.9998535,0,0,0,90.00000001 +353.39,50.30085681,-2.665681815,10500,0,199.9989614,0,0,0,90.00000001 +353.4,50.30085681,-2.66565379,10500,0,199.9989614,0,0,0,90.00000001 +353.41,50.30085681,-2.665625765,10500,0,199.9998535,0,0,0,90.00000001 +353.42,50.30085681,-2.66559774,10500,0,200.0009685,0,0,0,90.00000001 +353.43,50.30085681,-2.665569714,10500,0,200.0009685,0,0,0,90.00000001 +353.44,50.30085681,-2.665541689,10500,0,199.9998535,0,0,0,90.00000001 +353.45,50.30085681,-2.665513664,10500,0,199.9989614,0,0,0,90.00000001 +353.46,50.30085681,-2.665485639,10500,0,199.9989614,0,0,0,90.00000001 +353.47,50.30085681,-2.665457614,10500,0,199.9998535,0,0,0,90.00000001 +353.48,50.30085681,-2.665429589,10500,0,200.0009685,0,0,0,90.00000001 +353.49,50.30085681,-2.665401563,10500,0,200.0009685,0,0,0,90.00000001 +353.5,50.30085681,-2.665373538,10500,0,199.9998535,0,0,0,90.00000001 +353.51,50.30085681,-2.665345513,10500,0,199.9991844,0,0,0,90.00000001 +353.52,50.30085681,-2.665317488,10500,0,199.9998535,0,0,0,90.00000001 +353.53,50.30085681,-2.665289463,10500,0,200.0009685,0,0,0,90.00000001 +353.54,50.30085681,-2.665261437,10500,0,200.0009685,0,0,0,90.00000001 +353.55,50.30085681,-2.665233412,10500,0,199.9998535,0,0,0,90.00000001 +353.56,50.30085681,-2.665205387,10500,0,199.9991844,0,0,0,90.00000001 +353.57,50.30085681,-2.665177362,10500,0,199.9998535,0,0,0,90.00000001 +353.58,50.30085681,-2.665149337,10500,0,200.0009685,0,0,0,90.00000001 +353.59,50.30085681,-2.665121311,10500,0,200.0009685,0,0,0,90.00000001 +353.6,50.30085681,-2.665093286,10500,0,199.9998535,0,0,0,90.00000001 +353.61,50.30085681,-2.665065261,10500,0,199.9991844,0,0,0,90.00000001 +353.62,50.30085681,-2.665037236,10500,0,199.9998535,0,0,0,90.00000001 +353.63,50.30085681,-2.665009211,10500,0,200.0009685,0,0,0,90.00000001 +353.64,50.30085681,-2.664981185,10500,0,200.0009685,0,0,0,90.00000001 +353.65,50.30085681,-2.66495316,10500,0,199.9998535,0,0,0,90.00000001 +353.66,50.30085681,-2.664925135,10500,0,199.9991844,0,0,0,90.00000001 +353.67,50.30085681,-2.66489711,10500,0,199.9998535,0,0,0,90.00000001 +353.68,50.30085681,-2.664869085,10500,0,200.0009685,0,0,0,90.00000001 +353.69,50.30085681,-2.664841059,10500,0,200.0009685,0,0,0,90.00000001 +353.7,50.30085681,-2.664813034,10500,0,199.9998535,0,0,0,90.00000001 +353.71,50.30085681,-2.664785009,10500,0,199.9991844,0,0,0,90.00000001 +353.72,50.30085681,-2.664756984,10500,0,199.9998535,0,0,0,90.00000001 +353.73,50.30085681,-2.664728959,10500,0,200.0009685,0,0,0,90.00000001 +353.74,50.30085681,-2.664700933,10500,0,200.0009685,0,0,0,90.00000001 +353.75,50.30085681,-2.664672908,10500,0,199.9998535,0,0,0,90.00000001 +353.76,50.30085681,-2.664644883,10500,0,199.9989614,0,0,0,90.00000001 +353.77,50.30085681,-2.664616858,10500,0,199.9989614,0,0,0,90.00000001 +353.78,50.30085681,-2.664588833,10500,0,199.9998535,0,0,0,90.00000001 +353.79,50.30085681,-2.664560808,10500,0,200.0009685,0,0,0,90.00000001 +353.8,50.30085681,-2.664532782,10500,0,200.0009685,0,0,0,90.00000001 +353.81,50.30085681,-2.664504757,10500,0,199.9998535,0,0,0,90.00000001 +353.82,50.30085681,-2.664476732,10500,0,199.9989614,0,0,0,90.00000001 +353.83,50.30085681,-2.664448707,10500,0,199.9989614,0,0,0,90.00000001 +353.84,50.30085681,-2.664420682,10500,0,199.9998535,0,0,0,90.00000001 +353.85,50.30085681,-2.664392657,10500,0,200.0009685,0,0,0,90.00000001 +353.86,50.30085681,-2.664364631,10500,0,200.0009685,0,0,0,90.00000001 +353.87,50.30085681,-2.664336606,10500,0,199.9998535,0,0,0,90.00000001 +353.88,50.30085681,-2.664308581,10500,0,199.9989614,0,0,0,90.00000001 +353.89,50.30085681,-2.664280556,10500,0,199.9987384,0,0,0,90.00000001 +353.9,50.30085681,-2.664252531,10500,0,199.9989614,0,0,0,90.00000001 +353.91,50.30085681,-2.664224506,10500,0,199.9998535,0,0,0,90.00000001 +353.92,50.30085681,-2.664196481,10500,0,200.0009685,0,0,0,90.00000001 +353.93,50.30085681,-2.664168455,10500,0,200.0009685,0,0,0,90.00000001 +353.94,50.30085681,-2.66414043,10500,0,199.9998535,0,0,0,90.00000001 +353.95,50.30085681,-2.664112405,10500,0,199.9989614,0,0,0,90.00000001 +353.96,50.30085681,-2.66408438,10500,0,199.9989614,0,0,0,90.00000001 +353.97,50.30085681,-2.664056355,10500,0,199.9998535,0,0,0,90.00000001 +353.98,50.30085681,-2.66402833,10500,0,200.0009685,0,0,0,90.00000001 +353.99,50.30085681,-2.664000304,10500,0,200.0009685,0,0,0,90.00000001 +354,50.30085681,-2.663972279,10500,0,199.9998535,0,0,0,90.00000001 +354.01,50.30085681,-2.663944254,10500,0,199.9989614,0,0,0,90.00000001 +354.02,50.30085681,-2.663916229,10500,0,199.9989614,0,0,0,90.00000001 +354.03,50.30085681,-2.663888204,10500,0,199.9998535,0,0,0,90.00000001 +354.04,50.30085681,-2.663860179,10500,0,200.0009685,0,0,0,90.00000001 +354.05,50.30085681,-2.663832153,10500,0,200.0009685,0,0,0,90.00000001 +354.06,50.30085681,-2.663804128,10500,0,199.9998535,0,0,0,90.00000001 +354.07,50.30085681,-2.663776103,10500,0,199.9989614,0,0,0,90.00000001 +354.08,50.30085681,-2.663748078,10500,0,199.9989614,0,0,0,90.00000001 +354.09,50.30085681,-2.663720053,10500,0,199.9998535,0,0,0,90.00000001 +354.1,50.30085681,-2.663692028,10500,0,200.0009685,0,0,0,90.00000001 +354.11,50.30085681,-2.663664002,10500,0,200.0009685,0,0,0,90.00000001 +354.12,50.30085681,-2.663635977,10500,0,199.9998535,0,0,0,90.00000001 +354.13,50.30085681,-2.663607952,10500,0,199.9991844,0,0,0,90.00000001 +354.14,50.30085681,-2.663579927,10500,0,199.9998535,0,0,0,90.00000001 +354.15,50.30085681,-2.663551902,10500,0,200.0009685,0,0,0,90.00000001 +354.16,50.30085681,-2.663523876,10500,0,200.0009685,0,0,0,90.00000001 +354.17,50.30085681,-2.663495851,10500,0,199.9998535,0,0,0,90.00000001 +354.18,50.30085681,-2.663467826,10500,0,199.9991844,0,0,0,90.00000001 +354.19,50.30085681,-2.663439801,10500,0,199.9998535,0,0,0,90.00000001 +354.2,50.30085681,-2.663411776,10500,0,200.0009685,0,0,0,90.00000001 +354.21,50.30085681,-2.66338375,10500,0,200.0009685,0,0,0,90.00000001 +354.22,50.30085681,-2.663355725,10500,0,199.9998535,0,0,0,90.00000001 +354.23,50.30085681,-2.6633277,10500,0,199.9991844,0,0,0,90.00000001 +354.24,50.30085681,-2.663299675,10500,0,199.9998535,0,0,0,90.00000001 +354.25,50.30085681,-2.66327165,10500,0,200.0009685,0,0,0,90.00000001 +354.26,50.30085681,-2.663243624,10500,0,200.0009685,0,0,0,90.00000001 +354.27,50.30085681,-2.663215599,10500,0,199.9998535,0,0,0,90.00000001 +354.28,50.30085681,-2.663187574,10500,0,199.9991844,0,0,0,90.00000001 +354.29,50.30085681,-2.663159549,10500,0,199.9998535,0,0,0,90.00000001 +354.3,50.30085681,-2.663131524,10500,0,200.0009685,0,0,0,90.00000001 +354.31,50.30085681,-2.663103498,10500,0,200.0009685,0,0,0,90.00000001 +354.32,50.30085681,-2.663075473,10500,0,199.9998535,0,0,0,90.00000001 +354.33,50.30085681,-2.663047448,10500,0,199.9991844,0,0,0,90.00000001 +354.34,50.30085681,-2.663019423,10500,0,199.9998535,0,0,0,90.00000001 +354.35,50.30085681,-2.662991398,10500,0,200.0009685,0,0,0,90.00000001 +354.36,50.30085681,-2.662963372,10500,0,200.0009685,0,0,0,90.00000001 +354.37,50.30085681,-2.662935347,10500,0,199.9998535,0,0,0,90.00000001 +354.38,50.30085681,-2.662907322,10500,0,199.9989614,0,0,0,90.00000001 +354.39,50.30085681,-2.662879297,10500,0,199.9989614,0,0,0,90.00000001 +354.4,50.30085681,-2.662851272,10500,0,199.9998535,0,0,0,90.00000001 +354.41,50.30085681,-2.662823247,10500,0,200.0009685,0,0,0,90.00000001 +354.42,50.30085681,-2.662795221,10500,0,200.0009685,0,0,0,90.00000001 +354.43,50.30085681,-2.662767196,10500,0,199.9998535,0,0,0,90.00000001 +354.44,50.30085681,-2.662739171,10500,0,199.9989614,0,0,0,90.00000001 +354.45,50.30085681,-2.662711146,10500,0,199.9987384,0,0,0,90.00000001 +354.46,50.30085681,-2.662683121,10500,0,199.9989614,0,0,0,90.00000001 +354.47,50.30085681,-2.662655096,10500,0,199.9998535,0,0,0,90.00000001 +354.48,50.30085681,-2.662627071,10500,0,200.0009685,0,0,0,90.00000001 +354.49,50.30085681,-2.662599045,10500,0,200.0009685,0,0,0,90.00000001 +354.5,50.30085681,-2.66257102,10500,0,199.9998535,0,0,0,90.00000001 +354.51,50.30085681,-2.662542995,10500,0,199.9989614,0,0,0,90.00000001 +354.52,50.30085681,-2.66251497,10500,0,199.9989614,0,0,0,90.00000001 +354.53,50.30085681,-2.662486945,10500,0,199.9998535,0,0,0,90.00000001 +354.54,50.30085681,-2.66245892,10500,0,200.0009685,0,0,0,90.00000001 +354.55,50.30085681,-2.662430894,10500,0,200.0009685,0,0,0,90.00000001 +354.56,50.30085681,-2.662402869,10500,0,199.9998535,0,0,0,90.00000001 +354.57,50.30085681,-2.662374844,10500,0,199.9989614,0,0,0,90.00000001 +354.58,50.30085681,-2.662346819,10500,0,199.9989614,0,0,0,90.00000001 +354.59,50.30085681,-2.662318794,10500,0,199.9998535,0,0,0,90.00000001 +354.6,50.30085681,-2.662290769,10500,0,200.0009685,0,0,0,90.00000001 +354.61,50.30085681,-2.662262743,10500,0,200.0009685,0,0,0,90.00000001 +354.62,50.30085681,-2.662234718,10500,0,199.9998535,0,0,0,90.00000001 +354.63,50.30085681,-2.662206693,10500,0,199.9989614,0,0,0,90.00000001 +354.64,50.30085681,-2.662178668,10500,0,199.9989614,0,0,0,90.00000001 +354.65,50.30085681,-2.662150643,10500,0,199.9998535,0,0,0,90.00000001 +354.66,50.30085681,-2.662122618,10500,0,200.0009685,0,0,0,90.00000001 +354.67,50.30085681,-2.662094592,10500,0,200.0009685,0,0,0,90.00000001 +354.68,50.30085681,-2.662066567,10500,0,199.9998535,0,0,0,90.00000001 +354.69,50.30085681,-2.662038542,10500,0,199.9989614,0,0,0,90.00000001 +354.7,50.30085681,-2.662010517,10500,0,199.9989614,0,0,0,90.00000001 +354.71,50.30085681,-2.661982492,10500,0,199.9998535,0,0,0,90.00000001 +354.72,50.30085681,-2.661954467,10500,0,200.0009685,0,0,0,90.00000001 +354.73,50.30085681,-2.661926441,10500,0,200.0009685,0,0,0,90.00000001 +354.74,50.30085681,-2.661898416,10500,0,199.9998535,0,0,0,90.00000001 +354.75,50.30085681,-2.661870391,10500,0,199.9991844,0,0,0,90.00000001 +354.76,50.30085681,-2.661842366,10500,0,199.9998535,0,0,0,90.00000001 +354.77,50.30085681,-2.661814341,10500,0,200.0009685,0,0,0,90.00000001 +354.78,50.30085681,-2.661786315,10500,0,200.0009685,0,0,0,90.00000001 +354.79,50.30085681,-2.66175829,10500,0,199.9998535,0,0,0,90.00000001 +354.8,50.30085681,-2.661730265,10500,0,199.9989614,0,0,0,90.00000001 +354.81,50.30085681,-2.66170224,10500,0,199.9989614,0,0,0,90.00000001 +354.82,50.30085681,-2.661674215,10500,0,199.9998535,0,0,0,90.00000001 +354.83,50.30085681,-2.66164619,10500,0,200.0009685,0,0,0,90.00000001 +354.84,50.30085681,-2.661618164,10500,0,200.0009685,0,0,0,90.00000001 +354.85,50.30085681,-2.661590139,10500,0,199.9998535,0,0,0,90.00000001 +354.86,50.30085681,-2.661562114,10500,0,199.9991844,0,0,0,90.00000001 +354.87,50.30085681,-2.661534089,10500,0,199.9998535,0,0,0,90.00000001 +354.88,50.30085681,-2.661506064,10500,0,200.0009685,0,0,0,90.00000001 +354.89,50.30085681,-2.661478038,10500,0,200.0009685,0,0,0,90.00000001 +354.9,50.30085681,-2.661450013,10500,0,199.9998535,0,0,0,90.00000001 +354.91,50.30085681,-2.661421988,10500,0,199.9991844,0,0,0,90.00000001 +354.92,50.30085681,-2.661393963,10500,0,199.9998535,0,0,0,90.00000001 +354.93,50.30085681,-2.661365938,10500,0,200.0009685,0,0,0,90.00000001 +354.94,50.30085681,-2.661337912,10500,0,200.0009685,0,0,0,90.00000001 +354.95,50.30085681,-2.661309887,10500,0,199.9998535,0,0,0,90.00000001 +354.96,50.30085681,-2.661281862,10500,0,199.9991844,0,0,0,90.00000001 +354.97,50.30085681,-2.661253837,10500,0,199.9998535,0,0,0,90.00000001 +354.98,50.30085681,-2.661225812,10500,0,200.0009685,0,0,0,90.00000001 +354.99,50.30085681,-2.661197786,10500,0,200.0009685,0,0,0,90.00000001 +355,50.30085681,-2.661169761,10500,0,199.9998535,0,0,0,90.00000001 +355.01,50.30085681,-2.661141736,10500,0,199.9991844,0,0,0,90.00000001 +355.02,50.30085681,-2.661113711,10500,0,199.9998535,0,0,0,90.00000001 +355.03,50.30085681,-2.661085686,10500,0,200.0009685,0,0,0,90.00000001 +355.04,50.30085681,-2.66105766,10500,0,200.0009685,0,0,0,90.00000001 +355.05,50.30085681,-2.661029635,10500,0,199.9998535,0,0,0,90.00000001 +355.06,50.30085681,-2.66100161,10500,0,199.9989614,0,0,0,90.00000001 +355.07,50.30085681,-2.660973585,10500,0,199.9987384,0,0,0,90.00000001 +355.08,50.30085681,-2.66094556,10500,0,199.9989614,0,0,0,90.00000001 +355.09,50.30085681,-2.660917535,10500,0,199.9998535,0,0,0,90.00000001 +355.1,50.30085681,-2.66088951,10500,0,200.0009685,0,0,0,90.00000001 +355.11,50.30085681,-2.660861484,10500,0,200.0009685,0,0,0,90.00000001 +355.12,50.30085681,-2.660833459,10500,0,199.9998535,0,0,0,90.00000001 +355.13,50.30085681,-2.660805434,10500,0,199.9989614,0,0,0,90.00000001 +355.14,50.30085681,-2.660777409,10500,0,199.9989614,0,0,0,90.00000001 +355.15,50.30085681,-2.660749384,10500,0,199.9998535,0,0,0,90.00000001 +355.16,50.30085681,-2.660721359,10500,0,200.0009685,0,0,0,90.00000001 +355.17,50.30085681,-2.660693333,10500,0,200.0009685,0,0,0,90.00000001 +355.18,50.30085681,-2.660665308,10500,0,199.9998535,0,0,0,90.00000001 +355.19,50.30085681,-2.660637283,10500,0,199.9989614,0,0,0,90.00000001 +355.2,50.30085681,-2.660609258,10500,0,199.9989614,0,0,0,90.00000001 +355.21,50.30085681,-2.660581233,10500,0,199.9998535,0,0,0,90.00000001 +355.22,50.30085681,-2.660553208,10500,0,200.0009685,0,0,0,90.00000001 +355.23,50.30085681,-2.660525182,10500,0,200.0009685,0,0,0,90.00000001 +355.24,50.30085681,-2.660497157,10500,0,199.9998535,0,0,0,90.00000001 +355.25,50.30085681,-2.660469132,10500,0,199.9989614,0,0,0,90.00000001 +355.26,50.30085681,-2.660441107,10500,0,199.9989614,0,0,0,90.00000001 +355.27,50.30085681,-2.660413082,10500,0,199.9998535,0,0,0,90.00000001 +355.28,50.30085681,-2.660385057,10500,0,200.0009685,0,0,0,90.00000001 +355.29,50.30085681,-2.660357031,10500,0,200.0009685,0,0,0,90.00000001 +355.3,50.30085681,-2.660329006,10500,0,199.9998535,0,0,0,90.00000001 +355.31,50.30085681,-2.660300981,10500,0,199.9989614,0,0,0,90.00000001 +355.32,50.30085681,-2.660272956,10500,0,199.9987384,0,0,0,90.00000001 +355.33,50.30085681,-2.660244931,10500,0,199.9989614,0,0,0,90.00000001 +355.34,50.30085681,-2.660216906,10500,0,199.9998535,0,0,0,90.00000001 +355.35,50.30085681,-2.660188881,10500,0,200.0009685,0,0,0,90.00000001 +355.36,50.30085681,-2.660160855,10500,0,200.0009685,0,0,0,90.00000001 +355.37,50.30085681,-2.66013283,10500,0,199.9998535,0,0,0,90.00000001 +355.38,50.30085681,-2.660104805,10500,0,199.9991844,0,0,0,90.00000001 +355.39,50.30085681,-2.66007678,10500,0,199.9998535,0,0,0,90.00000001 +355.4,50.30085681,-2.660048755,10500,0,200.0009685,0,0,0,90.00000001 +355.41,50.30085681,-2.660020729,10500,0,200.0009685,0,0,0,90.00000001 +355.42,50.30085681,-2.659992704,10500,0,199.9998535,0,0,0,90.00000001 +355.43,50.30085681,-2.659964679,10500,0,199.9991844,0,0,0,90.00000001 +355.44,50.30085681,-2.659936654,10500,0,199.9998535,0,0,0,90.00000001 +355.45,50.30085681,-2.659908629,10500,0,200.0009685,0,0,0,90.00000001 +355.46,50.30085681,-2.659880603,10500,0,200.0009685,0,0,0,90.00000001 +355.47,50.30085681,-2.659852578,10500,0,199.9998535,0,0,0,90.00000001 +355.48,50.30085681,-2.659824553,10500,0,199.9991844,0,0,0,90.00000001 +355.49,50.30085681,-2.659796528,10500,0,199.9998535,0,0,0,90.00000001 +355.5,50.30085681,-2.659768503,10500,0,200.0009685,0,0,0,90.00000001 +355.51,50.30085681,-2.659740477,10500,0,200.0009685,0,0,0,90.00000001 +355.52,50.30085681,-2.659712452,10500,0,199.9998535,0,0,0,90.00000001 +355.53,50.30085681,-2.659684427,10500,0,199.9991844,0,0,0,90.00000001 +355.54,50.30085681,-2.659656402,10500,0,199.9998535,0,0,0,90.00000001 +355.55,50.30085681,-2.659628377,10500,0,200.0009685,0,0,0,90.00000001 +355.56,50.30085681,-2.659600351,10500,0,200.0009685,0,0,0,90.00000001 +355.57,50.30085681,-2.659572326,10500,0,199.9998535,0,0,0,90.00000001 +355.58,50.30085681,-2.659544301,10500,0,199.9991844,0,0,0,90.00000001 +355.59,50.30085681,-2.659516276,10500,0,199.9998535,0,0,0,90.00000001 +355.6,50.30085681,-2.659488251,10500,0,200.0009685,0,0,0,90.00000001 +355.61,50.30085681,-2.659460225,10500,0,200.0009685,0,0,0,90.00000001 +355.62,50.30085681,-2.6594322,10500,0,199.9998535,0,0,0,90.00000001 +355.63,50.30085681,-2.659404175,10500,0,199.9989614,0,0,0,90.00000001 +355.64,50.30085681,-2.65937615,10500,0,199.9989614,0,0,0,90.00000001 +355.65,50.30085681,-2.659348125,10500,0,199.9998535,0,0,0,90.00000001 +355.66,50.30085681,-2.6593201,10500,0,200.0009685,0,0,0,90.00000001 +355.67,50.30085681,-2.659292074,10500,0,200.0009685,0,0,0,90.00000001 +355.68,50.30085681,-2.659264049,10500,0,199.9998535,0,0,0,90.00000001 +355.69,50.30085681,-2.659236024,10500,0,199.9989614,0,0,0,90.00000001 +355.7,50.30085681,-2.659207999,10500,0,199.9989614,0,0,0,90.00000001 +355.71,50.30085681,-2.659179974,10500,0,199.9998535,0,0,0,90.00000001 +355.72,50.30085681,-2.659151949,10500,0,200.0009685,0,0,0,90.00000001 +355.73,50.30085681,-2.659123923,10500,0,200.0009685,0,0,0,90.00000001 +355.74,50.30085681,-2.659095898,10500,0,199.9998535,0,0,0,90.00000001 +355.75,50.30085681,-2.659067873,10500,0,199.9989614,0,0,0,90.00000001 +355.76,50.30085681,-2.659039848,10500,0,199.9989614,0,0,0,90.00000001 +355.77,50.30085681,-2.659011823,10500,0,199.9998535,0,0,0,90.00000001 +355.78,50.30085681,-2.658983798,10500,0,200.0009685,0,0,0,90.00000001 +355.79,50.30085681,-2.658955772,10500,0,200.0009685,0,0,0,90.00000001 +355.8,50.30085681,-2.658927747,10500,0,199.9998535,0,0,0,90.00000001 +355.81,50.30085681,-2.658899722,10500,0,199.9989614,0,0,0,90.00000001 +355.82,50.30085681,-2.658871697,10500,0,199.9989614,0,0,0,90.00000001 +355.83,50.30085681,-2.658843672,10500,0,199.9998535,0,0,0,90.00000001 +355.84,50.30085681,-2.658815647,10500,0,200.0009685,0,0,0,90.00000001 +355.85,50.30085681,-2.658787621,10500,0,200.0009685,0,0,0,90.00000001 +355.86,50.30085681,-2.658759596,10500,0,199.9998535,0,0,0,90.00000001 +355.87,50.30085681,-2.658731571,10500,0,199.9989614,0,0,0,90.00000001 +355.88,50.30085681,-2.658703546,10500,0,199.9987384,0,0,0,90.00000001 +355.89,50.30085681,-2.658675521,10500,0,199.9989614,0,0,0,90.00000001 +355.9,50.30085681,-2.658647496,10500,0,199.9998535,0,0,0,90.00000001 +355.91,50.30085681,-2.658619471,10500,0,200.0009685,0,0,0,90.00000001 +355.92,50.30085681,-2.658591445,10500,0,200.0009685,0,0,0,90.00000001 +355.93,50.30085681,-2.65856342,10500,0,199.9998535,0,0,0,90.00000001 +355.94,50.30085681,-2.658535395,10500,0,199.9989614,0,0,0,90.00000001 +355.95,50.30085681,-2.65850737,10500,0,199.9989614,0,0,0,90.00000001 +355.96,50.30085681,-2.658479345,10500,0,199.9998535,0,0,0,90.00000001 +355.97,50.30085681,-2.65845132,10500,0,200.0009685,0,0,0,90.00000001 +355.98,50.30085681,-2.658423294,10500,0,200.0009685,0,0,0,90.00000001 +355.99,50.30085681,-2.658395269,10500,0,199.9998535,0,0,0,90.00000001 +356,50.30085681,-2.658367244,10500,0,199.9991844,0,0,0,90.00000001 +356.01,50.30085681,-2.658339219,10500,0,199.9998535,0,0,0,90.00000001 +356.02,50.30085681,-2.658311194,10500,0,200.0009685,0,0,0,90.00000001 +356.03,50.30085681,-2.658283168,10500,0,200.0009685,0,0,0,90.00000001 +356.04,50.30085681,-2.658255143,10500,0,199.9998535,0,0,0,90.00000001 +356.05,50.30085681,-2.658227118,10500,0,199.9991844,0,0,0,90.00000001 +356.06,50.30085681,-2.658199093,10500,0,199.9998535,0,0,0,90.00000001 +356.07,50.30085681,-2.658171068,10500,0,200.0009685,0,0,0,90.00000001 +356.08,50.30085681,-2.658143042,10500,0,200.0009685,0,0,0,90.00000001 +356.09,50.30085681,-2.658115017,10500,0,199.9998535,0,0,0,90.00000001 +356.1,50.30085681,-2.658086992,10500,0,199.9991844,0,0,0,90.00000001 +356.11,50.30085681,-2.658058967,10500,0,199.9998535,0,0,0,90.00000001 +356.12,50.30085681,-2.658030942,10500,0,200.0009685,0,0,0,90.00000001 +356.13,50.30085681,-2.658002916,10500,0,200.0009685,0,0,0,90.00000001 +356.14,50.30085681,-2.657974891,10500,0,199.9998535,0,0,0,90.00000001 +356.15,50.30085681,-2.657946866,10500,0,199.9991844,0,0,0,90.00000001 +356.16,50.30085681,-2.657918841,10500,0,199.9998535,0,0,0,90.00000001 +356.17,50.30085681,-2.657890816,10500,0,200.0009685,0,0,0,90.00000001 +356.18,50.30085681,-2.65786279,10500,0,200.0009685,0,0,0,90.00000001 +356.19,50.30085681,-2.657834765,10500,0,199.9998535,0,0,0,90.00000001 +356.2,50.30085681,-2.65780674,10500,0,199.9991844,0,0,0,90.00000001 +356.21,50.30085681,-2.657778715,10500,0,199.9998535,0,0,0,90.00000001 +356.22,50.30085681,-2.65775069,10500,0,200.0009685,0,0,0,90.00000001 +356.23,50.30085681,-2.657722664,10500,0,200.0009685,0,0,0,90.00000001 +356.24,50.30085681,-2.657694639,10500,0,199.9998535,0,0,0,90.00000001 +356.25,50.30085681,-2.657666614,10500,0,199.9989614,0,0,0,90.00000001 +356.26,50.30085681,-2.657638589,10500,0,199.9989614,0,0,0,90.00000001 +356.27,50.30085681,-2.657610564,10500,0,199.9998535,0,0,0,90.00000001 +356.28,50.30085681,-2.657582539,10500,0,200.0009685,0,0,0,90.00000001 +356.29,50.30085681,-2.657554513,10500,0,200.0009685,0,0,0,90.00000001 +356.3,50.30085681,-2.657526488,10500,0,199.9998535,0,0,0,90.00000001 +356.31,50.30085681,-2.657498463,10500,0,199.9989614,0,0,0,90.00000001 +356.32,50.30085681,-2.657470438,10500,0,199.9989614,0,0,0,90.00000001 +356.33,50.30085681,-2.657442413,10500,0,199.9998535,0,0,0,90.00000001 +356.34,50.30085681,-2.657414388,10500,0,200.0009685,0,0,0,90.00000001 +356.35,50.30085681,-2.657386362,10500,0,200.0009685,0,0,0,90.00000001 +356.36,50.30085681,-2.657358337,10500,0,199.9998535,0,0,0,90.00000001 +356.37,50.30085681,-2.657330312,10500,0,199.9989614,0,0,0,90.00000001 +356.38,50.30085681,-2.657302287,10500,0,199.9989614,0,0,0,90.00000001 +356.39,50.30085681,-2.657274262,10500,0,199.9998535,0,0,0,90.00000001 +356.4,50.30085681,-2.657246237,10500,0,200.0009685,0,0,0,90.00000001 +356.41,50.30085681,-2.657218211,10500,0,200.0009685,0,0,0,90.00000001 +356.42,50.30085681,-2.657190186,10500,0,199.9998535,0,0,0,90.00000001 +356.43,50.30085681,-2.657162161,10500,0,199.9989614,0,0,0,90.00000001 +356.44,50.30085681,-2.657134136,10500,0,199.9989614,0,0,0,90.00000001 +356.45,50.30085681,-2.657106111,10500,0,199.9998535,0,0,0,90.00000001 +356.46,50.30085681,-2.657078086,10500,0,200.0009685,0,0,0,90.00000001 +356.47,50.30085681,-2.65705006,10500,0,200.0009685,0,0,0,90.00000001 +356.48,50.30085681,-2.657022035,10500,0,199.9998535,0,0,0,90.00000001 +356.49,50.30085681,-2.65699401,10500,0,199.9989614,0,0,0,90.00000001 +356.5,50.30085681,-2.656965985,10500,0,199.9987384,0,0,0,90.00000001 +356.51,50.30085681,-2.65693796,10500,0,199.9989614,0,0,0,90.00000001 +356.52,50.30085681,-2.656909935,10500,0,199.9998535,0,0,0,90.00000001 +356.53,50.30085681,-2.65688191,10500,0,200.0009685,0,0,0,90.00000001 +356.54,50.30085681,-2.656853884,10500,0,200.0009685,0,0,0,90.00000001 +356.55,50.30085681,-2.656825859,10500,0,199.9998535,0,0,0,90.00000001 +356.56,50.30085681,-2.656797834,10500,0,199.9989614,0,0,0,90.00000001 +356.57,50.30085681,-2.656769809,10500,0,199.9989614,0,0,0,90.00000001 +356.58,50.30085681,-2.656741784,10500,0,199.9998535,0,0,0,90.00000001 +356.59,50.30085681,-2.656713759,10500,0,200.0009685,0,0,0,90.00000001 +356.6,50.30085681,-2.656685733,10500,0,200.0009685,0,0,0,90.00000001 +356.61,50.30085681,-2.656657708,10500,0,199.9998535,0,0,0,90.00000001 +356.62,50.30085681,-2.656629683,10500,0,199.9991844,0,0,0,90.00000001 +356.63,50.30085681,-2.656601658,10500,0,199.9998535,0,0,0,90.00000001 +356.64,50.30085681,-2.656573633,10500,0,200.0009685,0,0,0,90.00000001 +356.65,50.30085681,-2.656545607,10500,0,200.0009685,0,0,0,90.00000001 +356.66,50.30085681,-2.656517582,10500,0,199.9998535,0,0,0,90.00000001 +356.67,50.30085681,-2.656489557,10500,0,199.9991844,0,0,0,90.00000001 +356.68,50.30085681,-2.656461532,10500,0,199.9998535,0,0,0,90.00000001 +356.69,50.30085681,-2.656433507,10500,0,200.0009685,0,0,0,90.00000001 +356.7,50.30085681,-2.656405481,10500,0,200.0009685,0,0,0,90.00000001 +356.71,50.30085681,-2.656377456,10500,0,199.9998535,0,0,0,90.00000001 +356.72,50.30085681,-2.656349431,10500,0,199.9991844,0,0,0,90.00000001 +356.73,50.30085681,-2.656321406,10500,0,199.9998535,0,0,0,90.00000001 +356.74,50.30085681,-2.656293381,10500,0,200.0009685,0,0,0,90.00000001 +356.75,50.30085681,-2.656265355,10500,0,200.0009685,0,0,0,90.00000001 +356.76,50.30085681,-2.65623733,10500,0,199.9998535,0,0,0,90.00000001 +356.77,50.30085681,-2.656209305,10500,0,199.9991844,0,0,0,90.00000001 +356.78,50.30085681,-2.65618128,10500,0,199.9998535,0,0,0,90.00000001 +356.79,50.30085681,-2.656153255,10500,0,200.0009685,0,0,0,90.00000001 +356.8,50.30085681,-2.656125229,10500,0,200.0009685,0,0,0,90.00000001 +356.81,50.30085681,-2.656097204,10500,0,199.9998535,0,0,0,90.00000001 +356.82,50.30085681,-2.656069179,10500,0,199.9989614,0,0,0,90.00000001 +356.83,50.30085681,-2.656041154,10500,0,199.9989614,0,0,0,90.00000001 +356.84,50.30085681,-2.656013129,10500,0,199.9998535,0,0,0,90.00000001 +356.85,50.30085681,-2.655985104,10500,0,200.0009685,0,0,0,90.00000001 +356.86,50.30085681,-2.655957078,10500,0,200.0009685,0,0,0,90.00000001 +356.87,50.30085681,-2.655929053,10500,0,199.9998535,0,0,0,90.00000001 +356.88,50.30085681,-2.655901028,10500,0,199.9991844,0,0,0,90.00000001 +356.89,50.30085681,-2.655873003,10500,0,199.9998535,0,0,0,90.00000001 +356.9,50.30085681,-2.655844978,10500,0,200.0009685,0,0,0,90.00000001 +356.91,50.30085681,-2.655816952,10500,0,200.0009685,0,0,0,90.00000001 +356.92,50.30085681,-2.655788927,10500,0,199.9998535,0,0,0,90.00000001 +356.93,50.30085681,-2.655760902,10500,0,199.9989614,0,0,0,90.00000001 +356.94,50.30085681,-2.655732877,10500,0,199.9989614,0,0,0,90.00000001 +356.95,50.30085681,-2.655704852,10500,0,199.9998535,0,0,0,90.00000001 +356.96,50.30085681,-2.655676827,10500,0,200.0009685,0,0,0,90.00000001 +356.97,50.30085681,-2.655648801,10500,0,200.0009685,0,0,0,90.00000001 +356.98,50.30085681,-2.655620776,10500,0,199.9998535,0,0,0,90.00000001 +356.99,50.30085681,-2.655592751,10500,0,199.9989614,0,0,0,90.00000001 +357,50.30085681,-2.655564726,10500,0,199.9989614,0,0,0,90.00000001 +357.01,50.30085681,-2.655536701,10500,0,199.9998535,0,0,0,90.00000001 +357.02,50.30085681,-2.655508676,10500,0,200.0009685,0,0,0,90.00000001 +357.03,50.30085681,-2.65548065,10500,0,200.0009685,0,0,0,90.00000001 +357.04,50.30085681,-2.655452625,10500,0,199.9998535,0,0,0,90.00000001 +357.05,50.30085681,-2.6554246,10500,0,199.9989614,0,0,0,90.00000001 +357.06,50.30085681,-2.655396575,10500,0,199.9987384,0,0,0,90.00000001 +357.07,50.30085681,-2.65536855,10500,0,199.9989614,0,0,0,90.00000001 +357.08,50.30085681,-2.655340525,10500,0,199.9998535,0,0,0,90.00000001 +357.09,50.30085681,-2.6553125,10500,0,200.0009685,0,0,0,90.00000001 +357.1,50.30085681,-2.655284474,10500,0,200.0009685,0,0,0,90.00000001 +357.11,50.30085681,-2.655256449,10500,0,199.9998535,0,0,0,90.00000001 +357.12,50.30085681,-2.655228424,10500,0,199.9989614,0,0,0,90.00000001 +357.13,50.30085681,-2.655200399,10500,0,199.9989614,0,0,0,90.00000001 +357.14,50.30085681,-2.655172374,10500,0,199.9998535,0,0,0,90.00000001 +357.15,50.30085681,-2.655144349,10500,0,200.0009685,0,0,0,90.00000001 +357.16,50.30085681,-2.655116323,10500,0,200.0009685,0,0,0,90.00000001 +357.17,50.30085681,-2.655088298,10500,0,199.9998535,0,0,0,90.00000001 +357.18,50.30085681,-2.655060273,10500,0,199.9989614,0,0,0,90.00000001 +357.19,50.30085681,-2.655032248,10500,0,199.9989614,0,0,0,90.00000001 +357.2,50.30085681,-2.655004223,10500,0,199.9998535,0,0,0,90.00000001 +357.21,50.30085681,-2.654976198,10500,0,200.0009685,0,0,0,90.00000001 +357.22,50.30085681,-2.654948172,10500,0,200.0009685,0,0,0,90.00000001 +357.23,50.30085681,-2.654920147,10500,0,199.9998535,0,0,0,90.00000001 +357.24,50.30085681,-2.654892122,10500,0,199.9989614,0,0,0,90.00000001 +357.25,50.30085681,-2.654864097,10500,0,199.9989614,0,0,0,90.00000001 +357.26,50.30085681,-2.654836072,10500,0,199.9998535,0,0,0,90.00000001 +357.27,50.30085681,-2.654808047,10500,0,200.0009685,0,0,0,90.00000001 +357.28,50.30085681,-2.654780021,10500,0,200.0009685,0,0,0,90.00000001 +357.29,50.30085681,-2.654751996,10500,0,199.9998535,0,0,0,90.00000001 +357.3,50.30085681,-2.654723971,10500,0,199.9991844,0,0,0,90.00000001 +357.31,50.30085681,-2.654695946,10500,0,199.9998535,0,0,0,90.00000001 +357.32,50.30085681,-2.654667921,10500,0,200.0009685,0,0,0,90.00000001 +357.33,50.30085681,-2.654639895,10500,0,200.0009685,0,0,0,90.00000001 +357.34,50.30085681,-2.65461187,10500,0,199.9998535,0,0,0,90.00000001 +357.35,50.30085681,-2.654583845,10500,0,199.9991844,0,0,0,90.00000001 +357.36,50.30085681,-2.65455582,10500,0,199.9998535,0,0,0,90.00000001 +357.37,50.30085681,-2.654527795,10500,0,200.0009685,0,0,0,90.00000001 +357.38,50.30085681,-2.654499769,10500,0,200.0009685,0,0,0,90.00000001 +357.39,50.30085681,-2.654471744,10500,0,199.9998535,0,0,0,90.00000001 +357.4,50.30085681,-2.654443719,10500,0,199.9991844,0,0,0,90.00000001 +357.41,50.30085681,-2.654415694,10500,0,199.9998535,0,0,0,90.00000001 +357.42,50.30085681,-2.654387669,10500,0,200.0009685,0,0,0,90.00000001 +357.43,50.30085681,-2.654359643,10500,0,200.0009685,0,0,0,90.00000001 +357.44,50.30085681,-2.654331618,10500,0,199.9998535,0,0,0,90.00000001 +357.45,50.30085681,-2.654303593,10500,0,199.9991844,0,0,0,90.00000001 +357.46,50.30085681,-2.654275568,10500,0,199.9998535,0,0,0,90.00000001 +357.47,50.30085681,-2.654247543,10500,0,200.0009685,0,0,0,90.00000001 +357.48,50.30085681,-2.654219517,10500,0,200.0009685,0,0,0,90.00000001 +357.49,50.30085681,-2.654191492,10500,0,199.9998535,0,0,0,90.00000001 +357.5,50.30085681,-2.654163467,10500,0,199.9991844,0,0,0,90.00000001 +357.51,50.30085681,-2.654135442,10500,0,199.9998535,0,0,0,90.00000001 +357.52,50.30085681,-2.654107417,10500,0,200.0009685,0,0,0,90.00000001 +357.53,50.30085681,-2.654079391,10500,0,200.0009685,0,0,0,90.00000001 +357.54,50.30085681,-2.654051366,10500,0,199.9998535,0,0,0,90.00000001 +357.55,50.30085681,-2.654023341,10500,0,199.9989614,0,0,0,90.00000001 +357.56,50.30085681,-2.653995316,10500,0,199.9989614,0,0,0,90.00000001 +357.57,50.30085681,-2.653967291,10500,0,199.9998535,0,0,0,90.00000001 +357.58,50.30085681,-2.653939266,10500,0,200.0009685,0,0,0,90.00000001 +357.59,50.30085681,-2.65391124,10500,0,200.0009685,0,0,0,90.00000001 +357.6,50.30085681,-2.653883215,10500,0,199.9998535,0,0,0,90.00000001 +357.61,50.30085681,-2.65385519,10500,0,199.9989614,0,0,0,90.00000001 +357.62,50.30085681,-2.653827165,10500,0,199.9987384,0,0,0,90.00000001 +357.63,50.30085681,-2.65379914,10500,0,199.9989614,0,0,0,90.00000001 +357.64,50.30085681,-2.653771115,10500,0,199.9998535,0,0,0,90.00000001 +357.65,50.30085681,-2.65374309,10500,0,200.0009685,0,0,0,90.00000001 +357.66,50.30085681,-2.653715064,10500,0,200.0009685,0,0,0,90.00000001 +357.67,50.30085681,-2.653687039,10500,0,199.9998535,0,0,0,90.00000001 +357.68,50.30085681,-2.653659014,10500,0,199.9989614,0,0,0,90.00000001 +357.69,50.30085681,-2.653630989,10500,0,199.9989614,0,0,0,90.00000001 +357.7,50.30085681,-2.653602964,10500,0,199.9998535,0,0,0,90.00000001 +357.71,50.30085681,-2.653574939,10500,0,200.0009685,0,0,0,90.00000001 +357.72,50.30085681,-2.653546913,10500,0,200.0009685,0,0,0,90.00000001 +357.73,50.30085681,-2.653518888,10500,0,199.9998535,0,0,0,90.00000001 +357.74,50.30085681,-2.653490863,10500,0,199.9989614,0,0,0,90.00000001 +357.75,50.30085681,-2.653462838,10500,0,199.9989614,0,0,0,90.00000001 +357.76,50.30085681,-2.653434813,10500,0,199.9998535,0,0,0,90.00000001 +357.77,50.30085681,-2.653406788,10500,0,200.0009685,0,0,0,90.00000001 +357.78,50.30085681,-2.653378762,10500,0,200.0009685,0,0,0,90.00000001 +357.79,50.30085681,-2.653350737,10500,0,199.9998535,0,0,0,90.00000001 +357.8,50.30085681,-2.653322712,10500,0,199.9989614,0,0,0,90.00000001 +357.81,50.30085681,-2.653294687,10500,0,199.9989614,0,0,0,90.00000001 +357.82,50.30085681,-2.653266662,10500,0,199.9998535,0,0,0,90.00000001 +357.83,50.30085681,-2.653238637,10500,0,200.0009685,0,0,0,90.00000001 +357.84,50.30085681,-2.653210611,10500,0,200.0009685,0,0,0,90.00000001 +357.85,50.30085681,-2.653182586,10500,0,199.9998535,0,0,0,90.00000001 +357.86,50.30085681,-2.653154561,10500,0,199.9989614,0,0,0,90.00000001 +357.87,50.30085681,-2.653126536,10500,0,199.9989614,0,0,0,90.00000001 +357.88,50.30085681,-2.653098511,10500,0,199.9998535,0,0,0,90.00000001 +357.89,50.30085681,-2.653070486,10500,0,200.0009685,0,0,0,90.00000001 +357.9,50.30085681,-2.65304246,10500,0,200.0009685,0,0,0,90.00000001 +357.91,50.30085681,-2.653014435,10500,0,199.9998535,0,0,0,90.00000001 +357.92,50.30085681,-2.65298641,10500,0,199.9991844,0,0,0,90.00000001 +357.93,50.30085681,-2.652958385,10500,0,199.9998535,0,0,0,90.00000001 +357.94,50.30085681,-2.65293036,10500,0,200.0009685,0,0,0,90.00000001 +357.95,50.30085681,-2.652902334,10500,0,200.0009685,0,0,0,90.00000001 +357.96,50.30085681,-2.652874309,10500,0,199.9998535,0,0,0,90.00000001 +357.97,50.30085681,-2.652846284,10500,0,199.9991844,0,0,0,90.00000001 +357.98,50.30085681,-2.652818259,10500,0,199.9998535,0,0,0,90.00000001 +357.99,50.30085681,-2.652790234,10500,0,200.0009685,0,0,0,90.00000001 +358,50.30085681,-2.652762208,10500,0,200.0009685,0,0,0,90.00000001 +358.01,50.30085681,-2.652734183,10500,0,199.9998535,0,0,0,90.00000001 +358.02,50.30085681,-2.652706158,10500,0,199.9991844,0,0,0,90.00000001 +358.03,50.30085681,-2.652678133,10500,0,199.9998535,0,0,0,90.00000001 +358.04,50.30085681,-2.652650108,10500,0,200.0009685,0,0,0,90.00000001 +358.05,50.30085681,-2.652622082,10500,0,200.0009685,0,0,0,90.00000001 +358.06,50.30085681,-2.652594057,10500,0,199.9998535,0,0,0,90.00000001 +358.07,50.30085681,-2.652566032,10500,0,199.9991844,0,0,0,90.00000001 +358.08,50.30085681,-2.652538007,10500,0,199.9998535,0,0,0,90.00000001 +358.09,50.30085681,-2.652509982,10500,0,200.0009685,0,0,0,90.00000001 +358.1,50.30085681,-2.652481956,10500,0,200.0009685,0,0,0,90.00000001 +358.11,50.30085681,-2.652453931,10500,0,199.9998535,0,0,0,90.00000001 +358.12,50.30085681,-2.652425906,10500,0,199.9991844,0,0,0,90.00000001 +358.13,50.30085681,-2.652397881,10500,0,199.9998535,0,0,0,90.00000001 +358.14,50.30085681,-2.652369856,10500,0,200.0009685,0,0,0,90.00000001 +358.15,50.30085681,-2.65234183,10500,0,200.0009685,0,0,0,90.00000001 +358.16,50.30085681,-2.652313805,10500,0,199.9998535,0,0,0,90.00000001 +358.17,50.30085681,-2.65228578,10500,0,199.9989614,0,0,0,90.00000001 +358.18,50.30085681,-2.652257755,10500,0,199.9987384,0,0,0,90.00000001 +358.19,50.30085681,-2.65222973,10500,0,199.9989614,0,0,0,90.00000001 +358.2,50.30085681,-2.652201705,10500,0,199.9998535,0,0,0,90.00000001 +358.21,50.30085681,-2.65217368,10500,0,200.0009685,0,0,0,90.00000001 +358.22,50.30085681,-2.652145654,10500,0,200.0009685,0,0,0,90.00000001 +358.23,50.30085681,-2.652117629,10500,0,199.9998535,0,0,0,90.00000001 +358.24,50.30085681,-2.652089604,10500,0,199.9989614,0,0,0,90.00000001 +358.25,50.30085681,-2.652061579,10500,0,199.9989614,0,0,0,90.00000001 +358.26,50.30085681,-2.652033554,10500,0,199.9998535,0,0,0,90.00000001 +358.27,50.30085681,-2.652005529,10500,0,200.0009685,0,0,0,90.00000001 +358.28,50.30085681,-2.651977503,10500,0,200.0009685,0,0,0,90.00000001 +358.29,50.30085681,-2.651949478,10500,0,199.9998535,0,0,0,90.00000001 +358.3,50.30085681,-2.651921453,10500,0,199.9989614,0,0,0,90.00000001 +358.31,50.30085681,-2.651893428,10500,0,199.9989614,0,0,0,90.00000001 +358.32,50.30085681,-2.651865403,10500,0,199.9998535,0,0,0,90.00000001 +358.33,50.30085681,-2.651837378,10500,0,200.0009685,0,0,0,90.00000001 +358.34,50.30085681,-2.651809352,10500,0,200.0009685,0,0,0,90.00000001 +358.35,50.30085681,-2.651781327,10500,0,199.9998535,0,0,0,90.00000001 +358.36,50.30085681,-2.651753302,10500,0,199.9989614,0,0,0,90.00000001 +358.37,50.30085681,-2.651725277,10500,0,199.9989614,0,0,0,90.00000001 +358.38,50.30085681,-2.651697252,10500,0,199.9998535,0,0,0,90.00000001 +358.39,50.30085681,-2.651669227,10500,0,200.0009685,0,0,0,90.00000001 +358.4,50.30085681,-2.651641201,10500,0,200.0009685,0,0,0,90.00000001 +358.41,50.30085681,-2.651613176,10500,0,199.9998535,0,0,0,90.00000001 +358.42,50.30085681,-2.651585151,10500,0,199.9989614,0,0,0,90.00000001 +358.43,50.30085681,-2.651557126,10500,0,199.9989614,0,0,0,90.00000001 +358.44,50.30085681,-2.651529101,10500,0,199.9998535,0,0,0,90.00000001 +358.45,50.30085681,-2.651501076,10500,0,200.0009685,0,0,0,90.00000001 +358.46,50.30085681,-2.65147305,10500,0,200.0009685,0,0,0,90.00000001 +358.47,50.30085681,-2.651445025,10500,0,199.9998535,0,0,0,90.00000001 +358.48,50.30085681,-2.651417,10500,0,199.9989614,0,0,0,90.00000001 +358.49,50.30085681,-2.651388975,10500,0,199.9989614,0,0,0,90.00000001 +358.5,50.30085681,-2.65136095,10500,0,199.9998535,0,0,0,90.00000001 +358.51,50.30085681,-2.651332925,10500,0,200.0009685,0,0,0,90.00000001 +358.52,50.30085681,-2.651304899,10500,0,200.0009685,0,0,0,90.00000001 +358.53,50.30085681,-2.651276874,10500,0,199.9998535,0,0,0,90.00000001 +358.54,50.30085681,-2.651248849,10500,0,199.9991844,0,0,0,90.00000001 +358.55,50.30085681,-2.651220824,10500,0,199.9998535,0,0,0,90.00000001 +358.56,50.30085681,-2.651192799,10500,0,200.0009685,0,0,0,90.00000001 +358.57,50.30085681,-2.651164773,10500,0,200.0009685,0,0,0,90.00000001 +358.58,50.30085681,-2.651136748,10500,0,199.9998535,0,0,0,90.00000001 +358.59,50.30085681,-2.651108723,10500,0,199.9991844,0,0,0,90.00000001 +358.6,50.30085681,-2.651080698,10500,0,199.9998535,0,0,0,90.00000001 +358.61,50.30085681,-2.651052673,10500,0,200.0009685,0,0,0,90.00000001 +358.62,50.30085681,-2.651024647,10500,0,200.0009685,0,0,0,90.00000001 +358.63,50.30085681,-2.650996622,10500,0,199.9998535,0,0,0,90.00000001 +358.64,50.30085681,-2.650968597,10500,0,199.9991844,0,0,0,90.00000001 +358.65,50.30085681,-2.650940572,10500,0,199.9998535,0,0,0,90.00000001 +358.66,50.30085681,-2.650912547,10500,0,200.0009685,0,0,0,90.00000001 +358.67,50.30085681,-2.650884521,10500,0,200.0009685,0,0,0,90.00000001 +358.68,50.30085681,-2.650856496,10500,0,199.9998535,0,0,0,90.00000001 +358.69,50.30085681,-2.650828471,10500,0,199.9991844,0,0,0,90.00000001 +358.7,50.30085681,-2.650800446,10500,0,199.9998535,0,0,0,90.00000001 +358.71,50.30085681,-2.650772421,10500,0,200.0009685,0,0,0,90.00000001 +358.72,50.30085681,-2.650744395,10500,0,200.0009685,0,0,0,90.00000001 +358.73,50.30085681,-2.65071637,10500,0,199.9998535,0,0,0,90.00000001 +358.74,50.30085681,-2.650688345,10500,0,199.9989614,0,0,0,90.00000001 +358.75,50.30085681,-2.65066032,10500,0,199.9989614,0,0,0,90.00000001 +358.76,50.30085681,-2.650632295,10500,0,199.9998535,0,0,0,90.00000001 +358.77,50.30085681,-2.65060427,10500,0,200.0009685,0,0,0,90.00000001 +358.78,50.30085681,-2.650576244,10500,0,200.0009685,0,0,0,90.00000001 +358.79,50.30085681,-2.650548219,10500,0,199.9998535,0,0,0,90.00000001 +358.8,50.30085681,-2.650520194,10500,0,199.9989614,0,0,0,90.00000001 +358.81,50.30085681,-2.650492169,10500,0,199.9989614,0,0,0,90.00000001 +358.82,50.30085681,-2.650464144,10500,0,199.9998535,0,0,0,90.00000001 +358.83,50.30085681,-2.650436119,10500,0,200.0009685,0,0,0,90.00000001 +358.84,50.30085681,-2.650408093,10500,0,200.0009685,0,0,0,90.00000001 +358.85,50.30085681,-2.650380068,10500,0,199.9998535,0,0,0,90.00000001 +358.86,50.30085681,-2.650352043,10500,0,199.9989614,0,0,0,90.00000001 +358.87,50.30085681,-2.650324018,10500,0,199.9989614,0,0,0,90.00000001 +358.88,50.30085681,-2.650295993,10500,0,199.9998535,0,0,0,90.00000001 +358.89,50.30085681,-2.650267968,10500,0,200.0009685,0,0,0,90.00000001 +358.9,50.30085681,-2.650239942,10500,0,200.0009685,0,0,0,90.00000001 +358.91,50.30085681,-2.650211917,10500,0,199.9998535,0,0,0,90.00000001 +358.92,50.30085681,-2.650183892,10500,0,199.9989614,0,0,0,90.00000001 +358.93,50.30085681,-2.650155867,10500,0,199.9989614,0,0,0,90.00000001 +358.94,50.30085681,-2.650127842,10500,0,199.9998535,0,0,0,90.00000001 +358.95,50.30085681,-2.650099817,10500,0,200.0009685,0,0,0,90.00000001 +358.96,50.30085681,-2.650071791,10500,0,200.0009685,0,0,0,90.00000001 +358.97,50.30085681,-2.650043766,10500,0,199.9998535,0,0,0,90.00000001 +358.98,50.30085681,-2.650015741,10500,0,199.9989614,0,0,0,90.00000001 +358.99,50.30085681,-2.649987716,10500,0,199.9989614,0,0,0,90.00000001 +359,50.30085681,-2.649959691,10500,0,199.9998535,0,0,0,90.00000001 +359.01,50.30085681,-2.649931666,10500,0,200.0009685,0,0,0,90.00000001 +359.02,50.30085681,-2.64990364,10500,0,200.0009685,0,0,0,90.00000001 +359.03,50.30085681,-2.649875615,10500,0,199.9998535,0,0,0,90.00000001 +359.04,50.30085681,-2.64984759,10500,0,199.9989614,0,0,0,90.00000001 +359.05,50.30085681,-2.649819565,10500,0,199.9987384,0,0,0,90.00000001 +359.06,50.30085681,-2.64979154,10500,0,199.9989614,0,0,0,90.00000001 +359.07,50.30085681,-2.649763515,10500,0,199.9998535,0,0,0,90.00000001 +359.08,50.30085681,-2.64973549,10500,0,200.0009685,0,0,0,90.00000001 +359.09,50.30085681,-2.649707464,10500,0,200.0009685,0,0,0,90.00000001 +359.1,50.30085681,-2.649679439,10500,0,199.9998535,0,0,0,90.00000001 +359.11,50.30085681,-2.649651414,10500,0,199.9991844,0,0,0,90.00000001 +359.12,50.30085681,-2.649623389,10500,0,199.9998535,0,0,0,90.00000001 +359.13,50.30085681,-2.649595364,10500,0,200.0009685,0,0,0,90.00000001 +359.14,50.30085681,-2.649567338,10500,0,200.0009685,0,0,0,90.00000001 +359.15,50.30085681,-2.649539313,10500,0,199.9998535,0,0,0,90.00000001 +359.16,50.30085681,-2.649511288,10500,0,199.9991844,0,0,0,90.00000001 +359.17,50.30085681,-2.649483263,10500,0,199.9998535,0,0,0,90.00000001 +359.18,50.30085681,-2.649455238,10500,0,200.0009685,0,0,0,90.00000001 +359.19,50.30085681,-2.649427212,10500,0,200.0009685,0,0,0,90.00000001 +359.2,50.30085681,-2.649399187,10500,0,199.9998535,0,0,0,90.00000001 +359.21,50.30085681,-2.649371162,10500,0,199.9989614,0,0,0,90.00000001 +359.22,50.30085681,-2.649343137,10500,0,199.9989614,0,0,0,90.00000001 +359.23,50.30085681,-2.649315112,10500,0,199.9998535,0,0,0,90.00000001 +359.24,50.30085681,-2.649287087,10500,0,200.0009685,0,0,0,90.00000001 +359.25,50.30085681,-2.649259061,10500,0,200.0009685,0,0,0,90.00000001 +359.26,50.30085681,-2.649231036,10500,0,199.9998535,0,0,0,90.00000001 +359.27,50.30085681,-2.649203011,10500,0,199.9991844,0,0,0,90.00000001 +359.28,50.30085681,-2.649174986,10500,0,199.9998535,0,0,0,90.00000001 +359.29,50.30085681,-2.649146961,10500,0,200.0009685,0,0,0,90.00000001 +359.3,50.30085681,-2.649118935,10500,0,200.0009685,0,0,0,90.00000001 +359.31,50.30085681,-2.64909091,10500,0,199.9998535,0,0,0,90.00000001 +359.32,50.30085681,-2.649062885,10500,0,199.9991844,0,0,0,90.00000001 +359.33,50.30085681,-2.64903486,10500,0,199.9998535,0,0,0,90.00000001 +359.34,50.30085681,-2.649006835,10500,0,200.0009685,0,0,0,90.00000001 +359.35,50.30085681,-2.648978809,10500,0,200.0009685,0,0,0,90.00000001 +359.36,50.30085681,-2.648950784,10500,0,199.9998535,0,0,0,90.00000001 +359.37,50.30085681,-2.648922759,10500,0,199.9991844,0,0,0,90.00000001 +359.38,50.30085681,-2.648894734,10500,0,199.9998535,0,0,0,90.00000001 +359.39,50.30085681,-2.648866709,10500,0,200.0009685,0,0,0,90.00000001 +359.4,50.30085681,-2.648838683,10500,0,200.0009685,0,0,0,90.00000001 +359.41,50.30085681,-2.648810658,10500,0,199.9998535,0,0,0,90.00000001 +359.42,50.30085681,-2.648782633,10500,0,199.9989614,0,0,0,90.00000001 +359.43,50.30085681,-2.648754608,10500,0,199.9989614,0,0,0,90.00000001 +359.44,50.30085681,-2.648726583,10500,0,199.9998535,0,0,0,90.00000001 +359.45,50.30085681,-2.648698558,10500,0,200.0009685,0,0,0,90.00000001 +359.46,50.30085681,-2.648670532,10500,0,200.0009685,0,0,0,90.00000001 +359.47,50.30085681,-2.648642507,10500,0,199.9998535,0,0,0,90.00000001 +359.48,50.30085681,-2.648614482,10500,0,199.9989614,0,0,0,90.00000001 +359.49,50.30085681,-2.648586457,10500,0,199.9989614,0,0,0,90.00000001 +359.5,50.30085681,-2.648558432,10500,0,199.9998535,0,0,0,90.00000001 +359.51,50.30085681,-2.648530407,10500,0,200.0009685,0,0,0,90.00000001 +359.52,50.30085681,-2.648502381,10500,0,200.0009685,0,0,0,90.00000001 +359.53,50.30085681,-2.648474356,10500,0,199.9998535,0,0,0,90.00000001 +359.54,50.30085681,-2.648446331,10500,0,199.9989614,0,0,0,90.00000001 +359.55,50.30085681,-2.648418306,10500,0,199.9989614,0,0,0,90.00000001 +359.56,50.30085681,-2.648390281,10500,0,199.9998535,0,0,0,90.00000001 +359.57,50.30085681,-2.648362256,10500,0,200.0009685,0,0,0,90.00000001 +359.58,50.30085681,-2.64833423,10500,0,200.0009685,0,0,0,90.00000001 +359.59,50.30085681,-2.648306205,10500,0,199.9998535,0,0,0,90.00000001 +359.6,50.30085681,-2.64827818,10500,0,199.9989614,0,0,0,90.00000001 +359.61,50.30085681,-2.648250155,10500,0,199.9987384,0,0,0,90.00000001 +359.62,50.30085681,-2.64822213,10500,0,199.9989614,0,0,0,90.00000001 +359.63,50.30085681,-2.648194105,10500,0,199.9998535,0,0,0,90.00000001 +359.64,50.30085681,-2.64816608,10500,0,200.0009685,0,0,0,90.00000001 +359.65,50.30085681,-2.648138054,10500,0,200.0009685,0,0,0,90.00000001 +359.66,50.30085681,-2.648110029,10500,0,199.9998535,0,0,0,90.00000001 +359.67,50.30085681,-2.648082004,10500,0,199.9989614,0,0,0,90.00000001 +359.68,50.30085681,-2.648053979,10500,0,199.9989614,0,0,0,90.00000001 +359.69,50.30085681,-2.648025954,10500,0,199.9998535,0,0,0,90.00000001 +359.7,50.30085681,-2.647997929,10500,0,200.0009685,0,0,0,90.00000001 +359.71,50.30085681,-2.647969903,10500,0,200.0009685,0,0,0,90.00000001 +359.72,50.30085681,-2.647941878,10500,0,199.9998535,0,0,0,90.00000001 +359.73,50.30085681,-2.647913853,10500,0,199.9989614,0,0,0,90.00000001 +359.74,50.30085681,-2.647885828,10500,0,199.9989614,0,0,0,90.00000001 +359.75,50.30085681,-2.647857803,10500,0,199.9998535,0,0,0,90.00000001 +359.76,50.30085681,-2.647829778,10500,0,200.0009685,0,0,0,90.00000001 +359.77,50.30085681,-2.647801752,10500,0,200.0009685,0,0,0,90.00000001 +359.78,50.30085681,-2.647773727,10500,0,199.9998535,0,0,0,90.00000001 +359.79,50.30085681,-2.647745702,10500,0,199.9991844,0,0,0,90.00000001 +359.8,50.30085681,-2.647717677,10500,0,199.9998535,0,0,0,90.00000001 +359.81,50.30085681,-2.647689652,10500,0,200.0009685,0,0,0,90.00000001 +359.82,50.30085681,-2.647661626,10500,0,200.0009685,0,0,0,90.00000001 +359.83,50.30085681,-2.647633601,10500,0,199.9998535,0,0,0,90.00000001 +359.84,50.30085681,-2.647605576,10500,0,199.9991844,0,0,0,90.00000001 +359.85,50.30085681,-2.647577551,10500,0,199.9998535,0,0,0,90.00000001 +359.86,50.30085681,-2.647549526,10500,0,200.0009685,0,0,0,90.00000001 +359.87,50.30085681,-2.6475215,10500,0,200.0009685,0,0,0,90.00000001 +359.88,50.30085681,-2.647493475,10500,0,199.9998535,0,0,0,90.00000001 +359.89,50.30085681,-2.64746545,10500,0,199.9991844,0,0,0,90.00000001 +359.9,50.30085681,-2.647437425,10500,0,199.9998535,0,0,0,90.00000001 +359.91,50.30085681,-2.6474094,10500,0,200.0009685,0,0,0,90.00000001 +359.92,50.30085681,-2.647381374,10500,0,200.0009685,0,0,0,90.00000001 +359.93,50.30085681,-2.647353349,10500,0,199.9998535,0,0,0,90.00000001 +359.94,50.30085681,-2.647325324,10500,0,199.9991844,0,0,0,90.00000001 +359.95,50.30085681,-2.647297299,10500,0,199.9998535,0,0,0,90.00000001 +359.96,50.30085681,-2.647269274,10500,0,200.0009685,0,0,0,90.00000001 +359.97,50.30085681,-2.647241248,10500,0,200.0009685,0,0,0,90.00000001 +359.98,50.30085681,-2.647213223,10500,0,199.9998535,0,0,0,90.00000001 +359.99,50.30085681,-2.647185198,10500,0,199.9991844,0,0,0,90.00000001 +360,50.30085681,-2.647157173,10500,0,199.9998535,0,0,0,90.00000001 +360.01,50.30085681,-2.647129148,10500,0,200.0009685,0,0,0,90.00000001 +360.02,50.30085681,-2.647101122,10500,0,200.0009685,0,0,0,90.00000001 +360.03,50.30085681,-2.647073097,10500,0,199.9998535,0,0,0,90.00000001 +360.04,50.30085681,-2.647045072,10500,0,199.9989614,0,0,0,90.00000001 +360.05,50.30085681,-2.647017047,10500,0,199.9989614,0,0,0,90.00000001 +360.06,50.30085681,-2.646989022,10500,0,199.9998535,0,0,0,90.00000001 +360.07,50.30085681,-2.646960997,10500,0,200.0009685,0,0,0,90.00000001 +360.08,50.30085681,-2.646932971,10500,0,200.0009685,0,0,0,90.00000001 +360.09,50.30085681,-2.646904946,10500,0,199.9998535,0,0,0,90.00000001 +360.1,50.30085681,-2.646876921,10500,0,199.9989614,0,0,0,90.00000001 +360.11,50.30085681,-2.646848896,10500,0,199.9989614,0,0,0,90.00000001 +360.12,50.30085681,-2.646820871,10500,0,199.9998535,0,0,0,90.00000001 +360.13,50.30085681,-2.646792846,10500,0,200.0009685,0,0,0,90.00000001 +360.14,50.30085681,-2.64676482,10500,0,200.0009685,0,0,0,90.00000001 +360.15,50.30085681,-2.646736795,10500,0,199.9998535,0,0,0,90.00000001 +360.16,50.30085681,-2.64670877,10500,0,199.9989614,0,0,0,90.00000001 +360.17,50.30085681,-2.646680745,10500,0,199.9987384,0,0,0,90.00000001 +360.18,50.30085681,-2.64665272,10500,0,199.9989614,0,0,0,90.00000001 +360.19,50.30085681,-2.646624695,10500,0,199.9998535,0,0,0,90.00000001 +360.2,50.30085681,-2.64659667,10500,0,200.0009685,0,0,0,90.00000001 +360.21,50.30085681,-2.646568644,10500,0,200.0009685,0,0,0,90.00000001 +360.22,50.30085681,-2.646540619,10500,0,199.9998535,0,0,0,90.00000001 +360.23,50.30085681,-2.646512594,10500,0,199.9989614,0,0,0,90.00000001 +360.24,50.30085681,-2.646484569,10500,0,199.9989614,0,0,0,90.00000001 +360.25,50.30085681,-2.646456544,10500,0,199.9998535,0,0,0,90.00000001 +360.26,50.30085681,-2.646428519,10500,0,200.0009685,0,0,0,90.00000001 +360.27,50.30085681,-2.646400493,10500,0,200.0009685,0,0,0,90.00000001 +360.28,50.30085681,-2.646372468,10500,0,199.9998535,0,0,0,90.00000001 +360.29,50.30085681,-2.646344443,10500,0,199.9989614,0,0,0,90.00000001 +360.3,50.30085681,-2.646316418,10500,0,199.9989614,0,0,0,90.00000001 +360.31,50.30085681,-2.646288393,10500,0,199.9998535,0,0,0,90.00000001 +360.32,50.30085681,-2.646260368,10500,0,200.0009685,0,0,0,90.00000001 +360.33,50.30085681,-2.646232342,10500,0,200.0009685,0,0,0,90.00000001 +360.34,50.30085681,-2.646204317,10500,0,199.9998535,0,0,0,90.00000001 +360.35,50.30085681,-2.646176292,10500,0,199.9989614,0,0,0,90.00000001 +360.36,50.30085681,-2.646148267,10500,0,199.9989614,0,0,0,90.00000001 +360.37,50.30085681,-2.646120242,10500,0,199.9998535,0,0,0,90.00000001 +360.38,50.30085681,-2.646092217,10500,0,200.0009685,0,0,0,90.00000001 +360.39,50.30085681,-2.646064191,10500,0,200.0009685,0,0,0,90.00000001 +360.4,50.30085681,-2.646036166,10500,0,199.9998535,0,0,0,90.00000001 +360.41,50.30085681,-2.646008141,10500,0,199.9991844,0,0,0,90.00000001 +360.42,50.30085681,-2.645980116,10500,0,199.9998535,0,0,0,90.00000001 +360.43,50.30085681,-2.645952091,10500,0,200.0009685,0,0,0,90.00000001 +360.44,50.30085681,-2.645924065,10500,0,200.0009685,0,0,0,90.00000001 +360.45,50.30085681,-2.64589604,10500,0,199.9998535,0,0,0,90.00000001 +360.46,50.30085681,-2.645868015,10500,0,199.9991844,0,0,0,90.00000001 +360.47,50.30085681,-2.64583999,10500,0,199.9998535,0,0,0,90.00000001 +360.48,50.30085681,-2.645811965,10500,0,200.0009685,0,0,0,90.00000001 +360.49,50.30085681,-2.645783939,10500,0,200.0009685,0,0,0,90.00000001 +360.5,50.30085681,-2.645755914,10500,0,199.9998535,0,0,0,90.00000001 +360.51,50.30085681,-2.645727889,10500,0,199.9991844,0,0,0,90.00000001 +360.52,50.30085681,-2.645699864,10500,0,199.9998535,0,0,0,90.00000001 +360.53,50.30085681,-2.645671839,10500,0,200.0009685,0,0,0,90.00000001 +360.54,50.30085681,-2.645643813,10500,0,200.0009685,0,0,0,90.00000001 +360.55,50.30085681,-2.645615788,10500,0,199.9998535,0,0,0,90.00000001 +360.56,50.30085681,-2.645587763,10500,0,199.9991844,0,0,0,90.00000001 +360.57,50.30085681,-2.645559738,10500,0,199.9998535,0,0,0,90.00000001 +360.58,50.30085681,-2.645531713,10500,0,200.0009685,0,0,0,90.00000001 +360.59,50.30085681,-2.645503687,10500,0,200.0009685,0,0,0,90.00000001 +360.6,50.30085681,-2.645475662,10500,0,199.9998535,0,0,0,90.00000001 +360.61,50.30085681,-2.645447637,10500,0,199.9991844,0,0,0,90.00000001 +360.62,50.30085681,-2.645419612,10500,0,199.9998535,0,0,0,90.00000001 +360.63,50.30085681,-2.645391587,10500,0,200.0009685,0,0,0,90.00000001 +360.64,50.30085681,-2.645363561,10500,0,200.0009685,0,0,0,90.00000001 +360.65,50.30085681,-2.645335536,10500,0,199.9998535,0,0,0,90.00000001 +360.66,50.30085681,-2.645307511,10500,0,199.9989614,0,0,0,90.00000001 +360.67,50.30085681,-2.645279486,10500,0,199.9989614,0,0,0,90.00000001 +360.68,50.30085681,-2.645251461,10500,0,199.9998535,0,0,0,90.00000001 +360.69,50.30085681,-2.645223436,10500,0,200.0009685,0,0,0,90.00000001 +360.7,50.30085681,-2.64519541,10500,0,200.0009685,0,0,0,90.00000001 +360.71,50.30085681,-2.645167385,10500,0,199.9998535,0,0,0,90.00000001 +360.72,50.30085681,-2.64513936,10500,0,199.9989614,0,0,0,90.00000001 +360.73,50.30085681,-2.645111335,10500,0,199.9989614,0,0,0,90.00000001 +360.74,50.30085681,-2.64508331,10500,0,199.9998535,0,0,0,90.00000001 +360.75,50.30085681,-2.645055285,10500,0,200.0009685,0,0,0,90.00000001 +360.76,50.30085681,-2.645027259,10500,0,200.0009685,0,0,0,90.00000001 +360.77,50.30085681,-2.644999234,10500,0,199.9998535,0,0,0,90.00000001 +360.78,50.30085681,-2.644971209,10500,0,199.9989614,0,0,0,90.00000001 +360.79,50.30085681,-2.644943184,10500,0,199.9987384,0,0,0,90.00000001 +360.8,50.30085681,-2.644915159,10500,0,199.9989614,0,0,0,90.00000001 +360.81,50.30085681,-2.644887134,10500,0,199.9998535,0,0,0,90.00000001 +360.82,50.30085681,-2.644859109,10500,0,200.0009685,0,0,0,90.00000001 +360.83,50.30085681,-2.644831083,10500,0,200.0009685,0,0,0,90.00000001 +360.84,50.30085681,-2.644803058,10500,0,199.9998535,0,0,0,90.00000001 +360.85,50.30085681,-2.644775033,10500,0,199.9989614,0,0,0,90.00000001 +360.86,50.30085681,-2.644747008,10500,0,199.9989614,0,0,0,90.00000001 +360.87,50.30085681,-2.644718983,10500,0,199.9998535,0,0,0,90.00000001 +360.88,50.30085681,-2.644690958,10500,0,200.0009685,0,0,0,90.00000001 +360.89,50.30085681,-2.644662932,10500,0,200.0009685,0,0,0,90.00000001 +360.9,50.30085681,-2.644634907,10500,0,199.9998535,0,0,0,90.00000001 +360.91,50.30085681,-2.644606882,10500,0,199.9989614,0,0,0,90.00000001 +360.92,50.30085681,-2.644578857,10500,0,199.9989614,0,0,0,90.00000001 +360.93,50.30085681,-2.644550832,10500,0,199.9998535,0,0,0,90.00000001 +360.94,50.30085681,-2.644522807,10500,0,200.0009685,0,0,0,90.00000001 +360.95,50.30085681,-2.644494781,10500,0,200.0009685,0,0,0,90.00000001 +360.96,50.30085681,-2.644466756,10500,0,199.9998535,0,0,0,90.00000001 +360.97,50.30085681,-2.644438731,10500,0,199.9989614,0,0,0,90.00000001 +360.98,50.30085681,-2.644410706,10500,0,199.9989614,0,0,0,90.00000001 +360.99,50.30085681,-2.644382681,10500,0,199.9998535,0,0,0,90.00000001 +361,50.30085681,-2.644354656,10500,0,200.0009685,0,0,0,90.00000001 +361.01,50.30085681,-2.64432663,10500,0,200.0009685,0,0,0,90.00000001 +361.02,50.30085681,-2.644298605,10500,0,199.9998535,0,0,0,90.00000001 +361.03,50.30085681,-2.64427058,10500,0,199.9991844,0,0,0,90.00000001 +361.04,50.30085681,-2.644242555,10500,0,199.9998535,0,0,0,90.00000001 +361.05,50.30085681,-2.64421453,10500,0,200.0009685,0,0,0,90.00000001 +361.06,50.30085681,-2.644186504,10500,0,200.0009685,0,0,0,90.00000001 +361.07,50.30085681,-2.644158479,10500,0,199.9998535,0,0,0,90.00000001 +361.08,50.30085681,-2.644130454,10500,0,199.9991844,0,0,0,90.00000001 +361.09,50.30085681,-2.644102429,10500,0,199.9998535,0,0,0,90.00000001 +361.1,50.30085681,-2.644074404,10500,0,200.0009685,0,0,0,90.00000001 +361.11,50.30085681,-2.644046378,10500,0,200.0009685,0,0,0,90.00000001 +361.12,50.30085681,-2.644018353,10500,0,199.9998535,0,0,0,90.00000001 +361.13,50.30085681,-2.643990328,10500,0,199.9991844,0,0,0,90.00000001 +361.14,50.30085681,-2.643962303,10500,0,199.9998535,0,0,0,90.00000001 +361.15,50.30085681,-2.643934278,10500,0,200.0009685,0,0,0,90.00000001 +361.16,50.30085681,-2.643906252,10500,0,200.0009685,0,0,0,90.00000001 +361.17,50.30085681,-2.643878227,10500,0,199.9998535,0,0,0,90.00000001 +361.18,50.30085681,-2.643850202,10500,0,199.9991844,0,0,0,90.00000001 +361.19,50.30085681,-2.643822177,10500,0,199.9998535,0,0,0,90.00000001 +361.2,50.30085681,-2.643794152,10500,0,200.0009685,0,0,0,90.00000001 +361.21,50.30085681,-2.643766126,10500,0,200.0009685,0,0,0,90.00000001 +361.22,50.30085681,-2.643738101,10500,0,199.9998535,0,0,0,90.00000001 +361.23,50.30085681,-2.643710076,10500,0,199.9991844,0,0,0,90.00000001 +361.24,50.30085681,-2.643682051,10500,0,199.9998535,0,0,0,90.00000001 +361.25,50.30085681,-2.643654026,10500,0,200.0009685,0,0,0,90.00000001 +361.26,50.30085681,-2.643626,10500,0,200.0009685,0,0,0,90.00000001 +361.27,50.30085681,-2.643597975,10500,0,199.9998535,0,0,0,90.00000001 +361.28,50.30085681,-2.64356995,10500,0,199.9989614,0,0,0,90.00000001 +361.29,50.30085681,-2.643541925,10500,0,199.9989614,0,0,0,90.00000001 +361.3,50.30085681,-2.6435139,10500,0,199.9998535,0,0,0,90.00000001 +361.31,50.30085681,-2.643485875,10500,0,200.0009685,0,0,0,90.00000001 +361.32,50.30085681,-2.643457849,10500,0,200.0009685,0,0,0,90.00000001 +361.33,50.30085681,-2.643429824,10500,0,199.9998535,0,0,0,90.00000001 +361.34,50.30085681,-2.643401799,10500,0,199.9989614,0,0,0,90.00000001 +361.35,50.30085681,-2.643373774,10500,0,199.9987384,0,0,0,90.00000001 +361.36,50.30085681,-2.643345749,10500,0,199.9989614,0,0,0,90.00000001 +361.37,50.30085681,-2.643317724,10500,0,199.9998535,0,0,0,90.00000001 +361.38,50.30085681,-2.643289699,10500,0,200.0009685,0,0,0,90.00000001 +361.39,50.30085681,-2.643261673,10500,0,200.0009685,0,0,0,90.00000001 +361.4,50.30085681,-2.643233648,10500,0,199.9998535,0,0,0,90.00000001 +361.41,50.30085681,-2.643205623,10500,0,199.9989614,0,0,0,90.00000001 +361.42,50.30085681,-2.643177598,10500,0,199.9989614,0,0,0,90.00000001 +361.43,50.30085681,-2.643149573,10500,0,199.9998535,0,0,0,90.00000001 +361.44,50.30085681,-2.643121548,10500,0,200.0009685,0,0,0,90.00000001 +361.45,50.30085681,-2.643093522,10500,0,200.0009685,0,0,0,90.00000001 +361.46,50.30085681,-2.643065497,10500,0,199.9998535,0,0,0,90.00000001 +361.47,50.30085681,-2.643037472,10500,0,199.9989614,0,0,0,90.00000001 +361.48,50.30085681,-2.643009447,10500,0,199.9989614,0,0,0,90.00000001 +361.49,50.30085681,-2.642981422,10500,0,199.9998535,0,0,0,90.00000001 +361.5,50.30085681,-2.642953397,10500,0,200.0009685,0,0,0,90.00000001 +361.51,50.30085681,-2.642925371,10500,0,200.0009685,0,0,0,90.00000001 +361.52,50.30085681,-2.642897346,10500,0,199.9998535,0,0,0,90.00000001 +361.53,50.30085681,-2.642869321,10500,0,199.9989614,0,0,0,90.00000001 +361.54,50.30085681,-2.642841296,10500,0,199.9989614,0,0,0,90.00000001 +361.55,50.30085681,-2.642813271,10500,0,199.9998535,0,0,0,90.00000001 +361.56,50.30085681,-2.642785246,10500,0,200.0009685,0,0,0,90.00000001 +361.57,50.30085681,-2.64275722,10500,0,200.0009685,0,0,0,90.00000001 +361.58,50.30085681,-2.642729195,10500,0,199.9998535,0,0,0,90.00000001 +361.59,50.30085681,-2.64270117,10500,0,199.9989614,0,0,0,90.00000001 +361.6,50.30085681,-2.642673145,10500,0,199.9987384,0,0,0,90.00000001 +361.61,50.30085681,-2.64264512,10500,0,199.9989614,0,0,0,90.00000001 +361.62,50.30085681,-2.642617095,10500,0,199.9998535,0,0,0,90.00000001 +361.63,50.30085681,-2.64258907,10500,0,200.0009685,0,0,0,90.00000001 +361.64,50.30085681,-2.642561044,10500,0,200.0009685,0,0,0,90.00000001 +361.65,50.30085681,-2.642533019,10500,0,199.9998535,0,0,0,90.00000001 +361.66,50.30085681,-2.642504994,10500,0,199.9991844,0,0,0,90.00000001 +361.67,50.30085681,-2.642476969,10500,0,199.9998535,0,0,0,90.00000001 +361.68,50.30085681,-2.642448944,10500,0,200.0009685,0,0,0,90.00000001 +361.69,50.30085681,-2.642420918,10500,0,200.0009685,0,0,0,90.00000001 +361.7,50.30085681,-2.642392893,10500,0,199.9998535,0,0,0,90.00000001 +361.71,50.30085681,-2.642364868,10500,0,199.9991844,0,0,0,90.00000001 +361.72,50.30085681,-2.642336843,10500,0,199.9998535,0,0,0,90.00000001 +361.73,50.30085681,-2.642308818,10500,0,200.0009685,0,0,0,90.00000001 +361.74,50.30085681,-2.642280792,10500,0,200.0009685,0,0,0,90.00000001 +361.75,50.30085681,-2.642252767,10500,0,199.9998535,0,0,0,90.00000001 +361.76,50.30085681,-2.642224742,10500,0,199.9991844,0,0,0,90.00000001 +361.77,50.30085681,-2.642196717,10500,0,199.9998535,0,0,0,90.00000001 +361.78,50.30085681,-2.642168692,10500,0,200.0009685,0,0,0,90.00000001 +361.79,50.30085681,-2.642140666,10500,0,200.0009685,0,0,0,90.00000001 +361.8,50.30085681,-2.642112641,10500,0,199.9998535,0,0,0,90.00000001 +361.81,50.30085681,-2.642084616,10500,0,199.9991844,0,0,0,90.00000001 +361.82,50.30085681,-2.642056591,10500,0,199.9998535,0,0,0,90.00000001 +361.83,50.30085681,-2.642028566,10500,0,200.0009685,0,0,0,90.00000001 +361.84,50.30085681,-2.64200054,10500,0,200.0009685,0,0,0,90.00000001 +361.85,50.30085681,-2.641972515,10500,0,199.9998535,0,0,0,90.00000001 +361.86,50.30085681,-2.64194449,10500,0,199.9991844,0,0,0,90.00000001 +361.87,50.30085681,-2.641916465,10500,0,199.9998535,0,0,0,90.00000001 +361.88,50.30085681,-2.64188844,10500,0,200.0009685,0,0,0,90.00000001 +361.89,50.30085681,-2.641860414,10500,0,200.0009685,0,0,0,90.00000001 +361.9,50.30085681,-2.641832389,10500,0,199.9998535,0,0,0,90.00000001 +361.91,50.30085681,-2.641804364,10500,0,199.9989614,0,0,0,90.00000001 +361.92,50.30085681,-2.641776339,10500,0,199.9989614,0,0,0,90.00000001 +361.93,50.30085681,-2.641748314,10500,0,199.9998535,0,0,0,90.00000001 +361.94,50.30085681,-2.641720289,10500,0,200.0009685,0,0,0,90.00000001 +361.95,50.30085681,-2.641692263,10500,0,200.0009685,0,0,0,90.00000001 +361.96,50.30085681,-2.641664238,10500,0,199.9998535,0,0,0,90.00000001 +361.97,50.30085681,-2.641636213,10500,0,199.9989614,0,0,0,90.00000001 +361.98,50.30085681,-2.641608188,10500,0,199.9989614,0,0,0,90.00000001 +361.99,50.30085681,-2.641580163,10500,0,199.9998535,0,0,0,90.00000001 +362,50.30085681,-2.641552138,10500,0,200.0009685,0,0,0,90.00000001 +362.01,50.30085681,-2.641524112,10500,0,200.0009685,0,0,0,90.00000001 +362.02,50.30085681,-2.641496087,10500,0,199.9998535,0,0,0,90.00000001 +362.03,50.30085681,-2.641468062,10500,0,199.9989614,0,0,0,90.00000001 +362.04,50.30085681,-2.641440037,10500,0,199.9989614,0,0,0,90.00000001 +362.05,50.30085681,-2.641412012,10500,0,199.9998535,0,0,0,90.00000001 +362.06,50.30085681,-2.641383987,10500,0,200.0009685,0,0,0,90.00000001 +362.07,50.30085681,-2.641355961,10500,0,200.0009685,0,0,0,90.00000001 +362.08,50.30085681,-2.641327936,10500,0,199.9998535,0,0,0,90.00000001 +362.09,50.30085681,-2.641299911,10500,0,199.9989614,0,0,0,90.00000001 +362.1,50.30085681,-2.641271886,10500,0,199.9989614,0,0,0,90.00000001 +362.11,50.30085681,-2.641243861,10500,0,199.9998535,0,0,0,90.00000001 +362.12,50.30085681,-2.641215836,10500,0,200.0009685,0,0,0,90.00000001 +362.13,50.30085681,-2.64118781,10500,0,200.0009685,0,0,0,90.00000001 +362.14,50.30085681,-2.641159785,10500,0,199.9998535,0,0,0,90.00000001 +362.15,50.30085681,-2.64113176,10500,0,199.9989614,0,0,0,90.00000001 +362.16,50.30085681,-2.641103735,10500,0,199.9989614,0,0,0,90.00000001 +362.17,50.30085681,-2.64107571,10500,0,199.9998535,0,0,0,90.00000001 +362.18,50.30085681,-2.641047685,10500,0,200.0009685,0,0,0,90.00000001 +362.19,50.30085681,-2.641019659,10500,0,200.0009685,0,0,0,90.00000001 +362.2,50.30085681,-2.640991634,10500,0,199.9998535,0,0,0,90.00000001 +362.21,50.30085681,-2.640963609,10500,0,199.9989614,0,0,0,90.00000001 +362.22,50.30085681,-2.640935584,10500,0,199.9987384,0,0,0,90.00000001 +362.23,50.30085681,-2.640907559,10500,0,199.9989614,0,0,0,90.00000001 +362.24,50.30085681,-2.640879534,10500,0,199.9998535,0,0,0,90.00000001 +362.25,50.30085681,-2.640851509,10500,0,200.0009685,0,0,0,90.00000001 +362.26,50.30085681,-2.640823483,10500,0,200.0009685,0,0,0,90.00000001 +362.27,50.30085681,-2.640795458,10500,0,199.9998535,0,0,0,90.00000001 +362.28,50.30085681,-2.640767433,10500,0,199.9991844,0,0,0,90.00000001 +362.29,50.30085681,-2.640739408,10500,0,199.9998535,0,0,0,90.00000001 +362.3,50.30085681,-2.640711383,10500,0,200.0009685,0,0,0,90.00000001 +362.31,50.30085681,-2.640683357,10500,0,200.0009685,0,0,0,90.00000001 +362.32,50.30085681,-2.640655332,10500,0,199.9998535,0,0,0,90.00000001 +362.33,50.30085681,-2.640627307,10500,0,199.9991844,0,0,0,90.00000001 +362.34,50.30085681,-2.640599282,10500,0,199.9998535,0,0,0,90.00000001 +362.35,50.30085681,-2.640571257,10500,0,200.0009685,0,0,0,90.00000001 +362.36,50.30085681,-2.640543231,10500,0,200.0009685,0,0,0,90.00000001 +362.37,50.30085681,-2.640515206,10500,0,199.9998535,0,0,0,90.00000001 +362.38,50.30085681,-2.640487181,10500,0,199.9991844,0,0,0,90.00000001 +362.39,50.30085681,-2.640459156,10500,0,199.9998535,0,0,0,90.00000001 +362.4,50.30085681,-2.640431131,10500,0,200.0009685,0,0,0,90.00000001 +362.41,50.30085681,-2.640403105,10500,0,200.0009685,0,0,0,90.00000001 +362.42,50.30085681,-2.64037508,10500,0,199.9998535,0,0,0,90.00000001 +362.43,50.30085681,-2.640347055,10500,0,199.9991844,0,0,0,90.00000001 +362.44,50.30085681,-2.64031903,10500,0,199.9998535,0,0,0,90.00000001 +362.45,50.30085681,-2.640291005,10500,0,200.0009685,0,0,0,90.00000001 +362.46,50.30085681,-2.640262979,10500,0,200.0009685,0,0,0,90.00000001 +362.47,50.30085681,-2.640234954,10500,0,199.9998535,0,0,0,90.00000001 +362.48,50.30085681,-2.640206929,10500,0,199.9991844,0,0,0,90.00000001 +362.49,50.30085681,-2.640178904,10500,0,199.9998535,0,0,0,90.00000001 +362.5,50.30085681,-2.640150879,10500,0,200.0009685,0,0,0,90.00000001 +362.51,50.30085681,-2.640122853,10500,0,200.0009685,0,0,0,90.00000001 +362.52,50.30085681,-2.640094828,10500,0,199.9998535,0,0,0,90.00000001 +362.53,50.30085681,-2.640066803,10500,0,199.9989614,0,0,0,90.00000001 +362.54,50.30085681,-2.640038778,10500,0,199.9989614,0,0,0,90.00000001 +362.55,50.30085681,-2.640010753,10500,0,199.9998535,0,0,0,90.00000001 +362.56,50.30085681,-2.639982728,10500,0,200.0009685,0,0,0,90.00000001 +362.57,50.30085681,-2.639954702,10500,0,200.0009685,0,0,0,90.00000001 +362.58,50.30085681,-2.639926677,10500,0,199.9998535,0,0,0,90.00000001 +362.59,50.30085681,-2.639898652,10500,0,199.9989614,0,0,0,90.00000001 +362.6,50.30085681,-2.639870627,10500,0,199.9989614,0,0,0,90.00000001 +362.61,50.30085681,-2.639842602,10500,0,199.9998535,0,0,0,90.00000001 +362.62,50.30085681,-2.639814577,10500,0,200.0009685,0,0,0,90.00000001 +362.63,50.30085681,-2.639786551,10500,0,200.0009685,0,0,0,90.00000001 +362.64,50.30085681,-2.639758526,10500,0,199.9998535,0,0,0,90.00000001 +362.65,50.30085681,-2.639730501,10500,0,199.9989614,0,0,0,90.00000001 +362.66,50.30085681,-2.639702476,10500,0,199.9989614,0,0,0,90.00000001 +362.67,50.30085681,-2.639674451,10500,0,199.9998535,0,0,0,90.00000001 +362.68,50.30085681,-2.639646426,10500,0,200.0009685,0,0,0,90.00000001 +362.69,50.30085681,-2.6396184,10500,0,200.0009685,0,0,0,90.00000001 +362.7,50.30085681,-2.639590375,10500,0,199.9998535,0,0,0,90.00000001 +362.71,50.30085681,-2.63956235,10500,0,199.9989614,0,0,0,90.00000001 +362.72,50.30085681,-2.639534325,10500,0,199.9989614,0,0,0,90.00000001 +362.73,50.30085681,-2.6395063,10500,0,199.9998535,0,0,0,90.00000001 +362.74,50.30085681,-2.639478275,10500,0,200.0009685,0,0,0,90.00000001 +362.75,50.30085681,-2.639450249,10500,0,200.0009685,0,0,0,90.00000001 +362.76,50.30085681,-2.639422224,10500,0,199.9998535,0,0,0,90.00000001 +362.77,50.30085681,-2.639394199,10500,0,199.9989614,0,0,0,90.00000001 +362.78,50.30085681,-2.639366174,10500,0,199.9987384,0,0,0,90.00000001 +362.79,50.30085681,-2.639338149,10500,0,199.9989614,0,0,0,90.00000001 +362.8,50.30085681,-2.639310124,10500,0,199.9998535,0,0,0,90.00000001 +362.81,50.30085681,-2.639282099,10500,0,200.0009685,0,0,0,90.00000001 +362.82,50.30085681,-2.639254073,10500,0,200.0009685,0,0,0,90.00000001 +362.83,50.30085681,-2.639226048,10500,0,199.9998535,0,0,0,90.00000001 +362.84,50.30085681,-2.639198023,10500,0,199.9989614,0,0,0,90.00000001 +362.85,50.30085681,-2.639169998,10500,0,199.9989614,0,0,0,90.00000001 +362.86,50.30085681,-2.639141973,10500,0,199.9998535,0,0,0,90.00000001 +362.87,50.30085681,-2.639113948,10500,0,200.0009685,0,0,0,90.00000001 +362.88,50.30085681,-2.639085922,10500,0,200.0009685,0,0,0,90.00000001 +362.89,50.30085681,-2.639057897,10500,0,199.9998535,0,0,0,90.00000001 +362.9,50.30085681,-2.639029872,10500,0,199.9991844,0,0,0,90.00000001 +362.91,50.30085681,-2.639001847,10500,0,199.9998535,0,0,0,90.00000001 +362.92,50.30085681,-2.638973822,10500,0,200.0009685,0,0,0,90.00000001 +362.93,50.30085681,-2.638945796,10500,0,200.0009685,0,0,0,90.00000001 +362.94,50.30085681,-2.638917771,10500,0,199.9998535,0,0,0,90.00000001 +362.95,50.30085681,-2.638889746,10500,0,199.9991844,0,0,0,90.00000001 +362.96,50.30085681,-2.638861721,10500,0,199.9998535,0,0,0,90.00000001 +362.97,50.30085681,-2.638833696,10500,0,200.0009685,0,0,0,90.00000001 +362.98,50.30085681,-2.63880567,10500,0,200.0009685,0,0,0,90.00000001 +362.99,50.30085681,-2.638777645,10500,0,199.9998535,0,0,0,90.00000001 +363,50.30085681,-2.63874962,10500,0,199.9991844,0,0,0,90.00000001 +363.01,50.30085681,-2.638721595,10500,0,199.9998535,0,0,0,90.00000001 +363.02,50.30085681,-2.63869357,10500,0,200.0009685,0,0,0,90.00000001 +363.03,50.30085681,-2.638665544,10500,0,200.0009685,0,0,0,90.00000001 +363.04,50.30085681,-2.638637519,10500,0,199.9998535,0,0,0,90.00000001 +363.05,50.30085681,-2.638609494,10500,0,199.9991844,0,0,0,90.00000001 +363.06,50.30085681,-2.638581469,10500,0,199.9998535,0,0,0,90.00000001 +363.07,50.30085681,-2.638553444,10500,0,200.0009685,0,0,0,90.00000001 +363.08,50.30085681,-2.638525418,10500,0,200.0009685,0,0,0,90.00000001 +363.09,50.30085681,-2.638497393,10500,0,199.9998535,0,0,0,90.00000001 +363.1,50.30085681,-2.638469368,10500,0,199.9991844,0,0,0,90.00000001 +363.11,50.30085681,-2.638441343,10500,0,199.9998535,0,0,0,90.00000001 +363.12,50.30085681,-2.638413318,10500,0,200.0009685,0,0,0,90.00000001 +363.13,50.30085681,-2.638385292,10500,0,200.0009685,0,0,0,90.00000001 +363.14,50.30085681,-2.638357267,10500,0,199.9998535,0,0,0,90.00000001 +363.15,50.30085681,-2.638329242,10500,0,199.9989614,0,0,0,90.00000001 +363.16,50.30085681,-2.638301217,10500,0,199.9989614,0,0,0,90.00000001 +363.17,50.30085681,-2.638273192,10500,0,199.9998535,0,0,0,90.00000001 +363.18,50.30085681,-2.638245167,10500,0,200.0009685,0,0,0,90.00000001 +363.19,50.30085681,-2.638217141,10500,0,200.0009685,0,0,0,90.00000001 +363.2,50.30085681,-2.638189116,10500,0,199.9998535,0,0,0,90.00000001 +363.21,50.30085681,-2.638161091,10500,0,199.9989614,0,0,0,90.00000001 +363.22,50.30085681,-2.638133066,10500,0,199.9989614,0,0,0,90.00000001 +363.23,50.30085681,-2.638105041,10500,0,199.9998535,0,0,0,90.00000001 +363.24,50.30085681,-2.638077016,10500,0,200.0009685,0,0,0,90.00000001 +363.25,50.30085681,-2.63804899,10500,0,200.0009685,0,0,0,90.00000001 +363.26,50.30085681,-2.638020965,10500,0,199.9998535,0,0,0,90.00000001 +363.27,50.30085681,-2.63799294,10500,0,199.9989614,0,0,0,90.00000001 +363.28,50.30085681,-2.637964915,10500,0,199.9989614,0,0,0,90.00000001 +363.29,50.30085681,-2.63793689,10500,0,199.9998535,0,0,0,90.00000001 +363.3,50.30085681,-2.637908865,10500,0,200.0009685,0,0,0,90.00000001 +363.31,50.30085681,-2.637880839,10500,0,200.0009685,0,0,0,90.00000001 +363.32,50.30085681,-2.637852814,10500,0,199.9998535,0,0,0,90.00000001 +363.33,50.30085681,-2.637824789,10500,0,199.9989614,0,0,0,90.00000001 +363.34,50.30085681,-2.637796764,10500,0,199.9987384,0,0,0,90.00000001 +363.35,50.30085681,-2.637768739,10500,0,199.9989614,0,0,0,90.00000001 +363.36,50.30085681,-2.637740714,10500,0,199.9998535,0,0,0,90.00000001 +363.37,50.30085681,-2.637712689,10500,0,200.0009685,0,0,0,90.00000001 +363.38,50.30085681,-2.637684663,10500,0,200.0009685,0,0,0,90.00000001 +363.39,50.30085681,-2.637656638,10500,0,199.9998535,0,0,0,90.00000001 +363.4,50.30085681,-2.637628613,10500,0,199.9989614,0,0,0,90.00000001 +363.41,50.30085681,-2.637600588,10500,0,199.9989614,0,0,0,90.00000001 +363.42,50.30085681,-2.637572563,10500,0,199.9998535,0,0,0,90.00000001 +363.43,50.30085681,-2.637544538,10500,0,200.0009685,0,0,0,90.00000001 +363.44,50.30085681,-2.637516512,10500,0,200.0009685,0,0,0,90.00000001 +363.45,50.30085681,-2.637488487,10500,0,199.9998535,0,0,0,90.00000001 +363.46,50.30085681,-2.637460462,10500,0,199.9989614,0,0,0,90.00000001 +363.47,50.30085681,-2.637432437,10500,0,199.9989614,0,0,0,90.00000001 +363.48,50.30085681,-2.637404412,10500,0,199.9998535,0,0,0,90.00000001 +363.49,50.30085681,-2.637376387,10500,0,200.0009685,0,0,0,90.00000001 +363.5,50.30085681,-2.637348361,10500,0,200.0009685,0,0,0,90.00000001 +363.51,50.30085681,-2.637320336,10500,0,199.9998535,0,0,0,90.00000001 +363.52,50.30085681,-2.637292311,10500,0,199.9991844,0,0,0,90.00000001 +363.53,50.30085681,-2.637264286,10500,0,199.9998535,0,0,0,90.00000001 +363.54,50.30085681,-2.637236261,10500,0,200.0009685,0,0,0,90.00000001 +363.55,50.30085681,-2.637208235,10500,0,200.0009685,0,0,0,90.00000001 +363.56,50.30085681,-2.63718021,10500,0,199.9998535,0,0,0,90.00000001 +363.57,50.30085681,-2.637152185,10500,0,199.9991844,0,0,0,90.00000001 +363.58,50.30085681,-2.63712416,10500,0,199.9998535,0,0,0,90.00000001 +363.59,50.30085681,-2.637096135,10500,0,200.0009685,0,0,0,90.00000001 +363.6,50.30085681,-2.637068109,10500,0,200.0009685,0,0,0,90.00000001 +363.61,50.30085681,-2.637040084,10500,0,199.9998535,0,0,0,90.00000001 +363.62,50.30085681,-2.637012059,10500,0,199.9991844,0,0,0,90.00000001 +363.63,50.30085681,-2.636984034,10500,0,199.9998535,0,0,0,90.00000001 +363.64,50.30085681,-2.636956009,10500,0,200.0009685,0,0,0,90.00000001 +363.65,50.30085681,-2.636927983,10500,0,200.0009685,0,0,0,90.00000001 +363.66,50.30085681,-2.636899958,10500,0,199.9998535,0,0,0,90.00000001 +363.67,50.30085681,-2.636871933,10500,0,199.9989614,0,0,0,90.00000001 +363.68,50.30085681,-2.636843908,10500,0,199.9989614,0,0,0,90.00000001 +363.69,50.30085681,-2.636815883,10500,0,199.9998535,0,0,0,90.00000001 +363.7,50.30085681,-2.636787858,10500,0,200.0009685,0,0,0,90.00000001 +363.71,50.30085681,-2.636759832,10500,0,200.0009685,0,0,0,90.00000001 +363.72,50.30085681,-2.636731807,10500,0,199.9998535,0,0,0,90.00000001 +363.73,50.30085681,-2.636703782,10500,0,199.9991844,0,0,0,90.00000001 +363.74,50.30085681,-2.636675757,10500,0,199.9998535,0,0,0,90.00000001 +363.75,50.30085681,-2.636647732,10500,0,200.0009685,0,0,0,90.00000001 +363.76,50.30085681,-2.636619706,10500,0,200.0009685,0,0,0,90.00000001 +363.77,50.30085681,-2.636591681,10500,0,199.9998535,0,0,0,90.00000001 +363.78,50.30085681,-2.636563656,10500,0,199.9991844,0,0,0,90.00000001 +363.79,50.30085681,-2.636535631,10500,0,199.9998535,0,0,0,90.00000001 +363.8,50.30085681,-2.636507606,10500,0,200.0009685,0,0,0,90.00000001 +363.81,50.30085681,-2.63647958,10500,0,200.0009685,0,0,0,90.00000001 +363.82,50.30085681,-2.636451555,10500,0,199.9998535,0,0,0,90.00000001 +363.83,50.30085681,-2.63642353,10500,0,199.9989614,0,0,0,90.00000001 +363.84,50.30085681,-2.636395505,10500,0,199.9989614,0,0,0,90.00000001 +363.85,50.30085681,-2.63636748,10500,0,199.9998535,0,0,0,90.00000001 +363.86,50.30085681,-2.636339455,10500,0,200.0009685,0,0,0,90.00000001 +363.87,50.30085681,-2.636311429,10500,0,200.0009685,0,0,0,90.00000001 +363.88,50.30085681,-2.636283404,10500,0,199.9998535,0,0,0,90.00000001 +363.89,50.30085681,-2.636255379,10500,0,199.9989614,0,0,0,90.00000001 +363.9,50.30085681,-2.636227354,10500,0,199.9987384,0,0,0,90.00000001 +363.91,50.30085681,-2.636199329,10500,0,199.9989614,0,0,0,90.00000001 +363.92,50.30085681,-2.636171304,10500,0,199.9998535,0,0,0,90.00000001 +363.93,50.30085681,-2.636143279,10500,0,200.0009685,0,0,0,90.00000001 +363.94,50.30085681,-2.636115253,10500,0,200.0009685,0,0,0,90.00000001 +363.95,50.30085681,-2.636087228,10500,0,199.9998535,0,0,0,90.00000001 +363.96,50.30085681,-2.636059203,10500,0,199.9989614,0,0,0,90.00000001 +363.97,50.30085681,-2.636031178,10500,0,199.9989614,0,0,0,90.00000001 +363.98,50.30085681,-2.636003153,10500,0,199.9998535,0,0,0,90.00000001 +363.99,50.30085681,-2.635975128,10500,0,200.0009685,0,0,0,90.00000001 +364,50.30085681,-2.635947102,10500,0,200.0009685,0,0,0,90.00000001 +364.01,50.30085681,-2.635919077,10500,0,199.9998535,0,0,0,90.00000001 +364.02,50.30085681,-2.635891052,10500,0,199.9989614,0,0,0,90.00000001 +364.03,50.30085681,-2.635863027,10500,0,199.9989614,0,0,0,90.00000001 +364.04,50.30085681,-2.635835002,10500,0,199.9998535,0,0,0,90.00000001 +364.05,50.30085681,-2.635806977,10500,0,200.0009685,0,0,0,90.00000001 +364.06,50.30085681,-2.635778951,10500,0,200.0009685,0,0,0,90.00000001 +364.07,50.30085681,-2.635750926,10500,0,199.9998535,0,0,0,90.00000001 +364.08,50.30085681,-2.635722901,10500,0,199.9989614,0,0,0,90.00000001 +364.09,50.30085681,-2.635694876,10500,0,199.9989614,0,0,0,90.00000001 +364.1,50.30085681,-2.635666851,10500,0,199.9998535,0,0,0,90.00000001 +364.11,50.30085681,-2.635638826,10500,0,200.0009685,0,0,0,90.00000001 +364.12,50.30085681,-2.6356108,10500,0,200.0009685,0,0,0,90.00000001 +364.13,50.30085681,-2.635582775,10500,0,199.9998535,0,0,0,90.00000001 +364.14,50.30085681,-2.63555475,10500,0,199.9989614,0,0,0,90.00000001 +364.15,50.30085681,-2.635526725,10500,0,199.9989614,0,0,0,90.00000001 +364.16,50.30085681,-2.6354987,10500,0,199.9998535,0,0,0,90.00000001 +364.17,50.30085681,-2.635470675,10500,0,200.0009685,0,0,0,90.00000001 +364.18,50.30085681,-2.635442649,10500,0,200.0009685,0,0,0,90.00000001 +364.19,50.30085681,-2.635414624,10500,0,199.9998535,0,0,0,90.00000001 +364.2,50.30085681,-2.635386599,10500,0,199.9991844,0,0,0,90.00000001 +364.21,50.30085681,-2.635358574,10500,0,199.9998535,0,0,0,90.00000001 +364.22,50.30085681,-2.635330549,10500,0,200.0009685,0,0,0,90.00000001 +364.23,50.30085681,-2.635302523,10500,0,200.0009685,0,0,0,90.00000001 +364.24,50.30085681,-2.635274498,10500,0,199.9998535,0,0,0,90.00000001 +364.25,50.30085681,-2.635246473,10500,0,199.9991844,0,0,0,90.00000001 +364.26,50.30085681,-2.635218448,10500,0,199.9998535,0,0,0,90.00000001 +364.27,50.30085681,-2.635190423,10500,0,200.0009685,0,0,0,90.00000001 +364.28,50.30085681,-2.635162397,10500,0,200.0009685,0,0,0,90.00000001 +364.29,50.30085681,-2.635134372,10500,0,199.9998535,0,0,0,90.00000001 +364.3,50.30085681,-2.635106347,10500,0,199.9991844,0,0,0,90.00000001 +364.31,50.30085681,-2.635078322,10500,0,199.9998535,0,0,0,90.00000001 +364.32,50.30085681,-2.635050297,10500,0,200.0009685,0,0,0,90.00000001 +364.33,50.30085681,-2.635022271,10500,0,200.0009685,0,0,0,90.00000001 +364.34,50.30085681,-2.634994246,10500,0,199.9998535,0,0,0,90.00000001 +364.35,50.30085681,-2.634966221,10500,0,199.9991844,0,0,0,90.00000001 +364.36,50.30085681,-2.634938196,10500,0,199.9998535,0,0,0,90.00000001 +364.37,50.30085681,-2.634910171,10500,0,200.0009685,0,0,0,90.00000001 +364.38,50.30085681,-2.634882145,10500,0,200.0009685,0,0,0,90.00000001 +364.39,50.30085681,-2.63485412,10500,0,199.9998535,0,0,0,90.00000001 +364.4,50.30085681,-2.634826095,10500,0,199.9991844,0,0,0,90.00000001 +364.41,50.30085681,-2.63479807,10500,0,199.9998535,0,0,0,90.00000001 +364.42,50.30085681,-2.634770045,10500,0,200.0009685,0,0,0,90.00000001 +364.43,50.30085681,-2.634742019,10500,0,200.0009685,0,0,0,90.00000001 +364.44,50.30085681,-2.634713994,10500,0,199.9998535,0,0,0,90.00000001 +364.45,50.30085681,-2.634685969,10500,0,199.9989614,0,0,0,90.00000001 +364.46,50.30085681,-2.634657944,10500,0,199.9987384,0,0,0,90.00000001 +364.47,50.30085681,-2.634629919,10500,0,199.9989614,0,0,0,90.00000001 +364.48,50.30085681,-2.634601894,10500,0,199.9998535,0,0,0,90.00000001 +364.49,50.30085681,-2.634573869,10500,0,200.0009685,0,0,0,90.00000001 +364.5,50.30085681,-2.634545843,10500,0,200.0009685,0,0,0,90.00000001 +364.51,50.30085681,-2.634517818,10500,0,199.9998535,0,0,0,90.00000001 +364.52,50.30085681,-2.634489793,10500,0,199.9989614,0,0,0,90.00000001 +364.53,50.30085681,-2.634461768,10500,0,199.9989614,0,0,0,90.00000001 +364.54,50.30085681,-2.634433743,10500,0,199.9998535,0,0,0,90.00000001 +364.55,50.30085681,-2.634405718,10500,0,200.0009685,0,0,0,90.00000001 +364.56,50.30085681,-2.634377692,10500,0,200.0009685,0,0,0,90.00000001 +364.57,50.30085681,-2.634349667,10500,0,199.9998535,0,0,0,90.00000001 +364.58,50.30085681,-2.634321642,10500,0,199.9989614,0,0,0,90.00000001 +364.59,50.30085681,-2.634293617,10500,0,199.9989614,0,0,0,90.00000001 +364.6,50.30085681,-2.634265592,10500,0,199.9998535,0,0,0,90.00000001 +364.61,50.30085681,-2.634237567,10500,0,200.0009685,0,0,0,90.00000001 +364.62,50.30085681,-2.634209541,10500,0,200.0009685,0,0,0,90.00000001 +364.63,50.30085681,-2.634181516,10500,0,199.9998535,0,0,0,90.00000001 +364.64,50.30085681,-2.634153491,10500,0,199.9989614,0,0,0,90.00000001 +364.65,50.30085681,-2.634125466,10500,0,199.9989614,0,0,0,90.00000001 +364.66,50.30085681,-2.634097441,10500,0,199.9998535,0,0,0,90.00000001 +364.67,50.30085681,-2.634069416,10500,0,200.0009685,0,0,0,90.00000001 +364.68,50.30085681,-2.63404139,10500,0,200.0009685,0,0,0,90.00000001 +364.69,50.30085681,-2.634013365,10500,0,199.9998535,0,0,0,90.00000001 +364.7,50.30085681,-2.63398534,10500,0,199.9989614,0,0,0,90.00000001 +364.71,50.30085681,-2.633957315,10500,0,199.9989614,0,0,0,90.00000001 +364.72,50.30085681,-2.63392929,10500,0,199.9998535,0,0,0,90.00000001 +364.73,50.30085681,-2.633901265,10500,0,200.0009685,0,0,0,90.00000001 +364.74,50.30085681,-2.633873239,10500,0,200.0009685,0,0,0,90.00000001 +364.75,50.30085681,-2.633845214,10500,0,199.9998535,0,0,0,90.00000001 +364.76,50.30085681,-2.633817189,10500,0,199.9989614,0,0,0,90.00000001 +364.77,50.30085681,-2.633789164,10500,0,199.9989614,0,0,0,90.00000001 +364.78,50.30085681,-2.633761139,10500,0,199.9998535,0,0,0,90.00000001 +364.79,50.30085681,-2.633733114,10500,0,200.0009685,0,0,0,90.00000001 +364.8,50.30085681,-2.633705088,10500,0,200.0009685,0,0,0,90.00000001 +364.81,50.30085681,-2.633677063,10500,0,199.9998535,0,0,0,90.00000001 +364.82,50.30085681,-2.633649038,10500,0,199.9991844,0,0,0,90.00000001 +364.83,50.30085681,-2.633621013,10500,0,199.9998535,0,0,0,90.00000001 +364.84,50.30085681,-2.633592988,10500,0,200.0009685,0,0,0,90.00000001 +364.85,50.30085681,-2.633564962,10500,0,200.0009685,0,0,0,90.00000001 +364.86,50.30085681,-2.633536937,10500,0,199.9998535,0,0,0,90.00000001 +364.87,50.30085681,-2.633508912,10500,0,199.9991844,0,0,0,90.00000001 +364.88,50.30085681,-2.633480887,10500,0,199.9998535,0,0,0,90.00000001 +364.89,50.30085681,-2.633452862,10500,0,200.0009685,0,0,0,90.00000001 +364.9,50.30085681,-2.633424836,10500,0,200.0009685,0,0,0,90.00000001 +364.91,50.30085681,-2.633396811,10500,0,199.9998535,0,0,0,90.00000001 +364.92,50.30085681,-2.633368786,10500,0,199.9991844,0,0,0,90.00000001 +364.93,50.30085681,-2.633340761,10500,0,199.9998535,0,0,0,90.00000001 +364.94,50.30085681,-2.633312736,10500,0,200.0009685,0,0,0,90.00000001 +364.95,50.30085681,-2.63328471,10500,0,200.0009685,0,0,0,90.00000001 +364.96,50.30085681,-2.633256685,10500,0,199.9998535,0,0,0,90.00000001 +364.97,50.30085681,-2.63322866,10500,0,199.9991844,0,0,0,90.00000001 +364.98,50.30085681,-2.633200635,10500,0,199.9998535,0,0,0,90.00000001 +364.99,50.30085681,-2.63317261,10500,0,200.0009685,0,0,0,90.00000001 +365,50.30085681,-2.633144584,10500,0,200.0009685,0,0,0,90.00000001 +365.01,50.30085681,-2.633116559,10500,0,199.9998535,0,0,0,90.00000001 +365.02,50.30085681,-2.633088534,10500,0,199.9991844,0,0,0,90.00000001 +365.03,50.30085681,-2.633060509,10500,0,199.9998535,0,0,0,90.00000001 +365.04,50.30085681,-2.633032484,10500,0,200.0009685,0,0,0,90.00000001 +365.05,50.30085681,-2.633004458,10500,0,200.0009685,0,0,0,90.00000001 +365.06,50.30085681,-2.632976433,10500,0,199.9998535,0,0,0,90.00000001 +365.07,50.30085681,-2.632948408,10500,0,199.9989614,0,0,0,90.00000001 +365.08,50.30085681,-2.632920383,10500,0,199.9987384,0,0,0,90.00000001 +365.09,50.30085681,-2.632892358,10500,0,199.9989614,0,0,0,90.00000001 +365.1,50.30085681,-2.632864333,10500,0,199.9998535,0,0,0,90.00000001 +365.11,50.30085681,-2.632836308,10500,0,200.0009685,0,0,0,90.00000001 +365.12,50.30085681,-2.632808282,10500,0,200.0009685,0,0,0,90.00000001 +365.13,50.30085681,-2.632780257,10500,0,199.9998535,0,0,0,90.00000001 +365.14,50.30085681,-2.632752232,10500,0,199.9989614,0,0,0,90.00000001 +365.15,50.30085681,-2.632724207,10500,0,199.9989614,0,0,0,90.00000001 +365.16,50.30085681,-2.632696182,10500,0,199.9998535,0,0,0,90.00000001 +365.17,50.30085681,-2.632668157,10500,0,200.0009685,0,0,0,90.00000001 +365.18,50.30085681,-2.632640131,10500,0,200.0009685,0,0,0,90.00000001 +365.19,50.30085681,-2.632612106,10500,0,199.9998535,0,0,0,90.00000001 +365.2,50.30085681,-2.632584081,10500,0,199.9989614,0,0,0,90.00000001 +365.21,50.30085681,-2.632556056,10500,0,199.9989614,0,0,0,90.00000001 +365.22,50.30085681,-2.632528031,10500,0,199.9998535,0,0,0,90.00000001 +365.23,50.30085681,-2.632500006,10500,0,200.0009685,0,0,0,90.00000001 +365.24,50.30085681,-2.63247198,10500,0,200.0009685,0,0,0,90.00000001 +365.25,50.30085681,-2.632443955,10500,0,199.9998535,0,0,0,90.00000001 +365.26,50.30085681,-2.63241593,10500,0,199.9989614,0,0,0,90.00000001 +365.27,50.30085681,-2.632387905,10500,0,199.9989614,0,0,0,90.00000001 +365.28,50.30085681,-2.63235988,10500,0,199.9998535,0,0,0,90.00000001 +365.29,50.30085681,-2.632331855,10500,0,200.0009685,0,0,0,90.00000001 +365.3,50.30085681,-2.632303829,10500,0,200.0009685,0,0,0,90.00000001 +365.31,50.30085681,-2.632275804,10500,0,199.9998535,0,0,0,90.00000001 +365.32,50.30085681,-2.632247779,10500,0,199.9989614,0,0,0,90.00000001 +365.33,50.30085681,-2.632219754,10500,0,199.9987384,0,0,0,90.00000001 +365.34,50.30085681,-2.632191729,10500,0,199.9989614,0,0,0,90.00000001 +365.35,50.30085681,-2.632163704,10500,0,199.9998535,0,0,0,90.00000001 +365.36,50.30085681,-2.632135679,10500,0,200.0009685,0,0,0,90.00000001 +365.37,50.30085681,-2.632107653,10500,0,200.0009685,0,0,0,90.00000001 +365.38,50.30085681,-2.632079628,10500,0,199.9998535,0,0,0,90.00000001 +365.39,50.30085681,-2.632051603,10500,0,199.9991844,0,0,0,90.00000001 +365.4,50.30085681,-2.632023578,10500,0,199.9998535,0,0,0,90.00000001 +365.41,50.30085681,-2.631995553,10500,0,200.0009685,0,0,0,90.00000001 +365.42,50.30085681,-2.631967527,10500,0,200.0009685,0,0,0,90.00000001 +365.43,50.30085681,-2.631939502,10500,0,199.9998535,0,0,0,90.00000001 +365.44,50.30085681,-2.631911477,10500,0,199.9991844,0,0,0,90.00000001 +365.45,50.30085681,-2.631883452,10500,0,199.9998535,0,0,0,90.00000001 +365.46,50.30085681,-2.631855427,10500,0,200.0009685,0,0,0,90.00000001 +365.47,50.30085681,-2.631827401,10500,0,200.0009685,0,0,0,90.00000001 +365.48,50.30085681,-2.631799376,10500,0,199.9998535,0,0,0,90.00000001 +365.49,50.30085681,-2.631771351,10500,0,199.9991844,0,0,0,90.00000001 +365.5,50.30085681,-2.631743326,10500,0,199.9998535,0,0,0,90.00000001 +365.51,50.30085681,-2.631715301,10500,0,200.0009685,0,0,0,90.00000001 +365.52,50.30085681,-2.631687275,10500,0,200.0009685,0,0,0,90.00000001 +365.53,50.30085681,-2.63165925,10500,0,199.9998535,0,0,0,90.00000001 +365.54,50.30085681,-2.631631225,10500,0,199.9991844,0,0,0,90.00000001 +365.55,50.30085681,-2.6316032,10500,0,199.9998535,0,0,0,90.00000001 +365.56,50.30085681,-2.631575175,10500,0,200.0009685,0,0,0,90.00000001 +365.57,50.30085681,-2.631547149,10500,0,200.0009685,0,0,0,90.00000001 +365.58,50.30085681,-2.631519124,10500,0,199.9998535,0,0,0,90.00000001 +365.59,50.30085681,-2.631491099,10500,0,199.9991844,0,0,0,90.00000001 +365.6,50.30085681,-2.631463074,10500,0,199.9998535,0,0,0,90.00000001 +365.61,50.30085681,-2.631435049,10500,0,200.0009685,0,0,0,90.00000001 +365.62,50.30085681,-2.631407023,10500,0,200.0009685,0,0,0,90.00000001 +365.63,50.30085681,-2.631378998,10500,0,199.9998535,0,0,0,90.00000001 +365.64,50.30085681,-2.631350973,10500,0,199.9989614,0,0,0,90.00000001 +365.65,50.30085681,-2.631322948,10500,0,199.9989614,0,0,0,90.00000001 +365.66,50.30085681,-2.631294923,10500,0,199.9998535,0,0,0,90.00000001 +365.67,50.30085681,-2.631266898,10500,0,200.0009685,0,0,0,90.00000001 +365.68,50.30085681,-2.631238872,10500,0,200.0009685,0,0,0,90.00000001 +365.69,50.30085681,-2.631210847,10500,0,199.9998535,0,0,0,90.00000001 +365.7,50.30085681,-2.631182822,10500,0,199.9989614,0,0,0,90.00000001 +365.71,50.30085681,-2.631154797,10500,0,199.9989614,0,0,0,90.00000001 +365.72,50.30085681,-2.631126772,10500,0,199.9998535,0,0,0,90.00000001 +365.73,50.30085681,-2.631098747,10500,0,200.0009685,0,0,0,90.00000001 +365.74,50.30085681,-2.631070721,10500,0,200.0009685,0,0,0,90.00000001 +365.75,50.30085681,-2.631042696,10500,0,199.9998535,0,0,0,90.00000001 +365.76,50.30085681,-2.631014671,10500,0,199.9989614,0,0,0,90.00000001 +365.77,50.30085681,-2.630986646,10500,0,199.9989614,0,0,0,90.00000001 +365.78,50.30085681,-2.630958621,10500,0,199.9998535,0,0,0,90.00000001 +365.79,50.30085681,-2.630930596,10500,0,200.0009685,0,0,0,90.00000001 +365.8,50.30085681,-2.63090257,10500,0,200.0009685,0,0,0,90.00000001 +365.81,50.30085681,-2.630874545,10500,0,199.9998535,0,0,0,90.00000001 +365.82,50.30085681,-2.63084652,10500,0,199.9989614,0,0,0,90.00000001 +365.83,50.30085681,-2.630818495,10500,0,199.9989614,0,0,0,90.00000001 +365.84,50.30085681,-2.63079047,10500,0,199.9998535,0,0,0,90.00000001 +365.85,50.30085681,-2.630762445,10500,0,200.0009685,0,0,0,90.00000001 +365.86,50.30085681,-2.630734419,10500,0,200.0009685,0,0,0,90.00000001 +365.87,50.30085681,-2.630706394,10500,0,199.9998535,0,0,0,90.00000001 +365.88,50.30085681,-2.630678369,10500,0,199.9989614,0,0,0,90.00000001 +365.89,50.30085681,-2.630650344,10500,0,199.9987384,0,0,0,90.00000001 +365.9,50.30085681,-2.630622319,10500,0,199.9989614,0,0,0,90.00000001 +365.91,50.30085681,-2.630594294,10500,0,199.9998535,0,0,0,90.00000001 +365.92,50.30085681,-2.630566269,10500,0,200.0009685,0,0,0,90.00000001 +365.93,50.30085681,-2.630538243,10500,0,200.0009685,0,0,0,90.00000001 +365.94,50.30085681,-2.630510218,10500,0,199.9998535,0,0,0,90.00000001 +365.95,50.30085681,-2.630482193,10500,0,199.9989614,0,0,0,90.00000001 +365.96,50.30085681,-2.630454168,10500,0,199.9989614,0,0,0,90.00000001 +365.97,50.30085681,-2.630426143,10500,0,199.9998535,0,0,0,90.00000001 +365.98,50.30085681,-2.630398118,10500,0,200.0009685,0,0,0,90.00000001 +365.99,50.30085681,-2.630370092,10500,0,200.0009685,0,0,0,90.00000001 +366,50.30085681,-2.630342067,10500,0,199.9998535,0,0,0,90.00000001 +366.01,50.30085681,-2.630314042,10500,0,199.9991844,0,0,0,90.00000001 +366.02,50.30085681,-2.630286017,10500,0,199.9998535,0,0,0,90.00000001 +366.03,50.30085681,-2.630257992,10500,0,200.0009685,0,0,0,90.00000001 +366.04,50.30085681,-2.630229966,10500,0,200.0009685,0,0,0,90.00000001 +366.05,50.30085681,-2.630201941,10500,0,199.9998535,0,0,0,90.00000001 +366.06,50.30085681,-2.630173916,10500,0,199.9989614,0,0,0,90.00000001 +366.07,50.30085681,-2.630145891,10500,0,199.9989614,0,0,0,90.00000001 +366.08,50.30085681,-2.630117866,10500,0,199.9998535,0,0,0,90.00000001 +366.09,50.30085681,-2.630089841,10500,0,200.0009685,0,0,0,90.00000001 +366.1,50.30085681,-2.630061815,10500,0,200.0009685,0,0,0,90.00000001 +366.11,50.30085681,-2.63003379,10500,0,199.9998535,0,0,0,90.00000001 +366.12,50.30085681,-2.630005765,10500,0,199.9991844,0,0,0,90.00000001 +366.13,50.30085681,-2.62997774,10500,0,199.9998535,0,0,0,90.00000001 +366.14,50.30085681,-2.629949715,10500,0,200.0009685,0,0,0,90.00000001 +366.15,50.30085681,-2.629921689,10500,0,200.0009685,0,0,0,90.00000001 +366.16,50.30085681,-2.629893664,10500,0,199.9998535,0,0,0,90.00000001 +366.17,50.30085681,-2.629865639,10500,0,199.9991844,0,0,0,90.00000001 +366.18,50.30085681,-2.629837614,10500,0,199.9998535,0,0,0,90.00000001 +366.19,50.30085681,-2.629809589,10500,0,200.0009685,0,0,0,90.00000001 +366.2,50.30085681,-2.629781563,10500,0,200.0009685,0,0,0,90.00000001 +366.21,50.30085681,-2.629753538,10500,0,199.9998535,0,0,0,90.00000001 +366.22,50.30085681,-2.629725513,10500,0,199.9991844,0,0,0,90.00000001 +366.23,50.30085681,-2.629697488,10500,0,199.9998535,0,0,0,90.00000001 +366.24,50.30085681,-2.629669463,10500,0,200.0009685,0,0,0,90.00000001 +366.25,50.30085681,-2.629641437,10500,0,200.0009685,0,0,0,90.00000001 +366.26,50.30085681,-2.629613412,10500,0,199.9998535,0,0,0,90.00000001 +366.27,50.30085681,-2.629585387,10500,0,199.9991844,0,0,0,90.00000001 +366.28,50.30085681,-2.629557362,10500,0,199.9998535,0,0,0,90.00000001 +366.29,50.30085681,-2.629529337,10500,0,200.0009685,0,0,0,90.00000001 +366.3,50.30085681,-2.629501311,10500,0,200.0009685,0,0,0,90.00000001 +366.31,50.30085681,-2.629473286,10500,0,199.9998535,0,0,0,90.00000001 +366.32,50.30085681,-2.629445261,10500,0,199.9989614,0,0,0,90.00000001 +366.33,50.30085681,-2.629417236,10500,0,199.9989614,0,0,0,90.00000001 +366.34,50.30085681,-2.629389211,10500,0,199.9998535,0,0,0,90.00000001 +366.35,50.30085681,-2.629361186,10500,0,200.0009685,0,0,0,90.00000001 +366.36,50.30085681,-2.62933316,10500,0,200.0009685,0,0,0,90.00000001 +366.37,50.30085681,-2.629305135,10500,0,199.9998535,0,0,0,90.00000001 +366.38,50.30085681,-2.62927711,10500,0,199.9989614,0,0,0,90.00000001 +366.39,50.30085681,-2.629249085,10500,0,199.9989614,0,0,0,90.00000001 +366.4,50.30085681,-2.62922106,10500,0,199.9998535,0,0,0,90.00000001 +366.41,50.30085681,-2.629193035,10500,0,200.0009685,0,0,0,90.00000001 +366.42,50.30085681,-2.629165009,10500,0,200.0009685,0,0,0,90.00000001 +366.43,50.30085681,-2.629136984,10500,0,199.9998535,0,0,0,90.00000001 +366.44,50.30085681,-2.629108959,10500,0,199.9989614,0,0,0,90.00000001 +366.45,50.30085681,-2.629080934,10500,0,199.9989614,0,0,0,90.00000001 +366.46,50.30085681,-2.629052909,10500,0,199.9998535,0,0,0,90.00000001 +366.47,50.30085681,-2.629024884,10500,0,200.0009685,0,0,0,90.00000001 +366.48,50.30085681,-2.628996858,10500,0,200.0009685,0,0,0,90.00000001 +366.49,50.30085681,-2.628968833,10500,0,199.9998535,0,0,0,90.00000001 +366.5,50.30085681,-2.628940808,10500,0,199.9989614,0,0,0,90.00000001 +366.51,50.30085681,-2.628912783,10500,0,199.9987384,0,0,0,90.00000001 +366.52,50.30085681,-2.628884758,10500,0,199.9989614,0,0,0,90.00000001 +366.53,50.30085681,-2.628856733,10500,0,199.9998535,0,0,0,90.00000001 +366.54,50.30085681,-2.628828708,10500,0,200.0009685,0,0,0,90.00000001 +366.55,50.30085681,-2.628800682,10500,0,200.0009685,0,0,0,90.00000001 +366.56,50.30085681,-2.628772657,10500,0,199.9998535,0,0,0,90.00000001 +366.57,50.30085681,-2.628744632,10500,0,199.9989614,0,0,0,90.00000001 +366.58,50.30085681,-2.628716607,10500,0,199.9989614,0,0,0,90.00000001 +366.59,50.30085681,-2.628688582,10500,0,199.9998535,0,0,0,90.00000001 +366.6,50.30085681,-2.628660557,10500,0,200.0009685,0,0,0,90.00000001 +366.61,50.30085681,-2.628632531,10500,0,200.0009685,0,0,0,90.00000001 +366.62,50.30085681,-2.628604506,10500,0,199.9998535,0,0,0,90.00000001 +366.63,50.30085681,-2.628576481,10500,0,199.9989614,0,0,0,90.00000001 +366.64,50.30085681,-2.628548456,10500,0,199.9989614,0,0,0,90.00000001 +366.65,50.30085681,-2.628520431,10500,0,199.9998535,0,0,0,90.00000001 +366.66,50.30085681,-2.628492406,10500,0,200.0009685,0,0,0,90.00000001 +366.67,50.30085681,-2.62846438,10500,0,200.0009685,0,0,0,90.00000001 +366.68,50.30085681,-2.628436355,10500,0,199.9998535,0,0,0,90.00000001 +366.69,50.30085681,-2.62840833,10500,0,199.9991844,0,0,0,90.00000001 +366.7,50.30085681,-2.628380305,10500,0,199.9998535,0,0,0,90.00000001 +366.71,50.30085681,-2.62835228,10500,0,200.0009685,0,0,0,90.00000001 +366.72,50.30085681,-2.628324254,10500,0,200.0009685,0,0,0,90.00000001 +366.73,50.30085681,-2.628296229,10500,0,199.9998535,0,0,0,90.00000001 +366.74,50.30085681,-2.628268204,10500,0,199.9991844,0,0,0,90.00000001 +366.75,50.30085681,-2.628240179,10500,0,199.9998535,0,0,0,90.00000001 +366.76,50.30085681,-2.628212154,10500,0,200.0009685,0,0,0,90.00000001 +366.77,50.30085681,-2.628184128,10500,0,200.0009685,0,0,0,90.00000001 +366.78,50.30085681,-2.628156103,10500,0,199.9998535,0,0,0,90.00000001 +366.79,50.30085681,-2.628128078,10500,0,199.9991844,0,0,0,90.00000001 +366.8,50.30085681,-2.628100053,10500,0,199.9998535,0,0,0,90.00000001 +366.81,50.30085681,-2.628072028,10500,0,200.0009685,0,0,0,90.00000001 +366.82,50.30085681,-2.628044002,10500,0,200.0009685,0,0,0,90.00000001 +366.83,50.30085681,-2.628015977,10500,0,199.9998535,0,0,0,90.00000001 +366.84,50.30085681,-2.627987952,10500,0,199.9991844,0,0,0,90.00000001 +366.85,50.30085681,-2.627959927,10500,0,199.9998535,0,0,0,90.00000001 +366.86,50.30085681,-2.627931902,10500,0,200.0009685,0,0,0,90.00000001 +366.87,50.30085681,-2.627903876,10500,0,200.0009685,0,0,0,90.00000001 +366.88,50.30085681,-2.627875851,10500,0,199.9998535,0,0,0,90.00000001 +366.89,50.30085681,-2.627847826,10500,0,199.9991844,0,0,0,90.00000001 +366.9,50.30085681,-2.627819801,10500,0,199.9998535,0,0,0,90.00000001 +366.91,50.30085681,-2.627791776,10500,0,200.0009685,0,0,0,90.00000001 +366.92,50.30085681,-2.62776375,10500,0,200.0009685,0,0,0,90.00000001 +366.93,50.30085681,-2.627735725,10500,0,199.9998535,0,0,0,90.00000001 +366.94,50.30085681,-2.6277077,10500,0,199.9989614,0,0,0,90.00000001 +366.95,50.30085681,-2.627679675,10500,0,199.9989614,0,0,0,90.00000001 +366.96,50.30085681,-2.62765165,10500,0,199.9998535,0,0,0,90.00000001 +366.97,50.30085681,-2.627623625,10500,0,200.0009685,0,0,0,90.00000001 +366.98,50.30085681,-2.627595599,10500,0,200.0009685,0,0,0,90.00000001 +366.99,50.30085681,-2.627567574,10500,0,199.9998535,0,0,0,90.00000001 +367,50.30085681,-2.627539549,10500,0,199.9989614,0,0,0,90.00000001 +367.01,50.30085681,-2.627511524,10500,0,199.9989614,0,0,0,90.00000001 +367.02,50.30085681,-2.627483499,10500,0,199.9998535,0,0,0,90.00000001 +367.03,50.30085681,-2.627455474,10500,0,200.0009685,0,0,0,90.00000001 +367.04,50.30085681,-2.627427448,10500,0,200.0009685,0,0,0,90.00000001 +367.05,50.30085681,-2.627399423,10500,0,199.9998535,0,0,0,90.00000001 +367.06,50.30085681,-2.627371398,10500,0,199.9989614,0,0,0,90.00000001 +367.07,50.30085681,-2.627343373,10500,0,199.9987384,0,0,0,90.00000001 +367.08,50.30085681,-2.627315348,10500,0,199.9989614,0,0,0,90.00000001 +367.09,50.30085681,-2.627287323,10500,0,199.9998535,0,0,0,90.00000001 +367.1,50.30085681,-2.627259298,10500,0,200.0009685,0,0,0,90.00000001 +367.11,50.30085681,-2.627231272,10500,0,200.0009685,0,0,0,90.00000001 +367.12,50.30085681,-2.627203247,10500,0,199.9998535,0,0,0,90.00000001 +367.13,50.30085681,-2.627175222,10500,0,199.9989614,0,0,0,90.00000001 +367.14,50.30085681,-2.627147197,10500,0,199.9989614,0,0,0,90.00000001 +367.15,50.30085681,-2.627119172,10500,0,199.9998535,0,0,0,90.00000001 +367.16,50.30085681,-2.627091147,10500,0,200.0009685,0,0,0,90.00000001 +367.17,50.30085681,-2.627063121,10500,0,200.0009685,0,0,0,90.00000001 +367.18,50.30085681,-2.627035096,10500,0,199.9998535,0,0,0,90.00000001 +367.19,50.30085681,-2.627007071,10500,0,199.9989614,0,0,0,90.00000001 +367.2,50.30085681,-2.626979046,10500,0,199.9989614,0,0,0,90.00000001 +367.21,50.30085681,-2.626951021,10500,0,199.9998535,0,0,0,90.00000001 +367.22,50.30085681,-2.626922996,10500,0,200.0009685,0,0,0,90.00000001 +367.23,50.30085681,-2.62689497,10500,0,200.0009685,0,0,0,90.00000001 +367.24,50.30085681,-2.626866945,10500,0,199.9998535,0,0,0,90.00000001 +367.25,50.30085681,-2.62683892,10500,0,199.9989614,0,0,0,90.00000001 +367.26,50.30085681,-2.626810895,10500,0,199.9989614,0,0,0,90.00000001 +367.27,50.30085681,-2.62678287,10500,0,199.9998535,0,0,0,90.00000001 +367.28,50.30085681,-2.626754845,10500,0,200.0009685,0,0,0,90.00000001 +367.29,50.30085681,-2.626726819,10500,0,200.0009685,0,0,0,90.00000001 +367.3,50.30085681,-2.626698794,10500,0,199.9998535,0,0,0,90.00000001 +367.31,50.30085681,-2.626670769,10500,0,199.9991844,0,0,0,90.00000001 +367.32,50.30085681,-2.626642744,10500,0,199.9998535,0,0,0,90.00000001 +367.33,50.30085681,-2.626614719,10500,0,200.0009685,0,0,0,90.00000001 +367.34,50.30085681,-2.626586693,10500,0,200.0009685,0,0,0,90.00000001 +367.35,50.30085681,-2.626558668,10500,0,199.9998535,0,0,0,90.00000001 +367.36,50.30085681,-2.626530643,10500,0,199.9991844,0,0,0,90.00000001 +367.37,50.30085681,-2.626502618,10500,0,199.9998535,0,0,0,90.00000001 +367.38,50.30085681,-2.626474593,10500,0,200.0009685,0,0,0,90.00000001 +367.39,50.30085681,-2.626446567,10500,0,200.0009685,0,0,0,90.00000001 +367.4,50.30085681,-2.626418542,10500,0,199.9998535,0,0,0,90.00000001 +367.41,50.30085681,-2.626390517,10500,0,199.9991844,0,0,0,90.00000001 +367.42,50.30085681,-2.626362492,10500,0,199.9998535,0,0,0,90.00000001 +367.43,50.30085681,-2.626334467,10500,0,200.0009685,0,0,0,90.00000001 +367.44,50.30085681,-2.626306441,10500,0,200.0009685,0,0,0,90.00000001 +367.45,50.30085681,-2.626278416,10500,0,199.9998535,0,0,0,90.00000001 +367.46,50.30085681,-2.626250391,10500,0,199.9991844,0,0,0,90.00000001 +367.47,50.30085681,-2.626222366,10500,0,199.9998535,0,0,0,90.00000001 +367.48,50.30085681,-2.626194341,10500,0,200.0009685,0,0,0,90.00000001 +367.49,50.30085681,-2.626166315,10500,0,200.0009685,0,0,0,90.00000001 +367.5,50.30085681,-2.62613829,10500,0,199.9998535,0,0,0,90.00000001 +367.51,50.30085681,-2.626110265,10500,0,199.9991844,0,0,0,90.00000001 +367.52,50.30085681,-2.62608224,10500,0,199.9998535,0,0,0,90.00000001 +367.53,50.30085681,-2.626054215,10500,0,200.0009685,0,0,0,90.00000001 +367.54,50.30085681,-2.626026189,10500,0,200.0009685,0,0,0,90.00000001 +367.55,50.30085681,-2.625998164,10500,0,199.9998535,0,0,0,90.00000001 +367.56,50.30085681,-2.625970139,10500,0,199.9989614,0,0,0,90.00000001 +367.57,50.30085681,-2.625942114,10500,0,199.9989614,0,0,0,90.00000001 +367.58,50.30085681,-2.625914089,10500,0,199.9998535,0,0,0,90.00000001 +367.59,50.30085681,-2.625886064,10500,0,200.0009685,0,0,0,90.00000001 +367.6,50.30085681,-2.625858038,10500,0,200.0009685,0,0,0,90.00000001 +367.61,50.30085681,-2.625830013,10500,0,199.9998535,0,0,0,90.00000001 +367.62,50.30085681,-2.625801988,10500,0,199.9989614,0,0,0,90.00000001 +367.63,50.30085681,-2.625773963,10500,0,199.9987384,0,0,0,90.00000001 +367.64,50.30085681,-2.625745938,10500,0,199.9989614,0,0,0,90.00000001 +367.65,50.30085681,-2.625717913,10500,0,199.9998535,0,0,0,90.00000001 +367.66,50.30085681,-2.625689888,10500,0,200.0009685,0,0,0,90.00000001 +367.67,50.30085681,-2.625661862,10500,0,200.0009685,0,0,0,90.00000001 +367.68,50.30085681,-2.625633837,10500,0,199.9998535,0,0,0,90.00000001 +367.69,50.30085681,-2.625605812,10500,0,199.9989614,0,0,0,90.00000001 +367.7,50.30085681,-2.625577787,10500,0,199.9989614,0,0,0,90.00000001 +367.71,50.30085681,-2.625549762,10500,0,199.9998535,0,0,0,90.00000001 +367.72,50.30085681,-2.625521737,10500,0,200.0009685,0,0,0,90.00000001 +367.73,50.30085681,-2.625493711,10500,0,200.0009685,0,0,0,90.00000001 +367.74,50.30085681,-2.625465686,10500,0,199.9998535,0,0,0,90.00000001 +367.75,50.30085681,-2.625437661,10500,0,199.9989614,0,0,0,90.00000001 +367.76,50.30085681,-2.625409636,10500,0,199.9989614,0,0,0,90.00000001 +367.77,50.30085681,-2.625381611,10500,0,199.9998535,0,0,0,90.00000001 +367.78,50.30085681,-2.625353586,10500,0,200.0009685,0,0,0,90.00000001 +367.79,50.30085681,-2.62532556,10500,0,200.0009685,0,0,0,90.00000001 +367.8,50.30085681,-2.625297535,10500,0,199.9998535,0,0,0,90.00000001 +367.81,50.30085681,-2.62526951,10500,0,199.9989614,0,0,0,90.00000001 +367.82,50.30085681,-2.625241485,10500,0,199.9989614,0,0,0,90.00000001 +367.83,50.30085681,-2.62521346,10500,0,199.9998535,0,0,0,90.00000001 +367.84,50.30085681,-2.625185435,10500,0,200.0009685,0,0,0,90.00000001 +367.85,50.30085681,-2.625157409,10500,0,200.0009685,0,0,0,90.00000001 +367.86,50.30085681,-2.625129384,10500,0,199.9998535,0,0,0,90.00000001 +367.87,50.30085681,-2.625101359,10500,0,199.9989614,0,0,0,90.00000001 +367.88,50.30085681,-2.625073334,10500,0,199.9989614,0,0,0,90.00000001 +367.89,50.30085681,-2.625045309,10500,0,199.9998535,0,0,0,90.00000001 +367.9,50.30085681,-2.625017284,10500,0,200.0009685,0,0,0,90.00000001 +367.91,50.30085681,-2.624989258,10500,0,200.0009685,0,0,0,90.00000001 +367.92,50.30085681,-2.624961233,10500,0,199.9998535,0,0,0,90.00000001 +367.93,50.30085681,-2.624933208,10500,0,199.9991844,0,0,0,90.00000001 +367.94,50.30085681,-2.624905183,10500,0,199.9998535,0,0,0,90.00000001 +367.95,50.30085681,-2.624877158,10500,0,200.0009685,0,0,0,90.00000001 +367.96,50.30085681,-2.624849132,10500,0,200.0009685,0,0,0,90.00000001 +367.97,50.30085681,-2.624821107,10500,0,199.9998535,0,0,0,90.00000001 +367.98,50.30085681,-2.624793082,10500,0,199.9991844,0,0,0,90.00000001 +367.99,50.30085681,-2.624765057,10500,0,199.9998535,0,0,0,90.00000001 +368,50.30085681,-2.624737032,10500,0,200.0009685,0,0,0,90.00000001 +368.01,50.30085681,-2.624709006,10500,0,200.0009685,0,0,0,90.00000001 +368.02,50.30085681,-2.624680981,10500,0,199.9998535,0,0,0,90.00000001 +368.03,50.30085681,-2.624652956,10500,0,199.9991844,0,0,0,90.00000001 +368.04,50.30085681,-2.624624931,10500,0,199.9998535,0,0,0,90.00000001 +368.05,50.30085681,-2.624596906,10500,0,200.0009685,0,0,0,90.00000001 +368.06,50.30085681,-2.62456888,10500,0,200.0009685,0,0,0,90.00000001 +368.07,50.30085681,-2.624540855,10500,0,199.9998535,0,0,0,90.00000001 +368.08,50.30085681,-2.62451283,10500,0,199.9991844,0,0,0,90.00000001 +368.09,50.30085681,-2.624484805,10500,0,199.9998535,0,0,0,90.00000001 +368.1,50.30085681,-2.62445678,10500,0,200.0009685,0,0,0,90.00000001 +368.11,50.30085681,-2.624428754,10500,0,200.0009685,0,0,0,90.00000001 +368.12,50.30085681,-2.624400729,10500,0,199.9998535,0,0,0,90.00000001 +368.13,50.30085681,-2.624372704,10500,0,199.9989614,0,0,0,90.00000001 +368.14,50.30085681,-2.624344679,10500,0,199.9989614,0,0,0,90.00000001 +368.15,50.30085681,-2.624316654,10500,0,199.9998535,0,0,0,90.00000001 +368.16,50.30085681,-2.624288629,10500,0,200.0009685,0,0,0,90.00000001 +368.17,50.30085681,-2.624260603,10500,0,200.0009685,0,0,0,90.00000001 +368.18,50.30085681,-2.624232578,10500,0,199.9998535,0,0,0,90.00000001 +368.19,50.30085681,-2.624204553,10500,0,199.9989614,0,0,0,90.00000001 +368.2,50.30085681,-2.624176528,10500,0,199.9989614,0,0,0,90.00000001 +368.21,50.30085681,-2.624148503,10500,0,199.9998535,0,0,0,90.00000001 +368.22,50.30085681,-2.624120478,10500,0,200.0009685,0,0,0,90.00000001 +368.23,50.30085681,-2.624092452,10500,0,200.0009685,0,0,0,90.00000001 +368.24,50.30085681,-2.624064427,10500,0,199.9998535,0,0,0,90.00000001 +368.25,50.30085681,-2.624036402,10500,0,199.9989614,0,0,0,90.00000001 +368.26,50.30085681,-2.624008377,10500,0,199.9989614,0,0,0,90.00000001 +368.27,50.30085681,-2.623980352,10500,0,199.9998535,0,0,0,90.00000001 +368.28,50.30085681,-2.623952327,10500,0,200.0009685,0,0,0,90.00000001 +368.29,50.30085681,-2.623924301,10500,0,200.0009685,0,0,0,90.00000001 +368.3,50.30085681,-2.623896276,10500,0,199.9998535,0,0,0,90.00000001 +368.31,50.30085681,-2.623868251,10500,0,199.9989614,0,0,0,90.00000001 +368.32,50.30085681,-2.623840226,10500,0,199.9989614,0,0,0,90.00000001 +368.33,50.30085681,-2.623812201,10500,0,199.9998535,0,0,0,90.00000001 +368.34,50.30085681,-2.623784176,10500,0,200.0009685,0,0,0,90.00000001 +368.35,50.30085681,-2.62375615,10500,0,200.0009685,0,0,0,90.00000001 +368.36,50.30085681,-2.623728125,10500,0,199.9998535,0,0,0,90.00000001 +368.37,50.30085681,-2.6237001,10500,0,199.9989614,0,0,0,90.00000001 +368.38,50.30085681,-2.623672075,10500,0,199.9989614,0,0,0,90.00000001 +368.39,50.30085681,-2.62364405,10500,0,199.9998535,0,0,0,90.00000001 +368.4,50.30085681,-2.623616025,10500,0,200.0009685,0,0,0,90.00000001 +368.41,50.30085681,-2.623587999,10500,0,200.0009685,0,0,0,90.00000001 +368.42,50.30085681,-2.623559974,10500,0,199.9998535,0,0,0,90.00000001 +368.43,50.30085681,-2.623531949,10500,0,199.9989614,0,0,0,90.00000001 +368.44,50.30085681,-2.623503924,10500,0,199.9989614,0,0,0,90.00000001 +368.45,50.30085681,-2.623475899,10500,0,199.9998535,0,0,0,90.00000001 +368.46,50.30085681,-2.623447874,10500,0,200.0009685,0,0,0,90.00000001 +368.47,50.30085681,-2.623419848,10500,0,200.0009685,0,0,0,90.00000001 +368.48,50.30085681,-2.623391823,10500,0,199.9998535,0,0,0,90.00000001 +368.49,50.30085681,-2.623363798,10500,0,199.9989614,0,0,0,90.00000001 +368.5,50.30085681,-2.623335773,10500,0,199.9987384,0,0,0,90.00000001 +368.51,50.30085681,-2.623307748,10500,0,199.9989614,0,0,0,90.00000001 +368.52,50.30085681,-2.623279723,10500,0,199.9998535,0,0,0,90.00000001 +368.53,50.30085681,-2.623251698,10500,0,200.0009685,0,0,0,90.00000001 +368.54,50.30085681,-2.623223672,10500,0,200.0009685,0,0,0,90.00000001 +368.55,50.30085681,-2.623195647,10500,0,199.9998535,0,0,0,90.00000001 +368.56,50.30085681,-2.623167622,10500,0,199.9991844,0,0,0,90.00000001 +368.57,50.30085681,-2.623139597,10500,0,199.9998535,0,0,0,90.00000001 +368.58,50.30085681,-2.623111572,10500,0,200.0009685,0,0,0,90.00000001 +368.59,50.30085681,-2.623083546,10500,0,200.0009685,0,0,0,90.00000001 +368.6,50.30085681,-2.623055521,10500,0,199.9998535,0,0,0,90.00000001 +368.61,50.30085681,-2.623027496,10500,0,199.9991844,0,0,0,90.00000001 +368.62,50.30085681,-2.622999471,10500,0,199.9998535,0,0,0,90.00000001 +368.63,50.30085681,-2.622971446,10500,0,200.0009685,0,0,0,90.00000001 +368.64,50.30085681,-2.62294342,10500,0,200.0009685,0,0,0,90.00000001 +368.65,50.30085681,-2.622915395,10500,0,199.9998535,0,0,0,90.00000001 +368.66,50.30085681,-2.62288737,10500,0,199.9991844,0,0,0,90.00000001 +368.67,50.30085681,-2.622859345,10500,0,199.9998535,0,0,0,90.00000001 +368.68,50.30085681,-2.62283132,10500,0,200.0009685,0,0,0,90.00000001 +368.69,50.30085681,-2.622803294,10500,0,200.0009685,0,0,0,90.00000001 +368.7,50.30085681,-2.622775269,10500,0,199.9998535,0,0,0,90.00000001 +368.71,50.30085681,-2.622747244,10500,0,199.9991844,0,0,0,90.00000001 +368.72,50.30085681,-2.622719219,10500,0,199.9998535,0,0,0,90.00000001 +368.73,50.30085681,-2.622691194,10500,0,200.0009685,0,0,0,90.00000001 +368.74,50.30085681,-2.622663168,10500,0,200.0009685,0,0,0,90.00000001 +368.75,50.30085681,-2.622635143,10500,0,199.9998535,0,0,0,90.00000001 +368.76,50.30085681,-2.622607118,10500,0,199.9991844,0,0,0,90.00000001 +368.77,50.30085681,-2.622579093,10500,0,199.9998535,0,0,0,90.00000001 +368.78,50.30085681,-2.622551068,10500,0,200.0009685,0,0,0,90.00000001 +368.79,50.30085681,-2.622523042,10500,0,200.0009685,0,0,0,90.00000001 +368.8,50.30085681,-2.622495017,10500,0,199.9998535,0,0,0,90.00000001 +368.81,50.30085681,-2.622466992,10500,0,199.9989614,0,0,0,90.00000001 +368.82,50.30085681,-2.622438967,10500,0,199.9989614,0,0,0,90.00000001 +368.83,50.30085681,-2.622410942,10500,0,199.9998535,0,0,0,90.00000001 +368.84,50.30085681,-2.622382917,10500,0,200.0009685,0,0,0,90.00000001 +368.85,50.30085681,-2.622354891,10500,0,200.0009685,0,0,0,90.00000001 +368.86,50.30085681,-2.622326866,10500,0,199.9998535,0,0,0,90.00000001 +368.87,50.30085681,-2.622298841,10500,0,199.9989614,0,0,0,90.00000001 +368.88,50.30085681,-2.622270816,10500,0,199.9989614,0,0,0,90.00000001 +368.89,50.30085681,-2.622242791,10500,0,199.9998535,0,0,0,90.00000001 +368.9,50.30085681,-2.622214766,10500,0,200.0009685,0,0,0,90.00000001 +368.91,50.30085681,-2.62218674,10500,0,200.0009685,0,0,0,90.00000001 +368.92,50.30085681,-2.622158715,10500,0,199.9998535,0,0,0,90.00000001 +368.93,50.30085681,-2.62213069,10500,0,199.9989614,0,0,0,90.00000001 +368.94,50.30085681,-2.622102665,10500,0,199.9989614,0,0,0,90.00000001 +368.95,50.30085681,-2.62207464,10500,0,199.9998535,0,0,0,90.00000001 +368.96,50.30085681,-2.622046615,10500,0,200.0009685,0,0,0,90.00000001 +368.97,50.30085681,-2.622018589,10500,0,200.0009685,0,0,0,90.00000001 +368.98,50.30085681,-2.621990564,10500,0,199.9998535,0,0,0,90.00000001 +368.99,50.30085681,-2.621962539,10500,0,199.9989614,0,0,0,90.00000001 +369,50.30085681,-2.621934514,10500,0,199.9989614,0,0,0,90.00000001 +369.01,50.30085681,-2.621906489,10500,0,199.9998535,0,0,0,90.00000001 +369.02,50.30085681,-2.621878464,10500,0,200.0009685,0,0,0,90.00000001 +369.03,50.30085681,-2.621850438,10500,0,200.0009685,0,0,0,90.00000001 +369.04,50.30085681,-2.621822413,10500,0,199.9998535,0,0,0,90.00000001 +369.05,50.30085681,-2.621794388,10500,0,199.9989614,0,0,0,90.00000001 +369.06,50.30085681,-2.621766363,10500,0,199.9987384,0,0,0,90.00000001 +369.07,50.30085681,-2.621738338,10500,0,199.9989614,0,0,0,90.00000001 +369.08,50.30085681,-2.621710313,10500,0,199.9998535,0,0,0,90.00000001 +369.09,50.30085681,-2.621682288,10500,0,200.0009685,0,0,0,90.00000001 +369.1,50.30085681,-2.621654262,10500,0,200.0009685,0,0,0,90.00000001 +369.11,50.30085681,-2.621626237,10500,0,199.9998535,0,0,0,90.00000001 +369.12,50.30085681,-2.621598212,10500,0,199.9989614,0,0,0,90.00000001 +369.13,50.30085681,-2.621570187,10500,0,199.9989614,0,0,0,90.00000001 +369.14,50.30085681,-2.621542162,10500,0,199.9998535,0,0,0,90.00000001 +369.15,50.30085681,-2.621514137,10500,0,200.0009685,0,0,0,90.00000001 +369.16,50.30085681,-2.621486111,10500,0,200.0009685,0,0,0,90.00000001 +369.17,50.30085681,-2.621458086,10500,0,199.9998535,0,0,0,90.00000001 +369.18,50.30085681,-2.621430061,10500,0,199.9991844,0,0,0,90.00000001 +369.19,50.30085681,-2.621402036,10500,0,199.9998535,0,0,0,90.00000001 +369.2,50.30085681,-2.621374011,10500,0,200.0009685,0,0,0,90.00000001 +369.21,50.30085681,-2.621345985,10500,0,200.0009685,0,0,0,90.00000001 +369.22,50.30085681,-2.62131796,10500,0,199.9998535,0,0,0,90.00000001 +369.23,50.30085681,-2.621289935,10500,0,199.9991844,0,0,0,90.00000001 +369.24,50.30085681,-2.62126191,10500,0,199.9998535,0,0,0,90.00000001 +369.25,50.30085681,-2.621233885,10500,0,200.0009685,0,0,0,90.00000001 +369.26,50.30085681,-2.621205859,10500,0,200.0009685,0,0,0,90.00000001 +369.27,50.30085681,-2.621177834,10500,0,199.9998535,0,0,0,90.00000001 +369.28,50.30085681,-2.621149809,10500,0,199.9991844,0,0,0,90.00000001 +369.29,50.30085681,-2.621121784,10500,0,199.9998535,0,0,0,90.00000001 +369.3,50.30085681,-2.621093759,10500,0,200.0009685,0,0,0,90.00000001 +369.31,50.30085681,-2.621065733,10500,0,200.0009685,0,0,0,90.00000001 +369.32,50.30085681,-2.621037708,10500,0,199.9998535,0,0,0,90.00000001 +369.33,50.30085681,-2.621009683,10500,0,199.9991844,0,0,0,90.00000001 +369.34,50.30085681,-2.620981658,10500,0,199.9998535,0,0,0,90.00000001 +369.35,50.30085681,-2.620953633,10500,0,200.0009685,0,0,0,90.00000001 +369.36,50.30085681,-2.620925607,10500,0,200.0009685,0,0,0,90.00000001 +369.37,50.30085681,-2.620897582,10500,0,199.9998535,0,0,0,90.00000001 +369.38,50.30085681,-2.620869557,10500,0,199.9991844,0,0,0,90.00000001 +369.39,50.30085681,-2.620841532,10500,0,199.9998535,0,0,0,90.00000001 +369.4,50.30085681,-2.620813507,10500,0,200.0009685,0,0,0,90.00000001 +369.41,50.30085681,-2.620785481,10500,0,200.0009685,0,0,0,90.00000001 +369.42,50.30085681,-2.620757456,10500,0,199.9998535,0,0,0,90.00000001 +369.43,50.30085681,-2.620729431,10500,0,199.9989614,0,0,0,90.00000001 +369.44,50.30085681,-2.620701406,10500,0,199.9989614,0,0,0,90.00000001 +369.45,50.30085681,-2.620673381,10500,0,199.9998535,0,0,0,90.00000001 +369.46,50.30085681,-2.620645356,10500,0,200.0009685,0,0,0,90.00000001 +369.47,50.30085681,-2.62061733,10500,0,200.0009685,0,0,0,90.00000001 +369.48,50.30085681,-2.620589305,10500,0,199.9998535,0,0,0,90.00000001 +369.49,50.30085681,-2.62056128,10500,0,199.9989614,0,0,0,90.00000001 +369.5,50.30085681,-2.620533255,10500,0,199.9989614,0,0,0,90.00000001 +369.51,50.30085681,-2.62050523,10500,0,199.9998535,0,0,0,90.00000001 +369.52,50.30085681,-2.620477205,10500,0,200.0009685,0,0,0,90.00000001 +369.53,50.30085681,-2.620449179,10500,0,200.0009685,0,0,0,90.00000001 +369.54,50.30085681,-2.620421154,10500,0,199.9998535,0,0,0,90.00000001 +369.55,50.30085681,-2.620393129,10500,0,199.9989614,0,0,0,90.00000001 +369.56,50.30085681,-2.620365104,10500,0,199.9989614,0,0,0,90.00000001 +369.57,50.30085681,-2.620337079,10500,0,199.9998535,0,0,0,90.00000001 +369.58,50.30085681,-2.620309054,10500,0,200.0009685,0,0,0,90.00000001 +369.59,50.30085681,-2.620281028,10500,0,200.0009685,0,0,0,90.00000001 +369.6,50.30085681,-2.620253003,10500,0,199.9998535,0,0,0,90.00000001 +369.61,50.30085681,-2.620224978,10500,0,199.9989614,0,0,0,90.00000001 +369.62,50.30085681,-2.620196953,10500,0,199.9987384,0,0,0,90.00000001 +369.63,50.30085681,-2.620168928,10500,0,199.9989614,0,0,0,90.00000001 +369.64,50.30085681,-2.620140903,10500,0,199.9998535,0,0,0,90.00000001 +369.65,50.30085681,-2.620112878,10500,0,200.0009685,0,0,0,90.00000001 +369.66,50.30085681,-2.620084852,10500,0,200.0009685,0,0,0,90.00000001 +369.67,50.30085681,-2.620056827,10500,0,199.9998535,0,0,0,90.00000001 +369.68,50.30085681,-2.620028802,10500,0,199.9989614,0,0,0,90.00000001 +369.69,50.30085681,-2.620000777,10500,0,199.9989614,0,0,0,90.00000001 +369.7,50.30085681,-2.619972752,10500,0,199.9998535,0,0,0,90.00000001 +369.71,50.30085681,-2.619944727,10500,0,200.0009685,0,0,0,90.00000001 +369.72,50.30085681,-2.619916701,10500,0,200.0009685,0,0,0,90.00000001 +369.73,50.30085681,-2.619888676,10500,0,199.9998535,0,0,0,90.00000001 +369.74,50.30085681,-2.619860651,10500,0,199.9989614,0,0,0,90.00000001 +369.75,50.30085681,-2.619832626,10500,0,199.9989614,0,0,0,90.00000001 +369.76,50.30085681,-2.619804601,10500,0,199.9998535,0,0,0,90.00000001 +369.77,50.30085681,-2.619776576,10500,0,200.0009685,0,0,0,90.00000001 +369.78,50.30085681,-2.61974855,10500,0,200.0009685,0,0,0,90.00000001 +369.79,50.30085681,-2.619720525,10500,0,199.9998535,0,0,0,90.00000001 +369.8,50.30085681,-2.6196925,10500,0,199.9991844,0,0,0,90.00000001 +369.81,50.30085681,-2.619664475,10500,0,199.9998535,0,0,0,90.00000001 +369.82,50.30085681,-2.61963645,10500,0,200.0009685,0,0,0,90.00000001 +369.83,50.30085681,-2.619608424,10500,0,200.0009685,0,0,0,90.00000001 +369.84,50.30085681,-2.619580399,10500,0,199.9998535,0,0,0,90.00000001 +369.85,50.30085681,-2.619552374,10500,0,199.9991844,0,0,0,90.00000001 +369.86,50.30085681,-2.619524349,10500,0,199.9998535,0,0,0,90.00000001 +369.87,50.30085681,-2.619496324,10500,0,200.0009685,0,0,0,90.00000001 +369.88,50.30085681,-2.619468298,10500,0,200.0009685,0,0,0,90.00000001 +369.89,50.30085681,-2.619440273,10500,0,199.9998535,0,0,0,90.00000001 +369.9,50.30085681,-2.619412248,10500,0,199.9991844,0,0,0,90.00000001 +369.91,50.30085681,-2.619384223,10500,0,199.9998535,0,0,0,90.00000001 +369.92,50.30085681,-2.619356198,10500,0,200.0009685,0,0,0,90.00000001 +369.93,50.30085681,-2.619328172,10500,0,200.0009685,0,0,0,90.00000001 +369.94,50.30085681,-2.619300147,10500,0,199.9998535,0,0,0,90.00000001 +369.95,50.30085681,-2.619272122,10500,0,199.9991844,0,0,0,90.00000001 +369.96,50.30085681,-2.619244097,10500,0,199.9998535,0,0,0,90.00000001 +369.97,50.30085681,-2.619216072,10500,0,200.0009685,0,0,0,90.00000001 +369.98,50.30085681,-2.619188046,10500,0,200.0009685,0,0,0,90.00000001 +369.99,50.30085681,-2.619160021,10500,0,199.9998535,0,0,0,90.00000001 +370,50.30085681,-2.619131996,10500,0,199.9991844,0,0,0,90.00000001 +370.01,50.30085681,-2.619103971,10500,0,199.9998535,0,0,0,90.00000001 +370.02,50.30085681,-2.619075946,10500,0,200.0009685,0,0,0,90.00000001 +370.03,50.30085681,-2.61904792,10500,0,200.0009685,0,0,0,90.00000001 +370.04,50.30085681,-2.619019895,10500,0,199.9998535,0,0,0,90.00000001 +370.05,50.30085681,-2.61899187,10500,0,199.9989614,0,0,0,90.00000001 +370.06,50.30085681,-2.618963845,10500,0,199.9989614,0,0,0,90.00000001 +370.07,50.30085681,-2.61893582,10500,0,199.9998535,0,0,0,90.00000001 +370.08,50.30085681,-2.618907795,10500,0,200.0009685,0,0,0,90.00000001 +370.09,50.30085681,-2.618879769,10500,0,200.0009685,0,0,0,90.00000001 +370.1,50.30085681,-2.618851744,10500,0,199.9998535,0,0,0,90.00000001 +370.11,50.30085681,-2.618823719,10500,0,199.9989614,0,0,0,90.00000001 +370.12,50.30085681,-2.618795694,10500,0,199.9989614,0,0,0,90.00000001 +370.13,50.30085681,-2.618767669,10500,0,199.9998535,0,0,0,90.00000001 +370.14,50.30085681,-2.618739644,10500,0,200.0009685,0,0,0,90.00000001 +370.15,50.30085681,-2.618711618,10500,0,200.0009685,0,0,0,90.00000001 +370.16,50.30085681,-2.618683593,10500,0,199.9998535,0,0,0,90.00000001 +370.17,50.30085681,-2.618655568,10500,0,199.9989614,0,0,0,90.00000001 +370.18,50.30085681,-2.618627543,10500,0,199.9989614,0,0,0,90.00000001 +370.19,50.30085681,-2.618599518,10500,0,199.9998535,0,0,0,90.00000001 +370.2,50.30085681,-2.618571493,10500,0,200.0009685,0,0,0,90.00000001 +370.21,50.30085681,-2.618543467,10500,0,200.0009685,0,0,0,90.00000001 +370.22,50.30085681,-2.618515442,10500,0,199.9998535,0,0,0,90.00000001 +370.23,50.30085681,-2.618487417,10500,0,199.9989614,0,0,0,90.00000001 +370.24,50.30085681,-2.618459392,10500,0,199.9987384,0,0,0,90.00000001 +370.25,50.30085681,-2.618431367,10500,0,199.9989614,0,0,0,90.00000001 +370.26,50.30085681,-2.618403342,10500,0,199.9998535,0,0,0,90.00000001 +370.27,50.30085681,-2.618375317,10500,0,200.0009685,0,0,0,90.00000001 +370.28,50.30085681,-2.618347291,10500,0,200.0009685,0,0,0,90.00000001 +370.29,50.30085681,-2.618319266,10500,0,199.9998535,0,0,0,90.00000001 +370.3,50.30085681,-2.618291241,10500,0,199.9989614,0,0,0,90.00000001 +370.31,50.30085681,-2.618263216,10500,0,199.9989614,0,0,0,90.00000001 +370.32,50.30085681,-2.618235191,10500,0,199.9998535,0,0,0,90.00000001 +370.33,50.30085681,-2.618207166,10500,0,200.0009685,0,0,0,90.00000001 +370.34,50.30085681,-2.61817914,10500,0,200.0009685,0,0,0,90.00000001 +370.35,50.30085681,-2.618151115,10500,0,199.9998535,0,0,0,90.00000001 +370.36,50.30085681,-2.61812309,10500,0,199.9989614,0,0,0,90.00000001 +370.37,50.30085681,-2.618095065,10500,0,199.9989614,0,0,0,90.00000001 +370.38,50.30085681,-2.61806704,10500,0,199.9998535,0,0,0,90.00000001 +370.39,50.30085681,-2.618039015,10500,0,200.0009685,0,0,0,90.00000001 +370.4,50.30085681,-2.618010989,10500,0,200.0009685,0,0,0,90.00000001 +370.41,50.30085681,-2.617982964,10500,0,199.9998535,0,0,0,90.00000001 +370.42,50.30085681,-2.617954939,10500,0,199.9991844,0,0,0,90.00000001 +370.43,50.30085681,-2.617926914,10500,0,199.9998535,0,0,0,90.00000001 +370.44,50.30085681,-2.617898889,10500,0,200.0009685,0,0,0,90.00000001 +370.45,50.30085681,-2.617870863,10500,0,200.0009685,0,0,0,90.00000001 +370.46,50.30085681,-2.617842838,10500,0,199.9998535,0,0,0,90.00000001 +370.47,50.30085681,-2.617814813,10500,0,199.9991844,0,0,0,90.00000001 +370.48,50.30085681,-2.617786788,10500,0,199.9998535,0,0,0,90.00000001 +370.49,50.30085681,-2.617758763,10500,0,200.0009685,0,0,0,90.00000001 +370.5,50.30085681,-2.617730737,10500,0,200.0009685,0,0,0,90.00000001 +370.51,50.30085681,-2.617702712,10500,0,199.9998535,0,0,0,90.00000001 +370.52,50.30085681,-2.617674687,10500,0,199.9989614,0,0,0,90.00000001 +370.53,50.30085681,-2.617646662,10500,0,199.9989614,0,0,0,90.00000001 +370.54,50.30085681,-2.617618637,10500,0,199.9998535,0,0,0,90.00000001 +370.55,50.30085681,-2.617590612,10500,0,200.0009685,0,0,0,90.00000001 +370.56,50.30085681,-2.617562586,10500,0,200.0009685,0,0,0,90.00000001 +370.57,50.30085681,-2.617534561,10500,0,199.9998535,0,0,0,90.00000001 +370.58,50.30085681,-2.617506536,10500,0,199.9991844,0,0,0,90.00000001 +370.59,50.30085681,-2.617478511,10500,0,199.9998535,0,0,0,90.00000001 +370.6,50.30085681,-2.617450486,10500,0,200.0009685,0,0,0,90.00000001 +370.61,50.30085681,-2.61742246,10500,0,200.0009685,0,0,0,90.00000001 +370.62,50.30085681,-2.617394435,10500,0,199.9998535,0,0,0,90.00000001 +370.63,50.30085681,-2.61736641,10500,0,199.9991844,0,0,0,90.00000001 +370.64,50.30085681,-2.617338385,10500,0,199.9998535,0,0,0,90.00000001 +370.65,50.30085681,-2.61731036,10500,0,200.0009685,0,0,0,90.00000001 +370.66,50.30085681,-2.617282334,10500,0,200.0009685,0,0,0,90.00000001 +370.67,50.30085681,-2.617254309,10500,0,199.9998535,0,0,0,90.00000001 +370.68,50.30085681,-2.617226284,10500,0,199.9991844,0,0,0,90.00000001 +370.69,50.30085681,-2.617198259,10500,0,199.9998535,0,0,0,90.00000001 +370.7,50.30085681,-2.617170234,10500,0,200.0009685,0,0,0,90.00000001 +370.71,50.30085681,-2.617142208,10500,0,200.0009685,0,0,0,90.00000001 +370.72,50.30085681,-2.617114183,10500,0,199.9998535,0,0,0,90.00000001 +370.73,50.30085681,-2.617086158,10500,0,199.9989614,0,0,0,90.00000001 +370.74,50.30085681,-2.617058133,10500,0,199.9989614,0,0,0,90.00000001 +370.75,50.30085681,-2.617030108,10500,0,199.9998535,0,0,0,90.00000001 +370.76,50.30085681,-2.617002083,10500,0,200.0009685,0,0,0,90.00000001 +370.77,50.30085681,-2.616974057,10500,0,200.0009685,0,0,0,90.00000001 +370.78,50.30085681,-2.616946032,10500,0,199.9998535,0,0,0,90.00000001 +370.79,50.30085681,-2.616918007,10500,0,199.9989614,0,0,0,90.00000001 +370.8,50.30085681,-2.616889982,10500,0,199.9987384,0,0,0,90.00000001 +370.81,50.30085681,-2.616861957,10500,0,199.9989614,0,0,0,90.00000001 +370.82,50.30085681,-2.616833932,10500,0,199.9998535,0,0,0,90.00000001 +370.83,50.30085681,-2.616805907,10500,0,200.0009685,0,0,0,90.00000001 +370.84,50.30085681,-2.616777881,10500,0,200.0009685,0,0,0,90.00000001 +370.85,50.30085681,-2.616749856,10500,0,199.9998535,0,0,0,90.00000001 +370.86,50.30085681,-2.616721831,10500,0,199.9989614,0,0,0,90.00000001 +370.87,50.30085681,-2.616693806,10500,0,199.9989614,0,0,0,90.00000001 +370.88,50.30085681,-2.616665781,10500,0,199.9998535,0,0,0,90.00000001 +370.89,50.30085681,-2.616637756,10500,0,200.0009685,0,0,0,90.00000001 +370.9,50.30085681,-2.61660973,10500,0,200.0009685,0,0,0,90.00000001 +370.91,50.30085681,-2.616581705,10500,0,199.9998535,0,0,0,90.00000001 +370.92,50.30085681,-2.61655368,10500,0,199.9989614,0,0,0,90.00000001 +370.93,50.30085681,-2.616525655,10500,0,199.9989614,0,0,0,90.00000001 +370.94,50.30085681,-2.61649763,10500,0,199.9998535,0,0,0,90.00000001 +370.95,50.30085681,-2.616469605,10500,0,200.0009685,0,0,0,90.00000001 +370.96,50.30085681,-2.616441579,10500,0,200.0009685,0,0,0,90.00000001 +370.97,50.30085681,-2.616413554,10500,0,199.9998535,0,0,0,90.00000001 +370.98,50.30085681,-2.616385529,10500,0,199.9989614,0,0,0,90.00000001 +370.99,50.30085681,-2.616357504,10500,0,199.9989614,0,0,0,90.00000001 +371,50.30085681,-2.616329479,10500,0,199.9998535,0,0,0,90.00000001 +371.01,50.30085681,-2.616301454,10500,0,200.0009685,0,0,0,90.00000001 +371.02,50.30085681,-2.616273428,10500,0,200.0009685,0,0,0,90.00000001 +371.03,50.30085681,-2.616245403,10500,0,199.9998535,0,0,0,90.00000001 +371.04,50.30085681,-2.616217378,10500,0,199.9989614,0,0,0,90.00000001 +371.05,50.30085681,-2.616189353,10500,0,199.9989614,0,0,0,90.00000001 +371.06,50.30085681,-2.616161328,10500,0,199.9998535,0,0,0,90.00000001 +371.07,50.30085681,-2.616133303,10500,0,200.0009685,0,0,0,90.00000001 +371.08,50.30085681,-2.616105277,10500,0,200.0009685,0,0,0,90.00000001 +371.09,50.30085681,-2.616077252,10500,0,199.9998535,0,0,0,90.00000001 +371.1,50.30085681,-2.616049227,10500,0,199.9991844,0,0,0,90.00000001 +371.11,50.30085681,-2.616021202,10500,0,199.9998535,0,0,0,90.00000001 +371.12,50.30085681,-2.615993177,10500,0,200.0009685,0,0,0,90.00000001 +371.13,50.30085681,-2.615965151,10500,0,200.0009685,0,0,0,90.00000001 +371.14,50.30085681,-2.615937126,10500,0,199.9998535,0,0,0,90.00000001 +371.15,50.30085681,-2.615909101,10500,0,199.9991844,0,0,0,90.00000001 +371.16,50.30085681,-2.615881076,10500,0,199.9998535,0,0,0,90.00000001 +371.17,50.30085681,-2.615853051,10500,0,200.0009685,0,0,0,90.00000001 +371.18,50.30085681,-2.615825025,10500,0,200.0009685,0,0,0,90.00000001 +371.19,50.30085681,-2.615797,10500,0,199.9998535,0,0,0,90.00000001 +371.2,50.30085681,-2.615768975,10500,0,199.9991844,0,0,0,90.00000001 +371.21,50.30085681,-2.61574095,10500,0,199.9998535,0,0,0,90.00000001 +371.22,50.30085681,-2.615712925,10500,0,200.0009685,0,0,0,90.00000001 +371.23,50.30085681,-2.615684899,10500,0,200.0009685,0,0,0,90.00000001 +371.24,50.30085681,-2.615656874,10500,0,199.9998535,0,0,0,90.00000001 +371.25,50.30085681,-2.615628849,10500,0,199.9991844,0,0,0,90.00000001 +371.26,50.30085681,-2.615600824,10500,0,199.9998535,0,0,0,90.00000001 +371.27,50.30085681,-2.615572799,10500,0,200.0009685,0,0,0,90.00000001 +371.28,50.30085681,-2.615544773,10500,0,200.0009685,0,0,0,90.00000001 +371.29,50.30085681,-2.615516748,10500,0,199.9998535,0,0,0,90.00000001 +371.3,50.30085681,-2.615488723,10500,0,199.9991844,0,0,0,90.00000001 +371.31,50.30085681,-2.615460698,10500,0,199.9998535,0,0,0,90.00000001 +371.32,50.30085681,-2.615432673,10500,0,200.0009685,0,0,0,90.00000001 +371.33,50.30085681,-2.615404647,10500,0,200.0009685,0,0,0,90.00000001 +371.34,50.30085681,-2.615376622,10500,0,199.9998535,0,0,0,90.00000001 +371.35,50.30085681,-2.615348597,10500,0,199.9989614,0,0,0,90.00000001 +371.36,50.30085681,-2.615320572,10500,0,199.9987384,0,0,0,90.00000001 +371.37,50.30085681,-2.615292547,10500,0,199.9989614,0,0,0,90.00000001 +371.38,50.30085681,-2.615264522,10500,0,199.9998535,0,0,0,90.00000001 +371.39,50.30085681,-2.615236497,10500,0,200.0009685,0,0,0,90.00000001 +371.4,50.30085681,-2.615208471,10500,0,200.0009685,0,0,0,90.00000001 +371.41,50.30085681,-2.615180446,10500,0,199.9998535,0,0,0,90.00000001 +371.42,50.30085681,-2.615152421,10500,0,199.9989614,0,0,0,90.00000001 +371.43,50.30085681,-2.615124396,10500,0,199.9989614,0,0,0,90.00000001 +371.44,50.30085681,-2.615096371,10500,0,199.9998535,0,0,0,90.00000001 +371.45,50.30085681,-2.615068346,10500,0,200.0009685,0,0,0,90.00000001 +371.46,50.30085681,-2.61504032,10500,0,200.0009685,0,0,0,90.00000001 +371.47,50.30085681,-2.615012295,10500,0,199.9998535,0,0,0,90.00000001 +371.48,50.30085681,-2.61498427,10500,0,199.9989614,0,0,0,90.00000001 +371.49,50.30085681,-2.614956245,10500,0,199.9989614,0,0,0,90.00000001 +371.5,50.30085681,-2.61492822,10500,0,199.9998535,0,0,0,90.00000001 +371.51,50.30085681,-2.614900195,10500,0,200.0009685,0,0,0,90.00000001 +371.52,50.30085681,-2.614872169,10500,0,200.0009685,0,0,0,90.00000001 +371.53,50.30085681,-2.614844144,10500,0,199.9998535,0,0,0,90.00000001 +371.54,50.30085681,-2.614816119,10500,0,199.9989614,0,0,0,90.00000001 +371.55,50.30085681,-2.614788094,10500,0,199.9989614,0,0,0,90.00000001 +371.56,50.30085681,-2.614760069,10500,0,199.9998535,0,0,0,90.00000001 +371.57,50.30085681,-2.614732044,10500,0,200.0009685,0,0,0,90.00000001 +371.58,50.30085681,-2.614704018,10500,0,200.0009685,0,0,0,90.00000001 +371.59,50.30085681,-2.614675993,10500,0,199.9998535,0,0,0,90.00000001 +371.6,50.30085681,-2.614647968,10500,0,199.9989614,0,0,0,90.00000001 +371.61,50.30085681,-2.614619943,10500,0,199.9989614,0,0,0,90.00000001 +371.62,50.30085681,-2.614591918,10500,0,199.9998535,0,0,0,90.00000001 +371.63,50.30085681,-2.614563893,10500,0,200.0009685,0,0,0,90.00000001 +371.64,50.30085681,-2.614535867,10500,0,200.0009685,0,0,0,90.00000001 +371.65,50.30085681,-2.614507842,10500,0,199.9998535,0,0,0,90.00000001 +371.66,50.30085681,-2.614479817,10500,0,199.9989614,0,0,0,90.00000001 +371.67,50.30085681,-2.614451792,10500,0,199.9989614,0,0,0,90.00000001 +371.68,50.30085681,-2.614423767,10500,0,199.9998535,0,0,0,90.00000001 +371.69,50.30085681,-2.614395742,10500,0,200.0009685,0,0,0,90.00000001 +371.7,50.30085681,-2.614367716,10500,0,200.0009685,0,0,0,90.00000001 +371.71,50.30085681,-2.614339691,10500,0,199.9998535,0,0,0,90.00000001 +371.72,50.30085681,-2.614311666,10500,0,199.9991844,0,0,0,90.00000001 +371.73,50.30085681,-2.614283641,10500,0,199.9998535,0,0,0,90.00000001 +371.74,50.30085681,-2.614255616,10500,0,200.0009685,0,0,0,90.00000001 +371.75,50.30085681,-2.61422759,10500,0,200.0009685,0,0,0,90.00000001 +371.76,50.30085681,-2.614199565,10500,0,199.9998535,0,0,0,90.00000001 +371.77,50.30085681,-2.61417154,10500,0,199.9991844,0,0,0,90.00000001 +371.78,50.30085681,-2.614143515,10500,0,199.9998535,0,0,0,90.00000001 +371.79,50.30085681,-2.61411549,10500,0,200.0009685,0,0,0,90.00000001 +371.8,50.30085681,-2.614087464,10500,0,200.0009685,0,0,0,90.00000001 +371.81,50.30085681,-2.614059439,10500,0,199.9998535,0,0,0,90.00000001 +371.82,50.30085681,-2.614031414,10500,0,199.9991844,0,0,0,90.00000001 +371.83,50.30085681,-2.614003389,10500,0,199.9998535,0,0,0,90.00000001 +371.84,50.30085681,-2.613975364,10500,0,200.0009685,0,0,0,90.00000001 +371.85,50.30085681,-2.613947338,10500,0,200.0009685,0,0,0,90.00000001 +371.86,50.30085681,-2.613919313,10500,0,199.9998535,0,0,0,90.00000001 +371.87,50.30085681,-2.613891288,10500,0,199.9991844,0,0,0,90.00000001 +371.88,50.30085681,-2.613863263,10500,0,199.9998535,0,0,0,90.00000001 +371.89,50.30085681,-2.613835238,10500,0,200.0009685,0,0,0,90.00000001 +371.9,50.30085681,-2.613807212,10500,0,200.0009685,0,0,0,90.00000001 +371.91,50.30085681,-2.613779187,10500,0,199.9998535,0,0,0,90.00000001 +371.92,50.30085681,-2.613751162,10500,0,199.9989614,0,0,0,90.00000001 +371.93,50.30085681,-2.613723137,10500,0,199.9989614,0,0,0,90.00000001 +371.94,50.30085681,-2.613695112,10500,0,199.9998535,0,0,0,90.00000001 +371.95,50.30085681,-2.613667087,10500,0,200.0009685,0,0,0,90.00000001 +371.96,50.30085681,-2.613639061,10500,0,200.0009685,0,0,0,90.00000001 +371.97,50.30085681,-2.613611036,10500,0,199.9998535,0,0,0,90.00000001 +371.98,50.30085681,-2.613583011,10500,0,199.9989614,0,0,0,90.00000001 +371.99,50.30085681,-2.613554986,10500,0,199.9989614,0,0,0,90.00000001 +372,50.30085681,-2.613526961,10500,0,199.9998535,0,0,0,90.00000001 +372.01,50.30085681,-2.613498936,10500,0,200.0009685,0,0,0,90.00000001 +372.02,50.30085681,-2.61347091,10500,0,200.0009685,0,0,0,90.00000001 +372.03,50.30085681,-2.613442885,10500,0,199.9998535,0,0,0,90.00000001 +372.04,50.30085681,-2.61341486,10500,0,199.9989614,0,0,0,90.00000001 +372.05,50.30085681,-2.613386835,10500,0,199.9989614,0,0,0,90.00000001 +372.06,50.30085681,-2.61335881,10500,0,199.9998535,0,0,0,90.00000001 +372.07,50.30085681,-2.613330785,10500,0,200.0009685,0,0,0,90.00000001 +372.08,50.30085681,-2.613302759,10500,0,200.0009685,0,0,0,90.00000001 +372.09,50.30085681,-2.613274734,10500,0,199.9998535,0,0,0,90.00000001 +372.1,50.30085681,-2.613246709,10500,0,199.9989614,0,0,0,90.00000001 +372.11,50.30085681,-2.613218684,10500,0,199.9989614,0,0,0,90.00000001 +372.12,50.30085681,-2.613190659,10500,0,199.9998535,0,0,0,90.00000001 +372.13,50.30085681,-2.613162634,10500,0,200.0009685,0,0,0,90.00000001 +372.14,50.30085681,-2.613134608,10500,0,200.0009685,0,0,0,90.00000001 +372.15,50.30085681,-2.613106583,10500,0,199.9998535,0,0,0,90.00000001 +372.16,50.30085681,-2.613078558,10500,0,199.9989614,0,0,0,90.00000001 +372.17,50.30085681,-2.613050533,10500,0,199.9989614,0,0,0,90.00000001 +372.18,50.30085681,-2.613022508,10500,0,199.9998535,0,0,0,90.00000001 +372.19,50.30085681,-2.612994483,10500,0,200.0009685,0,0,0,90.00000001 +372.2,50.30085681,-2.612966457,10500,0,200.0009685,0,0,0,90.00000001 +372.21,50.30085681,-2.612938432,10500,0,199.9998535,0,0,0,90.00000001 +372.22,50.30085681,-2.612910407,10500,0,199.9989614,0,0,0,90.00000001 +372.23,50.30085681,-2.612882382,10500,0,199.9987384,0,0,0,90.00000001 +372.24,50.30085681,-2.612854357,10500,0,199.9989614,0,0,0,90.00000001 +372.25,50.30085681,-2.612826332,10500,0,199.9998535,0,0,0,90.00000001 +372.26,50.30085681,-2.612798307,10500,0,200.0009685,0,0,0,90.00000001 +372.27,50.30085681,-2.612770281,10500,0,200.0009685,0,0,0,90.00000001 +372.28,50.30085681,-2.612742256,10500,0,199.9998535,0,0,0,90.00000001 +372.29,50.30085681,-2.612714231,10500,0,199.9991844,0,0,0,90.00000001 +372.3,50.30085681,-2.612686206,10500,0,199.9998535,0,0,0,90.00000001 +372.31,50.30085681,-2.612658181,10500,0,200.0009685,0,0,0,90.00000001 +372.32,50.30085681,-2.612630155,10500,0,200.0009685,0,0,0,90.00000001 +372.33,50.30085681,-2.61260213,10500,0,199.9998535,0,0,0,90.00000001 +372.34,50.30085681,-2.612574105,10500,0,199.9991844,0,0,0,90.00000001 +372.35,50.30085681,-2.61254608,10500,0,199.9998535,0,0,0,90.00000001 +372.36,50.30085681,-2.612518055,10500,0,200.0009685,0,0,0,90.00000001 +372.37,50.30085681,-2.612490029,10500,0,200.0009685,0,0,0,90.00000001 +372.38,50.30085681,-2.612462004,10500,0,199.9998535,0,0,0,90.00000001 +372.39,50.30085681,-2.612433979,10500,0,199.9991844,0,0,0,90.00000001 +372.4,50.30085681,-2.612405954,10500,0,199.9998535,0,0,0,90.00000001 +372.41,50.30085681,-2.612377929,10500,0,200.0009685,0,0,0,90.00000001 +372.42,50.30085681,-2.612349903,10500,0,200.0009685,0,0,0,90.00000001 +372.43,50.30085681,-2.612321878,10500,0,199.9998535,0,0,0,90.00000001 +372.44,50.30085681,-2.612293853,10500,0,199.9991844,0,0,0,90.00000001 +372.45,50.30085681,-2.612265828,10500,0,199.9998535,0,0,0,90.00000001 +372.46,50.30085681,-2.612237803,10500,0,200.0009685,0,0,0,90.00000001 +372.47,50.30085681,-2.612209777,10500,0,200.0009685,0,0,0,90.00000001 +372.48,50.30085681,-2.612181752,10500,0,199.9998535,0,0,0,90.00000001 +372.49,50.30085681,-2.612153727,10500,0,199.9991844,0,0,0,90.00000001 +372.5,50.30085681,-2.612125702,10500,0,199.9998535,0,0,0,90.00000001 +372.51,50.30085681,-2.612097677,10500,0,200.0009685,0,0,0,90.00000001 +372.52,50.30085681,-2.612069651,10500,0,200.0009685,0,0,0,90.00000001 +372.53,50.30085681,-2.612041626,10500,0,199.9998535,0,0,0,90.00000001 +372.54,50.30085681,-2.612013601,10500,0,199.9989614,0,0,0,90.00000001 +372.55,50.30085681,-2.611985576,10500,0,199.9989614,0,0,0,90.00000001 +372.56,50.30085681,-2.611957551,10500,0,199.9998535,0,0,0,90.00000001 +372.57,50.30085681,-2.611929526,10500,0,200.0009685,0,0,0,90.00000001 +372.58,50.30085681,-2.6119015,10500,0,200.0009685,0,0,0,90.00000001 +372.59,50.30085681,-2.611873475,10500,0,199.9998535,0,0,0,90.00000001 +372.6,50.30085681,-2.61184545,10500,0,199.9989614,0,0,0,90.00000001 +372.61,50.30085681,-2.611817425,10500,0,199.9989614,0,0,0,90.00000001 +372.62,50.30085681,-2.6117894,10500,0,199.9998535,0,0,0,90.00000001 +372.63,50.30085681,-2.611761375,10500,0,200.0009685,0,0,0,90.00000001 +372.64,50.30085681,-2.611733349,10500,0,200.0009685,0,0,0,90.00000001 +372.65,50.30085681,-2.611705324,10500,0,199.9998535,0,0,0,90.00000001 +372.66,50.30085681,-2.611677299,10500,0,199.9989614,0,0,0,90.00000001 +372.67,50.30085681,-2.611649274,10500,0,199.9989614,0,0,0,90.00000001 +372.68,50.30085681,-2.611621249,10500,0,199.9998535,0,0,0,90.00000001 +372.69,50.30085681,-2.611593224,10500,0,200.0009685,0,0,0,90.00000001 +372.7,50.30085681,-2.611565198,10500,0,200.0009685,0,0,0,90.00000001 +372.71,50.30085681,-2.611537173,10500,0,199.9998535,0,0,0,90.00000001 +372.72,50.30085681,-2.611509148,10500,0,199.9989614,0,0,0,90.00000001 +372.73,50.30085681,-2.611481123,10500,0,199.9989614,0,0,0,90.00000001 +372.74,50.30085681,-2.611453098,10500,0,199.9998535,0,0,0,90.00000001 +372.75,50.30085681,-2.611425073,10500,0,200.0009685,0,0,0,90.00000001 +372.76,50.30085681,-2.611397047,10500,0,200.0009685,0,0,0,90.00000001 +372.77,50.30085681,-2.611369022,10500,0,199.9998535,0,0,0,90.00000001 +372.78,50.30085681,-2.611340997,10500,0,199.9989614,0,0,0,90.00000001 +372.79,50.30085681,-2.611312972,10500,0,199.9987384,0,0,0,90.00000001 +372.8,50.30085681,-2.611284947,10500,0,199.9989614,0,0,0,90.00000001 +372.81,50.30085681,-2.611256922,10500,0,199.9998535,0,0,0,90.00000001 +372.82,50.30085681,-2.611228897,10500,0,200.0009685,0,0,0,90.00000001 +372.83,50.30085681,-2.611200871,10500,0,200.0009685,0,0,0,90.00000001 +372.84,50.30085681,-2.611172846,10500,0,199.9998535,0,0,0,90.00000001 +372.85,50.30085681,-2.611144821,10500,0,199.9989614,0,0,0,90.00000001 +372.86,50.30085681,-2.611116796,10500,0,199.9989614,0,0,0,90.00000001 +372.87,50.30085681,-2.611088771,10500,0,199.9998535,0,0,0,90.00000001 +372.88,50.30085681,-2.611060746,10500,0,200.0009685,0,0,0,90.00000001 +372.89,50.30085681,-2.61103272,10500,0,200.0009685,0,0,0,90.00000001 +372.9,50.30085681,-2.611004695,10500,0,199.9998535,0,0,0,90.00000001 +372.91,50.30085681,-2.61097667,10500,0,199.9989614,0,0,0,90.00000001 +372.92,50.30085681,-2.610948645,10500,0,199.9989614,0,0,0,90.00000001 +372.93,50.30085681,-2.61092062,10500,0,199.9998535,0,0,0,90.00000001 +372.94,50.30085681,-2.610892595,10500,0,200.0009685,0,0,0,90.00000001 +372.95,50.30085681,-2.610864569,10500,0,200.0009685,0,0,0,90.00000001 +372.96,50.30085681,-2.610836544,10500,0,199.9998535,0,0,0,90.00000001 +372.97,50.30085681,-2.610808519,10500,0,199.9991844,0,0,0,90.00000001 +372.98,50.30085681,-2.610780494,10500,0,199.9998535,0,0,0,90.00000001 +372.99,50.30085681,-2.610752469,10500,0,200.0009685,0,0,0,90.00000001 +373,50.30085681,-2.610724443,10500,0,200.0009685,0,0,0,90.00000001 +373.01,50.30085681,-2.610696418,10500,0,199.9998535,0,0,0,90.00000001 +373.02,50.30085681,-2.610668393,10500,0,199.9991844,0,0,0,90.00000001 +373.03,50.30085681,-2.610640368,10500,0,199.9998535,0,0,0,90.00000001 +373.04,50.30085681,-2.610612343,10500,0,200.0009685,0,0,0,90.00000001 +373.05,50.30085681,-2.610584317,10500,0,200.0009685,0,0,0,90.00000001 +373.06,50.30085681,-2.610556292,10500,0,199.9998535,0,0,0,90.00000001 +373.07,50.30085681,-2.610528267,10500,0,199.9991844,0,0,0,90.00000001 +373.08,50.30085681,-2.610500242,10500,0,199.9998535,0,0,0,90.00000001 +373.09,50.30085681,-2.610472217,10500,0,200.0009685,0,0,0,90.00000001 +373.1,50.30085681,-2.610444191,10500,0,200.0009685,0,0,0,90.00000001 +373.11,50.30085681,-2.610416166,10500,0,199.9998535,0,0,0,90.00000001 +373.12,50.30085681,-2.610388141,10500,0,199.9991844,0,0,0,90.00000001 +373.13,50.30085681,-2.610360116,10500,0,199.9998535,0,0,0,90.00000001 +373.14,50.30085681,-2.610332091,10500,0,200.0009685,0,0,0,90.00000001 +373.15,50.30085681,-2.610304065,10500,0,200.0009685,0,0,0,90.00000001 +373.16,50.30085681,-2.61027604,10500,0,199.9998535,0,0,0,90.00000001 +373.17,50.30085681,-2.610248015,10500,0,199.9991844,0,0,0,90.00000001 +373.18,50.30085681,-2.61021999,10500,0,199.9998535,0,0,0,90.00000001 +373.19,50.30085681,-2.610191965,10500,0,200.0009685,0,0,0,90.00000001 +373.2,50.30085681,-2.610163939,10500,0,200.0009685,0,0,0,90.00000001 +373.21,50.30085681,-2.610135914,10500,0,199.9998535,0,0,0,90.00000001 +373.22,50.30085681,-2.610107889,10500,0,199.9989614,0,0,0,90.00000001 +373.23,50.30085681,-2.610079864,10500,0,199.9989614,0,0,0,90.00000001 +373.24,50.30085681,-2.610051839,10500,0,199.9998535,0,0,0,90.00000001 +373.25,50.30085681,-2.610023814,10500,0,200.0009685,0,0,0,90.00000001 +373.26,50.30085681,-2.609995788,10500,0,200.0009685,0,0,0,90.00000001 +373.27,50.30085681,-2.609967763,10500,0,199.9998535,0,0,0,90.00000001 +373.28,50.30085681,-2.609939738,10500,0,199.9989614,0,0,0,90.00000001 +373.29,50.30085681,-2.609911713,10500,0,199.9989614,0,0,0,90.00000001 +373.3,50.30085681,-2.609883688,10500,0,199.9998535,0,0,0,90.00000001 +373.31,50.30085681,-2.609855663,10500,0,200.0009685,0,0,0,90.00000001 +373.32,50.30085681,-2.609827637,10500,0,200.0009685,0,0,0,90.00000001 +373.33,50.30085681,-2.609799612,10500,0,199.9998535,0,0,0,90.00000001 +373.34,50.30085681,-2.609771587,10500,0,199.9989614,0,0,0,90.00000001 +373.35,50.30085681,-2.609743562,10500,0,199.9987384,0,0,0,90.00000001 +373.36,50.30085681,-2.609715537,10500,0,199.9989614,0,0,0,90.00000001 +373.37,50.30085681,-2.609687512,10500,0,199.9998535,0,0,0,90.00000001 +373.38,50.30085681,-2.609659487,10500,0,200.0009685,0,0,0,90.00000001 +373.39,50.30085681,-2.609631461,10500,0,200.0009685,0,0,0,90.00000001 +373.4,50.30085681,-2.609603436,10500,0,199.9998535,0,0,0,90.00000001 +373.41,50.30085681,-2.609575411,10500,0,199.9989614,0,0,0,90.00000001 +373.42,50.30085681,-2.609547386,10500,0,199.9989614,0,0,0,90.00000001 +373.43,50.30085681,-2.609519361,10500,0,199.9998535,0,0,0,90.00000001 +373.44,50.30085681,-2.609491336,10500,0,200.0009685,0,0,0,90.00000001 +373.45,50.30085681,-2.60946331,10500,0,200.0009685,0,0,0,90.00000001 +373.46,50.30085681,-2.609435285,10500,0,199.9998535,0,0,0,90.00000001 +373.47,50.30085681,-2.60940726,10500,0,199.9989614,0,0,0,90.00000001 +373.48,50.30085681,-2.609379235,10500,0,199.9989614,0,0,0,90.00000001 +373.49,50.30085681,-2.60935121,10500,0,199.9998535,0,0,0,90.00000001 +373.5,50.30085681,-2.609323185,10500,0,200.0009685,0,0,0,90.00000001 +373.51,50.30085681,-2.609295159,10500,0,200.0009685,0,0,0,90.00000001 +373.52,50.30085681,-2.609267134,10500,0,199.9998535,0,0,0,90.00000001 +373.53,50.30085681,-2.609239109,10500,0,199.9989614,0,0,0,90.00000001 +373.54,50.30085681,-2.609211084,10500,0,199.9989614,0,0,0,90.00000001 +373.55,50.30085681,-2.609183059,10500,0,199.9998535,0,0,0,90.00000001 +373.56,50.30085681,-2.609155034,10500,0,200.0009685,0,0,0,90.00000001 +373.57,50.30085681,-2.609127008,10500,0,200.0009685,0,0,0,90.00000001 +373.58,50.30085681,-2.609098983,10500,0,199.9998535,0,0,0,90.00000001 +373.59,50.30085681,-2.609070958,10500,0,199.9991844,0,0,0,90.00000001 +373.6,50.30085681,-2.609042933,10500,0,199.9998535,0,0,0,90.00000001 +373.61,50.30085681,-2.609014908,10500,0,200.0009685,0,0,0,90.00000001 +373.62,50.30085681,-2.608986882,10500,0,200.0009685,0,0,0,90.00000001 +373.63,50.30085681,-2.608958857,10500,0,199.9998535,0,0,0,90.00000001 +373.64,50.30085681,-2.608930832,10500,0,199.9991844,0,0,0,90.00000001 +373.65,50.30085681,-2.608902807,10500,0,199.9998535,0,0,0,90.00000001 +373.66,50.30085681,-2.608874782,10500,0,200.0009685,0,0,0,90.00000001 +373.67,50.30085681,-2.608846756,10500,0,200.0009685,0,0,0,90.00000001 +373.68,50.30085681,-2.608818731,10500,0,199.9998535,0,0,0,90.00000001 +373.69,50.30085681,-2.608790706,10500,0,199.9991844,0,0,0,90.00000001 +373.7,50.30085681,-2.608762681,10500,0,199.9998535,0,0,0,90.00000001 +373.71,50.30085681,-2.608734656,10500,0,200.0009685,0,0,0,90.00000001 +373.72,50.30085681,-2.60870663,10500,0,200.0009685,0,0,0,90.00000001 +373.73,50.30085681,-2.608678605,10500,0,199.9998535,0,0,0,90.00000001 +373.74,50.30085681,-2.60865058,10500,0,199.9991844,0,0,0,90.00000001 +373.75,50.30085681,-2.608622555,10500,0,199.9998535,0,0,0,90.00000001 +373.76,50.30085681,-2.60859453,10500,0,200.0009685,0,0,0,90.00000001 +373.77,50.30085681,-2.608566504,10500,0,200.0009685,0,0,0,90.00000001 +373.78,50.30085681,-2.608538479,10500,0,199.9998535,0,0,0,90.00000001 +373.79,50.30085681,-2.608510454,10500,0,199.9991844,0,0,0,90.00000001 +373.8,50.30085681,-2.608482429,10500,0,199.9998535,0,0,0,90.00000001 +373.81,50.30085681,-2.608454404,10500,0,200.0009685,0,0,0,90.00000001 +373.82,50.30085681,-2.608426378,10500,0,200.0009685,0,0,0,90.00000001 +373.83,50.30085681,-2.608398353,10500,0,199.9998535,0,0,0,90.00000001 +373.84,50.30085681,-2.608370328,10500,0,199.9989614,0,0,0,90.00000001 +373.85,50.30085681,-2.608342303,10500,0,199.9989614,0,0,0,90.00000001 +373.86,50.30085681,-2.608314278,10500,0,199.9998535,0,0,0,90.00000001 +373.87,50.30085681,-2.608286253,10500,0,200.0009685,0,0,0,90.00000001 +373.88,50.30085681,-2.608258227,10500,0,200.0009685,0,0,0,90.00000001 +373.89,50.30085681,-2.608230202,10500,0,199.9998535,0,0,0,90.00000001 +373.9,50.30085681,-2.608202177,10500,0,199.9989614,0,0,0,90.00000001 +373.91,50.30085681,-2.608174152,10500,0,199.9987384,0,0,0,90.00000001 +373.92,50.30085681,-2.608146127,10500,0,199.9989614,0,0,0,90.00000001 +373.93,50.30085681,-2.608118102,10500,0,199.9998535,0,0,0,90.00000001 +373.94,50.30085681,-2.608090077,10500,0,200.0009685,0,0,0,90.00000001 +373.95,50.30085681,-2.608062051,10500,0,200.0009685,0,0,0,90.00000001 +373.96,50.30085681,-2.608034026,10500,0,199.9998535,0,0,0,90.00000001 +373.97,50.30085681,-2.608006001,10500,0,199.9989614,0,0,0,90.00000001 +373.98,50.30085681,-2.607977976,10500,0,199.9989614,0,0,0,90.00000001 +373.99,50.30085681,-2.607949951,10500,0,199.9998535,0,0,0,90.00000001 +374,50.30085681,-2.607921926,10500,0,200.0009685,0,0,0,90.00000001 +374.01,50.30085681,-2.6078939,10500,0,200.0009685,0,0,0,90.00000001 +374.02,50.30085681,-2.607865875,10500,0,199.9998535,0,0,0,90.00000001 +374.03,50.30085681,-2.60783785,10500,0,199.9989614,0,0,0,90.00000001 +374.04,50.30085681,-2.607809825,10500,0,199.9989614,0,0,0,90.00000001 +374.05,50.30085681,-2.6077818,10500,0,199.9998535,0,0,0,90.00000001 +374.06,50.30085681,-2.607753775,10500,0,200.0009685,0,0,0,90.00000001 +374.07,50.30085681,-2.607725749,10500,0,200.0009685,0,0,0,90.00000001 +374.08,50.30085681,-2.607697724,10500,0,199.9998535,0,0,0,90.00000001 +374.09,50.30085681,-2.607669699,10500,0,199.9989614,0,0,0,90.00000001 +374.1,50.30085681,-2.607641674,10500,0,199.9989614,0,0,0,90.00000001 +374.11,50.30085681,-2.607613649,10500,0,199.9998535,0,0,0,90.00000001 +374.12,50.30085681,-2.607585624,10500,0,200.0009685,0,0,0,90.00000001 +374.13,50.30085681,-2.607557598,10500,0,200.0009685,0,0,0,90.00000001 +374.14,50.30085681,-2.607529573,10500,0,199.9998535,0,0,0,90.00000001 +374.15,50.30085681,-2.607501548,10500,0,199.9989614,0,0,0,90.00000001 +374.16,50.30085681,-2.607473523,10500,0,199.9989614,0,0,0,90.00000001 +374.17,50.30085681,-2.607445498,10500,0,199.9998535,0,0,0,90.00000001 +374.18,50.30085681,-2.607417473,10500,0,200.0009685,0,0,0,90.00000001 +374.19,50.30085681,-2.607389447,10500,0,200.0009685,0,0,0,90.00000001 +374.2,50.30085681,-2.607361422,10500,0,199.9998535,0,0,0,90.00000001 +374.21,50.30085681,-2.607333397,10500,0,199.9991844,0,0,0,90.00000001 +374.22,50.30085681,-2.607305372,10500,0,199.9998535,0,0,0,90.00000001 +374.23,50.30085681,-2.607277347,10500,0,200.0009685,0,0,0,90.00000001 +374.24,50.30085681,-2.607249321,10500,0,200.0009685,0,0,0,90.00000001 +374.25,50.30085681,-2.607221296,10500,0,199.9998535,0,0,0,90.00000001 +374.26,50.30085681,-2.607193271,10500,0,199.9991844,0,0,0,90.00000001 +374.27,50.30085681,-2.607165246,10500,0,199.9998535,0,0,0,90.00000001 +374.28,50.30085681,-2.607137221,10500,0,200.0009685,0,0,0,90.00000001 +374.29,50.30085681,-2.607109195,10500,0,200.0009685,0,0,0,90.00000001 +374.3,50.30085681,-2.60708117,10500,0,199.9998535,0,0,0,90.00000001 +374.31,50.30085681,-2.607053145,10500,0,199.9991844,0,0,0,90.00000001 +374.32,50.30085681,-2.60702512,10500,0,199.9998535,0,0,0,90.00000001 +374.33,50.30085681,-2.606997095,10500,0,200.0009685,0,0,0,90.00000001 +374.34,50.30085681,-2.606969069,10500,0,200.0009685,0,0,0,90.00000001 +374.35,50.30085681,-2.606941044,10500,0,199.9998535,0,0,0,90.00000001 +374.36,50.30085681,-2.606913019,10500,0,199.9991844,0,0,0,90.00000001 +374.37,50.30085681,-2.606884994,10500,0,199.9998535,0,0,0,90.00000001 +374.38,50.30085681,-2.606856969,10500,0,200.0009685,0,0,0,90.00000001 +374.39,50.30085681,-2.606828943,10500,0,200.0009685,0,0,0,90.00000001 +374.4,50.30085681,-2.606800918,10500,0,199.9998535,0,0,0,90.00000001 +374.41,50.30085681,-2.606772893,10500,0,199.9991844,0,0,0,90.00000001 +374.42,50.30085681,-2.606744868,10500,0,199.9998535,0,0,0,90.00000001 +374.43,50.30085681,-2.606716843,10500,0,200.0009685,0,0,0,90.00000001 +374.44,50.30085681,-2.606688817,10500,0,200.0009685,0,0,0,90.00000001 +374.45,50.30085681,-2.606660792,10500,0,199.9998535,0,0,0,90.00000001 +374.46,50.30085681,-2.606632767,10500,0,199.9989614,0,0,0,90.00000001 +374.47,50.30085681,-2.606604742,10500,0,199.9989614,0,0,0,90.00000001 +374.48,50.30085681,-2.606576717,10500,0,199.9998535,0,0,0,90.00000001 +374.49,50.30085681,-2.606548692,10500,0,200.0009685,0,0,0,90.00000001 +374.5,50.30085681,-2.606520666,10500,0,200.0009685,0,0,0,90.00000001 +374.51,50.30085681,-2.606492641,10500,0,199.9998535,0,0,0,90.00000001 +374.52,50.30085681,-2.606464616,10500,0,199.9989614,0,0,0,90.00000001 +374.53,50.30085681,-2.606436591,10500,0,199.9987384,0,0,0,90.00000001 +374.54,50.30085681,-2.606408566,10500,0,199.9989614,0,0,0,90.00000001 +374.55,50.30085681,-2.606380541,10500,0,199.9998535,0,0,0,90.00000001 +374.56,50.30085681,-2.606352516,10500,0,200.0009685,0,0,0,90.00000001 +374.57,50.30085681,-2.60632449,10500,0,200.0009685,0,0,0,90.00000001 +374.58,50.30085681,-2.606296465,10500,0,199.9998535,0,0,0,90.00000001 +374.59,50.30085681,-2.60626844,10500,0,199.9989614,0,0,0,90.00000001 +374.6,50.30085681,-2.606240415,10500,0,199.9989614,0,0,0,90.00000001 +374.61,50.30085681,-2.60621239,10500,0,199.9998535,0,0,0,90.00000001 +374.62,50.30085681,-2.606184365,10500,0,200.0009685,0,0,0,90.00000001 +374.63,50.30085681,-2.606156339,10500,0,200.0009685,0,0,0,90.00000001 +374.64,50.30085681,-2.606128314,10500,0,199.9998535,0,0,0,90.00000001 +374.65,50.30085681,-2.606100289,10500,0,199.9989614,0,0,0,90.00000001 +374.66,50.30085681,-2.606072264,10500,0,199.9989614,0,0,0,90.00000001 +374.67,50.30085681,-2.606044239,10500,0,199.9998535,0,0,0,90.00000001 +374.68,50.30085681,-2.606016214,10500,0,200.0009685,0,0,0,90.00000001 +374.69,50.30085681,-2.605988188,10500,0,200.0009685,0,0,0,90.00000001 +374.7,50.30085681,-2.605960163,10500,0,199.9998535,0,0,0,90.00000001 +374.71,50.30085681,-2.605932138,10500,0,199.9989614,0,0,0,90.00000001 +374.72,50.30085681,-2.605904113,10500,0,199.9989614,0,0,0,90.00000001 +374.73,50.30085681,-2.605876088,10500,0,199.9998535,0,0,0,90.00000001 +374.74,50.30085681,-2.605848063,10500,0,200.0009685,0,0,0,90.00000001 +374.75,50.30085681,-2.605820037,10500,0,200.0009685,0,0,0,90.00000001 +374.76,50.30085681,-2.605792012,10500,0,199.9998535,0,0,0,90.00000001 +374.77,50.30085681,-2.605763987,10500,0,199.9989614,0,0,0,90.00000001 +374.78,50.30085681,-2.605735962,10500,0,199.9989614,0,0,0,90.00000001 +374.79,50.30085681,-2.605707937,10500,0,199.9998535,0,0,0,90.00000001 +374.8,50.30085681,-2.605679912,10500,0,200.0009685,0,0,0,90.00000001 +374.81,50.30085681,-2.605651886,10500,0,200.0009685,0,0,0,90.00000001 +374.82,50.30085681,-2.605623861,10500,0,199.9998535,0,0,0,90.00000001 +374.83,50.30085681,-2.605595836,10500,0,199.9991844,0,0,0,90.00000001 +374.84,50.30085681,-2.605567811,10500,0,199.9998535,0,0,0,90.00000001 +374.85,50.30085681,-2.605539786,10500,0,200.0009685,0,0,0,90.00000001 +374.86,50.30085681,-2.60551176,10500,0,200.0009685,0,0,0,90.00000001 +374.87,50.30085681,-2.605483735,10500,0,199.9998535,0,0,0,90.00000001 +374.88,50.30085681,-2.60545571,10500,0,199.9991844,0,0,0,90.00000001 +374.89,50.30085681,-2.605427685,10500,0,199.9998535,0,0,0,90.00000001 +374.9,50.30085681,-2.60539966,10500,0,200.0009685,0,0,0,90.00000001 +374.91,50.30085681,-2.605371634,10500,0,200.0009685,0,0,0,90.00000001 +374.92,50.30085681,-2.605343609,10500,0,199.9998535,0,0,0,90.00000001 +374.93,50.30085681,-2.605315584,10500,0,199.9991844,0,0,0,90.00000001 +374.94,50.30085681,-2.605287559,10500,0,199.9998535,0,0,0,90.00000001 +374.95,50.30085681,-2.605259534,10500,0,200.0009685,0,0,0,90.00000001 +374.96,50.30085681,-2.605231508,10500,0,200.0009685,0,0,0,90.00000001 +374.97,50.30085681,-2.605203483,10500,0,199.9998535,0,0,0,90.00000001 +374.98,50.30085681,-2.605175458,10500,0,199.9989614,0,0,0,90.00000001 +374.99,50.30085681,-2.605147433,10500,0,199.9989614,0,0,0,90.00000001 +375,50.30085681,-2.605119408,10500,0,199.9998535,0,0,0,90.00000001 +375.01,50.30085681,-2.605091383,10500,0,200.0009685,0,0,0,90.00000001 +375.02,50.30085681,-2.605063357,10500,0,200.0009685,0,0,0,90.00000001 +375.03,50.30085681,-2.605035332,10500,0,199.9998535,0,0,0,90.00000001 +375.04,50.30085681,-2.605007307,10500,0,199.9991844,0,0,0,90.00000001 +375.05,50.30085681,-2.604979282,10500,0,199.9998535,0,0,0,90.00000001 +375.06,50.30085681,-2.604951257,10500,0,200.0009685,0,0,0,90.00000001 +375.07,50.30085681,-2.604923231,10500,0,200.0009685,0,0,0,90.00000001 +375.08,50.30085681,-2.604895206,10500,0,199.9998535,0,0,0,90.00000001 +375.09,50.30085681,-2.604867181,10500,0,199.9989614,0,0,0,90.00000001 +375.1,50.30085681,-2.604839156,10500,0,199.9989614,0,0,0,90.00000001 +375.11,50.30085681,-2.604811131,10500,0,199.9998535,0,0,0,90.00000001 +375.12,50.30085681,-2.604783106,10500,0,200.0009685,0,0,0,90.00000001 +375.13,50.30085681,-2.60475508,10500,0,200.0009685,0,0,0,90.00000001 +375.14,50.30085681,-2.604727055,10500,0,199.9998535,0,0,0,90.00000001 +375.15,50.30085681,-2.60469903,10500,0,199.9989614,0,0,0,90.00000001 +375.16,50.30085681,-2.604671005,10500,0,199.9989614,0,0,0,90.00000001 +375.17,50.30085681,-2.60464298,10500,0,199.9998535,0,0,0,90.00000001 +375.18,50.30085681,-2.604614955,10500,0,200.0009685,0,0,0,90.00000001 +375.19,50.30085681,-2.604586929,10500,0,200.0009685,0,0,0,90.00000001 +375.2,50.30085681,-2.604558904,10500,0,199.9998535,0,0,0,90.00000001 +375.21,50.30085681,-2.604530879,10500,0,199.9989614,0,0,0,90.00000001 +375.22,50.30085681,-2.604502854,10500,0,199.9989614,0,0,0,90.00000001 +375.23,50.30085681,-2.604474829,10500,0,199.9998535,0,0,0,90.00000001 +375.24,50.30085681,-2.604446804,10500,0,200.0009685,0,0,0,90.00000001 +375.25,50.30085681,-2.604418778,10500,0,200.0009685,0,0,0,90.00000001 +375.26,50.30085681,-2.604390753,10500,0,199.9998535,0,0,0,90.00000001 +375.27,50.30085681,-2.604362728,10500,0,199.9989614,0,0,0,90.00000001 +375.28,50.30085681,-2.604334703,10500,0,199.9989614,0,0,0,90.00000001 +375.29,50.30085681,-2.604306678,10500,0,199.9998535,0,0,0,90.00000001 +375.3,50.30085681,-2.604278653,10500,0,200.0009685,0,0,0,90.00000001 +375.31,50.30085681,-2.604250627,10500,0,200.0009685,0,0,0,90.00000001 +375.32,50.30085681,-2.604222602,10500,0,199.9998535,0,0,0,90.00000001 +375.33,50.30085681,-2.604194577,10500,0,199.9989614,0,0,0,90.00000001 +375.34,50.30085681,-2.604166552,10500,0,199.9987384,0,0,0,90.00000001 +375.35,50.30085681,-2.604138527,10500,0,199.9989614,0,0,0,90.00000001 +375.36,50.30085681,-2.604110502,10500,0,199.9998535,0,0,0,90.00000001 +375.37,50.30085681,-2.604082477,10500,0,200.0009685,0,0,0,90.00000001 +375.38,50.30085681,-2.604054451,10500,0,200.0009685,0,0,0,90.00000001 +375.39,50.30085681,-2.604026426,10500,0,199.9998535,0,0,0,90.00000001 +375.4,50.30085681,-2.603998401,10500,0,199.9989614,0,0,0,90.00000001 +375.41,50.30085681,-2.603970376,10500,0,199.9989614,0,0,0,90.00000001 +375.42,50.30085681,-2.603942351,10500,0,199.9998535,0,0,0,90.00000001 +375.43,50.30085681,-2.603914326,10500,0,200.0009685,0,0,0,90.00000001 +375.44,50.30085681,-2.6038863,10500,0,200.0009685,0,0,0,90.00000001 +375.45,50.30085681,-2.603858275,10500,0,199.9998535,0,0,0,90.00000001 +375.46,50.30085681,-2.60383025,10500,0,199.9991844,0,0,0,90.00000001 +375.47,50.30085681,-2.603802225,10500,0,199.9998535,0,0,0,90.00000001 +375.48,50.30085681,-2.6037742,10500,0,200.0009685,0,0,0,90.00000001 +375.49,50.30085681,-2.603746174,10500,0,200.0009685,0,0,0,90.00000001 +375.5,50.30085681,-2.603718149,10500,0,199.9998535,0,0,0,90.00000001 +375.51,50.30085681,-2.603690124,10500,0,199.9991844,0,0,0,90.00000001 +375.52,50.30085681,-2.603662099,10500,0,199.9998535,0,0,0,90.00000001 +375.53,50.30085681,-2.603634074,10500,0,200.0009685,0,0,0,90.00000001 +375.54,50.30085681,-2.603606048,10500,0,200.0009685,0,0,0,90.00000001 +375.55,50.30085681,-2.603578023,10500,0,199.9998535,0,0,0,90.00000001 +375.56,50.30085681,-2.603549998,10500,0,199.9991844,0,0,0,90.00000001 +375.57,50.30085681,-2.603521973,10500,0,199.9998535,0,0,0,90.00000001 +375.58,50.30085681,-2.603493948,10500,0,200.0009685,0,0,0,90.00000001 +375.59,50.30085681,-2.603465922,10500,0,200.0009685,0,0,0,90.00000001 +375.6,50.30085681,-2.603437897,10500,0,199.9998535,0,0,0,90.00000001 +375.61,50.30085681,-2.603409872,10500,0,199.9991844,0,0,0,90.00000001 +375.62,50.30085681,-2.603381847,10500,0,199.9998535,0,0,0,90.00000001 +375.63,50.30085681,-2.603353822,10500,0,200.0009685,0,0,0,90.00000001 +375.64,50.30085681,-2.603325796,10500,0,200.0009685,0,0,0,90.00000001 +375.65,50.30085681,-2.603297771,10500,0,199.9998535,0,0,0,90.00000001 +375.66,50.30085681,-2.603269746,10500,0,199.9991844,0,0,0,90.00000001 +375.67,50.30085681,-2.603241721,10500,0,199.9998535,0,0,0,90.00000001 +375.68,50.30085681,-2.603213696,10500,0,200.0009685,0,0,0,90.00000001 +375.69,50.30085681,-2.60318567,10500,0,200.0009685,0,0,0,90.00000001 +375.7,50.30085681,-2.603157645,10500,0,199.9998535,0,0,0,90.00000001 +375.71,50.30085681,-2.60312962,10500,0,199.9989614,0,0,0,90.00000001 +375.72,50.30085681,-2.603101595,10500,0,199.9989614,0,0,0,90.00000001 +375.73,50.30085681,-2.60307357,10500,0,199.9998535,0,0,0,90.00000001 +375.74,50.30085681,-2.603045545,10500,0,200.0009685,0,0,0,90.00000001 +375.75,50.30085681,-2.603017519,10500,0,200.0009685,0,0,0,90.00000001 +375.76,50.30085681,-2.602989494,10500,0,199.9998535,0,0,0,90.00000001 +375.77,50.30085681,-2.602961469,10500,0,199.9989614,0,0,0,90.00000001 +375.78,50.30085681,-2.602933444,10500,0,199.9989614,0,0,0,90.00000001 +375.79,50.30085681,-2.602905419,10500,0,199.9998535,0,0,0,90.00000001 +375.8,50.30085681,-2.602877394,10500,0,200.0009685,0,0,0,90.00000001 +375.81,50.30085681,-2.602849368,10500,0,200.0009685,0,0,0,90.00000001 +375.82,50.30085681,-2.602821343,10500,0,199.9998535,0,0,0,90.00000001 +375.83,50.30085681,-2.602793318,10500,0,199.9989614,0,0,0,90.00000001 +375.84,50.30085681,-2.602765293,10500,0,199.9989614,0,0,0,90.00000001 +375.85,50.30085681,-2.602737268,10500,0,199.9998535,0,0,0,90.00000001 +375.86,50.30085681,-2.602709243,10500,0,200.0009685,0,0,0,90.00000001 +375.87,50.30085681,-2.602681217,10500,0,200.0009685,0,0,0,90.00000001 +375.88,50.30085681,-2.602653192,10500,0,199.9998535,0,0,0,90.00000001 +375.89,50.30085681,-2.602625167,10500,0,199.9989614,0,0,0,90.00000001 +375.9,50.30085681,-2.602597142,10500,0,199.9989614,0,0,0,90.00000001 +375.91,50.30085681,-2.602569117,10500,0,199.9998535,0,0,0,90.00000001 +375.92,50.30085681,-2.602541092,10500,0,200.0009685,0,0,0,90.00000001 +375.93,50.30085681,-2.602513066,10500,0,200.0009685,0,0,0,90.00000001 +375.94,50.30085681,-2.602485041,10500,0,199.9998535,0,0,0,90.00000001 +375.95,50.30085681,-2.602457016,10500,0,199.9989614,0,0,0,90.00000001 +375.96,50.30085681,-2.602428991,10500,0,199.9987384,0,0,0,90.00000001 +375.97,50.30085681,-2.602400966,10500,0,199.9989614,0,0,0,90.00000001 +375.98,50.30085681,-2.602372941,10500,0,199.9998535,0,0,0,90.00000001 +375.99,50.30085681,-2.602344916,10500,0,200.0009685,0,0,0,90.00000001 +376,50.30085681,-2.60231689,10500,0,200.0009685,0,0,0,90.00000001 +376.01,50.30085681,-2.602288865,10500,0,199.9998535,0,0,0,90.00000001 +376.02,50.30085681,-2.60226084,10500,0,199.9989614,0,0,0,90.00000001 +376.03,50.30085681,-2.602232815,10500,0,199.9989614,0,0,0,90.00000001 +376.04,50.30085681,-2.60220479,10500,0,199.9998535,0,0,0,90.00000001 +376.05,50.30085681,-2.602176765,10500,0,200.0009685,0,0,0,90.00000001 +376.06,50.30085681,-2.602148739,10500,0,200.0009685,0,0,0,90.00000001 +376.07,50.30085681,-2.602120714,10500,0,199.9998535,0,0,0,90.00000001 +376.08,50.30085681,-2.602092689,10500,0,199.9991844,0,0,0,90.00000001 +376.09,50.30085681,-2.602064664,10500,0,199.9998535,0,0,0,90.00000001 +376.1,50.30085681,-2.602036639,10500,0,200.0009685,0,0,0,90.00000001 +376.11,50.30085681,-2.602008613,10500,0,200.0009685,0,0,0,90.00000001 +376.12,50.30085681,-2.601980588,10500,0,199.9998535,0,0,0,90.00000001 +376.13,50.30085681,-2.601952563,10500,0,199.9991844,0,0,0,90.00000001 +376.14,50.30085681,-2.601924538,10500,0,199.9998535,0,0,0,90.00000001 +376.15,50.30085681,-2.601896513,10500,0,200.0009685,0,0,0,90.00000001 +376.16,50.30085681,-2.601868487,10500,0,200.0009685,0,0,0,90.00000001 +376.17,50.30085681,-2.601840462,10500,0,199.9998535,0,0,0,90.00000001 +376.18,50.30085681,-2.601812437,10500,0,199.9991844,0,0,0,90.00000001 +376.19,50.30085681,-2.601784412,10500,0,199.9998535,0,0,0,90.00000001 +376.2,50.30085681,-2.601756387,10500,0,200.0009685,0,0,0,90.00000001 +376.21,50.30085681,-2.601728361,10500,0,200.0009685,0,0,0,90.00000001 +376.22,50.30085681,-2.601700336,10500,0,199.9998535,0,0,0,90.00000001 +376.23,50.30085681,-2.601672311,10500,0,199.9991844,0,0,0,90.00000001 +376.24,50.30085681,-2.601644286,10500,0,199.9998535,0,0,0,90.00000001 +376.25,50.30085681,-2.601616261,10500,0,200.0009685,0,0,0,90.00000001 +376.26,50.30085681,-2.601588235,10500,0,200.0009685,0,0,0,90.00000001 +376.27,50.30085681,-2.60156021,10500,0,199.9998535,0,0,0,90.00000001 +376.28,50.30085681,-2.601532185,10500,0,199.9991844,0,0,0,90.00000001 +376.29,50.30085681,-2.60150416,10500,0,199.9998535,0,0,0,90.00000001 +376.3,50.30085681,-2.601476135,10500,0,200.0009685,0,0,0,90.00000001 +376.31,50.30085681,-2.601448109,10500,0,200.0009685,0,0,0,90.00000001 +376.32,50.30085681,-2.601420084,10500,0,199.9998535,0,0,0,90.00000001 +376.33,50.30085681,-2.601392059,10500,0,199.9989614,0,0,0,90.00000001 +376.34,50.30085681,-2.601364034,10500,0,199.9989614,0,0,0,90.00000001 +376.35,50.30085681,-2.601336009,10500,0,199.9998535,0,0,0,90.00000001 +376.36,50.30085681,-2.601307984,10500,0,200.0009685,0,0,0,90.00000001 +376.37,50.30085681,-2.601279958,10500,0,200.0009685,0,0,0,90.00000001 +376.38,50.30085681,-2.601251933,10500,0,199.9998535,0,0,0,90.00000001 +376.39,50.30085681,-2.601223908,10500,0,199.9989614,0,0,0,90.00000001 +376.4,50.30085681,-2.601195883,10500,0,199.9989614,0,0,0,90.00000001 +376.41,50.30085681,-2.601167858,10500,0,199.9998535,0,0,0,90.00000001 +376.42,50.30085681,-2.601139833,10500,0,200.0009685,0,0,0,90.00000001 +376.43,50.30085681,-2.601111807,10500,0,200.0009685,0,0,0,90.00000001 +376.44,50.30085681,-2.601083782,10500,0,199.9998535,0,0,0,90.00000001 +376.45,50.30085681,-2.601055757,10500,0,199.9989614,0,0,0,90.00000001 +376.46,50.30085681,-2.601027732,10500,0,199.9989614,0,0,0,90.00000001 +376.47,50.30085681,-2.600999707,10500,0,199.9998535,0,0,0,90.00000001 +376.48,50.30085681,-2.600971682,10500,0,200.0009685,0,0,0,90.00000001 +376.49,50.30085681,-2.600943656,10500,0,200.0009685,0,0,0,90.00000001 +376.5,50.30085681,-2.600915631,10500,0,199.9998535,0,0,0,90.00000001 +376.51,50.30085681,-2.600887606,10500,0,199.9989614,0,0,0,90.00000001 +376.52,50.30085681,-2.600859581,10500,0,199.9987384,0,0,0,90.00000001 +376.53,50.30085681,-2.600831556,10500,0,199.9989614,0,0,0,90.00000001 +376.54,50.30085681,-2.600803531,10500,0,199.9998535,0,0,0,90.00000001 +376.55,50.30085681,-2.600775506,10500,0,200.0009685,0,0,0,90.00000001 +376.56,50.30085681,-2.60074748,10500,0,200.0009685,0,0,0,90.00000001 +376.57,50.30085681,-2.600719455,10500,0,199.9998535,0,0,0,90.00000001 +376.58,50.30085681,-2.60069143,10500,0,199.9989614,0,0,0,90.00000001 +376.59,50.30085681,-2.600663405,10500,0,199.9989614,0,0,0,90.00000001 +376.6,50.30085681,-2.60063538,10500,0,199.9998535,0,0,0,90.00000001 +376.61,50.30085681,-2.600607355,10500,0,200.0009685,0,0,0,90.00000001 +376.62,50.30085681,-2.600579329,10500,0,200.0009685,0,0,0,90.00000001 +376.63,50.30085681,-2.600551304,10500,0,199.9998535,0,0,0,90.00000001 +376.64,50.30085681,-2.600523279,10500,0,199.9989614,0,0,0,90.00000001 +376.65,50.30085681,-2.600495254,10500,0,199.9989614,0,0,0,90.00000001 +376.66,50.30085681,-2.600467229,10500,0,199.9998535,0,0,0,90.00000001 +376.67,50.30085681,-2.600439204,10500,0,200.0009685,0,0,0,90.00000001 +376.68,50.30085681,-2.600411178,10500,0,200.0009685,0,0,0,90.00000001 +376.69,50.30085681,-2.600383153,10500,0,199.9998535,0,0,0,90.00000001 +376.7,50.30085681,-2.600355128,10500,0,199.9991844,0,0,0,90.00000001 +376.71,50.30085681,-2.600327103,10500,0,199.9998535,0,0,0,90.00000001 +376.72,50.30085681,-2.600299078,10500,0,200.0009685,0,0,0,90.00000001 +376.73,50.30085681,-2.600271052,10500,0,200.0009685,0,0,0,90.00000001 +376.74,50.30085681,-2.600243027,10500,0,199.9998535,0,0,0,90.00000001 +376.75,50.30085681,-2.600215002,10500,0,199.9991844,0,0,0,90.00000001 +376.76,50.30085681,-2.600186977,10500,0,199.9998535,0,0,0,90.00000001 +376.77,50.30085681,-2.600158952,10500,0,200.0009685,0,0,0,90.00000001 +376.78,50.30085681,-2.600130926,10500,0,200.0009685,0,0,0,90.00000001 +376.79,50.30085681,-2.600102901,10500,0,199.9998535,0,0,0,90.00000001 +376.8,50.30085681,-2.600074876,10500,0,199.9991844,0,0,0,90.00000001 +376.81,50.30085681,-2.600046851,10500,0,199.9998535,0,0,0,90.00000001 +376.82,50.30085681,-2.600018826,10500,0,200.0009685,0,0,0,90.00000001 +376.83,50.30085681,-2.5999908,10500,0,200.0009685,0,0,0,90.00000001 +376.84,50.30085681,-2.599962775,10500,0,199.9998535,0,0,0,90.00000001 +376.85,50.30085681,-2.59993475,10500,0,199.9991844,0,0,0,90.00000001 +376.86,50.30085681,-2.599906725,10500,0,199.9998535,0,0,0,90.00000001 +376.87,50.30085681,-2.5998787,10500,0,200.0009685,0,0,0,90.00000001 +376.88,50.30085681,-2.599850674,10500,0,200.0009685,0,0,0,90.00000001 +376.89,50.30085681,-2.599822649,10500,0,199.9998535,0,0,0,90.00000001 +376.9,50.30085681,-2.599794624,10500,0,199.9991844,0,0,0,90.00000001 +376.91,50.30085681,-2.599766599,10500,0,199.9998535,0,0,0,90.00000001 +376.92,50.30085681,-2.599738574,10500,0,200.0009685,0,0,0,90.00000001 +376.93,50.30085681,-2.599710548,10500,0,200.0009685,0,0,0,90.00000001 +376.94,50.30085681,-2.599682523,10500,0,199.9998535,0,0,0,90.00000001 +376.95,50.30085681,-2.599654498,10500,0,199.9989614,0,0,0,90.00000001 +376.96,50.30085681,-2.599626473,10500,0,199.9989614,0,0,0,90.00000001 +376.97,50.30085681,-2.599598448,10500,0,199.9998535,0,0,0,90.00000001 +376.98,50.30085681,-2.599570423,10500,0,200.0009685,0,0,0,90.00000001 +376.99,50.30085681,-2.599542397,10500,0,200.0009685,0,0,0,90.00000001 +377,50.30085681,-2.599514372,10500,0,199.9998535,0,0,0,90.00000001 +377.01,50.30085681,-2.599486347,10500,0,199.9989614,0,0,0,90.00000001 +377.02,50.30085681,-2.599458322,10500,0,199.9989614,0,0,0,90.00000001 +377.03,50.30085681,-2.599430297,10500,0,199.9998535,0,0,0,90.00000001 +377.04,50.30085681,-2.599402272,10500,0,200.0009685,0,0,0,90.00000001 +377.05,50.30085681,-2.599374246,10500,0,200.0009685,0,0,0,90.00000001 +377.06,50.30085681,-2.599346221,10500,0,199.9998535,0,0,0,90.00000001 +377.07,50.30085681,-2.599318196,10500,0,199.9989614,0,0,0,90.00000001 +377.08,50.30085681,-2.599290171,10500,0,199.9987384,0,0,0,90.00000001 +377.09,50.30085681,-2.599262146,10500,0,199.9989614,0,0,0,90.00000001 +377.1,50.30085681,-2.599234121,10500,0,199.9998535,0,0,0,90.00000001 +377.11,50.30085681,-2.599206096,10500,0,200.0009685,0,0,0,90.00000001 +377.12,50.30085681,-2.59917807,10500,0,200.0009685,0,0,0,90.00000001 +377.13,50.30085681,-2.599150045,10500,0,199.9998535,0,0,0,90.00000001 +377.14,50.30085681,-2.59912202,10500,0,199.9989614,0,0,0,90.00000001 +377.15,50.30085681,-2.599093995,10500,0,199.9989614,0,0,0,90.00000001 +377.16,50.30085681,-2.59906597,10500,0,199.9998535,0,0,0,90.00000001 +377.17,50.30085681,-2.599037945,10500,0,200.0009685,0,0,0,90.00000001 +377.18,50.30085681,-2.599009919,10500,0,200.0009685,0,0,0,90.00000001 +377.19,50.30085681,-2.598981894,10500,0,199.9998535,0,0,0,90.00000001 +377.2,50.30085681,-2.598953869,10500,0,199.9989614,0,0,0,90.00000001 +377.21,50.30085681,-2.598925844,10500,0,199.9989614,0,0,0,90.00000001 +377.22,50.30085681,-2.598897819,10500,0,199.9998535,0,0,0,90.00000001 +377.23,50.30085681,-2.598869794,10500,0,200.0009685,0,0,0,90.00000001 +377.24,50.30085681,-2.598841768,10500,0,200.0009685,0,0,0,90.00000001 +377.25,50.30085681,-2.598813743,10500,0,199.9998535,0,0,0,90.00000001 +377.26,50.30085681,-2.598785718,10500,0,199.9989614,0,0,0,90.00000001 +377.27,50.30085681,-2.598757693,10500,0,199.9989614,0,0,0,90.00000001 +377.28,50.30085681,-2.598729668,10500,0,199.9998535,0,0,0,90.00000001 +377.29,50.30085681,-2.598701643,10500,0,200.0009685,0,0,0,90.00000001 +377.3,50.30085681,-2.598673617,10500,0,200.0009685,0,0,0,90.00000001 +377.31,50.30085681,-2.598645592,10500,0,199.9998535,0,0,0,90.00000001 +377.32,50.30085681,-2.598617567,10500,0,199.9991844,0,0,0,90.00000001 +377.33,50.30085681,-2.598589542,10500,0,199.9998535,0,0,0,90.00000001 +377.34,50.30085681,-2.598561517,10500,0,200.0009685,0,0,0,90.00000001 +377.35,50.30085681,-2.598533491,10500,0,200.0009685,0,0,0,90.00000001 +377.36,50.30085681,-2.598505466,10500,0,199.9998535,0,0,0,90.00000001 +377.37,50.30085681,-2.598477441,10500,0,199.9989614,0,0,0,90.00000001 +377.38,50.30085681,-2.598449416,10500,0,199.9989614,0,0,0,90.00000001 +377.39,50.30085681,-2.598421391,10500,0,199.9998535,0,0,0,90.00000001 +377.4,50.30085681,-2.598393366,10500,0,200.0009685,0,0,0,90.00000001 +377.41,50.30085681,-2.59836534,10500,0,200.0009685,0,0,0,90.00000001 +377.42,50.30085681,-2.598337315,10500,0,199.9998535,0,0,0,90.00000001 +377.43,50.30085681,-2.59830929,10500,0,199.9991844,0,0,0,90.00000001 +377.44,50.30085681,-2.598281265,10500,0,199.9998535,0,0,0,90.00000001 +377.45,50.30085681,-2.59825324,10500,0,200.0009685,0,0,0,90.00000001 +377.46,50.30085681,-2.598225214,10500,0,200.0009685,0,0,0,90.00000001 +377.47,50.30085681,-2.598197189,10500,0,199.9998535,0,0,0,90.00000001 +377.48,50.30085681,-2.598169164,10500,0,199.9991844,0,0,0,90.00000001 +377.49,50.30085681,-2.598141139,10500,0,199.9998535,0,0,0,90.00000001 +377.5,50.30085681,-2.598113114,10500,0,200.0009685,0,0,0,90.00000001 +377.51,50.30085681,-2.598085088,10500,0,200.0009685,0,0,0,90.00000001 +377.52,50.30085681,-2.598057063,10500,0,199.9998535,0,0,0,90.00000001 +377.53,50.30085681,-2.598029038,10500,0,199.9991844,0,0,0,90.00000001 +377.54,50.30085681,-2.598001013,10500,0,199.9998535,0,0,0,90.00000001 +377.55,50.30085681,-2.597972988,10500,0,200.0009685,0,0,0,90.00000001 +377.56,50.30085681,-2.597944962,10500,0,200.0009685,0,0,0,90.00000001 +377.57,50.30085681,-2.597916937,10500,0,199.9998535,0,0,0,90.00000001 +377.58,50.30085681,-2.597888912,10500,0,199.9991844,0,0,0,90.00000001 +377.59,50.30085681,-2.597860887,10500,0,199.9998535,0,0,0,90.00000001 +377.6,50.30085681,-2.597832862,10500,0,200.0009685,0,0,0,90.00000001 +377.61,50.30085681,-2.597804836,10500,0,200.0009685,0,0,0,90.00000001 +377.62,50.30085681,-2.597776811,10500,0,199.9998535,0,0,0,90.00000001 +377.63,50.30085681,-2.597748786,10500,0,199.9989614,0,0,0,90.00000001 +377.64,50.30085681,-2.597720761,10500,0,199.9987384,0,0,0,90.00000001 +377.65,50.30085681,-2.597692736,10500,0,199.9989614,0,0,0,90.00000001 +377.66,50.30085681,-2.597664711,10500,0,199.9998535,0,0,0,90.00000001 +377.67,50.30085681,-2.597636686,10500,0,200.0009685,0,0,0,90.00000001 +377.68,50.30085681,-2.59760866,10500,0,200.0009685,0,0,0,90.00000001 +377.69,50.30085681,-2.597580635,10500,0,199.9998535,0,0,0,90.00000001 +377.7,50.30085681,-2.59755261,10500,0,199.9989614,0,0,0,90.00000001 +377.71,50.30085681,-2.597524585,10500,0,199.9989614,0,0,0,90.00000001 +377.72,50.30085681,-2.59749656,10500,0,199.9998535,0,0,0,90.00000001 +377.73,50.30085681,-2.597468535,10500,0,200.0009685,0,0,0,90.00000001 +377.74,50.30085681,-2.597440509,10500,0,200.0009685,0,0,0,90.00000001 +377.75,50.30085681,-2.597412484,10500,0,199.9998535,0,0,0,90.00000001 +377.76,50.30085681,-2.597384459,10500,0,199.9989614,0,0,0,90.00000001 +377.77,50.30085681,-2.597356434,10500,0,199.9989614,0,0,0,90.00000001 +377.78,50.30085681,-2.597328409,10500,0,199.9998535,0,0,0,90.00000001 +377.79,50.30085681,-2.597300384,10500,0,200.0009685,0,0,0,90.00000001 +377.8,50.30085681,-2.597272358,10500,0,200.0009685,0,0,0,90.00000001 +377.81,50.30085681,-2.597244333,10500,0,199.9998535,0,0,0,90.00000001 +377.82,50.30085681,-2.597216308,10500,0,199.9989614,0,0,0,90.00000001 +377.83,50.30085681,-2.597188283,10500,0,199.9989614,0,0,0,90.00000001 +377.84,50.30085681,-2.597160258,10500,0,199.9998535,0,0,0,90.00000001 +377.85,50.30085681,-2.597132233,10500,0,200.0009685,0,0,0,90.00000001 +377.86,50.30085681,-2.597104207,10500,0,200.0009685,0,0,0,90.00000001 +377.87,50.30085681,-2.597076182,10500,0,199.9998535,0,0,0,90.00000001 +377.88,50.30085681,-2.597048157,10500,0,199.9989614,0,0,0,90.00000001 +377.89,50.30085681,-2.597020132,10500,0,199.9989614,0,0,0,90.00000001 +377.9,50.30085681,-2.596992107,10500,0,199.9998535,0,0,0,90.00000001 +377.91,50.30085681,-2.596964082,10500,0,200.0009685,0,0,0,90.00000001 +377.92,50.30085681,-2.596936056,10500,0,200.0009685,0,0,0,90.00000001 +377.93,50.30085681,-2.596908031,10500,0,199.9998535,0,0,0,90.00000001 +377.94,50.30085681,-2.596880006,10500,0,199.9989614,0,0,0,90.00000001 +377.95,50.30085681,-2.596851981,10500,0,199.9989614,0,0,0,90.00000001 +377.96,50.30085681,-2.596823956,10500,0,199.9998535,0,0,0,90.00000001 +377.97,50.30085681,-2.596795931,10500,0,200.0009685,0,0,0,90.00000001 +377.98,50.30085681,-2.596767905,10500,0,200.0009685,0,0,0,90.00000001 +377.99,50.30085681,-2.59673988,10500,0,199.9998535,0,0,0,90.00000001 +378,50.30085681,-2.596711855,10500,0,199.9991844,0,0,0,90.00000001 +378.01,50.30085681,-2.59668383,10500,0,199.9998535,0,0,0,90.00000001 +378.02,50.30085681,-2.596655805,10500,0,200.0009685,0,0,0,90.00000001 +378.03,50.30085681,-2.596627779,10500,0,200.0009685,0,0,0,90.00000001 +378.04,50.30085681,-2.596599754,10500,0,199.9998535,0,0,0,90.00000001 +378.05,50.30085681,-2.596571729,10500,0,199.9991844,0,0,0,90.00000001 +378.06,50.30085681,-2.596543704,10500,0,199.9998535,0,0,0,90.00000001 +378.07,50.30085681,-2.596515679,10500,0,200.0009685,0,0,0,90.00000001 +378.08,50.30085681,-2.596487653,10500,0,200.0009685,0,0,0,90.00000001 +378.09,50.30085681,-2.596459628,10500,0,199.9998535,0,0,0,90.00000001 +378.1,50.30085681,-2.596431603,10500,0,199.9991844,0,0,0,90.00000001 +378.11,50.30085681,-2.596403578,10500,0,199.9998535,0,0,0,90.00000001 +378.12,50.30085681,-2.596375553,10500,0,200.0009685,0,0,0,90.00000001 +378.13,50.30085681,-2.596347527,10500,0,200.0009685,0,0,0,90.00000001 +378.14,50.30085681,-2.596319502,10500,0,199.9998535,0,0,0,90.00000001 +378.15,50.30085681,-2.596291477,10500,0,199.9991844,0,0,0,90.00000001 +378.16,50.30085681,-2.596263452,10500,0,199.9998535,0,0,0,90.00000001 +378.17,50.30085681,-2.596235427,10500,0,200.0009685,0,0,0,90.00000001 +378.18,50.30085681,-2.596207401,10500,0,200.0009685,0,0,0,90.00000001 +378.19,50.30085681,-2.596179376,10500,0,199.9998535,0,0,0,90.00000001 +378.2,50.30085681,-2.596151351,10500,0,199.9989614,0,0,0,90.00000001 +378.21,50.30085681,-2.596123326,10500,0,199.9989614,0,0,0,90.00000001 +378.22,50.30085681,-2.596095301,10500,0,199.9998535,0,0,0,90.00000001 +378.23,50.30085681,-2.596067276,10500,0,200.0009685,0,0,0,90.00000001 +378.24,50.30085681,-2.59603925,10500,0,200.0009685,0,0,0,90.00000001 +378.25,50.30085681,-2.596011225,10500,0,199.9998535,0,0,0,90.00000001 +378.26,50.30085681,-2.5959832,10500,0,199.9989614,0,0,0,90.00000001 +378.27,50.30085681,-2.595955175,10500,0,199.9989614,0,0,0,90.00000001 +378.28,50.30085681,-2.59592715,10500,0,199.9998535,0,0,0,90.00000001 +378.29,50.30085681,-2.595899125,10500,0,200.0009685,0,0,0,90.00000001 +378.3,50.30085681,-2.595871099,10500,0,200.0009685,0,0,0,90.00000001 +378.31,50.30085681,-2.595843074,10500,0,199.9998535,0,0,0,90.00000001 +378.32,50.30085681,-2.595815049,10500,0,199.9989614,0,0,0,90.00000001 +378.33,50.30085681,-2.595787024,10500,0,199.9989614,0,0,0,90.00000001 +378.34,50.30085681,-2.595758999,10500,0,199.9998535,0,0,0,90.00000001 +378.35,50.30085681,-2.595730974,10500,0,200.0009685,0,0,0,90.00000001 +378.36,50.30085681,-2.595702948,10500,0,200.0009685,0,0,0,90.00000001 +378.37,50.30085681,-2.595674923,10500,0,199.9998535,0,0,0,90.00000001 +378.38,50.30085681,-2.595646898,10500,0,199.9989614,0,0,0,90.00000001 +378.39,50.30085681,-2.595618873,10500,0,199.9989614,0,0,0,90.00000001 +378.4,50.30085681,-2.595590848,10500,0,199.9998535,0,0,0,90.00000001 +378.41,50.30085681,-2.595562823,10500,0,200.0009685,0,0,0,90.00000001 +378.42,50.30085681,-2.595534797,10500,0,200.0009685,0,0,0,90.00000001 +378.43,50.30085681,-2.595506772,10500,0,199.9998535,0,0,0,90.00000001 +378.44,50.30085681,-2.595478747,10500,0,199.9989614,0,0,0,90.00000001 +378.45,50.30085681,-2.595450722,10500,0,199.9989614,0,0,0,90.00000001 +378.46,50.30085681,-2.595422697,10500,0,199.9998535,0,0,0,90.00000001 +378.47,50.30085681,-2.595394672,10500,0,200.0009685,0,0,0,90.00000001 +378.48,50.30085681,-2.595366646,10500,0,200.0009685,0,0,0,90.00000001 +378.49,50.30085681,-2.595338621,10500,0,199.9998535,0,0,0,90.00000001 +378.5,50.30085681,-2.595310596,10500,0,199.9989614,0,0,0,90.00000001 +378.51,50.30085681,-2.595282571,10500,0,199.9987384,0,0,0,90.00000001 +378.52,50.30085681,-2.595254546,10500,0,199.9989614,0,0,0,90.00000001 +378.53,50.30085681,-2.595226521,10500,0,199.9998535,0,0,0,90.00000001 +378.54,50.30085681,-2.595198496,10500,0,200.0009685,0,0,0,90.00000001 +378.55,50.30085681,-2.59517047,10500,0,200.0009685,0,0,0,90.00000001 +378.56,50.30085681,-2.595142445,10500,0,199.9998535,0,0,0,90.00000001 +378.57,50.30085681,-2.59511442,10500,0,199.9991844,0,0,0,90.00000001 +378.58,50.30085681,-2.595086395,10500,0,199.9998535,0,0,0,90.00000001 +378.59,50.30085681,-2.59505837,10500,0,200.0009685,0,0,0,90.00000001 +378.6,50.30085681,-2.595030344,10500,0,200.0009685,0,0,0,90.00000001 +378.61,50.30085681,-2.595002319,10500,0,199.9998535,0,0,0,90.00000001 +378.62,50.30085681,-2.594974294,10500,0,199.9991844,0,0,0,90.00000001 +378.63,50.30085681,-2.594946269,10500,0,199.9998535,0,0,0,90.00000001 +378.64,50.30085681,-2.594918244,10500,0,200.0009685,0,0,0,90.00000001 +378.65,50.30085681,-2.594890218,10500,0,200.0009685,0,0,0,90.00000001 +378.66,50.30085681,-2.594862193,10500,0,199.9998535,0,0,0,90.00000001 +378.67,50.30085681,-2.594834168,10500,0,199.9991844,0,0,0,90.00000001 +378.68,50.30085681,-2.594806143,10500,0,199.9998535,0,0,0,90.00000001 +378.69,50.30085681,-2.594778118,10500,0,200.0009685,0,0,0,90.00000001 +378.7,50.30085681,-2.594750092,10500,0,200.0009685,0,0,0,90.00000001 +378.71,50.30085681,-2.594722067,10500,0,199.9998535,0,0,0,90.00000001 +378.72,50.30085681,-2.594694042,10500,0,199.9991844,0,0,0,90.00000001 +378.73,50.30085681,-2.594666017,10500,0,199.9998535,0,0,0,90.00000001 +378.74,50.30085681,-2.594637992,10500,0,200.0009685,0,0,0,90.00000001 +378.75,50.30085681,-2.594609966,10500,0,200.0009685,0,0,0,90.00000001 +378.76,50.30085681,-2.594581941,10500,0,199.9998535,0,0,0,90.00000001 +378.77,50.30085681,-2.594553916,10500,0,199.9991844,0,0,0,90.00000001 +378.78,50.30085681,-2.594525891,10500,0,199.9998535,0,0,0,90.00000001 +378.79,50.30085681,-2.594497866,10500,0,200.0009685,0,0,0,90.00000001 +378.8,50.30085681,-2.59446984,10500,0,200.0009685,0,0,0,90.00000001 +378.81,50.30085681,-2.594441815,10500,0,199.9998535,0,0,0,90.00000001 +378.82,50.30085681,-2.59441379,10500,0,199.9989614,0,0,0,90.00000001 +378.83,50.30085681,-2.594385765,10500,0,199.9989614,0,0,0,90.00000001 +378.84,50.30085681,-2.59435774,10500,0,199.9998535,0,0,0,90.00000001 +378.85,50.30085681,-2.594329715,10500,0,200.0009685,0,0,0,90.00000001 +378.86,50.30085681,-2.594301689,10500,0,200.0009685,0,0,0,90.00000001 +378.87,50.30085681,-2.594273664,10500,0,199.9998535,0,0,0,90.00000001 +378.88,50.30085681,-2.594245639,10500,0,199.9989614,0,0,0,90.00000001 +378.89,50.30085681,-2.594217614,10500,0,199.9989614,0,0,0,90.00000001 +378.9,50.30085681,-2.594189589,10500,0,199.9998535,0,0,0,90.00000001 +378.91,50.30085681,-2.594161564,10500,0,200.0009685,0,0,0,90.00000001 +378.92,50.30085681,-2.594133538,10500,0,200.0009685,0,0,0,90.00000001 +378.93,50.30085681,-2.594105513,10500,0,199.9998535,0,0,0,90.00000001 +378.94,50.30085681,-2.594077488,10500,0,199.9989614,0,0,0,90.00000001 +378.95,50.30085681,-2.594049463,10500,0,199.9989614,0,0,0,90.00000001 +378.96,50.30085681,-2.594021438,10500,0,199.9998535,0,0,0,90.00000001 +378.97,50.30085681,-2.593993413,10500,0,200.0009685,0,0,0,90.00000001 +378.98,50.30085681,-2.593965387,10500,0,200.0009685,0,0,0,90.00000001 +378.99,50.30085681,-2.593937362,10500,0,199.9998535,0,0,0,90.00000001 +379,50.30085681,-2.593909337,10500,0,199.9989614,0,0,0,90.00000001 +379.01,50.30085681,-2.593881312,10500,0,199.9989614,0,0,0,90.00000001 +379.02,50.30085681,-2.593853287,10500,0,199.9998535,0,0,0,90.00000001 +379.03,50.30085681,-2.593825262,10500,0,200.0009685,0,0,0,90.00000001 +379.04,50.30085681,-2.593797236,10500,0,200.0009685,0,0,0,90.00000001 +379.05,50.30085681,-2.593769211,10500,0,199.9998535,0,0,0,90.00000001 +379.06,50.30085681,-2.593741186,10500,0,199.9989614,0,0,0,90.00000001 +379.07,50.30085681,-2.593713161,10500,0,199.9987384,0,0,0,90.00000001 +379.08,50.30085681,-2.593685136,10500,0,199.9989614,0,0,0,90.00000001 +379.09,50.30085681,-2.593657111,10500,0,199.9998535,0,0,0,90.00000001 +379.1,50.30085681,-2.593629086,10500,0,200.0009685,0,0,0,90.00000001 +379.11,50.30085681,-2.59360106,10500,0,200.0009685,0,0,0,90.00000001 +379.12,50.30085681,-2.593573035,10500,0,199.9998535,0,0,0,90.00000001 +379.13,50.30085681,-2.59354501,10500,0,199.9989614,0,0,0,90.00000001 +379.14,50.30085681,-2.593516985,10500,0,199.9989614,0,0,0,90.00000001 +379.15,50.30085681,-2.59348896,10500,0,199.9998535,0,0,0,90.00000001 +379.16,50.30085681,-2.593460935,10500,0,200.0009685,0,0,0,90.00000001 +379.17,50.30085681,-2.593432909,10500,0,200.0009685,0,0,0,90.00000001 +379.18,50.30085681,-2.593404884,10500,0,199.9998535,0,0,0,90.00000001 +379.19,50.30085681,-2.593376859,10500,0,199.9991844,0,0,0,90.00000001 +379.2,50.30085681,-2.593348834,10500,0,199.9998535,0,0,0,90.00000001 +379.21,50.30085681,-2.593320809,10500,0,200.0009685,0,0,0,90.00000001 +379.22,50.30085681,-2.593292783,10500,0,200.0009685,0,0,0,90.00000001 +379.23,50.30085681,-2.593264758,10500,0,199.9998535,0,0,0,90.00000001 +379.24,50.30085681,-2.593236733,10500,0,199.9991844,0,0,0,90.00000001 +379.25,50.30085681,-2.593208708,10500,0,199.9998535,0,0,0,90.00000001 +379.26,50.30085681,-2.593180683,10500,0,200.0009685,0,0,0,90.00000001 +379.27,50.30085681,-2.593152657,10500,0,200.0009685,0,0,0,90.00000001 +379.28,50.30085681,-2.593124632,10500,0,199.9998535,0,0,0,90.00000001 +379.29,50.30085681,-2.593096607,10500,0,199.9991844,0,0,0,90.00000001 +379.3,50.30085681,-2.593068582,10500,0,199.9998535,0,0,0,90.00000001 +379.31,50.30085681,-2.593040557,10500,0,200.0009685,0,0,0,90.00000001 +379.32,50.30085681,-2.593012531,10500,0,200.0009685,0,0,0,90.00000001 +379.33,50.30085681,-2.592984506,10500,0,199.9998535,0,0,0,90.00000001 +379.34,50.30085681,-2.592956481,10500,0,199.9991844,0,0,0,90.00000001 +379.35,50.30085681,-2.592928456,10500,0,199.9998535,0,0,0,90.00000001 +379.36,50.30085681,-2.592900431,10500,0,200.0009685,0,0,0,90.00000001 +379.37,50.30085681,-2.592872405,10500,0,200.0009685,0,0,0,90.00000001 +379.38,50.30085681,-2.59284438,10500,0,199.9998535,0,0,0,90.00000001 +379.39,50.30085681,-2.592816355,10500,0,199.9991844,0,0,0,90.00000001 +379.4,50.30085681,-2.59278833,10500,0,199.9998535,0,0,0,90.00000001 +379.41,50.30085681,-2.592760305,10500,0,200.0009685,0,0,0,90.00000001 +379.42,50.30085681,-2.592732279,10500,0,200.0009685,0,0,0,90.00000001 +379.43,50.30085681,-2.592704254,10500,0,199.9998535,0,0,0,90.00000001 +379.44,50.30085681,-2.592676229,10500,0,199.9989614,0,0,0,90.00000001 +379.45,50.30085681,-2.592648204,10500,0,199.9989614,0,0,0,90.00000001 +379.46,50.30085681,-2.592620179,10500,0,199.9998535,0,0,0,90.00000001 +379.47,50.30085681,-2.592592154,10500,0,200.0009685,0,0,0,90.00000001 +379.48,50.30085681,-2.592564128,10500,0,200.0009685,0,0,0,90.00000001 +379.49,50.30085681,-2.592536103,10500,0,199.9998535,0,0,0,90.00000001 +379.5,50.30085681,-2.592508078,10500,0,199.9989614,0,0,0,90.00000001 +379.51,50.30085681,-2.592480053,10500,0,199.9989614,0,0,0,90.00000001 +379.52,50.30085681,-2.592452028,10500,0,199.9998535,0,0,0,90.00000001 +379.53,50.30085681,-2.592424003,10500,0,200.0009685,0,0,0,90.00000001 +379.54,50.30085681,-2.592395977,10500,0,200.0009685,0,0,0,90.00000001 +379.55,50.30085681,-2.592367952,10500,0,199.9998535,0,0,0,90.00000001 +379.56,50.30085681,-2.592339927,10500,0,199.9989614,0,0,0,90.00000001 +379.57,50.30085681,-2.592311902,10500,0,199.9989614,0,0,0,90.00000001 +379.58,50.30085681,-2.592283877,10500,0,199.9998535,0,0,0,90.00000001 +379.59,50.30085681,-2.592255852,10500,0,200.0009685,0,0,0,90.00000001 +379.6,50.30085681,-2.592227826,10500,0,200.0009685,0,0,0,90.00000001 +379.61,50.30085681,-2.592199801,10500,0,199.9998535,0,0,0,90.00000001 +379.62,50.30085681,-2.592171776,10500,0,199.9989614,0,0,0,90.00000001 +379.63,50.30085681,-2.592143751,10500,0,199.9987384,0,0,0,90.00000001 +379.64,50.30085681,-2.592115726,10500,0,199.9989614,0,0,0,90.00000001 +379.65,50.30085681,-2.592087701,10500,0,199.9998535,0,0,0,90.00000001 +379.66,50.30085681,-2.592059676,10500,0,200.0009685,0,0,0,90.00000001 +379.67,50.30085681,-2.59203165,10500,0,200.0009685,0,0,0,90.00000001 +379.68,50.30085681,-2.592003625,10500,0,199.9998535,0,0,0,90.00000001 +379.69,50.30085681,-2.5919756,10500,0,199.9989614,0,0,0,90.00000001 +379.7,50.30085681,-2.591947575,10500,0,199.9989614,0,0,0,90.00000001 +379.71,50.30085681,-2.59191955,10500,0,199.9998535,0,0,0,90.00000001 +379.72,50.30085681,-2.591891525,10500,0,200.0009685,0,0,0,90.00000001 +379.73,50.30085681,-2.591863499,10500,0,200.0009685,0,0,0,90.00000001 +379.74,50.30085681,-2.591835474,10500,0,199.9998535,0,0,0,90.00000001 +379.75,50.30085681,-2.591807449,10500,0,199.9989614,0,0,0,90.00000001 +379.76,50.30085681,-2.591779424,10500,0,199.9989614,0,0,0,90.00000001 +379.77,50.30085681,-2.591751399,10500,0,199.9998535,0,0,0,90.00000001 +379.78,50.30085681,-2.591723374,10500,0,200.0009685,0,0,0,90.00000001 +379.79,50.30085681,-2.591695348,10500,0,200.0009685,0,0,0,90.00000001 +379.8,50.30085681,-2.591667323,10500,0,199.9998535,0,0,0,90.00000001 +379.81,50.30085681,-2.591639298,10500,0,199.9989614,0,0,0,90.00000001 +379.82,50.30085681,-2.591611273,10500,0,199.9989614,0,0,0,90.00000001 +379.83,50.30085681,-2.591583248,10500,0,199.9998535,0,0,0,90.00000001 +379.84,50.30085681,-2.591555223,10500,0,200.0009685,0,0,0,90.00000001 +379.85,50.30085681,-2.591527197,10500,0,200.0009685,0,0,0,90.00000001 +379.86,50.30085681,-2.591499172,10500,0,199.9998535,0,0,0,90.00000001 +379.87,50.30085681,-2.591471147,10500,0,199.9991844,0,0,0,90.00000001 +379.88,50.30085681,-2.591443122,10500,0,199.9998535,0,0,0,90.00000001 +379.89,50.30085681,-2.591415097,10500,0,200.0009685,0,0,0,90.00000001 +379.9,50.30085681,-2.591387071,10500,0,200.0009685,0,0,0,90.00000001 +379.91,50.30085681,-2.591359046,10500,0,199.9998535,0,0,0,90.00000001 +379.92,50.30085681,-2.591331021,10500,0,199.9991844,0,0,0,90.00000001 +379.93,50.30085681,-2.591302996,10500,0,199.9998535,0,0,0,90.00000001 +379.94,50.30085681,-2.591274971,10500,0,200.0009685,0,0,0,90.00000001 +379.95,50.30085681,-2.591246945,10500,0,200.0009685,0,0,0,90.00000001 +379.96,50.30085681,-2.59121892,10500,0,199.9998535,0,0,0,90.00000001 +379.97,50.30085681,-2.591190895,10500,0,199.9991844,0,0,0,90.00000001 +379.98,50.30085681,-2.59116287,10500,0,199.9998535,0,0,0,90.00000001 +379.99,50.30085681,-2.591134845,10500,0,200.0009685,0,0,0,90.00000001 +380,50.30085681,-2.591106819,10500,0,200.0009685,0,0,0,90.00000001 +380.01,50.30085681,-2.591078794,10500,0,199.9998535,0,0,0,90.00000001 +380.02,50.30085681,-2.591050769,10500,0,199.9991844,0,0,0,90.00000001 +380.03,50.30085681,-2.591022744,10500,0,199.9998535,0,0,0,90.00000001 +380.04,50.30085681,-2.590994719,10500,0,200.0009685,0,0,0,90.00000001 +380.05,50.30085681,-2.590966693,10500,0,200.0009685,0,0,0,90.00000001 +380.06,50.30085681,-2.590938668,10500,0,199.9998535,0,0,0,90.00000001 +380.07,50.30085681,-2.590910643,10500,0,199.9991844,0,0,0,90.00000001 +380.08,50.30085681,-2.590882618,10500,0,199.9998535,0,0,0,90.00000001 +380.09,50.30085681,-2.590854593,10500,0,200.0009685,0,0,0,90.00000001 +380.1,50.30085681,-2.590826567,10500,0,200.0009685,0,0,0,90.00000001 +380.11,50.30085681,-2.590798542,10500,0,199.9998535,0,0,0,90.00000001 +380.12,50.30085681,-2.590770517,10500,0,199.9989614,0,0,0,90.00000001 +380.13,50.30085681,-2.590742492,10500,0,199.9989614,0,0,0,90.00000001 +380.14,50.30085681,-2.590714467,10500,0,199.9998535,0,0,0,90.00000001 +380.15,50.30085681,-2.590686442,10500,0,200.0009685,0,0,0,90.00000001 +380.16,50.30085681,-2.590658416,10500,0,200.0009685,0,0,0,90.00000001 +380.17,50.30085681,-2.590630391,10500,0,199.9998535,0,0,0,90.00000001 +380.18,50.30085681,-2.590602366,10500,0,199.9989614,0,0,0,90.00000001 +380.19,50.30085681,-2.590574341,10500,0,199.9989614,0,0,0,90.00000001 +380.2,50.30085681,-2.590546316,10500,0,199.9998535,0,0,0,90.00000001 +380.21,50.30085681,-2.590518291,10500,0,200.0009685,0,0,0,90.00000001 +380.22,50.30085681,-2.590490265,10500,0,200.0009685,0,0,0,90.00000001 +380.23,50.30085681,-2.59046224,10500,0,199.9998535,0,0,0,90.00000001 +380.24,50.30085681,-2.590434215,10500,0,199.9989614,0,0,0,90.00000001 +380.25,50.30085681,-2.59040619,10500,0,199.9987384,0,0,0,90.00000001 +380.26,50.30085681,-2.590378165,10500,0,199.9989614,0,0,0,90.00000001 +380.27,50.30085681,-2.59035014,10500,0,199.9998535,0,0,0,90.00000001 +380.28,50.30085681,-2.590322115,10500,0,200.0009685,0,0,0,90.00000001 +380.29,50.30085681,-2.590294089,10500,0,200.0009685,0,0,0,90.00000001 +380.3,50.30085681,-2.590266064,10500,0,199.9998535,0,0,0,90.00000001 +380.31,50.30085681,-2.590238039,10500,0,199.9989614,0,0,0,90.00000001 +380.32,50.30085681,-2.590210014,10500,0,199.9989614,0,0,0,90.00000001 +380.33,50.30085681,-2.590181989,10500,0,199.9998535,0,0,0,90.00000001 +380.34,50.30085681,-2.590153964,10500,0,200.0009685,0,0,0,90.00000001 +380.35,50.30085681,-2.590125938,10500,0,200.0009685,0,0,0,90.00000001 +380.36,50.30085681,-2.590097913,10500,0,199.9998535,0,0,0,90.00000001 +380.37,50.30085681,-2.590069888,10500,0,199.9989614,0,0,0,90.00000001 +380.38,50.30085681,-2.590041863,10500,0,199.9989614,0,0,0,90.00000001 +380.39,50.30085681,-2.590013838,10500,0,199.9998535,0,0,0,90.00000001 +380.4,50.30085681,-2.589985813,10500,0,200.0009685,0,0,0,90.00000001 +380.41,50.30085681,-2.589957787,10500,0,200.0009685,0,0,0,90.00000001 +380.42,50.30085681,-2.589929762,10500,0,199.9998535,0,0,0,90.00000001 +380.43,50.30085681,-2.589901737,10500,0,199.9989614,0,0,0,90.00000001 +380.44,50.30085681,-2.589873712,10500,0,199.9989614,0,0,0,90.00000001 +380.45,50.30085681,-2.589845687,10500,0,199.9998535,0,0,0,90.00000001 +380.46,50.30085681,-2.589817662,10500,0,200.0009685,0,0,0,90.00000001 +380.47,50.30085681,-2.589789636,10500,0,200.0009685,0,0,0,90.00000001 +380.48,50.30085681,-2.589761611,10500,0,199.9998535,0,0,0,90.00000001 +380.49,50.30085681,-2.589733586,10500,0,199.9991844,0,0,0,90.00000001 +380.5,50.30085681,-2.589705561,10500,0,199.9998535,0,0,0,90.00000001 +380.51,50.30085681,-2.589677536,10500,0,200.0009685,0,0,0,90.00000001 +380.52,50.30085681,-2.58964951,10500,0,200.0009685,0,0,0,90.00000001 +380.53,50.30085681,-2.589621485,10500,0,199.9998535,0,0,0,90.00000001 +380.54,50.30085681,-2.58959346,10500,0,199.9991844,0,0,0,90.00000001 +380.55,50.30085681,-2.589565435,10500,0,199.9998535,0,0,0,90.00000001 +380.56,50.30085681,-2.58953741,10500,0,200.0009685,0,0,0,90.00000001 +380.57,50.30085681,-2.589509384,10500,0,200.0009685,0,0,0,90.00000001 +380.58,50.30085681,-2.589481359,10500,0,199.9998535,0,0,0,90.00000001 +380.59,50.30085681,-2.589453334,10500,0,199.9991844,0,0,0,90.00000001 +380.6,50.30085681,-2.589425309,10500,0,199.9998535,0,0,0,90.00000001 +380.61,50.30085681,-2.589397284,10500,0,200.0009685,0,0,0,90.00000001 +380.62,50.30085681,-2.589369258,10500,0,200.0009685,0,0,0,90.00000001 +380.63,50.30085681,-2.589341233,10500,0,199.9998535,0,0,0,90.00000001 +380.64,50.30085681,-2.589313208,10500,0,199.9991844,0,0,0,90.00000001 +380.65,50.30085681,-2.589285183,10500,0,199.9998535,0,0,0,90.00000001 +380.66,50.30085681,-2.589257158,10500,0,200.0009685,0,0,0,90.00000001 +380.67,50.30085681,-2.589229132,10500,0,200.0009685,0,0,0,90.00000001 +380.68,50.30085681,-2.589201107,10500,0,199.9998535,0,0,0,90.00000001 +380.69,50.30085681,-2.589173082,10500,0,199.9991844,0,0,0,90.00000001 +380.7,50.30085681,-2.589145057,10500,0,199.9998535,0,0,0,90.00000001 +380.71,50.30085681,-2.589117032,10500,0,200.0009685,0,0,0,90.00000001 +380.72,50.30085681,-2.589089006,10500,0,200.0009685,0,0,0,90.00000001 +380.73,50.30085681,-2.589060981,10500,0,199.9998535,0,0,0,90.00000001 +380.74,50.30085681,-2.589032956,10500,0,199.9989614,0,0,0,90.00000001 +380.75,50.30085681,-2.589004931,10500,0,199.9989614,0,0,0,90.00000001 +380.76,50.30085681,-2.588976906,10500,0,199.9998535,0,0,0,90.00000001 +380.77,50.30085681,-2.588948881,10500,0,200.0009685,0,0,0,90.00000001 +380.78,50.30085681,-2.588920855,10500,0,200.0009685,0,0,0,90.00000001 +380.79,50.30085681,-2.58889283,10500,0,199.9998535,0,0,0,90.00000001 +380.8,50.30085681,-2.588864805,10500,0,199.9989614,0,0,0,90.00000001 +380.81,50.30085681,-2.58883678,10500,0,199.9987384,0,0,0,90.00000001 +380.82,50.30085681,-2.588808755,10500,0,199.9989614,0,0,0,90.00000001 +380.83,50.30085681,-2.58878073,10500,0,199.9998535,0,0,0,90.00000001 +380.84,50.30085681,-2.588752705,10500,0,200.0009685,0,0,0,90.00000001 +380.85,50.30085681,-2.588724679,10500,0,200.0009685,0,0,0,90.00000001 +380.86,50.30085681,-2.588696654,10500,0,199.9998535,0,0,0,90.00000001 +380.87,50.30085681,-2.588668629,10500,0,199.9989614,0,0,0,90.00000001 +380.88,50.30085681,-2.588640604,10500,0,199.9989614,0,0,0,90.00000001 +380.89,50.30085681,-2.588612579,10500,0,199.9998535,0,0,0,90.00000001 +380.9,50.30085681,-2.588584554,10500,0,200.0009685,0,0,0,90.00000001 +380.91,50.30085681,-2.588556528,10500,0,200.0009685,0,0,0,90.00000001 +380.92,50.30085681,-2.588528503,10500,0,199.9998535,0,0,0,90.00000001 +380.93,50.30085681,-2.588500478,10500,0,199.9989614,0,0,0,90.00000001 +380.94,50.30085681,-2.588472453,10500,0,199.9989614,0,0,0,90.00000001 +380.95,50.30085681,-2.588444428,10500,0,199.9998535,0,0,0,90.00000001 +380.96,50.30085681,-2.588416403,10500,0,200.0009685,0,0,0,90.00000001 +380.97,50.30085681,-2.588388377,10500,0,200.0009685,0,0,0,90.00000001 +380.98,50.30085681,-2.588360352,10500,0,199.9998535,0,0,0,90.00000001 +380.99,50.30085681,-2.588332327,10500,0,199.9989614,0,0,0,90.00000001 +381,50.30085681,-2.588304302,10500,0,199.9989614,0,0,0,90.00000001 +381.01,50.30085681,-2.588276277,10500,0,199.9998535,0,0,0,90.00000001 +381.02,50.30085681,-2.588248252,10500,0,200.0009685,0,0,0,90.00000001 +381.03,50.30085681,-2.588220226,10500,0,200.0009685,0,0,0,90.00000001 +381.04,50.30085681,-2.588192201,10500,0,199.9998535,0,0,0,90.00000001 +381.05,50.30085681,-2.588164176,10500,0,199.9989614,0,0,0,90.00000001 +381.06,50.30085681,-2.588136151,10500,0,199.9989614,0,0,0,90.00000001 +381.07,50.30085681,-2.588108126,10500,0,199.9998535,0,0,0,90.00000001 +381.08,50.30085681,-2.588080101,10500,0,200.0009685,0,0,0,90.00000001 +381.09,50.30085681,-2.588052075,10500,0,200.0009685,0,0,0,90.00000001 +381.1,50.30085681,-2.58802405,10500,0,199.9998535,0,0,0,90.00000001 +381.11,50.30085681,-2.587996025,10500,0,199.9991844,0,0,0,90.00000001 +381.12,50.30085681,-2.587968,10500,0,199.9998535,0,0,0,90.00000001 +381.13,50.30085681,-2.587939975,10500,0,200.0009685,0,0,0,90.00000001 +381.14,50.30085681,-2.587911949,10500,0,200.0009685,0,0,0,90.00000001 +381.15,50.30085681,-2.587883924,10500,0,199.9998535,0,0,0,90.00000001 +381.16,50.30085681,-2.587855899,10500,0,199.9991844,0,0,0,90.00000001 +381.17,50.30085681,-2.587827874,10500,0,199.9998535,0,0,0,90.00000001 +381.18,50.30085681,-2.587799849,10500,0,200.0009685,0,0,0,90.00000001 +381.19,50.30085681,-2.587771823,10500,0,200.0009685,0,0,0,90.00000001 +381.2,50.30085681,-2.587743798,10500,0,199.9998535,0,0,0,90.00000001 +381.21,50.30085681,-2.587715773,10500,0,199.9991844,0,0,0,90.00000001 +381.22,50.30085681,-2.587687748,10500,0,199.9998535,0,0,0,90.00000001 +381.23,50.30085681,-2.587659723,10500,0,200.0009685,0,0,0,90.00000001 +381.24,50.30085681,-2.587631697,10500,0,200.0009685,0,0,0,90.00000001 +381.25,50.30085681,-2.587603672,10500,0,199.9998535,0,0,0,90.00000001 +381.26,50.30085681,-2.587575647,10500,0,199.9991844,0,0,0,90.00000001 +381.27,50.30085681,-2.587547622,10500,0,199.9998535,0,0,0,90.00000001 +381.28,50.30085681,-2.587519597,10500,0,200.0009685,0,0,0,90.00000001 +381.29,50.30085681,-2.587491571,10500,0,200.0009685,0,0,0,90.00000001 +381.3,50.30085681,-2.587463546,10500,0,199.9998535,0,0,0,90.00000001 +381.31,50.30085681,-2.587435521,10500,0,199.9991844,0,0,0,90.00000001 +381.32,50.30085681,-2.587407496,10500,0,199.9998535,0,0,0,90.00000001 +381.33,50.30085681,-2.587379471,10500,0,200.0009685,0,0,0,90.00000001 +381.34,50.30085681,-2.587351445,10500,0,200.0009685,0,0,0,90.00000001 +381.35,50.30085681,-2.58732342,10500,0,199.9998535,0,0,0,90.00000001 +381.36,50.30085681,-2.587295395,10500,0,199.9989614,0,0,0,90.00000001 +381.37,50.30085681,-2.58726737,10500,0,199.9987384,0,0,0,90.00000001 +381.38,50.30085681,-2.587239345,10500,0,199.9989614,0,0,0,90.00000001 +381.39,50.30085681,-2.58721132,10500,0,199.9998535,0,0,0,90.00000001 +381.4,50.30085681,-2.587183295,10500,0,200.0009685,0,0,0,90.00000001 +381.41,50.30085681,-2.587155269,10500,0,200.0009685,0,0,0,90.00000001 +381.42,50.30085681,-2.587127244,10500,0,199.9998535,0,0,0,90.00000001 +381.43,50.30085681,-2.587099219,10500,0,199.9989614,0,0,0,90.00000001 +381.44,50.30085681,-2.587071194,10500,0,199.9989614,0,0,0,90.00000001 +381.45,50.30085681,-2.587043169,10500,0,199.9998535,0,0,0,90.00000001 +381.46,50.30085681,-2.587015144,10500,0,200.0009685,0,0,0,90.00000001 +381.47,50.30085681,-2.586987118,10500,0,200.0009685,0,0,0,90.00000001 +381.48,50.30085681,-2.586959093,10500,0,199.9998535,0,0,0,90.00000001 +381.49,50.30085681,-2.586931068,10500,0,199.9989614,0,0,0,90.00000001 +381.5,50.30085681,-2.586903043,10500,0,199.9989614,0,0,0,90.00000001 +381.51,50.30085681,-2.586875018,10500,0,199.9998535,0,0,0,90.00000001 +381.52,50.30085681,-2.586846993,10500,0,200.0009685,0,0,0,90.00000001 +381.53,50.30085681,-2.586818967,10500,0,200.0009685,0,0,0,90.00000001 +381.54,50.30085681,-2.586790942,10500,0,199.9998535,0,0,0,90.00000001 +381.55,50.30085681,-2.586762917,10500,0,199.9989614,0,0,0,90.00000001 +381.56,50.30085681,-2.586734892,10500,0,199.9989614,0,0,0,90.00000001 +381.57,50.30085681,-2.586706867,10500,0,199.9998535,0,0,0,90.00000001 +381.58,50.30085681,-2.586678842,10500,0,200.0009685,0,0,0,90.00000001 +381.59,50.30085681,-2.586650816,10500,0,200.0009685,0,0,0,90.00000001 +381.6,50.30085681,-2.586622791,10500,0,199.9998535,0,0,0,90.00000001 +381.61,50.30085681,-2.586594766,10500,0,199.9989614,0,0,0,90.00000001 +381.62,50.30085681,-2.586566741,10500,0,199.9989614,0,0,0,90.00000001 +381.63,50.30085681,-2.586538716,10500,0,199.9998535,0,0,0,90.00000001 +381.64,50.30085681,-2.586510691,10500,0,200.0009685,0,0,0,90.00000001 +381.65,50.30085681,-2.586482665,10500,0,200.0009685,0,0,0,90.00000001 +381.66,50.30085681,-2.58645464,10500,0,199.9998535,0,0,0,90.00000001 +381.67,50.30085681,-2.586426615,10500,0,199.9989614,0,0,0,90.00000001 +381.68,50.30085681,-2.58639859,10500,0,199.9989614,0,0,0,90.00000001 +381.69,50.30085681,-2.586370565,10500,0,199.9998535,0,0,0,90.00000001 +381.7,50.30085681,-2.58634254,10500,0,200.0009685,0,0,0,90.00000001 +381.71,50.30085681,-2.586314514,10500,0,200.0009685,0,0,0,90.00000001 +381.72,50.30085681,-2.586286489,10500,0,199.9998535,0,0,0,90.00000001 +381.73,50.30085681,-2.586258464,10500,0,199.9991844,0,0,0,90.00000001 +381.74,50.30085681,-2.586230439,10500,0,199.9998535,0,0,0,90.00000001 +381.75,50.30085681,-2.586202414,10500,0,200.0009685,0,0,0,90.00000001 +381.76,50.30085681,-2.586174388,10500,0,200.0009685,0,0,0,90.00000001 +381.77,50.30085681,-2.586146363,10500,0,199.9998535,0,0,0,90.00000001 +381.78,50.30085681,-2.586118338,10500,0,199.9991844,0,0,0,90.00000001 +381.79,50.30085681,-2.586090313,10500,0,199.9998535,0,0,0,90.00000001 +381.8,50.30085681,-2.586062288,10500,0,200.0009685,0,0,0,90.00000001 +381.81,50.30085681,-2.586034262,10500,0,200.0009685,0,0,0,90.00000001 +381.82,50.30085681,-2.586006237,10500,0,199.9998535,0,0,0,90.00000001 +381.83,50.30085681,-2.585978212,10500,0,199.9989614,0,0,0,90.00000001 +381.84,50.30085681,-2.585950187,10500,0,199.9989614,0,0,0,90.00000001 +381.85,50.30085681,-2.585922162,10500,0,199.9998535,0,0,0,90.00000001 +381.86,50.30085681,-2.585894137,10500,0,200.0009685,0,0,0,90.00000001 +381.87,50.30085681,-2.585866111,10500,0,200.0009685,0,0,0,90.00000001 +381.88,50.30085681,-2.585838086,10500,0,199.9998535,0,0,0,90.00000001 +381.89,50.30085681,-2.585810061,10500,0,199.9991844,0,0,0,90.00000001 +381.9,50.30085681,-2.585782036,10500,0,199.9998535,0,0,0,90.00000001 +381.91,50.30085681,-2.585754011,10500,0,200.0009685,0,0,0,90.00000001 +381.92,50.30085681,-2.585725985,10500,0,200.0009685,0,0,0,90.00000001 +381.93,50.30085681,-2.58569796,10500,0,199.9998535,0,0,0,90.00000001 +381.94,50.30085681,-2.585669935,10500,0,199.9991844,0,0,0,90.00000001 +381.95,50.30085681,-2.58564191,10500,0,199.9998535,0,0,0,90.00000001 +381.96,50.30085681,-2.585613885,10500,0,200.0009685,0,0,0,90.00000001 +381.97,50.30085681,-2.585585859,10500,0,200.0009685,0,0,0,90.00000001 +381.98,50.30085681,-2.585557834,10500,0,199.9998535,0,0,0,90.00000001 +381.99,50.30085681,-2.585529809,10500,0,199.9989614,0,0,0,90.00000001 +382,50.30085681,-2.585501784,10500,0,199.9989614,0,0,0,90.00000001 +382.01,50.30085681,-2.585473759,10500,0,199.9998535,0,0,0,90.00000001 +382.02,50.30085681,-2.585445734,10500,0,200.0009685,0,0,0,90.00000001 +382.03,50.30085681,-2.585417708,10500,0,200.0009685,0,0,0,90.00000001 +382.04,50.30085681,-2.585389683,10500,0,199.9998535,0,0,0,90.00000001 +382.05,50.30085681,-2.585361658,10500,0,199.9989614,0,0,0,90.00000001 +382.06,50.30085681,-2.585333633,10500,0,199.9989614,0,0,0,90.00000001 +382.07,50.30085681,-2.585305608,10500,0,199.9998535,0,0,0,90.00000001 +382.08,50.30085681,-2.585277583,10500,0,200.0009685,0,0,0,90.00000001 +382.09,50.30085681,-2.585249557,10500,0,200.0009685,0,0,0,90.00000001 +382.1,50.30085681,-2.585221532,10500,0,199.9998535,0,0,0,90.00000001 +382.11,50.30085681,-2.585193507,10500,0,199.9989614,0,0,0,90.00000001 +382.12,50.30085681,-2.585165482,10500,0,199.9989614,0,0,0,90.00000001 +382.13,50.30085681,-2.585137457,10500,0,199.9998535,0,0,0,90.00000001 +382.14,50.30085681,-2.585109432,10500,0,200.0009685,0,0,0,90.00000001 +382.15,50.30085681,-2.585081406,10500,0,200.0009685,0,0,0,90.00000001 +382.16,50.30085681,-2.585053381,10500,0,199.9998535,0,0,0,90.00000001 +382.17,50.30085681,-2.585025356,10500,0,199.9989614,0,0,0,90.00000001 +382.18,50.30085681,-2.584997331,10500,0,199.9989614,0,0,0,90.00000001 +382.19,50.30085681,-2.584969306,10500,0,199.9998535,0,0,0,90.00000001 +382.2,50.30085681,-2.584941281,10500,0,200.0009685,0,0,0,90.00000001 +382.21,50.30085681,-2.584913255,10500,0,200.0009685,0,0,0,90.00000001 +382.22,50.30085681,-2.58488523,10500,0,199.9998535,0,0,0,90.00000001 +382.23,50.30085681,-2.584857205,10500,0,199.9989614,0,0,0,90.00000001 +382.24,50.30085681,-2.58482918,10500,0,199.9987384,0,0,0,90.00000001 +382.25,50.30085681,-2.584801155,10500,0,199.9989614,0,0,0,90.00000001 +382.26,50.30085681,-2.58477313,10500,0,199.9998535,0,0,0,90.00000001 +382.27,50.30085681,-2.584745105,10500,0,200.0009685,0,0,0,90.00000001 +382.28,50.30085681,-2.584717079,10500,0,200.0009685,0,0,0,90.00000001 +382.29,50.30085681,-2.584689054,10500,0,199.9998535,0,0,0,90.00000001 +382.3,50.30085681,-2.584661029,10500,0,199.9989614,0,0,0,90.00000001 +382.31,50.30085681,-2.584633004,10500,0,199.9989614,0,0,0,90.00000001 +382.32,50.30085681,-2.584604979,10500,0,199.9998535,0,0,0,90.00000001 +382.33,50.30085681,-2.584576954,10500,0,200.0009685,0,0,0,90.00000001 +382.34,50.30085681,-2.584548928,10500,0,200.0009685,0,0,0,90.00000001 +382.35,50.30085681,-2.584520903,10500,0,199.9998535,0,0,0,90.00000001 +382.36,50.30085681,-2.584492878,10500,0,199.9991844,0,0,0,90.00000001 +382.37,50.30085681,-2.584464853,10500,0,199.9998535,0,0,0,90.00000001 +382.38,50.30085681,-2.584436828,10500,0,200.0009685,0,0,0,90.00000001 +382.39,50.30085681,-2.584408802,10500,0,200.0009685,0,0,0,90.00000001 +382.4,50.30085681,-2.584380777,10500,0,199.9998535,0,0,0,90.00000001 +382.41,50.30085681,-2.584352752,10500,0,199.9991844,0,0,0,90.00000001 +382.42,50.30085681,-2.584324727,10500,0,199.9998535,0,0,0,90.00000001 +382.43,50.30085681,-2.584296702,10500,0,200.0009685,0,0,0,90.00000001 +382.44,50.30085681,-2.584268676,10500,0,200.0009685,0,0,0,90.00000001 +382.45,50.30085681,-2.584240651,10500,0,199.9998535,0,0,0,90.00000001 +382.46,50.30085681,-2.584212626,10500,0,199.9991844,0,0,0,90.00000001 +382.47,50.30085681,-2.584184601,10500,0,199.9998535,0,0,0,90.00000001 +382.48,50.30085681,-2.584156576,10500,0,200.0009685,0,0,0,90.00000001 +382.49,50.30085681,-2.58412855,10500,0,200.0009685,0,0,0,90.00000001 +382.5,50.30085681,-2.584100525,10500,0,199.9998535,0,0,0,90.00000001 +382.51,50.30085681,-2.5840725,10500,0,199.9991844,0,0,0,90.00000001 +382.52,50.30085681,-2.584044475,10500,0,199.9998535,0,0,0,90.00000001 +382.53,50.30085681,-2.58401645,10500,0,200.0009685,0,0,0,90.00000001 +382.54,50.30085681,-2.583988424,10500,0,200.0009685,0,0,0,90.00000001 +382.55,50.30085681,-2.583960399,10500,0,199.9998535,0,0,0,90.00000001 +382.56,50.30085681,-2.583932374,10500,0,199.9991844,0,0,0,90.00000001 +382.57,50.30085681,-2.583904349,10500,0,199.9998535,0,0,0,90.00000001 +382.58,50.30085681,-2.583876324,10500,0,200.0009685,0,0,0,90.00000001 +382.59,50.30085681,-2.583848298,10500,0,200.0009685,0,0,0,90.00000001 +382.6,50.30085681,-2.583820273,10500,0,199.9998535,0,0,0,90.00000001 +382.61,50.30085681,-2.583792248,10500,0,199.9989614,0,0,0,90.00000001 +382.62,50.30085681,-2.583764223,10500,0,199.9989614,0,0,0,90.00000001 +382.63,50.30085681,-2.583736198,10500,0,199.9998535,0,0,0,90.00000001 +382.64,50.30085681,-2.583708173,10500,0,200.0009685,0,0,0,90.00000001 +382.65,50.30085681,-2.583680147,10500,0,200.0009685,0,0,0,90.00000001 +382.66,50.30085681,-2.583652122,10500,0,199.9998535,0,0,0,90.00000001 +382.67,50.30085681,-2.583624097,10500,0,199.9989614,0,0,0,90.00000001 +382.68,50.30085681,-2.583596072,10500,0,199.9989614,0,0,0,90.00000001 +382.69,50.30085681,-2.583568047,10500,0,199.9998535,0,0,0,90.00000001 +382.7,50.30085681,-2.583540022,10500,0,200.0009685,0,0,0,90.00000001 +382.71,50.30085681,-2.583511996,10500,0,200.0009685,0,0,0,90.00000001 +382.72,50.30085681,-2.583483971,10500,0,199.9998535,0,0,0,90.00000001 +382.73,50.30085681,-2.583455946,10500,0,199.9989614,0,0,0,90.00000001 +382.74,50.30085681,-2.583427921,10500,0,199.9989614,0,0,0,90.00000001 +382.75,50.30085681,-2.583399896,10500,0,199.9998535,0,0,0,90.00000001 +382.76,50.30085681,-2.583371871,10500,0,200.0009685,0,0,0,90.00000001 +382.77,50.30085681,-2.583343845,10500,0,200.0009685,0,0,0,90.00000001 +382.78,50.30085681,-2.58331582,10500,0,199.9998535,0,0,0,90.00000001 +382.79,50.30085681,-2.583287795,10500,0,199.9989614,0,0,0,90.00000001 +382.8,50.30085681,-2.58325977,10500,0,199.9987384,0,0,0,90.00000001 +382.81,50.30085681,-2.583231745,10500,0,199.9989614,0,0,0,90.00000001 +382.82,50.30085681,-2.58320372,10500,0,199.9998535,0,0,0,90.00000001 +382.83,50.30085681,-2.583175695,10500,0,200.0009685,0,0,0,90.00000001 +382.84,50.30085681,-2.583147669,10500,0,200.0009685,0,0,0,90.00000001 +382.85,50.30085681,-2.583119644,10500,0,199.9998535,0,0,0,90.00000001 +382.86,50.30085681,-2.583091619,10500,0,199.9989614,0,0,0,90.00000001 +382.87,50.30085681,-2.583063594,10500,0,199.9989614,0,0,0,90.00000001 +382.88,50.30085681,-2.583035569,10500,0,199.9998535,0,0,0,90.00000001 +382.89,50.30085681,-2.583007544,10500,0,200.0009685,0,0,0,90.00000001 +382.9,50.30085681,-2.582979518,10500,0,200.0009685,0,0,0,90.00000001 +382.91,50.30085681,-2.582951493,10500,0,199.9998535,0,0,0,90.00000001 +382.92,50.30085681,-2.582923468,10500,0,199.9989614,0,0,0,90.00000001 +382.93,50.30085681,-2.582895443,10500,0,199.9989614,0,0,0,90.00000001 +382.94,50.30085681,-2.582867418,10500,0,199.9998535,0,0,0,90.00000001 +382.95,50.30085681,-2.582839393,10500,0,200.0009685,0,0,0,90.00000001 +382.96,50.30085681,-2.582811367,10500,0,200.0009685,0,0,0,90.00000001 +382.97,50.30085681,-2.582783342,10500,0,199.9998535,0,0,0,90.00000001 +382.98,50.30085681,-2.582755317,10500,0,199.9991844,0,0,0,90.00000001 +382.99,50.30085681,-2.582727292,10500,0,199.9998535,0,0,0,90.00000001 +383,50.30085681,-2.582699267,10500,0,200.0009685,0,0,0,90.00000001 +383.01,50.30085681,-2.582671241,10500,0,200.0009685,0,0,0,90.00000001 +383.02,50.30085681,-2.582643216,10500,0,199.9998535,0,0,0,90.00000001 +383.03,50.30085681,-2.582615191,10500,0,199.9991844,0,0,0,90.00000001 +383.04,50.30085681,-2.582587166,10500,0,199.9998535,0,0,0,90.00000001 +383.05,50.30085681,-2.582559141,10500,0,200.0009685,0,0,0,90.00000001 +383.06,50.30085681,-2.582531115,10500,0,200.0009685,0,0,0,90.00000001 +383.07,50.30085681,-2.58250309,10500,0,199.9998535,0,0,0,90.00000001 +383.08,50.30085681,-2.582475065,10500,0,199.9991844,0,0,0,90.00000001 +383.09,50.30085681,-2.58244704,10500,0,199.9998535,0,0,0,90.00000001 +383.1,50.30085681,-2.582419015,10500,0,200.0009685,0,0,0,90.00000001 +383.11,50.30085681,-2.582390989,10500,0,200.0009685,0,0,0,90.00000001 +383.12,50.30085681,-2.582362964,10500,0,199.9998535,0,0,0,90.00000001 +383.13,50.30085681,-2.582334939,10500,0,199.9991844,0,0,0,90.00000001 +383.14,50.30085681,-2.582306914,10500,0,199.9998535,0,0,0,90.00000001 +383.15,50.30085681,-2.582278889,10500,0,200.0009685,0,0,0,90.00000001 +383.16,50.30085681,-2.582250863,10500,0,200.0009685,0,0,0,90.00000001 +383.17,50.30085681,-2.582222838,10500,0,199.9998535,0,0,0,90.00000001 +383.18,50.30085681,-2.582194813,10500,0,199.9991844,0,0,0,90.00000001 +383.19,50.30085681,-2.582166788,10500,0,199.9998535,0,0,0,90.00000001 +383.2,50.30085681,-2.582138763,10500,0,200.0009685,0,0,0,90.00000001 +383.21,50.30085681,-2.582110737,10500,0,200.0009685,0,0,0,90.00000001 +383.22,50.30085681,-2.582082712,10500,0,199.9998535,0,0,0,90.00000001 +383.23,50.30085681,-2.582054687,10500,0,199.9989614,0,0,0,90.00000001 +383.24,50.30085681,-2.582026662,10500,0,199.9989614,0,0,0,90.00000001 +383.25,50.30085681,-2.581998637,10500,0,199.9998535,0,0,0,90.00000001 +383.26,50.30085681,-2.581970612,10500,0,200.0009685,0,0,0,90.00000001 +383.27,50.30085681,-2.581942586,10500,0,200.0009685,0,0,0,90.00000001 +383.28,50.30085681,-2.581914561,10500,0,199.9998535,0,0,0,90.00000001 +383.29,50.30085681,-2.581886536,10500,0,199.9989614,0,0,0,90.00000001 +383.3,50.30085681,-2.581858511,10500,0,199.9989614,0,0,0,90.00000001 +383.31,50.30085681,-2.581830486,10500,0,199.9998535,0,0,0,90.00000001 +383.32,50.30085681,-2.581802461,10500,0,200.0009685,0,0,0,90.00000001 +383.33,50.30085681,-2.581774435,10500,0,200.0009685,0,0,0,90.00000001 +383.34,50.30085681,-2.58174641,10500,0,199.9998535,0,0,0,90.00000001 +383.35,50.30085681,-2.581718385,10500,0,199.9989614,0,0,0,90.00000001 +383.36,50.30085681,-2.58169036,10500,0,199.9987384,0,0,0,90.00000001 +383.37,50.30085681,-2.581662335,10500,0,199.9989614,0,0,0,90.00000001 +383.38,50.30085681,-2.58163431,10500,0,199.9998535,0,0,0,90.00000001 +383.39,50.30085681,-2.581606285,10500,0,200.0009685,0,0,0,90.00000001 +383.4,50.30085681,-2.581578259,10500,0,200.0009685,0,0,0,90.00000001 +383.41,50.30085681,-2.581550234,10500,0,199.9998535,0,0,0,90.00000001 +383.42,50.30085681,-2.581522209,10500,0,199.9989614,0,0,0,90.00000001 +383.43,50.30085681,-2.581494184,10500,0,199.9989614,0,0,0,90.00000001 +383.44,50.30085681,-2.581466159,10500,0,199.9998535,0,0,0,90.00000001 +383.45,50.30085681,-2.581438134,10500,0,200.0009685,0,0,0,90.00000001 +383.46,50.30085681,-2.581410108,10500,0,200.0009685,0,0,0,90.00000001 +383.47,50.30085681,-2.581382083,10500,0,199.9998535,0,0,0,90.00000001 +383.48,50.30085681,-2.581354058,10500,0,199.9989614,0,0,0,90.00000001 +383.49,50.30085681,-2.581326033,10500,0,199.9989614,0,0,0,90.00000001 +383.5,50.30085681,-2.581298008,10500,0,199.9998535,0,0,0,90.00000001 +383.51,50.30085681,-2.581269983,10500,0,200.0009685,0,0,0,90.00000001 +383.52,50.30085681,-2.581241957,10500,0,200.0009685,0,0,0,90.00000001 +383.53,50.30085681,-2.581213932,10500,0,199.9998535,0,0,0,90.00000001 +383.54,50.30085681,-2.581185907,10500,0,199.9989614,0,0,0,90.00000001 +383.55,50.30085681,-2.581157882,10500,0,199.9989614,0,0,0,90.00000001 +383.56,50.30085681,-2.581129857,10500,0,199.9998535,0,0,0,90.00000001 +383.57,50.30085681,-2.581101832,10500,0,200.0009685,0,0,0,90.00000001 +383.58,50.30085681,-2.581073806,10500,0,200.0009685,0,0,0,90.00000001 +383.59,50.30085681,-2.581045781,10500,0,199.9998535,0,0,0,90.00000001 +383.6,50.30085681,-2.581017756,10500,0,199.9991844,0,0,0,90.00000001 +383.61,50.30085681,-2.580989731,10500,0,199.9998535,0,0,0,90.00000001 +383.62,50.30085681,-2.580961706,10500,0,200.0009685,0,0,0,90.00000001 +383.63,50.30085681,-2.58093368,10500,0,200.0009685,0,0,0,90.00000001 +383.64,50.30085681,-2.580905655,10500,0,199.9998535,0,0,0,90.00000001 +383.65,50.30085681,-2.58087763,10500,0,199.9991844,0,0,0,90.00000001 +383.66,50.30085681,-2.580849605,10500,0,199.9998535,0,0,0,90.00000001 +383.67,50.30085681,-2.58082158,10500,0,200.0009685,0,0,0,90.00000001 +383.68,50.30085681,-2.580793554,10500,0,200.0009685,0,0,0,90.00000001 +383.69,50.30085681,-2.580765529,10500,0,199.9998535,0,0,0,90.00000001 +383.7,50.30085681,-2.580737504,10500,0,199.9991844,0,0,0,90.00000001 +383.71,50.30085681,-2.580709479,10500,0,199.9998535,0,0,0,90.00000001 +383.72,50.30085681,-2.580681454,10500,0,200.0009685,0,0,0,90.00000001 +383.73,50.30085681,-2.580653428,10500,0,200.0009685,0,0,0,90.00000001 +383.74,50.30085681,-2.580625403,10500,0,199.9998535,0,0,0,90.00000001 +383.75,50.30085681,-2.580597378,10500,0,199.9991844,0,0,0,90.00000001 +383.76,50.30085681,-2.580569353,10500,0,199.9998535,0,0,0,90.00000001 +383.77,50.30085681,-2.580541328,10500,0,200.0009685,0,0,0,90.00000001 +383.78,50.30085681,-2.580513302,10500,0,200.0009685,0,0,0,90.00000001 +383.79,50.30085681,-2.580485277,10500,0,199.9998535,0,0,0,90.00000001 +383.8,50.30085681,-2.580457252,10500,0,199.9991844,0,0,0,90.00000001 +383.81,50.30085681,-2.580429227,10500,0,199.9998535,0,0,0,90.00000001 +383.82,50.30085681,-2.580401202,10500,0,200.0009685,0,0,0,90.00000001 +383.83,50.30085681,-2.580373176,10500,0,200.0009685,0,0,0,90.00000001 +383.84,50.30085681,-2.580345151,10500,0,199.9998535,0,0,0,90.00000001 +383.85,50.30085681,-2.580317126,10500,0,199.9989614,0,0,0,90.00000001 +383.86,50.30085681,-2.580289101,10500,0,199.9989614,0,0,0,90.00000001 +383.87,50.30085681,-2.580261076,10500,0,199.9998535,0,0,0,90.00000001 +383.88,50.30085681,-2.580233051,10500,0,200.0009685,0,0,0,90.00000001 +383.89,50.30085681,-2.580205025,10500,0,200.0009685,0,0,0,90.00000001 +383.9,50.30085681,-2.580177,10500,0,199.9998535,0,0,0,90.00000001 +383.91,50.30085681,-2.580148975,10500,0,199.9989614,0,0,0,90.00000001 +383.92,50.30085681,-2.58012095,10500,0,199.9987384,0,0,0,90.00000001 +383.93,50.30085681,-2.580092925,10500,0,199.9989614,0,0,0,90.00000001 +383.94,50.30085681,-2.5800649,10500,0,199.9998535,0,0,0,90.00000001 +383.95,50.30085681,-2.580036875,10500,0,200.0009685,0,0,0,90.00000001 +383.96,50.30085681,-2.580008849,10500,0,200.0009685,0,0,0,90.00000001 +383.97,50.30085681,-2.579980824,10500,0,199.9998535,0,0,0,90.00000001 +383.98,50.30085681,-2.579952799,10500,0,199.9989614,0,0,0,90.00000001 +383.99,50.30085681,-2.579924774,10500,0,199.9989614,0,0,0,90.00000001 +384,50.30085681,-2.579896749,10500,0,199.9998535,0,0,0,90.00000001 +384.01,50.30085681,-2.579868724,10500,0,200.0009685,0,0,0,90.00000001 +384.02,50.30085681,-2.579840698,10500,0,200.0009685,0,0,0,90.00000001 +384.03,50.30085681,-2.579812673,10500,0,199.9998535,0,0,0,90.00000001 +384.04,50.30085681,-2.579784648,10500,0,199.9989614,0,0,0,90.00000001 +384.05,50.30085681,-2.579756623,10500,0,199.9989614,0,0,0,90.00000001 +384.06,50.30085681,-2.579728598,10500,0,199.9998535,0,0,0,90.00000001 +384.07,50.30085681,-2.579700573,10500,0,200.0009685,0,0,0,90.00000001 +384.08,50.30085681,-2.579672547,10500,0,200.0009685,0,0,0,90.00000001 +384.09,50.30085681,-2.579644522,10500,0,199.9998535,0,0,0,90.00000001 +384.1,50.30085681,-2.579616497,10500,0,199.9989614,0,0,0,90.00000001 +384.11,50.30085681,-2.579588472,10500,0,199.9989614,0,0,0,90.00000001 +384.12,50.30085681,-2.579560447,10500,0,199.9998535,0,0,0,90.00000001 +384.13,50.30085681,-2.579532422,10500,0,200.0009685,0,0,0,90.00000001 +384.14,50.30085681,-2.579504396,10500,0,200.0009685,0,0,0,90.00000001 +384.15,50.30085681,-2.579476371,10500,0,199.9998535,0,0,0,90.00000001 +384.16,50.30085681,-2.579448346,10500,0,199.9989614,0,0,0,90.00000001 +384.17,50.30085681,-2.579420321,10500,0,199.9989614,0,0,0,90.00000001 +384.18,50.30085681,-2.579392296,10500,0,199.9998535,0,0,0,90.00000001 +384.19,50.30085681,-2.579364271,10500,0,200.0009685,0,0,0,90.00000001 +384.2,50.30085681,-2.579336245,10500,0,200.0009685,0,0,0,90.00000001 +384.21,50.30085681,-2.57930822,10500,0,199.9998535,0,0,0,90.00000001 +384.22,50.30085681,-2.579280195,10500,0,199.9989614,0,0,0,90.00000001 +384.23,50.30085681,-2.57925217,10500,0,199.9989614,0,0,0,90.00000001 +384.24,50.30085681,-2.579224145,10500,0,199.9998535,0,0,0,90.00000001 +384.25,50.30085681,-2.57919612,10500,0,200.0009685,0,0,0,90.00000001 +384.26,50.30085681,-2.579168094,10500,0,200.0009685,0,0,0,90.00000001 +384.27,50.30085681,-2.579140069,10500,0,199.9998535,0,0,0,90.00000001 +384.28,50.30085681,-2.579112044,10500,0,199.9991844,0,0,0,90.00000001 +384.29,50.30085681,-2.579084019,10500,0,199.9998535,0,0,0,90.00000001 +384.3,50.30085681,-2.579055994,10500,0,200.0009685,0,0,0,90.00000001 +384.31,50.30085681,-2.579027968,10500,0,200.0009685,0,0,0,90.00000001 +384.32,50.30085681,-2.578999943,10500,0,199.9998535,0,0,0,90.00000001 +384.33,50.30085681,-2.578971918,10500,0,199.9991844,0,0,0,90.00000001 +384.34,50.30085681,-2.578943893,10500,0,199.9998535,0,0,0,90.00000001 +384.35,50.30085681,-2.578915868,10500,0,200.0009685,0,0,0,90.00000001 +384.36,50.30085681,-2.578887842,10500,0,200.0009685,0,0,0,90.00000001 +384.37,50.30085681,-2.578859817,10500,0,199.9998535,0,0,0,90.00000001 +384.38,50.30085681,-2.578831792,10500,0,199.9991844,0,0,0,90.00000001 +384.39,50.30085681,-2.578803767,10500,0,199.9998535,0,0,0,90.00000001 +384.4,50.30085681,-2.578775742,10500,0,200.0009685,0,0,0,90.00000001 +384.41,50.30085681,-2.578747716,10500,0,200.0009685,0,0,0,90.00000001 +384.42,50.30085681,-2.578719691,10500,0,199.9998535,0,0,0,90.00000001 +384.43,50.30085681,-2.578691666,10500,0,199.9991844,0,0,0,90.00000001 +384.44,50.30085681,-2.578663641,10500,0,199.9998535,0,0,0,90.00000001 +384.45,50.30085681,-2.578635616,10500,0,200.0009685,0,0,0,90.00000001 +384.46,50.30085681,-2.57860759,10500,0,200.0009685,0,0,0,90.00000001 +384.47,50.30085681,-2.578579565,10500,0,199.9998535,0,0,0,90.00000001 +384.48,50.30085681,-2.57855154,10500,0,199.9991844,0,0,0,90.00000001 +384.49,50.30085681,-2.578523515,10500,0,199.9998535,0,0,0,90.00000001 +384.5,50.30085681,-2.57849549,10500,0,200.0009685,0,0,0,90.00000001 +384.51,50.30085681,-2.578467464,10500,0,200.0009685,0,0,0,90.00000001 +384.52,50.30085681,-2.578439439,10500,0,199.9998535,0,0,0,90.00000001 +384.53,50.30085681,-2.578411414,10500,0,199.9989614,0,0,0,90.00000001 +384.54,50.30085681,-2.578383389,10500,0,199.9987384,0,0,0,90.00000001 +384.55,50.30085681,-2.578355364,10500,0,199.9989614,0,0,0,90.00000001 +384.56,50.30085681,-2.578327339,10500,0,199.9998535,0,0,0,90.00000001 +384.57,50.30085681,-2.578299314,10500,0,200.0009685,0,0,0,90.00000001 +384.58,50.30085681,-2.578271288,10500,0,200.0009685,0,0,0,90.00000001 +384.59,50.30085681,-2.578243263,10500,0,199.9998535,0,0,0,90.00000001 +384.6,50.30085681,-2.578215238,10500,0,199.9989614,0,0,0,90.00000001 +384.61,50.30085681,-2.578187213,10500,0,199.9989614,0,0,0,90.00000001 +384.62,50.30085681,-2.578159188,10500,0,199.9998535,0,0,0,90.00000001 +384.63,50.30085681,-2.578131163,10500,0,200.0009685,0,0,0,90.00000001 +384.64,50.30085681,-2.578103137,10500,0,200.0009685,0,0,0,90.00000001 +384.65,50.30085681,-2.578075112,10500,0,199.9998535,0,0,0,90.00000001 +384.66,50.30085681,-2.578047087,10500,0,199.9989614,0,0,0,90.00000001 +384.67,50.30085681,-2.578019062,10500,0,199.9989614,0,0,0,90.00000001 +384.68,50.30085681,-2.577991037,10500,0,199.9998535,0,0,0,90.00000001 +384.69,50.30085681,-2.577963012,10500,0,200.0009685,0,0,0,90.00000001 +384.7,50.30085681,-2.577934986,10500,0,200.0009685,0,0,0,90.00000001 +384.71,50.30085681,-2.577906961,10500,0,199.9998535,0,0,0,90.00000001 +384.72,50.30085681,-2.577878936,10500,0,199.9989614,0,0,0,90.00000001 +384.73,50.30085681,-2.577850911,10500,0,199.9989614,0,0,0,90.00000001 +384.74,50.30085681,-2.577822886,10500,0,199.9998535,0,0,0,90.00000001 +384.75,50.30085681,-2.577794861,10500,0,200.0009685,0,0,0,90.00000001 +384.76,50.30085681,-2.577766835,10500,0,200.0009685,0,0,0,90.00000001 +384.77,50.30085681,-2.57773881,10500,0,199.9998535,0,0,0,90.00000001 +384.78,50.30085681,-2.577710785,10500,0,199.9989614,0,0,0,90.00000001 +384.79,50.30085681,-2.57768276,10500,0,199.9987384,0,0,0,90.00000001 +384.8,50.30085681,-2.577654735,10500,0,199.9989614,0,0,0,90.00000001 +384.81,50.30085681,-2.57762671,10500,0,199.9998535,0,0,0,90.00000001 +384.82,50.30085681,-2.577598685,10500,0,200.0009685,0,0,0,90.00000001 +384.83,50.30085681,-2.577570659,10500,0,200.0009685,0,0,0,90.00000001 +384.84,50.30085681,-2.577542634,10500,0,199.9998535,0,0,0,90.00000001 +384.85,50.30085681,-2.577514609,10500,0,199.9991844,0,0,0,90.00000001 +384.86,50.30085681,-2.577486584,10500,0,199.9998535,0,0,0,90.00000001 +384.87,50.30085681,-2.577458559,10500,0,200.0009685,0,0,0,90.00000001 +384.88,50.30085681,-2.577430533,10500,0,200.0009685,0,0,0,90.00000001 +384.89,50.30085681,-2.577402508,10500,0,199.9998535,0,0,0,90.00000001 +384.9,50.30085681,-2.577374483,10500,0,199.9991844,0,0,0,90.00000001 +384.91,50.30085681,-2.577346458,10500,0,199.9998535,0,0,0,90.00000001 +384.92,50.30085681,-2.577318433,10500,0,200.0009685,0,0,0,90.00000001 +384.93,50.30085681,-2.577290407,10500,0,200.0009685,0,0,0,90.00000001 +384.94,50.30085681,-2.577262382,10500,0,199.9998535,0,0,0,90.00000001 +384.95,50.30085681,-2.577234357,10500,0,199.9991844,0,0,0,90.00000001 +384.96,50.30085681,-2.577206332,10500,0,199.9998535,0,0,0,90.00000001 +384.97,50.30085681,-2.577178307,10500,0,200.0009685,0,0,0,90.00000001 +384.98,50.30085681,-2.577150281,10500,0,200.0009685,0,0,0,90.00000001 +384.99,50.30085681,-2.577122256,10500,0,199.9998535,0,0,0,90.00000001 +385,50.30085681,-2.577094231,10500,0,199.9991844,0,0,0,90.00000001 +385.01,50.30085681,-2.577066206,10500,0,199.9998535,0,0,0,90.00000001 +385.02,50.30085681,-2.577038181,10500,0,200.0009685,0,0,0,90.00000001 +385.03,50.30085681,-2.577010155,10500,0,200.0009685,0,0,0,90.00000001 +385.04,50.30085681,-2.57698213,10500,0,199.9998535,0,0,0,90.00000001 +385.05,50.30085681,-2.576954105,10500,0,199.9991844,0,0,0,90.00000001 +385.06,50.30085681,-2.57692608,10500,0,199.9998535,0,0,0,90.00000001 +385.07,50.30085681,-2.576898055,10500,0,200.0009685,0,0,0,90.00000001 +385.08,50.30085681,-2.576870029,10500,0,200.0009685,0,0,0,90.00000001 +385.09,50.30085681,-2.576842004,10500,0,199.9998535,0,0,0,90.00000001 +385.1,50.30085681,-2.576813979,10500,0,199.9989614,0,0,0,90.00000001 +385.11,50.30085681,-2.576785954,10500,0,199.9989614,0,0,0,90.00000001 +385.12,50.30085681,-2.576757929,10500,0,199.9998535,0,0,0,90.00000001 +385.13,50.30085681,-2.576729904,10500,0,200.0009685,0,0,0,90.00000001 +385.14,50.30085681,-2.576701878,10500,0,200.0009685,0,0,0,90.00000001 +385.15,50.30085681,-2.576673853,10500,0,199.9998535,0,0,0,90.00000001 +385.16,50.30085681,-2.576645828,10500,0,199.9989614,0,0,0,90.00000001 +385.17,50.30085681,-2.576617803,10500,0,199.9989614,0,0,0,90.00000001 +385.18,50.30085681,-2.576589778,10500,0,199.9998535,0,0,0,90.00000001 +385.19,50.30085681,-2.576561753,10500,0,200.0009685,0,0,0,90.00000001 +385.2,50.30085681,-2.576533727,10500,0,200.0009685,0,0,0,90.00000001 +385.21,50.30085681,-2.576505702,10500,0,199.9998535,0,0,0,90.00000001 +385.22,50.30085681,-2.576477677,10500,0,199.9989614,0,0,0,90.00000001 +385.23,50.30085681,-2.576449652,10500,0,199.9989614,0,0,0,90.00000001 +385.24,50.30085681,-2.576421627,10500,0,199.9998535,0,0,0,90.00000001 +385.25,50.30085681,-2.576393602,10500,0,200.0009685,0,0,0,90.00000001 +385.26,50.30085681,-2.576365576,10500,0,200.0009685,0,0,0,90.00000001 +385.27,50.30085681,-2.576337551,10500,0,199.9998535,0,0,0,90.00000001 +385.28,50.30085681,-2.576309526,10500,0,199.9989614,0,0,0,90.00000001 +385.29,50.30085681,-2.576281501,10500,0,199.9989614,0,0,0,90.00000001 +385.3,50.30085681,-2.576253476,10500,0,199.9998535,0,0,0,90.00000001 +385.31,50.30085681,-2.576225451,10500,0,200.0009685,0,0,0,90.00000001 +385.32,50.30085681,-2.576197425,10500,0,200.0009685,0,0,0,90.00000001 +385.33,50.30085681,-2.5761694,10500,0,199.9998535,0,0,0,90.00000001 +385.34,50.30085681,-2.576141375,10500,0,199.9989614,0,0,0,90.00000001 +385.35,50.30085681,-2.57611335,10500,0,199.9987384,0,0,0,90.00000001 +385.36,50.30085681,-2.576085325,10500,0,199.9989614,0,0,0,90.00000001 +385.37,50.30085681,-2.5760573,10500,0,199.9998535,0,0,0,90.00000001 +385.38,50.30085681,-2.576029275,10500,0,200.0009685,0,0,0,90.00000001 +385.39,50.30085681,-2.576001249,10500,0,200.0009685,0,0,0,90.00000001 +385.4,50.30085681,-2.575973224,10500,0,199.9998535,0,0,0,90.00000001 +385.41,50.30085681,-2.575945199,10500,0,199.9989614,0,0,0,90.00000001 +385.42,50.30085681,-2.575917174,10500,0,199.9989614,0,0,0,90.00000001 +385.43,50.30085681,-2.575889149,10500,0,199.9998535,0,0,0,90.00000001 +385.44,50.30085681,-2.575861124,10500,0,200.0009685,0,0,0,90.00000001 +385.45,50.30085681,-2.575833098,10500,0,200.0009685,0,0,0,90.00000001 +385.46,50.30085681,-2.575805073,10500,0,199.9998535,0,0,0,90.00000001 +385.47,50.30085681,-2.575777048,10500,0,199.9991844,0,0,0,90.00000001 +385.48,50.30085681,-2.575749023,10500,0,199.9998535,0,0,0,90.00000001 +385.49,50.30085681,-2.575720998,10500,0,200.0009685,0,0,0,90.00000001 +385.5,50.30085681,-2.575692972,10500,0,200.0009685,0,0,0,90.00000001 +385.51,50.30085681,-2.575664947,10500,0,199.9998535,0,0,0,90.00000001 +385.52,50.30085681,-2.575636922,10500,0,199.9991844,0,0,0,90.00000001 +385.53,50.30085681,-2.575608897,10500,0,199.9998535,0,0,0,90.00000001 +385.54,50.30085681,-2.575580872,10500,0,200.0009685,0,0,0,90.00000001 +385.55,50.30085681,-2.575552846,10500,0,200.0009685,0,0,0,90.00000001 +385.56,50.30085681,-2.575524821,10500,0,199.9998535,0,0,0,90.00000001 +385.57,50.30085681,-2.575496796,10500,0,199.9991844,0,0,0,90.00000001 +385.58,50.30085681,-2.575468771,10500,0,199.9998535,0,0,0,90.00000001 +385.59,50.30085681,-2.575440746,10500,0,200.0009685,0,0,0,90.00000001 +385.6,50.30085681,-2.57541272,10500,0,200.0009685,0,0,0,90.00000001 +385.61,50.30085681,-2.575384695,10500,0,199.9998535,0,0,0,90.00000001 +385.62,50.30085681,-2.57535667,10500,0,199.9991844,0,0,0,90.00000001 +385.63,50.30085681,-2.575328645,10500,0,199.9998535,0,0,0,90.00000001 +385.64,50.30085681,-2.57530062,10500,0,200.0009685,0,0,0,90.00000001 +385.65,50.30085681,-2.575272594,10500,0,200.0009685,0,0,0,90.00000001 +385.66,50.30085681,-2.575244569,10500,0,199.9998535,0,0,0,90.00000001 +385.67,50.30085681,-2.575216544,10500,0,199.9991844,0,0,0,90.00000001 +385.68,50.30085681,-2.575188519,10500,0,199.9998535,0,0,0,90.00000001 +385.69,50.30085681,-2.575160494,10500,0,200.0009685,0,0,0,90.00000001 +385.7,50.30085681,-2.575132468,10500,0,200.0009685,0,0,0,90.00000001 +385.71,50.30085681,-2.575104443,10500,0,199.9998535,0,0,0,90.00000001 +385.72,50.30085681,-2.575076418,10500,0,199.9989614,0,0,0,90.00000001 +385.73,50.30085681,-2.575048393,10500,0,199.9989614,0,0,0,90.00000001 +385.74,50.30085681,-2.575020368,10500,0,199.9998535,0,0,0,90.00000001 +385.75,50.30085681,-2.574992343,10500,0,200.0009685,0,0,0,90.00000001 +385.76,50.30085681,-2.574964317,10500,0,200.0009685,0,0,0,90.00000001 +385.77,50.30085681,-2.574936292,10500,0,199.9998535,0,0,0,90.00000001 +385.78,50.30085681,-2.574908267,10500,0,199.9989614,0,0,0,90.00000001 +385.79,50.30085681,-2.574880242,10500,0,199.9989614,0,0,0,90.00000001 +385.8,50.30085681,-2.574852217,10500,0,199.9998535,0,0,0,90.00000001 +385.81,50.30085681,-2.574824192,10500,0,200.0009685,0,0,0,90.00000001 +385.82,50.30085681,-2.574796166,10500,0,200.0009685,0,0,0,90.00000001 +385.83,50.30085681,-2.574768141,10500,0,199.9998535,0,0,0,90.00000001 +385.84,50.30085681,-2.574740116,10500,0,199.9989614,0,0,0,90.00000001 +385.85,50.30085681,-2.574712091,10500,0,199.9989614,0,0,0,90.00000001 +385.86,50.30085681,-2.574684066,10500,0,199.9998535,0,0,0,90.00000001 +385.87,50.30085681,-2.574656041,10500,0,200.0009685,0,0,0,90.00000001 +385.88,50.30085681,-2.574628015,10500,0,200.0009685,0,0,0,90.00000001 +385.89,50.30085681,-2.57459999,10500,0,199.9998535,0,0,0,90.00000001 +385.9,50.30085681,-2.574571965,10500,0,199.9989614,0,0,0,90.00000001 +385.91,50.30085681,-2.57454394,10500,0,199.9989614,0,0,0,90.00000001 +385.92,50.30085681,-2.574515915,10500,0,199.9998535,0,0,0,90.00000001 +385.93,50.30085681,-2.57448789,10500,0,200.0009685,0,0,0,90.00000001 +385.94,50.30085681,-2.574459864,10500,0,200.0009685,0,0,0,90.00000001 +385.95,50.30085681,-2.574431839,10500,0,199.9998535,0,0,0,90.00000001 +385.96,50.30085681,-2.574403814,10500,0,199.9989614,0,0,0,90.00000001 +385.97,50.30085681,-2.574375789,10500,0,199.9987384,0,0,0,90.00000001 +385.98,50.30085681,-2.574347764,10500,0,199.9989614,0,0,0,90.00000001 +385.99,50.30085681,-2.574319739,10500,0,199.9998535,0,0,0,90.00000001 +386,50.30085681,-2.574291714,10500,0,200.0009685,0,0,0,90.00000001 +386.01,50.30085681,-2.574263688,10500,0,200.0009685,0,0,0,90.00000001 +386.02,50.30085681,-2.574235663,10500,0,199.9998535,0,0,0,90.00000001 +386.03,50.30085681,-2.574207638,10500,0,199.9989614,0,0,0,90.00000001 +386.04,50.30085681,-2.574179613,10500,0,199.9989614,0,0,0,90.00000001 +386.05,50.30085681,-2.574151588,10500,0,199.9998535,0,0,0,90.00000001 +386.06,50.30085681,-2.574123563,10500,0,200.0009685,0,0,0,90.00000001 +386.07,50.30085681,-2.574095537,10500,0,200.0009685,0,0,0,90.00000001 +386.08,50.30085681,-2.574067512,10500,0,199.9998535,0,0,0,90.00000001 +386.09,50.30085681,-2.574039487,10500,0,199.9991844,0,0,0,90.00000001 +386.1,50.30085681,-2.574011462,10500,0,199.9998535,0,0,0,90.00000001 +386.11,50.30085681,-2.573983437,10500,0,200.0009685,0,0,0,90.00000001 +386.12,50.30085681,-2.573955411,10500,0,200.0009685,0,0,0,90.00000001 +386.13,50.30085681,-2.573927386,10500,0,199.9998535,0,0,0,90.00000001 +386.14,50.30085681,-2.573899361,10500,0,199.9991844,0,0,0,90.00000001 +386.15,50.30085681,-2.573871336,10500,0,199.9998535,0,0,0,90.00000001 +386.16,50.30085681,-2.573843311,10500,0,200.0009685,0,0,0,90.00000001 +386.17,50.30085681,-2.573815285,10500,0,200.0009685,0,0,0,90.00000001 +386.18,50.30085681,-2.57378726,10500,0,199.9998535,0,0,0,90.00000001 +386.19,50.30085681,-2.573759235,10500,0,199.9991844,0,0,0,90.00000001 +386.2,50.30085681,-2.57373121,10500,0,199.9998535,0,0,0,90.00000001 +386.21,50.30085681,-2.573703185,10500,0,200.0009685,0,0,0,90.00000001 +386.22,50.30085681,-2.573675159,10500,0,200.0009685,0,0,0,90.00000001 +386.23,50.30085681,-2.573647134,10500,0,199.9998535,0,0,0,90.00000001 +386.24,50.30085681,-2.573619109,10500,0,199.9989614,0,0,0,90.00000001 +386.25,50.30085681,-2.573591084,10500,0,199.9989614,0,0,0,90.00000001 +386.26,50.30085681,-2.573563059,10500,0,199.9998535,0,0,0,90.00000001 +386.27,50.30085681,-2.573535034,10500,0,200.0009685,0,0,0,90.00000001 +386.28,50.30085681,-2.573507008,10500,0,200.0009685,0,0,0,90.00000001 +386.29,50.30085681,-2.573478983,10500,0,199.9998535,0,0,0,90.00000001 +386.3,50.30085681,-2.573450958,10500,0,199.9991844,0,0,0,90.00000001 +386.31,50.30085681,-2.573422933,10500,0,199.9998535,0,0,0,90.00000001 +386.32,50.30085681,-2.573394908,10500,0,200.0009685,0,0,0,90.00000001 +386.33,50.30085681,-2.573366882,10500,0,200.0009685,0,0,0,90.00000001 +386.34,50.30085681,-2.573338857,10500,0,199.9998535,0,0,0,90.00000001 +386.35,50.30085681,-2.573310832,10500,0,199.9991844,0,0,0,90.00000001 +386.36,50.30085681,-2.573282807,10500,0,199.9998535,0,0,0,90.00000001 +386.37,50.30085681,-2.573254782,10500,0,200.0009685,0,0,0,90.00000001 +386.38,50.30085681,-2.573226756,10500,0,200.0009685,0,0,0,90.00000001 +386.39,50.30085681,-2.573198731,10500,0,199.9998535,0,0,0,90.00000001 +386.4,50.30085681,-2.573170706,10500,0,199.9989614,0,0,0,90.00000001 +386.41,50.30085681,-2.573142681,10500,0,199.9989614,0,0,0,90.00000001 +386.42,50.30085681,-2.573114656,10500,0,199.9998535,0,0,0,90.00000001 +386.43,50.30085681,-2.573086631,10500,0,200.0009685,0,0,0,90.00000001 +386.44,50.30085681,-2.573058605,10500,0,200.0009685,0,0,0,90.00000001 +386.45,50.30085681,-2.57303058,10500,0,199.9998535,0,0,0,90.00000001 +386.46,50.30085681,-2.573002555,10500,0,199.9989614,0,0,0,90.00000001 +386.47,50.30085681,-2.57297453,10500,0,199.9989614,0,0,0,90.00000001 +386.48,50.30085681,-2.572946505,10500,0,199.9998535,0,0,0,90.00000001 +386.49,50.30085681,-2.57291848,10500,0,200.0009685,0,0,0,90.00000001 +386.5,50.30085681,-2.572890454,10500,0,200.0009685,0,0,0,90.00000001 +386.51,50.30085681,-2.572862429,10500,0,199.9998535,0,0,0,90.00000001 +386.52,50.30085681,-2.572834404,10500,0,199.9989614,0,0,0,90.00000001 +386.53,50.30085681,-2.572806379,10500,0,199.9987384,0,0,0,90.00000001 +386.54,50.30085681,-2.572778354,10500,0,199.9989614,0,0,0,90.00000001 +386.55,50.30085681,-2.572750329,10500,0,199.9998535,0,0,0,90.00000001 +386.56,50.30085681,-2.572722304,10500,0,200.0009685,0,0,0,90.00000001 +386.57,50.30085681,-2.572694278,10500,0,200.0009685,0,0,0,90.00000001 +386.58,50.30085681,-2.572666253,10500,0,199.9998535,0,0,0,90.00000001 +386.59,50.30085681,-2.572638228,10500,0,199.9989614,0,0,0,90.00000001 +386.6,50.30085681,-2.572610203,10500,0,199.9989614,0,0,0,90.00000001 +386.61,50.30085681,-2.572582178,10500,0,199.9998535,0,0,0,90.00000001 +386.62,50.30085681,-2.572554153,10500,0,200.0009685,0,0,0,90.00000001 +386.63,50.30085681,-2.572526127,10500,0,200.0009685,0,0,0,90.00000001 +386.64,50.30085681,-2.572498102,10500,0,199.9998535,0,0,0,90.00000001 +386.65,50.30085681,-2.572470077,10500,0,199.9989614,0,0,0,90.00000001 +386.66,50.30085681,-2.572442052,10500,0,199.9989614,0,0,0,90.00000001 +386.67,50.30085681,-2.572414027,10500,0,199.9998535,0,0,0,90.00000001 +386.68,50.30085681,-2.572386002,10500,0,200.0009685,0,0,0,90.00000001 +386.69,50.30085681,-2.572357976,10500,0,200.0009685,0,0,0,90.00000001 +386.7,50.30085681,-2.572329951,10500,0,199.9998535,0,0,0,90.00000001 +386.71,50.30085681,-2.572301926,10500,0,199.9989614,0,0,0,90.00000001 +386.72,50.30085681,-2.572273901,10500,0,199.9989614,0,0,0,90.00000001 +386.73,50.30085681,-2.572245876,10500,0,199.9998535,0,0,0,90.00000001 +386.74,50.30085681,-2.572217851,10500,0,200.0009685,0,0,0,90.00000001 +386.75,50.30085681,-2.572189825,10500,0,200.0009685,0,0,0,90.00000001 +386.76,50.30085681,-2.5721618,10500,0,199.9998535,0,0,0,90.00000001 +386.77,50.30085681,-2.572133775,10500,0,199.9991844,0,0,0,90.00000001 +386.78,50.30085681,-2.57210575,10500,0,199.9998535,0,0,0,90.00000001 +386.79,50.30085681,-2.572077725,10500,0,200.0009685,0,0,0,90.00000001 +386.8,50.30085681,-2.572049699,10500,0,200.0009685,0,0,0,90.00000001 +386.81,50.30085681,-2.572021674,10500,0,199.9998535,0,0,0,90.00000001 +386.82,50.30085681,-2.571993649,10500,0,199.9991844,0,0,0,90.00000001 +386.83,50.30085681,-2.571965624,10500,0,199.9998535,0,0,0,90.00000001 +386.84,50.30085681,-2.571937599,10500,0,200.0009685,0,0,0,90.00000001 +386.85,50.30085681,-2.571909573,10500,0,200.0009685,0,0,0,90.00000001 +386.86,50.30085681,-2.571881548,10500,0,199.9998535,0,0,0,90.00000001 +386.87,50.30085681,-2.571853523,10500,0,199.9991844,0,0,0,90.00000001 +386.88,50.30085681,-2.571825498,10500,0,199.9998535,0,0,0,90.00000001 +386.89,50.30085681,-2.571797473,10500,0,200.0009685,0,0,0,90.00000001 +386.9,50.30085681,-2.571769447,10500,0,200.0009685,0,0,0,90.00000001 +386.91,50.30085681,-2.571741422,10500,0,199.9998535,0,0,0,90.00000001 +386.92,50.30085681,-2.571713397,10500,0,199.9991844,0,0,0,90.00000001 +386.93,50.30085681,-2.571685372,10500,0,199.9998535,0,0,0,90.00000001 +386.94,50.30085681,-2.571657347,10500,0,200.0009685,0,0,0,90.00000001 +386.95,50.30085681,-2.571629321,10500,0,200.0009685,0,0,0,90.00000001 +386.96,50.30085681,-2.571601296,10500,0,199.9998535,0,0,0,90.00000001 +386.97,50.30085681,-2.571573271,10500,0,199.9991844,0,0,0,90.00000001 +386.98,50.30085681,-2.571545246,10500,0,199.9998535,0,0,0,90.00000001 +386.99,50.30085681,-2.571517221,10500,0,200.0009685,0,0,0,90.00000001 +387,50.30085681,-2.571489195,10500,0,200.0009685,0,0,0,90.00000001 +387.01,50.30085681,-2.57146117,10500,0,199.9998535,0,0,0,90.00000001 +387.02,50.30085681,-2.571433145,10500,0,199.9989614,0,0,0,90.00000001 +387.03,50.30085681,-2.57140512,10500,0,199.9989614,0,0,0,90.00000001 +387.04,50.30085681,-2.571377095,10500,0,199.9998535,0,0,0,90.00000001 +387.05,50.30085681,-2.57134907,10500,0,200.0009685,0,0,0,90.00000001 +387.06,50.30085681,-2.571321044,10500,0,200.0009685,0,0,0,90.00000001 +387.07,50.30085681,-2.571293019,10500,0,199.9998535,0,0,0,90.00000001 +387.08,50.30085681,-2.571264994,10500,0,199.9989614,0,0,0,90.00000001 +387.09,50.30085681,-2.571236969,10500,0,199.9987384,0,0,0,90.00000001 +387.1,50.30085681,-2.571208944,10500,0,199.9989614,0,0,0,90.00000001 +387.11,50.30085681,-2.571180919,10500,0,199.9998535,0,0,0,90.00000001 +387.12,50.30085681,-2.571152894,10500,0,200.0009685,0,0,0,90.00000001 +387.13,50.30085681,-2.571124868,10500,0,200.0009685,0,0,0,90.00000001 +387.14,50.30085681,-2.571096843,10500,0,199.9998535,0,0,0,90.00000001 +387.15,50.30085681,-2.571068818,10500,0,199.9989614,0,0,0,90.00000001 +387.16,50.30085681,-2.571040793,10500,0,199.9989614,0,0,0,90.00000001 +387.17,50.30085681,-2.571012768,10500,0,199.9998535,0,0,0,90.00000001 +387.18,50.30085681,-2.570984743,10500,0,200.0009685,0,0,0,90.00000001 +387.19,50.30085681,-2.570956717,10500,0,200.0009685,0,0,0,90.00000001 +387.2,50.30085681,-2.570928692,10500,0,199.9998535,0,0,0,90.00000001 +387.21,50.30085681,-2.570900667,10500,0,199.9989614,0,0,0,90.00000001 +387.22,50.30085681,-2.570872642,10500,0,199.9989614,0,0,0,90.00000001 +387.23,50.30085681,-2.570844617,10500,0,199.9998535,0,0,0,90.00000001 +387.24,50.30085681,-2.570816592,10500,0,200.0009685,0,0,0,90.00000001 +387.25,50.30085681,-2.570788566,10500,0,200.0009685,0,0,0,90.00000001 +387.26,50.30085681,-2.570760541,10500,0,199.9998535,0,0,0,90.00000001 +387.27,50.30085681,-2.570732516,10500,0,199.9989614,0,0,0,90.00000001 +387.28,50.30085681,-2.570704491,10500,0,199.9989614,0,0,0,90.00000001 +387.29,50.30085681,-2.570676466,10500,0,199.9998535,0,0,0,90.00000001 +387.3,50.30085681,-2.570648441,10500,0,200.0009685,0,0,0,90.00000001 +387.31,50.30085681,-2.570620415,10500,0,200.0009685,0,0,0,90.00000001 +387.32,50.30085681,-2.57059239,10500,0,199.9998535,0,0,0,90.00000001 +387.33,50.30085681,-2.570564365,10500,0,199.9989614,0,0,0,90.00000001 +387.34,50.30085681,-2.57053634,10500,0,199.9989614,0,0,0,90.00000001 +387.35,50.30085681,-2.570508315,10500,0,199.9998535,0,0,0,90.00000001 +387.36,50.30085681,-2.57048029,10500,0,200.0009685,0,0,0,90.00000001 +387.37,50.30085681,-2.570452264,10500,0,200.0009685,0,0,0,90.00000001 +387.38,50.30085681,-2.570424239,10500,0,199.9998535,0,0,0,90.00000001 +387.39,50.30085681,-2.570396214,10500,0,199.9991844,0,0,0,90.00000001 +387.4,50.30085681,-2.570368189,10500,0,199.9998535,0,0,0,90.00000001 +387.41,50.30085681,-2.570340164,10500,0,200.0009685,0,0,0,90.00000001 +387.42,50.30085681,-2.570312138,10500,0,200.0009685,0,0,0,90.00000001 +387.43,50.30085681,-2.570284113,10500,0,199.9998535,0,0,0,90.00000001 +387.44,50.30085681,-2.570256088,10500,0,199.9991844,0,0,0,90.00000001 +387.45,50.30085681,-2.570228063,10500,0,199.9998535,0,0,0,90.00000001 +387.46,50.30085681,-2.570200038,10500,0,200.0009685,0,0,0,90.00000001 +387.47,50.30085681,-2.570172012,10500,0,200.0009685,0,0,0,90.00000001 +387.48,50.30085681,-2.570143987,10500,0,199.9998535,0,0,0,90.00000001 +387.49,50.30085681,-2.570115962,10500,0,199.9991844,0,0,0,90.00000001 +387.5,50.30085681,-2.570087937,10500,0,199.9998535,0,0,0,90.00000001 +387.51,50.30085681,-2.570059912,10500,0,200.0009685,0,0,0,90.00000001 +387.52,50.30085681,-2.570031886,10500,0,200.0009685,0,0,0,90.00000001 +387.53,50.30085681,-2.570003861,10500,0,199.9998535,0,0,0,90.00000001 +387.54,50.30085681,-2.569975836,10500,0,199.9991844,0,0,0,90.00000001 +387.55,50.30085681,-2.569947811,10500,0,199.9998535,0,0,0,90.00000001 +387.56,50.30085681,-2.569919786,10500,0,200.0009685,0,0,0,90.00000001 +387.57,50.30085681,-2.56989176,10500,0,200.0009685,0,0,0,90.00000001 +387.58,50.30085681,-2.569863735,10500,0,199.9998535,0,0,0,90.00000001 +387.59,50.30085681,-2.56983571,10500,0,199.9991844,0,0,0,90.00000001 +387.6,50.30085681,-2.569807685,10500,0,199.9998535,0,0,0,90.00000001 +387.61,50.30085681,-2.56977966,10500,0,200.0009685,0,0,0,90.00000001 +387.62,50.30085681,-2.569751634,10500,0,200.0009685,0,0,0,90.00000001 +387.63,50.30085681,-2.569723609,10500,0,199.9998535,0,0,0,90.00000001 +387.64,50.30085681,-2.569695584,10500,0,199.9989614,0,0,0,90.00000001 +387.65,50.30085681,-2.569667559,10500,0,199.9987384,0,0,0,90.00000001 +387.66,50.30085681,-2.569639534,10500,0,199.9989614,0,0,0,90.00000001 +387.67,50.30085681,-2.569611509,10500,0,199.9998535,0,0,0,90.00000001 +387.68,50.30085681,-2.569583484,10500,0,200.0009685,0,0,0,90.00000001 +387.69,50.30085681,-2.569555458,10500,0,200.0009685,0,0,0,90.00000001 +387.7,50.30085681,-2.569527433,10500,0,199.9998535,0,0,0,90.00000001 +387.71,50.30085681,-2.569499408,10500,0,199.9989614,0,0,0,90.00000001 +387.72,50.30085681,-2.569471383,10500,0,199.9989614,0,0,0,90.00000001 +387.73,50.30085681,-2.569443358,10500,0,199.9998535,0,0,0,90.00000001 +387.74,50.30085681,-2.569415333,10500,0,200.0009685,0,0,0,90.00000001 +387.75,50.30085681,-2.569387307,10500,0,200.0009685,0,0,0,90.00000001 +387.76,50.30085681,-2.569359282,10500,0,199.9998535,0,0,0,90.00000001 +387.77,50.30085681,-2.569331257,10500,0,199.9989614,0,0,0,90.00000001 +387.78,50.30085681,-2.569303232,10500,0,199.9989614,0,0,0,90.00000001 +387.79,50.30085681,-2.569275207,10500,0,199.9998535,0,0,0,90.00000001 +387.8,50.30085681,-2.569247182,10500,0,200.0009685,0,0,0,90.00000001 +387.81,50.30085681,-2.569219156,10500,0,200.0009685,0,0,0,90.00000001 +387.82,50.30085681,-2.569191131,10500,0,199.9998535,0,0,0,90.00000001 +387.83,50.30085681,-2.569163106,10500,0,199.9989614,0,0,0,90.00000001 +387.84,50.30085681,-2.569135081,10500,0,199.9989614,0,0,0,90.00000001 +387.85,50.30085681,-2.569107056,10500,0,199.9998535,0,0,0,90.00000001 +387.86,50.30085681,-2.569079031,10500,0,200.0009685,0,0,0,90.00000001 +387.87,50.30085681,-2.569051005,10500,0,200.0009685,0,0,0,90.00000001 +387.88,50.30085681,-2.56902298,10500,0,199.9998535,0,0,0,90.00000001 +387.89,50.30085681,-2.568994955,10500,0,199.9989614,0,0,0,90.00000001 +387.9,50.30085681,-2.56896693,10500,0,199.9989614,0,0,0,90.00000001 +387.91,50.30085681,-2.568938905,10500,0,199.9998535,0,0,0,90.00000001 +387.92,50.30085681,-2.56891088,10500,0,200.0009685,0,0,0,90.00000001 +387.93,50.30085681,-2.568882854,10500,0,200.0009685,0,0,0,90.00000001 +387.94,50.30085681,-2.568854829,10500,0,199.9998535,0,0,0,90.00000001 +387.95,50.30085681,-2.568826804,10500,0,199.9989614,0,0,0,90.00000001 +387.96,50.30085681,-2.568798779,10500,0,199.9989614,0,0,0,90.00000001 +387.97,50.30085681,-2.568770754,10500,0,199.9998535,0,0,0,90.00000001 +387.98,50.30085681,-2.568742729,10500,0,200.0009685,0,0,0,90.00000001 +387.99,50.30085681,-2.568714703,10500,0,200.0009685,0,0,0,90.00000001 +388,50.30085681,-2.568686678,10500,0,199.9998535,0,0,0,90.00000001 +388.01,50.30085681,-2.568658653,10500,0,199.9991844,0,0,0,90.00000001 +388.02,50.30085681,-2.568630628,10500,0,199.9998535,0,0,0,90.00000001 +388.03,50.30085681,-2.568602603,10500,0,200.0009685,0,0,0,90.00000001 +388.04,50.30085681,-2.568574577,10500,0,200.0009685,0,0,0,90.00000001 +388.05,50.30085681,-2.568546552,10500,0,199.9998535,0,0,0,90.00000001 +388.06,50.30085681,-2.568518527,10500,0,199.9991844,0,0,0,90.00000001 +388.07,50.30085681,-2.568490502,10500,0,199.9998535,0,0,0,90.00000001 +388.08,50.30085681,-2.568462477,10500,0,200.0009685,0,0,0,90.00000001 +388.09,50.30085681,-2.568434451,10500,0,200.0009685,0,0,0,90.00000001 +388.1,50.30085681,-2.568406426,10500,0,199.9998535,0,0,0,90.00000001 +388.11,50.30085681,-2.568378401,10500,0,199.9991844,0,0,0,90.00000001 +388.12,50.30085681,-2.568350376,10500,0,199.9998535,0,0,0,90.00000001 +388.13,50.30085681,-2.568322351,10500,0,200.0009685,0,0,0,90.00000001 +388.14,50.30085681,-2.568294325,10500,0,200.0009685,0,0,0,90.00000001 +388.15,50.30085681,-2.5682663,10500,0,199.9998535,0,0,0,90.00000001 +388.16,50.30085681,-2.568238275,10500,0,199.9991844,0,0,0,90.00000001 +388.17,50.30085681,-2.56821025,10500,0,199.9998535,0,0,0,90.00000001 +388.18,50.30085681,-2.568182225,10500,0,200.0009685,0,0,0,90.00000001 +388.19,50.30085681,-2.568154199,10500,0,200.0009685,0,0,0,90.00000001 +388.2,50.30085681,-2.568126174,10500,0,199.9998535,0,0,0,90.00000001 +388.21,50.30085681,-2.568098149,10500,0,199.9989614,0,0,0,90.00000001 +388.22,50.30085681,-2.568070124,10500,0,199.9989614,0,0,0,90.00000001 +388.23,50.30085681,-2.568042099,10500,0,199.9998535,0,0,0,90.00000001 +388.24,50.30085681,-2.568014074,10500,0,200.0009685,0,0,0,90.00000001 +388.25,50.30085681,-2.567986048,10500,0,200.0009685,0,0,0,90.00000001 +388.26,50.30085681,-2.567958023,10500,0,199.9998535,0,0,0,90.00000001 +388.27,50.30085681,-2.567929998,10500,0,199.9989614,0,0,0,90.00000001 +388.28,50.30085681,-2.567901973,10500,0,199.9989614,0,0,0,90.00000001 +388.29,50.30085681,-2.567873948,10500,0,199.9998535,0,0,0,90.00000001 +388.3,50.30085681,-2.567845923,10500,0,200.0009685,0,0,0,90.00000001 +388.31,50.30085681,-2.567817897,10500,0,200.0009685,0,0,0,90.00000001 +388.32,50.30085681,-2.567789872,10500,0,199.9998535,0,0,0,90.00000001 +388.33,50.30085681,-2.567761847,10500,0,199.9989614,0,0,0,90.00000001 +388.34,50.30085681,-2.567733822,10500,0,199.9989614,0,0,0,90.00000001 +388.35,50.30085681,-2.567705797,10500,0,199.9998535,0,0,0,90.00000001 +388.36,50.30085681,-2.567677772,10500,0,200.0009685,0,0,0,90.00000001 +388.37,50.30085681,-2.567649746,10500,0,200.0009685,0,0,0,90.00000001 +388.38,50.30085681,-2.567621721,10500,0,199.9998535,0,0,0,90.00000001 +388.39,50.30085681,-2.567593696,10500,0,199.9989614,0,0,0,90.00000001 +388.4,50.30085681,-2.567565671,10500,0,199.9989614,0,0,0,90.00000001 +388.41,50.30085681,-2.567537646,10500,0,199.9998535,0,0,0,90.00000001 +388.42,50.30085681,-2.567509621,10500,0,200.0009685,0,0,0,90.00000001 +388.43,50.30085681,-2.567481595,10500,0,200.0009685,0,0,0,90.00000001 +388.44,50.30085681,-2.56745357,10500,0,199.9998535,0,0,0,90.00000001 +388.45,50.30085681,-2.567425545,10500,0,199.9989614,0,0,0,90.00000001 +388.46,50.30085681,-2.56739752,10500,0,199.9989614,0,0,0,90.00000001 +388.47,50.30085681,-2.567369495,10500,0,199.9998535,0,0,0,90.00000001 +388.48,50.30085681,-2.56734147,10500,0,200.0009685,0,0,0,90.00000001 +388.49,50.30085681,-2.567313444,10500,0,200.0009685,0,0,0,90.00000001 +388.5,50.30085681,-2.567285419,10500,0,199.9998535,0,0,0,90.00000001 +388.51,50.30085681,-2.567257394,10500,0,199.9989614,0,0,0,90.00000001 +388.52,50.30085681,-2.567229369,10500,0,199.9987384,0,0,0,90.00000001 +388.53,50.30085681,-2.567201344,10500,0,199.9989614,0,0,0,90.00000001 +388.54,50.30085681,-2.567173319,10500,0,199.9998535,0,0,0,90.00000001 +388.55,50.30085681,-2.567145294,10500,0,200.0009685,0,0,0,90.00000001 +388.56,50.30085681,-2.567117268,10500,0,200.0009685,0,0,0,90.00000001 +388.57,50.30085681,-2.567089243,10500,0,199.9998535,0,0,0,90.00000001 +388.58,50.30085681,-2.567061218,10500,0,199.9991844,0,0,0,90.00000001 +388.59,50.30085681,-2.567033193,10500,0,199.9998535,0,0,0,90.00000001 +388.6,50.30085681,-2.567005168,10500,0,200.0009685,0,0,0,90.00000001 +388.61,50.30085681,-2.566977142,10500,0,200.0009685,0,0,0,90.00000001 +388.62,50.30085681,-2.566949117,10500,0,199.9998535,0,0,0,90.00000001 +388.63,50.30085681,-2.566921092,10500,0,199.9989614,0,0,0,90.00000001 +388.64,50.30085681,-2.566893067,10500,0,199.9989614,0,0,0,90.00000001 +388.65,50.30085681,-2.566865042,10500,0,199.9998535,0,0,0,90.00000001 +388.66,50.30085681,-2.566837017,10500,0,200.0009685,0,0,0,90.00000001 +388.67,50.30085681,-2.566808991,10500,0,200.0009685,0,0,0,90.00000001 +388.68,50.30085681,-2.566780966,10500,0,199.9998535,0,0,0,90.00000001 +388.69,50.30085681,-2.566752941,10500,0,199.9991844,0,0,0,90.00000001 +388.7,50.30085681,-2.566724916,10500,0,199.9998535,0,0,0,90.00000001 +388.71,50.30085681,-2.566696891,10500,0,200.0009685,0,0,0,90.00000001 +388.72,50.30085681,-2.566668865,10500,0,200.0009685,0,0,0,90.00000001 +388.73,50.30085681,-2.56664084,10500,0,199.9998535,0,0,0,90.00000001 +388.74,50.30085681,-2.566612815,10500,0,199.9991844,0,0,0,90.00000001 +388.75,50.30085681,-2.56658479,10500,0,199.9998535,0,0,0,90.00000001 +388.76,50.30085681,-2.566556765,10500,0,200.0009685,0,0,0,90.00000001 +388.77,50.30085681,-2.566528739,10500,0,200.0009685,0,0,0,90.00000001 +388.78,50.30085681,-2.566500714,10500,0,199.9998535,0,0,0,90.00000001 +388.79,50.30085681,-2.566472689,10500,0,199.9991844,0,0,0,90.00000001 +388.8,50.30085681,-2.566444664,10500,0,199.9998535,0,0,0,90.00000001 +388.81,50.30085681,-2.566416639,10500,0,200.0009685,0,0,0,90.00000001 +388.82,50.30085681,-2.566388613,10500,0,200.0009685,0,0,0,90.00000001 +388.83,50.30085681,-2.566360588,10500,0,199.9998535,0,0,0,90.00000001 +388.84,50.30085681,-2.566332563,10500,0,199.9991844,0,0,0,90.00000001 +388.85,50.30085681,-2.566304538,10500,0,199.9998535,0,0,0,90.00000001 +388.86,50.30085681,-2.566276513,10500,0,200.0009685,0,0,0,90.00000001 +388.87,50.30085681,-2.566248487,10500,0,200.0009685,0,0,0,90.00000001 +388.88,50.30085681,-2.566220462,10500,0,199.9998535,0,0,0,90.00000001 +388.89,50.30085681,-2.566192437,10500,0,199.9989614,0,0,0,90.00000001 +388.9,50.30085681,-2.566164412,10500,0,199.9989614,0,0,0,90.00000001 +388.91,50.30085681,-2.566136387,10500,0,199.9998535,0,0,0,90.00000001 +388.92,50.30085681,-2.566108362,10500,0,200.0009685,0,0,0,90.00000001 +388.93,50.30085681,-2.566080336,10500,0,200.0009685,0,0,0,90.00000001 +388.94,50.30085681,-2.566052311,10500,0,199.9998535,0,0,0,90.00000001 +388.95,50.30085681,-2.566024286,10500,0,199.9989614,0,0,0,90.00000001 +388.96,50.30085681,-2.565996261,10500,0,199.9989614,0,0,0,90.00000001 +388.97,50.30085681,-2.565968236,10500,0,199.9998535,0,0,0,90.00000001 +388.98,50.30085681,-2.565940211,10500,0,200.0009685,0,0,0,90.00000001 +388.99,50.30085681,-2.565912185,10500,0,200.0009685,0,0,0,90.00000001 +389,50.30085681,-2.56588416,10500,0,199.9998535,0,0,0,90.00000001 +389.01,50.30085681,-2.565856135,10500,0,199.9989614,0,0,0,90.00000001 +389.02,50.30085681,-2.56582811,10500,0,199.9989614,0,0,0,90.00000001 +389.03,50.30085681,-2.565800085,10500,0,199.9998535,0,0,0,90.00000001 +389.04,50.30085681,-2.56577206,10500,0,200.0009685,0,0,0,90.00000001 +389.05,50.30085681,-2.565744034,10500,0,200.0009685,0,0,0,90.00000001 +389.06,50.30085681,-2.565716009,10500,0,199.9998535,0,0,0,90.00000001 +389.07,50.30085681,-2.565687984,10500,0,199.9989614,0,0,0,90.00000001 +389.08,50.30085681,-2.565659959,10500,0,199.9987384,0,0,0,90.00000001 +389.09,50.30085681,-2.565631934,10500,0,199.9989614,0,0,0,90.00000001 +389.1,50.30085681,-2.565603909,10500,0,199.9998535,0,0,0,90.00000001 +389.11,50.30085681,-2.565575884,10500,0,200.0009685,0,0,0,90.00000001 +389.12,50.30085681,-2.565547858,10500,0,200.0009685,0,0,0,90.00000001 +389.13,50.30085681,-2.565519833,10500,0,199.9998535,0,0,0,90.00000001 +389.14,50.30085681,-2.565491808,10500,0,199.9989614,0,0,0,90.00000001 +389.15,50.30085681,-2.565463783,10500,0,199.9989614,0,0,0,90.00000001 +389.16,50.30085681,-2.565435758,10500,0,199.9998535,0,0,0,90.00000001 +389.17,50.30085681,-2.565407733,10500,0,200.0009685,0,0,0,90.00000001 +389.18,50.30085681,-2.565379707,10500,0,200.0009685,0,0,0,90.00000001 +389.19,50.30085681,-2.565351682,10500,0,199.9998535,0,0,0,90.00000001 +389.2,50.30085681,-2.565323657,10500,0,199.9989614,0,0,0,90.00000001 +389.21,50.30085681,-2.565295632,10500,0,199.9989614,0,0,0,90.00000001 +389.22,50.30085681,-2.565267607,10500,0,199.9998535,0,0,0,90.00000001 +389.23,50.30085681,-2.565239582,10500,0,200.0009685,0,0,0,90.00000001 +389.24,50.30085681,-2.565211556,10500,0,200.0009685,0,0,0,90.00000001 +389.25,50.30085681,-2.565183531,10500,0,199.9998535,0,0,0,90.00000001 +389.26,50.30085681,-2.565155506,10500,0,199.9991844,0,0,0,90.00000001 +389.27,50.30085681,-2.565127481,10500,0,199.9998535,0,0,0,90.00000001 +389.28,50.30085681,-2.565099456,10500,0,200.0009685,0,0,0,90.00000001 +389.29,50.30085681,-2.56507143,10500,0,200.0009685,0,0,0,90.00000001 +389.3,50.30085681,-2.565043405,10500,0,199.9998535,0,0,0,90.00000001 +389.31,50.30085681,-2.56501538,10500,0,199.9991844,0,0,0,90.00000001 +389.32,50.30085681,-2.564987355,10500,0,199.9998535,0,0,0,90.00000001 +389.33,50.30085681,-2.56495933,10500,0,200.0009685,0,0,0,90.00000001 +389.34,50.30085681,-2.564931304,10500,0,200.0009685,0,0,0,90.00000001 +389.35,50.30085681,-2.564903279,10500,0,199.9998535,0,0,0,90.00000001 +389.36,50.30085681,-2.564875254,10500,0,199.9991844,0,0,0,90.00000001 +389.37,50.30085681,-2.564847229,10500,0,199.9998535,0,0,0,90.00000001 +389.38,50.30085681,-2.564819204,10500,0,200.0009685,0,0,0,90.00000001 +389.39,50.30085681,-2.564791178,10500,0,200.0009685,0,0,0,90.00000001 +389.4,50.30085681,-2.564763153,10500,0,199.9998535,0,0,0,90.00000001 +389.41,50.30085681,-2.564735128,10500,0,199.9991844,0,0,0,90.00000001 +389.42,50.30085681,-2.564707103,10500,0,199.9998535,0,0,0,90.00000001 +389.43,50.30085681,-2.564679078,10500,0,200.0009685,0,0,0,90.00000001 +389.44,50.30085681,-2.564651052,10500,0,200.0009685,0,0,0,90.00000001 +389.45,50.30085681,-2.564623027,10500,0,199.9998535,0,0,0,90.00000001 +389.46,50.30085681,-2.564595002,10500,0,199.9991844,0,0,0,90.00000001 +389.47,50.30085681,-2.564566977,10500,0,199.9998535,0,0,0,90.00000001 +389.48,50.30085681,-2.564538952,10500,0,200.0009685,0,0,0,90.00000001 +389.49,50.30085681,-2.564510926,10500,0,200.0009685,0,0,0,90.00000001 +389.5,50.30085681,-2.564482901,10500,0,199.9998535,0,0,0,90.00000001 +389.51,50.30085681,-2.564454876,10500,0,199.9989614,0,0,0,90.00000001 +389.52,50.30085681,-2.564426851,10500,0,199.9989614,0,0,0,90.00000001 +389.53,50.30085681,-2.564398826,10500,0,199.9998535,0,0,0,90.00000001 +389.54,50.30085681,-2.564370801,10500,0,200.0009685,0,0,0,90.00000001 +389.55,50.30085681,-2.564342775,10500,0,200.0009685,0,0,0,90.00000001 +389.56,50.30085681,-2.56431475,10500,0,199.9998535,0,0,0,90.00000001 +389.57,50.30085681,-2.564286725,10500,0,199.9989614,0,0,0,90.00000001 +389.58,50.30085681,-2.5642587,10500,0,199.9989614,0,0,0,90.00000001 +389.59,50.30085681,-2.564230675,10500,0,199.9998535,0,0,0,90.00000001 +389.6,50.30085681,-2.56420265,10500,0,200.0009685,0,0,0,90.00000001 +389.61,50.30085681,-2.564174624,10500,0,200.0009685,0,0,0,90.00000001 +389.62,50.30085681,-2.564146599,10500,0,199.9998535,0,0,0,90.00000001 +389.63,50.30085681,-2.564118574,10500,0,199.9989614,0,0,0,90.00000001 +389.64,50.30085681,-2.564090549,10500,0,199.9987384,0,0,0,90.00000001 +389.65,50.30085681,-2.564062524,10500,0,199.9989614,0,0,0,90.00000001 +389.66,50.30085681,-2.564034499,10500,0,199.9998535,0,0,0,90.00000001 +389.67,50.30085681,-2.564006474,10500,0,200.0009685,0,0,0,90.00000001 +389.68,50.30085681,-2.563978448,10500,0,200.0009685,0,0,0,90.00000001 +389.69,50.30085681,-2.563950423,10500,0,199.9998535,0,0,0,90.00000001 +389.7,50.30085681,-2.563922398,10500,0,199.9989614,0,0,0,90.00000001 +389.71,50.30085681,-2.563894373,10500,0,199.9989614,0,0,0,90.00000001 +389.72,50.30085681,-2.563866348,10500,0,199.9998535,0,0,0,90.00000001 +389.73,50.30085681,-2.563838323,10500,0,200.0009685,0,0,0,90.00000001 +389.74,50.30085681,-2.563810297,10500,0,200.0009685,0,0,0,90.00000001 +389.75,50.30085681,-2.563782272,10500,0,199.9998535,0,0,0,90.00000001 +389.76,50.30085681,-2.563754247,10500,0,199.9989614,0,0,0,90.00000001 +389.77,50.30085681,-2.563726222,10500,0,199.9989614,0,0,0,90.00000001 +389.78,50.30085681,-2.563698197,10500,0,199.9998535,0,0,0,90.00000001 +389.79,50.30085681,-2.563670172,10500,0,200.0009685,0,0,0,90.00000001 +389.8,50.30085681,-2.563642146,10500,0,200.0009685,0,0,0,90.00000001 +389.81,50.30085681,-2.563614121,10500,0,199.9998535,0,0,0,90.00000001 +389.82,50.30085681,-2.563586096,10500,0,199.9989614,0,0,0,90.00000001 +389.83,50.30085681,-2.563558071,10500,0,199.9989614,0,0,0,90.00000001 +389.84,50.30085681,-2.563530046,10500,0,199.9998535,0,0,0,90.00000001 +389.85,50.30085681,-2.563502021,10500,0,200.0009685,0,0,0,90.00000001 +389.86,50.30085681,-2.563473995,10500,0,200.0009685,0,0,0,90.00000001 +389.87,50.30085681,-2.56344597,10500,0,199.9998535,0,0,0,90.00000001 +389.88,50.30085681,-2.563417945,10500,0,199.9991844,0,0,0,90.00000001 +389.89,50.30085681,-2.56338992,10500,0,199.9998535,0,0,0,90.00000001 +389.9,50.30085681,-2.563361895,10500,0,200.0009685,0,0,0,90.00000001 +389.91,50.30085681,-2.563333869,10500,0,200.0009685,0,0,0,90.00000001 +389.92,50.30085681,-2.563305844,10500,0,199.9998535,0,0,0,90.00000001 +389.93,50.30085681,-2.563277819,10500,0,199.9991844,0,0,0,90.00000001 +389.94,50.30085681,-2.563249794,10500,0,199.9998535,0,0,0,90.00000001 +389.95,50.30085681,-2.563221769,10500,0,200.0009685,0,0,0,90.00000001 +389.96,50.30085681,-2.563193743,10500,0,200.0009685,0,0,0,90.00000001 +389.97,50.30085681,-2.563165718,10500,0,199.9998535,0,0,0,90.00000001 +389.98,50.30085681,-2.563137693,10500,0,199.9991844,0,0,0,90.00000001 +389.99,50.30085681,-2.563109668,10500,0,199.9998535,0,0,0,90.00000001 +390,50.30085681,-2.563081643,10500,0,200.0009685,0,0,0,90.00000001 +390.01,50.30085681,-2.563053617,10500,0,200.0009685,0,0,0,90.00000001 +390.02,50.30085681,-2.563025592,10500,0,199.9998535,0,0,0,90.00000001 +390.03,50.30085681,-2.562997567,10500,0,199.9991844,0,0,0,90.00000001 +390.04,50.30085681,-2.562969542,10500,0,199.9998535,0,0,0,90.00000001 +390.05,50.30085681,-2.562941517,10500,0,200.0009685,0,0,0,90.00000001 +390.06,50.30085681,-2.562913491,10500,0,200.0009685,0,0,0,90.00000001 +390.07,50.30085681,-2.562885466,10500,0,199.9998535,0,0,0,90.00000001 +390.08,50.30085681,-2.562857441,10500,0,199.9991844,0,0,0,90.00000001 +390.09,50.30085681,-2.562829416,10500,0,199.9998535,0,0,0,90.00000001 +390.1,50.30085681,-2.562801391,10500,0,200.0009685,0,0,0,90.00000001 +390.11,50.30085681,-2.562773365,10500,0,200.0009685,0,0,0,90.00000001 +390.12,50.30085681,-2.56274534,10500,0,199.9998535,0,0,0,90.00000001 +390.13,50.30085681,-2.562717315,10500,0,199.9989614,0,0,0,90.00000001 +390.14,50.30085681,-2.56268929,10500,0,199.9989614,0,0,0,90.00000001 +390.15,50.30085681,-2.562661265,10500,0,199.9998535,0,0,0,90.00000001 +390.16,50.30085681,-2.56263324,10500,0,200.0009685,0,0,0,90.00000001 +390.17,50.30085681,-2.562605214,10500,0,200.0009685,0,0,0,90.00000001 +390.18,50.30085681,-2.562577189,10500,0,199.9998535,0,0,0,90.00000001 +390.19,50.30085681,-2.562549164,10500,0,199.9989614,0,0,0,90.00000001 +390.2,50.30085681,-2.562521139,10500,0,199.9989614,0,0,0,90.00000001 +390.21,50.30085681,-2.562493114,10500,0,199.9998535,0,0,0,90.00000001 +390.22,50.30085681,-2.562465089,10500,0,200.0009685,0,0,0,90.00000001 +390.23,50.30085681,-2.562437063,10500,0,200.0009685,0,0,0,90.00000001 +390.24,50.30085681,-2.562409038,10500,0,199.9998535,0,0,0,90.00000001 +390.25,50.30085681,-2.562381013,10500,0,199.9989614,0,0,0,90.00000001 +390.26,50.30085681,-2.562352988,10500,0,199.9987384,0,0,0,90.00000001 +390.27,50.30085681,-2.562324963,10500,0,199.9989614,0,0,0,90.00000001 +390.28,50.30085681,-2.562296938,10500,0,199.9998535,0,0,0,90.00000001 +390.29,50.30085681,-2.562268913,10500,0,200.0009685,0,0,0,90.00000001 +390.3,50.30085681,-2.562240887,10500,0,200.0009685,0,0,0,90.00000001 +390.31,50.30085681,-2.562212862,10500,0,199.9998535,0,0,0,90.00000001 +390.32,50.30085681,-2.562184837,10500,0,199.9989614,0,0,0,90.00000001 +390.33,50.30085681,-2.562156812,10500,0,199.9989614,0,0,0,90.00000001 +390.34,50.30085681,-2.562128787,10500,0,199.9998535,0,0,0,90.00000001 +390.35,50.30085681,-2.562100762,10500,0,200.0009685,0,0,0,90.00000001 +390.36,50.30085681,-2.562072736,10500,0,200.0009685,0,0,0,90.00000001 +390.37,50.30085681,-2.562044711,10500,0,199.9998535,0,0,0,90.00000001 +390.38,50.30085681,-2.562016686,10500,0,199.9989614,0,0,0,90.00000001 +390.39,50.30085681,-2.561988661,10500,0,199.9989614,0,0,0,90.00000001 +390.4,50.30085681,-2.561960636,10500,0,199.9998535,0,0,0,90.00000001 +390.41,50.30085681,-2.561932611,10500,0,200.0009685,0,0,0,90.00000001 +390.42,50.30085681,-2.561904585,10500,0,200.0009685,0,0,0,90.00000001 +390.43,50.30085681,-2.56187656,10500,0,199.9998535,0,0,0,90.00000001 +390.44,50.30085681,-2.561848535,10500,0,199.9989614,0,0,0,90.00000001 +390.45,50.30085681,-2.56182051,10500,0,199.9989614,0,0,0,90.00000001 +390.46,50.30085681,-2.561792485,10500,0,199.9998535,0,0,0,90.00000001 +390.47,50.30085681,-2.56176446,10500,0,200.0009685,0,0,0,90.00000001 +390.48,50.30085681,-2.561736434,10500,0,200.0009685,0,0,0,90.00000001 +390.49,50.30085681,-2.561708409,10500,0,199.9998535,0,0,0,90.00000001 +390.5,50.30085681,-2.561680384,10500,0,199.9991844,0,0,0,90.00000001 +390.51,50.30085681,-2.561652359,10500,0,199.9998535,0,0,0,90.00000001 +390.52,50.30085681,-2.561624334,10500,0,200.0009685,0,0,0,90.00000001 +390.53,50.30085681,-2.561596308,10500,0,200.0009685,0,0,0,90.00000001 +390.54,50.30085681,-2.561568283,10500,0,199.9998535,0,0,0,90.00000001 +390.55,50.30085681,-2.561540258,10500,0,199.9991844,0,0,0,90.00000001 +390.56,50.30085681,-2.561512233,10500,0,199.9998535,0,0,0,90.00000001 +390.57,50.30085681,-2.561484208,10500,0,200.0009685,0,0,0,90.00000001 +390.58,50.30085681,-2.561456182,10500,0,200.0009685,0,0,0,90.00000001 +390.59,50.30085681,-2.561428157,10500,0,199.9998535,0,0,0,90.00000001 +390.6,50.30085681,-2.561400132,10500,0,199.9991844,0,0,0,90.00000001 +390.61,50.30085681,-2.561372107,10500,0,199.9998535,0,0,0,90.00000001 +390.62,50.30085681,-2.561344082,10500,0,200.0009685,0,0,0,90.00000001 +390.63,50.30085681,-2.561316056,10500,0,200.0009685,0,0,0,90.00000001 +390.64,50.30085681,-2.561288031,10500,0,199.9998535,0,0,0,90.00000001 +390.65,50.30085681,-2.561260006,10500,0,199.9991844,0,0,0,90.00000001 +390.66,50.30085681,-2.561231981,10500,0,199.9998535,0,0,0,90.00000001 +390.67,50.30085681,-2.561203956,10500,0,200.0009685,0,0,0,90.00000001 +390.68,50.30085681,-2.56117593,10500,0,200.0009685,0,0,0,90.00000001 +390.69,50.30085681,-2.561147905,10500,0,199.9998535,0,0,0,90.00000001 +390.7,50.30085681,-2.56111988,10500,0,199.9989614,0,0,0,90.00000001 +390.71,50.30085681,-2.561091855,10500,0,199.9989614,0,0,0,90.00000001 +390.72,50.30085681,-2.56106383,10500,0,199.9998535,0,0,0,90.00000001 +390.73,50.30085681,-2.561035805,10500,0,200.0009685,0,0,0,90.00000001 +390.74,50.30085681,-2.561007779,10500,0,200.0009685,0,0,0,90.00000001 +390.75,50.30085681,-2.560979754,10500,0,199.9998535,0,0,0,90.00000001 +390.76,50.30085681,-2.560951729,10500,0,199.9991844,0,0,0,90.00000001 +390.77,50.30085681,-2.560923704,10500,0,199.9998535,0,0,0,90.00000001 +390.78,50.30085681,-2.560895679,10500,0,200.0009685,0,0,0,90.00000001 +390.79,50.30085681,-2.560867653,10500,0,200.0009685,0,0,0,90.00000001 +390.8,50.30085681,-2.560839628,10500,0,199.9998535,0,0,0,90.00000001 +390.81,50.30085681,-2.560811603,10500,0,199.9989614,0,0,0,90.00000001 +390.82,50.30085681,-2.560783578,10500,0,199.9987384,0,0,0,90.00000001 +390.83,50.30085681,-2.560755553,10500,0,199.9989614,0,0,0,90.00000001 +390.84,50.30085681,-2.560727528,10500,0,199.9998535,0,0,0,90.00000001 +390.85,50.30085681,-2.560699503,10500,0,200.0009685,0,0,0,90.00000001 +390.86,50.30085681,-2.560671477,10500,0,200.0009685,0,0,0,90.00000001 +390.87,50.30085681,-2.560643452,10500,0,199.9998535,0,0,0,90.00000001 +390.88,50.30085681,-2.560615427,10500,0,199.9989614,0,0,0,90.00000001 +390.89,50.30085681,-2.560587402,10500,0,199.9989614,0,0,0,90.00000001 +390.9,50.30085681,-2.560559377,10500,0,199.9998535,0,0,0,90.00000001 +390.91,50.30085681,-2.560531352,10500,0,200.0009685,0,0,0,90.00000001 +390.92,50.30085681,-2.560503326,10500,0,200.0009685,0,0,0,90.00000001 +390.93,50.30085681,-2.560475301,10500,0,199.9998535,0,0,0,90.00000001 +390.94,50.30085681,-2.560447276,10500,0,199.9989614,0,0,0,90.00000001 +390.95,50.30085681,-2.560419251,10500,0,199.9989614,0,0,0,90.00000001 +390.96,50.30085681,-2.560391226,10500,0,199.9998535,0,0,0,90.00000001 +390.97,50.30085681,-2.560363201,10500,0,200.0009685,0,0,0,90.00000001 +390.98,50.30085681,-2.560335175,10500,0,200.0009685,0,0,0,90.00000001 +390.99,50.30085681,-2.56030715,10500,0,199.9998535,0,0,0,90.00000001 +391,50.30085681,-2.560279125,10500,0,199.9989614,0,0,0,90.00000001 +391.01,50.30085681,-2.5602511,10500,0,199.9989614,0,0,0,90.00000001 +391.02,50.30085681,-2.560223075,10500,0,199.9998535,0,0,0,90.00000001 +391.03,50.30085681,-2.56019505,10500,0,200.0009685,0,0,0,90.00000001 +391.04,50.30085681,-2.560167024,10500,0,200.0009685,0,0,0,90.00000001 +391.05,50.30085681,-2.560138999,10500,0,199.9998535,0,0,0,90.00000001 +391.06,50.30085681,-2.560110974,10500,0,199.9989614,0,0,0,90.00000001 +391.07,50.30085681,-2.560082949,10500,0,199.9987384,0,0,0,90.00000001 +391.08,50.30085681,-2.560054924,10500,0,199.9989614,0,0,0,90.00000001 +391.09,50.30085681,-2.560026899,10500,0,199.9998535,0,0,0,90.00000001 +391.1,50.30085681,-2.559998874,10500,0,200.0009685,0,0,0,90.00000001 +391.11,50.30085681,-2.559970848,10500,0,200.0009685,0,0,0,90.00000001 +391.12,50.30085681,-2.559942823,10500,0,199.9998535,0,0,0,90.00000001 +391.13,50.30085681,-2.559914798,10500,0,199.9991844,0,0,0,90.00000001 +391.14,50.30085681,-2.559886773,10500,0,199.9998535,0,0,0,90.00000001 +391.15,50.30085681,-2.559858748,10500,0,200.0009685,0,0,0,90.00000001 +391.16,50.30085681,-2.559830722,10500,0,200.0009685,0,0,0,90.00000001 +391.17,50.30085681,-2.559802697,10500,0,199.9998535,0,0,0,90.00000001 +391.18,50.30085681,-2.559774672,10500,0,199.9991844,0,0,0,90.00000001 +391.19,50.30085681,-2.559746647,10500,0,199.9998535,0,0,0,90.00000001 +391.2,50.30085681,-2.559718622,10500,0,200.0009685,0,0,0,90.00000001 +391.21,50.30085681,-2.559690596,10500,0,200.0009685,0,0,0,90.00000001 +391.22,50.30085681,-2.559662571,10500,0,199.9998535,0,0,0,90.00000001 +391.23,50.30085681,-2.559634546,10500,0,199.9991844,0,0,0,90.00000001 +391.24,50.30085681,-2.559606521,10500,0,199.9998535,0,0,0,90.00000001 +391.25,50.30085681,-2.559578496,10500,0,200.0009685,0,0,0,90.00000001 +391.26,50.30085681,-2.55955047,10500,0,200.0009685,0,0,0,90.00000001 +391.27,50.30085681,-2.559522445,10500,0,199.9998535,0,0,0,90.00000001 +391.28,50.30085681,-2.55949442,10500,0,199.9991844,0,0,0,90.00000001 +391.29,50.30085681,-2.559466395,10500,0,199.9998535,0,0,0,90.00000001 +391.3,50.30085681,-2.55943837,10500,0,200.0009685,0,0,0,90.00000001 +391.31,50.30085681,-2.559410344,10500,0,200.0009685,0,0,0,90.00000001 +391.32,50.30085681,-2.559382319,10500,0,199.9998535,0,0,0,90.00000001 +391.33,50.30085681,-2.559354294,10500,0,199.9991844,0,0,0,90.00000001 +391.34,50.30085681,-2.559326269,10500,0,199.9998535,0,0,0,90.00000001 +391.35,50.30085681,-2.559298244,10500,0,200.0009685,0,0,0,90.00000001 +391.36,50.30085681,-2.559270218,10500,0,200.0009685,0,0,0,90.00000001 +391.37,50.30085681,-2.559242193,10500,0,199.9998535,0,0,0,90.00000001 +391.38,50.30085681,-2.559214168,10500,0,199.9989614,0,0,0,90.00000001 +391.39,50.30085681,-2.559186143,10500,0,199.9989614,0,0,0,90.00000001 +391.4,50.30085681,-2.559158118,10500,0,199.9998535,0,0,0,90.00000001 +391.41,50.30085681,-2.559130093,10500,0,200.0009685,0,0,0,90.00000001 +391.42,50.30085681,-2.559102067,10500,0,200.0009685,0,0,0,90.00000001 +391.43,50.30085681,-2.559074042,10500,0,199.9998535,0,0,0,90.00000001 +391.44,50.30085681,-2.559046017,10500,0,199.9989614,0,0,0,90.00000001 +391.45,50.30085681,-2.559017992,10500,0,199.9989614,0,0,0,90.00000001 +391.46,50.30085681,-2.558989967,10500,0,199.9998535,0,0,0,90.00000001 +391.47,50.30085681,-2.558961942,10500,0,200.0009685,0,0,0,90.00000001 +391.48,50.30085681,-2.558933916,10500,0,200.0009685,0,0,0,90.00000001 +391.49,50.30085681,-2.558905891,10500,0,199.9998535,0,0,0,90.00000001 +391.5,50.30085681,-2.558877866,10500,0,199.9989614,0,0,0,90.00000001 +391.51,50.30085681,-2.558849841,10500,0,199.9989614,0,0,0,90.00000001 +391.52,50.30085681,-2.558821816,10500,0,199.9998535,0,0,0,90.00000001 +391.53,50.30085681,-2.558793791,10500,0,200.0009685,0,0,0,90.00000001 +391.54,50.30085681,-2.558765765,10500,0,200.0009685,0,0,0,90.00000001 +391.55,50.30085681,-2.55873774,10500,0,199.9998535,0,0,0,90.00000001 +391.56,50.30085681,-2.558709715,10500,0,199.9989614,0,0,0,90.00000001 +391.57,50.30085681,-2.55868169,10500,0,199.9989614,0,0,0,90.00000001 +391.58,50.30085681,-2.558653665,10500,0,199.9998535,0,0,0,90.00000001 +391.59,50.30085681,-2.55862564,10500,0,200.0009685,0,0,0,90.00000001 +391.6,50.30085681,-2.558597614,10500,0,200.0009685,0,0,0,90.00000001 +391.61,50.30085681,-2.558569589,10500,0,199.9998535,0,0,0,90.00000001 +391.62,50.30085681,-2.558541564,10500,0,199.9989614,0,0,0,90.00000001 +391.63,50.30085681,-2.558513539,10500,0,199.9989614,0,0,0,90.00000001 +391.64,50.30085681,-2.558485514,10500,0,199.9998535,0,0,0,90.00000001 +391.65,50.30085681,-2.558457489,10500,0,200.0009685,0,0,0,90.00000001 +391.66,50.30085681,-2.558429463,10500,0,200.0009685,0,0,0,90.00000001 +391.67,50.30085681,-2.558401438,10500,0,199.9998535,0,0,0,90.00000001 +391.68,50.30085681,-2.558373413,10500,0,199.9989614,0,0,0,90.00000001 +391.69,50.30085681,-2.558345388,10500,0,199.9987384,0,0,0,90.00000001 +391.7,50.30085681,-2.558317363,10500,0,199.9989614,0,0,0,90.00000001 +391.71,50.30085681,-2.558289338,10500,0,199.9998535,0,0,0,90.00000001 +391.72,50.30085681,-2.558261313,10500,0,200.0009685,0,0,0,90.00000001 +391.73,50.30085681,-2.558233287,10500,0,200.0009685,0,0,0,90.00000001 +391.74,50.30085681,-2.558205262,10500,0,199.9998535,0,0,0,90.00000001 +391.75,50.30085681,-2.558177237,10500,0,199.9991844,0,0,0,90.00000001 +391.76,50.30085681,-2.558149212,10500,0,199.9998535,0,0,0,90.00000001 +391.77,50.30085681,-2.558121187,10500,0,200.0009685,0,0,0,90.00000001 +391.78,50.30085681,-2.558093161,10500,0,200.0009685,0,0,0,90.00000001 +391.79,50.30085681,-2.558065136,10500,0,199.9998535,0,0,0,90.00000001 +391.8,50.30085681,-2.558037111,10500,0,199.9991844,0,0,0,90.00000001 +391.81,50.30085681,-2.558009086,10500,0,199.9998535,0,0,0,90.00000001 +391.82,50.30085681,-2.557981061,10500,0,200.0009685,0,0,0,90.00000001 +391.83,50.30085681,-2.557953035,10500,0,200.0009685,0,0,0,90.00000001 +391.84,50.30085681,-2.55792501,10500,0,199.9998535,0,0,0,90.00000001 +391.85,50.30085681,-2.557896985,10500,0,199.9991844,0,0,0,90.00000001 +391.86,50.30085681,-2.55786896,10500,0,199.9998535,0,0,0,90.00000001 +391.87,50.30085681,-2.557840935,10500,0,200.0009685,0,0,0,90.00000001 +391.88,50.30085681,-2.557812909,10500,0,200.0009685,0,0,0,90.00000001 +391.89,50.30085681,-2.557784884,10500,0,199.9998535,0,0,0,90.00000001 +391.9,50.30085681,-2.557756859,10500,0,199.9991844,0,0,0,90.00000001 +391.91,50.30085681,-2.557728834,10500,0,199.9998535,0,0,0,90.00000001 +391.92,50.30085681,-2.557700809,10500,0,200.0009685,0,0,0,90.00000001 +391.93,50.30085681,-2.557672783,10500,0,200.0009685,0,0,0,90.00000001 +391.94,50.30085681,-2.557644758,10500,0,199.9998535,0,0,0,90.00000001 +391.95,50.30085681,-2.557616733,10500,0,199.9991844,0,0,0,90.00000001 +391.96,50.30085681,-2.557588708,10500,0,199.9998535,0,0,0,90.00000001 +391.97,50.30085681,-2.557560683,10500,0,200.0009685,0,0,0,90.00000001 +391.98,50.30085681,-2.557532657,10500,0,200.0009685,0,0,0,90.00000001 +391.99,50.30085681,-2.557504632,10500,0,199.9998535,0,0,0,90.00000001 +392,50.30085681,-2.557476607,10500,0,199.9989614,0,0,0,90.00000001 +392.01,50.30085681,-2.557448582,10500,0,199.9989614,0,0,0,90.00000001 +392.02,50.30085681,-2.557420557,10500,0,199.9998535,0,0,0,90.00000001 +392.03,50.30085681,-2.557392532,10500,0,200.0009685,0,0,0,90.00000001 +392.04,50.30085681,-2.557364506,10500,0,200.0009685,0,0,0,90.00000001 +392.05,50.30085681,-2.557336481,10500,0,199.9998535,0,0,0,90.00000001 +392.06,50.30085681,-2.557308456,10500,0,199.9989614,0,0,0,90.00000001 +392.07,50.30085681,-2.557280431,10500,0,199.9989614,0,0,0,90.00000001 +392.08,50.30085681,-2.557252406,10500,0,199.9998535,0,0,0,90.00000001 +392.09,50.30085681,-2.557224381,10500,0,200.0009685,0,0,0,90.00000001 +392.1,50.30085681,-2.557196355,10500,0,200.0009685,0,0,0,90.00000001 +392.11,50.30085681,-2.55716833,10500,0,199.9998535,0,0,0,90.00000001 +392.12,50.30085681,-2.557140305,10500,0,199.9989614,0,0,0,90.00000001 +392.13,50.30085681,-2.55711228,10500,0,199.9989614,0,0,0,90.00000001 +392.14,50.30085681,-2.557084255,10500,0,199.9998535,0,0,0,90.00000001 +392.15,50.30085681,-2.55705623,10500,0,200.0009685,0,0,0,90.00000001 +392.16,50.30085681,-2.557028204,10500,0,200.0009685,0,0,0,90.00000001 +392.17,50.30085681,-2.557000179,10500,0,199.9998535,0,0,0,90.00000001 +392.18,50.30085681,-2.556972154,10500,0,199.9989614,0,0,0,90.00000001 +392.19,50.30085681,-2.556944129,10500,0,199.9989614,0,0,0,90.00000001 +392.2,50.30085681,-2.556916104,10500,0,199.9998535,0,0,0,90.00000001 +392.21,50.30085681,-2.556888079,10500,0,200.0009685,0,0,0,90.00000001 +392.22,50.30085681,-2.556860053,10500,0,200.0009685,0,0,0,90.00000001 +392.23,50.30085681,-2.556832028,10500,0,199.9998535,0,0,0,90.00000001 +392.24,50.30085681,-2.556804003,10500,0,199.9989614,0,0,0,90.00000001 +392.25,50.30085681,-2.556775978,10500,0,199.9987384,0,0,0,90.00000001 +392.26,50.30085681,-2.556747953,10500,0,199.9989614,0,0,0,90.00000001 +392.27,50.30085681,-2.556719928,10500,0,199.9998535,0,0,0,90.00000001 +392.28,50.30085681,-2.556691903,10500,0,200.0009685,0,0,0,90.00000001 +392.29,50.30085681,-2.556663877,10500,0,200.0009685,0,0,0,90.00000001 +392.3,50.30085681,-2.556635852,10500,0,199.9998535,0,0,0,90.00000001 +392.31,50.30085681,-2.556607827,10500,0,199.9989614,0,0,0,90.00000001 +392.32,50.30085681,-2.556579802,10500,0,199.9989614,0,0,0,90.00000001 +392.33,50.30085681,-2.556551777,10500,0,199.9998535,0,0,0,90.00000001 +392.34,50.30085681,-2.556523752,10500,0,200.0009685,0,0,0,90.00000001 +392.35,50.30085681,-2.556495726,10500,0,200.0009685,0,0,0,90.00000001 +392.36,50.30085681,-2.556467701,10500,0,199.9998535,0,0,0,90.00000001 +392.37,50.30085681,-2.556439676,10500,0,199.9991844,0,0,0,90.00000001 +392.38,50.30085681,-2.556411651,10500,0,199.9998535,0,0,0,90.00000001 +392.39,50.30085681,-2.556383626,10500,0,200.0009685,0,0,0,90.00000001 +392.4,50.30085681,-2.5563556,10500,0,200.0009685,0,0,0,90.00000001 +392.41,50.30085681,-2.556327575,10500,0,199.9998535,0,0,0,90.00000001 +392.42,50.30085681,-2.55629955,10500,0,199.9991844,0,0,0,90.00000001 +392.43,50.30085681,-2.556271525,10500,0,199.9998535,0,0,0,90.00000001 +392.44,50.30085681,-2.5562435,10500,0,200.0009685,0,0,0,90.00000001 +392.45,50.30085681,-2.556215474,10500,0,200.0009685,0,0,0,90.00000001 +392.46,50.30085681,-2.556187449,10500,0,199.9998535,0,0,0,90.00000001 +392.47,50.30085681,-2.556159424,10500,0,199.9991844,0,0,0,90.00000001 +392.48,50.30085681,-2.556131399,10500,0,199.9998535,0,0,0,90.00000001 +392.49,50.30085681,-2.556103374,10500,0,200.0009685,0,0,0,90.00000001 +392.5,50.30085681,-2.556075348,10500,0,200.0009685,0,0,0,90.00000001 +392.51,50.30085681,-2.556047323,10500,0,199.9998535,0,0,0,90.00000001 +392.52,50.30085681,-2.556019298,10500,0,199.9991844,0,0,0,90.00000001 +392.53,50.30085681,-2.555991273,10500,0,199.9998535,0,0,0,90.00000001 +392.54,50.30085681,-2.555963248,10500,0,200.0009685,0,0,0,90.00000001 +392.55,50.30085681,-2.555935222,10500,0,200.0009685,0,0,0,90.00000001 +392.56,50.30085681,-2.555907197,10500,0,199.9998535,0,0,0,90.00000001 +392.57,50.30085681,-2.555879172,10500,0,199.9991844,0,0,0,90.00000001 +392.58,50.30085681,-2.555851147,10500,0,199.9998535,0,0,0,90.00000001 +392.59,50.30085681,-2.555823122,10500,0,200.0009685,0,0,0,90.00000001 +392.6,50.30085681,-2.555795096,10500,0,200.0009685,0,0,0,90.00000001 +392.61,50.30085681,-2.555767071,10500,0,199.9998535,0,0,0,90.00000001 +392.62,50.30085681,-2.555739046,10500,0,199.9989614,0,0,0,90.00000001 +392.63,50.30085681,-2.555711021,10500,0,199.9989614,0,0,0,90.00000001 +392.64,50.30085681,-2.555682996,10500,0,199.9998535,0,0,0,90.00000001 +392.65,50.30085681,-2.555654971,10500,0,200.0009685,0,0,0,90.00000001 +392.66,50.30085681,-2.555626945,10500,0,200.0009685,0,0,0,90.00000001 +392.67,50.30085681,-2.55559892,10500,0,199.9998535,0,0,0,90.00000001 +392.68,50.30085681,-2.555570895,10500,0,199.9989614,0,0,0,90.00000001 +392.69,50.30085681,-2.55554287,10500,0,199.9989614,0,0,0,90.00000001 +392.7,50.30085681,-2.555514845,10500,0,199.9998535,0,0,0,90.00000001 +392.71,50.30085681,-2.55548682,10500,0,200.0009685,0,0,0,90.00000001 +392.72,50.30085681,-2.555458794,10500,0,200.0009685,0,0,0,90.00000001 +392.73,50.30085681,-2.555430769,10500,0,199.9998535,0,0,0,90.00000001 +392.74,50.30085681,-2.555402744,10500,0,199.9989614,0,0,0,90.00000001 +392.75,50.30085681,-2.555374719,10500,0,199.9989614,0,0,0,90.00000001 +392.76,50.30085681,-2.555346694,10500,0,199.9998535,0,0,0,90.00000001 +392.77,50.30085681,-2.555318669,10500,0,200.0009685,0,0,0,90.00000001 +392.78,50.30085681,-2.555290643,10500,0,200.0009685,0,0,0,90.00000001 +392.79,50.30085681,-2.555262618,10500,0,199.9998535,0,0,0,90.00000001 +392.8,50.30085681,-2.555234593,10500,0,199.9989614,0,0,0,90.00000001 +392.81,50.30085681,-2.555206568,10500,0,199.9987384,0,0,0,90.00000001 +392.82,50.30085681,-2.555178543,10500,0,199.9989614,0,0,0,90.00000001 +392.83,50.30085681,-2.555150518,10500,0,199.9998535,0,0,0,90.00000001 +392.84,50.30085681,-2.555122493,10500,0,200.0009685,0,0,0,90.00000001 +392.85,50.30085681,-2.555094467,10500,0,200.0009685,0,0,0,90.00000001 +392.86,50.30085681,-2.555066442,10500,0,199.9998535,0,0,0,90.00000001 +392.87,50.30085681,-2.555038417,10500,0,199.9989614,0,0,0,90.00000001 +392.88,50.30085681,-2.555010392,10500,0,199.9989614,0,0,0,90.00000001 +392.89,50.30085681,-2.554982367,10500,0,199.9998535,0,0,0,90.00000001 +392.9,50.30085681,-2.554954342,10500,0,200.0009685,0,0,0,90.00000001 +392.91,50.30085681,-2.554926316,10500,0,200.0009685,0,0,0,90.00000001 +392.92,50.30085681,-2.554898291,10500,0,199.9998535,0,0,0,90.00000001 +392.93,50.30085681,-2.554870266,10500,0,199.9989614,0,0,0,90.00000001 +392.94,50.30085681,-2.554842241,10500,0,199.9989614,0,0,0,90.00000001 +392.95,50.30085681,-2.554814216,10500,0,199.9998535,0,0,0,90.00000001 +392.96,50.30085681,-2.554786191,10500,0,200.0009685,0,0,0,90.00000001 +392.97,50.30085681,-2.554758165,10500,0,200.0009685,0,0,0,90.00000001 +392.98,50.30085681,-2.55473014,10500,0,199.9998535,0,0,0,90.00000001 +392.99,50.30085681,-2.554702115,10500,0,199.9991844,0,0,0,90.00000001 +393,50.30085681,-2.55467409,10500,0,199.9998535,0,0,0,90.00000001 +393.01,50.30085681,-2.554646065,10500,0,200.0009685,0,0,0,90.00000001 +393.02,50.30085681,-2.554618039,10500,0,200.0009685,0,0,0,90.00000001 +393.03,50.30085681,-2.554590014,10500,0,199.9998535,0,0,0,90.00000001 +393.04,50.30085681,-2.554561989,10500,0,199.9991844,0,0,0,90.00000001 +393.05,50.30085681,-2.554533964,10500,0,199.9998535,0,0,0,90.00000001 +393.06,50.30085681,-2.554505939,10500,0,200.0009685,0,0,0,90.00000001 +393.07,50.30085681,-2.554477913,10500,0,200.0009685,0,0,0,90.00000001 +393.08,50.30085681,-2.554449888,10500,0,199.9998535,0,0,0,90.00000001 +393.09,50.30085681,-2.554421863,10500,0,199.9989614,0,0,0,90.00000001 +393.1,50.30085681,-2.554393838,10500,0,199.9989614,0,0,0,90.00000001 +393.11,50.30085681,-2.554365813,10500,0,199.9998535,0,0,0,90.00000001 +393.12,50.30085681,-2.554337788,10500,0,200.0009685,0,0,0,90.00000001 +393.13,50.30085681,-2.554309762,10500,0,200.0009685,0,0,0,90.00000001 +393.14,50.30085681,-2.554281737,10500,0,199.9998535,0,0,0,90.00000001 +393.15,50.30085681,-2.554253712,10500,0,199.9991844,0,0,0,90.00000001 +393.16,50.30085681,-2.554225687,10500,0,199.9998535,0,0,0,90.00000001 +393.17,50.30085681,-2.554197662,10500,0,200.0009685,0,0,0,90.00000001 +393.18,50.30085681,-2.554169636,10500,0,200.0009685,0,0,0,90.00000001 +393.19,50.30085681,-2.554141611,10500,0,199.9998535,0,0,0,90.00000001 +393.2,50.30085681,-2.554113586,10500,0,199.9991844,0,0,0,90.00000001 +393.21,50.30085681,-2.554085561,10500,0,199.9998535,0,0,0,90.00000001 +393.22,50.30085681,-2.554057536,10500,0,200.0009685,0,0,0,90.00000001 +393.23,50.30085681,-2.55402951,10500,0,200.0009685,0,0,0,90.00000001 +393.24,50.30085681,-2.554001485,10500,0,199.9998535,0,0,0,90.00000001 +393.25,50.30085681,-2.55397346,10500,0,199.9991844,0,0,0,90.00000001 +393.26,50.30085681,-2.553945435,10500,0,199.9998535,0,0,0,90.00000001 +393.27,50.30085681,-2.55391741,10500,0,200.0009685,0,0,0,90.00000001 +393.28,50.30085681,-2.553889384,10500,0,200.0009685,0,0,0,90.00000001 +393.29,50.30085681,-2.553861359,10500,0,199.9998535,0,0,0,90.00000001 +393.3,50.30085681,-2.553833334,10500,0,199.9989614,0,0,0,90.00000001 +393.31,50.30085681,-2.553805309,10500,0,199.9989614,0,0,0,90.00000001 +393.32,50.30085681,-2.553777284,10500,0,199.9998535,0,0,0,90.00000001 +393.33,50.30085681,-2.553749259,10500,0,200.0009685,0,0,0,90.00000001 +393.34,50.30085681,-2.553721233,10500,0,200.0009685,0,0,0,90.00000001 +393.35,50.30085681,-2.553693208,10500,0,199.9998535,0,0,0,90.00000001 +393.36,50.30085681,-2.553665183,10500,0,199.9989614,0,0,0,90.00000001 +393.37,50.30085681,-2.553637158,10500,0,199.9987384,0,0,0,90.00000001 +393.38,50.30085681,-2.553609133,10500,0,199.9989614,0,0,0,90.00000001 +393.39,50.30085681,-2.553581108,10500,0,199.9998535,0,0,0,90.00000001 +393.4,50.30085681,-2.553553083,10500,0,200.0009685,0,0,0,90.00000001 +393.41,50.30085681,-2.553525057,10500,0,200.0009685,0,0,0,90.00000001 +393.42,50.30085681,-2.553497032,10500,0,199.9998535,0,0,0,90.00000001 +393.43,50.30085681,-2.553469007,10500,0,199.9989614,0,0,0,90.00000001 +393.44,50.30085681,-2.553440982,10500,0,199.9989614,0,0,0,90.00000001 +393.45,50.30085681,-2.553412957,10500,0,199.9998535,0,0,0,90.00000001 +393.46,50.30085681,-2.553384932,10500,0,200.0009685,0,0,0,90.00000001 +393.47,50.30085681,-2.553356906,10500,0,200.0009685,0,0,0,90.00000001 +393.48,50.30085681,-2.553328881,10500,0,199.9998535,0,0,0,90.00000001 +393.49,50.30085681,-2.553300856,10500,0,199.9989614,0,0,0,90.00000001 +393.5,50.30085681,-2.553272831,10500,0,199.9989614,0,0,0,90.00000001 +393.51,50.30085681,-2.553244806,10500,0,199.9998535,0,0,0,90.00000001 +393.52,50.30085681,-2.553216781,10500,0,200.0009685,0,0,0,90.00000001 +393.53,50.30085681,-2.553188755,10500,0,200.0009685,0,0,0,90.00000001 +393.54,50.30085681,-2.55316073,10500,0,199.9998535,0,0,0,90.00000001 +393.55,50.30085681,-2.553132705,10500,0,199.9989614,0,0,0,90.00000001 +393.56,50.30085681,-2.55310468,10500,0,199.9989614,0,0,0,90.00000001 +393.57,50.30085681,-2.553076655,10500,0,199.9998535,0,0,0,90.00000001 +393.58,50.30085681,-2.55304863,10500,0,200.0009685,0,0,0,90.00000001 +393.59,50.30085681,-2.553020604,10500,0,200.0009685,0,0,0,90.00000001 +393.6,50.30085681,-2.552992579,10500,0,199.9998535,0,0,0,90.00000001 +393.61,50.30085681,-2.552964554,10500,0,199.9989614,0,0,0,90.00000001 +393.62,50.30085681,-2.552936529,10500,0,199.9989614,0,0,0,90.00000001 +393.63,50.30085681,-2.552908504,10500,0,199.9998535,0,0,0,90.00000001 +393.64,50.30085681,-2.552880479,10500,0,200.0009685,0,0,0,90.00000001 +393.65,50.30085681,-2.552852453,10500,0,200.0009685,0,0,0,90.00000001 +393.66,50.30085681,-2.552824428,10500,0,199.9998535,0,0,0,90.00000001 +393.67,50.30085681,-2.552796403,10500,0,199.9991844,0,0,0,90.00000001 +393.68,50.30085681,-2.552768378,10500,0,199.9998535,0,0,0,90.00000001 +393.69,50.30085681,-2.552740353,10500,0,200.0009685,0,0,0,90.00000001 +393.7,50.30085681,-2.552712327,10500,0,200.0009685,0,0,0,90.00000001 +393.71,50.30085681,-2.552684302,10500,0,199.9998535,0,0,0,90.00000001 +393.72,50.30085681,-2.552656277,10500,0,199.9991844,0,0,0,90.00000001 +393.73,50.30085681,-2.552628252,10500,0,199.9998535,0,0,0,90.00000001 +393.74,50.30085681,-2.552600227,10500,0,200.0009685,0,0,0,90.00000001 +393.75,50.30085681,-2.552572201,10500,0,200.0009685,0,0,0,90.00000001 +393.76,50.30085681,-2.552544176,10500,0,199.9998535,0,0,0,90.00000001 +393.77,50.30085681,-2.552516151,10500,0,199.9991844,0,0,0,90.00000001 +393.78,50.30085681,-2.552488126,10500,0,199.9998535,0,0,0,90.00000001 +393.79,50.30085681,-2.552460101,10500,0,200.0009685,0,0,0,90.00000001 +393.8,50.30085681,-2.552432075,10500,0,200.0009685,0,0,0,90.00000001 +393.81,50.30085681,-2.55240405,10500,0,199.9998535,0,0,0,90.00000001 +393.82,50.30085681,-2.552376025,10500,0,199.9991844,0,0,0,90.00000001 +393.83,50.30085681,-2.552348,10500,0,199.9998535,0,0,0,90.00000001 +393.84,50.30085681,-2.552319975,10500,0,200.0009685,0,0,0,90.00000001 +393.85,50.30085681,-2.552291949,10500,0,200.0009685,0,0,0,90.00000001 +393.86,50.30085681,-2.552263924,10500,0,199.9998535,0,0,0,90.00000001 +393.87,50.30085681,-2.552235899,10500,0,199.9991844,0,0,0,90.00000001 +393.88,50.30085681,-2.552207874,10500,0,199.9998535,0,0,0,90.00000001 +393.89,50.30085681,-2.552179849,10500,0,200.0009685,0,0,0,90.00000001 +393.9,50.30085681,-2.552151823,10500,0,200.0009685,0,0,0,90.00000001 +393.91,50.30085681,-2.552123798,10500,0,199.9998535,0,0,0,90.00000001 +393.92,50.30085681,-2.552095773,10500,0,199.9989614,0,0,0,90.00000001 +393.93,50.30085681,-2.552067748,10500,0,199.9987384,0,0,0,90.00000001 +393.94,50.30085681,-2.552039723,10500,0,199.9989614,0,0,0,90.00000001 +393.95,50.30085681,-2.552011698,10500,0,199.9998535,0,0,0,90.00000001 +393.96,50.30085681,-2.551983673,10500,0,200.0009685,0,0,0,90.00000001 +393.97,50.30085681,-2.551955647,10500,0,200.0009685,0,0,0,90.00000001 +393.98,50.30085681,-2.551927622,10500,0,199.9998535,0,0,0,90.00000001 +393.99,50.30085681,-2.551899597,10500,0,199.9989614,0,0,0,90.00000001 +394,50.30085681,-2.551871572,10500,0,199.9989614,0,0,0,90.00000001 +394.01,50.30085681,-2.551843547,10500,0,199.9998535,0,0,0,90.00000001 +394.02,50.30085681,-2.551815522,10500,0,200.0009685,0,0,0,90.00000001 +394.03,50.30085681,-2.551787496,10500,0,200.0009685,0,0,0,90.00000001 +394.04,50.30085681,-2.551759471,10500,0,199.9998535,0,0,0,90.00000001 +394.05,50.30085681,-2.551731446,10500,0,199.9989614,0,0,0,90.00000001 +394.06,50.30085681,-2.551703421,10500,0,199.9989614,0,0,0,90.00000001 +394.07,50.30085681,-2.551675396,10500,0,199.9998535,0,0,0,90.00000001 +394.08,50.30085681,-2.551647371,10500,0,200.0009685,0,0,0,90.00000001 +394.09,50.30085681,-2.551619345,10500,0,200.0009685,0,0,0,90.00000001 +394.1,50.30085681,-2.55159132,10500,0,199.9998535,0,0,0,90.00000001 +394.11,50.30085681,-2.551563295,10500,0,199.9989614,0,0,0,90.00000001 +394.12,50.30085681,-2.55153527,10500,0,199.9989614,0,0,0,90.00000001 +394.13,50.30085681,-2.551507245,10500,0,199.9998535,0,0,0,90.00000001 +394.14,50.30085681,-2.55147922,10500,0,200.0009685,0,0,0,90.00000001 +394.15,50.30085681,-2.551451194,10500,0,200.0009685,0,0,0,90.00000001 +394.16,50.30085681,-2.551423169,10500,0,199.9998535,0,0,0,90.00000001 +394.17,50.30085681,-2.551395144,10500,0,199.9989614,0,0,0,90.00000001 +394.18,50.30085681,-2.551367119,10500,0,199.9989614,0,0,0,90.00000001 +394.19,50.30085681,-2.551339094,10500,0,199.9998535,0,0,0,90.00000001 +394.2,50.30085681,-2.551311069,10500,0,200.0009685,0,0,0,90.00000001 +394.21,50.30085681,-2.551283043,10500,0,200.0009685,0,0,0,90.00000001 +394.22,50.30085681,-2.551255018,10500,0,199.9998535,0,0,0,90.00000001 +394.23,50.30085681,-2.551226993,10500,0,199.9989614,0,0,0,90.00000001 +394.24,50.30085681,-2.551198968,10500,0,199.9989614,0,0,0,90.00000001 +394.25,50.30085681,-2.551170943,10500,0,199.9998535,0,0,0,90.00000001 +394.26,50.30085681,-2.551142918,10500,0,200.0009685,0,0,0,90.00000001 +394.27,50.30085681,-2.551114892,10500,0,200.0009685,0,0,0,90.00000001 +394.28,50.30085681,-2.551086867,10500,0,199.9998535,0,0,0,90.00000001 +394.29,50.30085681,-2.551058842,10500,0,199.9991844,0,0,0,90.00000001 +394.3,50.30085681,-2.551030817,10500,0,199.9998535,0,0,0,90.00000001 +394.31,50.30085681,-2.551002792,10500,0,200.0009685,0,0,0,90.00000001 +394.32,50.30085681,-2.550974766,10500,0,200.0009685,0,0,0,90.00000001 +394.33,50.30085681,-2.550946741,10500,0,199.9998535,0,0,0,90.00000001 +394.34,50.30085681,-2.550918716,10500,0,199.9991844,0,0,0,90.00000001 +394.35,50.30085681,-2.550890691,10500,0,199.9998535,0,0,0,90.00000001 +394.36,50.30085681,-2.550862666,10500,0,200.0009685,0,0,0,90.00000001 +394.37,50.30085681,-2.55083464,10500,0,200.0009685,0,0,0,90.00000001 +394.38,50.30085681,-2.550806615,10500,0,199.9998535,0,0,0,90.00000001 +394.39,50.30085681,-2.55077859,10500,0,199.9991844,0,0,0,90.00000001 +394.4,50.30085681,-2.550750565,10500,0,199.9998535,0,0,0,90.00000001 +394.41,50.30085681,-2.55072254,10500,0,200.0009685,0,0,0,90.00000001 +394.42,50.30085681,-2.550694514,10500,0,200.0009685,0,0,0,90.00000001 +394.43,50.30085681,-2.550666489,10500,0,199.9998535,0,0,0,90.00000001 +394.44,50.30085681,-2.550638464,10500,0,199.9991844,0,0,0,90.00000001 +394.45,50.30085681,-2.550610439,10500,0,199.9998535,0,0,0,90.00000001 +394.46,50.30085681,-2.550582414,10500,0,200.0009685,0,0,0,90.00000001 +394.47,50.30085681,-2.550554388,10500,0,200.0009685,0,0,0,90.00000001 +394.48,50.30085681,-2.550526363,10500,0,199.9998535,0,0,0,90.00000001 +394.49,50.30085681,-2.550498338,10500,0,199.9991844,0,0,0,90.00000001 +394.5,50.30085681,-2.550470313,10500,0,199.9998535,0,0,0,90.00000001 +394.51,50.30085681,-2.550442288,10500,0,200.0009685,0,0,0,90.00000001 +394.52,50.30085681,-2.550414262,10500,0,200.0009685,0,0,0,90.00000001 +394.53,50.30085681,-2.550386237,10500,0,199.9998535,0,0,0,90.00000001 +394.54,50.30085681,-2.550358212,10500,0,199.9989614,0,0,0,90.00000001 +394.55,50.30085681,-2.550330187,10500,0,199.9987384,0,0,0,90.00000001 +394.56,50.30085681,-2.550302162,10500,0,199.9989614,0,0,0,90.00000001 +394.57,50.30085681,-2.550274137,10500,0,199.9998535,0,0,0,90.00000001 +394.58,50.30085681,-2.550246112,10500,0,200.0009685,0,0,0,90.00000001 +394.59,50.30085681,-2.550218086,10500,0,200.0009685,0,0,0,90.00000001 +394.6,50.30085681,-2.550190061,10500,0,199.9998535,0,0,0,90.00000001 +394.61,50.30085681,-2.550162036,10500,0,199.9989614,0,0,0,90.00000001 +394.62,50.30085681,-2.550134011,10500,0,199.9989614,0,0,0,90.00000001 +394.63,50.30085681,-2.550105986,10500,0,199.9998535,0,0,0,90.00000001 +394.64,50.30085681,-2.550077961,10500,0,200.0009685,0,0,0,90.00000001 +394.65,50.30085681,-2.550049935,10500,0,200.0009685,0,0,0,90.00000001 +394.66,50.30085681,-2.55002191,10500,0,199.9998535,0,0,0,90.00000001 +394.67,50.30085681,-2.549993885,10500,0,199.9989614,0,0,0,90.00000001 +394.68,50.30085681,-2.54996586,10500,0,199.9989614,0,0,0,90.00000001 +394.69,50.30085681,-2.549937835,10500,0,199.9998535,0,0,0,90.00000001 +394.7,50.30085681,-2.54990981,10500,0,200.0009685,0,0,0,90.00000001 +394.71,50.30085681,-2.549881784,10500,0,200.0009685,0,0,0,90.00000001 +394.72,50.30085681,-2.549853759,10500,0,199.9998535,0,0,0,90.00000001 +394.73,50.30085681,-2.549825734,10500,0,199.9989614,0,0,0,90.00000001 +394.74,50.30085681,-2.549797709,10500,0,199.9989614,0,0,0,90.00000001 +394.75,50.30085681,-2.549769684,10500,0,199.9998535,0,0,0,90.00000001 +394.76,50.30085681,-2.549741659,10500,0,200.0009685,0,0,0,90.00000001 +394.77,50.30085681,-2.549713633,10500,0,200.0009685,0,0,0,90.00000001 +394.78,50.30085681,-2.549685608,10500,0,199.9998535,0,0,0,90.00000001 +394.79,50.30085681,-2.549657583,10500,0,199.9989614,0,0,0,90.00000001 +394.8,50.30085681,-2.549629558,10500,0,199.9987384,0,0,0,90.00000001 +394.81,50.30085681,-2.549601533,10500,0,199.9989614,0,0,0,90.00000001 +394.82,50.30085681,-2.549573508,10500,0,199.9998535,0,0,0,90.00000001 +394.83,50.30085681,-2.549545483,10500,0,200.0009685,0,0,0,90.00000001 +394.84,50.30085681,-2.549517457,10500,0,200.0009685,0,0,0,90.00000001 +394.85,50.30085681,-2.549489432,10500,0,199.9998535,0,0,0,90.00000001 +394.86,50.30085681,-2.549461407,10500,0,199.9991844,0,0,0,90.00000001 +394.87,50.30085681,-2.549433382,10500,0,199.9998535,0,0,0,90.00000001 +394.88,50.30085681,-2.549405357,10500,0,200.0009685,0,0,0,90.00000001 +394.89,50.30085681,-2.549377331,10500,0,200.0009685,0,0,0,90.00000001 +394.9,50.30085681,-2.549349306,10500,0,199.9998535,0,0,0,90.00000001 +394.91,50.30085681,-2.549321281,10500,0,199.9991844,0,0,0,90.00000001 +394.92,50.30085681,-2.549293256,10500,0,199.9998535,0,0,0,90.00000001 +394.93,50.30085681,-2.549265231,10500,0,200.0009685,0,0,0,90.00000001 +394.94,50.30085681,-2.549237205,10500,0,200.0009685,0,0,0,90.00000001 +394.95,50.30085681,-2.54920918,10500,0,199.9998535,0,0,0,90.00000001 +394.96,50.30085681,-2.549181155,10500,0,199.9991844,0,0,0,90.00000001 +394.97,50.30085681,-2.54915313,10500,0,199.9998535,0,0,0,90.00000001 +394.98,50.30085681,-2.549125105,10500,0,200.0009685,0,0,0,90.00000001 +394.99,50.30085681,-2.549097079,10500,0,200.0009685,0,0,0,90.00000001 +395,50.30085681,-2.549069054,10500,0,199.9998535,0,0,0,90.00000001 +395.01,50.30085681,-2.549041029,10500,0,199.9991844,0,0,0,90.00000001 +395.02,50.30085681,-2.549013004,10500,0,199.9998535,0,0,0,90.00000001 +395.03,50.30085681,-2.548984979,10500,0,200.0009685,0,0,0,90.00000001 +395.04,50.30085681,-2.548956953,10500,0,200.0009685,0,0,0,90.00000001 +395.05,50.30085681,-2.548928928,10500,0,199.9998535,0,0,0,90.00000001 +395.06,50.30085681,-2.548900903,10500,0,199.9991844,0,0,0,90.00000001 +395.07,50.30085681,-2.548872878,10500,0,199.9998535,0,0,0,90.00000001 +395.08,50.30085681,-2.548844853,10500,0,200.0009685,0,0,0,90.00000001 +395.09,50.30085681,-2.548816827,10500,0,200.0009685,0,0,0,90.00000001 +395.1,50.30085681,-2.548788802,10500,0,199.9998535,0,0,0,90.00000001 +395.11,50.30085681,-2.548760777,10500,0,199.9989614,0,0,0,90.00000001 +395.12,50.30085681,-2.548732752,10500,0,199.9989614,0,0,0,90.00000001 +395.13,50.30085681,-2.548704727,10500,0,199.9998535,0,0,0,90.00000001 +395.14,50.30085681,-2.548676702,10500,0,200.0009685,0,0,0,90.00000001 +395.15,50.30085681,-2.548648676,10500,0,200.0009685,0,0,0,90.00000001 +395.16,50.30085681,-2.548620651,10500,0,199.9998535,0,0,0,90.00000001 +395.17,50.30085681,-2.548592626,10500,0,199.9989614,0,0,0,90.00000001 +395.18,50.30085681,-2.548564601,10500,0,199.9989614,0,0,0,90.00000001 +395.19,50.30085681,-2.548536576,10500,0,199.9998535,0,0,0,90.00000001 +395.2,50.30085681,-2.548508551,10500,0,200.0009685,0,0,0,90.00000001 +395.21,50.30085681,-2.548480525,10500,0,200.0009685,0,0,0,90.00000001 +395.22,50.30085681,-2.5484525,10500,0,199.9998535,0,0,0,90.00000001 +395.23,50.30085681,-2.548424475,10500,0,199.9989614,0,0,0,90.00000001 +395.24,50.30085681,-2.54839645,10500,0,199.9989614,0,0,0,90.00000001 +395.25,50.30085681,-2.548368425,10500,0,199.9998535,0,0,0,90.00000001 +395.26,50.30085681,-2.5483404,10500,0,200.0009685,0,0,0,90.00000001 +395.27,50.30085681,-2.548312374,10500,0,200.0009685,0,0,0,90.00000001 +395.28,50.30085681,-2.548284349,10500,0,199.9998535,0,0,0,90.00000001 +395.29,50.30085681,-2.548256324,10500,0,199.9989614,0,0,0,90.00000001 +395.3,50.30085681,-2.548228299,10500,0,199.9989614,0,0,0,90.00000001 +395.31,50.30085681,-2.548200274,10500,0,199.9998535,0,0,0,90.00000001 +395.32,50.30085681,-2.548172249,10500,0,200.0009685,0,0,0,90.00000001 +395.33,50.30085681,-2.548144223,10500,0,200.0009685,0,0,0,90.00000001 +395.34,50.30085681,-2.548116198,10500,0,199.9998535,0,0,0,90.00000001 +395.35,50.30085681,-2.548088173,10500,0,199.9989614,0,0,0,90.00000001 +395.36,50.30085681,-2.548060148,10500,0,199.9987384,0,0,0,90.00000001 +395.37,50.30085681,-2.548032123,10500,0,199.9989614,0,0,0,90.00000001 +395.38,50.30085681,-2.548004098,10500,0,199.9998535,0,0,0,90.00000001 +395.39,50.30085681,-2.547976073,10500,0,200.0009685,0,0,0,90.00000001 +395.4,50.30085681,-2.547948047,10500,0,200.0009685,0,0,0,90.00000001 +395.41,50.30085681,-2.547920022,10500,0,199.9998535,0,0,0,90.00000001 +395.42,50.30085681,-2.547891997,10500,0,199.9989614,0,0,0,90.00000001 +395.43,50.30085681,-2.547863972,10500,0,199.9989614,0,0,0,90.00000001 +395.44,50.30085681,-2.547835947,10500,0,199.9998535,0,0,0,90.00000001 +395.45,50.30085681,-2.547807922,10500,0,200.0009685,0,0,0,90.00000001 +395.46,50.30085681,-2.547779896,10500,0,200.0009685,0,0,0,90.00000001 +395.47,50.30085681,-2.547751871,10500,0,199.9998535,0,0,0,90.00000001 +395.48,50.30085681,-2.547723846,10500,0,199.9989614,0,0,0,90.00000001 +395.49,50.30085681,-2.547695821,10500,0,199.9989614,0,0,0,90.00000001 +395.5,50.30085681,-2.547667796,10500,0,199.9998535,0,0,0,90.00000001 +395.51,50.30085681,-2.547639771,10500,0,200.0009685,0,0,0,90.00000001 +395.52,50.30085681,-2.547611745,10500,0,200.0009685,0,0,0,90.00000001 +395.53,50.30085681,-2.54758372,10500,0,199.9998535,0,0,0,90.00000001 +395.54,50.30085681,-2.547555695,10500,0,199.9991844,0,0,0,90.00000001 +395.55,50.30085681,-2.54752767,10500,0,199.9998535,0,0,0,90.00000001 +395.56,50.30085681,-2.547499645,10500,0,200.0009685,0,0,0,90.00000001 +395.57,50.30085681,-2.547471619,10500,0,200.0009685,0,0,0,90.00000001 +395.58,50.30085681,-2.547443594,10500,0,199.9998535,0,0,0,90.00000001 +395.59,50.30085681,-2.547415569,10500,0,199.9991844,0,0,0,90.00000001 +395.6,50.30085681,-2.547387544,10500,0,199.9998535,0,0,0,90.00000001 +395.61,50.30085681,-2.547359519,10500,0,200.0009685,0,0,0,90.00000001 +395.62,50.30085681,-2.547331493,10500,0,200.0009685,0,0,0,90.00000001 +395.63,50.30085681,-2.547303468,10500,0,199.9998535,0,0,0,90.00000001 +395.64,50.30085681,-2.547275443,10500,0,199.9991844,0,0,0,90.00000001 +395.65,50.30085681,-2.547247418,10500,0,199.9998535,0,0,0,90.00000001 +395.66,50.30085681,-2.547219393,10500,0,200.0009685,0,0,0,90.00000001 +395.67,50.30085681,-2.547191367,10500,0,200.0009685,0,0,0,90.00000001 +395.68,50.30085681,-2.547163342,10500,0,199.9998535,0,0,0,90.00000001 +395.69,50.30085681,-2.547135317,10500,0,199.9991844,0,0,0,90.00000001 +395.7,50.30085681,-2.547107292,10500,0,199.9998535,0,0,0,90.00000001 +395.71,50.30085681,-2.547079267,10500,0,200.0009685,0,0,0,90.00000001 +395.72,50.30085681,-2.547051241,10500,0,200.0009685,0,0,0,90.00000001 +395.73,50.30085681,-2.547023216,10500,0,199.9998535,0,0,0,90.00000001 +395.74,50.30085681,-2.546995191,10500,0,199.9991844,0,0,0,90.00000001 +395.75,50.30085681,-2.546967166,10500,0,199.9998535,0,0,0,90.00000001 +395.76,50.30085681,-2.546939141,10500,0,200.0009685,0,0,0,90.00000001 +395.77,50.30085681,-2.546911115,10500,0,200.0009685,0,0,0,90.00000001 +395.78,50.30085681,-2.54688309,10500,0,199.9998535,0,0,0,90.00000001 +395.79,50.30085681,-2.546855065,10500,0,199.9989614,0,0,0,90.00000001 +395.8,50.30085681,-2.54682704,10500,0,199.9989614,0,0,0,90.00000001 +395.81,50.30085681,-2.546799015,10500,0,199.9998535,0,0,0,90.00000001 +395.82,50.30085681,-2.54677099,10500,0,200.0009685,0,0,0,90.00000001 +395.83,50.30085681,-2.546742964,10500,0,200.0009685,0,0,0,90.00000001 +395.84,50.30085681,-2.546714939,10500,0,199.9998535,0,0,0,90.00000001 +395.85,50.30085681,-2.546686914,10500,0,199.9989614,0,0,0,90.00000001 +395.86,50.30085681,-2.546658889,10500,0,199.9989614,0,0,0,90.00000001 +395.87,50.30085681,-2.546630864,10500,0,199.9998535,0,0,0,90.00000001 +395.88,50.30085681,-2.546602839,10500,0,200.0009685,0,0,0,90.00000001 +395.89,50.30085681,-2.546574813,10500,0,200.0009685,0,0,0,90.00000001 +395.9,50.30085681,-2.546546788,10500,0,199.9998535,0,0,0,90.00000001 +395.91,50.30085681,-2.546518763,10500,0,199.9989614,0,0,0,90.00000001 +395.92,50.30085681,-2.546490738,10500,0,199.9989614,0,0,0,90.00000001 +395.93,50.30085681,-2.546462713,10500,0,199.9998535,0,0,0,90.00000001 +395.94,50.30085681,-2.546434688,10500,0,200.0009685,0,0,0,90.00000001 +395.95,50.30085681,-2.546406662,10500,0,200.0009685,0,0,0,90.00000001 +395.96,50.30085681,-2.546378637,10500,0,199.9998535,0,0,0,90.00000001 +395.97,50.30085681,-2.546350612,10500,0,199.9989614,0,0,0,90.00000001 +395.98,50.30085681,-2.546322587,10500,0,199.9987384,0,0,0,90.00000001 +395.99,50.30085681,-2.546294562,10500,0,199.9989614,0,0,0,90.00000001 +396,50.30085681,-2.546266537,10500,0,199.9998535,0,0,0,90.00000001 +396.01,50.30085681,-2.546238512,10500,0,200.0009685,0,0,0,90.00000001 +396.02,50.30085681,-2.546210486,10500,0,200.0009685,0,0,0,90.00000001 +396.03,50.30085681,-2.546182461,10500,0,199.9998535,0,0,0,90.00000001 +396.04,50.30085681,-2.546154436,10500,0,199.9989614,0,0,0,90.00000001 +396.05,50.30085681,-2.546126411,10500,0,199.9989614,0,0,0,90.00000001 +396.06,50.30085681,-2.546098386,10500,0,199.9998535,0,0,0,90.00000001 +396.07,50.30085681,-2.546070361,10500,0,200.0009685,0,0,0,90.00000001 +396.08,50.30085681,-2.546042335,10500,0,200.0009685,0,0,0,90.00000001 +396.09,50.30085681,-2.54601431,10500,0,199.9998535,0,0,0,90.00000001 +396.1,50.30085681,-2.545986285,10500,0,199.9989614,0,0,0,90.00000001 +396.11,50.30085681,-2.54595826,10500,0,199.9989614,0,0,0,90.00000001 +396.12,50.30085681,-2.545930235,10500,0,199.9998535,0,0,0,90.00000001 +396.13,50.30085681,-2.54590221,10500,0,200.0009685,0,0,0,90.00000001 +396.14,50.30085681,-2.545874184,10500,0,200.0009685,0,0,0,90.00000001 +396.15,50.30085681,-2.545846159,10500,0,199.9998535,0,0,0,90.00000001 +396.16,50.30085681,-2.545818134,10500,0,199.9991844,0,0,0,90.00000001 +396.17,50.30085681,-2.545790109,10500,0,199.9998535,0,0,0,90.00000001 +396.18,50.30085681,-2.545762084,10500,0,200.0009685,0,0,0,90.00000001 +396.19,50.30085681,-2.545734058,10500,0,200.0009685,0,0,0,90.00000001 +396.2,50.30085681,-2.545706033,10500,0,199.9998535,0,0,0,90.00000001 +396.21,50.30085681,-2.545678008,10500,0,199.9991844,0,0,0,90.00000001 +396.22,50.30085681,-2.545649983,10500,0,199.9998535,0,0,0,90.00000001 +396.23,50.30085681,-2.545621958,10500,0,200.0009685,0,0,0,90.00000001 +396.24,50.30085681,-2.545593932,10500,0,200.0009685,0,0,0,90.00000001 +396.25,50.30085681,-2.545565907,10500,0,199.9998535,0,0,0,90.00000001 +396.26,50.30085681,-2.545537882,10500,0,199.9991844,0,0,0,90.00000001 +396.27,50.30085681,-2.545509857,10500,0,199.9998535,0,0,0,90.00000001 +396.28,50.30085681,-2.545481832,10500,0,200.0009685,0,0,0,90.00000001 +396.29,50.30085681,-2.545453806,10500,0,200.0009685,0,0,0,90.00000001 +396.3,50.30085681,-2.545425781,10500,0,199.9998535,0,0,0,90.00000001 +396.31,50.30085681,-2.545397756,10500,0,199.9991844,0,0,0,90.00000001 +396.32,50.30085681,-2.545369731,10500,0,199.9998535,0,0,0,90.00000001 +396.33,50.30085681,-2.545341706,10500,0,200.0009685,0,0,0,90.00000001 +396.34,50.30085681,-2.54531368,10500,0,200.0009685,0,0,0,90.00000001 +396.35,50.30085681,-2.545285655,10500,0,199.9998535,0,0,0,90.00000001 +396.36,50.30085681,-2.54525763,10500,0,199.9991844,0,0,0,90.00000001 +396.37,50.30085681,-2.545229605,10500,0,199.9998535,0,0,0,90.00000001 +396.38,50.30085681,-2.54520158,10500,0,200.0009685,0,0,0,90.00000001 +396.39,50.30085681,-2.545173554,10500,0,200.0009685,0,0,0,90.00000001 +396.4,50.30085681,-2.545145529,10500,0,199.9998535,0,0,0,90.00000001 +396.41,50.30085681,-2.545117504,10500,0,199.9989614,0,0,0,90.00000001 +396.42,50.30085681,-2.545089479,10500,0,199.9989614,0,0,0,90.00000001 +396.43,50.30085681,-2.545061454,10500,0,199.9998535,0,0,0,90.00000001 +396.44,50.30085681,-2.545033429,10500,0,200.0009685,0,0,0,90.00000001 +396.45,50.30085681,-2.545005403,10500,0,200.0009685,0,0,0,90.00000001 +396.46,50.30085681,-2.544977378,10500,0,199.9998535,0,0,0,90.00000001 +396.47,50.30085681,-2.544949353,10500,0,199.9989614,0,0,0,90.00000001 +396.48,50.30085681,-2.544921328,10500,0,199.9989614,0,0,0,90.00000001 +396.49,50.30085681,-2.544893303,10500,0,199.9998535,0,0,0,90.00000001 +396.5,50.30085681,-2.544865278,10500,0,200.0009685,0,0,0,90.00000001 +396.51,50.30085681,-2.544837252,10500,0,200.0009685,0,0,0,90.00000001 +396.52,50.30085681,-2.544809227,10500,0,199.9998535,0,0,0,90.00000001 +396.53,50.30085681,-2.544781202,10500,0,199.9989614,0,0,0,90.00000001 +396.54,50.30085681,-2.544753177,10500,0,199.9987384,0,0,0,90.00000001 +396.55,50.30085681,-2.544725152,10500,0,199.9989614,0,0,0,90.00000001 +396.56,50.30085681,-2.544697127,10500,0,199.9998535,0,0,0,90.00000001 +396.57,50.30085681,-2.544669102,10500,0,200.0009685,0,0,0,90.00000001 +396.58,50.30085681,-2.544641076,10500,0,200.0009685,0,0,0,90.00000001 +396.59,50.30085681,-2.544613051,10500,0,199.9998535,0,0,0,90.00000001 +396.6,50.30085681,-2.544585026,10500,0,199.9989614,0,0,0,90.00000001 +396.61,50.30085681,-2.544557001,10500,0,199.9989614,0,0,0,90.00000001 +396.62,50.30085681,-2.544528976,10500,0,199.9998535,0,0,0,90.00000001 +396.63,50.30085681,-2.544500951,10500,0,200.0009685,0,0,0,90.00000001 +396.64,50.30085681,-2.544472925,10500,0,200.0009685,0,0,0,90.00000001 +396.65,50.30085681,-2.5444449,10500,0,199.9998535,0,0,0,90.00000001 +396.66,50.30085681,-2.544416875,10500,0,199.9989614,0,0,0,90.00000001 +396.67,50.30085681,-2.54438885,10500,0,199.9989614,0,0,0,90.00000001 +396.68,50.30085681,-2.544360825,10500,0,199.9998535,0,0,0,90.00000001 +396.69,50.30085681,-2.5443328,10500,0,200.0009685,0,0,0,90.00000001 +396.7,50.30085681,-2.544304774,10500,0,200.0009685,0,0,0,90.00000001 +396.71,50.30085681,-2.544276749,10500,0,199.9998535,0,0,0,90.00000001 +396.72,50.30085681,-2.544248724,10500,0,199.9989614,0,0,0,90.00000001 +396.73,50.30085681,-2.544220699,10500,0,199.9989614,0,0,0,90.00000001 +396.74,50.30085681,-2.544192674,10500,0,199.9998535,0,0,0,90.00000001 +396.75,50.30085681,-2.544164649,10500,0,200.0009685,0,0,0,90.00000001 +396.76,50.30085681,-2.544136623,10500,0,200.0009685,0,0,0,90.00000001 +396.77,50.30085681,-2.544108598,10500,0,199.9998535,0,0,0,90.00000001 +396.78,50.30085681,-2.544080573,10500,0,199.9991844,0,0,0,90.00000001 +396.79,50.30085681,-2.544052548,10500,0,199.9998535,0,0,0,90.00000001 +396.8,50.30085681,-2.544024523,10500,0,200.0009685,0,0,0,90.00000001 +396.81,50.30085681,-2.543996497,10500,0,200.0009685,0,0,0,90.00000001 +396.82,50.30085681,-2.543968472,10500,0,199.9998535,0,0,0,90.00000001 +396.83,50.30085681,-2.543940447,10500,0,199.9991844,0,0,0,90.00000001 +396.84,50.30085681,-2.543912422,10500,0,199.9998535,0,0,0,90.00000001 +396.85,50.30085681,-2.543884397,10500,0,200.0009685,0,0,0,90.00000001 +396.86,50.30085681,-2.543856371,10500,0,200.0009685,0,0,0,90.00000001 +396.87,50.30085681,-2.543828346,10500,0,199.9998535,0,0,0,90.00000001 +396.88,50.30085681,-2.543800321,10500,0,199.9991844,0,0,0,90.00000001 +396.89,50.30085681,-2.543772296,10500,0,199.9998535,0,0,0,90.00000001 +396.9,50.30085681,-2.543744271,10500,0,200.0009685,0,0,0,90.00000001 +396.91,50.30085681,-2.543716245,10500,0,200.0009685,0,0,0,90.00000001 +396.92,50.30085681,-2.54368822,10500,0,199.9998535,0,0,0,90.00000001 +396.93,50.30085681,-2.543660195,10500,0,199.9991844,0,0,0,90.00000001 +396.94,50.30085681,-2.54363217,10500,0,199.9998535,0,0,0,90.00000001 +396.95,50.30085681,-2.543604145,10500,0,200.0009685,0,0,0,90.00000001 +396.96,50.30085681,-2.543576119,10500,0,200.0009685,0,0,0,90.00000001 +396.97,50.30085681,-2.543548094,10500,0,199.9998535,0,0,0,90.00000001 +396.98,50.30085681,-2.543520069,10500,0,199.9991844,0,0,0,90.00000001 +396.99,50.30085681,-2.543492044,10500,0,199.9998535,0,0,0,90.00000001 +397,50.30085681,-2.543464019,10500,0,200.0009685,0,0,0,90.00000001 +397.01,50.30085681,-2.543435993,10500,0,200.0009685,0,0,0,90.00000001 +397.02,50.30085681,-2.543407968,10500,0,199.9998535,0,0,0,90.00000001 +397.03,50.30085681,-2.543379943,10500,0,199.9989614,0,0,0,90.00000001 +397.04,50.30085681,-2.543351918,10500,0,199.9989614,0,0,0,90.00000001 +397.05,50.30085681,-2.543323893,10500,0,199.9998535,0,0,0,90.00000001 +397.06,50.30085681,-2.543295868,10500,0,200.0009685,0,0,0,90.00000001 +397.07,50.30085681,-2.543267842,10500,0,200.0009685,0,0,0,90.00000001 +397.08,50.30085681,-2.543239817,10500,0,199.9998535,0,0,0,90.00000001 +397.09,50.30085681,-2.543211792,10500,0,199.9989614,0,0,0,90.00000001 +397.1,50.30085681,-2.543183767,10500,0,199.9987384,0,0,0,90.00000001 +397.11,50.30085681,-2.543155742,10500,0,199.9989614,0,0,0,90.00000001 +397.12,50.30085681,-2.543127717,10500,0,199.9998535,0,0,0,90.00000001 +397.13,50.30085681,-2.543099692,10500,0,200.0009685,0,0,0,90.00000001 +397.14,50.30085681,-2.543071666,10500,0,200.0009685,0,0,0,90.00000001 +397.15,50.30085681,-2.543043641,10500,0,199.9998535,0,0,0,90.00000001 +397.16,50.30085681,-2.543015616,10500,0,199.9989614,0,0,0,90.00000001 +397.17,50.30085681,-2.542987591,10500,0,199.9989614,0,0,0,90.00000001 +397.18,50.30085681,-2.542959566,10500,0,199.9998535,0,0,0,90.00000001 +397.19,50.30085681,-2.542931541,10500,0,200.0009685,0,0,0,90.00000001 +397.2,50.30085681,-2.542903515,10500,0,200.0009685,0,0,0,90.00000001 +397.21,50.30085681,-2.54287549,10500,0,199.9998535,0,0,0,90.00000001 +397.22,50.30085681,-2.542847465,10500,0,199.9989614,0,0,0,90.00000001 +397.23,50.30085681,-2.54281944,10500,0,199.9989614,0,0,0,90.00000001 +397.24,50.30085681,-2.542791415,10500,0,199.9998535,0,0,0,90.00000001 +397.25,50.30085681,-2.54276339,10500,0,200.0009685,0,0,0,90.00000001 +397.26,50.30085681,-2.542735364,10500,0,200.0009685,0,0,0,90.00000001 +397.27,50.30085681,-2.542707339,10500,0,199.9998535,0,0,0,90.00000001 +397.28,50.30085681,-2.542679314,10500,0,199.9989614,0,0,0,90.00000001 +397.29,50.30085681,-2.542651289,10500,0,199.9989614,0,0,0,90.00000001 +397.3,50.30085681,-2.542623264,10500,0,199.9998535,0,0,0,90.00000001 +397.31,50.30085681,-2.542595239,10500,0,200.0009685,0,0,0,90.00000001 +397.32,50.30085681,-2.542567213,10500,0,200.0009685,0,0,0,90.00000001 +397.33,50.30085681,-2.542539188,10500,0,199.9998535,0,0,0,90.00000001 +397.34,50.30085681,-2.542511163,10500,0,199.9989614,0,0,0,90.00000001 +397.35,50.30085681,-2.542483138,10500,0,199.9989614,0,0,0,90.00000001 +397.36,50.30085681,-2.542455113,10500,0,199.9998535,0,0,0,90.00000001 +397.37,50.30085681,-2.542427088,10500,0,200.0009685,0,0,0,90.00000001 +397.38,50.30085681,-2.542399062,10500,0,200.0009685,0,0,0,90.00000001 +397.39,50.30085681,-2.542371037,10500,0,199.9998535,0,0,0,90.00000001 +397.4,50.30085681,-2.542343012,10500,0,199.9991844,0,0,0,90.00000001 +397.41,50.30085681,-2.542314987,10500,0,199.9998535,0,0,0,90.00000001 +397.42,50.30085681,-2.542286962,10500,0,200.0009685,0,0,0,90.00000001 +397.43,50.30085681,-2.542258936,10500,0,200.0009685,0,0,0,90.00000001 +397.44,50.30085681,-2.542230911,10500,0,199.9998535,0,0,0,90.00000001 +397.45,50.30085681,-2.542202886,10500,0,199.9991844,0,0,0,90.00000001 +397.46,50.30085681,-2.542174861,10500,0,199.9998535,0,0,0,90.00000001 +397.47,50.30085681,-2.542146836,10500,0,200.0009685,0,0,0,90.00000001 +397.48,50.30085681,-2.54211881,10500,0,200.0009685,0,0,0,90.00000001 +397.49,50.30085681,-2.542090785,10500,0,199.9998535,0,0,0,90.00000001 +397.5,50.30085681,-2.54206276,10500,0,199.9991844,0,0,0,90.00000001 +397.51,50.30085681,-2.542034735,10500,0,199.9998535,0,0,0,90.00000001 +397.52,50.30085681,-2.54200671,10500,0,200.0009685,0,0,0,90.00000001 +397.53,50.30085681,-2.541978684,10500,0,200.0009685,0,0,0,90.00000001 +397.54,50.30085681,-2.541950659,10500,0,199.9998535,0,0,0,90.00000001 +397.55,50.30085681,-2.541922634,10500,0,199.9989614,0,0,0,90.00000001 +397.56,50.30085681,-2.541894609,10500,0,199.9989614,0,0,0,90.00000001 +397.57,50.30085681,-2.541866584,10500,0,199.9998535,0,0,0,90.00000001 +397.58,50.30085681,-2.541838559,10500,0,200.0009685,0,0,0,90.00000001 +397.59,50.30085681,-2.541810533,10500,0,200.0009685,0,0,0,90.00000001 +397.6,50.30085681,-2.541782508,10500,0,199.9998535,0,0,0,90.00000001 +397.61,50.30085681,-2.541754483,10500,0,199.9991844,0,0,0,90.00000001 +397.62,50.30085681,-2.541726458,10500,0,199.9998535,0,0,0,90.00000001 +397.63,50.30085681,-2.541698433,10500,0,200.0009685,0,0,0,90.00000001 +397.64,50.30085681,-2.541670407,10500,0,200.0009685,0,0,0,90.00000001 +397.65,50.30085681,-2.541642382,10500,0,199.9998535,0,0,0,90.00000001 +397.66,50.30085681,-2.541614357,10500,0,199.9989614,0,0,0,90.00000001 +397.67,50.30085681,-2.541586332,10500,0,199.9989614,0,0,0,90.00000001 +397.68,50.30085681,-2.541558307,10500,0,199.9998535,0,0,0,90.00000001 +397.69,50.30085681,-2.541530282,10500,0,200.0009685,0,0,0,90.00000001 +397.7,50.30085681,-2.541502256,10500,0,200.0009685,0,0,0,90.00000001 +397.71,50.30085681,-2.541474231,10500,0,199.9998535,0,0,0,90.00000001 +397.72,50.30085681,-2.541446206,10500,0,199.9989614,0,0,0,90.00000001 +397.73,50.30085681,-2.541418181,10500,0,199.9989614,0,0,0,90.00000001 +397.74,50.30085681,-2.541390156,10500,0,199.9998535,0,0,0,90.00000001 +397.75,50.30085681,-2.541362131,10500,0,200.0009685,0,0,0,90.00000001 +397.76,50.30085681,-2.541334105,10500,0,200.0009685,0,0,0,90.00000001 +397.77,50.30085681,-2.54130608,10500,0,199.9998535,0,0,0,90.00000001 +397.78,50.30085681,-2.541278055,10500,0,199.9989614,0,0,0,90.00000001 +397.79,50.30085681,-2.54125003,10500,0,199.9989614,0,0,0,90.00000001 +397.8,50.30085681,-2.541222005,10500,0,199.9998535,0,0,0,90.00000001 +397.81,50.30085681,-2.54119398,10500,0,200.0009685,0,0,0,90.00000001 +397.82,50.30085681,-2.541165954,10500,0,200.0009685,0,0,0,90.00000001 +397.83,50.30085681,-2.541137929,10500,0,199.9998535,0,0,0,90.00000001 +397.84,50.30085681,-2.541109904,10500,0,199.9989614,0,0,0,90.00000001 +397.85,50.30085681,-2.541081879,10500,0,199.9989614,0,0,0,90.00000001 +397.86,50.30085681,-2.541053854,10500,0,199.9998535,0,0,0,90.00000001 +397.87,50.30085681,-2.541025829,10500,0,200.0009685,0,0,0,90.00000001 +397.88,50.30085681,-2.540997803,10500,0,200.0009685,0,0,0,90.00000001 +397.89,50.30085681,-2.540969778,10500,0,199.9998535,0,0,0,90.00000001 +397.9,50.30085681,-2.540941753,10500,0,199.9989614,0,0,0,90.00000001 +397.91,50.30085681,-2.540913728,10500,0,199.9989614,0,0,0,90.00000001 +397.92,50.30085681,-2.540885703,10500,0,199.9998535,0,0,0,90.00000001 +397.93,50.30085681,-2.540857678,10500,0,200.0009685,0,0,0,90.00000001 +397.94,50.30085681,-2.540829652,10500,0,200.0009685,0,0,0,90.00000001 +397.95,50.30085681,-2.540801627,10500,0,199.9998535,0,0,0,90.00000001 +397.96,50.30085681,-2.540773602,10500,0,199.9989614,0,0,0,90.00000001 +397.97,50.30085681,-2.540745577,10500,0,199.9987384,0,0,0,90.00000001 +397.98,50.30085681,-2.540717552,10500,0,199.9989614,0,0,0,90.00000001 +397.99,50.30085681,-2.540689527,10500,0,199.9998535,0,0,0,90.00000001 +398,50.30085681,-2.540661502,10500,0,200.0009685,0,0,0,90.00000001 +398.01,50.30085681,-2.540633476,10500,0,200.0009685,0,0,0,90.00000001 +398.02,50.30085681,-2.540605451,10500,0,199.9998535,0,0,0,90.00000001 +398.03,50.30085681,-2.540577426,10500,0,199.9991844,0,0,0,90.00000001 +398.04,50.30085681,-2.540549401,10500,0,199.9998535,0,0,0,90.00000001 +398.05,50.30085681,-2.540521376,10500,0,200.0009685,0,0,0,90.00000001 +398.06,50.30085681,-2.54049335,10500,0,200.0009685,0,0,0,90.00000001 +398.07,50.30085681,-2.540465325,10500,0,199.9998535,0,0,0,90.00000001 +398.08,50.30085681,-2.5404373,10500,0,199.9991844,0,0,0,90.00000001 +398.09,50.30085681,-2.540409275,10500,0,199.9998535,0,0,0,90.00000001 +398.1,50.30085681,-2.54038125,10500,0,200.0009685,0,0,0,90.00000001 +398.11,50.30085681,-2.540353224,10500,0,200.0009685,0,0,0,90.00000001 +398.12,50.30085681,-2.540325199,10500,0,199.9998535,0,0,0,90.00000001 +398.13,50.30085681,-2.540297174,10500,0,199.9991844,0,0,0,90.00000001 +398.14,50.30085681,-2.540269149,10500,0,199.9998535,0,0,0,90.00000001 +398.15,50.30085681,-2.540241124,10500,0,200.0009685,0,0,0,90.00000001 +398.16,50.30085681,-2.540213098,10500,0,200.0009685,0,0,0,90.00000001 +398.17,50.30085681,-2.540185073,10500,0,199.9998535,0,0,0,90.00000001 +398.18,50.30085681,-2.540157048,10500,0,199.9991844,0,0,0,90.00000001 +398.19,50.30085681,-2.540129023,10500,0,199.9998535,0,0,0,90.00000001 +398.2,50.30085681,-2.540100998,10500,0,200.0009685,0,0,0,90.00000001 +398.21,50.30085681,-2.540072972,10500,0,200.0009685,0,0,0,90.00000001 +398.22,50.30085681,-2.540044947,10500,0,199.9998535,0,0,0,90.00000001 +398.23,50.30085681,-2.540016922,10500,0,199.9991844,0,0,0,90.00000001 +398.24,50.30085681,-2.539988897,10500,0,199.9998535,0,0,0,90.00000001 +398.25,50.30085681,-2.539960872,10500,0,200.0009685,0,0,0,90.00000001 +398.26,50.30085681,-2.539932846,10500,0,200.0009685,0,0,0,90.00000001 +398.27,50.30085681,-2.539904821,10500,0,199.9998535,0,0,0,90.00000001 +398.28,50.30085681,-2.539876796,10500,0,199.9989614,0,0,0,90.00000001 +398.29,50.30085681,-2.539848771,10500,0,199.9989614,0,0,0,90.00000001 +398.3,50.30085681,-2.539820746,10500,0,199.9998535,0,0,0,90.00000001 +398.31,50.30085681,-2.539792721,10500,0,200.0009685,0,0,0,90.00000001 +398.32,50.30085681,-2.539764695,10500,0,200.0009685,0,0,0,90.00000001 +398.33,50.30085681,-2.53973667,10500,0,199.9998535,0,0,0,90.00000001 +398.34,50.30085681,-2.539708645,10500,0,199.9989614,0,0,0,90.00000001 +398.35,50.30085681,-2.53968062,10500,0,199.9989614,0,0,0,90.00000001 +398.36,50.30085681,-2.539652595,10500,0,199.9998535,0,0,0,90.00000001 +398.37,50.30085681,-2.53962457,10500,0,200.0009685,0,0,0,90.00000001 +398.38,50.30085681,-2.539596544,10500,0,200.0009685,0,0,0,90.00000001 +398.39,50.30085681,-2.539568519,10500,0,199.9998535,0,0,0,90.00000001 +398.4,50.30085681,-2.539540494,10500,0,199.9989614,0,0,0,90.00000001 +398.41,50.30085681,-2.539512469,10500,0,199.9989614,0,0,0,90.00000001 +398.42,50.30085681,-2.539484444,10500,0,199.9998535,0,0,0,90.00000001 +398.43,50.30085681,-2.539456419,10500,0,200.0009685,0,0,0,90.00000001 +398.44,50.30085681,-2.539428393,10500,0,200.0009685,0,0,0,90.00000001 +398.45,50.30085681,-2.539400368,10500,0,199.9998535,0,0,0,90.00000001 +398.46,50.30085681,-2.539372343,10500,0,199.9989614,0,0,0,90.00000001 +398.47,50.30085681,-2.539344318,10500,0,199.9989614,0,0,0,90.00000001 +398.48,50.30085681,-2.539316293,10500,0,199.9998535,0,0,0,90.00000001 +398.49,50.30085681,-2.539288268,10500,0,200.0009685,0,0,0,90.00000001 +398.5,50.30085681,-2.539260242,10500,0,200.0009685,0,0,0,90.00000001 +398.51,50.30085681,-2.539232217,10500,0,199.9998535,0,0,0,90.00000001 +398.52,50.30085681,-2.539204192,10500,0,199.9989614,0,0,0,90.00000001 +398.53,50.30085681,-2.539176167,10500,0,199.9987384,0,0,0,90.00000001 +398.54,50.30085681,-2.539148142,10500,0,199.9989614,0,0,0,90.00000001 +398.55,50.30085681,-2.539120117,10500,0,199.9998535,0,0,0,90.00000001 +398.56,50.30085681,-2.539092092,10500,0,200.0009685,0,0,0,90.00000001 +398.57,50.30085681,-2.539064066,10500,0,200.0009685,0,0,0,90.00000001 +398.58,50.30085681,-2.539036041,10500,0,199.9998535,0,0,0,90.00000001 +398.59,50.30085681,-2.539008016,10500,0,199.9989614,0,0,0,90.00000001 +398.6,50.30085681,-2.538979991,10500,0,199.9989614,0,0,0,90.00000001 +398.61,50.30085681,-2.538951966,10500,0,199.9998535,0,0,0,90.00000001 +398.62,50.30085681,-2.538923941,10500,0,200.0009685,0,0,0,90.00000001 +398.63,50.30085681,-2.538895915,10500,0,200.0009685,0,0,0,90.00000001 +398.64,50.30085681,-2.53886789,10500,0,199.9998535,0,0,0,90.00000001 +398.65,50.30085681,-2.538839865,10500,0,199.9991844,0,0,0,90.00000001 +398.66,50.30085681,-2.53881184,10500,0,199.9998535,0,0,0,90.00000001 +398.67,50.30085681,-2.538783815,10500,0,200.0009685,0,0,0,90.00000001 +398.68,50.30085681,-2.538755789,10500,0,200.0009685,0,0,0,90.00000001 +398.69,50.30085681,-2.538727764,10500,0,199.9998535,0,0,0,90.00000001 +398.7,50.30085681,-2.538699739,10500,0,199.9991844,0,0,0,90.00000001 +398.71,50.30085681,-2.538671714,10500,0,199.9998535,0,0,0,90.00000001 +398.72,50.30085681,-2.538643689,10500,0,200.0009685,0,0,0,90.00000001 +398.73,50.30085681,-2.538615663,10500,0,200.0009685,0,0,0,90.00000001 +398.74,50.30085681,-2.538587638,10500,0,199.9998535,0,0,0,90.00000001 +398.75,50.30085681,-2.538559613,10500,0,199.9991844,0,0,0,90.00000001 +398.76,50.30085681,-2.538531588,10500,0,199.9998535,0,0,0,90.00000001 +398.77,50.30085681,-2.538503563,10500,0,200.0009685,0,0,0,90.00000001 +398.78,50.30085681,-2.538475537,10500,0,200.0009685,0,0,0,90.00000001 +398.79,50.30085681,-2.538447512,10500,0,199.9998535,0,0,0,90.00000001 +398.8,50.30085681,-2.538419487,10500,0,199.9991844,0,0,0,90.00000001 +398.81,50.30085681,-2.538391462,10500,0,199.9998535,0,0,0,90.00000001 +398.82,50.30085681,-2.538363437,10500,0,200.0009685,0,0,0,90.00000001 +398.83,50.30085681,-2.538335411,10500,0,200.0009685,0,0,0,90.00000001 +398.84,50.30085681,-2.538307386,10500,0,199.9998535,0,0,0,90.00000001 +398.85,50.30085681,-2.538279361,10500,0,199.9991844,0,0,0,90.00000001 +398.86,50.30085681,-2.538251336,10500,0,199.9998535,0,0,0,90.00000001 +398.87,50.30085681,-2.538223311,10500,0,200.0009685,0,0,0,90.00000001 +398.88,50.30085681,-2.538195285,10500,0,200.0009685,0,0,0,90.00000001 +398.89,50.30085681,-2.53816726,10500,0,199.9998535,0,0,0,90.00000001 +398.9,50.30085681,-2.538139235,10500,0,199.9989614,0,0,0,90.00000001 +398.91,50.30085681,-2.53811121,10500,0,199.9989614,0,0,0,90.00000001 +398.92,50.30085681,-2.538083185,10500,0,199.9998535,0,0,0,90.00000001 +398.93,50.30085681,-2.53805516,10500,0,200.0009685,0,0,0,90.00000001 +398.94,50.30085681,-2.538027134,10500,0,200.0009685,0,0,0,90.00000001 +398.95,50.30085681,-2.537999109,10500,0,199.9998535,0,0,0,90.00000001 +398.96,50.30085681,-2.537971084,10500,0,199.9989614,0,0,0,90.00000001 +398.97,50.30085681,-2.537943059,10500,0,199.9989614,0,0,0,90.00000001 +398.98,50.30085681,-2.537915034,10500,0,199.9998535,0,0,0,90.00000001 +398.99,50.30085681,-2.537887009,10500,0,200.0009685,0,0,0,90.00000001 +399,50.30085681,-2.537858983,10500,0,200.0009685,0,0,0,90.00000001 +399.01,50.30085681,-2.537830958,10500,0,199.9998535,0,0,0,90.00000001 +399.02,50.30085681,-2.537802933,10500,0,199.9989614,0,0,0,90.00000001 +399.03,50.30085681,-2.537774908,10500,0,199.9989614,0,0,0,90.00000001 +399.04,50.30085681,-2.537746883,10500,0,199.9998535,0,0,0,90.00000001 +399.05,50.30085681,-2.537718858,10500,0,200.0009685,0,0,0,90.00000001 +399.06,50.30085681,-2.537690832,10500,0,200.0009685,0,0,0,90.00000001 +399.07,50.30085681,-2.537662807,10500,0,199.9998535,0,0,0,90.00000001 +399.08,50.30085681,-2.537634782,10500,0,199.9989614,0,0,0,90.00000001 +399.09,50.30085681,-2.537606757,10500,0,199.9987384,0,0,0,90.00000001 +399.1,50.30085681,-2.537578732,10500,0,199.9989614,0,0,0,90.00000001 +399.11,50.30085681,-2.537550707,10500,0,199.9998535,0,0,0,90.00000001 +399.12,50.30085681,-2.537522682,10500,0,200.0009685,0,0,0,90.00000001 +399.13,50.30085681,-2.537494656,10500,0,200.0009685,0,0,0,90.00000001 +399.14,50.30085681,-2.537466631,10500,0,199.9998535,0,0,0,90.00000001 +399.15,50.30085681,-2.537438606,10500,0,199.9989614,0,0,0,90.00000001 +399.16,50.30085681,-2.537410581,10500,0,199.9989614,0,0,0,90.00000001 +399.17,50.30085681,-2.537382556,10500,0,199.9998535,0,0,0,90.00000001 +399.18,50.30085681,-2.537354531,10500,0,200.0009685,0,0,0,90.00000001 +399.19,50.30085681,-2.537326505,10500,0,200.0009685,0,0,0,90.00000001 +399.2,50.30085681,-2.53729848,10500,0,199.9998535,0,0,0,90.00000001 +399.21,50.30085681,-2.537270455,10500,0,199.9989614,0,0,0,90.00000001 +399.22,50.30085681,-2.53724243,10500,0,199.9989614,0,0,0,90.00000001 +399.23,50.30085681,-2.537214405,10500,0,199.9998535,0,0,0,90.00000001 +399.24,50.30085681,-2.53718638,10500,0,200.0009685,0,0,0,90.00000001 +399.25,50.30085681,-2.537158354,10500,0,200.0009685,0,0,0,90.00000001 +399.26,50.30085681,-2.537130329,10500,0,199.9998535,0,0,0,90.00000001 +399.27,50.30085681,-2.537102304,10500,0,199.9991844,0,0,0,90.00000001 +399.28,50.30085681,-2.537074279,10500,0,199.9998535,0,0,0,90.00000001 +399.29,50.30085681,-2.537046254,10500,0,200.0009685,0,0,0,90.00000001 +399.3,50.30085681,-2.537018228,10500,0,200.0009685,0,0,0,90.00000001 +399.31,50.30085681,-2.536990203,10500,0,199.9998535,0,0,0,90.00000001 +399.32,50.30085681,-2.536962178,10500,0,199.9991844,0,0,0,90.00000001 +399.33,50.30085681,-2.536934153,10500,0,199.9998535,0,0,0,90.00000001 +399.34,50.30085681,-2.536906128,10500,0,200.0009685,0,0,0,90.00000001 +399.35,50.30085681,-2.536878102,10500,0,200.0009685,0,0,0,90.00000001 +399.36,50.30085681,-2.536850077,10500,0,199.9998535,0,0,0,90.00000001 +399.37,50.30085681,-2.536822052,10500,0,199.9991844,0,0,0,90.00000001 +399.38,50.30085681,-2.536794027,10500,0,199.9998535,0,0,0,90.00000001 +399.39,50.30085681,-2.536766002,10500,0,200.0009685,0,0,0,90.00000001 +399.4,50.30085681,-2.536737976,10500,0,200.0009685,0,0,0,90.00000001 +399.41,50.30085681,-2.536709951,10500,0,199.9998535,0,0,0,90.00000001 +399.42,50.30085681,-2.536681926,10500,0,199.9991844,0,0,0,90.00000001 +399.43,50.30085681,-2.536653901,10500,0,199.9998535,0,0,0,90.00000001 +399.44,50.30085681,-2.536625876,10500,0,200.0009685,0,0,0,90.00000001 +399.45,50.30085681,-2.53659785,10500,0,200.0009685,0,0,0,90.00000001 +399.46,50.30085681,-2.536569825,10500,0,199.9998535,0,0,0,90.00000001 +399.47,50.30085681,-2.5365418,10500,0,199.9991844,0,0,0,90.00000001 +399.48,50.30085681,-2.536513775,10500,0,199.9998535,0,0,0,90.00000001 +399.49,50.30085681,-2.53648575,10500,0,200.0009685,0,0,0,90.00000001 +399.5,50.30085681,-2.536457724,10500,0,200.0009685,0,0,0,90.00000001 +399.51,50.30085681,-2.536429699,10500,0,199.9998535,0,0,0,90.00000001 +399.52,50.30085681,-2.536401674,10500,0,199.9989614,0,0,0,90.00000001 +399.53,50.30085681,-2.536373649,10500,0,199.9989614,0,0,0,90.00000001 +399.54,50.30085681,-2.536345624,10500,0,199.9998535,0,0,0,90.00000001 +399.55,50.30085681,-2.536317599,10500,0,200.0009685,0,0,0,90.00000001 +399.56,50.30085681,-2.536289573,10500,0,200.0009685,0,0,0,90.00000001 +399.57,50.30085681,-2.536261548,10500,0,199.9998535,0,0,0,90.00000001 +399.58,50.30085681,-2.536233523,10500,0,199.9989614,0,0,0,90.00000001 +399.59,50.30085681,-2.536205498,10500,0,199.9989614,0,0,0,90.00000001 +399.6,50.30085681,-2.536177473,10500,0,199.9998535,0,0,0,90.00000001 +399.61,50.30085681,-2.536149448,10500,0,200.0009685,0,0,0,90.00000001 +399.62,50.30085681,-2.536121422,10500,0,200.0009685,0,0,0,90.00000001 +399.63,50.30085681,-2.536093397,10500,0,199.9998535,0,0,0,90.00000001 +399.64,50.30085681,-2.536065372,10500,0,199.9989614,0,0,0,90.00000001 +399.65,50.30085681,-2.536037347,10500,0,199.9987384,0,0,0,90.00000001 +399.66,50.30085681,-2.536009322,10500,0,199.9989614,0,0,0,90.00000001 +399.67,50.30085681,-2.535981297,10500,0,199.9998535,0,0,0,90.00000001 +399.68,50.30085681,-2.535953272,10500,0,200.0009685,0,0,0,90.00000001 +399.69,50.30085681,-2.535925246,10500,0,200.0009685,0,0,0,90.00000001 +399.7,50.30085681,-2.535897221,10500,0,199.9998535,0,0,0,90.00000001 +399.71,50.30085681,-2.535869196,10500,0,199.9989614,0,0,0,90.00000001 +399.72,50.30085681,-2.535841171,10500,0,199.9989614,0,0,0,90.00000001 +399.73,50.30085681,-2.535813146,10500,0,199.9998535,0,0,0,90.00000001 +399.74,50.30085681,-2.535785121,10500,0,200.0009685,0,0,0,90.00000001 +399.75,50.30085681,-2.535757095,10500,0,200.0009685,0,0,0,90.00000001 +399.76,50.30085681,-2.53572907,10500,0,199.9998535,0,0,0,90.00000001 +399.77,50.30085681,-2.535701045,10500,0,199.9989614,0,0,0,90.00000001 +399.78,50.30085681,-2.53567302,10500,0,199.9989614,0,0,0,90.00000001 +399.79,50.30085681,-2.535644995,10500,0,199.9998535,0,0,0,90.00000001 +399.8,50.30085681,-2.53561697,10500,0,200.0009685,0,0,0,90.00000001 +399.81,50.30085681,-2.535588944,10500,0,200.0009685,0,0,0,90.00000001 +399.82,50.30085681,-2.535560919,10500,0,199.9998535,0,0,0,90.00000001 +399.83,50.30085681,-2.535532894,10500,0,199.9989614,0,0,0,90.00000001 +399.84,50.30085681,-2.535504869,10500,0,199.9989614,0,0,0,90.00000001 +399.85,50.30085681,-2.535476844,10500,0,199.9998535,0,0,0,90.00000001 +399.86,50.30085681,-2.535448819,10500,0,200.0009685,0,0,0,90.00000001 +399.87,50.30085681,-2.535420793,10500,0,200.0009685,0,0,0,90.00000001 +399.88,50.30085681,-2.535392768,10500,0,199.9998535,0,0,0,90.00000001 +399.89,50.30085681,-2.535364743,10500,0,199.9991844,0,0,0,90.00000001 +399.9,50.30085681,-2.535336718,10500,0,199.9998535,0,0,0,90.00000001 +399.91,50.30085681,-2.535308693,10500,0,200.0009685,0,0,0,90.00000001 +399.92,50.30085681,-2.535280667,10500,0,200.0009685,0,0,0,90.00000001 +399.93,50.30085681,-2.535252642,10500,0,199.9998535,0,0,0,90.00000001 +399.94,50.30085681,-2.535224617,10500,0,199.9989614,0,0,0,90.00000001 +399.95,50.30085681,-2.535196592,10500,0,199.9989614,0,0,0,90.00000001 +399.96,50.30085681,-2.535168567,10500,0,199.9998535,0,0,0,90.00000001 +399.97,50.30085681,-2.535140542,10500,0,200.0009685,0,0,0,90.00000001 +399.98,50.30085681,-2.535112516,10500,0,200.0009685,0,0,0,90.00000001 +399.99,50.30085681,-2.535084491,10500,0,199.9998535,0,0,0,90.00000001 +400,50.30085681,-2.535056466,10500,0,199.9991844,0,0,0,90.00000001 +400.01,50.30085681,-2.535028441,10500,0,199.9998535,0,0,0,90.00000001 +400.02,50.30085681,-2.535000416,10500,0,200.0009685,0,0,0,90.00000001 +400.03,50.30085681,-2.53497239,10500,0,200.0009685,0,0,0,90.00000001 +400.04,50.30085681,-2.534944365,10500,0,199.9998535,0,0,0,90.00000001 +400.05,50.30085681,-2.53491634,10500,0,199.9991844,0,0,0,90.00000001 +400.06,50.30085681,-2.534888315,10500,0,199.9998535,0,0,0,90.00000001 +400.07,50.30085681,-2.53486029,10500,0,200.0009685,0,0,0,90.00000001 +400.08,50.30085681,-2.534832264,10500,0,200.0009685,0,0,0,90.00000001 +400.09,50.30085681,-2.534804239,10500,0,199.9998535,0,0,0,90.00000001 +400.1,50.30085681,-2.534776214,10500,0,199.9991844,0,0,0,90.00000001 +400.11,50.30085681,-2.534748189,10500,0,199.9998535,0,0,0,90.00000001 +400.12,50.30085681,-2.534720164,10500,0,200.0009685,0,0,0,90.00000001 +400.13,50.30085681,-2.534692138,10500,0,200.0009685,0,0,0,90.00000001 +400.14,50.30085681,-2.534664113,10500,0,199.9998535,0,0,0,90.00000001 +400.15,50.30085681,-2.534636088,10500,0,199.9991844,0,0,0,90.00000001 +400.16,50.30085681,-2.534608063,10500,0,199.9998535,0,0,0,90.00000001 +400.17,50.30085681,-2.534580038,10500,0,200.0009685,0,0,0,90.00000001 +400.18,50.30085681,-2.534552012,10500,0,200.0009685,0,0,0,90.00000001 +400.19,50.30085681,-2.534523987,10500,0,199.9998535,0,0,0,90.00000001 +400.2,50.30085681,-2.534495962,10500,0,199.9989614,0,0,0,90.00000001 +400.21,50.30085681,-2.534467937,10500,0,199.9989614,0,0,0,90.00000001 +400.22,50.30085681,-2.534439912,10500,0,199.9998535,0,0,0,90.00000001 +400.23,50.30085681,-2.534411887,10500,0,200.0009685,0,0,0,90.00000001 +400.24,50.30085681,-2.534383861,10500,0,200.0009685,0,0,0,90.00000001 +400.25,50.30085681,-2.534355836,10500,0,199.9998535,0,0,0,90.00000001 +400.26,50.30085681,-2.534327811,10500,0,199.9989614,0,0,0,90.00000001 +400.27,50.30085681,-2.534299786,10500,0,199.9987384,0,0,0,90.00000001 +400.28,50.30085681,-2.534271761,10500,0,199.9989614,0,0,0,90.00000001 +400.29,50.30085681,-2.534243736,10500,0,199.9998535,0,0,0,90.00000001 +400.3,50.30085681,-2.534215711,10500,0,200.0009685,0,0,0,90.00000001 +400.31,50.30085681,-2.534187685,10500,0,200.0009685,0,0,0,90.00000001 +400.32,50.30085681,-2.53415966,10500,0,199.9998535,0,0,0,90.00000001 +400.33,50.30085681,-2.534131635,10500,0,199.9989614,0,0,0,90.00000001 +400.34,50.30085681,-2.53410361,10500,0,199.9989614,0,0,0,90.00000001 +400.35,50.30085681,-2.534075585,10500,0,199.9998535,0,0,0,90.00000001 +400.36,50.30085681,-2.53404756,10500,0,200.0009685,0,0,0,90.00000001 +400.37,50.30085681,-2.534019534,10500,0,200.0009685,0,0,0,90.00000001 +400.38,50.30085681,-2.533991509,10500,0,199.9998535,0,0,0,90.00000001 +400.39,50.30085681,-2.533963484,10500,0,199.9989614,0,0,0,90.00000001 +400.4,50.30085681,-2.533935459,10500,0,199.9989614,0,0,0,90.00000001 +400.41,50.30085681,-2.533907434,10500,0,199.9998535,0,0,0,90.00000001 +400.42,50.30085681,-2.533879409,10500,0,200.0009685,0,0,0,90.00000001 +400.43,50.30085681,-2.533851383,10500,0,200.0009685,0,0,0,90.00000001 +400.44,50.30085681,-2.533823358,10500,0,199.9998535,0,0,0,90.00000001 +400.45,50.30085681,-2.533795333,10500,0,199.9989614,0,0,0,90.00000001 +400.46,50.30085681,-2.533767308,10500,0,199.9989614,0,0,0,90.00000001 +400.47,50.30085681,-2.533739283,10500,0,199.9998535,0,0,0,90.00000001 +400.48,50.30085681,-2.533711258,10500,0,200.0009685,0,0,0,90.00000001 +400.49,50.30085681,-2.533683232,10500,0,200.0009685,0,0,0,90.00000001 +400.5,50.30085681,-2.533655207,10500,0,199.9998535,0,0,0,90.00000001 +400.51,50.30085681,-2.533627182,10500,0,199.9989614,0,0,0,90.00000001 +400.52,50.30085681,-2.533599157,10500,0,199.9989614,0,0,0,90.00000001 +400.53,50.30085681,-2.533571132,10500,0,199.9998535,0,0,0,90.00000001 +400.54,50.30085681,-2.533543107,10500,0,200.0009685,0,0,0,90.00000001 +400.55,50.30085681,-2.533515081,10500,0,200.0009685,0,0,0,90.00000001 +400.56,50.30085681,-2.533487056,10500,0,199.9998535,0,0,0,90.00000001 +400.57,50.30085681,-2.533459031,10500,0,199.9991844,0,0,0,90.00000001 +400.58,50.30085681,-2.533431006,10500,0,199.9998535,0,0,0,90.00000001 +400.59,50.30085681,-2.533402981,10500,0,200.0009685,0,0,0,90.00000001 +400.6,50.30085681,-2.533374955,10500,0,200.0009685,0,0,0,90.00000001 +400.61,50.30085681,-2.53334693,10500,0,199.9998535,0,0,0,90.00000001 +400.62,50.30085681,-2.533318905,10500,0,199.9991844,0,0,0,90.00000001 +400.63,50.30085681,-2.53329088,10500,0,199.9998535,0,0,0,90.00000001 +400.64,50.30085681,-2.533262855,10500,0,200.0009685,0,0,0,90.00000001 +400.65,50.30085681,-2.533234829,10500,0,200.0009685,0,0,0,90.00000001 +400.66,50.30085681,-2.533206804,10500,0,199.9998535,0,0,0,90.00000001 +400.67,50.30085681,-2.533178779,10500,0,199.9991844,0,0,0,90.00000001 +400.68,50.30085681,-2.533150754,10500,0,199.9998535,0,0,0,90.00000001 +400.69,50.30085681,-2.533122729,10500,0,200.0009685,0,0,0,90.00000001 +400.7,50.30085681,-2.533094703,10500,0,200.0009685,0,0,0,90.00000001 +400.71,50.30085681,-2.533066678,10500,0,199.9998535,0,0,0,90.00000001 +400.72,50.30085681,-2.533038653,10500,0,199.9991844,0,0,0,90.00000001 +400.73,50.30085681,-2.533010628,10500,0,199.9998535,0,0,0,90.00000001 +400.74,50.30085681,-2.532982603,10500,0,200.0009685,0,0,0,90.00000001 +400.75,50.30085681,-2.532954577,10500,0,200.0009685,0,0,0,90.00000001 +400.76,50.30085681,-2.532926552,10500,0,199.9998535,0,0,0,90.00000001 +400.77,50.30085681,-2.532898527,10500,0,199.9991844,0,0,0,90.00000001 +400.78,50.30085681,-2.532870502,10500,0,199.9998535,0,0,0,90.00000001 +400.79,50.30085681,-2.532842477,10500,0,200.0009685,0,0,0,90.00000001 +400.8,50.30085681,-2.532814451,10500,0,200.0009685,0,0,0,90.00000001 +400.81,50.30085681,-2.532786426,10500,0,199.9998535,0,0,0,90.00000001 +400.82,50.30085681,-2.532758401,10500,0,199.9989614,0,0,0,90.00000001 +400.83,50.30085681,-2.532730376,10500,0,199.9987384,0,0,0,90.00000001 +400.84,50.30085681,-2.532702351,10500,0,199.9989614,0,0,0,90.00000001 +400.85,50.30085681,-2.532674326,10500,0,199.9998535,0,0,0,90.00000001 +400.86,50.30085681,-2.532646301,10500,0,200.0009685,0,0,0,90.00000001 +400.87,50.30085681,-2.532618275,10500,0,200.0009685,0,0,0,90.00000001 +400.88,50.30085681,-2.53259025,10500,0,199.9998535,0,0,0,90.00000001 +400.89,50.30085681,-2.532562225,10500,0,199.9989614,0,0,0,90.00000001 +400.9,50.30085681,-2.5325342,10500,0,199.9989614,0,0,0,90.00000001 +400.91,50.30085681,-2.532506175,10500,0,199.9998535,0,0,0,90.00000001 +400.92,50.30085681,-2.53247815,10500,0,200.0009685,0,0,0,90.00000001 +400.93,50.30085681,-2.532450124,10500,0,200.0009685,0,0,0,90.00000001 +400.94,50.30085681,-2.532422099,10500,0,199.9998535,0,0,0,90.00000001 +400.95,50.30085681,-2.532394074,10500,0,199.9989614,0,0,0,90.00000001 +400.96,50.30085681,-2.532366049,10500,0,199.9989614,0,0,0,90.00000001 +400.97,50.30085681,-2.532338024,10500,0,199.9998535,0,0,0,90.00000001 +400.98,50.30085681,-2.532309999,10500,0,200.0009685,0,0,0,90.00000001 +400.99,50.30085681,-2.532281973,10500,0,200.0009685,0,0,0,90.00000001 +401,50.30085681,-2.532253948,10500,0,199.9998535,0,0,0,90.00000001 +401.01,50.30085681,-2.532225923,10500,0,199.9989614,0,0,0,90.00000001 +401.02,50.30085681,-2.532197898,10500,0,199.9989614,0,0,0,90.00000001 +401.03,50.30085681,-2.532169873,10500,0,199.9998535,0,0,0,90.00000001 +401.04,50.30085681,-2.532141848,10500,0,200.0009685,0,0,0,90.00000001 +401.05,50.30085681,-2.532113822,10500,0,200.0009685,0,0,0,90.00000001 +401.06,50.30085681,-2.532085797,10500,0,199.9998535,0,0,0,90.00000001 +401.07,50.30085681,-2.532057772,10500,0,199.9989614,0,0,0,90.00000001 +401.08,50.30085681,-2.532029747,10500,0,199.9987384,0,0,0,90.00000001 +401.09,50.30085681,-2.532001722,10500,0,199.9989614,0,0,0,90.00000001 +401.1,50.30085681,-2.531973697,10500,0,199.9998535,0,0,0,90.00000001 +401.11,50.30085681,-2.531945672,10500,0,200.0009685,0,0,0,90.00000001 +401.12,50.30085681,-2.531917646,10500,0,200.0009685,0,0,0,90.00000001 +401.13,50.30085681,-2.531889621,10500,0,199.9998535,0,0,0,90.00000001 +401.14,50.30085681,-2.531861596,10500,0,199.9991844,0,0,0,90.00000001 +401.15,50.30085681,-2.531833571,10500,0,199.9998535,0,0,0,90.00000001 +401.16,50.30085681,-2.531805546,10500,0,200.0009685,0,0,0,90.00000001 +401.17,50.30085681,-2.53177752,10500,0,200.0009685,0,0,0,90.00000001 +401.18,50.30085681,-2.531749495,10500,0,199.9998535,0,0,0,90.00000001 +401.19,50.30085681,-2.53172147,10500,0,199.9991844,0,0,0,90.00000001 +401.2,50.30085681,-2.531693445,10500,0,199.9998535,0,0,0,90.00000001 +401.21,50.30085681,-2.53166542,10500,0,200.0009685,0,0,0,90.00000001 +401.22,50.30085681,-2.531637394,10500,0,200.0009685,0,0,0,90.00000001 +401.23,50.30085681,-2.531609369,10500,0,199.9998535,0,0,0,90.00000001 +401.24,50.30085681,-2.531581344,10500,0,199.9991844,0,0,0,90.00000001 +401.25,50.30085681,-2.531553319,10500,0,199.9998535,0,0,0,90.00000001 +401.26,50.30085681,-2.531525294,10500,0,200.0009685,0,0,0,90.00000001 +401.27,50.30085681,-2.531497268,10500,0,200.0009685,0,0,0,90.00000001 +401.28,50.30085681,-2.531469243,10500,0,199.9998535,0,0,0,90.00000001 +401.29,50.30085681,-2.531441218,10500,0,199.9991844,0,0,0,90.00000001 +401.3,50.30085681,-2.531413193,10500,0,199.9998535,0,0,0,90.00000001 +401.31,50.30085681,-2.531385168,10500,0,200.0009685,0,0,0,90.00000001 +401.32,50.30085681,-2.531357142,10500,0,200.0009685,0,0,0,90.00000001 +401.33,50.30085681,-2.531329117,10500,0,199.9998535,0,0,0,90.00000001 +401.34,50.30085681,-2.531301092,10500,0,199.9991844,0,0,0,90.00000001 +401.35,50.30085681,-2.531273067,10500,0,199.9998535,0,0,0,90.00000001 +401.36,50.30085681,-2.531245042,10500,0,200.0009685,0,0,0,90.00000001 +401.37,50.30085681,-2.531217016,10500,0,200.0009685,0,0,0,90.00000001 +401.38,50.30085681,-2.531188991,10500,0,199.9998535,0,0,0,90.00000001 +401.39,50.30085681,-2.531160966,10500,0,199.9989614,0,0,0,90.00000001 +401.4,50.30085681,-2.531132941,10500,0,199.9989614,0,0,0,90.00000001 +401.41,50.30085681,-2.531104916,10500,0,199.9998535,0,0,0,90.00000001 +401.42,50.30085681,-2.531076891,10500,0,200.0009685,0,0,0,90.00000001 +401.43,50.30085681,-2.531048865,10500,0,200.0009685,0,0,0,90.00000001 +401.44,50.30085681,-2.53102084,10500,0,199.9998535,0,0,0,90.00000001 +401.45,50.30085681,-2.530992815,10500,0,199.9989614,0,0,0,90.00000001 +401.46,50.30085681,-2.53096479,10500,0,199.9989614,0,0,0,90.00000001 +401.47,50.30085681,-2.530936765,10500,0,199.9998535,0,0,0,90.00000001 +401.48,50.30085681,-2.53090874,10500,0,200.0009685,0,0,0,90.00000001 +401.49,50.30085681,-2.530880714,10500,0,200.0009685,0,0,0,90.00000001 +401.5,50.30085681,-2.530852689,10500,0,199.9998535,0,0,0,90.00000001 +401.51,50.30085681,-2.530824664,10500,0,199.9989614,0,0,0,90.00000001 +401.52,50.30085681,-2.530796639,10500,0,199.9989614,0,0,0,90.00000001 +401.53,50.30085681,-2.530768614,10500,0,199.9998535,0,0,0,90.00000001 +401.54,50.30085681,-2.530740589,10500,0,200.0009685,0,0,0,90.00000001 +401.55,50.30085681,-2.530712563,10500,0,200.0009685,0,0,0,90.00000001 +401.56,50.30085681,-2.530684538,10500,0,199.9998535,0,0,0,90.00000001 +401.57,50.30085681,-2.530656513,10500,0,199.9989614,0,0,0,90.00000001 +401.58,50.30085681,-2.530628488,10500,0,199.9989614,0,0,0,90.00000001 +401.59,50.30085681,-2.530600463,10500,0,199.9998535,0,0,0,90.00000001 +401.6,50.30085681,-2.530572438,10500,0,200.0009685,0,0,0,90.00000001 +401.61,50.30085681,-2.530544412,10500,0,200.0009685,0,0,0,90.00000001 +401.62,50.30085681,-2.530516387,10500,0,199.9998535,0,0,0,90.00000001 +401.63,50.30085681,-2.530488362,10500,0,199.9989614,0,0,0,90.00000001 +401.64,50.30085681,-2.530460337,10500,0,199.9989614,0,0,0,90.00000001 +401.65,50.30085681,-2.530432312,10500,0,199.9998535,0,0,0,90.00000001 +401.66,50.30085681,-2.530404287,10500,0,200.0009685,0,0,0,90.00000001 +401.67,50.30085681,-2.530376261,10500,0,200.0009685,0,0,0,90.00000001 +401.68,50.30085681,-2.530348236,10500,0,199.9998535,0,0,0,90.00000001 +401.69,50.30085681,-2.530320211,10500,0,199.9989614,0,0,0,90.00000001 +401.7,50.30085681,-2.530292186,10500,0,199.9987384,0,0,0,90.00000001 +401.71,50.30085681,-2.530264161,10500,0,199.9989614,0,0,0,90.00000001 +401.72,50.30085681,-2.530236136,10500,0,199.9998535,0,0,0,90.00000001 +401.73,50.30085681,-2.530208111,10500,0,200.0009685,0,0,0,90.00000001 +401.74,50.30085681,-2.530180085,10500,0,200.0009685,0,0,0,90.00000001 +401.75,50.30085681,-2.53015206,10500,0,199.9998535,0,0,0,90.00000001 +401.76,50.30085681,-2.530124035,10500,0,199.9991844,0,0,0,90.00000001 +401.77,50.30085681,-2.53009601,10500,0,199.9998535,0,0,0,90.00000001 +401.78,50.30085681,-2.530067985,10500,0,200.0009685,0,0,0,90.00000001 +401.79,50.30085681,-2.530039959,10500,0,200.0009685,0,0,0,90.00000001 +401.8,50.30085681,-2.530011934,10500,0,199.9998535,0,0,0,90.00000001 +401.81,50.30085681,-2.529983909,10500,0,199.9991844,0,0,0,90.00000001 +401.82,50.30085681,-2.529955884,10500,0,199.9998535,0,0,0,90.00000001 +401.83,50.30085681,-2.529927859,10500,0,200.0009685,0,0,0,90.00000001 +401.84,50.30085681,-2.529899833,10500,0,200.0009685,0,0,0,90.00000001 +401.85,50.30085681,-2.529871808,10500,0,199.9998535,0,0,0,90.00000001 +401.86,50.30085681,-2.529843783,10500,0,199.9991844,0,0,0,90.00000001 +401.87,50.30085681,-2.529815758,10500,0,199.9998535,0,0,0,90.00000001 +401.88,50.30085681,-2.529787733,10500,0,200.0009685,0,0,0,90.00000001 +401.89,50.30085681,-2.529759707,10500,0,200.0009685,0,0,0,90.00000001 +401.9,50.30085681,-2.529731682,10500,0,199.9998535,0,0,0,90.00000001 +401.91,50.30085681,-2.529703657,10500,0,199.9991844,0,0,0,90.00000001 +401.92,50.30085681,-2.529675632,10500,0,199.9998535,0,0,0,90.00000001 +401.93,50.30085681,-2.529647607,10500,0,200.0009685,0,0,0,90.00000001 +401.94,50.30085681,-2.529619581,10500,0,200.0009685,0,0,0,90.00000001 +401.95,50.30085681,-2.529591556,10500,0,199.9998535,0,0,0,90.00000001 +401.96,50.30085681,-2.529563531,10500,0,199.9991844,0,0,0,90.00000001 +401.97,50.30085681,-2.529535506,10500,0,199.9998535,0,0,0,90.00000001 +401.98,50.30085681,-2.529507481,10500,0,200.0009685,0,0,0,90.00000001 +401.99,50.30085681,-2.529479455,10500,0,200.0009685,0,0,0,90.00000001 +402,50.30085681,-2.52945143,10500,0,199.9998535,0,0,0,90.00000001 +402.01,50.30085681,-2.529423405,10500,0,199.9989614,0,0,0,90.00000001 +402.02,50.30085681,-2.52939538,10500,0,199.9989614,0,0,0,90.00000001 +402.03,50.30085681,-2.529367355,10500,0,199.9998535,0,0,0,90.00000001 +402.04,50.30085681,-2.52933933,10500,0,200.0009685,0,0,0,90.00000001 +402.05,50.30085681,-2.529311304,10500,0,200.0009685,0,0,0,90.00000001 +402.06,50.30085681,-2.529283279,10500,0,199.9998535,0,0,0,90.00000001 +402.07,50.30085681,-2.529255254,10500,0,199.9989614,0,0,0,90.00000001 +402.08,50.30085681,-2.529227229,10500,0,199.9989614,0,0,0,90.00000001 +402.09,50.30085681,-2.529199204,10500,0,199.9998535,0,0,0,90.00000001 +402.1,50.30085681,-2.529171179,10500,0,200.0009685,0,0,0,90.00000001 +402.11,50.30085681,-2.529143153,10500,0,200.0009685,0,0,0,90.00000001 +402.12,50.30085681,-2.529115128,10500,0,199.9998535,0,0,0,90.00000001 +402.13,50.30085681,-2.529087103,10500,0,199.9989614,0,0,0,90.00000001 +402.14,50.30085681,-2.529059078,10500,0,199.9989614,0,0,0,90.00000001 +402.15,50.30085681,-2.529031053,10500,0,199.9998535,0,0,0,90.00000001 +402.16,50.30085681,-2.529003028,10500,0,200.0009685,0,0,0,90.00000001 +402.17,50.30085681,-2.528975002,10500,0,200.0009685,0,0,0,90.00000001 +402.18,50.30085681,-2.528946977,10500,0,199.9998535,0,0,0,90.00000001 +402.19,50.30085681,-2.528918952,10500,0,199.9989614,0,0,0,90.00000001 +402.2,50.30085681,-2.528890927,10500,0,199.9989614,0,0,0,90.00000001 +402.21,50.30085681,-2.528862902,10500,0,199.9998535,0,0,0,90.00000001 +402.22,50.30085681,-2.528834877,10500,0,200.0009685,0,0,0,90.00000001 +402.23,50.30085681,-2.528806851,10500,0,200.0009685,0,0,0,90.00000001 +402.24,50.30085681,-2.528778826,10500,0,199.9998535,0,0,0,90.00000001 +402.25,50.30085681,-2.528750801,10500,0,199.9989614,0,0,0,90.00000001 +402.26,50.30085681,-2.528722776,10500,0,199.9987384,0,0,0,90.00000001 +402.27,50.30085681,-2.528694751,10500,0,199.9989614,0,0,0,90.00000001 +402.28,50.30085681,-2.528666726,10500,0,199.9998535,0,0,0,90.00000001 +402.29,50.30085681,-2.528638701,10500,0,200.0009685,0,0,0,90.00000001 +402.3,50.30085681,-2.528610675,10500,0,200.0009685,0,0,0,90.00000001 +402.31,50.30085681,-2.52858265,10500,0,199.9998535,0,0,0,90.00000001 +402.32,50.30085681,-2.528554625,10500,0,199.9989614,0,0,0,90.00000001 +402.33,50.30085681,-2.5285266,10500,0,199.9989614,0,0,0,90.00000001 +402.34,50.30085681,-2.528498575,10500,0,199.9998535,0,0,0,90.00000001 +402.35,50.30085681,-2.52847055,10500,0,200.0009685,0,0,0,90.00000001 +402.36,50.30085681,-2.528442524,10500,0,200.0009685,0,0,0,90.00000001 +402.37,50.30085681,-2.528414499,10500,0,199.9998535,0,0,0,90.00000001 +402.38,50.30085681,-2.528386474,10500,0,199.9989614,0,0,0,90.00000001 +402.39,50.30085681,-2.528358449,10500,0,199.9989614,0,0,0,90.00000001 +402.4,50.30085681,-2.528330424,10500,0,199.9998535,0,0,0,90.00000001 +402.41,50.30085681,-2.528302399,10500,0,200.0009685,0,0,0,90.00000001 +402.42,50.30085681,-2.528274373,10500,0,200.0009685,0,0,0,90.00000001 +402.43,50.30085681,-2.528246348,10500,0,199.9998535,0,0,0,90.00000001 +402.44,50.30085681,-2.528218323,10500,0,199.9991844,0,0,0,90.00000001 +402.45,50.30085681,-2.528190298,10500,0,199.9998535,0,0,0,90.00000001 +402.46,50.30085681,-2.528162273,10500,0,200.0009685,0,0,0,90.00000001 +402.47,50.30085681,-2.528134247,10500,0,200.0009685,0,0,0,90.00000001 +402.48,50.30085681,-2.528106222,10500,0,199.9998535,0,0,0,90.00000001 +402.49,50.30085681,-2.528078197,10500,0,199.9991844,0,0,0,90.00000001 +402.5,50.30085681,-2.528050172,10500,0,199.9998535,0,0,0,90.00000001 +402.51,50.30085681,-2.528022147,10500,0,200.0009685,0,0,0,90.00000001 +402.52,50.30085681,-2.527994121,10500,0,200.0009685,0,0,0,90.00000001 +402.53,50.30085681,-2.527966096,10500,0,199.9998535,0,0,0,90.00000001 +402.54,50.30085681,-2.527938071,10500,0,199.9991844,0,0,0,90.00000001 +402.55,50.30085681,-2.527910046,10500,0,199.9998535,0,0,0,90.00000001 +402.56,50.30085681,-2.527882021,10500,0,200.0009685,0,0,0,90.00000001 +402.57,50.30085681,-2.527853995,10500,0,200.0009685,0,0,0,90.00000001 +402.58,50.30085681,-2.52782597,10500,0,199.9998535,0,0,0,90.00000001 +402.59,50.30085681,-2.527797945,10500,0,199.9991844,0,0,0,90.00000001 +402.6,50.30085681,-2.52776992,10500,0,199.9998535,0,0,0,90.00000001 +402.61,50.30085681,-2.527741895,10500,0,200.0009685,0,0,0,90.00000001 +402.62,50.30085681,-2.527713869,10500,0,200.0009685,0,0,0,90.00000001 +402.63,50.30085681,-2.527685844,10500,0,199.9998535,0,0,0,90.00000001 +402.64,50.30085681,-2.527657819,10500,0,199.9991844,0,0,0,90.00000001 +402.65,50.30085681,-2.527629794,10500,0,199.9998535,0,0,0,90.00000001 +402.66,50.30085681,-2.527601769,10500,0,200.0009685,0,0,0,90.00000001 +402.67,50.30085681,-2.527573743,10500,0,200.0009685,0,0,0,90.00000001 +402.68,50.30085681,-2.527545718,10500,0,199.9998535,0,0,0,90.00000001 +402.69,50.30085681,-2.527517693,10500,0,199.9989614,0,0,0,90.00000001 +402.7,50.30085681,-2.527489668,10500,0,199.9989614,0,0,0,90.00000001 +402.71,50.30085681,-2.527461643,10500,0,199.9998535,0,0,0,90.00000001 +402.72,50.30085681,-2.527433618,10500,0,200.0009685,0,0,0,90.00000001 +402.73,50.30085681,-2.527405592,10500,0,200.0009685,0,0,0,90.00000001 +402.74,50.30085681,-2.527377567,10500,0,199.9998535,0,0,0,90.00000001 +402.75,50.30085681,-2.527349542,10500,0,199.9989614,0,0,0,90.00000001 +402.76,50.30085681,-2.527321517,10500,0,199.9989614,0,0,0,90.00000001 +402.77,50.30085681,-2.527293492,10500,0,199.9998535,0,0,0,90.00000001 +402.78,50.30085681,-2.527265467,10500,0,200.0009685,0,0,0,90.00000001 +402.79,50.30085681,-2.527237441,10500,0,200.0009685,0,0,0,90.00000001 +402.8,50.30085681,-2.527209416,10500,0,199.9998535,0,0,0,90.00000001 +402.81,50.30085681,-2.527181391,10500,0,199.9989614,0,0,0,90.00000001 +402.82,50.30085681,-2.527153366,10500,0,199.9987384,0,0,0,90.00000001 +402.83,50.30085681,-2.527125341,10500,0,199.9989614,0,0,0,90.00000001 +402.84,50.30085681,-2.527097316,10500,0,199.9998535,0,0,0,90.00000001 +402.85,50.30085681,-2.527069291,10500,0,200.0009685,0,0,0,90.00000001 +402.86,50.30085681,-2.527041265,10500,0,200.0009685,0,0,0,90.00000001 +402.87,50.30085681,-2.52701324,10500,0,199.9998535,0,0,0,90.00000001 +402.88,50.30085681,-2.526985215,10500,0,199.9989614,0,0,0,90.00000001 +402.89,50.30085681,-2.52695719,10500,0,199.9989614,0,0,0,90.00000001 +402.9,50.30085681,-2.526929165,10500,0,199.9998535,0,0,0,90.00000001 +402.91,50.30085681,-2.52690114,10500,0,200.0009685,0,0,0,90.00000001 +402.92,50.30085681,-2.526873114,10500,0,200.0009685,0,0,0,90.00000001 +402.93,50.30085681,-2.526845089,10500,0,199.9998535,0,0,0,90.00000001 +402.94,50.30085681,-2.526817064,10500,0,199.9989614,0,0,0,90.00000001 +402.95,50.30085681,-2.526789039,10500,0,199.9989614,0,0,0,90.00000001 +402.96,50.30085681,-2.526761014,10500,0,199.9998535,0,0,0,90.00000001 +402.97,50.30085681,-2.526732989,10500,0,200.0009685,0,0,0,90.00000001 +402.98,50.30085681,-2.526704963,10500,0,200.0009685,0,0,0,90.00000001 +402.99,50.30085681,-2.526676938,10500,0,199.9998535,0,0,0,90.00000001 +403,50.30085681,-2.526648913,10500,0,199.9989614,0,0,0,90.00000001 +403.01,50.30085681,-2.526620888,10500,0,199.9989614,0,0,0,90.00000001 +403.02,50.30085681,-2.526592863,10500,0,199.9998535,0,0,0,90.00000001 +403.03,50.30085681,-2.526564838,10500,0,200.0009685,0,0,0,90.00000001 +403.04,50.30085681,-2.526536812,10500,0,200.0009685,0,0,0,90.00000001 +403.05,50.30085681,-2.526508787,10500,0,199.9998535,0,0,0,90.00000001 +403.06,50.30085681,-2.526480762,10500,0,199.9991844,0,0,0,90.00000001 +403.07,50.30085681,-2.526452737,10500,0,199.9998535,0,0,0,90.00000001 +403.08,50.30085681,-2.526424712,10500,0,200.0009685,0,0,0,90.00000001 +403.09,50.30085681,-2.526396686,10500,0,200.0009685,0,0,0,90.00000001 +403.1,50.30085681,-2.526368661,10500,0,199.9998535,0,0,0,90.00000001 +403.11,50.30085681,-2.526340636,10500,0,199.9991844,0,0,0,90.00000001 +403.12,50.30085681,-2.526312611,10500,0,199.9998535,0,0,0,90.00000001 +403.13,50.30085681,-2.526284586,10500,0,200.0009685,0,0,0,90.00000001 +403.14,50.30085681,-2.52625656,10500,0,200.0009685,0,0,0,90.00000001 +403.15,50.30085681,-2.526228535,10500,0,199.9998535,0,0,0,90.00000001 +403.16,50.30085681,-2.52620051,10500,0,199.9991844,0,0,0,90.00000001 +403.17,50.30085681,-2.526172485,10500,0,199.9998535,0,0,0,90.00000001 +403.18,50.30085681,-2.52614446,10500,0,200.0009685,0,0,0,90.00000001 +403.19,50.30085681,-2.526116434,10500,0,200.0009685,0,0,0,90.00000001 +403.2,50.30085681,-2.526088409,10500,0,199.9998535,0,0,0,90.00000001 +403.21,50.30085681,-2.526060384,10500,0,199.9991844,0,0,0,90.00000001 +403.22,50.30085681,-2.526032359,10500,0,199.9998535,0,0,0,90.00000001 +403.23,50.30085681,-2.526004334,10500,0,200.0009685,0,0,0,90.00000001 +403.24,50.30085681,-2.525976308,10500,0,200.0009685,0,0,0,90.00000001 +403.25,50.30085681,-2.525948283,10500,0,199.9998535,0,0,0,90.00000001 +403.26,50.30085681,-2.525920258,10500,0,199.9991844,0,0,0,90.00000001 +403.27,50.30085681,-2.525892233,10500,0,199.9998535,0,0,0,90.00000001 +403.28,50.30085681,-2.525864208,10500,0,200.0009685,0,0,0,90.00000001 +403.29,50.30085681,-2.525836182,10500,0,200.0009685,0,0,0,90.00000001 +403.3,50.30085681,-2.525808157,10500,0,199.9998535,0,0,0,90.00000001 +403.31,50.30085681,-2.525780132,10500,0,199.9989614,0,0,0,90.00000001 +403.32,50.30085681,-2.525752107,10500,0,199.9989614,0,0,0,90.00000001 +403.33,50.30085681,-2.525724082,10500,0,199.9998535,0,0,0,90.00000001 +403.34,50.30085681,-2.525696057,10500,0,200.0009685,0,0,0,90.00000001 +403.35,50.30085681,-2.525668031,10500,0,200.0009685,0,0,0,90.00000001 +403.36,50.30085681,-2.525640006,10500,0,199.9998535,0,0,0,90.00000001 +403.37,50.30085681,-2.525611981,10500,0,199.9989614,0,0,0,90.00000001 +403.38,50.30085681,-2.525583956,10500,0,199.9987384,0,0,0,90.00000001 +403.39,50.30085681,-2.525555931,10500,0,199.9989614,0,0,0,90.00000001 +403.4,50.30085681,-2.525527906,10500,0,199.9998535,0,0,0,90.00000001 +403.41,50.30085681,-2.525499881,10500,0,200.0009685,0,0,0,90.00000001 +403.42,50.30085681,-2.525471855,10500,0,200.0009685,0,0,0,90.00000001 +403.43,50.30085681,-2.52544383,10500,0,199.9998535,0,0,0,90.00000001 +403.44,50.30085681,-2.525415805,10500,0,199.9989614,0,0,0,90.00000001 +403.45,50.30085681,-2.52538778,10500,0,199.9989614,0,0,0,90.00000001 +403.46,50.30085681,-2.525359755,10500,0,199.9998535,0,0,0,90.00000001 +403.47,50.30085681,-2.52533173,10500,0,200.0009685,0,0,0,90.00000001 +403.48,50.30085681,-2.525303704,10500,0,200.0009685,0,0,0,90.00000001 +403.49,50.30085681,-2.525275679,10500,0,199.9998535,0,0,0,90.00000001 +403.5,50.30085681,-2.525247654,10500,0,199.9989614,0,0,0,90.00000001 +403.51,50.30085681,-2.525219629,10500,0,199.9989614,0,0,0,90.00000001 +403.52,50.30085681,-2.525191604,10500,0,199.9998535,0,0,0,90.00000001 +403.53,50.30085681,-2.525163579,10500,0,200.0009685,0,0,0,90.00000001 +403.54,50.30085681,-2.525135553,10500,0,200.0009685,0,0,0,90.00000001 +403.55,50.30085681,-2.525107528,10500,0,199.9998535,0,0,0,90.00000001 +403.56,50.30085681,-2.525079503,10500,0,199.9989614,0,0,0,90.00000001 +403.57,50.30085681,-2.525051478,10500,0,199.9989614,0,0,0,90.00000001 +403.58,50.30085681,-2.525023453,10500,0,199.9998535,0,0,0,90.00000001 +403.59,50.30085681,-2.524995428,10500,0,200.0009685,0,0,0,90.00000001 +403.6,50.30085681,-2.524967402,10500,0,200.0009685,0,0,0,90.00000001 +403.61,50.30085681,-2.524939377,10500,0,199.9998535,0,0,0,90.00000001 +403.62,50.30085681,-2.524911352,10500,0,199.9989614,0,0,0,90.00000001 +403.63,50.30085681,-2.524883327,10500,0,199.9989614,0,0,0,90.00000001 +403.64,50.30085681,-2.524855302,10500,0,199.9998535,0,0,0,90.00000001 +403.65,50.30085681,-2.524827277,10500,0,200.0009685,0,0,0,90.00000001 +403.66,50.30085681,-2.524799251,10500,0,200.0009685,0,0,0,90.00000001 +403.67,50.30085681,-2.524771226,10500,0,199.9998535,0,0,0,90.00000001 +403.68,50.30085681,-2.524743201,10500,0,199.9991844,0,0,0,90.00000001 +403.69,50.30085681,-2.524715176,10500,0,199.9998535,0,0,0,90.00000001 +403.7,50.30085681,-2.524687151,10500,0,200.0009685,0,0,0,90.00000001 +403.71,50.30085681,-2.524659125,10500,0,200.0009685,0,0,0,90.00000001 +403.72,50.30085681,-2.5246311,10500,0,199.9998535,0,0,0,90.00000001 +403.73,50.30085681,-2.524603075,10500,0,199.9991844,0,0,0,90.00000001 +403.74,50.30085681,-2.52457505,10500,0,199.9998535,0,0,0,90.00000001 +403.75,50.30085681,-2.524547025,10500,0,200.0009685,0,0,0,90.00000001 +403.76,50.30085681,-2.524518999,10500,0,200.0009685,0,0,0,90.00000001 +403.77,50.30085681,-2.524490974,10500,0,199.9998535,0,0,0,90.00000001 +403.78,50.30085681,-2.524462949,10500,0,199.9991844,0,0,0,90.00000001 +403.79,50.30085681,-2.524434924,10500,0,199.9998535,0,0,0,90.00000001 +403.8,50.30085681,-2.524406899,10500,0,200.0009685,0,0,0,90.00000001 +403.81,50.30085681,-2.524378873,10500,0,200.0009685,0,0,0,90.00000001 +403.82,50.30085681,-2.524350848,10500,0,199.9998535,0,0,0,90.00000001 +403.83,50.30085681,-2.524322823,10500,0,199.9991844,0,0,0,90.00000001 +403.84,50.30085681,-2.524294798,10500,0,199.9998535,0,0,0,90.00000001 +403.85,50.30085681,-2.524266773,10500,0,200.0009685,0,0,0,90.00000001 +403.86,50.30085681,-2.524238747,10500,0,200.0009685,0,0,0,90.00000001 +403.87,50.30085681,-2.524210722,10500,0,199.9998535,0,0,0,90.00000001 +403.88,50.30085681,-2.524182697,10500,0,199.9991844,0,0,0,90.00000001 +403.89,50.30085681,-2.524154672,10500,0,199.9998535,0,0,0,90.00000001 +403.9,50.30085681,-2.524126647,10500,0,200.0009685,0,0,0,90.00000001 +403.91,50.30085681,-2.524098621,10500,0,200.0009685,0,0,0,90.00000001 +403.92,50.30085681,-2.524070596,10500,0,199.9998535,0,0,0,90.00000001 +403.93,50.30085681,-2.524042571,10500,0,199.9989614,0,0,0,90.00000001 +403.94,50.30085681,-2.524014546,10500,0,199.9987384,0,0,0,90.00000001 +403.95,50.30085681,-2.523986521,10500,0,199.9989614,0,0,0,90.00000001 +403.96,50.30085681,-2.523958496,10500,0,199.9998535,0,0,0,90.00000001 +403.97,50.30085681,-2.523930471,10500,0,200.0009685,0,0,0,90.00000001 +403.98,50.30085681,-2.523902445,10500,0,200.0009685,0,0,0,90.00000001 +403.99,50.30085681,-2.52387442,10500,0,199.9998535,0,0,0,90.00000001 +404,50.30085681,-2.523846395,10500,0,199.9989614,0,0,0,90.00000001 +404.01,50.30085681,-2.52381837,10500,0,199.9989614,0,0,0,90.00000001 +404.02,50.30085681,-2.523790345,10500,0,199.9998535,0,0,0,90.00000001 +404.03,50.30085681,-2.52376232,10500,0,200.0009685,0,0,0,90.00000001 +404.04,50.30085681,-2.523734294,10500,0,200.0009685,0,0,0,90.00000001 +404.05,50.30085681,-2.523706269,10500,0,199.9998535,0,0,0,90.00000001 +404.06,50.30085681,-2.523678244,10500,0,199.9989614,0,0,0,90.00000001 +404.07,50.30085681,-2.523650219,10500,0,199.9989614,0,0,0,90.00000001 +404.08,50.30085681,-2.523622194,10500,0,199.9998535,0,0,0,90.00000001 +404.09,50.30085681,-2.523594169,10500,0,200.0009685,0,0,0,90.00000001 +404.1,50.30085681,-2.523566143,10500,0,200.0009685,0,0,0,90.00000001 +404.11,50.30085681,-2.523538118,10500,0,199.9998535,0,0,0,90.00000001 +404.12,50.30085681,-2.523510093,10500,0,199.9989614,0,0,0,90.00000001 +404.13,50.30085681,-2.523482068,10500,0,199.9989614,0,0,0,90.00000001 +404.14,50.30085681,-2.523454043,10500,0,199.9998535,0,0,0,90.00000001 +404.15,50.30085681,-2.523426018,10500,0,200.0009685,0,0,0,90.00000001 +404.16,50.30085681,-2.523397992,10500,0,200.0009685,0,0,0,90.00000001 +404.17,50.30085681,-2.523369967,10500,0,199.9998535,0,0,0,90.00000001 +404.18,50.30085681,-2.523341942,10500,0,199.9989614,0,0,0,90.00000001 +404.19,50.30085681,-2.523313917,10500,0,199.9989614,0,0,0,90.00000001 +404.2,50.30085681,-2.523285892,10500,0,199.9998535,0,0,0,90.00000001 +404.21,50.30085681,-2.523257867,10500,0,200.0009685,0,0,0,90.00000001 +404.22,50.30085681,-2.523229841,10500,0,200.0009685,0,0,0,90.00000001 +404.23,50.30085681,-2.523201816,10500,0,199.9998535,0,0,0,90.00000001 +404.24,50.30085681,-2.523173791,10500,0,199.9989614,0,0,0,90.00000001 +404.25,50.30085681,-2.523145766,10500,0,199.9989614,0,0,0,90.00000001 +404.26,50.30085681,-2.523117741,10500,0,199.9998535,0,0,0,90.00000001 +404.27,50.30085681,-2.523089716,10500,0,200.0009685,0,0,0,90.00000001 +404.28,50.30085681,-2.52306169,10500,0,200.0009685,0,0,0,90.00000001 +404.29,50.30085681,-2.523033665,10500,0,199.9998535,0,0,0,90.00000001 +404.3,50.30085681,-2.52300564,10500,0,199.9991844,0,0,0,90.00000001 +404.31,50.30085681,-2.522977615,10500,0,199.9998535,0,0,0,90.00000001 +404.32,50.30085681,-2.52294959,10500,0,200.0009685,0,0,0,90.00000001 +404.33,50.30085681,-2.522921564,10500,0,200.0009685,0,0,0,90.00000001 +404.34,50.30085681,-2.522893539,10500,0,199.9998535,0,0,0,90.00000001 +404.35,50.30085681,-2.522865514,10500,0,199.9991844,0,0,0,90.00000001 +404.36,50.30085681,-2.522837489,10500,0,199.9998535,0,0,0,90.00000001 +404.37,50.30085681,-2.522809464,10500,0,200.0009685,0,0,0,90.00000001 +404.38,50.30085681,-2.522781438,10500,0,200.0009685,0,0,0,90.00000001 +404.39,50.30085681,-2.522753413,10500,0,199.9998535,0,0,0,90.00000001 +404.4,50.30085681,-2.522725388,10500,0,199.9989614,0,0,0,90.00000001 +404.41,50.30085681,-2.522697363,10500,0,199.9989614,0,0,0,90.00000001 +404.42,50.30085681,-2.522669338,10500,0,199.9998535,0,0,0,90.00000001 +404.43,50.30085681,-2.522641313,10500,0,200.0009685,0,0,0,90.00000001 +404.44,50.30085681,-2.522613287,10500,0,200.0009685,0,0,0,90.00000001 +404.45,50.30085681,-2.522585262,10500,0,199.9998535,0,0,0,90.00000001 +404.46,50.30085681,-2.522557237,10500,0,199.9991844,0,0,0,90.00000001 +404.47,50.30085681,-2.522529212,10500,0,199.9998535,0,0,0,90.00000001 +404.48,50.30085681,-2.522501187,10500,0,200.0009685,0,0,0,90.00000001 +404.49,50.30085681,-2.522473161,10500,0,200.0009685,0,0,0,90.00000001 +404.5,50.30085681,-2.522445136,10500,0,199.9998535,0,0,0,90.00000001 +404.51,50.30085681,-2.522417111,10500,0,199.9991844,0,0,0,90.00000001 +404.52,50.30085681,-2.522389086,10500,0,199.9998535,0,0,0,90.00000001 +404.53,50.30085681,-2.522361061,10500,0,200.0009685,0,0,0,90.00000001 +404.54,50.30085681,-2.522333035,10500,0,200.0009685,0,0,0,90.00000001 +404.55,50.30085681,-2.52230501,10500,0,199.9998535,0,0,0,90.00000001 +404.56,50.30085681,-2.522276985,10500,0,199.9989614,0,0,0,90.00000001 +404.57,50.30085681,-2.52224896,10500,0,199.9989614,0,0,0,90.00000001 +404.58,50.30085681,-2.522220935,10500,0,199.9998535,0,0,0,90.00000001 +404.59,50.30085681,-2.52219291,10500,0,200.0009685,0,0,0,90.00000001 +404.6,50.30085681,-2.522164884,10500,0,200.0009685,0,0,0,90.00000001 +404.61,50.30085681,-2.522136859,10500,0,199.9998535,0,0,0,90.00000001 +404.62,50.30085681,-2.522108834,10500,0,199.9989614,0,0,0,90.00000001 +404.63,50.30085681,-2.522080809,10500,0,199.9989614,0,0,0,90.00000001 +404.64,50.30085681,-2.522052784,10500,0,199.9998535,0,0,0,90.00000001 +404.65,50.30085681,-2.522024759,10500,0,200.0009685,0,0,0,90.00000001 +404.66,50.30085681,-2.521996733,10500,0,200.0009685,0,0,0,90.00000001 +404.67,50.30085681,-2.521968708,10500,0,199.9998535,0,0,0,90.00000001 +404.68,50.30085681,-2.521940683,10500,0,199.9989614,0,0,0,90.00000001 +404.69,50.30085681,-2.521912658,10500,0,199.9989614,0,0,0,90.00000001 +404.7,50.30085681,-2.521884633,10500,0,199.9998535,0,0,0,90.00000001 +404.71,50.30085681,-2.521856608,10500,0,200.0009685,0,0,0,90.00000001 +404.72,50.30085681,-2.521828582,10500,0,200.0009685,0,0,0,90.00000001 +404.73,50.30085681,-2.521800557,10500,0,199.9998535,0,0,0,90.00000001 +404.74,50.30085681,-2.521772532,10500,0,199.9989614,0,0,0,90.00000001 +404.75,50.30085681,-2.521744507,10500,0,199.9989614,0,0,0,90.00000001 +404.76,50.30085681,-2.521716482,10500,0,199.9998535,0,0,0,90.00000001 +404.77,50.30085681,-2.521688457,10500,0,200.0009685,0,0,0,90.00000001 +404.78,50.30085681,-2.521660431,10500,0,200.0009685,0,0,0,90.00000001 +404.79,50.30085681,-2.521632406,10500,0,199.9998535,0,0,0,90.00000001 +404.8,50.30085681,-2.521604381,10500,0,199.9989614,0,0,0,90.00000001 +404.81,50.30085681,-2.521576356,10500,0,199.9987384,0,0,0,90.00000001 +404.82,50.30085681,-2.521548331,10500,0,199.9989614,0,0,0,90.00000001 +404.83,50.30085681,-2.521520306,10500,0,199.9998535,0,0,0,90.00000001 +404.84,50.30085681,-2.521492281,10500,0,200.0009685,0,0,0,90.00000001 +404.85,50.30085681,-2.521464255,10500,0,200.0009685,0,0,0,90.00000001 +404.86,50.30085681,-2.52143623,10500,0,199.9998535,0,0,0,90.00000001 +404.87,50.30085681,-2.521408205,10500,0,199.9989614,0,0,0,90.00000001 +404.88,50.30085681,-2.52138018,10500,0,199.9989614,0,0,0,90.00000001 +404.89,50.30085681,-2.521352155,10500,0,199.9998535,0,0,0,90.00000001 +404.9,50.30085681,-2.52132413,10500,0,200.0009685,0,0,0,90.00000001 +404.91,50.30085681,-2.521296104,10500,0,200.0009685,0,0,0,90.00000001 +404.92,50.30085681,-2.521268079,10500,0,199.9998535,0,0,0,90.00000001 +404.93,50.30085681,-2.521240054,10500,0,199.9991844,0,0,0,90.00000001 +404.94,50.30085681,-2.521212029,10500,0,199.9998535,0,0,0,90.00000001 +404.95,50.30085681,-2.521184004,10500,0,200.0009685,0,0,0,90.00000001 +404.96,50.30085681,-2.521155978,10500,0,200.0009685,0,0,0,90.00000001 +404.97,50.30085681,-2.521127953,10500,0,199.9998535,0,0,0,90.00000001 +404.98,50.30085681,-2.521099928,10500,0,199.9991844,0,0,0,90.00000001 +404.99,50.30085681,-2.521071903,10500,0,199.9998535,0,0,0,90.00000001 +405,50.30085681,-2.521043878,10500,0,200.0009685,0,0,0,90.00000001 +405.01,50.30085681,-2.521015852,10500,0,200.0009685,0,0,0,90.00000001 +405.02,50.30085681,-2.520987827,10500,0,199.9998535,0,0,0,90.00000001 +405.03,50.30085681,-2.520959802,10500,0,199.9991844,0,0,0,90.00000001 +405.04,50.30085681,-2.520931777,10500,0,199.9998535,0,0,0,90.00000001 +405.05,50.30085681,-2.520903752,10500,0,200.0009685,0,0,0,90.00000001 +405.06,50.30085681,-2.520875726,10500,0,200.0009685,0,0,0,90.00000001 +405.07,50.30085681,-2.520847701,10500,0,199.9998535,0,0,0,90.00000001 +405.08,50.30085681,-2.520819676,10500,0,199.9991844,0,0,0,90.00000001 +405.09,50.30085681,-2.520791651,10500,0,199.9998535,0,0,0,90.00000001 +405.1,50.30085681,-2.520763626,10500,0,200.0009685,0,0,0,90.00000001 +405.11,50.30085681,-2.5207356,10500,0,200.0009685,0,0,0,90.00000001 +405.12,50.30085681,-2.520707575,10500,0,199.9998535,0,0,0,90.00000001 +405.13,50.30085681,-2.52067955,10500,0,199.9991844,0,0,0,90.00000001 +405.14,50.30085681,-2.520651525,10500,0,199.9998535,0,0,0,90.00000001 +405.15,50.30085681,-2.5206235,10500,0,200.0009685,0,0,0,90.00000001 +405.16,50.30085681,-2.520595474,10500,0,200.0009685,0,0,0,90.00000001 +405.17,50.30085681,-2.520567449,10500,0,199.9998535,0,0,0,90.00000001 +405.18,50.30085681,-2.520539424,10500,0,199.9989614,0,0,0,90.00000001 +405.19,50.30085681,-2.520511399,10500,0,199.9989614,0,0,0,90.00000001 +405.2,50.30085681,-2.520483374,10500,0,199.9998535,0,0,0,90.00000001 +405.21,50.30085681,-2.520455349,10500,0,200.0009685,0,0,0,90.00000001 +405.22,50.30085681,-2.520427323,10500,0,200.0009685,0,0,0,90.00000001 +405.23,50.30085681,-2.520399298,10500,0,199.9998535,0,0,0,90.00000001 +405.24,50.30085681,-2.520371273,10500,0,199.9989614,0,0,0,90.00000001 +405.25,50.30085681,-2.520343248,10500,0,199.9989614,0,0,0,90.00000001 +405.26,50.30085681,-2.520315223,10500,0,199.9998535,0,0,0,90.00000001 +405.27,50.30085681,-2.520287198,10500,0,200.0009685,0,0,0,90.00000001 +405.28,50.30085681,-2.520259172,10500,0,200.0009685,0,0,0,90.00000001 +405.29,50.30085681,-2.520231147,10500,0,199.9998535,0,0,0,90.00000001 +405.3,50.30085681,-2.520203122,10500,0,199.9989614,0,0,0,90.00000001 +405.31,50.30085681,-2.520175097,10500,0,199.9989614,0,0,0,90.00000001 +405.32,50.30085681,-2.520147072,10500,0,199.9998535,0,0,0,90.00000001 +405.33,50.30085681,-2.520119047,10500,0,200.0009685,0,0,0,90.00000001 +405.34,50.30085681,-2.520091021,10500,0,200.0009685,0,0,0,90.00000001 +405.35,50.30085681,-2.520062996,10500,0,199.9998535,0,0,0,90.00000001 +405.36,50.30085681,-2.520034971,10500,0,199.9989614,0,0,0,90.00000001 +405.37,50.30085681,-2.520006946,10500,0,199.9987384,0,0,0,90.00000001 +405.38,50.30085681,-2.519978921,10500,0,199.9989614,0,0,0,90.00000001 +405.39,50.30085681,-2.519950896,10500,0,199.9998535,0,0,0,90.00000001 +405.4,50.30085681,-2.519922871,10500,0,200.0009685,0,0,0,90.00000001 +405.41,50.30085681,-2.519894845,10500,0,200.0009685,0,0,0,90.00000001 +405.42,50.30085681,-2.51986682,10500,0,199.9998535,0,0,0,90.00000001 +405.43,50.30085681,-2.519838795,10500,0,199.9989614,0,0,0,90.00000001 +405.44,50.30085681,-2.51981077,10500,0,199.9989614,0,0,0,90.00000001 +405.45,50.30085681,-2.519782745,10500,0,199.9998535,0,0,0,90.00000001 +405.46,50.30085681,-2.51975472,10500,0,200.0009685,0,0,0,90.00000001 +405.47,50.30085681,-2.519726694,10500,0,200.0009685,0,0,0,90.00000001 +405.48,50.30085681,-2.519698669,10500,0,199.9998535,0,0,0,90.00000001 +405.49,50.30085681,-2.519670644,10500,0,199.9989614,0,0,0,90.00000001 +405.5,50.30085681,-2.519642619,10500,0,199.9989614,0,0,0,90.00000001 +405.51,50.30085681,-2.519614594,10500,0,199.9998535,0,0,0,90.00000001 +405.52,50.30085681,-2.519586569,10500,0,200.0009685,0,0,0,90.00000001 +405.53,50.30085681,-2.519558543,10500,0,200.0009685,0,0,0,90.00000001 +405.54,50.30085681,-2.519530518,10500,0,199.9998535,0,0,0,90.00000001 +405.55,50.30085681,-2.519502493,10500,0,199.9991844,0,0,0,90.00000001 +405.56,50.30085681,-2.519474468,10500,0,199.9998535,0,0,0,90.00000001 +405.57,50.30085681,-2.519446443,10500,0,200.0009685,0,0,0,90.00000001 +405.58,50.30085681,-2.519418417,10500,0,200.0009685,0,0,0,90.00000001 +405.59,50.30085681,-2.519390392,10500,0,199.9998535,0,0,0,90.00000001 +405.6,50.30085681,-2.519362367,10500,0,199.9991844,0,0,0,90.00000001 +405.61,50.30085681,-2.519334342,10500,0,199.9998535,0,0,0,90.00000001 +405.62,50.30085681,-2.519306317,10500,0,200.0009685,0,0,0,90.00000001 +405.63,50.30085681,-2.519278291,10500,0,200.0009685,0,0,0,90.00000001 +405.64,50.30085681,-2.519250266,10500,0,199.9998535,0,0,0,90.00000001 +405.65,50.30085681,-2.519222241,10500,0,199.9991844,0,0,0,90.00000001 +405.66,50.30085681,-2.519194216,10500,0,199.9998535,0,0,0,90.00000001 +405.67,50.30085681,-2.519166191,10500,0,200.0009685,0,0,0,90.00000001 +405.68,50.30085681,-2.519138165,10500,0,200.0009685,0,0,0,90.00000001 +405.69,50.30085681,-2.51911014,10500,0,199.9998535,0,0,0,90.00000001 +405.7,50.30085681,-2.519082115,10500,0,199.9991844,0,0,0,90.00000001 +405.71,50.30085681,-2.51905409,10500,0,199.9998535,0,0,0,90.00000001 +405.72,50.30085681,-2.519026065,10500,0,200.0009685,0,0,0,90.00000001 +405.73,50.30085681,-2.518998039,10500,0,200.0009685,0,0,0,90.00000001 +405.74,50.30085681,-2.518970014,10500,0,199.9998535,0,0,0,90.00000001 +405.75,50.30085681,-2.518941989,10500,0,199.9991844,0,0,0,90.00000001 +405.76,50.30085681,-2.518913964,10500,0,199.9998535,0,0,0,90.00000001 +405.77,50.30085681,-2.518885939,10500,0,200.0009685,0,0,0,90.00000001 +405.78,50.30085681,-2.518857913,10500,0,200.0009685,0,0,0,90.00000001 +405.79,50.30085681,-2.518829888,10500,0,199.9998535,0,0,0,90.00000001 +405.8,50.30085681,-2.518801863,10500,0,199.9989614,0,0,0,90.00000001 +405.81,50.30085681,-2.518773838,10500,0,199.9989614,0,0,0,90.00000001 +405.82,50.30085681,-2.518745813,10500,0,199.9998535,0,0,0,90.00000001 +405.83,50.30085681,-2.518717788,10500,0,200.0009685,0,0,0,90.00000001 +405.84,50.30085681,-2.518689762,10500,0,200.0009685,0,0,0,90.00000001 +405.85,50.30085681,-2.518661737,10500,0,199.9998535,0,0,0,90.00000001 +405.86,50.30085681,-2.518633712,10500,0,199.9989614,0,0,0,90.00000001 +405.87,50.30085681,-2.518605687,10500,0,199.9989614,0,0,0,90.00000001 +405.88,50.30085681,-2.518577662,10500,0,199.9998535,0,0,0,90.00000001 +405.89,50.30085681,-2.518549637,10500,0,200.0009685,0,0,0,90.00000001 +405.9,50.30085681,-2.518521611,10500,0,200.0009685,0,0,0,90.00000001 +405.91,50.30085681,-2.518493586,10500,0,199.9998535,0,0,0,90.00000001 +405.92,50.30085681,-2.518465561,10500,0,199.9989614,0,0,0,90.00000001 +405.93,50.30085681,-2.518437536,10500,0,199.9989614,0,0,0,90.00000001 +405.94,50.30085681,-2.518409511,10500,0,199.9998535,0,0,0,90.00000001 +405.95,50.30085681,-2.518381486,10500,0,200.0009685,0,0,0,90.00000001 +405.96,50.30085681,-2.51835346,10500,0,200.0009685,0,0,0,90.00000001 +405.97,50.30085681,-2.518325435,10500,0,199.9998535,0,0,0,90.00000001 +405.98,50.30085681,-2.51829741,10500,0,199.9989614,0,0,0,90.00000001 +405.99,50.30085681,-2.518269385,10500,0,199.9987384,0,0,0,90.00000001 +406,50.30085681,-2.51824136,10500,0,199.9989614,0,0,0,90.00000001 +406.01,50.30085681,-2.518213335,10500,0,199.9998535,0,0,0,90.00000001 +406.02,50.30085681,-2.51818531,10500,0,200.0009685,0,0,0,90.00000001 +406.03,50.30085681,-2.518157284,10500,0,200.0009685,0,0,0,90.00000001 +406.04,50.30085681,-2.518129259,10500,0,199.9998535,0,0,0,90.00000001 +406.05,50.30085681,-2.518101234,10500,0,199.9989614,0,0,0,90.00000001 +406.06,50.30085681,-2.518073209,10500,0,199.9989614,0,0,0,90.00000001 +406.07,50.30085681,-2.518045184,10500,0,199.9998535,0,0,0,90.00000001 +406.08,50.30085681,-2.518017159,10500,0,200.0009685,0,0,0,90.00000001 +406.09,50.30085681,-2.517989133,10500,0,200.0009685,0,0,0,90.00000001 +406.1,50.30085681,-2.517961108,10500,0,199.9998535,0,0,0,90.00000001 +406.11,50.30085681,-2.517933083,10500,0,199.9989614,0,0,0,90.00000001 +406.12,50.30085681,-2.517905058,10500,0,199.9989614,0,0,0,90.00000001 +406.13,50.30085681,-2.517877033,10500,0,199.9998535,0,0,0,90.00000001 +406.14,50.30085681,-2.517849008,10500,0,200.0009685,0,0,0,90.00000001 +406.15,50.30085681,-2.517820982,10500,0,200.0009685,0,0,0,90.00000001 +406.16,50.30085681,-2.517792957,10500,0,199.9998535,0,0,0,90.00000001 +406.17,50.30085681,-2.517764932,10500,0,199.9991844,0,0,0,90.00000001 +406.18,50.30085681,-2.517736907,10500,0,199.9998535,0,0,0,90.00000001 +406.19,50.30085681,-2.517708882,10500,0,200.0009685,0,0,0,90.00000001 +406.2,50.30085681,-2.517680856,10500,0,200.0009685,0,0,0,90.00000001 +406.21,50.30085681,-2.517652831,10500,0,199.9998535,0,0,0,90.00000001 +406.22,50.30085681,-2.517624806,10500,0,199.9991844,0,0,0,90.00000001 +406.23,50.30085681,-2.517596781,10500,0,199.9998535,0,0,0,90.00000001 +406.24,50.30085681,-2.517568756,10500,0,200.0009685,0,0,0,90.00000001 +406.25,50.30085681,-2.51754073,10500,0,200.0009685,0,0,0,90.00000001 +406.26,50.30085681,-2.517512705,10500,0,199.9998535,0,0,0,90.00000001 +406.27,50.30085681,-2.51748468,10500,0,199.9991844,0,0,0,90.00000001 +406.28,50.30085681,-2.517456655,10500,0,199.9998535,0,0,0,90.00000001 +406.29,50.30085681,-2.51742863,10500,0,200.0009685,0,0,0,90.00000001 +406.3,50.30085681,-2.517400604,10500,0,200.0009685,0,0,0,90.00000001 +406.31,50.30085681,-2.517372579,10500,0,199.9998535,0,0,0,90.00000001 +406.32,50.30085681,-2.517344554,10500,0,199.9991844,0,0,0,90.00000001 +406.33,50.30085681,-2.517316529,10500,0,199.9998535,0,0,0,90.00000001 +406.34,50.30085681,-2.517288504,10500,0,200.0009685,0,0,0,90.00000001 +406.35,50.30085681,-2.517260478,10500,0,200.0009685,0,0,0,90.00000001 +406.36,50.30085681,-2.517232453,10500,0,199.9998535,0,0,0,90.00000001 +406.37,50.30085681,-2.517204428,10500,0,199.9991844,0,0,0,90.00000001 +406.38,50.30085681,-2.517176403,10500,0,199.9998535,0,0,0,90.00000001 +406.39,50.30085681,-2.517148378,10500,0,200.0009685,0,0,0,90.00000001 +406.4,50.30085681,-2.517120352,10500,0,200.0009685,0,0,0,90.00000001 +406.41,50.30085681,-2.517092327,10500,0,199.9998535,0,0,0,90.00000001 +406.42,50.30085681,-2.517064302,10500,0,199.9989614,0,0,0,90.00000001 +406.43,50.30085681,-2.517036277,10500,0,199.9989614,0,0,0,90.00000001 +406.44,50.30085681,-2.517008252,10500,0,199.9998535,0,0,0,90.00000001 +406.45,50.30085681,-2.516980227,10500,0,200.0009685,0,0,0,90.00000001 +406.46,50.30085681,-2.516952201,10500,0,200.0009685,0,0,0,90.00000001 +406.47,50.30085681,-2.516924176,10500,0,199.9998535,0,0,0,90.00000001 +406.48,50.30085681,-2.516896151,10500,0,199.9989614,0,0,0,90.00000001 +406.49,50.30085681,-2.516868126,10500,0,199.9989614,0,0,0,90.00000001 +406.5,50.30085681,-2.516840101,10500,0,199.9998535,0,0,0,90.00000001 +406.51,50.30085681,-2.516812076,10500,0,200.0009685,0,0,0,90.00000001 +406.52,50.30085681,-2.51678405,10500,0,200.0009685,0,0,0,90.00000001 +406.53,50.30085681,-2.516756025,10500,0,199.9998535,0,0,0,90.00000001 +406.54,50.30085681,-2.516728,10500,0,199.9989614,0,0,0,90.00000001 +406.55,50.30085681,-2.516699975,10500,0,199.9987384,0,0,0,90.00000001 +406.56,50.30085681,-2.51667195,10500,0,199.9989614,0,0,0,90.00000001 +406.57,50.30085681,-2.516643925,10500,0,199.9998535,0,0,0,90.00000001 +406.58,50.30085681,-2.5166159,10500,0,200.0009685,0,0,0,90.00000001 +406.59,50.30085681,-2.516587874,10500,0,200.0009685,0,0,0,90.00000001 +406.6,50.30085681,-2.516559849,10500,0,199.9998535,0,0,0,90.00000001 +406.61,50.30085681,-2.516531824,10500,0,199.9989614,0,0,0,90.00000001 +406.62,50.30085681,-2.516503799,10500,0,199.9989614,0,0,0,90.00000001 +406.63,50.30085681,-2.516475774,10500,0,199.9998535,0,0,0,90.00000001 +406.64,50.30085681,-2.516447749,10500,0,200.0009685,0,0,0,90.00000001 +406.65,50.30085681,-2.516419723,10500,0,200.0009685,0,0,0,90.00000001 +406.66,50.30085681,-2.516391698,10500,0,199.9998535,0,0,0,90.00000001 +406.67,50.30085681,-2.516363673,10500,0,199.9989614,0,0,0,90.00000001 +406.68,50.30085681,-2.516335648,10500,0,199.9989614,0,0,0,90.00000001 +406.69,50.30085681,-2.516307623,10500,0,199.9998535,0,0,0,90.00000001 +406.7,50.30085681,-2.516279598,10500,0,200.0009685,0,0,0,90.00000001 +406.71,50.30085681,-2.516251572,10500,0,200.0009685,0,0,0,90.00000001 +406.72,50.30085681,-2.516223547,10500,0,199.9998535,0,0,0,90.00000001 +406.73,50.30085681,-2.516195522,10500,0,199.9989614,0,0,0,90.00000001 +406.74,50.30085681,-2.516167497,10500,0,199.9989614,0,0,0,90.00000001 +406.75,50.30085681,-2.516139472,10500,0,199.9998535,0,0,0,90.00000001 +406.76,50.30085681,-2.516111447,10500,0,200.0009685,0,0,0,90.00000001 +406.77,50.30085681,-2.516083421,10500,0,200.0009685,0,0,0,90.00000001 +406.78,50.30085681,-2.516055396,10500,0,199.9998535,0,0,0,90.00000001 +406.79,50.30085681,-2.516027371,10500,0,199.9989614,0,0,0,90.00000001 +406.8,50.30085681,-2.515999346,10500,0,199.9989614,0,0,0,90.00000001 +406.81,50.30085681,-2.515971321,10500,0,199.9998535,0,0,0,90.00000001 +406.82,50.30085681,-2.515943296,10500,0,200.0009685,0,0,0,90.00000001 +406.83,50.30085681,-2.51591527,10500,0,200.0009685,0,0,0,90.00000001 +406.84,50.30085681,-2.515887245,10500,0,199.9998535,0,0,0,90.00000001 +406.85,50.30085681,-2.51585922,10500,0,199.9991844,0,0,0,90.00000001 +406.86,50.30085681,-2.515831195,10500,0,199.9998535,0,0,0,90.00000001 +406.87,50.30085681,-2.51580317,10500,0,200.0009685,0,0,0,90.00000001 +406.88,50.30085681,-2.515775144,10500,0,200.0009685,0,0,0,90.00000001 +406.89,50.30085681,-2.515747119,10500,0,199.9998535,0,0,0,90.00000001 +406.9,50.30085681,-2.515719094,10500,0,199.9991844,0,0,0,90.00000001 +406.91,50.30085681,-2.515691069,10500,0,199.9998535,0,0,0,90.00000001 +406.92,50.30085681,-2.515663044,10500,0,200.0009685,0,0,0,90.00000001 +406.93,50.30085681,-2.515635018,10500,0,200.0009685,0,0,0,90.00000001 +406.94,50.30085681,-2.515606993,10500,0,199.9998535,0,0,0,90.00000001 +406.95,50.30085681,-2.515578968,10500,0,199.9991844,0,0,0,90.00000001 +406.96,50.30085681,-2.515550943,10500,0,199.9998535,0,0,0,90.00000001 +406.97,50.30085681,-2.515522918,10500,0,200.0009685,0,0,0,90.00000001 +406.98,50.30085681,-2.515494892,10500,0,200.0009685,0,0,0,90.00000001 +406.99,50.30085681,-2.515466867,10500,0,199.9998535,0,0,0,90.00000001 +407,50.30085681,-2.515438842,10500,0,199.9991844,0,0,0,90.00000001 +407.01,50.30085681,-2.515410817,10500,0,199.9998535,0,0,0,90.00000001 +407.02,50.30085681,-2.515382792,10500,0,200.0009685,0,0,0,90.00000001 +407.03,50.30085681,-2.515354766,10500,0,200.0009685,0,0,0,90.00000001 +407.04,50.30085681,-2.515326741,10500,0,199.9998535,0,0,0,90.00000001 +407.05,50.30085681,-2.515298716,10500,0,199.9991844,0,0,0,90.00000001 +407.06,50.30085681,-2.515270691,10500,0,199.9998535,0,0,0,90.00000001 +407.07,50.30085681,-2.515242666,10500,0,200.0009685,0,0,0,90.00000001 +407.08,50.30085681,-2.51521464,10500,0,200.0009685,0,0,0,90.00000001 +407.09,50.30085681,-2.515186615,10500,0,199.9998535,0,0,0,90.00000001 +407.1,50.30085681,-2.51515859,10500,0,199.9989614,0,0,0,90.00000001 +407.11,50.30085681,-2.515130565,10500,0,199.9987384,0,0,0,90.00000001 +407.12,50.30085681,-2.51510254,10500,0,199.9989614,0,0,0,90.00000001 +407.13,50.30085681,-2.515074515,10500,0,199.9998535,0,0,0,90.00000001 +407.14,50.30085681,-2.51504649,10500,0,200.0009685,0,0,0,90.00000001 +407.15,50.30085681,-2.515018464,10500,0,200.0009685,0,0,0,90.00000001 +407.16,50.30085681,-2.514990439,10500,0,199.9998535,0,0,0,90.00000001 +407.17,50.30085681,-2.514962414,10500,0,199.9989614,0,0,0,90.00000001 +407.18,50.30085681,-2.514934389,10500,0,199.9989614,0,0,0,90.00000001 +407.19,50.30085681,-2.514906364,10500,0,199.9998535,0,0,0,90.00000001 +407.2,50.30085681,-2.514878339,10500,0,200.0009685,0,0,0,90.00000001 +407.21,50.30085681,-2.514850313,10500,0,200.0009685,0,0,0,90.00000001 +407.22,50.30085681,-2.514822288,10500,0,199.9998535,0,0,0,90.00000001 +407.23,50.30085681,-2.514794263,10500,0,199.9989614,0,0,0,90.00000001 +407.24,50.30085681,-2.514766238,10500,0,199.9989614,0,0,0,90.00000001 +407.25,50.30085681,-2.514738213,10500,0,199.9998535,0,0,0,90.00000001 +407.26,50.30085681,-2.514710188,10500,0,200.0009685,0,0,0,90.00000001 +407.27,50.30085681,-2.514682162,10500,0,200.0009685,0,0,0,90.00000001 +407.28,50.30085681,-2.514654137,10500,0,199.9998535,0,0,0,90.00000001 +407.29,50.30085681,-2.514626112,10500,0,199.9989614,0,0,0,90.00000001 +407.3,50.30085681,-2.514598087,10500,0,199.9989614,0,0,0,90.00000001 +407.31,50.30085681,-2.514570062,10500,0,199.9998535,0,0,0,90.00000001 +407.32,50.30085681,-2.514542037,10500,0,200.0009685,0,0,0,90.00000001 +407.33,50.30085681,-2.514514011,10500,0,200.0009685,0,0,0,90.00000001 +407.34,50.30085681,-2.514485986,10500,0,199.9998535,0,0,0,90.00000001 +407.35,50.30085681,-2.514457961,10500,0,199.9989614,0,0,0,90.00000001 +407.36,50.30085681,-2.514429936,10500,0,199.9989614,0,0,0,90.00000001 +407.37,50.30085681,-2.514401911,10500,0,199.9998535,0,0,0,90.00000001 +407.38,50.30085681,-2.514373886,10500,0,200.0009685,0,0,0,90.00000001 +407.39,50.30085681,-2.51434586,10500,0,200.0009685,0,0,0,90.00000001 +407.4,50.30085681,-2.514317835,10500,0,199.9998535,0,0,0,90.00000001 +407.41,50.30085681,-2.51428981,10500,0,199.9989614,0,0,0,90.00000001 +407.42,50.30085681,-2.514261785,10500,0,199.9989614,0,0,0,90.00000001 +407.43,50.30085681,-2.51423376,10500,0,199.9998535,0,0,0,90.00000001 +407.44,50.30085681,-2.514205735,10500,0,200.0009685,0,0,0,90.00000001 +407.45,50.30085681,-2.514177709,10500,0,200.0009685,0,0,0,90.00000001 +407.46,50.30085681,-2.514149684,10500,0,199.9998535,0,0,0,90.00000001 +407.47,50.30085681,-2.514121659,10500,0,199.9991844,0,0,0,90.00000001 +407.48,50.30085681,-2.514093634,10500,0,199.9998535,0,0,0,90.00000001 +407.49,50.30085681,-2.514065609,10500,0,200.0009685,0,0,0,90.00000001 +407.5,50.30085681,-2.514037583,10500,0,200.0009685,0,0,0,90.00000001 +407.51,50.30085681,-2.514009558,10500,0,199.9998535,0,0,0,90.00000001 +407.52,50.30085681,-2.513981533,10500,0,199.9991844,0,0,0,90.00000001 +407.53,50.30085681,-2.513953508,10500,0,199.9998535,0,0,0,90.00000001 +407.54,50.30085681,-2.513925483,10500,0,200.0009685,0,0,0,90.00000001 +407.55,50.30085681,-2.513897457,10500,0,200.0009685,0,0,0,90.00000001 +407.56,50.30085681,-2.513869432,10500,0,199.9998535,0,0,0,90.00000001 +407.57,50.30085681,-2.513841407,10500,0,199.9991844,0,0,0,90.00000001 +407.58,50.30085681,-2.513813382,10500,0,199.9998535,0,0,0,90.00000001 +407.59,50.30085681,-2.513785357,10500,0,200.0009685,0,0,0,90.00000001 +407.6,50.30085681,-2.513757331,10500,0,200.0009685,0,0,0,90.00000001 +407.61,50.30085681,-2.513729306,10500,0,199.9998535,0,0,0,90.00000001 +407.62,50.30085681,-2.513701281,10500,0,199.9991844,0,0,0,90.00000001 +407.63,50.30085681,-2.513673256,10500,0,199.9998535,0,0,0,90.00000001 +407.64,50.30085681,-2.513645231,10500,0,200.0009685,0,0,0,90.00000001 +407.65,50.30085681,-2.513617205,10500,0,200.0009685,0,0,0,90.00000001 +407.66,50.30085681,-2.51358918,10500,0,199.9998535,0,0,0,90.00000001 +407.67,50.30085681,-2.513561155,10500,0,199.9989614,0,0,0,90.00000001 +407.68,50.30085681,-2.51353313,10500,0,199.9989614,0,0,0,90.00000001 +407.69,50.30085681,-2.513505105,10500,0,199.9998535,0,0,0,90.00000001 +407.7,50.30085681,-2.51347708,10500,0,200.0009685,0,0,0,90.00000001 +407.71,50.30085681,-2.513449054,10500,0,200.0009685,0,0,0,90.00000001 +407.72,50.30085681,-2.513421029,10500,0,199.9998535,0,0,0,90.00000001 +407.73,50.30085681,-2.513393004,10500,0,199.9989614,0,0,0,90.00000001 +407.74,50.30085681,-2.513364979,10500,0,199.9989614,0,0,0,90.00000001 +407.75,50.30085681,-2.513336954,10500,0,199.9998535,0,0,0,90.00000001 +407.76,50.30085681,-2.513308929,10500,0,200.0009685,0,0,0,90.00000001 +407.77,50.30085681,-2.513280903,10500,0,200.0009685,0,0,0,90.00000001 +407.78,50.30085681,-2.513252878,10500,0,199.9998535,0,0,0,90.00000001 +407.79,50.30085681,-2.513224853,10500,0,199.9989614,0,0,0,90.00000001 +407.8,50.30085681,-2.513196828,10500,0,199.9989614,0,0,0,90.00000001 +407.81,50.30085681,-2.513168803,10500,0,199.9998535,0,0,0,90.00000001 +407.82,50.30085681,-2.513140778,10500,0,200.0009685,0,0,0,90.00000001 +407.83,50.30085681,-2.513112752,10500,0,200.0009685,0,0,0,90.00000001 +407.84,50.30085681,-2.513084727,10500,0,199.9998535,0,0,0,90.00000001 +407.85,50.30085681,-2.513056702,10500,0,199.9989614,0,0,0,90.00000001 +407.86,50.30085681,-2.513028677,10500,0,199.9989614,0,0,0,90.00000001 +407.87,50.30085681,-2.513000652,10500,0,199.9998535,0,0,0,90.00000001 +407.88,50.30085681,-2.512972627,10500,0,200.0009685,0,0,0,90.00000001 +407.89,50.30085681,-2.512944601,10500,0,200.0009685,0,0,0,90.00000001 +407.9,50.30085681,-2.512916576,10500,0,199.9998535,0,0,0,90.00000001 +407.91,50.30085681,-2.512888551,10500,0,199.9989614,0,0,0,90.00000001 +407.92,50.30085681,-2.512860526,10500,0,199.9989614,0,0,0,90.00000001 +407.93,50.30085681,-2.512832501,10500,0,199.9998535,0,0,0,90.00000001 +407.94,50.30085681,-2.512804476,10500,0,200.0009685,0,0,0,90.00000001 +407.95,50.30085681,-2.51277645,10500,0,200.0009685,0,0,0,90.00000001 +407.96,50.30085681,-2.512748425,10500,0,199.9998535,0,0,0,90.00000001 +407.97,50.30085681,-2.5127204,10500,0,199.9989614,0,0,0,90.00000001 +407.98,50.30085681,-2.512692375,10500,0,199.9987384,0,0,0,90.00000001 +407.99,50.30085681,-2.51266435,10500,0,199.9989614,0,0,0,90.00000001 +408,50.30085681,-2.512636325,10500,0,199.9998535,0,0,0,90.00000001 +408.01,50.30085681,-2.5126083,10500,0,200.0009685,0,0,0,90.00000001 +408.02,50.30085681,-2.512580274,10500,0,200.0009685,0,0,0,90.00000001 +408.03,50.30085681,-2.512552249,10500,0,199.9998535,0,0,0,90.00000001 +408.04,50.30085681,-2.512524224,10500,0,199.9991844,0,0,0,90.00000001 +408.05,50.30085681,-2.512496199,10500,0,199.9998535,0,0,0,90.00000001 +408.06,50.30085681,-2.512468174,10500,0,200.0009685,0,0,0,90.00000001 +408.07,50.30085681,-2.512440148,10500,0,200.0009685,0,0,0,90.00000001 +408.08,50.30085681,-2.512412123,10500,0,199.9998535,0,0,0,90.00000001 +408.09,50.30085681,-2.512384098,10500,0,199.9991844,0,0,0,90.00000001 +408.1,50.30085681,-2.512356073,10500,0,199.9998535,0,0,0,90.00000001 +408.11,50.30085681,-2.512328048,10500,0,200.0009685,0,0,0,90.00000001 +408.12,50.30085681,-2.512300022,10500,0,200.0009685,0,0,0,90.00000001 +408.13,50.30085681,-2.512271997,10500,0,199.9998535,0,0,0,90.00000001 +408.14,50.30085681,-2.512243972,10500,0,199.9991844,0,0,0,90.00000001 +408.15,50.30085681,-2.512215947,10500,0,199.9998535,0,0,0,90.00000001 +408.16,50.30085681,-2.512187922,10500,0,200.0009685,0,0,0,90.00000001 +408.17,50.30085681,-2.512159896,10500,0,200.0009685,0,0,0,90.00000001 +408.18,50.30085681,-2.512131871,10500,0,199.9998535,0,0,0,90.00000001 +408.19,50.30085681,-2.512103846,10500,0,199.9991844,0,0,0,90.00000001 +408.2,50.30085681,-2.512075821,10500,0,199.9998535,0,0,0,90.00000001 +408.21,50.30085681,-2.512047796,10500,0,200.0009685,0,0,0,90.00000001 +408.22,50.30085681,-2.51201977,10500,0,200.0009685,0,0,0,90.00000001 +408.23,50.30085681,-2.511991745,10500,0,199.9998535,0,0,0,90.00000001 +408.24,50.30085681,-2.51196372,10500,0,199.9991844,0,0,0,90.00000001 +408.25,50.30085681,-2.511935695,10500,0,199.9998535,0,0,0,90.00000001 +408.26,50.30085681,-2.51190767,10500,0,200.0009685,0,0,0,90.00000001 +408.27,50.30085681,-2.511879644,10500,0,200.0009685,0,0,0,90.00000001 +408.28,50.30085681,-2.511851619,10500,0,199.9998535,0,0,0,90.00000001 +408.29,50.30085681,-2.511823594,10500,0,199.9989614,0,0,0,90.00000001 +408.3,50.30085681,-2.511795569,10500,0,199.9989614,0,0,0,90.00000001 +408.31,50.30085681,-2.511767544,10500,0,199.9998535,0,0,0,90.00000001 +408.32,50.30085681,-2.511739519,10500,0,200.0009685,0,0,0,90.00000001 +408.33,50.30085681,-2.511711493,10500,0,200.0009685,0,0,0,90.00000001 +408.34,50.30085681,-2.511683468,10500,0,199.9998535,0,0,0,90.00000001 +408.35,50.30085681,-2.511655443,10500,0,199.9989614,0,0,0,90.00000001 +408.36,50.30085681,-2.511627418,10500,0,199.9989614,0,0,0,90.00000001 +408.37,50.30085681,-2.511599393,10500,0,199.9998535,0,0,0,90.00000001 +408.38,50.30085681,-2.511571368,10500,0,200.0009685,0,0,0,90.00000001 +408.39,50.30085681,-2.511543342,10500,0,200.0009685,0,0,0,90.00000001 +408.4,50.30085681,-2.511515317,10500,0,199.9998535,0,0,0,90.00000001 +408.41,50.30085681,-2.511487292,10500,0,199.9989614,0,0,0,90.00000001 +408.42,50.30085681,-2.511459267,10500,0,199.9989614,0,0,0,90.00000001 +408.43,50.30085681,-2.511431242,10500,0,199.9998535,0,0,0,90.00000001 +408.44,50.30085681,-2.511403217,10500,0,200.0009685,0,0,0,90.00000001 +408.45,50.30085681,-2.511375191,10500,0,200.0009685,0,0,0,90.00000001 +408.46,50.30085681,-2.511347166,10500,0,199.9998535,0,0,0,90.00000001 +408.47,50.30085681,-2.511319141,10500,0,199.9989614,0,0,0,90.00000001 +408.48,50.30085681,-2.511291116,10500,0,199.9989614,0,0,0,90.00000001 +408.49,50.30085681,-2.511263091,10500,0,199.9998535,0,0,0,90.00000001 +408.5,50.30085681,-2.511235066,10500,0,200.0009685,0,0,0,90.00000001 +408.51,50.30085681,-2.51120704,10500,0,200.0009685,0,0,0,90.00000001 +408.52,50.30085681,-2.511179015,10500,0,199.9998535,0,0,0,90.00000001 +408.53,50.30085681,-2.51115099,10500,0,199.9989614,0,0,0,90.00000001 +408.54,50.30085681,-2.511122965,10500,0,199.9987384,0,0,0,90.00000001 +408.55,50.30085681,-2.51109494,10500,0,199.9989614,0,0,0,90.00000001 +408.56,50.30085681,-2.511066915,10500,0,199.9998535,0,0,0,90.00000001 +408.57,50.30085681,-2.51103889,10500,0,200.0009685,0,0,0,90.00000001 +408.58,50.30085681,-2.511010864,10500,0,200.0009685,0,0,0,90.00000001 +408.59,50.30085681,-2.510982839,10500,0,199.9998535,0,0,0,90.00000001 +408.6,50.30085681,-2.510954814,10500,0,199.9989614,0,0,0,90.00000001 +408.61,50.30085681,-2.510926789,10500,0,199.9989614,0,0,0,90.00000001 +408.62,50.30085681,-2.510898764,10500,0,199.9998535,0,0,0,90.00000001 +408.63,50.30085681,-2.510870739,10500,0,200.0009685,0,0,0,90.00000001 +408.64,50.30085681,-2.510842713,10500,0,200.0009685,0,0,0,90.00000001 +408.65,50.30085681,-2.510814688,10500,0,199.9998535,0,0,0,90.00000001 +408.66,50.30085681,-2.510786663,10500,0,199.9991844,0,0,0,90.00000001 +408.67,50.30085681,-2.510758638,10500,0,199.9998535,0,0,0,90.00000001 +408.68,50.30085681,-2.510730613,10500,0,200.0009685,0,0,0,90.00000001 +408.69,50.30085681,-2.510702587,10500,0,200.0009685,0,0,0,90.00000001 +408.7,50.30085681,-2.510674562,10500,0,199.9998535,0,0,0,90.00000001 +408.71,50.30085681,-2.510646537,10500,0,199.9991844,0,0,0,90.00000001 +408.72,50.30085681,-2.510618512,10500,0,199.9998535,0,0,0,90.00000001 +408.73,50.30085681,-2.510590487,10500,0,200.0009685,0,0,0,90.00000001 +408.74,50.30085681,-2.510562461,10500,0,200.0009685,0,0,0,90.00000001 +408.75,50.30085681,-2.510534436,10500,0,199.9998535,0,0,0,90.00000001 +408.76,50.30085681,-2.510506411,10500,0,199.9991844,0,0,0,90.00000001 +408.77,50.30085681,-2.510478386,10500,0,199.9998535,0,0,0,90.00000001 +408.78,50.30085681,-2.510450361,10500,0,200.0009685,0,0,0,90.00000001 +408.79,50.30085681,-2.510422335,10500,0,200.0009685,0,0,0,90.00000001 +408.8,50.30085681,-2.51039431,10500,0,199.9998535,0,0,0,90.00000001 +408.81,50.30085681,-2.510366285,10500,0,199.9991844,0,0,0,90.00000001 +408.82,50.30085681,-2.51033826,10500,0,199.9998535,0,0,0,90.00000001 +408.83,50.30085681,-2.510310235,10500,0,200.0009685,0,0,0,90.00000001 +408.84,50.30085681,-2.510282209,10500,0,200.0009685,0,0,0,90.00000001 +408.85,50.30085681,-2.510254184,10500,0,199.9998535,0,0,0,90.00000001 +408.86,50.30085681,-2.510226159,10500,0,199.9989614,0,0,0,90.00000001 +408.87,50.30085681,-2.510198134,10500,0,199.9989614,0,0,0,90.00000001 +408.88,50.30085681,-2.510170109,10500,0,199.9998535,0,0,0,90.00000001 +408.89,50.30085681,-2.510142084,10500,0,200.0009685,0,0,0,90.00000001 +408.9,50.30085681,-2.510114058,10500,0,200.0009685,0,0,0,90.00000001 +408.91,50.30085681,-2.510086033,10500,0,199.9998535,0,0,0,90.00000001 +408.92,50.30085681,-2.510058008,10500,0,199.9991844,0,0,0,90.00000001 +408.93,50.30085681,-2.510029983,10500,0,199.9998535,0,0,0,90.00000001 +408.94,50.30085681,-2.510001958,10500,0,200.0009685,0,0,0,90.00000001 +408.95,50.30085681,-2.509973932,10500,0,200.0009685,0,0,0,90.00000001 +408.96,50.30085681,-2.509945907,10500,0,199.9998535,0,0,0,90.00000001 +408.97,50.30085681,-2.509917882,10500,0,199.9989614,0,0,0,90.00000001 +408.98,50.30085681,-2.509889857,10500,0,199.9989614,0,0,0,90.00000001 +408.99,50.30085681,-2.509861832,10500,0,199.9998535,0,0,0,90.00000001 +409,50.30085681,-2.509833807,10500,0,200.0009685,0,0,0,90.00000001 +409.01,50.30085681,-2.509805781,10500,0,200.0009685,0,0,0,90.00000001 +409.02,50.30085681,-2.509777756,10500,0,199.9998535,0,0,0,90.00000001 +409.03,50.30085681,-2.509749731,10500,0,199.9989614,0,0,0,90.00000001 +409.04,50.30085681,-2.509721706,10500,0,199.9989614,0,0,0,90.00000001 +409.05,50.30085681,-2.509693681,10500,0,199.9998535,0,0,0,90.00000001 +409.06,50.30085681,-2.509665656,10500,0,200.0009685,0,0,0,90.00000001 +409.07,50.30085681,-2.50963763,10500,0,200.0009685,0,0,0,90.00000001 +409.08,50.30085681,-2.509609605,10500,0,199.9998535,0,0,0,90.00000001 +409.09,50.30085681,-2.50958158,10500,0,199.9989614,0,0,0,90.00000001 +409.1,50.30085681,-2.509553555,10500,0,199.9987384,0,0,0,90.00000001 +409.11,50.30085681,-2.50952553,10500,0,199.9989614,0,0,0,90.00000001 +409.12,50.30085681,-2.509497505,10500,0,199.9998535,0,0,0,90.00000001 +409.13,50.30085681,-2.50946948,10500,0,200.0009685,0,0,0,90.00000001 +409.14,50.30085681,-2.509441454,10500,0,200.0009685,0,0,0,90.00000001 +409.15,50.30085681,-2.509413429,10500,0,199.9998535,0,0,0,90.00000001 +409.16,50.30085681,-2.509385404,10500,0,199.9989614,0,0,0,90.00000001 +409.17,50.30085681,-2.509357379,10500,0,199.9989614,0,0,0,90.00000001 +409.18,50.30085681,-2.509329354,10500,0,199.9998535,0,0,0,90.00000001 +409.19,50.30085681,-2.509301329,10500,0,200.0009685,0,0,0,90.00000001 +409.2,50.30085681,-2.509273303,10500,0,200.0009685,0,0,0,90.00000001 +409.21,50.30085681,-2.509245278,10500,0,199.9998535,0,0,0,90.00000001 +409.22,50.30085681,-2.509217253,10500,0,199.9989614,0,0,0,90.00000001 +409.23,50.30085681,-2.509189228,10500,0,199.9989614,0,0,0,90.00000001 +409.24,50.30085681,-2.509161203,10500,0,199.9998535,0,0,0,90.00000001 +409.25,50.30085681,-2.509133178,10500,0,200.0009685,0,0,0,90.00000001 +409.26,50.30085681,-2.509105152,10500,0,200.0009685,0,0,0,90.00000001 +409.27,50.30085681,-2.509077127,10500,0,199.9998535,0,0,0,90.00000001 +409.28,50.30085681,-2.509049102,10500,0,199.9989614,0,0,0,90.00000001 +409.29,50.30085681,-2.509021077,10500,0,199.9989614,0,0,0,90.00000001 +409.3,50.30085681,-2.508993052,10500,0,199.9998535,0,0,0,90.00000001 +409.31,50.30085681,-2.508965027,10500,0,200.0009685,0,0,0,90.00000001 +409.32,50.30085681,-2.508937001,10500,0,200.0009685,0,0,0,90.00000001 +409.33,50.30085681,-2.508908976,10500,0,199.9998535,0,0,0,90.00000001 +409.34,50.30085681,-2.508880951,10500,0,199.9991844,0,0,0,90.00000001 +409.35,50.30085681,-2.508852926,10500,0,199.9998535,0,0,0,90.00000001 +409.36,50.30085681,-2.508824901,10500,0,200.0009685,0,0,0,90.00000001 +409.37,50.30085681,-2.508796875,10500,0,200.0009685,0,0,0,90.00000001 +409.38,50.30085681,-2.50876885,10500,0,199.9998535,0,0,0,90.00000001 +409.39,50.30085681,-2.508740825,10500,0,199.9991844,0,0,0,90.00000001 +409.4,50.30085681,-2.5087128,10500,0,199.9998535,0,0,0,90.00000001 +409.41,50.30085681,-2.508684775,10500,0,200.0009685,0,0,0,90.00000001 +409.42,50.30085681,-2.508656749,10500,0,200.0009685,0,0,0,90.00000001 +409.43,50.30085681,-2.508628724,10500,0,199.9998535,0,0,0,90.00000001 +409.44,50.30085681,-2.508600699,10500,0,199.9991844,0,0,0,90.00000001 +409.45,50.30085681,-2.508572674,10500,0,199.9998535,0,0,0,90.00000001 +409.46,50.30085681,-2.508544649,10500,0,200.0009685,0,0,0,90.00000001 +409.47,50.30085681,-2.508516623,10500,0,200.0009685,0,0,0,90.00000001 +409.48,50.30085681,-2.508488598,10500,0,199.9998535,0,0,0,90.00000001 +409.49,50.30085681,-2.508460573,10500,0,199.9991844,0,0,0,90.00000001 +409.5,50.30085681,-2.508432548,10500,0,199.9998535,0,0,0,90.00000001 +409.51,50.30085681,-2.508404523,10500,0,200.0009685,0,0,0,90.00000001 +409.52,50.30085681,-2.508376497,10500,0,200.0009685,0,0,0,90.00000001 +409.53,50.30085681,-2.508348472,10500,0,199.9998535,0,0,0,90.00000001 +409.54,50.30085681,-2.508320447,10500,0,199.9991844,0,0,0,90.00000001 +409.55,50.30085681,-2.508292422,10500,0,199.9998535,0,0,0,90.00000001 +409.56,50.30085681,-2.508264397,10500,0,200.0009685,0,0,0,90.00000001 +409.57,50.30085681,-2.508236371,10500,0,200.0009685,0,0,0,90.00000001 +409.58,50.30085681,-2.508208346,10500,0,199.9998535,0,0,0,90.00000001 +409.59,50.30085681,-2.508180321,10500,0,199.9989614,0,0,0,90.00000001 +409.6,50.30085681,-2.508152296,10500,0,199.9989614,0,0,0,90.00000001 +409.61,50.30085681,-2.508124271,10500,0,199.9998535,0,0,0,90.00000001 +409.62,50.30085681,-2.508096246,10500,0,200.0009685,0,0,0,90.00000001 +409.63,50.30085681,-2.50806822,10500,0,200.0009685,0,0,0,90.00000001 +409.64,50.30085681,-2.508040195,10500,0,199.9998535,0,0,0,90.00000001 +409.65,50.30085681,-2.50801217,10500,0,199.9989614,0,0,0,90.00000001 +409.66,50.30085681,-2.507984145,10500,0,199.9987384,0,0,0,90.00000001 +409.67,50.30085681,-2.50795612,10500,0,199.9989614,0,0,0,90.00000001 +409.68,50.30085681,-2.507928095,10500,0,199.9998535,0,0,0,90.00000001 +409.69,50.30085681,-2.50790007,10500,0,200.0009685,0,0,0,90.00000001 +409.7,50.30085681,-2.507872044,10500,0,200.0009685,0,0,0,90.00000001 +409.71,50.30085681,-2.507844019,10500,0,199.9998535,0,0,0,90.00000001 +409.72,50.30085681,-2.507815994,10500,0,199.9989614,0,0,0,90.00000001 +409.73,50.30085681,-2.507787969,10500,0,199.9989614,0,0,0,90.00000001 +409.74,50.30085681,-2.507759944,10500,0,199.9998535,0,0,0,90.00000001 +409.75,50.30085681,-2.507731919,10500,0,200.0009685,0,0,0,90.00000001 +409.76,50.30085681,-2.507703893,10500,0,200.0009685,0,0,0,90.00000001 +409.77,50.30085681,-2.507675868,10500,0,199.9998535,0,0,0,90.00000001 +409.78,50.30085681,-2.507647843,10500,0,199.9989614,0,0,0,90.00000001 +409.79,50.30085681,-2.507619818,10500,0,199.9989614,0,0,0,90.00000001 +409.8,50.30085681,-2.507591793,10500,0,199.9998535,0,0,0,90.00000001 +409.81,50.30085681,-2.507563768,10500,0,200.0009685,0,0,0,90.00000001 +409.82,50.30085681,-2.507535742,10500,0,200.0009685,0,0,0,90.00000001 +409.83,50.30085681,-2.507507717,10500,0,199.9998535,0,0,0,90.00000001 +409.84,50.30085681,-2.507479692,10500,0,199.9989614,0,0,0,90.00000001 +409.85,50.30085681,-2.507451667,10500,0,199.9989614,0,0,0,90.00000001 +409.86,50.30085681,-2.507423642,10500,0,199.9998535,0,0,0,90.00000001 +409.87,50.30085681,-2.507395617,10500,0,200.0009685,0,0,0,90.00000001 +409.88,50.30085681,-2.507367591,10500,0,200.0009685,0,0,0,90.00000001 +409.89,50.30085681,-2.507339566,10500,0,199.9998535,0,0,0,90.00000001 +409.9,50.30085681,-2.507311541,10500,0,199.9989614,0,0,0,90.00000001 +409.91,50.30085681,-2.507283516,10500,0,199.9989614,0,0,0,90.00000001 +409.92,50.30085681,-2.507255491,10500,0,199.9998535,0,0,0,90.00000001 +409.93,50.30085681,-2.507227466,10500,0,200.0009685,0,0,0,90.00000001 +409.94,50.30085681,-2.50719944,10500,0,200.0009685,0,0,0,90.00000001 +409.95,50.30085681,-2.507171415,10500,0,199.9998535,0,0,0,90.00000001 +409.96,50.30085681,-2.50714339,10500,0,199.9991844,0,0,0,90.00000001 +409.97,50.30085681,-2.507115365,10500,0,199.9998535,0,0,0,90.00000001 +409.98,50.30085681,-2.50708734,10500,0,200.0009685,0,0,0,90.00000001 +409.99,50.30085681,-2.507059314,10500,0,200.0009685,0,0,0,90.00000001 +410,50.30085681,-2.507031289,10500,0,199.9998535,0,0,0,90.00000001 +410.01,50.30085681,-2.507003264,10500,0,199.9991844,0,0,0,90.00000001 +410.02,50.30085681,-2.506975239,10500,0,199.9998535,0,0,0,90.00000001 +410.03,50.30085681,-2.506947214,10500,0,200.0009685,0,0,0,90.00000001 +410.04,50.30085681,-2.506919188,10500,0,200.0009685,0,0,0,90.00000001 +410.05,50.30085681,-2.506891163,10500,0,199.9998535,0,0,0,90.00000001 +410.06,50.30085681,-2.506863138,10500,0,199.9991844,0,0,0,90.00000001 +410.07,50.30085681,-2.506835113,10500,0,199.9998535,0,0,0,90.00000001 +410.08,50.30085681,-2.506807088,10500,0,200.0009685,0,0,0,90.00000001 +410.09,50.30085681,-2.506779062,10500,0,200.0009685,0,0,0,90.00000001 +410.1,50.30085681,-2.506751037,10500,0,199.9998535,0,0,0,90.00000001 +410.11,50.30085681,-2.506723012,10500,0,199.9991844,0,0,0,90.00000001 +410.12,50.30085681,-2.506694987,10500,0,199.9998535,0,0,0,90.00000001 +410.13,50.30085681,-2.506666962,10500,0,200.0009685,0,0,0,90.00000001 +410.14,50.30085681,-2.506638936,10500,0,200.0009685,0,0,0,90.00000001 +410.15,50.30085681,-2.506610911,10500,0,199.9998535,0,0,0,90.00000001 +410.16,50.30085681,-2.506582886,10500,0,199.9991844,0,0,0,90.00000001 +410.17,50.30085681,-2.506554861,10500,0,199.9998535,0,0,0,90.00000001 +410.18,50.30085681,-2.506526836,10500,0,200.0009685,0,0,0,90.00000001 +410.19,50.30085681,-2.50649881,10500,0,200.0009685,0,0,0,90.00000001 +410.2,50.30085681,-2.506470785,10500,0,199.9998535,0,0,0,90.00000001 +410.21,50.30085681,-2.50644276,10500,0,199.9989614,0,0,0,90.00000001 +410.22,50.30085681,-2.506414735,10500,0,199.9989614,0,0,0,90.00000001 +410.23,50.30085681,-2.50638671,10500,0,199.9998535,0,0,0,90.00000001 +410.24,50.30085681,-2.506358685,10500,0,200.0009685,0,0,0,90.00000001 +410.25,50.30085681,-2.506330659,10500,0,200.0009685,0,0,0,90.00000001 +410.26,50.30085681,-2.506302634,10500,0,199.9998535,0,0,0,90.00000001 +410.27,50.30085681,-2.506274609,10500,0,199.9989614,0,0,0,90.00000001 +410.28,50.30085681,-2.506246584,10500,0,199.9987384,0,0,0,90.00000001 +410.29,50.30085681,-2.506218559,10500,0,199.9989614,0,0,0,90.00000001 +410.3,50.30085681,-2.506190534,10500,0,199.9998535,0,0,0,90.00000001 +410.31,50.30085681,-2.506162509,10500,0,200.0009685,0,0,0,90.00000001 +410.32,50.30085681,-2.506134483,10500,0,200.0009685,0,0,0,90.00000001 +410.33,50.30085681,-2.506106458,10500,0,199.9998535,0,0,0,90.00000001 +410.34,50.30085681,-2.506078433,10500,0,199.9989614,0,0,0,90.00000001 +410.35,50.30085681,-2.506050408,10500,0,199.9989614,0,0,0,90.00000001 +410.36,50.30085681,-2.506022383,10500,0,199.9998535,0,0,0,90.00000001 +410.37,50.30085681,-2.505994358,10500,0,200.0009685,0,0,0,90.00000001 +410.38,50.30085681,-2.505966332,10500,0,200.0009685,0,0,0,90.00000001 +410.39,50.30085681,-2.505938307,10500,0,199.9998535,0,0,0,90.00000001 +410.4,50.30085681,-2.505910282,10500,0,199.9989614,0,0,0,90.00000001 +410.41,50.30085681,-2.505882257,10500,0,199.9989614,0,0,0,90.00000001 +410.42,50.30085681,-2.505854232,10500,0,199.9998535,0,0,0,90.00000001 +410.43,50.30085681,-2.505826207,10500,0,200.0009685,0,0,0,90.00000001 +410.44,50.30085681,-2.505798181,10500,0,200.0009685,0,0,0,90.00000001 +410.45,50.30085681,-2.505770156,10500,0,199.9998535,0,0,0,90.00000001 +410.46,50.30085681,-2.505742131,10500,0,199.9989614,0,0,0,90.00000001 +410.47,50.30085681,-2.505714106,10500,0,199.9989614,0,0,0,90.00000001 +410.48,50.30085681,-2.505686081,10500,0,199.9998535,0,0,0,90.00000001 +410.49,50.30085681,-2.505658056,10500,0,200.0009685,0,0,0,90.00000001 +410.5,50.30085681,-2.50563003,10500,0,200.0009685,0,0,0,90.00000001 +410.51,50.30085681,-2.505602005,10500,0,199.9998535,0,0,0,90.00000001 +410.52,50.30085681,-2.50557398,10500,0,199.9989614,0,0,0,90.00000001 +410.53,50.30085681,-2.505545955,10500,0,199.9989614,0,0,0,90.00000001 +410.54,50.30085681,-2.50551793,10500,0,199.9998535,0,0,0,90.00000001 +410.55,50.30085681,-2.505489905,10500,0,200.0009685,0,0,0,90.00000001 +410.56,50.30085681,-2.505461879,10500,0,200.0009685,0,0,0,90.00000001 +410.57,50.30085681,-2.505433854,10500,0,199.9998535,0,0,0,90.00000001 +410.58,50.30085681,-2.505405829,10500,0,199.9991844,0,0,0,90.00000001 +410.59,50.30085681,-2.505377804,10500,0,199.9998535,0,0,0,90.00000001 +410.6,50.30085681,-2.505349779,10500,0,200.0009685,0,0,0,90.00000001 +410.61,50.30085681,-2.505321753,10500,0,200.0009685,0,0,0,90.00000001 +410.62,50.30085681,-2.505293728,10500,0,199.9998535,0,0,0,90.00000001 +410.63,50.30085681,-2.505265703,10500,0,199.9991844,0,0,0,90.00000001 +410.64,50.30085681,-2.505237678,10500,0,199.9998535,0,0,0,90.00000001 +410.65,50.30085681,-2.505209653,10500,0,200.0009685,0,0,0,90.00000001 +410.66,50.30085681,-2.505181627,10500,0,200.0009685,0,0,0,90.00000001 +410.67,50.30085681,-2.505153602,10500,0,199.9998535,0,0,0,90.00000001 +410.68,50.30085681,-2.505125577,10500,0,199.9991844,0,0,0,90.00000001 +410.69,50.30085681,-2.505097552,10500,0,199.9998535,0,0,0,90.00000001 +410.7,50.30085681,-2.505069527,10500,0,200.0009685,0,0,0,90.00000001 +410.71,50.30085681,-2.505041501,10500,0,200.0009685,0,0,0,90.00000001 +410.72,50.30085681,-2.505013476,10500,0,199.9998535,0,0,0,90.00000001 +410.73,50.30085681,-2.504985451,10500,0,199.9991844,0,0,0,90.00000001 +410.74,50.30085681,-2.504957426,10500,0,199.9998535,0,0,0,90.00000001 +410.75,50.30085681,-2.504929401,10500,0,200.0009685,0,0,0,90.00000001 +410.76,50.30085681,-2.504901375,10500,0,200.0009685,0,0,0,90.00000001 +410.77,50.30085681,-2.50487335,10500,0,199.9998535,0,0,0,90.00000001 +410.78,50.30085681,-2.504845325,10500,0,199.9991844,0,0,0,90.00000001 +410.79,50.30085681,-2.5048173,10500,0,199.9998535,0,0,0,90.00000001 +410.8,50.30085681,-2.504789275,10500,0,200.0009685,0,0,0,90.00000001 +410.81,50.30085681,-2.504761249,10500,0,200.0009685,0,0,0,90.00000001 +410.82,50.30085681,-2.504733224,10500,0,199.9998535,0,0,0,90.00000001 +410.83,50.30085681,-2.504705199,10500,0,199.9989614,0,0,0,90.00000001 +410.84,50.30085681,-2.504677174,10500,0,199.9987384,0,0,0,90.00000001 +410.85,50.30085681,-2.504649149,10500,0,199.9989614,0,0,0,90.00000001 +410.86,50.30085681,-2.504621124,10500,0,199.9998535,0,0,0,90.00000001 +410.87,50.30085681,-2.504593099,10500,0,200.0009685,0,0,0,90.00000001 +410.88,50.30085681,-2.504565073,10500,0,200.0009685,0,0,0,90.00000001 +410.89,50.30085681,-2.504537048,10500,0,199.9998535,0,0,0,90.00000001 +410.9,50.30085681,-2.504509023,10500,0,199.9989614,0,0,0,90.00000001 +410.91,50.30085681,-2.504480998,10500,0,199.9989614,0,0,0,90.00000001 +410.92,50.30085681,-2.504452973,10500,0,199.9998535,0,0,0,90.00000001 +410.93,50.30085681,-2.504424948,10500,0,200.0009685,0,0,0,90.00000001 +410.94,50.30085681,-2.504396922,10500,0,200.0009685,0,0,0,90.00000001 +410.95,50.30085681,-2.504368897,10500,0,199.9998535,0,0,0,90.00000001 +410.96,50.30085681,-2.504340872,10500,0,199.9989614,0,0,0,90.00000001 +410.97,50.30085681,-2.504312847,10500,0,199.9989614,0,0,0,90.00000001 +410.98,50.30085681,-2.504284822,10500,0,199.9998535,0,0,0,90.00000001 +410.99,50.30085681,-2.504256797,10500,0,200.0009685,0,0,0,90.00000001 +411,50.30085681,-2.504228771,10500,0,200.0009685,0,0,0,90.00000001 +411.01,50.30085681,-2.504200746,10500,0,199.9998535,0,0,0,90.00000001 +411.02,50.30085681,-2.504172721,10500,0,199.9989614,0,0,0,90.00000001 +411.03,50.30085681,-2.504144696,10500,0,199.9989614,0,0,0,90.00000001 +411.04,50.30085681,-2.504116671,10500,0,199.9998535,0,0,0,90.00000001 +411.05,50.30085681,-2.504088646,10500,0,200.0009685,0,0,0,90.00000001 +411.06,50.30085681,-2.50406062,10500,0,200.0009685,0,0,0,90.00000001 +411.07,50.30085681,-2.504032595,10500,0,199.9998535,0,0,0,90.00000001 +411.08,50.30085681,-2.50400457,10500,0,199.9989614,0,0,0,90.00000001 +411.09,50.30085681,-2.503976545,10500,0,199.9987384,0,0,0,90.00000001 +411.1,50.30085681,-2.50394852,10500,0,199.9989614,0,0,0,90.00000001 +411.11,50.30085681,-2.503920495,10500,0,199.9998535,0,0,0,90.00000001 +411.12,50.30085681,-2.50389247,10500,0,200.0009685,0,0,0,90.00000001 +411.13,50.30085681,-2.503864444,10500,0,200.0009685,0,0,0,90.00000001 +411.14,50.30085681,-2.503836419,10500,0,199.9998535,0,0,0,90.00000001 +411.15,50.30085681,-2.503808394,10500,0,199.9991844,0,0,0,90.00000001 +411.16,50.30085681,-2.503780369,10500,0,199.9998535,0,0,0,90.00000001 +411.17,50.30085681,-2.503752344,10500,0,200.0009685,0,0,0,90.00000001 +411.18,50.30085681,-2.503724318,10500,0,200.0009685,0,0,0,90.00000001 +411.19,50.30085681,-2.503696293,10500,0,199.9998535,0,0,0,90.00000001 +411.2,50.30085681,-2.503668268,10500,0,199.9991844,0,0,0,90.00000001 +411.21,50.30085681,-2.503640243,10500,0,199.9998535,0,0,0,90.00000001 +411.22,50.30085681,-2.503612218,10500,0,200.0009685,0,0,0,90.00000001 +411.23,50.30085681,-2.503584192,10500,0,200.0009685,0,0,0,90.00000001 +411.24,50.30085681,-2.503556167,10500,0,199.9998535,0,0,0,90.00000001 +411.25,50.30085681,-2.503528142,10500,0,199.9989614,0,0,0,90.00000001 +411.26,50.30085681,-2.503500117,10500,0,199.9989614,0,0,0,90.00000001 +411.27,50.30085681,-2.503472092,10500,0,199.9998535,0,0,0,90.00000001 +411.28,50.30085681,-2.503444067,10500,0,200.0009685,0,0,0,90.00000001 +411.29,50.30085681,-2.503416041,10500,0,200.0009685,0,0,0,90.00000001 +411.3,50.30085681,-2.503388016,10500,0,199.9998535,0,0,0,90.00000001 +411.31,50.30085681,-2.503359991,10500,0,199.9991844,0,0,0,90.00000001 +411.32,50.30085681,-2.503331966,10500,0,199.9998535,0,0,0,90.00000001 +411.33,50.30085681,-2.503303941,10500,0,200.0009685,0,0,0,90.00000001 +411.34,50.30085681,-2.503275915,10500,0,200.0009685,0,0,0,90.00000001 +411.35,50.30085681,-2.50324789,10500,0,199.9998535,0,0,0,90.00000001 +411.36,50.30085681,-2.503219865,10500,0,199.9991844,0,0,0,90.00000001 +411.37,50.30085681,-2.50319184,10500,0,199.9998535,0,0,0,90.00000001 +411.38,50.30085681,-2.503163815,10500,0,200.0009685,0,0,0,90.00000001 +411.39,50.30085681,-2.503135789,10500,0,200.0009685,0,0,0,90.00000001 +411.4,50.30085681,-2.503107764,10500,0,199.9998535,0,0,0,90.00000001 +411.41,50.30085681,-2.503079739,10500,0,199.9991844,0,0,0,90.00000001 +411.42,50.30085681,-2.503051714,10500,0,199.9998535,0,0,0,90.00000001 +411.43,50.30085681,-2.503023689,10500,0,200.0009685,0,0,0,90.00000001 +411.44,50.30085681,-2.502995663,10500,0,200.0009685,0,0,0,90.00000001 +411.45,50.30085681,-2.502967638,10500,0,199.9998535,0,0,0,90.00000001 +411.46,50.30085681,-2.502939613,10500,0,199.9989614,0,0,0,90.00000001 +411.47,50.30085681,-2.502911588,10500,0,199.9989614,0,0,0,90.00000001 +411.48,50.30085681,-2.502883563,10500,0,199.9998535,0,0,0,90.00000001 +411.49,50.30085681,-2.502855538,10500,0,200.0009685,0,0,0,90.00000001 +411.5,50.30085681,-2.502827512,10500,0,200.0009685,0,0,0,90.00000001 +411.51,50.30085681,-2.502799487,10500,0,199.9998535,0,0,0,90.00000001 +411.52,50.30085681,-2.502771462,10500,0,199.9989614,0,0,0,90.00000001 +411.53,50.30085681,-2.502743437,10500,0,199.9989614,0,0,0,90.00000001 +411.54,50.30085681,-2.502715412,10500,0,199.9998535,0,0,0,90.00000001 +411.55,50.30085681,-2.502687387,10500,0,200.0009685,0,0,0,90.00000001 +411.56,50.30085681,-2.502659361,10500,0,200.0009685,0,0,0,90.00000001 +411.57,50.30085681,-2.502631336,10500,0,199.9998535,0,0,0,90.00000001 +411.58,50.30085681,-2.502603311,10500,0,199.9989614,0,0,0,90.00000001 +411.59,50.30085681,-2.502575286,10500,0,199.9989614,0,0,0,90.00000001 +411.6,50.30085681,-2.502547261,10500,0,199.9998535,0,0,0,90.00000001 +411.61,50.30085681,-2.502519236,10500,0,200.0009685,0,0,0,90.00000001 +411.62,50.30085681,-2.50249121,10500,0,200.0009685,0,0,0,90.00000001 +411.63,50.30085681,-2.502463185,10500,0,199.9998535,0,0,0,90.00000001 +411.64,50.30085681,-2.50243516,10500,0,199.9989614,0,0,0,90.00000001 +411.65,50.30085681,-2.502407135,10500,0,199.9989614,0,0,0,90.00000001 +411.66,50.30085681,-2.50237911,10500,0,199.9998535,0,0,0,90.00000001 +411.67,50.30085681,-2.502351085,10500,0,200.0009685,0,0,0,90.00000001 +411.68,50.30085681,-2.502323059,10500,0,200.0009685,0,0,0,90.00000001 +411.69,50.30085681,-2.502295034,10500,0,199.9998535,0,0,0,90.00000001 +411.7,50.30085681,-2.502267009,10500,0,199.9989614,0,0,0,90.00000001 +411.71,50.30085681,-2.502238984,10500,0,199.9987384,0,0,0,90.00000001 +411.72,50.30085681,-2.502210959,10500,0,199.9989614,0,0,0,90.00000001 +411.73,50.30085681,-2.502182934,10500,0,199.9998535,0,0,0,90.00000001 +411.74,50.30085681,-2.502154909,10500,0,200.0009685,0,0,0,90.00000001 +411.75,50.30085681,-2.502126883,10500,0,200.0009685,0,0,0,90.00000001 +411.76,50.30085681,-2.502098858,10500,0,199.9998535,0,0,0,90.00000001 +411.77,50.30085681,-2.502070833,10500,0,199.9989614,0,0,0,90.00000001 +411.78,50.30085681,-2.502042808,10500,0,199.9989614,0,0,0,90.00000001 +411.79,50.30085681,-2.502014783,10500,0,199.9998535,0,0,0,90.00000001 +411.8,50.30085681,-2.501986758,10500,0,200.0009685,0,0,0,90.00000001 +411.81,50.30085681,-2.501958732,10500,0,200.0009685,0,0,0,90.00000001 +411.82,50.30085681,-2.501930707,10500,0,199.9998535,0,0,0,90.00000001 +411.83,50.30085681,-2.501902682,10500,0,199.9991844,0,0,0,90.00000001 +411.84,50.30085681,-2.501874657,10500,0,199.9998535,0,0,0,90.00000001 +411.85,50.30085681,-2.501846632,10500,0,200.0009685,0,0,0,90.00000001 +411.86,50.30085681,-2.501818606,10500,0,200.0009685,0,0,0,90.00000001 +411.87,50.30085681,-2.501790581,10500,0,199.9998535,0,0,0,90.00000001 +411.88,50.30085681,-2.501762556,10500,0,199.9991844,0,0,0,90.00000001 +411.89,50.30085681,-2.501734531,10500,0,199.9998535,0,0,0,90.00000001 +411.9,50.30085681,-2.501706506,10500,0,200.0009685,0,0,0,90.00000001 +411.91,50.30085681,-2.50167848,10500,0,200.0009685,0,0,0,90.00000001 +411.92,50.30085681,-2.501650455,10500,0,199.9998535,0,0,0,90.00000001 +411.93,50.30085681,-2.50162243,10500,0,199.9991844,0,0,0,90.00000001 +411.94,50.30085681,-2.501594405,10500,0,199.9998535,0,0,0,90.00000001 +411.95,50.30085681,-2.50156638,10500,0,200.0009685,0,0,0,90.00000001 +411.96,50.30085681,-2.501538354,10500,0,200.0009685,0,0,0,90.00000001 +411.97,50.30085681,-2.501510329,10500,0,199.9998535,0,0,0,90.00000001 +411.98,50.30085681,-2.501482304,10500,0,199.9991844,0,0,0,90.00000001 +411.99,50.30085681,-2.501454279,10500,0,199.9998535,0,0,0,90.00000001 +412,50.30085681,-2.501426254,10500,0,200.0009685,0,0,0,90.00000001 +412.01,50.30085681,-2.501398228,10500,0,200.0009685,0,0,0,90.00000001 +412.02,50.30085681,-2.501370203,10500,0,199.9998535,0,0,0,90.00000001 +412.03,50.30085681,-2.501342178,10500,0,199.9991844,0,0,0,90.00000001 +412.04,50.30085681,-2.501314153,10500,0,199.9998535,0,0,0,90.00000001 +412.05,50.30085681,-2.501286128,10500,0,200.0009685,0,0,0,90.00000001 +412.06,50.30085681,-2.501258102,10500,0,200.0009685,0,0,0,90.00000001 +412.07,50.30085681,-2.501230077,10500,0,199.9998535,0,0,0,90.00000001 +412.08,50.30085681,-2.501202052,10500,0,199.9989614,0,0,0,90.00000001 +412.09,50.30085681,-2.501174027,10500,0,199.9989614,0,0,0,90.00000001 +412.1,50.30085681,-2.501146002,10500,0,199.9998535,0,0,0,90.00000001 +412.11,50.30085681,-2.501117977,10500,0,200.0009685,0,0,0,90.00000001 +412.12,50.30085681,-2.501089951,10500,0,200.0009685,0,0,0,90.00000001 +412.13,50.30085681,-2.501061926,10500,0,199.9998535,0,0,0,90.00000001 +412.14,50.30085681,-2.501033901,10500,0,199.9989614,0,0,0,90.00000001 +412.15,50.30085681,-2.501005876,10500,0,199.9989614,0,0,0,90.00000001 +412.16,50.30085681,-2.500977851,10500,0,199.9998535,0,0,0,90.00000001 +412.17,50.30085681,-2.500949826,10500,0,200.0009685,0,0,0,90.00000001 +412.18,50.30085681,-2.5009218,10500,0,200.0009685,0,0,0,90.00000001 +412.19,50.30085681,-2.500893775,10500,0,199.9998535,0,0,0,90.00000001 +412.2,50.30085681,-2.50086575,10500,0,199.9989614,0,0,0,90.00000001 +412.21,50.30085681,-2.500837725,10500,0,199.9989614,0,0,0,90.00000001 +412.22,50.30085681,-2.5008097,10500,0,199.9998535,0,0,0,90.00000001 +412.23,50.30085681,-2.500781675,10500,0,200.0009685,0,0,0,90.00000001 +412.24,50.30085681,-2.500753649,10500,0,200.0009685,0,0,0,90.00000001 +412.25,50.30085681,-2.500725624,10500,0,199.9998535,0,0,0,90.00000001 +412.26,50.30085681,-2.500697599,10500,0,199.9989614,0,0,0,90.00000001 +412.27,50.30085681,-2.500669574,10500,0,199.9987384,0,0,0,90.00000001 +412.28,50.30085681,-2.500641549,10500,0,199.9989614,0,0,0,90.00000001 +412.29,50.30085681,-2.500613524,10500,0,199.9998535,0,0,0,90.00000001 +412.3,50.30085681,-2.500585499,10500,0,200.0009685,0,0,0,90.00000001 +412.31,50.30085681,-2.500557473,10500,0,200.0009685,0,0,0,90.00000001 +412.32,50.30085681,-2.500529448,10500,0,199.9998535,0,0,0,90.00000001 +412.33,50.30085681,-2.500501423,10500,0,199.9989614,0,0,0,90.00000001 +412.34,50.30085681,-2.500473398,10500,0,199.9989614,0,0,0,90.00000001 +412.35,50.30085681,-2.500445373,10500,0,199.9998535,0,0,0,90.00000001 +412.36,50.30085681,-2.500417348,10500,0,200.0009685,0,0,0,90.00000001 +412.37,50.30085681,-2.500389322,10500,0,200.0009685,0,0,0,90.00000001 +412.38,50.30085681,-2.500361297,10500,0,199.9998535,0,0,0,90.00000001 +412.39,50.30085681,-2.500333272,10500,0,199.9989614,0,0,0,90.00000001 +412.4,50.30085681,-2.500305247,10500,0,199.9989614,0,0,0,90.00000001 +412.41,50.30085681,-2.500277222,10500,0,199.9998535,0,0,0,90.00000001 +412.42,50.30085681,-2.500249197,10500,0,200.0009685,0,0,0,90.00000001 +412.43,50.30085681,-2.500221171,10500,0,200.0009685,0,0,0,90.00000001 +412.44,50.30085681,-2.500193146,10500,0,199.9998535,0,0,0,90.00000001 +412.45,50.30085681,-2.500165121,10500,0,199.9991844,0,0,0,90.00000001 +412.46,50.30085681,-2.500137096,10500,0,199.9998535,0,0,0,90.00000001 +412.47,50.30085681,-2.500109071,10500,0,200.0009685,0,0,0,90.00000001 +412.48,50.30085681,-2.500081045,10500,0,200.0009685,0,0,0,90.00000001 +412.49,50.30085681,-2.50005302,10500,0,199.9998535,0,0,0,90.00000001 +412.5,50.30085681,-2.500024995,10500,0,199.9991844,0,0,0,90.00000001 +412.51,50.30085681,-2.49999697,10500,0,199.9998535,0,0,0,90.00000001 +412.52,50.30085681,-2.499968945,10500,0,200.0009685,0,0,0,90.00000001 +412.53,50.30085681,-2.499940919,10500,0,200.0009685,0,0,0,90.00000001 +412.54,50.30085681,-2.499912894,10500,0,199.9998535,0,0,0,90.00000001 +412.55,50.30085681,-2.499884869,10500,0,199.9991844,0,0,0,90.00000001 +412.56,50.30085681,-2.499856844,10500,0,199.9998535,0,0,0,90.00000001 +412.57,50.30085681,-2.499828819,10500,0,200.0009685,0,0,0,90.00000001 +412.58,50.30085681,-2.499800793,10500,0,200.0009685,0,0,0,90.00000001 +412.59,50.30085681,-2.499772768,10500,0,199.9998535,0,0,0,90.00000001 +412.6,50.30085681,-2.499744743,10500,0,199.9991844,0,0,0,90.00000001 +412.61,50.30085681,-2.499716718,10500,0,199.9998535,0,0,0,90.00000001 +412.62,50.30085681,-2.499688693,10500,0,200.0009685,0,0,0,90.00000001 +412.63,50.30085681,-2.499660667,10500,0,200.0009685,0,0,0,90.00000001 +412.64,50.30085681,-2.499632642,10500,0,199.9998535,0,0,0,90.00000001 +412.65,50.30085681,-2.499604617,10500,0,199.9991844,0,0,0,90.00000001 +412.66,50.30085681,-2.499576592,10500,0,199.9998535,0,0,0,90.00000001 +412.67,50.30085681,-2.499548567,10500,0,200.0009685,0,0,0,90.00000001 +412.68,50.30085681,-2.499520541,10500,0,200.0009685,0,0,0,90.00000001 +412.69,50.30085681,-2.499492516,10500,0,199.9998535,0,0,0,90.00000001 +412.7,50.30085681,-2.499464491,10500,0,199.9989614,0,0,0,90.00000001 +412.71,50.30085681,-2.499436466,10500,0,199.9989614,0,0,0,90.00000001 +412.72,50.30085681,-2.499408441,10500,0,199.9998535,0,0,0,90.00000001 +412.73,50.30085681,-2.499380416,10500,0,200.0009685,0,0,0,90.00000001 +412.74,50.30085681,-2.49935239,10500,0,200.0009685,0,0,0,90.00000001 +412.75,50.30085681,-2.499324365,10500,0,199.9998535,0,0,0,90.00000001 +412.76,50.30085681,-2.49929634,10500,0,199.9989614,0,0,0,90.00000001 +412.77,50.30085681,-2.499268315,10500,0,199.9989614,0,0,0,90.00000001 +412.78,50.30085681,-2.49924029,10500,0,199.9998535,0,0,0,90.00000001 +412.79,50.30085681,-2.499212265,10500,0,200.0009685,0,0,0,90.00000001 +412.8,50.30085681,-2.499184239,10500,0,200.0009685,0,0,0,90.00000001 +412.81,50.30085681,-2.499156214,10500,0,199.9998535,0,0,0,90.00000001 +412.82,50.30085681,-2.499128189,10500,0,199.9989614,0,0,0,90.00000001 +412.83,50.30085681,-2.499100164,10500,0,199.9987384,0,0,0,90.00000001 +412.84,50.30085681,-2.499072139,10500,0,199.9989614,0,0,0,90.00000001 +412.85,50.30085681,-2.499044114,10500,0,199.9998535,0,0,0,90.00000001 +412.86,50.30085681,-2.499016089,10500,0,200.0009685,0,0,0,90.00000001 +412.87,50.30085681,-2.498988063,10500,0,200.0009685,0,0,0,90.00000001 +412.88,50.30085681,-2.498960038,10500,0,199.9998535,0,0,0,90.00000001 +412.89,50.30085681,-2.498932013,10500,0,199.9989614,0,0,0,90.00000001 +412.9,50.30085681,-2.498903988,10500,0,199.9989614,0,0,0,90.00000001 +412.91,50.30085681,-2.498875963,10500,0,199.9998535,0,0,0,90.00000001 +412.92,50.30085681,-2.498847938,10500,0,200.0009685,0,0,0,90.00000001 +412.93,50.30085681,-2.498819912,10500,0,200.0009685,0,0,0,90.00000001 +412.94,50.30085681,-2.498791887,10500,0,199.9998535,0,0,0,90.00000001 +412.95,50.30085681,-2.498763862,10500,0,199.9989614,0,0,0,90.00000001 +412.96,50.30085681,-2.498735837,10500,0,199.9989614,0,0,0,90.00000001 +412.97,50.30085681,-2.498707812,10500,0,199.9998535,0,0,0,90.00000001 +412.98,50.30085681,-2.498679787,10500,0,200.0009685,0,0,0,90.00000001 +412.99,50.30085681,-2.498651761,10500,0,200.0009685,0,0,0,90.00000001 +413,50.30085681,-2.498623736,10500,0,199.9998535,0,0,0,90.00000001 +413.01,50.30085681,-2.498595711,10500,0,199.9989614,0,0,0,90.00000001 +413.02,50.30085681,-2.498567686,10500,0,199.9989614,0,0,0,90.00000001 +413.03,50.30085681,-2.498539661,10500,0,199.9998535,0,0,0,90.00000001 +413.04,50.30085681,-2.498511636,10500,0,200.0009685,0,0,0,90.00000001 +413.05,50.30085681,-2.49848361,10500,0,200.0009685,0,0,0,90.00000001 +413.06,50.30085681,-2.498455585,10500,0,199.9998535,0,0,0,90.00000001 +413.07,50.30085681,-2.49842756,10500,0,199.9991844,0,0,0,90.00000001 +413.08,50.30085681,-2.498399535,10500,0,199.9998535,0,0,0,90.00000001 +413.09,50.30085681,-2.49837151,10500,0,200.0009685,0,0,0,90.00000001 +413.1,50.30085681,-2.498343484,10500,0,200.0009685,0,0,0,90.00000001 +413.11,50.30085681,-2.498315459,10500,0,199.9998535,0,0,0,90.00000001 +413.12,50.30085681,-2.498287434,10500,0,199.9991844,0,0,0,90.00000001 +413.13,50.30085681,-2.498259409,10500,0,199.9998535,0,0,0,90.00000001 +413.14,50.30085681,-2.498231384,10500,0,200.0009685,0,0,0,90.00000001 +413.15,50.30085681,-2.498203358,10500,0,200.0009685,0,0,0,90.00000001 +413.16,50.30085681,-2.498175333,10500,0,199.9998535,0,0,0,90.00000001 +413.17,50.30085681,-2.498147308,10500,0,199.9991844,0,0,0,90.00000001 +413.18,50.30085681,-2.498119283,10500,0,199.9998535,0,0,0,90.00000001 +413.19,50.30085681,-2.498091258,10500,0,200.0009685,0,0,0,90.00000001 +413.2,50.30085681,-2.498063232,10500,0,200.0009685,0,0,0,90.00000001 +413.21,50.30085681,-2.498035207,10500,0,199.9998535,0,0,0,90.00000001 +413.22,50.30085681,-2.498007182,10500,0,199.9991844,0,0,0,90.00000001 +413.23,50.30085681,-2.497979157,10500,0,199.9998535,0,0,0,90.00000001 +413.24,50.30085681,-2.497951132,10500,0,200.0009685,0,0,0,90.00000001 +413.25,50.30085681,-2.497923106,10500,0,200.0009685,0,0,0,90.00000001 +413.26,50.30085681,-2.497895081,10500,0,199.9998535,0,0,0,90.00000001 +413.27,50.30085681,-2.497867056,10500,0,199.9991844,0,0,0,90.00000001 +413.28,50.30085681,-2.497839031,10500,0,199.9998535,0,0,0,90.00000001 +413.29,50.30085681,-2.497811006,10500,0,200.0009685,0,0,0,90.00000001 +413.3,50.30085681,-2.49778298,10500,0,200.0009685,0,0,0,90.00000001 +413.31,50.30085681,-2.497754955,10500,0,199.9998535,0,0,0,90.00000001 +413.32,50.30085681,-2.49772693,10500,0,199.9989614,0,0,0,90.00000001 +413.33,50.30085681,-2.497698905,10500,0,199.9989614,0,0,0,90.00000001 +413.34,50.30085681,-2.49767088,10500,0,199.9998535,0,0,0,90.00000001 +413.35,50.30085681,-2.497642855,10500,0,200.0009685,0,0,0,90.00000001 +413.36,50.30085681,-2.497614829,10500,0,200.0009685,0,0,0,90.00000001 +413.37,50.30085681,-2.497586804,10500,0,199.9998535,0,0,0,90.00000001 +413.38,50.30085681,-2.497558779,10500,0,199.9989614,0,0,0,90.00000001 +413.39,50.30085681,-2.497530754,10500,0,199.9987384,0,0,0,90.00000001 +413.4,50.30085681,-2.497502729,10500,0,199.9989614,0,0,0,90.00000001 +413.41,50.30085681,-2.497474704,10500,0,199.9998535,0,0,0,90.00000001 +413.42,50.30085681,-2.497446679,10500,0,200.0009685,0,0,0,90.00000001 +413.43,50.30085681,-2.497418653,10500,0,200.0009685,0,0,0,90.00000001 +413.44,50.30085681,-2.497390628,10500,0,199.9998535,0,0,0,90.00000001 +413.45,50.30085681,-2.497362603,10500,0,199.9989614,0,0,0,90.00000001 +413.46,50.30085681,-2.497334578,10500,0,199.9989614,0,0,0,90.00000001 +413.47,50.30085681,-2.497306553,10500,0,199.9998535,0,0,0,90.00000001 +413.48,50.30085681,-2.497278528,10500,0,200.0009685,0,0,0,90.00000001 +413.49,50.30085681,-2.497250502,10500,0,200.0009685,0,0,0,90.00000001 +413.5,50.30085681,-2.497222477,10500,0,199.9998535,0,0,0,90.00000001 +413.51,50.30085681,-2.497194452,10500,0,199.9989614,0,0,0,90.00000001 +413.52,50.30085681,-2.497166427,10500,0,199.9989614,0,0,0,90.00000001 +413.53,50.30085681,-2.497138402,10500,0,199.9998535,0,0,0,90.00000001 +413.54,50.30085681,-2.497110377,10500,0,200.0009685,0,0,0,90.00000001 +413.55,50.30085681,-2.497082351,10500,0,200.0009685,0,0,0,90.00000001 +413.56,50.30085681,-2.497054326,10500,0,199.9998535,0,0,0,90.00000001 +413.57,50.30085681,-2.497026301,10500,0,199.9989614,0,0,0,90.00000001 +413.58,50.30085681,-2.496998276,10500,0,199.9989614,0,0,0,90.00000001 +413.59,50.30085681,-2.496970251,10500,0,199.9998535,0,0,0,90.00000001 +413.6,50.30085681,-2.496942226,10500,0,200.0009685,0,0,0,90.00000001 +413.61,50.30085681,-2.4969142,10500,0,200.0009685,0,0,0,90.00000001 +413.62,50.30085681,-2.496886175,10500,0,199.9998535,0,0,0,90.00000001 +413.63,50.30085681,-2.49685815,10500,0,199.9989614,0,0,0,90.00000001 +413.64,50.30085681,-2.496830125,10500,0,199.9989614,0,0,0,90.00000001 +413.65,50.30085681,-2.4968021,10500,0,199.9998535,0,0,0,90.00000001 +413.66,50.30085681,-2.496774075,10500,0,200.0009685,0,0,0,90.00000001 +413.67,50.30085681,-2.496746049,10500,0,200.0009685,0,0,0,90.00000001 +413.68,50.30085681,-2.496718024,10500,0,199.9998535,0,0,0,90.00000001 +413.69,50.30085681,-2.496689999,10500,0,199.9989614,0,0,0,90.00000001 +413.7,50.30085681,-2.496661974,10500,0,199.9989614,0,0,0,90.00000001 +413.71,50.30085681,-2.496633949,10500,0,199.9998535,0,0,0,90.00000001 +413.72,50.30085681,-2.496605924,10500,0,200.0009685,0,0,0,90.00000001 +413.73,50.30085681,-2.496577898,10500,0,200.0009685,0,0,0,90.00000001 +413.74,50.30085681,-2.496549873,10500,0,199.9998535,0,0,0,90.00000001 +413.75,50.30085681,-2.496521848,10500,0,199.9991844,0,0,0,90.00000001 +413.76,50.30085681,-2.496493823,10500,0,199.9998535,0,0,0,90.00000001 +413.77,50.30085681,-2.496465798,10500,0,200.0009685,0,0,0,90.00000001 +413.78,50.30085681,-2.496437772,10500,0,200.0009685,0,0,0,90.00000001 +413.79,50.30085681,-2.496409747,10500,0,199.9998535,0,0,0,90.00000001 +413.8,50.30085681,-2.496381722,10500,0,199.9991844,0,0,0,90.00000001 +413.81,50.30085681,-2.496353697,10500,0,199.9998535,0,0,0,90.00000001 +413.82,50.30085681,-2.496325672,10500,0,200.0009685,0,0,0,90.00000001 +413.83,50.30085681,-2.496297646,10500,0,200.0009685,0,0,0,90.00000001 +413.84,50.30085681,-2.496269621,10500,0,199.9998535,0,0,0,90.00000001 +413.85,50.30085681,-2.496241596,10500,0,199.9991844,0,0,0,90.00000001 +413.86,50.30085681,-2.496213571,10500,0,199.9998535,0,0,0,90.00000001 +413.87,50.30085681,-2.496185546,10500,0,200.0009685,0,0,0,90.00000001 +413.88,50.30085681,-2.49615752,10500,0,200.0009685,0,0,0,90.00000001 +413.89,50.30085681,-2.496129495,10500,0,199.9998535,0,0,0,90.00000001 +413.9,50.30085681,-2.49610147,10500,0,199.9991844,0,0,0,90.00000001 +413.91,50.30085681,-2.496073445,10500,0,199.9998535,0,0,0,90.00000001 +413.92,50.30085681,-2.49604542,10500,0,200.0009685,0,0,0,90.00000001 +413.93,50.30085681,-2.496017394,10500,0,200.0009685,0,0,0,90.00000001 +413.94,50.30085681,-2.495989369,10500,0,199.9998535,0,0,0,90.00000001 +413.95,50.30085681,-2.495961344,10500,0,199.9989614,0,0,0,90.00000001 +413.96,50.30085681,-2.495933319,10500,0,199.9989614,0,0,0,90.00000001 +413.97,50.30085681,-2.495905294,10500,0,199.9998535,0,0,0,90.00000001 +413.98,50.30085681,-2.495877269,10500,0,200.0009685,0,0,0,90.00000001 +413.99,50.30085681,-2.495849243,10500,0,200.0009685,0,0,0,90.00000001 +414,50.30085681,-2.495821218,10500,0,199.9998535,0,0,0,90.00000001 +414.01,50.30085681,-2.495793193,10500,0,199.9989614,0,0,0,90.00000001 +414.02,50.30085681,-2.495765168,10500,0,199.9989614,0,0,0,90.00000001 +414.03,50.30085681,-2.495737143,10500,0,199.9998535,0,0,0,90.00000001 +414.04,50.30085681,-2.495709118,10500,0,200.0009685,0,0,0,90.00000001 +414.05,50.30085681,-2.495681092,10500,0,200.0009685,0,0,0,90.00000001 +414.06,50.30085681,-2.495653067,10500,0,199.9998535,0,0,0,90.00000001 +414.07,50.30085681,-2.495625042,10500,0,199.9989614,0,0,0,90.00000001 +414.08,50.30085681,-2.495597017,10500,0,199.9989614,0,0,0,90.00000001 +414.09,50.30085681,-2.495568992,10500,0,199.9998535,0,0,0,90.00000001 +414.1,50.30085681,-2.495540967,10500,0,200.0009685,0,0,0,90.00000001 +414.11,50.30085681,-2.495512941,10500,0,200.0009685,0,0,0,90.00000001 +414.12,50.30085681,-2.495484916,10500,0,199.9998535,0,0,0,90.00000001 +414.13,50.30085681,-2.495456891,10500,0,199.9989614,0,0,0,90.00000001 +414.14,50.30085681,-2.495428866,10500,0,199.9989614,0,0,0,90.00000001 +414.15,50.30085681,-2.495400841,10500,0,199.9998535,0,0,0,90.00000001 +414.16,50.30085681,-2.495372816,10500,0,200.0009685,0,0,0,90.00000001 +414.17,50.30085681,-2.49534479,10500,0,200.0009685,0,0,0,90.00000001 +414.18,50.30085681,-2.495316765,10500,0,199.9998535,0,0,0,90.00000001 +414.19,50.30085681,-2.49528874,10500,0,199.9989614,0,0,0,90.00000001 +414.2,50.30085681,-2.495260715,10500,0,199.9989614,0,0,0,90.00000001 +414.21,50.30085681,-2.49523269,10500,0,199.9998535,0,0,0,90.00000001 +414.22,50.30085681,-2.495204665,10500,0,200.0009685,0,0,0,90.00000001 +414.23,50.30085681,-2.495176639,10500,0,200.0009685,0,0,0,90.00000001 +414.24,50.30085681,-2.495148614,10500,0,199.9998535,0,0,0,90.00000001 +414.25,50.30085681,-2.495120589,10500,0,199.9989614,0,0,0,90.00000001 +414.26,50.30085681,-2.495092564,10500,0,199.9987384,0,0,0,90.00000001 +414.27,50.30085681,-2.495064539,10500,0,199.9989614,0,0,0,90.00000001 +414.28,50.30085681,-2.495036514,10500,0,199.9998535,0,0,0,90.00000001 +414.29,50.30085681,-2.495008489,10500,0,200.0009685,0,0,0,90.00000001 +414.3,50.30085681,-2.494980463,10500,0,200.0009685,0,0,0,90.00000001 +414.31,50.30085681,-2.494952438,10500,0,199.9998535,0,0,0,90.00000001 +414.32,50.30085681,-2.494924413,10500,0,199.9991844,0,0,0,90.00000001 +414.33,50.30085681,-2.494896388,10500,0,199.9998535,0,0,0,90.00000001 +414.34,50.30085681,-2.494868363,10500,0,200.0009685,0,0,0,90.00000001 +414.35,50.30085681,-2.494840337,10500,0,200.0009685,0,0,0,90.00000001 +414.36,50.30085681,-2.494812312,10500,0,199.9998535,0,0,0,90.00000001 +414.37,50.30085681,-2.494784287,10500,0,199.9991844,0,0,0,90.00000001 +414.38,50.30085681,-2.494756262,10500,0,199.9998535,0,0,0,90.00000001 +414.39,50.30085681,-2.494728237,10500,0,200.0009685,0,0,0,90.00000001 +414.4,50.30085681,-2.494700211,10500,0,200.0009685,0,0,0,90.00000001 +414.41,50.30085681,-2.494672186,10500,0,199.9998535,0,0,0,90.00000001 +414.42,50.30085681,-2.494644161,10500,0,199.9991844,0,0,0,90.00000001 +414.43,50.30085681,-2.494616136,10500,0,199.9998535,0,0,0,90.00000001 +414.44,50.30085681,-2.494588111,10500,0,200.0009685,0,0,0,90.00000001 +414.45,50.30085681,-2.494560085,10500,0,200.0009685,0,0,0,90.00000001 +414.46,50.30085681,-2.49453206,10500,0,199.9998535,0,0,0,90.00000001 +414.47,50.30085681,-2.494504035,10500,0,199.9991844,0,0,0,90.00000001 +414.48,50.30085681,-2.49447601,10500,0,199.9998535,0,0,0,90.00000001 +414.49,50.30085681,-2.494447985,10500,0,200.0009685,0,0,0,90.00000001 +414.5,50.30085681,-2.494419959,10500,0,200.0009685,0,0,0,90.00000001 +414.51,50.30085681,-2.494391934,10500,0,199.9998535,0,0,0,90.00000001 +414.52,50.30085681,-2.494363909,10500,0,199.9991844,0,0,0,90.00000001 +414.53,50.30085681,-2.494335884,10500,0,199.9998535,0,0,0,90.00000001 +414.54,50.30085681,-2.494307859,10500,0,200.0009685,0,0,0,90.00000001 +414.55,50.30085681,-2.494279833,10500,0,200.0009685,0,0,0,90.00000001 +414.56,50.30085681,-2.494251808,10500,0,199.9998535,0,0,0,90.00000001 +414.57,50.30085681,-2.494223783,10500,0,199.9989614,0,0,0,90.00000001 +414.58,50.30085681,-2.494195758,10500,0,199.9989614,0,0,0,90.00000001 +414.59,50.30085681,-2.494167733,10500,0,199.9998535,0,0,0,90.00000001 +414.6,50.30085681,-2.494139708,10500,0,200.0009685,0,0,0,90.00000001 +414.61,50.30085681,-2.494111682,10500,0,200.0009685,0,0,0,90.00000001 +414.62,50.30085681,-2.494083657,10500,0,199.9998535,0,0,0,90.00000001 +414.63,50.30085681,-2.494055632,10500,0,199.9989614,0,0,0,90.00000001 +414.64,50.30085681,-2.494027607,10500,0,199.9989614,0,0,0,90.00000001 +414.65,50.30085681,-2.493999582,10500,0,199.9998535,0,0,0,90.00000001 +414.66,50.30085681,-2.493971557,10500,0,200.0009685,0,0,0,90.00000001 +414.67,50.30085681,-2.493943531,10500,0,200.0009685,0,0,0,90.00000001 +414.68,50.30085681,-2.493915506,10500,0,199.9998535,0,0,0,90.00000001 +414.69,50.30085681,-2.493887481,10500,0,199.9989614,0,0,0,90.00000001 +414.7,50.30085681,-2.493859456,10500,0,199.9989614,0,0,0,90.00000001 +414.71,50.30085681,-2.493831431,10500,0,199.9998535,0,0,0,90.00000001 +414.72,50.30085681,-2.493803406,10500,0,200.0009685,0,0,0,90.00000001 +414.73,50.30085681,-2.49377538,10500,0,200.0009685,0,0,0,90.00000001 +414.74,50.30085681,-2.493747355,10500,0,199.9998535,0,0,0,90.00000001 +414.75,50.30085681,-2.49371933,10500,0,199.9989614,0,0,0,90.00000001 +414.76,50.30085681,-2.493691305,10500,0,199.9989614,0,0,0,90.00000001 +414.77,50.30085681,-2.49366328,10500,0,199.9998535,0,0,0,90.00000001 +414.78,50.30085681,-2.493635255,10500,0,200.0009685,0,0,0,90.00000001 +414.79,50.30085681,-2.493607229,10500,0,200.0009685,0,0,0,90.00000001 +414.8,50.30085681,-2.493579204,10500,0,199.9998535,0,0,0,90.00000001 +414.81,50.30085681,-2.493551179,10500,0,199.9989614,0,0,0,90.00000001 +414.82,50.30085681,-2.493523154,10500,0,199.9987384,0,0,0,90.00000001 +414.83,50.30085681,-2.493495129,10500,0,199.9989614,0,0,0,90.00000001 +414.84,50.30085681,-2.493467104,10500,0,199.9998535,0,0,0,90.00000001 +414.85,50.30085681,-2.493439079,10500,0,200.0009685,0,0,0,90.00000001 +414.86,50.30085681,-2.493411053,10500,0,200.0009685,0,0,0,90.00000001 +414.87,50.30085681,-2.493383028,10500,0,199.9998535,0,0,0,90.00000001 +414.88,50.30085681,-2.493355003,10500,0,199.9989614,0,0,0,90.00000001 +414.89,50.30085681,-2.493326978,10500,0,199.9989614,0,0,0,90.00000001 +414.9,50.30085681,-2.493298953,10500,0,199.9998535,0,0,0,90.00000001 +414.91,50.30085681,-2.493270928,10500,0,200.0009685,0,0,0,90.00000001 +414.92,50.30085681,-2.493242902,10500,0,200.0009685,0,0,0,90.00000001 +414.93,50.30085681,-2.493214877,10500,0,199.9998535,0,0,0,90.00000001 +414.94,50.30085681,-2.493186852,10500,0,199.9991844,0,0,0,90.00000001 +414.95,50.30085681,-2.493158827,10500,0,199.9998535,0,0,0,90.00000001 +414.96,50.30085681,-2.493130802,10500,0,200.0009685,0,0,0,90.00000001 +414.97,50.30085681,-2.493102776,10500,0,200.0009685,0,0,0,90.00000001 +414.98,50.30085681,-2.493074751,10500,0,199.9998535,0,0,0,90.00000001 +414.99,50.30085681,-2.493046726,10500,0,199.9991844,0,0,0,90.00000001 +415,50.30085681,-2.493018701,10500,0,199.9998535,0,0,0,90.00000001 +415.01,50.30085681,-2.492990676,10500,0,200.0009685,0,0,0,90.00000001 +415.02,50.30085681,-2.49296265,10500,0,200.0009685,0,0,0,90.00000001 +415.03,50.30085681,-2.492934625,10500,0,199.9998535,0,0,0,90.00000001 +415.04,50.30085681,-2.4929066,10500,0,199.9991844,0,0,0,90.00000001 +415.05,50.30085681,-2.492878575,10500,0,199.9998535,0,0,0,90.00000001 +415.06,50.30085681,-2.49285055,10500,0,200.0009685,0,0,0,90.00000001 +415.07,50.30085681,-2.492822524,10500,0,200.0009685,0,0,0,90.00000001 +415.08,50.30085681,-2.492794499,10500,0,199.9998535,0,0,0,90.00000001 +415.09,50.30085681,-2.492766474,10500,0,199.9991844,0,0,0,90.00000001 +415.1,50.30085681,-2.492738449,10500,0,199.9998535,0,0,0,90.00000001 +415.11,50.30085681,-2.492710424,10500,0,200.0009685,0,0,0,90.00000001 +415.12,50.30085681,-2.492682398,10500,0,200.0009685,0,0,0,90.00000001 +415.13,50.30085681,-2.492654373,10500,0,199.9998535,0,0,0,90.00000001 +415.14,50.30085681,-2.492626348,10500,0,199.9991844,0,0,0,90.00000001 +415.15,50.30085681,-2.492598323,10500,0,199.9998535,0,0,0,90.00000001 +415.16,50.30085681,-2.492570298,10500,0,200.0009685,0,0,0,90.00000001 +415.17,50.30085681,-2.492542272,10500,0,200.0009685,0,0,0,90.00000001 +415.18,50.30085681,-2.492514247,10500,0,199.9998535,0,0,0,90.00000001 +415.19,50.30085681,-2.492486222,10500,0,199.9989614,0,0,0,90.00000001 +415.2,50.30085681,-2.492458197,10500,0,199.9989614,0,0,0,90.00000001 +415.21,50.30085681,-2.492430172,10500,0,199.9998535,0,0,0,90.00000001 +415.22,50.30085681,-2.492402147,10500,0,200.0009685,0,0,0,90.00000001 +415.23,50.30085681,-2.492374121,10500,0,200.0009685,0,0,0,90.00000001 +415.24,50.30085681,-2.492346096,10500,0,199.9998535,0,0,0,90.00000001 +415.25,50.30085681,-2.492318071,10500,0,199.9989614,0,0,0,90.00000001 +415.26,50.30085681,-2.492290046,10500,0,199.9989614,0,0,0,90.00000001 +415.27,50.30085681,-2.492262021,10500,0,199.9998535,0,0,0,90.00000001 +415.28,50.30085681,-2.492233996,10500,0,200.0009685,0,0,0,90.00000001 +415.29,50.30085681,-2.49220597,10500,0,200.0009685,0,0,0,90.00000001 +415.3,50.30085681,-2.492177945,10500,0,199.9998535,0,0,0,90.00000001 +415.31,50.30085681,-2.49214992,10500,0,199.9989614,0,0,0,90.00000001 +415.32,50.30085681,-2.492121895,10500,0,199.9989614,0,0,0,90.00000001 +415.33,50.30085681,-2.49209387,10500,0,199.9998535,0,0,0,90.00000001 +415.34,50.30085681,-2.492065845,10500,0,200.0009685,0,0,0,90.00000001 +415.35,50.30085681,-2.492037819,10500,0,200.0009685,0,0,0,90.00000001 +415.36,50.30085681,-2.492009794,10500,0,199.9998535,0,0,0,90.00000001 +415.37,50.30085681,-2.491981769,10500,0,199.9989614,0,0,0,90.00000001 +415.38,50.30085681,-2.491953744,10500,0,199.9987384,0,0,0,90.00000001 +415.39,50.30085681,-2.491925719,10500,0,199.9989614,0,0,0,90.00000001 +415.4,50.30085681,-2.491897694,10500,0,199.9998535,0,0,0,90.00000001 +415.41,50.30085681,-2.491869669,10500,0,200.0009685,0,0,0,90.00000001 +415.42,50.30085681,-2.491841643,10500,0,200.0009685,0,0,0,90.00000001 +415.43,50.30085681,-2.491813618,10500,0,199.9998535,0,0,0,90.00000001 +415.44,50.30085681,-2.491785593,10500,0,199.9989614,0,0,0,90.00000001 +415.45,50.30085681,-2.491757568,10500,0,199.9989614,0,0,0,90.00000001 +415.46,50.30085681,-2.491729543,10500,0,199.9998535,0,0,0,90.00000001 +415.47,50.30085681,-2.491701518,10500,0,200.0009685,0,0,0,90.00000001 +415.48,50.30085681,-2.491673492,10500,0,200.0009685,0,0,0,90.00000001 +415.49,50.30085681,-2.491645467,10500,0,199.9998535,0,0,0,90.00000001 +415.5,50.30085681,-2.491617442,10500,0,199.9989614,0,0,0,90.00000001 +415.51,50.30085681,-2.491589417,10500,0,199.9989614,0,0,0,90.00000001 +415.52,50.30085681,-2.491561392,10500,0,199.9998535,0,0,0,90.00000001 +415.53,50.30085681,-2.491533367,10500,0,200.0009685,0,0,0,90.00000001 +415.54,50.30085681,-2.491505341,10500,0,200.0009685,0,0,0,90.00000001 +415.55,50.30085681,-2.491477316,10500,0,199.9998535,0,0,0,90.00000001 +415.56,50.30085681,-2.491449291,10500,0,199.9991844,0,0,0,90.00000001 +415.57,50.30085681,-2.491421266,10500,0,199.9998535,0,0,0,90.00000001 +415.58,50.30085681,-2.491393241,10500,0,200.0009685,0,0,0,90.00000001 +415.59,50.30085681,-2.491365215,10500,0,200.0009685,0,0,0,90.00000001 +415.6,50.30085681,-2.49133719,10500,0,199.9998535,0,0,0,90.00000001 +415.61,50.30085681,-2.491309165,10500,0,199.9991844,0,0,0,90.00000001 +415.62,50.30085681,-2.49128114,10500,0,199.9998535,0,0,0,90.00000001 +415.63,50.30085681,-2.491253115,10500,0,200.0009685,0,0,0,90.00000001 +415.64,50.30085681,-2.491225089,10500,0,200.0009685,0,0,0,90.00000001 +415.65,50.30085681,-2.491197064,10500,0,199.9998535,0,0,0,90.00000001 +415.66,50.30085681,-2.491169039,10500,0,199.9989614,0,0,0,90.00000001 +415.67,50.30085681,-2.491141014,10500,0,199.9989614,0,0,0,90.00000001 +415.68,50.30085681,-2.491112989,10500,0,199.9998535,0,0,0,90.00000001 +415.69,50.30085681,-2.491084964,10500,0,200.0009685,0,0,0,90.00000001 +415.7,50.30085681,-2.491056938,10500,0,200.0009685,0,0,0,90.00000001 +415.71,50.30085681,-2.491028913,10500,0,199.9998535,0,0,0,90.00000001 +415.72,50.30085681,-2.491000888,10500,0,199.9991844,0,0,0,90.00000001 +415.73,50.30085681,-2.490972863,10500,0,199.9998535,0,0,0,90.00000001 +415.74,50.30085681,-2.490944838,10500,0,200.0009685,0,0,0,90.00000001 +415.75,50.30085681,-2.490916812,10500,0,200.0009685,0,0,0,90.00000001 +415.76,50.30085681,-2.490888787,10500,0,199.9998535,0,0,0,90.00000001 +415.77,50.30085681,-2.490860762,10500,0,199.9991844,0,0,0,90.00000001 +415.78,50.30085681,-2.490832737,10500,0,199.9998535,0,0,0,90.00000001 +415.79,50.30085681,-2.490804712,10500,0,200.0009685,0,0,0,90.00000001 +415.8,50.30085681,-2.490776686,10500,0,200.0009685,0,0,0,90.00000001 +415.81,50.30085681,-2.490748661,10500,0,199.9998535,0,0,0,90.00000001 +415.82,50.30085681,-2.490720636,10500,0,199.9991844,0,0,0,90.00000001 +415.83,50.30085681,-2.490692611,10500,0,199.9998535,0,0,0,90.00000001 +415.84,50.30085681,-2.490664586,10500,0,200.0009685,0,0,0,90.00000001 +415.85,50.30085681,-2.49063656,10500,0,200.0009685,0,0,0,90.00000001 +415.86,50.30085681,-2.490608535,10500,0,199.9998535,0,0,0,90.00000001 +415.87,50.30085681,-2.49058051,10500,0,199.9989614,0,0,0,90.00000001 +415.88,50.30085681,-2.490552485,10500,0,199.9989614,0,0,0,90.00000001 +415.89,50.30085681,-2.49052446,10500,0,199.9998535,0,0,0,90.00000001 +415.9,50.30085681,-2.490496435,10500,0,200.0009685,0,0,0,90.00000001 +415.91,50.30085681,-2.490468409,10500,0,200.0009685,0,0,0,90.00000001 +415.92,50.30085681,-2.490440384,10500,0,199.9998535,0,0,0,90.00000001 +415.93,50.30085681,-2.490412359,10500,0,199.9989614,0,0,0,90.00000001 +415.94,50.30085681,-2.490384334,10500,0,199.9989614,0,0,0,90.00000001 +415.95,50.30085681,-2.490356309,10500,0,199.9998535,0,0,0,90.00000001 +415.96,50.30085681,-2.490328284,10500,0,200.0009685,0,0,0,90.00000001 +415.97,50.30085681,-2.490300258,10500,0,200.0009685,0,0,0,90.00000001 +415.98,50.30085681,-2.490272233,10500,0,199.9998535,0,0,0,90.00000001 +415.99,50.30085681,-2.490244208,10500,0,199.9989614,0,0,0,90.00000001 +416,50.30085681,-2.490216183,10500,0,199.9987384,0,0,0,90.00000001 +416.01,50.30085681,-2.490188158,10500,0,199.9989614,0,0,0,90.00000001 +416.02,50.30085681,-2.490160133,10500,0,199.9998535,0,0,0,90.00000001 +416.03,50.30085681,-2.490132108,10500,0,200.0009685,0,0,0,90.00000001 +416.04,50.30085681,-2.490104082,10500,0,200.0009685,0,0,0,90.00000001 +416.05,50.30085681,-2.490076057,10500,0,199.9998535,0,0,0,90.00000001 +416.06,50.30085681,-2.490048032,10500,0,199.9989614,0,0,0,90.00000001 +416.07,50.30085681,-2.490020007,10500,0,199.9989614,0,0,0,90.00000001 +416.08,50.30085681,-2.489991982,10500,0,199.9998535,0,0,0,90.00000001 +416.09,50.30085681,-2.489963957,10500,0,200.0009685,0,0,0,90.00000001 +416.1,50.30085681,-2.489935931,10500,0,200.0009685,0,0,0,90.00000001 +416.11,50.30085681,-2.489907906,10500,0,199.9998535,0,0,0,90.00000001 +416.12,50.30085681,-2.489879881,10500,0,199.9989614,0,0,0,90.00000001 +416.13,50.30085681,-2.489851856,10500,0,199.9989614,0,0,0,90.00000001 +416.14,50.30085681,-2.489823831,10500,0,199.9998535,0,0,0,90.00000001 +416.15,50.30085681,-2.489795806,10500,0,200.0009685,0,0,0,90.00000001 +416.16,50.30085681,-2.48976778,10500,0,200.0009685,0,0,0,90.00000001 +416.17,50.30085681,-2.489739755,10500,0,199.9998535,0,0,0,90.00000001 +416.18,50.30085681,-2.48971173,10500,0,199.9989614,0,0,0,90.00000001 +416.19,50.30085681,-2.489683705,10500,0,199.9989614,0,0,0,90.00000001 +416.2,50.30085681,-2.48965568,10500,0,199.9998535,0,0,0,90.00000001 +416.21,50.30085681,-2.489627655,10500,0,200.0009685,0,0,0,90.00000001 +416.22,50.30085681,-2.489599629,10500,0,200.0009685,0,0,0,90.00000001 +416.23,50.30085681,-2.489571604,10500,0,199.9998535,0,0,0,90.00000001 +416.24,50.30085681,-2.489543579,10500,0,199.9991844,0,0,0,90.00000001 +416.25,50.30085681,-2.489515554,10500,0,199.9998535,0,0,0,90.00000001 +416.26,50.30085681,-2.489487529,10500,0,200.0009685,0,0,0,90.00000001 +416.27,50.30085681,-2.489459503,10500,0,200.0009685,0,0,0,90.00000001 +416.28,50.30085681,-2.489431478,10500,0,199.9998535,0,0,0,90.00000001 +416.29,50.30085681,-2.489403453,10500,0,199.9991844,0,0,0,90.00000001 +416.3,50.30085681,-2.489375428,10500,0,199.9998535,0,0,0,90.00000001 +416.31,50.30085681,-2.489347403,10500,0,200.0009685,0,0,0,90.00000001 +416.32,50.30085681,-2.489319377,10500,0,200.0009685,0,0,0,90.00000001 +416.33,50.30085681,-2.489291352,10500,0,199.9998535,0,0,0,90.00000001 +416.34,50.30085681,-2.489263327,10500,0,199.9991844,0,0,0,90.00000001 +416.35,50.30085681,-2.489235302,10500,0,199.9998535,0,0,0,90.00000001 +416.36,50.30085681,-2.489207277,10500,0,200.0009685,0,0,0,90.00000001 +416.37,50.30085681,-2.489179251,10500,0,200.0009685,0,0,0,90.00000001 +416.38,50.30085681,-2.489151226,10500,0,199.9998535,0,0,0,90.00000001 +416.39,50.30085681,-2.489123201,10500,0,199.9991844,0,0,0,90.00000001 +416.4,50.30085681,-2.489095176,10500,0,199.9998535,0,0,0,90.00000001 +416.41,50.30085681,-2.489067151,10500,0,200.0009685,0,0,0,90.00000001 +416.42,50.30085681,-2.489039125,10500,0,200.0009685,0,0,0,90.00000001 +416.43,50.30085681,-2.4890111,10500,0,199.9998535,0,0,0,90.00000001 +416.44,50.30085681,-2.488983075,10500,0,199.9991844,0,0,0,90.00000001 +416.45,50.30085681,-2.48895505,10500,0,199.9998535,0,0,0,90.00000001 +416.46,50.30085681,-2.488927025,10500,0,200.0009685,0,0,0,90.00000001 +416.47,50.30085681,-2.488898999,10500,0,200.0009685,0,0,0,90.00000001 +416.48,50.30085681,-2.488870974,10500,0,199.9998535,0,0,0,90.00000001 +416.49,50.30085681,-2.488842949,10500,0,199.9989614,0,0,0,90.00000001 +416.5,50.30085681,-2.488814924,10500,0,199.9989614,0,0,0,90.00000001 +416.51,50.30085681,-2.488786899,10500,0,199.9998535,0,0,0,90.00000001 +416.52,50.30085681,-2.488758874,10500,0,200.0009685,0,0,0,90.00000001 +416.53,50.30085681,-2.488730848,10500,0,200.0009685,0,0,0,90.00000001 +416.54,50.30085681,-2.488702823,10500,0,199.9998535,0,0,0,90.00000001 +416.55,50.30085681,-2.488674798,10500,0,199.9989614,0,0,0,90.00000001 +416.56,50.30085681,-2.488646773,10500,0,199.9987384,0,0,0,90.00000001 +416.57,50.30085681,-2.488618748,10500,0,199.9989614,0,0,0,90.00000001 +416.58,50.30085681,-2.488590723,10500,0,199.9998535,0,0,0,90.00000001 +416.59,50.30085681,-2.488562698,10500,0,200.0009685,0,0,0,90.00000001 +416.6,50.30085681,-2.488534672,10500,0,200.0009685,0,0,0,90.00000001 +416.61,50.30085681,-2.488506647,10500,0,199.9998535,0,0,0,90.00000001 +416.62,50.30085681,-2.488478622,10500,0,199.9989614,0,0,0,90.00000001 +416.63,50.30085681,-2.488450597,10500,0,199.9989614,0,0,0,90.00000001 +416.64,50.30085681,-2.488422572,10500,0,199.9998535,0,0,0,90.00000001 +416.65,50.30085681,-2.488394547,10500,0,200.0009685,0,0,0,90.00000001 +416.66,50.30085681,-2.488366521,10500,0,200.0009685,0,0,0,90.00000001 +416.67,50.30085681,-2.488338496,10500,0,199.9998535,0,0,0,90.00000001 +416.68,50.30085681,-2.488310471,10500,0,199.9989614,0,0,0,90.00000001 +416.69,50.30085681,-2.488282446,10500,0,199.9989614,0,0,0,90.00000001 +416.7,50.30085681,-2.488254421,10500,0,199.9998535,0,0,0,90.00000001 +416.71,50.30085681,-2.488226396,10500,0,200.0009685,0,0,0,90.00000001 +416.72,50.30085681,-2.48819837,10500,0,200.0009685,0,0,0,90.00000001 +416.73,50.30085681,-2.488170345,10500,0,199.9998535,0,0,0,90.00000001 +416.74,50.30085681,-2.48814232,10500,0,199.9989614,0,0,0,90.00000001 +416.75,50.30085681,-2.488114295,10500,0,199.9989614,0,0,0,90.00000001 +416.76,50.30085681,-2.48808627,10500,0,199.9998535,0,0,0,90.00000001 +416.77,50.30085681,-2.488058245,10500,0,200.0009685,0,0,0,90.00000001 +416.78,50.30085681,-2.488030219,10500,0,200.0009685,0,0,0,90.00000001 +416.79,50.30085681,-2.488002194,10500,0,199.9998535,0,0,0,90.00000001 +416.8,50.30085681,-2.487974169,10500,0,199.9989614,0,0,0,90.00000001 +416.81,50.30085681,-2.487946144,10500,0,199.9989614,0,0,0,90.00000001 +416.82,50.30085681,-2.487918119,10500,0,199.9998535,0,0,0,90.00000001 +416.83,50.30085681,-2.487890094,10500,0,200.0009685,0,0,0,90.00000001 +416.84,50.30085681,-2.487862068,10500,0,200.0009685,0,0,0,90.00000001 +416.85,50.30085681,-2.487834043,10500,0,199.9998535,0,0,0,90.00000001 +416.86,50.30085681,-2.487806018,10500,0,199.9991844,0,0,0,90.00000001 +416.87,50.30085681,-2.487777993,10500,0,199.9998535,0,0,0,90.00000001 +416.88,50.30085681,-2.487749968,10500,0,200.0009685,0,0,0,90.00000001 +416.89,50.30085681,-2.487721942,10500,0,200.0009685,0,0,0,90.00000001 +416.9,50.30085681,-2.487693917,10500,0,199.9998535,0,0,0,90.00000001 +416.91,50.30085681,-2.487665892,10500,0,199.9991844,0,0,0,90.00000001 +416.92,50.30085681,-2.487637867,10500,0,199.9998535,0,0,0,90.00000001 +416.93,50.30085681,-2.487609842,10500,0,200.0009685,0,0,0,90.00000001 +416.94,50.30085681,-2.487581816,10500,0,200.0009685,0,0,0,90.00000001 +416.95,50.30085681,-2.487553791,10500,0,199.9998535,0,0,0,90.00000001 +416.96,50.30085681,-2.487525766,10500,0,199.9991844,0,0,0,90.00000001 +416.97,50.30085681,-2.487497741,10500,0,199.9998535,0,0,0,90.00000001 +416.98,50.30085681,-2.487469716,10500,0,200.0009685,0,0,0,90.00000001 +416.99,50.30085681,-2.48744169,10500,0,200.0009685,0,0,0,90.00000001 +417,50.30085681,-2.487413665,10500,0,199.9998535,0,0,0,90.00000001 +417.01,50.30085681,-2.48738564,10500,0,199.9991844,0,0,0,90.00000001 +417.02,50.30085681,-2.487357615,10500,0,199.9998535,0,0,0,90.00000001 +417.03,50.30085681,-2.48732959,10500,0,200.0009685,0,0,0,90.00000001 +417.04,50.30085681,-2.487301564,10500,0,200.0009685,0,0,0,90.00000001 +417.05,50.30085681,-2.487273539,10500,0,199.9998535,0,0,0,90.00000001 +417.06,50.30085681,-2.487245514,10500,0,199.9991844,0,0,0,90.00000001 +417.07,50.30085681,-2.487217489,10500,0,199.9998535,0,0,0,90.00000001 +417.08,50.30085681,-2.487189464,10500,0,200.0009685,0,0,0,90.00000001 +417.09,50.30085681,-2.487161438,10500,0,200.0009685,0,0,0,90.00000001 +417.1,50.30085681,-2.487133413,10500,0,199.9998535,0,0,0,90.00000001 +417.11,50.30085681,-2.487105388,10500,0,199.9989614,0,0,0,90.00000001 +417.12,50.30085681,-2.487077363,10500,0,199.9987384,0,0,0,90.00000001 +417.13,50.30085681,-2.487049338,10500,0,199.9989614,0,0,0,90.00000001 +417.14,50.30085681,-2.487021313,10500,0,199.9998535,0,0,0,90.00000001 +417.15,50.30085681,-2.486993288,10500,0,200.0009685,0,0,0,90.00000001 +417.16,50.30085681,-2.486965262,10500,0,200.0009685,0,0,0,90.00000001 +417.17,50.30085681,-2.486937237,10500,0,199.9998535,0,0,0,90.00000001 +417.18,50.30085681,-2.486909212,10500,0,199.9989614,0,0,0,90.00000001 +417.19,50.30085681,-2.486881187,10500,0,199.9989614,0,0,0,90.00000001 +417.2,50.30085681,-2.486853162,10500,0,199.9998535,0,0,0,90.00000001 +417.21,50.30085681,-2.486825137,10500,0,200.0009685,0,0,0,90.00000001 +417.22,50.30085681,-2.486797111,10500,0,200.0009685,0,0,0,90.00000001 +417.23,50.30085681,-2.486769086,10500,0,199.9998535,0,0,0,90.00000001 +417.24,50.30085681,-2.486741061,10500,0,199.9989614,0,0,0,90.00000001 +417.25,50.30085681,-2.486713036,10500,0,199.9989614,0,0,0,90.00000001 +417.26,50.30085681,-2.486685011,10500,0,199.9998535,0,0,0,90.00000001 +417.27,50.30085681,-2.486656986,10500,0,200.0009685,0,0,0,90.00000001 +417.28,50.30085681,-2.48662896,10500,0,200.0009685,0,0,0,90.00000001 +417.29,50.30085681,-2.486600935,10500,0,199.9998535,0,0,0,90.00000001 +417.3,50.30085681,-2.48657291,10500,0,199.9989614,0,0,0,90.00000001 +417.31,50.30085681,-2.486544885,10500,0,199.9989614,0,0,0,90.00000001 +417.32,50.30085681,-2.48651686,10500,0,199.9998535,0,0,0,90.00000001 +417.33,50.30085681,-2.486488835,10500,0,200.0009685,0,0,0,90.00000001 +417.34,50.30085681,-2.486460809,10500,0,200.0009685,0,0,0,90.00000001 +417.35,50.30085681,-2.486432784,10500,0,199.9998535,0,0,0,90.00000001 +417.36,50.30085681,-2.486404759,10500,0,199.9989614,0,0,0,90.00000001 +417.37,50.30085681,-2.486376734,10500,0,199.9989614,0,0,0,90.00000001 +417.38,50.30085681,-2.486348709,10500,0,199.9998535,0,0,0,90.00000001 +417.39,50.30085681,-2.486320684,10500,0,200.0009685,0,0,0,90.00000001 +417.4,50.30085681,-2.486292658,10500,0,200.0009685,0,0,0,90.00000001 +417.41,50.30085681,-2.486264633,10500,0,199.9998535,0,0,0,90.00000001 +417.42,50.30085681,-2.486236608,10500,0,199.9989614,0,0,0,90.00000001 +417.43,50.30085681,-2.486208583,10500,0,199.9989614,0,0,0,90.00000001 +417.44,50.30085681,-2.486180558,10500,0,199.9998535,0,0,0,90.00000001 +417.45,50.30085681,-2.486152533,10500,0,200.0009685,0,0,0,90.00000001 +417.46,50.30085681,-2.486124507,10500,0,200.0009685,0,0,0,90.00000001 +417.47,50.30085681,-2.486096482,10500,0,199.9998535,0,0,0,90.00000001 +417.48,50.30085681,-2.486068457,10500,0,199.9991844,0,0,0,90.00000001 +417.49,50.30085681,-2.486040432,10500,0,199.9998535,0,0,0,90.00000001 +417.5,50.30085681,-2.486012407,10500,0,200.0009685,0,0,0,90.00000001 +417.51,50.30085681,-2.485984381,10500,0,200.0009685,0,0,0,90.00000001 +417.52,50.30085681,-2.485956356,10500,0,199.9998535,0,0,0,90.00000001 +417.53,50.30085681,-2.485928331,10500,0,199.9991844,0,0,0,90.00000001 +417.54,50.30085681,-2.485900306,10500,0,199.9998535,0,0,0,90.00000001 +417.55,50.30085681,-2.485872281,10500,0,200.0009685,0,0,0,90.00000001 +417.56,50.30085681,-2.485844255,10500,0,200.0009685,0,0,0,90.00000001 +417.57,50.30085681,-2.48581623,10500,0,199.9998535,0,0,0,90.00000001 +417.58,50.30085681,-2.485788205,10500,0,199.9991844,0,0,0,90.00000001 +417.59,50.30085681,-2.48576018,10500,0,199.9998535,0,0,0,90.00000001 +417.6,50.30085681,-2.485732155,10500,0,200.0009685,0,0,0,90.00000001 +417.61,50.30085681,-2.485704129,10500,0,200.0009685,0,0,0,90.00000001 +417.62,50.30085681,-2.485676104,10500,0,199.9998535,0,0,0,90.00000001 +417.63,50.30085681,-2.485648079,10500,0,199.9991844,0,0,0,90.00000001 +417.64,50.30085681,-2.485620054,10500,0,199.9998535,0,0,0,90.00000001 +417.65,50.30085681,-2.485592029,10500,0,200.0009685,0,0,0,90.00000001 +417.66,50.30085681,-2.485564003,10500,0,200.0009685,0,0,0,90.00000001 +417.67,50.30085681,-2.485535978,10500,0,199.9998535,0,0,0,90.00000001 +417.68,50.30085681,-2.485507953,10500,0,199.9989614,0,0,0,90.00000001 +417.69,50.30085681,-2.485479928,10500,0,199.9989614,0,0,0,90.00000001 +417.7,50.30085681,-2.485451903,10500,0,199.9998535,0,0,0,90.00000001 +417.71,50.30085681,-2.485423878,10500,0,200.0009685,0,0,0,90.00000001 +417.72,50.30085681,-2.485395852,10500,0,200.0009685,0,0,0,90.00000001 +417.73,50.30085681,-2.485367827,10500,0,199.9998535,0,0,0,90.00000001 +417.74,50.30085681,-2.485339802,10500,0,199.9989614,0,0,0,90.00000001 +417.75,50.30085681,-2.485311777,10500,0,199.9989614,0,0,0,90.00000001 +417.76,50.30085681,-2.485283752,10500,0,199.9998535,0,0,0,90.00000001 +417.77,50.30085681,-2.485255727,10500,0,200.0009685,0,0,0,90.00000001 +417.78,50.30085681,-2.485227701,10500,0,200.0009685,0,0,0,90.00000001 +417.79,50.30085681,-2.485199676,10500,0,199.9998535,0,0,0,90.00000001 +417.8,50.30085681,-2.485171651,10500,0,199.9989614,0,0,0,90.00000001 +417.81,50.30085681,-2.485143626,10500,0,199.9989614,0,0,0,90.00000001 +417.82,50.30085681,-2.485115601,10500,0,199.9998535,0,0,0,90.00000001 +417.83,50.30085681,-2.485087576,10500,0,200.0009685,0,0,0,90.00000001 +417.84,50.30085681,-2.48505955,10500,0,200.0009685,0,0,0,90.00000001 +417.85,50.30085681,-2.485031525,10500,0,199.9998535,0,0,0,90.00000001 +417.86,50.30085681,-2.4850035,10500,0,199.9989614,0,0,0,90.00000001 +417.87,50.30085681,-2.484975475,10500,0,199.9989614,0,0,0,90.00000001 +417.88,50.30085681,-2.48494745,10500,0,199.9998535,0,0,0,90.00000001 +417.89,50.30085681,-2.484919425,10500,0,200.0009685,0,0,0,90.00000001 +417.9,50.30085681,-2.484891399,10500,0,200.0009685,0,0,0,90.00000001 +417.91,50.30085681,-2.484863374,10500,0,199.9998535,0,0,0,90.00000001 +417.92,50.30085681,-2.484835349,10500,0,199.9989614,0,0,0,90.00000001 +417.93,50.30085681,-2.484807324,10500,0,199.9989614,0,0,0,90.00000001 +417.94,50.30085681,-2.484779299,10500,0,199.9998535,0,0,0,90.00000001 +417.95,50.30085681,-2.484751274,10500,0,200.0009685,0,0,0,90.00000001 +417.96,50.30085681,-2.484723248,10500,0,200.0009685,0,0,0,90.00000001 +417.97,50.30085681,-2.484695223,10500,0,199.9998535,0,0,0,90.00000001 +417.98,50.30085681,-2.484667198,10500,0,199.9989614,0,0,0,90.00000001 +417.99,50.30085681,-2.484639173,10500,0,199.9987384,0,0,0,90.00000001 +418,50.30085681,-2.484611148,10500,0,199.9989614,0,0,0,90.00000001 diff --git a/Profile_4.csv b/Profile_4.csv new file mode 100644 index 0000000..0f60202 --- /dev/null +++ b/Profile_4.csv @@ -0,0 +1,30001 @@ +0,50.425,-2.5958333,50,0,10,-3.11,0,0,90.00000001 +0.01,50.425,-2.595831893,49.9689,0,9.999262488,0.7759375,0.103612427,0.101276536,90.00000001 +0.02,50.425,-2.595830486,49.9378,0,9.999670951,2.7175,0.207203139,0.202464721,90.00000001 +0.03,50.425,-2.595829079,49.9068,0,10.00090737,3.103125,0.31075065,0.303476321,90.00000001 +0.04,50.425,-2.595827671,49.8757,0,10.0017956,3.098125,0.414233245,0.404223329,90.00000001 +0.05,50.425,-2.595826264,49.8448,0,10.00179555,3.0915625,0.517629324,0.504617853,90.00000001 +0.06,50.425,-2.595824856,49.8139,0,10.00090722,3.085,0.620917342,0.604572346,90.00000001 +0.07,50.425,-2.595823449,49.7831,0,9.999574756,3.0778125,0.724075643,0.70399966,90.00000001 +0.08,50.425,-2.595822042,49.7523,0,9.99868643,3.068125,0.82708274,0.80281305,90.00000001 +0.09,50.425,-2.595820635,49.7217,0,9.998686382,3.05625,0.929917148,0.900926343,90.00000001 +0.1,50.425,-2.595819228,49.6912,0,9.999574612,3.043125,1.032557323,0.998254053,90.00000001 +0.11,50.425,-2.595817821,49.6608,0,10.00068491,3.028125,1.134981837,1.094711269,90.00000001 +0.12,50.425,-2.595816413,49.6306,0,10.00068487,3.0115625,1.237169375,1.190213879,90.00000001 +0.13,50.425,-2.595815006,49.6006,0,9.999574471,2.9953125,1.33909851,1.284678577,90.00000001 +0.14,50.425,-2.595813599,49.5707,0,9.998908215,2.979375,1.440747983,1.378023028,90.00000001 +0.15,50.425,-2.595812192,49.541,0,9.999574377,2.96125,1.542096597,1.470165871,90.00000001 +0.16,50.425,-2.595810785,49.5114,0,10.00068468,2.94,1.643123208,1.561026664,90.00000001 +0.17,50.425,-2.595809377,49.4822,0,10.00068463,2.918125,1.743806618,1.650526224,90.00000001 +0.18,50.425,-2.59580797,49.4531,0,9.99957424,2.8965625,1.844125856,1.738586514,90.00000001 +0.19,50.425,-2.595806563,49.4242,0,9.998907986,2.8728125,1.944059951,1.8251307,90.00000001 +0.2,50.425,-2.595805156,49.3956,0,9.99957415,2.84625,2.043588106,1.910083382,90.00000001 +0.21,50.425,-2.595803749,49.3673,0,10.00068445,2.8184375,2.142689464,1.993370418,90.00000001 +0.22,50.425,-2.595802341,49.3392,0,10.00090648,2.79,2.241343343,2.074919214,90.00000001 +0.23,50.425,-2.595800934,49.3115,0,10.00068437,2.76125,2.339529172,2.15465861,90.00000001 +0.24,50.425,-2.595799527,49.284,0,10.00090639,2.731875,2.437226383,2.232519163,90.00000001 +0.25,50.425,-2.595798119,49.2568,0,10.00068428,2.7009375,2.534414635,2.308432919,90.00000001 +0.26,50.425,-2.595796712,49.23,0,9.99957389,2.6684375,2.63107359,2.382333703,90.00000001 +0.27,50.425,-2.595795305,49.2034,0,9.99890764,2.6346875,2.727183077,2.454156999,90.00000001 +0.28,50.425,-2.595793898,49.1773,0,9.999573808,2.5996875,2.822723045,2.523840298,90.00000001 +0.29,50.425,-2.595792491,49.1514,0,10.00068412,2.5634375,2.917673496,2.591322752,90.00000001 +0.3,50.425,-2.595791083,49.126,0,10.00068408,2.52625,3.012014664,2.656545517,90.00000001 +0.31,50.425,-2.595789676,49.1009,0,9.999573689,2.4884375,3.105726781,2.719451699,90.00000001 +0.32,50.425,-2.595788269,49.0762,0,9.998685371,2.4496875,3.198790368,2.779986524,90.00000001 +0.33,50.425,-2.595786862,49.0519,0,9.998685334,2.4096875,3.291185828,2.838097164,90.00000001 +0.34,50.425,-2.595785455,49.028,0,9.999573575,2.3684375,3.382894026,2.89373297,90.00000001 +0.35,50.425,-2.595784048,49.0045,0,10.00068389,2.32625,3.473895767,2.946845355,90.00000001 +0.36,50.425,-2.59578264,48.9815,0,10.00068385,2.283125,3.564172028,2.997388025,90.00000001 +0.37,50.425,-2.595781233,48.9588,0,9.999573467,2.2384375,3.653703903,3.045316976,90.00000001 +0.38,50.425,-2.595779826,48.9367,0,9.998907223,2.1928125,3.74247277,3.090590325,90.00000001 +0.39,50.425,-2.595778419,48.915,0,9.999573398,2.146875,3.830460122,3.133168652,90.00000001 +0.4,50.425,-2.595777012,48.8937,0,10.00090578,2.0996875,3.917647454,3.17301483,90.00000001 +0.41,50.425,-2.595775604,48.873,0,10.00179403,2.0515625,4.004016659,3.21009408,90.00000001 +0.42,50.425,-2.595774197,48.8527,0,10.001794,2.0034375,4.089549689,3.244374031,90.00000001 +0.43,50.425,-2.595772789,48.8329,0,10.00090569,1.954375,4.174228669,3.275824887,90.00000001 +0.44,50.425,-2.595771382,48.8136,0,9.99957324,1.9034375,4.25803595,3.304419205,90.00000001 +0.45,50.425,-2.595769975,48.7948,0,9.998684932,1.85125,4.340953944,3.330131947,90.00000001 +0.46,50.425,-2.595768568,48.7766,0,9.998684904,1.7984375,4.422965404,3.352940824,90.00000001 +0.47,50.425,-2.595767161,48.7588,0,9.999573154,1.745,4.504053199,3.37282584,90.00000001 +0.48,50.425,-2.595765754,48.7417,0,10.00068347,1.6915625,4.584200368,3.389769749,90.00000001 +0.49,50.425,-2.595764346,48.725,0,10.00068345,1.6384375,4.663390126,3.403757711,90.00000001 +0.5,50.425,-2.595762939,48.7089,0,9.999573076,1.584375,4.741606084,3.414777523,90.00000001 +0.51,50.425,-2.595761532,48.6933,0,9.998906843,1.528125,4.818831799,3.422819616,90.00000001 +0.52,50.425,-2.595760125,48.6783,0,9.999573028,1.47,4.895051114,3.427877,90.00000001 +0.53,50.425,-2.595758718,48.6639,0,10.00068335,1.411875,4.970248215,3.429945148,90.00000001 +0.54,50.425,-2.59575731,48.6501,0,10.00068333,1.355,5.044407289,3.4290224,90.00000001 +0.55,50.425,-2.595755903,48.6368,0,9.999572963,1.298125,5.117512922,3.425109442,90.00000001 +0.56,50.425,-2.595754496,48.6241,0,9.998684665,1.2396875,5.189549874,3.418209769,90.00000001 +0.57,50.425,-2.595753089,48.612,0,9.998684646,1.1796875,5.260503019,3.408329341,90.00000001 +0.58,50.425,-2.595751682,48.6005,0,9.999572906,1.1184375,5.330357575,3.395476809,90.00000001 +0.59,50.425,-2.595750275,48.5896,0,10.00090531,1.056875,5.399098932,3.379663403,90.00000001 +0.6,50.425,-2.595748867,48.5794,0,10.00179357,0.9965625,5.466712822,3.360902817,90.00000001 +0.61,50.425,-2.59574746,48.5697,0,10.00179355,0.9365625,5.533184979,3.339211495,90.00000001 +0.62,50.425,-2.595746052,48.5606,0,10.00090526,0.8746875,5.598501652,3.314608343,90.00000001 +0.63,50.425,-2.595744645,48.5522,0,9.999572831,0.811875,5.662649147,3.287114849,90.00000001 +0.64,50.425,-2.595743238,48.5444,0,9.998906609,0.75,5.725614057,3.256754904,90.00000001 +0.65,50.425,-2.595741831,48.5372,0,9.999572807,0.688125,5.787383262,3.223554979,90.00000001 +0.66,50.425,-2.595740424,48.5306,0,10.00068315,0.625,5.847943813,3.187544123,90.00000001 +0.67,50.425,-2.595739016,48.5247,0,10.00068314,0.5615625,5.907283103,3.148753677,90.00000001 +0.68,50.425,-2.595737609,48.5194,0,9.99957278,0.4984375,5.965388759,3.107217446,90.00000001 +0.69,50.425,-2.595736202,48.5147,0,9.998684493,0.4346875,6.022248632,3.062971639,90.00000001 +0.7,50.425,-2.595734795,48.5107,0,9.998684487,0.37,6.077850805,3.016054933,90.00000001 +0.71,50.425,-2.595733388,48.5073,0,9.99957276,0.3053125,6.132183706,2.966508178,90.00000001 +0.72,50.425,-2.595731981,48.5046,0,10.0006831,0.2415625,6.185235988,2.914374577,90.00000001 +0.73,50.425,-2.595730573,48.5025,0,10.0006831,0.1784375,6.236996537,2.859699621,90.00000001 +0.74,50.425,-2.595729166,48.501,0,9.999572751,0.1146875,6.287454581,2.802530923,90.00000001 +0.75,50.425,-2.595727759,48.5002,0,9.998906541,0.05,6.336599577,2.742918389,90.00000001 +0.76,50.425,-2.595726352,48.5,0,9.999572749,-0.015,6.384421213,2.680913985,90.00000001 +0.77,50.425,-2.595724945,48.5005,0,10.0006831,-0.08,6.430909633,2.616571799,90.00000001 +0.78,50.425,-2.595723537,48.5016,0,10.00090517,-0.145,6.476054983,2.549947922,90.00000001 +0.79,50.425,-2.59572213,48.5034,0,10.0006831,-0.2096875,6.519847867,2.481100454,90.00000001 +0.8,50.425,-2.595720723,48.5058,0,10.00090518,-0.2734375,6.56227923,2.410089383,90.00000001 +0.81,50.425,-2.595719315,48.5089,0,10.00068311,-0.336875,6.603340079,2.336976702,90.00000001 +0.82,50.425,-2.595717908,48.5125,0,9.999572768,-0.4015625,6.643021932,2.261826183,90.00000001 +0.83,50.425,-2.595716501,48.5169,0,9.998906567,-0.4665625,6.681316483,2.184703314,90.00000001 +0.84,50.425,-2.595715094,48.5219,0,9.999572784,-0.5296875,6.71821571,2.105675302,90.00000001 +0.85,50.425,-2.595713687,48.5275,0,10.00068314,-0.591875,6.753711935,2.024811133,90.00000001 +0.86,50.425,-2.595712279,48.5337,0,10.00068315,-0.655,6.787797767,1.942181337,90.00000001 +0.87,50.425,-2.595710872,48.5406,0,9.999572812,-0.718125,6.820465987,1.857857878,90.00000001 +0.88,50.425,-2.595709465,48.5481,0,9.998906616,-0.78,6.851709892,1.77191438,90.00000001 +0.89,50.425,-2.595708058,48.5562,0,9.999572838,-0.841875,6.881522891,1.684425673,90.00000001 +0.9,50.425,-2.595706651,48.5649,0,10.0006832,-0.9046875,6.909898798,1.595468188,90.00000001 +0.91,50.425,-2.595705243,48.5743,0,10.00068321,-0.9665625,6.936831596,1.505119448,90.00000001 +0.92,50.425,-2.595703836,48.5843,0,9.99957288,-1.0265625,6.962315784,1.413458175,90.00000001 +0.93,50.425,-2.595702429,48.5948,0,9.998906689,-1.086875,6.986345921,1.320564356,90.00000001 +0.94,50.425,-2.595701022,48.606,0,9.999572916,-1.1484375,7.008917135,1.226519006,90.00000001 +0.95,50.425,-2.595699615,48.6178,0,10.00068328,-1.209375,7.030024556,1.131404059,90.00000001 +0.96,50.425,-2.595698207,48.6302,0,10.00090537,-1.268125,7.049663888,1.035302536,90.00000001 +0.97,50.425,-2.5956968,48.6432,0,10.00068332,-1.325,7.067830947,0.93829826,90.00000001 +0.98,50.425,-2.595695393,48.6567,0,10.00090541,-1.381875,7.08452201,0.840475743,90.00000001 +0.99,50.425,-2.595693985,48.6708,0,10.00068336,-1.44,7.099733581,0.741920299,90.00000001 +1,50.425,-2.595692578,48.6855,0,9.99957304,-1.498125,7.113462394,0.642717928,90.00000001 +1.01,50.425,-2.595691171,48.7008,0,9.998684785,-1.5546875,7.1257057,0.542955032,90.00000001 +1.02,50.425,-2.595689764,48.7166,0,9.998684809,-1.61,7.13646092,0.442718759,90.00000001 +1.03,50.425,-2.595688357,48.733,0,9.999573113,-1.665,7.145725705,0.342096369,90.00000001 +1.04,50.425,-2.59568695,48.7499,0,10.00068349,-1.7196875,7.153498279,0.241175698,90.00000001 +1.05,50.425,-2.595685542,48.7674,0,10.00068352,-1.773125,7.159776865,0.140044693,90.00000001 +1.06,50.425,-2.595684135,48.7854,0,9.999573196,-1.8246875,7.16456026,0.038791535,90.00000001 +1.07,50.425,-2.595682728,48.8039,0,9.998907015,-1.8753125,7.167847434,-0.062495372,90.00000001 +1.08,50.425,-2.595681321,48.8229,0,9.999573254,-1.9265625,7.169637698,-0.163727847,90.00000001 +1.09,50.425,-2.595679914,48.8424,0,10.00068363,-1.978125,7.169930651,-0.264817483,90.00000001 +1.1,50.425,-2.595678506,48.8625,0,10.00068366,-2.0278125,7.168726294,-0.365676275,90.00000001 +1.11,50.425,-2.595677099,48.883,0,9.999795418,-2.075,7.166024798,-0.466216159,90.00000001 +1.12,50.425,-2.595675692,48.904,0,9.999795451,-2.1215625,7.161826793,-0.566349472,90.00000001 +1.13,50.425,-2.595674285,48.9254,0,10.00068376,-2.1684375,7.156133082,-0.665988952,90.00000001 +1.14,50.425,-2.595672877,48.9474,0,10.0006838,-2.2146875,7.148944983,-0.765047626,90.00000001 +1.15,50.425,-2.59567147,48.9697,0,9.999795553,-2.2596875,7.14026387,-0.863439204,90.00000001 +1.16,50.425,-2.595670063,48.9926,0,9.999795589,-2.3034375,7.130091635,-0.961077859,90.00000001 +1.17,50.425,-2.595668656,49.0158,0,10.0006839,-2.34625,7.11843034,-1.057878448,90.00000001 +1.18,50.425,-2.595667248,49.0395,0,10.00068394,-2.3884375,7.105282448,-1.153756518,90.00000001 +1.19,50.425,-2.595665841,49.0636,0,9.99957363,-2.4296875,7.09065071,-1.248628531,90.00000001 +1.2,50.425,-2.595664434,49.0881,0,9.99890746,-2.4696875,7.07453822,-1.342411695,90.00000001 +1.21,50.425,-2.595663027,49.113,0,9.999573708,-2.508125,7.056948301,-1.43502425,90.00000001 +1.22,50.425,-2.59566162,49.1383,0,10.0006841,-2.545,7.037884563,-1.526385464,90.00000001 +1.23,50.425,-2.595660212,49.1639,0,10.00068414,-2.58125,7.017351131,-1.61641564,90.00000001 +1.24,50.425,-2.595658805,49.1899,0,9.999573828,-2.6165625,6.995352187,-1.705036283,90.00000001 +1.25,50.425,-2.595657398,49.2163,0,9.998685591,-2.65,6.971892316,-1.7921701,90.00000001 +1.26,50.425,-2.595655991,49.2429,0,9.998685633,-2.683125,6.946976501,-1.877741117,90.00000001 +1.27,50.425,-2.595654584,49.2699,0,9.999573954,-2.7165625,6.9206099,-1.961674679,90.00000001 +1.28,50.425,-2.595653177,49.2973,0,10.00068434,-2.7478125,6.892797956,-2.043897675,90.00000001 +1.29,50.425,-2.595651769,49.3249,0,10.00090646,-2.7765625,6.863546627,-2.124338371,90.00000001 +1.3,50.425,-2.595650362,49.3528,0,10.00068443,-2.805,6.832861872,-2.20292658,90.00000001 +1.31,50.425,-2.595648955,49.381,0,10.00090655,-2.8328125,6.800750166,-2.279593833,90.00000001 +1.32,50.425,-2.595647547,49.4095,0,10.00068452,-2.858125,6.767218269,-2.354273267,90.00000001 +1.33,50.425,-2.59564614,49.4382,0,9.999796287,-2.8815625,6.732273058,-2.426899678,90.00000001 +1.34,50.425,-2.595644733,49.4671,0,9.999796332,-2.905,6.695921922,-2.497409813,90.00000001 +1.35,50.425,-2.595643326,49.4963,0,10.00068466,-2.928125,6.658172426,-2.565742192,90.00000001 +1.36,50.425,-2.595641918,49.5257,0,10.0006847,-2.9496875,6.619032476,-2.631837228,90.00000001 +1.37,50.425,-2.595640511,49.5553,0,9.9995744,-2.97,6.578510208,-2.695637224,90.00000001 +1.38,50.425,-2.595639104,49.5851,0,9.998686168,-2.989375,6.536614101,-2.757086604,90.00000001 +1.39,50.425,-2.595637697,49.6151,0,9.998686215,-3.0065625,6.493352923,-2.816131738,90.00000001 +1.4,50.425,-2.59563629,49.6453,0,9.99957454,-3.02125,6.448735668,-2.872721175,90.00000001 +1.41,50.425,-2.595634883,49.6755,0,10.00068494,-3.035,6.402771676,-2.926805584,90.00000001 +1.42,50.425,-2.595633475,49.706,0,10.00068498,-3.0484375,6.355470572,-2.978337751,90.00000001 +1.43,50.425,-2.595632068,49.7365,0,9.999574683,-3.0609375,6.306842155,-3.027272759,90.00000001 +1.44,50.425,-2.595630661,49.7672,0,9.998908522,-3.071875,6.256896679,-3.073567921,90.00000001 +1.45,50.425,-2.595629254,49.798,0,9.999574779,-3.08125,6.205644515,-3.1171829,90.00000001 +1.46,50.425,-2.595627847,49.8288,0,10.00068518,-3.0896875,6.153096436,-3.158079654,90.00000001 +1.47,50.425,-2.595626439,49.8598,0,10.00090729,-3.0965625,6.09926327,-3.196222543,90.00000001 +1.48,50.425,-2.595625032,49.8908,0,10.00068527,-3.10125,6.044156418,-3.231578221,90.00000001 +1.49,50.425,-2.595623625,49.9218,0,10.00090739,-3.105,5.987787283,-3.264115979,90.00000001 +1.5,50.425,-2.595622217,49.9529,0,10.00068537,-3.108125,5.930167725,-3.293807339,90.00000001 +1.51,50.425,-2.59562081,49.984,0,9.99957507,-3.109375,5.871309662,-3.320626463,90.00000001 +1.52,50.425,-2.595619403,50.0151,0,9.998908909,-3.1084375,5.811225526,-3.344549971,90.00000001 +1.53,50.425,-2.595617996,50.0462,0,9.999575168,-3.1065625,5.749927751,-3.365556953,90.00000001 +1.54,50.425,-2.595616589,50.0772,0,10.00068556,-3.1046875,5.687429171,-3.383629131,90.00000001 +1.55,50.425,-2.595615181,50.1083,0,10.00068561,-3.1015625,5.623742849,-3.39875069,90.00000001 +1.56,50.425,-2.595613774,50.1393,0,9.999575313,-3.09625,5.558882079,-3.410908568,90.00000001 +1.57,50.425,-2.595612367,50.1702,0,9.998909152,-3.0896875,5.492860381,-3.420091993,90.00000001 +1.58,50.425,-2.59561096,50.2011,0,9.99957541,-3.0815625,5.425691622,-3.426293115,90.00000001 +1.59,50.425,-2.595609553,50.2319,0,10.00068581,-3.07125,5.357389724,-3.429506434,90.00000001 +1.6,50.425,-2.595608145,50.2625,0,10.00068585,-3.06,5.287969069,-3.4297292,90.00000001 +1.61,50.425,-2.595606738,50.2931,0,9.999575554,-3.0484375,5.217444038,-3.426961127,90.00000001 +1.62,50.425,-2.595605331,50.3235,0,9.998687322,-3.03625,5.145829413,-3.421204734,90.00000001 +1.63,50.425,-2.595603924,50.3538,0,9.998687369,-3.023125,5.073140148,-3.412465008,90.00000001 +1.64,50.425,-2.595602517,50.384,0,9.999575696,-3.0078125,4.999391427,-3.400749568,90.00000001 +1.65,50.425,-2.59560111,50.414,0,10.00090816,-2.9896875,4.924598663,-3.386068613,90.00000001 +1.66,50.425,-2.595599702,50.4438,0,10.00179649,-2.97,4.848777439,-3.36843492,90.00000001 +1.67,50.425,-2.595598295,50.4734,0,10.00179653,-2.9496875,4.771943626,-3.347863959,90.00000001 +1.68,50.425,-2.595596887,50.5028,0,10.0009083,-2.9284375,4.694113269,-3.324373607,90.00000001 +1.69,50.425,-2.59559548,50.532,0,9.999575927,-2.90625,4.61530258,-3.297984316,90.00000001 +1.7,50.425,-2.595594073,50.5609,0,9.998909764,-2.883125,4.535528062,-3.268719122,90.00000001 +1.71,50.425,-2.595592666,50.5897,0,9.999576018,-2.8584375,4.45480633,-3.236603577,90.00000001 +1.72,50.425,-2.595591259,50.6181,0,10.00068641,-2.8328125,4.373154287,-3.201665699,90.00000001 +1.73,50.425,-2.595589851,50.6463,0,10.00068645,-2.8065625,4.290588948,-3.163935913,90.00000001 +1.74,50.425,-2.595588444,50.6743,0,9.99957615,-2.7778125,4.207127619,-3.123447105,90.00000001 +1.75,50.425,-2.595587037,50.7019,0,9.998687915,-2.7465625,4.122787658,-3.080234571,90.00000001 +1.76,50.425,-2.59558563,50.7292,0,9.998687958,-2.7153125,4.037586714,-3.034336068,90.00000001 +1.77,50.425,-2.595584223,50.7562,0,9.999576279,-2.6846875,3.951542548,-2.985791589,90.00000001 +1.78,50.425,-2.595582816,50.7829,0,10.00068667,-2.653125,3.864673151,-2.934643417,90.00000001 +1.79,50.425,-2.595581408,50.8093,0,10.00068671,-2.619375,3.776996686,-2.880936244,90.00000001 +1.8,50.425,-2.595580001,50.8353,0,9.999576402,-2.583125,3.688531429,-2.824716823,90.00000001 +1.81,50.425,-2.595578594,50.861,0,9.998910233,-2.5453125,3.599295888,-2.766034199,90.00000001 +1.82,50.425,-2.595577187,50.8862,0,9.999576482,-2.508125,3.509308684,-2.704939538,90.00000001 +1.83,50.425,-2.59557578,50.9111,0,10.00068687,-2.4715625,3.418588609,-2.641486181,90.00000001 +1.84,50.425,-2.595574372,50.9357,0,10.00090898,-2.4325,3.327154572,-2.575729362,90.00000001 +1.85,50.425,-2.595572965,50.9598,0,10.00068695,-2.39,3.235025709,-2.507726491,90.00000001 +1.86,50.425,-2.595571558,50.9835,0,10.00090905,-2.346875,3.142221271,-2.437536812,90.00000001 +1.87,50.425,-2.59557015,51.0067,0,10.00068702,-2.3046875,3.048760624,-2.365221631,90.00000001 +1.88,50.425,-2.595568743,51.0296,0,9.999576706,-2.2615625,2.954663307,-2.290843917,90.00000001 +1.89,50.425,-2.595567336,51.052,0,9.998910531,-2.21625,2.859948857,-2.214468528,90.00000001 +1.9,50.425,-2.595565929,51.0739,0,9.999576775,-2.17,2.764637214,-2.1361621,90.00000001 +1.91,50.425,-2.595564522,51.0954,0,10.00068716,-2.1234375,2.6687482,-2.055992871,90.00000001 +1.92,50.425,-2.595563114,51.1164,0,10.00068719,-2.07625,2.572301871,-1.974030858,90.00000001 +1.93,50.425,-2.595561707,51.1369,0,9.999576874,-2.0284375,2.475318336,-1.890347392,90.00000001 +1.94,50.425,-2.5955603,51.157,0,9.998688626,-1.9796875,2.377817822,-1.805015585,90.00000001 +1.95,50.425,-2.595558893,51.1765,0,9.998688656,-1.9296875,2.279820782,-1.718109747,90.00000001 +1.96,50.425,-2.595557486,51.1956,0,9.999576965,-1.8784375,2.181347614,-1.629705683,90.00000001 +1.97,50.425,-2.595556079,51.2141,0,10.00068734,-1.82625,2.082418888,-1.539880453,90.00000001 +1.98,50.425,-2.595554671,51.2321,0,10.00068737,-1.7734375,1.983055287,-1.448712498,90.00000001 +1.99,50.425,-2.595553264,51.2496,0,9.99957705,-1.7196875,1.883277551,-1.356281227,90.00000001 +2,50.425,-2.595551857,51.2665,0,9.998910867,-1.665,1.783106481,-1.2626672,90.00000001 +2.01,50.425,-2.59555045,51.2829,0,9.999577101,-1.61,1.682563102,-1.167952177,90.00000001 +2.02,50.425,-2.595549043,51.2987,0,10.00090955,-1.555,1.581668271,-1.072218665,90.00000001 +2.03,50.425,-2.595547635,51.314,0,10.00179785,-1.4996875,1.480443187,-0.975550142,90.00000001 +2.04,50.425,-2.595546228,51.3287,0,10.00179787,-1.443125,1.378908878,-0.878030949,90.00000001 +2.05,50.425,-2.59554482,51.3429,0,10.00090961,-1.385,1.277086657,-0.779746056,90.00000001 +2.06,50.425,-2.595543413,51.3564,0,9.999577217,-1.3265625,1.174997667,-0.680781233,90.00000001 +2.07,50.425,-2.595542006,51.3694,0,9.998688959,-1.2684375,1.072663337,-0.581222769,90.00000001 +2.08,50.425,-2.595540599,51.3818,0,9.998688978,-1.2096875,0.970104981,-0.481157523,90.00000001 +2.09,50.425,-2.595539192,51.3936,0,9.999577275,-1.15,0.867344026,-0.380672643,90.00000001 +2.1,50.425,-2.595537785,51.4048,0,10.00068764,-1.09,0.764401959,-0.279855792,90.00000001 +2.11,50.425,-2.595536377,51.4154,0,10.00068766,-1.03,0.661300267,-0.178794918,90.00000001 +2.12,50.425,-2.59553497,51.4254,0,9.999577325,-0.9696875,0.558060434,-0.077578142,90.00000001 +2.13,50.425,-2.595533563,51.4348,0,9.998911131,-0.908125,0.454704062,0.023706243,90.00000001 +2.14,50.425,-2.595532156,51.4436,0,9.999577353,-0.845,0.35125275,0.124970002,90.00000001 +2.15,50.425,-2.595530749,51.4517,0,10.00068771,-0.781875,0.2477281,0.226124784,90.00000001 +2.16,50.425,-2.595529341,51.4592,0,10.00068773,-0.72,0.144151712,0.327082411,90.00000001 +2.17,50.425,-2.595527934,51.4661,0,9.999577389,-0.658125,0.040545186,0.427754763,90.00000001 +2.18,50.425,-2.595526527,51.4724,0,9.99868912,-0.5946875,-0.063069819,0.528054119,90.00000001 +2.19,50.425,-2.59552512,51.478,0,9.998689129,-0.53,-0.166671589,0.627893046,90.00000001 +2.2,50.425,-2.595523713,51.483,0,9.999577415,-0.4653125,-0.270238638,0.727184397,90.00000001 +2.21,50.425,-2.595522306,51.4873,0,10.00090984,-0.4015625,-0.373749193,0.825841656,90.00000001 +2.22,50.425,-2.595520898,51.491,0,10.00179812,-0.3384375,-0.477181712,0.923778707,90.00000001 +2.23,50.425,-2.595519491,51.4941,0,10.00179813,-0.275,-0.580514535,1.020910294,90.00000001 +2.24,50.425,-2.595518083,51.4965,0,10.00090986,-0.2115625,-0.683726179,1.117151562,90.00000001 +2.25,50.425,-2.595516676,51.4983,0,9.99957744,-0.148125,-0.786794983,1.212418687,90.00000001 +2.26,50.425,-2.595515269,51.4995,0,9.998911232,-0.083125,-0.889699521,1.30662859,90.00000001 +2.27,50.425,-2.595513862,51.5,0,9.999577441,-0.016875,-0.992418249,1.399699052,90.00000001 +2.28,50.425,-2.595512455,51.4998,0,10.00068779,0.048125,-1.094929738,1.491549,90.00000001 +2.29,50.425,-2.595511047,51.499,0,10.00068779,0.1115625,-1.197212559,1.582098276,90.00000001 +2.3,50.425,-2.59550964,51.4976,0,9.999577438,0.1753125,-1.299245341,1.671267926,90.00000001 +2.31,50.425,-2.595508233,51.4955,0,9.998689156,0.24,-1.401006771,1.758980202,90.00000001 +2.32,50.425,-2.595506826,51.4928,0,9.998689151,0.3046875,-1.502475649,1.845158669,90.00000001 +2.33,50.425,-2.595505419,51.4894,0,9.999577425,0.3684375,-1.603630774,1.929728099,90.00000001 +2.34,50.425,-2.595504012,51.4854,0,10.00068777,0.4315625,-1.704450949,2.012614752,90.00000001 +2.35,50.425,-2.595502604,51.4808,0,10.00068776,0.4953125,-1.804915202,2.093746378,90.00000001 +2.36,50.425,-2.595501197,51.4755,0,9.999577404,0.5596875,-1.905002507,2.173052274,90.00000001 +2.37,50.425,-2.59549979,51.4696,0,9.998911185,0.623125,-2.004692006,2.250463169,90.00000001 +2.38,50.425,-2.595498383,51.463,0,9.999577383,0.6853125,-2.103962846,2.325911684,90.00000001 +2.39,50.425,-2.595496976,51.4559,0,10.00090979,0.748125,-2.202794284,2.399331928,90.00000001 +2.4,50.425,-2.595495568,51.4481,0,10.00179806,0.811875,-2.301165694,2.47065996,90.00000001 +2.41,50.425,-2.595494161,51.4396,0,10.00179804,0.874375,-2.399056508,2.539833498,90.00000001 +2.42,50.425,-2.595492753,51.4306,0,10.00090975,0.935,-2.496446384,2.606792326,90.00000001 +2.43,50.425,-2.595491346,51.4209,0,9.999577317,0.9953125,-2.593314869,2.671477943,90.00000001 +2.44,50.425,-2.595489939,51.4107,0,9.998689023,1.05625,-2.689641736,2.733833971,90.00000001 +2.45,50.425,-2.595488532,51.3998,0,9.998689006,1.116875,-2.785406934,2.793806094,90.00000001 +2.46,50.425,-2.595487125,51.3883,0,9.999577267,1.1765625,-2.880590464,2.851341943,90.00000001 +2.47,50.425,-2.595485718,51.3763,0,10.0006876,1.2365625,-2.975172389,2.906391441,90.00000001 +2.48,50.425,-2.59548431,51.3636,0,10.00068758,1.2965625,-3.069132998,2.958906461,90.00000001 +2.49,50.425,-2.595482903,51.3503,0,9.999577207,1.3546875,-3.16245264,3.00884128,90.00000001 +2.5,50.425,-2.595481496,51.3365,0,9.998910977,1.4115625,-3.25511189,3.056152353,90.00000001 +2.51,50.425,-2.595480089,51.3221,0,9.999577164,1.4684375,-3.347091326,3.100798427,90.00000001 +2.52,50.425,-2.595478682,51.3071,0,10.00068749,1.5246875,-3.438371753,3.142740542,90.00000001 +2.53,50.425,-2.595477274,51.2916,0,10.00068746,1.58,-3.52893415,3.1819422,90.00000001 +2.54,50.425,-2.595475867,51.2755,0,9.99957709,1.635,-3.618759551,3.218369081,90.00000001 +2.55,50.425,-2.59547446,51.2589,0,9.998688785,1.69,-3.707829221,3.251989556,90.00000001 +2.56,50.425,-2.595473053,51.2417,0,9.998688759,1.7446875,-3.796124538,3.282774178,90.00000001 +2.57,50.425,-2.595471646,51.224,0,9.999577011,1.798125,-3.883627111,3.310696245,90.00000001 +2.58,50.425,-2.595470239,51.2057,0,10.0009094,1.85,-3.970318604,3.335731292,90.00000001 +2.59,50.425,-2.595468831,51.187,0,10.00179765,1.90125,-4.056180971,3.357857547,90.00000001 +2.6,50.425,-2.595467424,51.1677,0,10.00179762,1.951875,-4.141196277,3.377055643,90.00000001 +2.61,50.425,-2.595466016,51.1479,0,10.00090931,2.00125,-4.22534676,3.393308966,90.00000001 +2.62,50.425,-2.595464609,51.1277,0,9.99957686,2.05,-4.308614774,3.406603249,90.00000001 +2.63,50.425,-2.595463202,51.1069,0,9.998910618,2.0984375,-4.390983014,3.416926917,90.00000001 +2.64,50.425,-2.595461795,51.0857,0,9.999576793,2.14625,-4.472434293,3.424270975,90.00000001 +2.65,50.425,-2.595460388,51.064,0,10.00068711,2.193125,-4.552951479,3.428629064,90.00000001 +2.66,50.425,-2.59545898,51.0418,0,10.00068707,2.238125,-4.632517899,3.429997287,90.00000001 +2.67,50.425,-2.595457573,51.0192,0,9.99957669,2.28125,-4.71111688,3.428374499,90.00000001 +2.68,50.425,-2.595456166,50.9962,0,9.998688375,2.3234375,-4.788731977,3.423762132,90.00000001 +2.69,50.425,-2.595454759,50.9727,0,9.998688338,2.365,-4.865347034,3.416164195,90.00000001 +2.7,50.425,-2.595453352,50.9489,0,9.999576579,2.4065625,-4.940946008,3.405587337,90.00000001 +2.71,50.425,-2.595451945,50.9246,0,10.00068689,2.448125,-5.015513142,3.392040724,90.00000001 +2.72,50.425,-2.595450537,50.8999,0,10.00068685,2.488125,-5.089032851,3.375536217,90.00000001 +2.73,50.425,-2.59544913,50.8748,0,9.999576464,2.52625,-5.161489724,3.356088196,90.00000001 +2.74,50.425,-2.595447723,50.8494,0,9.998910215,2.563125,-5.232868749,3.333713563,90.00000001 +2.75,50.425,-2.595446316,50.8235,0,9.999576384,2.5984375,-5.303154972,3.308431973,90.00000001 +2.76,50.425,-2.595444909,50.7974,0,10.00068669,2.633125,-5.372333667,3.28026531,90.00000001 +2.77,50.425,-2.595443501,50.7709,0,10.00090872,2.668125,-5.440390396,3.249238213,90.00000001 +2.78,50.425,-2.595442094,50.744,0,10.00068661,2.70125,-5.507311007,3.215377782,90.00000001 +2.79,50.425,-2.595440687,50.7168,0,10.00090863,2.7315625,-5.573081462,3.178713411,90.00000001 +2.8,50.425,-2.595439279,50.6894,0,10.00068652,2.7615625,-5.637688069,3.139277242,90.00000001 +2.81,50.425,-2.595437872,50.6616,0,9.99957613,2.7915625,-5.701117304,3.097103537,90.00000001 +2.82,50.425,-2.595436465,50.6335,0,9.998909877,2.819375,-5.763355933,3.052229082,90.00000001 +2.83,50.425,-2.595435058,50.6052,0,9.999576042,2.845,-5.82439095,3.004693065,90.00000001 +2.84,50.425,-2.595433651,50.5766,0,10.00068635,2.87,-5.884209635,2.954536913,90.00000001 +2.85,50.425,-2.595432243,50.5478,0,10.0006863,2.8946875,-5.942799497,2.901804398,90.00000001 +2.86,50.425,-2.595430836,50.5187,0,9.999575906,2.918125,-6.000148275,2.846541416,90.00000001 +2.87,50.425,-2.595429429,50.4894,0,9.998909651,2.939375,-6.056243937,2.788796208,90.00000001 +2.88,50.425,-2.595428022,50.4599,0,9.999575815,2.9584375,-6.111074909,2.728619139,90.00000001 +2.89,50.425,-2.595426615,50.4302,0,10.00068612,2.9765625,-6.164629618,2.66606269,90.00000001 +2.9,50.425,-2.595425207,50.4004,0,10.00068607,2.995,-6.216896948,2.60118135,90.00000001 +2.91,50.425,-2.5954238,50.3703,0,9.999575674,3.013125,-6.267865898,2.534031785,90.00000001 +2.92,50.425,-2.595422393,50.3401,0,9.998909418,3.029375,-6.317525984,2.464672494,90.00000001 +2.93,50.425,-2.595420986,50.3097,0,9.99957558,3.043125,-6.365866662,2.393163981,90.00000001 +2.94,50.425,-2.595419579,50.2792,0,10.00068588,3.0546875,-6.412877907,2.319568583,90.00000001 +2.95,50.425,-2.595418171,50.2486,0,10.0009079,3.065,-6.45854992,2.243950473,90.00000001 +2.96,50.425,-2.595416764,50.2179,0,10.00068578,3.075,-6.50287319,2.166375654,90.00000001 +2.97,50.425,-2.595415357,50.1871,0,10.00090781,3.0846875,-6.545838378,2.086911679,90.00000001 +2.98,50.425,-2.595413949,50.1562,0,10.00068569,3.093125,-6.587436546,2.005627876,90.00000001 +2.99,50.425,-2.595412542,50.1252,0,9.999575291,3.0996875,-6.627659043,1.922595176,90.00000001 +3,50.425,-2.595411135,50.0942,0,9.998686964,3.1046875,-6.666497388,1.837885887,90.00000001 +3.01,50.425,-2.595409728,50.0631,0,9.998686916,3.108125,-6.703943561,1.751573978,90.00000001 +3.02,50.425,-2.595408321,50.032,0,9.999575145,3.109375,-6.739989711,1.663734677,90.00000001 +3.03,50.425,-2.595406914,50.0009,0,10.00068544,3.1084375,-6.774628275,1.574444534,90.00000001 +3.04,50.425,-2.595405506,49.9698,0,10.0006854,3.1065625,-6.807852035,1.483781525,90.00000001 +3.05,50.425,-2.595404099,49.9388,0,9.999574999,3.105,-6.839654057,1.39182455,90.00000001 +3.06,50.425,-2.595402692,49.9077,0,9.998908742,3.103125,-6.870027753,1.298653934,90.00000001 +3.07,50.425,-2.595401285,49.8767,0,9.999574902,3.099375,-6.898966706,1.204350868,90.00000001 +3.08,50.425,-2.595399878,49.8457,0,10.0006852,3.093125,-6.926464898,1.10899757,90.00000001 +3.09,50.425,-2.59539847,49.8148,0,10.00068515,3.085,-6.952516602,1.012677234,90.00000001 +3.1,50.425,-2.595397063,49.784,0,9.999796827,3.0765625,-6.977116315,0.915473799,90.00000001 +3.11,50.425,-2.595395656,49.7533,0,9.999796779,3.0678125,-7.000258998,0.817472118,90.00000001 +3.12,50.425,-2.595394249,49.7226,0,10.00068501,3.0565625,-7.021939721,0.718757506,90.00000001 +3.13,50.425,-2.595392841,49.6921,0,10.00068496,3.0428125,-7.042154015,0.619416193,90.00000001 +3.14,50.425,-2.595391434,49.6618,0,9.999796635,3.0284375,-7.060897699,0.519534695,90.00000001 +3.15,50.425,-2.595390027,49.6315,0,9.999796589,3.013125,-7.078166762,0.419200216,90.00000001 +3.16,50.425,-2.59538862,49.6015,0,10.00068482,2.9965625,-7.093957593,0.318500134,90.00000001 +3.17,50.425,-2.595387212,49.5716,0,10.00068477,2.98,-7.108267042,0.217522338,90.00000001 +3.18,50.425,-2.595385805,49.5419,0,9.999574378,2.9625,-7.121091958,0.116354837,90.00000001 +3.19,50.425,-2.595384398,49.5123,0,9.998908123,2.9415625,-7.132429704,0.015085864,90.00000001 +3.2,50.425,-2.595382991,49.483,0,9.999574287,2.918125,-7.142277989,-0.086196229,90.00000001 +3.21,50.425,-2.595381584,49.454,0,10.00068459,2.895,-7.150634693,-0.18740315,90.00000001 +3.22,50.425,-2.595380176,49.4251,0,10.00068454,2.8715625,-7.15749804,-0.288446721,90.00000001 +3.23,50.425,-2.595378769,49.3965,0,9.999574151,2.84625,-7.162866654,-0.389238706,90.00000001 +3.24,50.425,-2.595377362,49.3682,0,9.998685828,2.82,-7.166739391,-0.489691271,90.00000001 +3.25,50.425,-2.595375955,49.3401,0,9.998685784,2.793125,-7.169115447,-0.589716811,90.00000001 +3.26,50.425,-2.595374548,49.3123,0,9.99957402,2.764375,-7.169994364,-0.68922812,90.00000001 +3.27,50.425,-2.595373141,49.2848,0,10.00068433,2.7334375,-7.169375856,-0.788138398,90.00000001 +3.28,50.425,-2.595371733,49.2576,0,10.00090635,2.7015625,-7.167260152,-0.886361469,90.00000001 +3.29,50.425,-2.595370326,49.2308,0,10.00068424,2.6696875,-7.163647653,-0.983811563,90.00000001 +3.3,50.425,-2.595368919,49.2042,0,10.00090627,2.6365625,-7.158539104,-1.080403768,90.00000001 +3.31,50.425,-2.595367511,49.178,0,10.00068416,2.60125,-7.151935594,-1.176053858,90.00000001 +3.32,50.425,-2.595366104,49.1522,0,9.999795839,2.565,-7.143838497,-1.270678411,90.00000001 +3.33,50.425,-2.595364697,49.1267,0,9.999795799,2.528125,-7.134249532,-1.364194863,90.00000001 +3.34,50.425,-2.59536329,49.1016,0,10.00068404,2.4896875,-7.123170649,-1.456521798,90.00000001 +3.35,50.425,-2.595361882,49.0769,0,10.000684,2.45,-7.110604137,-1.547578543,90.00000001 +3.36,50.425,-2.595360475,49.0526,0,9.999573614,2.41,-7.096552691,-1.637285857,90.00000001 +3.37,50.425,-2.595359068,49.0287,0,9.998685298,2.3696875,-7.081019232,-1.725565361,90.00000001 +3.38,50.425,-2.595357661,49.0052,0,9.998685261,2.328125,-7.064007027,-1.812340162,90.00000001 +3.39,50.425,-2.595356254,48.9821,0,9.999573503,2.2846875,-7.045519569,-1.897534632,90.00000001 +3.4,50.425,-2.595354847,48.9595,0,10.00068382,2.2396875,-7.025560699,-1.9810744,90.00000001 +3.41,50.425,-2.595353439,48.9373,0,10.00068378,2.1934375,-7.004134713,-2.062886585,90.00000001 +3.42,50.425,-2.595352032,48.9156,0,9.999573399,2.1465625,-6.981245966,-2.142899969,90.00000001 +3.43,50.425,-2.595350625,48.8944,0,9.998907157,2.1,-6.956899271,-2.221044651,90.00000001 +3.44,50.425,-2.595349218,48.8736,0,9.999573333,2.053125,-6.931099669,-2.297252622,90.00000001 +3.45,50.425,-2.595347811,48.8533,0,10.00068365,2.0046875,-6.903852661,-2.371457303,90.00000001 +3.46,50.425,-2.595346403,48.8335,0,10.00090569,1.955,-6.875163862,-2.443594064,90.00000001 +3.47,50.425,-2.595344996,48.8142,0,10.00068359,1.9046875,-6.84503923,-2.513599938,90.00000001 +3.48,50.425,-2.595343589,48.7954,0,10.00090563,1.853125,-6.813485127,-2.581413962,90.00000001 +3.49,50.425,-2.595342181,48.7771,0,10.00068353,1.8,-6.78050814,-2.64697695,90.00000001 +3.5,50.425,-2.595340774,48.7594,0,9.999573155,1.7465625,-6.746115088,-2.71023172,90.00000001 +3.51,50.425,-2.595339367,48.7422,0,9.998906918,1.6934375,-6.710313247,-2.771123096,90.00000001 +3.52,50.425,-2.59533796,48.7255,0,9.999573101,1.6396875,-6.673110009,-2.829598022,90.00000001 +3.53,50.425,-2.595336553,48.7094,0,10.00068342,1.585,-6.634513165,-2.885605564,90.00000001 +3.54,50.425,-2.595335145,48.6938,0,10.0006834,1.5296875,-6.594530852,-2.939096732,90.00000001 +3.55,50.425,-2.595333738,48.6788,0,9.999573029,1.473125,-6.553171264,-2.990025002,90.00000001 +3.56,50.425,-2.595332331,48.6643,0,9.998906797,1.415,-6.510443223,-3.038345913,90.00000001 +3.57,50.425,-2.595330924,48.6505,0,9.999572984,1.3565625,-6.466355495,-3.084017353,90.00000001 +3.58,50.425,-2.595329517,48.6372,0,10.00068331,1.2984375,-6.420917364,-3.126999501,90.00000001 +3.59,50.425,-2.595328109,48.6245,0,10.00068329,1.2396875,-6.374138282,-3.167254828,90.00000001 +3.6,50.425,-2.595326702,48.6124,0,9.999572926,1.18,-6.326028105,-3.204748269,90.00000001 +3.61,50.425,-2.595325295,48.6009,0,9.998684629,1.12,-6.276596801,-3.239447109,90.00000001 +3.62,50.425,-2.595323888,48.59,0,9.998684611,1.06,-6.225854685,-3.271321152,90.00000001 +3.63,50.425,-2.595322481,48.5797,0,9.999572873,1,-6.173812355,-3.300342496,90.00000001 +3.64,50.425,-2.595321074,48.57,0,10.00090528,0.9396875,-6.120480756,-3.32648593,90.00000001 +3.65,50.425,-2.595319666,48.5609,0,10.00179354,0.878125,-6.065870945,-3.349728593,90.00000001 +3.66,50.425,-2.595318259,48.5524,0,10.00179353,0.815,-6.009994382,-3.37005026,90.00000001 +3.67,50.425,-2.595316851,48.5446,0,10.00090524,0.751875,-5.952862698,-3.387433227,90.00000001 +3.68,50.425,-2.595315444,48.5374,0,9.999572807,0.69,-5.89448781,-3.401862252,90.00000001 +3.69,50.425,-2.595314037,48.5308,0,9.998684519,0.628125,-5.834881922,-3.413324789,90.00000001 +3.7,50.425,-2.59531263,48.5248,0,9.99868451,0.5646875,-5.774057524,-3.421810924,90.00000001 +3.71,50.425,-2.595311223,48.5195,0,9.99957278,0.5,-5.71202728,-3.427313095,90.00000001 +3.72,50.425,-2.595309816,48.5148,0,10.00068312,0.4353125,-5.648804195,-3.429826661,90.00000001 +3.73,50.425,-2.595308408,48.5108,0,10.00068311,0.3715625,-5.58440139,-3.429349387,90.00000001 +3.74,50.425,-2.595307001,48.5074,0,9.999572761,0.3084375,-5.518832329,-3.425881617,90.00000001 +3.75,50.425,-2.595305594,48.5046,0,9.998906548,0.2446875,-5.452110763,-3.419426445,90.00000001 +3.76,50.425,-2.595304187,48.5025,0,9.999572753,0.18,-5.384250616,-3.409989487,90.00000001 +3.77,50.425,-2.59530278,48.501,0,10.0006831,0.115,-5.315265982,-3.397578992,90.00000001 +3.78,50.425,-2.595301372,48.5002,0,10.0006831,0.05,-5.245171356,-3.382205732,90.00000001 +3.79,50.425,-2.595299965,48.5,0,9.99957275,-0.0146875,-5.17398135,-3.363883114,90.00000001 +3.8,50.425,-2.595298558,48.5005,0,9.998906542,-0.0784375,-5.101710803,-3.342627182,90.00000001 +3.81,50.425,-2.595297151,48.5016,0,9.999572752,-0.141875,-5.028374841,-3.318456385,90.00000001 +3.82,50.425,-2.595295744,48.5033,0,10.0006831,-0.2065625,-4.953988762,-3.291391864,90.00000001 +3.83,50.425,-2.595294336,48.5057,0,10.00090518,-0.2715625,-4.878568093,-3.261457226,90.00000001 +3.84,50.425,-2.595292929,48.5088,0,10.00068311,-0.335,-4.802128647,-3.228678539,90.00000001 +3.85,50.425,-2.595291522,48.5124,0,10.00090519,-0.3984375,-4.724686297,-3.193084396,90.00000001 +3.86,50.425,-2.595290114,48.5167,0,10.00068312,-0.4634375,-4.646257255,-3.154705792,90.00000001 +3.87,50.425,-2.595288707,48.5217,0,9.999572783,-0.528125,-4.56685791,-3.113576303,90.00000001 +3.88,50.425,-2.5952873,48.5273,0,9.998906583,-0.59125,-4.486504819,-3.069731682,90.00000001 +3.89,50.425,-2.595285893,48.5335,0,9.999572801,-0.6534375,-4.405214828,-3.023210259,90.00000001 +3.9,50.425,-2.595284486,48.5404,0,10.00068316,-0.7153125,-4.323004838,-2.974052486,90.00000001 +3.91,50.425,-2.595283078,48.5478,0,10.00068317,-0.778125,-4.239892038,-2.922301333,90.00000001 +3.92,50.425,-2.595281671,48.5559,0,9.999572837,-0.841875,-4.15589379,-2.868001894,90.00000001 +3.93,50.425,-2.595280264,48.5647,0,9.998684572,-0.904375,-4.071027625,-2.811201494,90.00000001 +3.94,50.425,-2.595278857,48.574,0,9.998684586,-0.965,-3.985311306,-2.751949693,90.00000001 +3.95,50.425,-2.59527745,48.584,0,9.99957288,-1.025,-3.89876265,-2.690298174,90.00000001 +3.96,50.425,-2.595276043,48.5945,0,10.00068325,-1.085,-3.811399822,-2.626300679,90.00000001 +3.97,50.425,-2.595274635,48.6057,0,10.00068326,-1.1453125,-3.72324104,-2.560012957,90.00000001 +3.98,50.425,-2.595273228,48.6174,0,9.999572933,-1.20625,-3.634304698,-2.491492935,90.00000001 +3.99,50.425,-2.595271821,48.6298,0,9.998906743,-1.2665625,-3.544609416,-2.420800199,90.00000001 +4,50.425,-2.595270414,48.6428,0,9.999572972,-1.3246875,-3.454173872,-2.347996572,90.00000001 +4.01,50.425,-2.595269007,48.6563,0,10.00090541,-1.3815625,-3.363016917,-2.273145423,90.00000001 +4.02,50.425,-2.595267599,48.6704,0,10.00179371,-1.4384375,-3.271157688,-2.196312069,90.00000001 +4.03,50.425,-2.595266192,48.6851,0,10.00179374,-1.495,-3.178615321,-2.117563489,90.00000001 +4.04,50.425,-2.595264784,48.7003,0,10.00090548,-1.5515625,-3.085409125,-2.036968381,90.00000001 +4.05,50.425,-2.595263377,48.7161,0,9.999573087,-1.608125,-2.991558581,-1.954596989,90.00000001 +4.06,50.425,-2.59526197,48.7325,0,9.998684834,-1.663125,-2.897083283,-1.870521162,90.00000001 +4.07,50.425,-2.595260563,48.7494,0,9.998684861,-1.7165625,-2.802002943,-1.784814239,90.00000001 +4.08,50.425,-2.595259156,48.7668,0,9.999573167,-1.77,-2.706337497,-1.697550876,90.00000001 +4.09,50.425,-2.595257749,48.7848,0,10.00068354,-1.823125,-2.610106829,-1.608807276,90.00000001 +4.1,50.425,-2.595256341,48.8033,0,10.00068357,-1.8746875,-2.513331049,-1.518660732,90.00000001 +4.11,50.425,-2.595254934,48.8223,0,9.999573253,-1.925,-2.41603044,-1.427189911,90.00000001 +4.12,50.425,-2.595253527,48.8418,0,9.998907075,-1.975,-2.318225283,-1.334474568,90.00000001 +4.13,50.425,-2.59525212,48.8618,0,9.999573315,-2.025,-2.219935978,-1.240595548,90.00000001 +4.14,50.425,-2.595250713,48.8823,0,10.00068369,-2.0746875,-2.121183035,-1.145634669,90.00000001 +4.15,50.425,-2.595249305,48.9033,0,10.00068373,-2.123125,-2.021987139,-1.049674838,90.00000001 +4.16,50.425,-2.595247898,48.9248,0,9.999573413,-2.1696875,-1.922368972,-0.952799592,90.00000001 +4.17,50.425,-2.595246491,48.9467,0,9.998685169,-2.2146875,-1.822349334,-0.855093558,90.00000001 +4.18,50.425,-2.595245084,48.9691,0,9.998685205,-2.2584375,-1.721949137,-0.756641876,90.00000001 +4.19,50.425,-2.595243677,48.9919,0,9.999573519,-2.3015625,-1.621189353,-0.657530376,90.00000001 +4.2,50.425,-2.59524227,49.0151,0,10.00090597,-2.345,-1.52009095,-0.55784546,90.00000001 +4.21,50.425,-2.595240862,49.0388,0,10.00179429,-2.3878125,-1.418675128,-0.45767416,90.00000001 +4.22,50.425,-2.595239455,49.0629,0,10.00179433,-2.428125,-1.31696303,-0.357103738,90.00000001 +4.23,50.425,-2.595238047,49.0874,0,10.00090609,-2.4665625,-1.214975912,-0.256221856,90.00000001 +4.24,50.425,-2.59523664,49.1122,0,9.999573707,-2.505,-1.112735089,-0.155116635,90.00000001 +4.25,50.425,-2.595235233,49.1375,0,9.998907538,-2.543125,-1.010261816,-0.053876081,90.00000001 +4.26,50.425,-2.595233826,49.1631,0,9.999573786,-2.5796875,-0.907577638,0.047411398,90.00000001 +4.27,50.425,-2.595232419,49.1891,0,10.00068417,-2.615,-0.804703868,0.148657567,90.00000001 +4.28,50.425,-2.595231011,49.2154,0,10.00068422,-2.6496875,-0.701662049,0.249774075,90.00000001 +4.29,50.425,-2.595229604,49.2421,0,9.99957391,-2.6834375,-0.598473726,0.350672802,90.00000001 +4.3,50.425,-2.595228197,49.2691,0,9.998685674,-2.71625,-0.495160382,0.451265742,90.00000001 +4.31,50.425,-2.59522679,49.2964,0,9.998685716,-2.748125,-0.391743678,0.551465174,90.00000001 +4.32,50.425,-2.595225383,49.3241,0,9.999574038,-2.7778125,-0.288245097,0.651183723,90.00000001 +4.33,50.425,-2.595223976,49.352,0,10.00068443,-2.8046875,-0.184686356,0.750334413,90.00000001 +4.34,50.425,-2.595222568,49.3802,0,10.00068447,-2.8303125,-0.081089055,0.848830786,90.00000001 +4.35,50.425,-2.595221161,49.4086,0,9.999574171,-2.85625,0.022525205,0.946587011,90.00000001 +4.36,50.425,-2.595219754,49.4373,0,9.998908006,-2.8815625,0.126134711,1.043517719,90.00000001 +4.37,50.425,-2.595218347,49.4663,0,9.99957426,-2.9046875,0.229717917,1.13953857,90.00000001 +4.38,50.425,-2.59521694,49.4954,0,10.00090672,-2.9265625,0.333253167,1.234565626,90.00000001 +4.39,50.425,-2.595215532,49.5248,0,10.00179505,-2.9484375,0.436718745,1.328516208,90.00000001 +4.4,50.425,-2.595214125,49.5544,0,10.0017951,-2.969375,0.540093222,1.42130827,90.00000001 +4.41,50.425,-2.595212717,49.5842,0,10.00090686,-2.988125,0.643354828,1.51286091,90.00000001 +4.42,50.425,-2.59521131,49.6142,0,9.999574491,-3.005,0.746482131,1.603094314,90.00000001 +4.43,50.425,-2.595209903,49.6443,0,9.99868626,-3.02125,0.849453476,1.691929816,90.00000001 +4.44,50.425,-2.595208496,49.6746,0,9.998686308,-3.0365625,0.95224749,1.779289894,90.00000001 +4.45,50.425,-2.595207089,49.7051,0,9.999574634,-3.049375,1.054842574,1.86509846,90.00000001 +4.46,50.425,-2.595205682,49.7356,0,10.00068503,-3.06,1.157217412,1.949280628,90.00000001 +4.47,50.425,-2.595204274,49.7663,0,10.00068508,-3.07,1.259350577,2.031762944,90.00000001 +4.48,50.425,-2.595202867,49.797,0,9.999574777,-3.0796875,1.361220754,2.112473561,90.00000001 +4.49,50.425,-2.59520146,49.8279,0,9.998908617,-3.0884375,1.462806629,2.191342061,90.00000001 +4.5,50.425,-2.595200053,49.8588,0,9.999574874,-3.0959375,1.564087061,2.268299689,90.00000001 +4.51,50.425,-2.595198646,49.8898,0,10.00068527,-3.1015625,1.665040792,2.343279353,90.00000001 +4.52,50.425,-2.595197238,49.9209,0,10.00068532,-3.1046875,1.765646852,2.41621562,90.00000001 +4.53,50.425,-2.595195831,49.9519,0,9.99957502,-3.1065625,1.865884157,2.487044891,90.00000001 +4.54,50.425,-2.595194424,49.983,0,9.99868679,-3.1084375,1.965731793,2.555705403,90.00000001 +4.55,50.425,-2.595193017,50.0141,0,9.998686839,-3.1096875,2.065168905,2.622137339,90.00000001 +4.56,50.425,-2.59519161,50.0452,0,9.999575166,-3.109375,2.164174751,2.686282714,90.00000001 +4.57,50.425,-2.595190203,50.0763,0,10.00090763,-3.1065625,2.262728591,2.748085666,90.00000001 +4.58,50.425,-2.595188795,50.1074,0,10.00179596,-3.10125,2.360809971,2.807492165,90.00000001 +4.59,50.425,-2.595187388,50.1383,0,10.00179601,-3.095,2.458398262,2.864450529,90.00000001 +4.6,50.425,-2.59518598,50.1693,0,10.00090778,-3.0884375,2.555473184,2.918911085,90.00000001 +4.61,50.425,-2.595184573,50.2001,0,9.999575408,-3.08125,2.652014395,2.970826275,90.00000001 +4.62,50.425,-2.595183166,50.2309,0,9.998687178,-3.073125,2.748001785,3.020150836,90.00000001 +4.63,50.425,-2.595181759,50.2616,0,9.998687226,-3.0628125,2.843415301,3.066841797,90.00000001 +4.64,50.425,-2.595180352,50.2922,0,9.999575552,-3.05,2.938235003,3.11085842,90.00000001 +4.65,50.425,-2.595178945,50.3226,0,10.00068595,-3.0365625,3.032441067,3.152162375,90.00000001 +4.66,50.425,-2.595177537,50.3529,0,10.000686,-3.023125,3.126013842,3.190717564,90.00000001 +4.67,50.425,-2.59517613,50.3831,0,9.999575695,-3.0078125,3.218933845,3.226490356,90.00000001 +4.68,50.425,-2.595174723,50.4131,0,9.998909533,-2.9896875,3.31118154,3.259449639,90.00000001 +4.69,50.425,-2.595173316,50.4429,0,9.999575788,-2.97,3.402737789,3.28956665,90.00000001 +4.7,50.425,-2.595171909,50.4725,0,10.00068618,-2.95,3.493583399,3.31681509,90.00000001 +4.71,50.425,-2.595170501,50.5019,0,10.00068623,-2.9296875,3.583699404,3.341171239,90.00000001 +4.72,50.425,-2.595169094,50.5311,0,9.999575926,-2.908125,3.673067069,3.362613841,90.00000001 +4.73,50.425,-2.595167687,50.5601,0,9.998909762,-2.8846875,3.761667601,3.381124159,90.00000001 +4.74,50.425,-2.59516628,50.5888,0,9.999576016,-2.8596875,3.84948255,3.396686094,90.00000001 +4.75,50.425,-2.595164873,50.6173,0,10.00068641,-2.8334375,3.936493583,3.409286066,90.00000001 +4.76,50.425,-2.595163465,50.6455,0,10.00090852,-2.80625,4.022682592,3.418913132,90.00000001 +4.77,50.425,-2.595162058,50.6734,0,10.0006865,-2.778125,4.108031474,3.425558813,90.00000001 +4.78,50.425,-2.595160651,50.7011,0,10.00090861,-2.748125,4.192522409,3.429217377,90.00000001 +4.79,50.425,-2.595159243,50.7284,0,10.00068658,-2.7165625,4.276137864,3.429885561,90.00000001 +4.8,50.425,-2.595157836,50.7554,0,9.999576276,-2.685,4.35886025,3.427562904,90.00000001 +4.81,50.425,-2.595156429,50.7821,0,9.998910109,-2.653125,4.440672321,3.422251299,90.00000001 +4.82,50.425,-2.595155022,50.8085,0,9.99957636,-2.6196875,4.521557059,3.4139555,90.00000001 +4.83,50.425,-2.595153615,50.8345,0,10.00068675,-2.5846875,4.601497506,3.40268267,90.00000001 +4.84,50.425,-2.595152207,50.8602,0,10.00068679,-2.548125,4.680477045,3.388442607,90.00000001 +4.85,50.425,-2.5951508,50.8855,0,9.99957648,-2.5096875,4.758479061,3.371247799,90.00000001 +4.86,50.425,-2.595149393,50.9104,0,9.99868824,-2.47,4.835487339,3.351113203,90.00000001 +4.87,50.425,-2.595147986,50.9349,0,9.998688278,-2.43,4.911485836,3.328056407,90.00000001 +4.88,50.425,-2.595146579,50.959,0,9.999576595,-2.39,4.986458567,3.302097466,90.00000001 +4.89,50.425,-2.595145172,50.9827,0,10.00068698,-2.3496875,5.060390004,3.273259068,90.00000001 +4.9,50.425,-2.595143764,51.006,0,10.00068702,-2.3078125,5.133264563,3.241566366,90.00000001 +4.91,50.425,-2.595142357,51.0289,0,9.999798774,-2.263125,5.205067176,3.207046919,90.00000001 +4.92,50.425,-2.59514095,51.0513,0,9.999798809,-2.216875,5.275782772,3.169730923,90.00000001 +4.93,50.425,-2.595139543,51.0732,0,10.00068712,-2.1715625,5.345396572,3.129650806,90.00000001 +4.94,50.425,-2.595138135,51.0947,0,10.00090923,-2.1265625,5.41389402,3.086841634,90.00000001 +4.95,50.425,-2.595136728,51.1158,0,10.00068719,-2.079375,5.481260908,3.041340706,90.00000001 +4.96,50.425,-2.595135321,51.1363,0,10.00090929,-2.03,5.547483026,2.993187672,90.00000001 +4.97,50.425,-2.595133913,51.1564,0,10.00068725,-1.98,5.612546681,2.942424528,90.00000001 +4.98,50.425,-2.595132506,51.1759,0,9.999576935,-1.9296875,5.676438236,2.889095564,90.00000001 +4.99,50.425,-2.595131099,51.195,0,9.998688686,-1.8784375,5.739144284,2.833247248,90.00000001 +5,50.425,-2.595129692,51.2135,0,9.998688715,-1.8265625,5.800651876,2.77492828,90.00000001 +5.01,50.425,-2.595128285,51.2315,0,9.999577022,-1.775,5.860948006,2.71418954,90.00000001 +5.02,50.425,-2.595126878,51.249,0,10.0006874,-1.723125,5.920020184,2.651084026,90.00000001 +5.03,50.425,-2.59512547,51.266,0,10.00068742,-1.6696875,5.977855977,2.585666684,90.00000001 +5.04,50.425,-2.595124063,51.2824,0,9.999577101,-1.6146875,6.034443466,2.517994639,90.00000001 +5.05,50.425,-2.595122656,51.2983,0,9.998910917,-1.558125,6.089770677,2.448126848,90.00000001 +5.06,50.425,-2.595121249,51.3136,0,9.99957715,-1.5,6.143826151,2.376124216,90.00000001 +5.07,50.425,-2.595119842,51.3283,0,10.00068752,-1.441875,6.196598543,2.302049654,90.00000001 +5.08,50.425,-2.595118434,51.3424,0,10.00068754,-1.3853125,6.248076853,2.225967562,90.00000001 +5.09,50.425,-2.595117027,51.356,0,9.999799286,-1.3296875,6.298250309,2.147944461,90.00000001 +5.1,50.425,-2.59511562,51.369,0,9.999799307,-1.2728125,6.347108482,2.068048304,90.00000001 +5.11,50.425,-2.595114213,51.3815,0,10.00068761,-1.213125,6.394641176,1.98634882,90.00000001 +5.12,50.425,-2.595112805,51.3933,0,10.00068762,-1.1515625,6.440838419,1.902917169,90.00000001 +5.13,50.425,-2.595111398,51.4045,0,9.999799361,-1.0903125,6.485690529,1.817826119,90.00000001 +5.14,50.425,-2.595109991,51.4151,0,9.999799378,-1.03,6.529188225,1.73114998,90.00000001 +5.15,50.425,-2.595108584,51.4251,0,10.00068767,-0.97,6.571322338,1.642964155,90.00000001 +5.16,50.425,-2.595107176,51.4345,0,10.00068769,-0.9096875,6.612084159,1.553345706,90.00000001 +5.17,50.425,-2.595105769,51.4433,0,9.999577353,-0.848125,6.651465153,1.462372728,90.00000001 +5.18,50.425,-2.595104362,51.4515,0,9.998911156,-0.785,6.68945701,1.370124461,90.00000001 +5.19,50.425,-2.595102955,51.459,0,9.999577377,-0.7215625,6.726051882,1.276681519,90.00000001 +5.2,50.425,-2.595101548,51.4659,0,10.00068774,-0.6584375,6.761242148,1.182125205,90.00000001 +5.21,50.425,-2.59510014,51.4722,0,10.00068775,-0.595,6.795020359,1.08653814,90.00000001 +5.22,50.425,-2.595098733,51.4778,0,9.999577407,-0.5315625,6.827379583,0.990003518,90.00000001 +5.23,50.425,-2.595097326,51.4828,0,9.998689136,-0.4684375,6.858312944,0.892605678,90.00000001 +5.24,50.425,-2.595095919,51.4872,0,9.998689142,-0.405,6.887814025,0.794429417,90.00000001 +5.25,50.425,-2.595094512,51.4909,0,9.999577427,-0.3415625,6.915876696,0.69556045,90.00000001 +5.26,50.425,-2.595093105,51.494,0,10.00068778,-0.2784375,6.942495054,0.596084893,90.00000001 +5.27,50.425,-2.595091697,51.4965,0,10.00090985,-0.2146875,6.9676636,0.496089548,90.00000001 +5.28,50.425,-2.59509029,51.4983,0,10.00068779,-0.1496875,6.991377006,0.39566162,90.00000001 +5.29,50.425,-2.595088883,51.4995,0,10.00090986,-0.08375,7.013630343,0.294888657,90.00000001 +5.3,50.425,-2.595087475,51.5,0,10.00068779,-0.0184375,7.034419028,0.193858551,90.00000001 +5.31,50.425,-2.595086068,51.4998,0,9.999799511,0.045,7.053738592,0.092659422,90.00000001 +5.32,50.425,-2.595084661,51.4991,0,9.99979951,0.1084375,7.071585138,-0.008620494,90.00000001 +5.33,50.425,-2.595083254,51.4977,0,10.00068779,0.17375,7.087954829,-0.109892961,90.00000001 +5.34,50.425,-2.595081846,51.4956,0,10.00068778,0.239375,7.102844341,-0.211069573,90.00000001 +5.35,50.425,-2.595080439,51.4929,0,9.99957743,0.3034375,7.116250464,-0.312062093,90.00000001 +5.36,50.425,-2.595079032,51.4895,0,9.998689146,0.3665625,7.12817045,-0.412782516,90.00000001 +5.37,50.425,-2.595077625,51.4856,0,9.99868914,0.43,7.138601834,-0.513143007,90.00000001 +5.38,50.425,-2.595076218,51.4809,0,9.999577412,0.4934375,7.147542382,-0.613056017,90.00000001 +5.39,50.425,-2.595074811,51.4757,0,10.00068775,0.5565625,7.154990318,-0.712434401,90.00000001 +5.4,50.425,-2.595073403,51.4698,0,10.00068774,0.6203125,7.16094398,-0.811191584,90.00000001 +5.41,50.425,-2.595071996,51.4633,0,9.999577384,0.6846875,7.165402164,-0.909241336,90.00000001 +5.42,50.425,-2.595070589,51.4561,0,9.998911164,0.748125,7.168363955,-1.006498228,90.00000001 +5.43,50.425,-2.595069182,51.4483,0,9.999577361,0.8096875,7.169828722,-1.102877464,90.00000001 +5.44,50.425,-2.595067775,51.4399,0,10.0006877,0.8703125,7.169796178,-1.198294991,90.00000001 +5.45,50.425,-2.595066367,51.4309,0,10.00090975,0.931875,7.168266323,-1.292667557,90.00000001 +5.46,50.425,-2.59506496,51.4213,0,10.00068767,0.9946875,7.165239444,-1.385912943,90.00000001 +5.47,50.425,-2.595063553,51.411,0,10.00090972,1.0565625,7.160716229,-1.477949732,90.00000001 +5.48,50.425,-2.595062145,51.4001,0,10.00068763,1.11625,7.154697537,-1.568697767,90.00000001 +5.49,50.425,-2.595060738,51.3887,0,9.999577268,1.175,7.147184742,-1.658077808,90.00000001 +5.5,50.425,-2.595059331,51.3766,0,9.998911039,1.23375,7.138179278,-1.746012047,90.00000001 +5.51,50.425,-2.595057924,51.364,0,9.999577228,1.293125,7.12768315,-1.832423708,90.00000001 +5.52,50.425,-2.595056517,51.3508,0,10.00068756,1.353125,7.115698477,-1.917237505,90.00000001 +5.53,50.425,-2.595055109,51.3369,0,10.00068754,1.41125,7.102227781,-2.00037941,90.00000001 +5.54,50.425,-2.595053702,51.3225,0,9.999577165,1.4665625,7.087273869,-2.081776946,90.00000001 +5.55,50.425,-2.595052295,51.3076,0,9.998910932,1.521875,7.070839892,-2.161359179,90.00000001 +5.56,50.425,-2.595050888,51.2921,0,9.999577116,1.5784375,7.052929232,-2.239056668,90.00000001 +5.57,50.425,-2.595049481,51.276,0,10.00068744,1.6346875,7.033545668,-2.314801631,90.00000001 +5.58,50.425,-2.595048073,51.2594,0,10.00068741,1.6896875,7.01269327,-2.388528064,90.00000001 +5.59,50.425,-2.595046666,51.2422,0,9.999577039,1.7434375,6.990376335,-2.460171681,90.00000001 +5.6,50.425,-2.595045259,51.2245,0,9.998688732,1.79625,6.966599503,-2.529669972,90.00000001 +5.61,50.425,-2.595043852,51.2063,0,9.998688703,1.8484375,6.941367874,-2.596962375,90.00000001 +5.62,50.425,-2.595042445,51.1875,0,9.999576952,1.8996875,6.914686548,-2.661990163,90.00000001 +5.63,50.425,-2.595041038,51.1683,0,10.00090934,1.95,6.886561253,-2.724696727,90.00000001 +5.64,50.425,-2.59503963,51.1485,0,10.00179759,2,6.856997719,-2.785027235,90.00000001 +5.65,50.425,-2.595038223,51.1283,0,10.00179756,2.049375,6.826002249,-2.842929203,90.00000001 +5.66,50.425,-2.595036815,51.1075,0,10.00090925,2.096875,6.793581203,-2.898352041,90.00000001 +5.67,50.425,-2.595035408,51.0863,0,9.999576794,2.143125,6.759741457,-2.951247505,90.00000001 +5.68,50.425,-2.595034001,51.0647,0,9.998688482,2.19,6.724489999,-3.001569471,90.00000001 +5.69,50.425,-2.595032594,51.0425,0,9.998688447,2.23625,6.687834222,-3.049273995,90.00000001 +5.7,50.425,-2.595031187,51.0199,0,9.999576691,2.2796875,6.649781746,-3.094319478,90.00000001 +5.71,50.425,-2.59502978,50.9969,0,10.000687,2.321875,6.610340592,-3.136666674,90.00000001 +5.72,50.425,-2.595028372,50.9735,0,10.00068697,2.365,6.569518896,-3.176278684,90.00000001 +5.73,50.425,-2.595026965,50.9496,0,9.99957658,2.4078125,6.52732531,-3.213120902,90.00000001 +5.74,50.425,-2.595025558,50.9253,0,9.998910333,2.448125,6.483768542,-3.247161241,90.00000001 +5.75,50.425,-2.595024151,50.9006,0,9.999576504,2.4865625,6.438857704,-3.278370023,90.00000001 +5.76,50.425,-2.595022744,50.8756,0,10.00068681,2.5246875,6.392602248,-3.306720032,90.00000001 +5.77,50.425,-2.595021336,50.8501,0,10.00068677,2.5615625,6.345011743,-3.332186516,90.00000001 +5.78,50.425,-2.595019929,50.8243,0,9.999576384,2.5965625,6.296096159,-3.354747245,90.00000001 +5.79,50.425,-2.595018522,50.7982,0,9.998910134,2.6315625,6.245865694,-3.374382623,90.00000001 +5.8,50.425,-2.595017115,50.7717,0,9.999576302,2.6665625,6.194330891,-3.391075462,90.00000001 +5.81,50.425,-2.595015708,50.7448,0,10.00068661,2.6996875,6.141502463,-3.404811266,90.00000001 +5.82,50.425,-2.5950143,50.7177,0,10.00090864,2.73125,6.087391527,-3.415578002,90.00000001 +5.83,50.425,-2.595012893,50.6902,0,10.00068652,2.7615625,6.032009254,-3.423366332,90.00000001 +5.84,50.425,-2.595011486,50.6624,0,10.00090855,2.7896875,5.975367277,-3.42816938,90.00000001 +5.85,50.425,-2.595010078,50.6344,0,10.00068644,2.8165625,5.917477398,-3.429983078,90.00000001 +5.86,50.425,-2.595008671,50.6061,0,9.999576044,2.8434375,5.858351763,-3.428805764,90.00000001 +5.87,50.425,-2.595007264,50.5775,0,9.99890979,2.8696875,5.798002691,-3.42463847,90.00000001 +5.88,50.425,-2.595005857,50.5487,0,9.999575954,2.8946875,5.736442788,-3.417484806,90.00000001 +5.89,50.425,-2.59500445,50.5196,0,10.00068626,2.918125,5.673684887,-3.407351073,90.00000001 +5.9,50.425,-2.595003042,50.4903,0,10.00068621,2.939375,5.60974211,-3.394246096,90.00000001 +5.91,50.425,-2.595001635,50.4608,0,9.999575816,2.9584375,5.544627805,-3.378181276,90.00000001 +5.92,50.425,-2.595000228,50.4311,0,9.998687491,2.9765625,5.478355611,-3.359170594,90.00000001 +5.93,50.425,-2.594998821,50.4013,0,9.998687444,2.995,5.410939276,-3.337230722,90.00000001 +5.94,50.425,-2.594997414,50.3712,0,9.999575676,3.013125,5.342392955,-3.312380683,90.00000001 +5.95,50.425,-2.594996007,50.341,0,10.00068598,3.029375,5.27273097,-3.284642249,90.00000001 +5.96,50.425,-2.594994599,50.3106,0,10.00068593,3.043125,5.201967818,-3.254039542,90.00000001 +5.97,50.425,-2.594993192,50.2801,0,9.999575534,3.0546875,5.13011828,-3.220599261,90.00000001 +5.98,50.425,-2.594991785,50.2495,0,9.998909277,3.065,5.057197426,-3.184350571,90.00000001 +5.99,50.425,-2.594990378,50.2188,0,9.999575438,3.075,4.983220438,-3.14532504,90.00000001 +6,50.425,-2.594988971,50.188,0,10.00090781,3.0846875,4.90820273,-3.103556818,90.00000001 +6.01,50.425,-2.594987563,50.1571,0,10.00179604,3.0928125,4.832160058,-3.059082173,90.00000001 +6.02,50.425,-2.594986156,50.1261,0,10.00179599,3.098125,4.755108236,-3.011940007,90.00000001 +6.03,50.425,-2.594984748,50.0951,0,10.00090766,3.1015625,4.677063362,-2.962171346,90.00000001 +6.04,50.425,-2.594983341,50.0641,0,9.999575195,3.105,4.598041711,-2.909819677,90.00000001 +6.05,50.425,-2.594981934,50.033,0,9.998686868,3.108125,4.518059839,-2.854930549,90.00000001 +6.06,50.425,-2.594980527,50.0019,0,9.99868682,3.1096875,4.437134478,-2.79755192,90.00000001 +6.07,50.425,-2.59497912,49.9708,0,9.99957505,3.1096875,4.355282415,-2.737733808,90.00000001 +6.08,50.425,-2.594977713,49.9397,0,10.00068535,3.108125,4.272520839,-2.675528296,90.00000001 +6.09,50.425,-2.594976305,49.9086,0,10.0006853,3.1046875,4.188866996,-2.6109897,90.00000001 +6.1,50.425,-2.594974898,49.8776,0,9.999574904,3.0996875,4.10433836,-2.544174284,90.00000001 +6.11,50.425,-2.594973491,49.8466,0,9.998908646,3.093125,4.01895258,-2.475140318,90.00000001 +6.12,50.425,-2.594972084,49.8157,0,9.999574807,3.0846875,3.932727474,-2.403947963,90.00000001 +6.13,50.425,-2.594970677,49.7849,0,10.00068511,3.075,3.84568109,-2.330659384,90.00000001 +6.14,50.425,-2.594969269,49.7542,0,10.00068506,3.065,3.757831591,-2.25533841,90.00000001 +6.15,50.425,-2.594967862,49.7236,0,9.999574663,3.055,3.669197312,-2.178050701,90.00000001 +6.16,50.425,-2.594966455,49.6931,0,9.998686336,3.044375,3.579796759,-2.098863751,90.00000001 +6.17,50.425,-2.594965048,49.6627,0,9.998686288,3.03125,3.489648611,-2.017846544,90.00000001 +6.18,50.425,-2.594963641,49.6324,0,9.99957452,3.0146875,3.398771718,-1.935069785,90.00000001 +6.19,50.425,-2.594962234,49.6024,0,10.00090689,2.996875,3.307185045,-1.85060555,90.00000001 +6.2,50.425,-2.594960826,49.5725,0,10.00179512,2.98,3.214907671,-1.764527579,90.00000001 +6.21,50.425,-2.594959419,49.5428,0,10.00179508,2.9628125,3.121958905,-1.676910931,90.00000001 +6.22,50.425,-2.594958011,49.5132,0,10.00090675,2.9428125,3.02835817,-1.587831979,90.00000001 +6.23,50.425,-2.594956604,49.4839,0,9.999574288,2.9196875,2.934125005,-1.497368475,90.00000001 +6.24,50.425,-2.594955197,49.4548,0,9.998908034,2.8953125,2.839279061,-1.405599143,90.00000001 +6.25,50.425,-2.59495379,49.426,0,9.999574197,2.8715625,2.743840221,-1.312604196,90.00000001 +6.26,50.425,-2.594952383,49.3974,0,10.0006845,2.848125,2.647828308,-1.218464595,90.00000001 +6.27,50.425,-2.594950975,49.369,0,10.00068446,2.8228125,2.551263491,-1.123262443,90.00000001 +6.28,50.425,-2.594949568,49.3409,0,9.999574064,2.7946875,2.454165823,-1.02708082,90.00000001 +6.29,50.425,-2.594948161,49.3131,0,9.998685743,2.7646875,2.356555644,-0.930003607,90.00000001 +6.3,50.425,-2.594946754,49.2856,0,9.9986857,2.7334375,2.258453352,-0.832115372,90.00000001 +6.31,50.425,-2.594945347,49.2584,0,9.999573936,2.7015625,2.159879401,-0.733501543,90.00000001 +6.32,50.425,-2.59494394,49.2316,0,10.00068424,2.6696875,2.060854361,-0.634248065,90.00000001 +6.33,50.425,-2.594942532,49.205,0,10.0006842,2.6365625,1.961398972,-0.534441509,90.00000001 +6.34,50.425,-2.594941125,49.1788,0,9.99957381,2.60125,1.861533975,-0.434168911,90.00000001 +6.35,50.425,-2.594939718,49.153,0,9.998907562,2.565,1.761280169,-0.333517759,90.00000001 +6.36,50.425,-2.594938311,49.1275,0,9.999573731,2.5284375,1.660658582,-0.232575716,90.00000001 +6.37,50.425,-2.594936904,49.1024,0,10.00068404,2.49125,1.559690183,-0.131430903,90.00000001 +6.38,50.425,-2.594935496,49.0777,0,10.00090607,2.453125,1.458396057,-0.030171442,90.00000001 +6.39,50.425,-2.594934089,49.0533,0,10.00068396,2.413125,1.356797348,0.071114261,90.00000001 +6.4,50.425,-2.594932682,49.0294,0,10.000906,2.37125,1.25491531,0.172338027,90.00000001 +6.41,50.425,-2.594931274,49.0059,0,10.00068389,2.3284375,1.152771202,0.273411449,90.00000001 +6.42,50.425,-2.594929867,48.9828,0,9.999573504,2.2846875,1.050386394,0.374246521,90.00000001 +6.43,50.425,-2.59492846,48.9602,0,9.998907259,2.24,0.947782144,0.474755178,90.00000001 +6.44,50.425,-2.594927053,48.938,0,9.999573434,2.195,0.844979993,0.574849874,90.00000001 +6.45,50.425,-2.594925646,48.9163,0,10.00068375,2.1496875,0.742001372,0.674443288,90.00000001 +6.46,50.425,-2.594924238,48.895,0,10.00068372,2.103125,0.638867823,0.773448562,90.00000001 +6.47,50.425,-2.594922831,48.8742,0,9.999573335,2.0546875,0.535600832,0.871779407,90.00000001 +6.48,50.425,-2.594921424,48.8539,0,9.998907094,2.005,0.432222,0.969350051,90.00000001 +6.49,50.425,-2.594920017,48.8341,0,9.999573271,1.955,0.328752927,1.066075354,90.00000001 +6.5,50.425,-2.59491861,48.8148,0,10.00068359,1.905,0.225215156,1.16187109,90.00000001 +6.51,50.425,-2.594917202,48.796,0,10.00068356,1.8546875,0.121630346,1.256653607,90.00000001 +6.52,50.425,-2.594915795,48.7777,0,9.999573184,1.803125,0.018020153,1.350340343,90.00000001 +6.53,50.425,-2.594914388,48.7599,0,9.998906947,1.75,-0.085593821,1.442849535,90.00000001 +6.54,50.425,-2.594912981,48.7427,0,9.999573128,1.69625,-0.189189862,1.534100513,90.00000001 +6.55,50.425,-2.594911574,48.726,0,10.00068345,1.641875,-0.292746426,1.624013805,90.00000001 +6.56,50.425,-2.594910166,48.7098,0,10.0009055,1.58625,-0.396241912,1.712510861,90.00000001 +6.57,50.425,-2.594908759,48.6943,0,10.0006834,1.53,-0.499654549,1.799514617,90.00000001 +6.58,50.425,-2.594907352,48.6792,0,10.00090545,1.4734375,-0.602962907,1.884949156,90.00000001 +6.59,50.425,-2.594905944,48.6648,0,10.00068335,1.41625,-0.70614533,1.968739993,90.00000001 +6.6,50.425,-2.594904537,48.6509,0,9.999572985,1.35875,-0.809180273,2.050814078,90.00000001 +6.61,50.425,-2.59490313,48.6376,0,9.998684686,1.30125,-0.91204625,2.131099846,90.00000001 +6.62,50.425,-2.594901723,48.6249,0,9.998684666,1.243125,-1.01472172,2.209527226,90.00000001 +6.63,50.425,-2.594900316,48.6127,0,9.999572925,1.183125,-1.117185309,2.286027863,90.00000001 +6.64,50.425,-2.594898909,48.6012,0,10.00068326,1.121875,-1.21941559,2.360535065,90.00000001 +6.65,50.425,-2.594897501,48.5903,0,10.00068324,1.061875,-1.321391192,2.432983802,90.00000001 +6.66,50.425,-2.594896094,48.58,0,9.999572874,1.0028125,-1.423090856,2.503310991,90.00000001 +6.67,50.425,-2.594894687,48.5702,0,9.99890665,0.9415625,-1.524493328,2.571455268,90.00000001 +6.68,50.425,-2.59489328,48.5611,0,9.999572845,0.878125,-1.625577407,2.63735716,90.00000001 +6.69,50.425,-2.594891873,48.5527,0,10.00068318,0.8153125,-1.726322009,2.700959257,90.00000001 +6.7,50.425,-2.594890465,48.5448,0,10.00068317,0.7534375,-1.826706105,2.762206039,90.00000001 +6.71,50.425,-2.594889058,48.5376,0,9.999572808,0.69125,-1.926708726,2.821044164,90.00000001 +6.72,50.425,-2.594887651,48.531,0,9.998906589,0.6284375,-2.026308959,2.877422294,90.00000001 +6.73,50.425,-2.594886244,48.525,0,9.999572789,0.565,-2.125486005,2.93129127,90.00000001 +6.74,50.425,-2.594884837,48.5197,0,10.00068313,0.5015625,-2.224219181,2.98260411,90.00000001 +6.75,50.425,-2.594883429,48.515,0,10.00090519,0.4384375,-2.32248786,3.031316122,90.00000001 +6.76,50.425,-2.594882022,48.5109,0,10.00068311,0.3746875,-2.420271531,3.077384736,90.00000001 +6.77,50.425,-2.594880615,48.5075,0,10.00090518,0.31,-2.517549795,3.120769845,90.00000001 +6.78,50.425,-2.594879207,48.5047,0,10.00068311,0.2453125,-2.614302255,3.161433577,90.00000001 +6.79,50.425,-2.5948778,48.5026,0,9.999572753,0.1815625,-2.710508745,3.199340465,90.00000001 +6.8,50.425,-2.594876393,48.5011,0,9.998906541,0.118125,-2.806149209,3.234457564,90.00000001 +6.81,50.425,-2.594874986,48.5002,0,9.999572749,0.0534375,-2.901203595,3.266754106,90.00000001 +6.82,50.425,-2.594873579,48.5,0,10.0006831,-0.011875,-2.995652135,3.296201959,90.00000001 +6.83,50.425,-2.594872171,48.5005,0,10.0006831,-0.07625,-3.089475063,3.32277557,90.00000001 +6.84,50.425,-2.594870764,48.5015,0,9.999572752,-0.14,-3.18265284,3.346451618,90.00000001 +6.85,50.425,-2.594869357,48.5033,0,9.998684476,-0.20375,-3.275165928,3.367209478,90.00000001 +6.86,50.425,-2.59486795,48.5056,0,9.998684479,-0.268125,-3.36699502,3.385031101,90.00000001 +6.87,50.425,-2.594866543,48.5086,0,9.999572762,-0.3334375,-3.458120978,3.39990096,90.00000001 +6.88,50.425,-2.594865136,48.5123,0,10.00068312,-0.398125,-3.548524723,3.411806049,90.00000001 +6.89,50.425,-2.594863728,48.5166,0,10.00068312,-0.4615625,-3.638187404,3.420735998,90.00000001 +6.9,50.425,-2.594862321,48.5215,0,9.999794853,-0.525,-3.727090343,3.426682956,90.00000001 +6.91,50.425,-2.594860914,48.5271,0,9.999794861,-0.5884375,-3.815214919,3.429641824,90.00000001 +6.92,50.425,-2.594859507,48.5333,0,10.00068315,-0.6515625,-3.902542682,3.429610025,90.00000001 +6.93,50.425,-2.594858099,48.5401,0,10.00090523,-0.715,-3.989055528,3.426587558,90.00000001 +6.94,50.425,-2.594856692,48.5476,0,10.00068317,-0.778125,-4.074735235,3.420577002,90.00000001 +6.95,50.425,-2.594855285,48.5557,0,10.00090525,-0.8396875,-4.159564043,3.411583684,90.00000001 +6.96,50.425,-2.594853877,48.5644,0,10.0006832,-0.9003125,-4.243524133,3.399615398,90.00000001 +6.97,50.425,-2.59485247,48.5737,0,9.999572864,-0.9615625,-4.326598085,3.384682628,90.00000001 +6.98,50.425,-2.594851063,48.5836,0,9.998684602,-1.0234375,-4.408768426,3.366798324,90.00000001 +6.99,50.425,-2.594849656,48.5942,0,9.998684618,-1.0846875,-4.490018024,3.345978183,90.00000001 +7,50.425,-2.594848249,48.6053,0,9.999572914,-1.145,-4.570330034,3.322240255,90.00000001 +7.01,50.425,-2.594846842,48.6171,0,10.00068328,-1.205,-4.649687496,3.295605281,90.00000001 +7.02,50.425,-2.594845434,48.6294,0,10.0006833,-1.2646875,-4.728073967,3.266096522,90.00000001 +7.03,50.425,-2.594844027,48.6424,0,9.999572971,-1.323125,-4.805473059,3.233739647,90.00000001 +7.04,50.425,-2.59484262,48.6559,0,9.998906784,-1.38,-4.881868559,3.198562904,90.00000001 +7.05,50.425,-2.594841213,48.67,0,9.999573016,-1.436875,-4.957244594,3.160596944,90.00000001 +7.06,50.425,-2.594839806,48.6846,0,10.00068339,-1.4946875,-5.031585295,3.119874943,90.00000001 +7.07,50.425,-2.594838398,48.6999,0,10.00068341,-1.5515625,-5.104875249,3.076432366,90.00000001 +7.08,50.425,-2.594836991,48.7157,0,9.999795156,-1.60625,-5.177099157,3.030307086,90.00000001 +7.09,50.425,-2.594835584,48.732,0,9.999795182,-1.6603125,-5.248241837,2.981539325,90.00000001 +7.1,50.425,-2.594834177,48.7489,0,10.00068349,-1.7146875,-5.318288506,2.930171596,90.00000001 +7.11,50.425,-2.594832769,48.7663,0,10.00068351,-1.768125,-5.387224553,2.876248705,90.00000001 +7.12,50.425,-2.594831362,48.7843,0,9.999795263,-1.82,-5.455035483,2.819817747,90.00000001 +7.13,50.425,-2.594829955,48.8027,0,9.999795292,-1.8715625,-5.521707259,2.760927828,90.00000001 +7.14,50.425,-2.594828548,48.8217,0,10.0006836,-1.9234375,-5.587225842,2.699630339,90.00000001 +7.15,50.425,-2.59482714,48.8412,0,10.00068363,-1.9746875,-5.651577654,2.635978739,90.00000001 +7.16,50.425,-2.594825733,48.8612,0,9.999573314,-2.0246875,-5.714749173,2.570028489,90.00000001 +7.17,50.425,-2.594824326,48.8817,0,9.998907137,-2.073125,-5.776727221,2.501837172,90.00000001 +7.18,50.425,-2.594822919,48.9027,0,9.999573378,-2.12,-5.837498907,2.431464204,90.00000001 +7.19,50.425,-2.594821512,48.9241,0,10.00068376,-2.1665625,-5.897051509,2.358971005,90.00000001 +7.2,50.425,-2.594820104,48.946,0,10.0006838,-2.213125,-5.955372597,2.284420716,90.00000001 +7.21,50.425,-2.594818697,48.9684,0,9.999573482,-2.258125,-6.012449965,2.207878368,90.00000001 +7.22,50.425,-2.59481729,48.9912,0,9.998685239,-2.30125,-6.068271696,2.129410709,90.00000001 +7.23,50.425,-2.594815883,49.0144,0,9.998685275,-2.3434375,-6.122826159,2.049086209,90.00000001 +7.24,50.425,-2.594814476,49.0381,0,9.99957359,-2.385,-6.176101952,1.966974825,90.00000001 +7.25,50.425,-2.594813069,49.0621,0,10.00068398,-2.42625,-6.22808796,1.883148292,90.00000001 +7.26,50.425,-2.594811661,49.0866,0,10.00090608,-2.4665625,-6.278773296,1.797679548,90.00000001 +7.27,50.425,-2.594810254,49.1115,0,10.00068405,-2.5046875,-6.328147361,1.710643248,90.00000001 +7.28,50.425,-2.594808847,49.1367,0,10.00090616,-2.5415625,-6.376199899,1.622115195,90.00000001 +7.29,50.425,-2.594807439,49.1623,0,10.00068413,-2.5784375,-6.422920883,1.532172681,90.00000001 +7.3,50.425,-2.594806032,49.1883,0,9.999573826,-2.6146875,-6.468300515,1.44089403,90.00000001 +7.31,50.425,-2.594804625,49.2146,0,9.998907658,-2.6496875,-6.512329285,1.34835894,90.00000001 +7.32,50.425,-2.594803218,49.2413,0,9.999573909,-2.683125,-6.554998025,1.254648083,90.00000001 +7.33,50.425,-2.594801811,49.2683,0,10.0006843,-2.7146875,-6.596297912,1.159843106,90.00000001 +7.34,50.425,-2.594800403,49.2956,0,10.00068434,-2.745,-6.636220178,1.064026743,90.00000001 +7.35,50.425,-2.594798996,49.3232,0,9.999574036,-2.7746875,-6.674756575,0.967282533,90.00000001 +7.36,50.425,-2.594797589,49.3511,0,9.998907872,-2.803125,-6.711899022,0.869694872,90.00000001 +7.37,50.425,-2.594796182,49.3793,0,9.999574125,-2.83,-6.747639786,0.771348786,90.00000001 +7.38,50.425,-2.594794775,49.4077,0,10.00068452,-2.8565625,-6.781971417,0.672330105,90.00000001 +7.39,50.425,-2.594793367,49.4364,0,10.00068456,-2.8828125,-6.814886696,0.572725117,90.00000001 +7.4,50.425,-2.59479196,49.4654,0,9.999574259,-2.90625,-6.846378806,0.472620681,90.00000001 +7.41,50.425,-2.594790553,49.4946,0,9.998908096,-2.9265625,-6.876441099,0.372104174,90.00000001 +7.42,50.425,-2.594789146,49.5239,0,9.999574351,-2.946875,-6.905067331,0.271263144,90.00000001 +7.43,50.425,-2.594787739,49.5535,0,10.00068475,-2.968125,-6.932251543,0.170185539,90.00000001 +7.44,50.425,-2.594786331,49.5833,0,10.00090686,-2.9878125,-6.957988062,0.068959596,90.00000001 +7.45,50.425,-2.594784924,49.6133,0,10.00068484,-3.0046875,-6.982271446,-0.032326508,90.00000001 +7.46,50.425,-2.594783517,49.6434,0,10.00090696,-3.02,-7.005096709,-0.133584422,90.00000001 +7.47,50.425,-2.594782109,49.6737,0,10.00068493,-3.0346875,-7.02645904,-0.234725854,90.00000001 +7.48,50.425,-2.594780702,49.7041,0,9.999574633,-3.048125,-7.046353968,-0.335662626,90.00000001 +7.49,50.425,-2.594779295,49.7347,0,9.998908472,-3.06,-7.064777368,-0.436306616,90.00000001 +7.5,50.425,-2.594777888,49.7653,0,9.999574728,-3.07125,-7.081725403,-0.53657022,90.00000001 +7.51,50.425,-2.594776481,49.7961,0,10.00068512,-3.0815625,-7.097194461,-0.636365888,90.00000001 +7.52,50.425,-2.594775073,49.827,0,10.00068517,-3.089375,-7.111181392,-0.735606648,90.00000001 +7.53,50.425,-2.594773666,49.8579,0,9.999574873,-3.095,-7.123683274,-0.834205923,90.00000001 +7.54,50.425,-2.594772259,49.8889,0,9.998686643,-3.1,-7.134697414,-0.932077829,90.00000001 +7.55,50.425,-2.594770852,49.9199,0,9.998686691,-3.1046875,-7.144221576,-1.029136879,90.00000001 +7.56,50.425,-2.594769445,49.951,0,9.999575018,-3.108125,-7.152253814,-1.125298506,90.00000001 +7.57,50.425,-2.594768038,49.9821,0,10.00068542,-3.1096875,-7.158792294,-1.220478885,90.00000001 +7.58,50.425,-2.59476663,50.0132,0,10.00068546,-3.1096875,-7.163835812,-1.314594995,90.00000001 +7.59,50.425,-2.594765223,50.0443,0,9.999575165,-3.108125,-7.167383281,-1.407564732,90.00000001 +7.6,50.425,-2.594763816,50.0754,0,9.998909004,-3.1046875,-7.169433897,-1.499307077,90.00000001 +7.61,50.425,-2.594762409,50.1064,0,9.999575262,-3.1,-7.169987259,-1.589741991,90.00000001 +7.62,50.425,-2.594761002,50.1374,0,10.00090773,-3.095,-7.169043254,-1.678790633,90.00000001 +7.63,50.425,-2.594759594,50.1683,0,10.00179606,-3.0896875,-7.16660211,-1.766375311,90.00000001 +7.64,50.425,-2.594758187,50.1992,0,10.0017961,-3.0828125,-7.162664343,-1.852419763,90.00000001 +7.65,50.425,-2.594756779,50.23,0,10.00090787,-3.073125,-7.157230698,-1.936848819,90.00000001 +7.66,50.425,-2.594755372,50.2607,0,9.999575503,-3.0615625,-7.150302377,-2.019588909,90.00000001 +7.67,50.425,-2.594753965,50.2912,0,9.998687272,-3.05,-7.141880815,-2.100567899,90.00000001 +7.68,50.425,-2.594752558,50.3217,0,9.99868732,-3.0378125,-7.131967728,-2.179715143,90.00000001 +7.69,50.425,-2.594751151,50.352,0,9.999575646,-3.023125,-7.120565238,-2.256961657,90.00000001 +7.7,50.425,-2.594749744,50.3822,0,10.00068604,-3.0065625,-7.107675693,-2.332240118,90.00000001 +7.71,50.425,-2.594748336,50.4121,0,10.00068609,-2.9896875,-7.093301843,-2.40548475,90.00000001 +7.72,50.425,-2.594746929,50.442,0,9.999575786,-2.9715625,-7.077446611,-2.476631785,90.00000001 +7.73,50.425,-2.594745522,50.4716,0,9.998909623,-2.95125,-7.060113377,-2.545619169,90.00000001 +7.74,50.425,-2.594744115,50.501,0,9.999575879,-2.93,-7.041305694,-2.612386743,90.00000001 +7.75,50.425,-2.594742708,50.5302,0,10.00068627,-2.908125,-7.021027572,-2.676876294,90.00000001 +7.76,50.425,-2.5947413,50.5592,0,10.00068632,-2.8846875,-6.999283136,-2.739031558,90.00000001 +7.77,50.425,-2.594739893,50.5879,0,9.999576015,-2.86,-6.976077027,-2.798798332,90.00000001 +7.78,50.425,-2.594738486,50.6164,0,9.99868778,-2.8346875,-6.951414059,-2.856124536,90.00000001 +7.79,50.425,-2.594737079,50.6446,0,9.998687825,-2.808125,-6.92529933,-2.910960092,90.00000001 +7.8,50.425,-2.594735672,50.6726,0,9.999576148,-2.7796875,-6.897738399,-2.96325733,90.00000001 +7.81,50.425,-2.594734265,50.7002,0,10.00090861,-2.7496875,-6.868736937,-3.012970529,90.00000001 +7.82,50.425,-2.594732857,50.7276,0,10.00179693,-2.7184375,-6.838301018,-3.060056373,90.00000001 +7.83,50.425,-2.59473145,50.7546,0,10.00179697,-2.68625,-6.806437058,-3.10447378,90.00000001 +7.84,50.425,-2.594730042,50.7813,0,10.00090873,-2.6534375,-6.773151591,-3.146184076,90.00000001 +7.85,50.425,-2.594728635,50.8077,0,9.999576358,-2.6196875,-6.738451663,-3.185150821,90.00000001 +7.86,50.425,-2.594727228,50.8337,0,9.99891019,-2.5846875,-6.70234455,-3.221340096,90.00000001 +7.87,50.425,-2.594725821,50.8594,0,9.99957644,-2.5484375,-6.664837644,-3.254720273,90.00000001 +7.88,50.425,-2.594724414,50.8847,0,10.00068683,-2.51125,-6.625938966,-3.285262361,90.00000001 +7.89,50.425,-2.594723006,50.9096,0,10.00068687,-2.473125,-6.585656481,-3.312939603,90.00000001 +7.9,50.425,-2.594721599,50.9342,0,9.999576557,-2.433125,-6.543998668,-3.337727878,90.00000001 +7.91,50.425,-2.594720192,50.9583,0,9.998688316,-2.3915625,-6.500974236,-3.359605641,90.00000001 +7.92,50.425,-2.594718785,50.982,0,9.998688353,-2.35,-6.45659218,-3.378553813,90.00000001 +7.93,50.425,-2.594717378,51.0053,0,9.999576668,-2.308125,-6.410861725,-3.39455578,90.00000001 +7.94,50.425,-2.594715971,51.0282,0,10.00068705,-2.2646875,-6.36379244,-3.407597674,90.00000001 +7.95,50.425,-2.594714563,51.0506,0,10.00068709,-2.2196875,-6.31539418,-3.417668095,90.00000001 +7.96,50.425,-2.594713156,51.0726,0,9.999576773,-2.1734375,-6.265677028,-3.424758219,90.00000001 +7.97,50.425,-2.594711749,51.0941,0,9.998910598,-2.1265625,-6.214651355,-3.428861914,90.00000001 +7.98,50.425,-2.594710342,51.1151,0,9.99957684,-2.0796875,-6.162327817,-3.42997563,90.00000001 +7.99,50.425,-2.594708935,51.1357,0,10.00090929,-2.0315625,-6.108717417,-3.428098333,90.00000001 +8,50.425,-2.594707527,51.1558,0,10.0017976,-1.9815625,-6.053831211,-3.423231687,90.00000001 +8.01,50.425,-2.59470612,51.1753,0,10.00179763,-1.9315625,-5.997680775,-3.415379931,90.00000001 +8.02,50.425,-2.594704712,51.1944,0,10.00090938,-1.8815625,-5.940277795,-3.404549883,90.00000001 +8.03,50.425,-2.594703305,51.213,0,9.999576993,-1.8296875,-5.881634304,-3.390751054,90.00000001 +8.04,50.425,-2.594701898,51.231,0,9.998688741,-1.7765625,-5.821762449,-3.373995418,90.00000001 +8.05,50.425,-2.594700491,51.2485,0,9.998688769,-1.7234375,-5.760674835,-3.354297645,90.00000001 +8.06,50.425,-2.594699084,51.2655,0,9.999577075,-1.6696875,-5.698384181,-3.331674865,90.00000001 +8.07,50.425,-2.594697677,51.2819,0,10.00068745,-1.6146875,-5.634903437,-3.306146788,90.00000001 +8.08,50.425,-2.594696269,51.2978,0,10.00068747,-1.5584375,-5.570245952,-3.277735701,90.00000001 +8.09,50.425,-2.594694862,51.3131,0,9.999577149,-1.5015625,-5.504425248,-3.246466415,90.00000001 +8.1,50.425,-2.594693455,51.3278,0,9.998910962,-1.4453125,-5.437454961,-3.212366087,90.00000001 +8.11,50.425,-2.594692048,51.342,0,9.999577194,-1.3896875,-5.36934913,-3.175464626,90.00000001 +8.12,50.425,-2.594690641,51.3556,0,10.00068756,-1.3328125,-5.300121962,-3.135794059,90.00000001 +8.13,50.425,-2.594689233,51.3687,0,10.00068759,-1.2734375,-5.229787955,-3.093389052,90.00000001 +8.14,50.425,-2.594687826,51.3811,0,9.999577256,-1.213125,-5.158361776,-3.048286502,90.00000001 +8.15,50.425,-2.594686419,51.3929,0,9.998688995,-1.1534375,-5.085858321,-3.000525886,90.00000001 +8.16,50.425,-2.594685012,51.4042,0,9.998689012,-1.093125,-5.012292775,-2.950148744,90.00000001 +8.17,50.425,-2.594683605,51.4148,0,9.999577308,-1.0315625,-4.937680435,-2.897198964,90.00000001 +8.18,50.425,-2.594682198,51.4248,0,10.00090974,-0.9703125,-4.862036942,-2.841722841,90.00000001 +8.19,50.425,-2.59468079,51.4342,0,10.00179804,-0.91,-4.785378112,-2.783768733,90.00000001 +8.2,50.425,-2.594679383,51.443,0,10.00179805,-0.8496875,-4.70771987,-2.72338706,90.00000001 +8.21,50.425,-2.594677975,51.4512,0,10.00090978,-0.788125,-4.629078491,-2.660630591,90.00000001 +8.22,50.425,-2.594676568,51.4588,0,9.999577377,-0.725,-4.549470417,-2.595553988,90.00000001 +8.23,50.425,-2.594675161,51.4657,0,9.998911179,-0.6615625,-4.468912207,-2.528214086,90.00000001 +8.24,50.425,-2.594673754,51.472,0,9.999577398,-0.5984375,-4.387420764,-2.4586695,90.00000001 +8.25,50.425,-2.594672347,51.4777,0,10.00068776,-0.5346875,-4.305012989,-2.386980906,90.00000001 +8.26,50.425,-2.594670939,51.4827,0,10.00068776,-0.47,-4.221706243,-2.313210814,90.00000001 +8.27,50.425,-2.594669532,51.4871,0,9.999577421,-0.4053125,-4.13751783,-2.237423624,90.00000001 +8.28,50.425,-2.594668125,51.4908,0,9.998689148,-0.3415625,-4.05246534,-2.159685341,90.00000001 +8.29,50.425,-2.594666718,51.4939,0,9.998689154,-0.2784375,-3.966566533,-2.080063745,90.00000001 +8.3,50.425,-2.594665311,51.4964,0,9.999577436,-0.215,-3.879839401,-1.998628337,90.00000001 +8.31,50.425,-2.594663904,51.4982,0,10.00068779,-0.1515625,-3.792301935,-1.915450106,90.00000001 +8.32,50.425,-2.594662496,51.4994,0,10.00068779,-0.088125,-3.703972584,-1.830601531,90.00000001 +8.33,50.425,-2.594661089,51.5,0,9.999577442,-0.023125,-3.614869683,-1.744156695,90.00000001 +8.34,50.425,-2.594659682,51.4999,0,9.998911233,0.043125,-3.525011795,-1.656190886,90.00000001 +8.35,50.425,-2.594658275,51.4991,0,9.999577441,0.108125,-3.434417829,-1.566780879,90.00000001 +8.36,50.425,-2.594656868,51.4977,0,10.00068779,0.1715625,-3.343106634,-1.476004655,90.00000001 +8.37,50.425,-2.59465546,51.4957,0,10.00090985,0.2353125,-3.251097232,-1.383941281,90.00000001 +8.38,50.425,-2.594654053,51.493,0,10.00068778,0.3,-3.158408875,-1.290671085,90.00000001 +8.39,50.425,-2.594652646,51.4897,0,10.00090984,0.365,-3.06506093,-1.196275429,90.00000001 +8.4,50.425,-2.594651238,51.4857,0,10.00068777,0.4296875,-2.971072933,-1.100836589,90.00000001 +8.41,50.425,-2.594649831,51.4811,0,9.999577412,0.493125,-2.876464423,-1.004437815,90.00000001 +8.42,50.425,-2.594648424,51.4758,0,9.998911194,0.5553125,-2.781255224,-0.90716316,90.00000001 +8.43,50.425,-2.594647017,51.47,0,9.999577394,0.618125,-2.685465161,-0.809097423,90.00000001 +8.44,50.425,-2.59464561,51.4635,0,10.00068773,0.681875,-2.589114286,-0.710326145,90.00000001 +8.45,50.425,-2.594644202,51.4563,0,10.00068772,0.7446875,-2.492222711,-0.610935443,90.00000001 +8.46,50.425,-2.594642795,51.4486,0,9.999577361,0.8065625,-2.394810661,-0.511012005,90.00000001 +8.47,50.425,-2.594641388,51.4402,0,9.998911139,0.86875,-2.296898534,-0.410642977,90.00000001 +8.48,50.425,-2.594639981,51.4312,0,9.999577333,0.93125,-2.198506669,-0.309915851,90.00000001 +8.49,50.425,-2.594638574,51.4216,0,10.00068767,0.9934375,-2.099655693,-0.20891846,90.00000001 +8.5,50.425,-2.594637166,51.4113,0,10.00068765,1.0546875,-2.000366232,-0.107738927,90.00000001 +8.51,50.425,-2.594635759,51.4005,0,9.999577286,1.1146875,-1.900659028,-0.00646537,90.00000001 +8.52,50.425,-2.594634352,51.389,0,9.998911059,1.1734375,-1.800554879,0.094813743,90.00000001 +8.53,50.425,-2.594632945,51.377,0,9.999577249,1.2315625,-1.700074697,0.196010237,90.00000001 +8.54,50.425,-2.594631538,51.3644,0,10.00068758,1.2903125,-1.599239511,0.29703576,90.00000001 +8.55,50.425,-2.59463013,51.3512,0,10.00090963,1.3496875,-1.498070348,0.397802305,90.00000001 +8.56,50.425,-2.594628723,51.3374,0,10.00068754,1.408125,-1.396588293,0.498221925,90.00000001 +8.57,50.425,-2.594627316,51.323,0,10.00090958,1.465,-1.294814602,0.598207128,90.00000001 +8.58,50.425,-2.594625908,51.3081,0,10.00068749,1.5215625,-1.192770532,0.697670654,90.00000001 +8.59,50.425,-2.594624501,51.2926,0,9.999577117,1.5784375,-1.090477283,0.796525812,90.00000001 +8.6,50.425,-2.594623094,51.2765,0,9.998688813,1.634375,-0.987956397,0.894686374,90.00000001 +8.61,50.425,-2.594621687,51.2599,0,9.998688787,1.6884375,-0.885229133,0.992066739,90.00000001 +8.62,50.425,-2.59462028,51.2427,0,9.999577039,1.7415625,-0.782317032,1.088582053,90.00000001 +8.63,50.425,-2.594618873,51.2251,0,10.00068736,1.7946875,-0.679241523,1.18414809,90.00000001 +8.64,50.425,-2.594617465,51.2068,0,10.00068733,1.846875,-0.576024151,1.278681542,90.00000001 +8.65,50.425,-2.594616058,51.1881,0,9.999576953,1.8978125,-0.472686514,1.372099962,90.00000001 +8.66,50.425,-2.594614651,51.1689,0,9.998910714,1.9484375,-0.369250157,1.464321873,90.00000001 +8.67,50.425,-2.594613244,51.1491,0,9.999576893,1.998125,-0.265736737,1.555266891,90.00000001 +8.68,50.425,-2.594611837,51.1289,0,10.00068721,2.0465625,-0.16216774,1.644855661,90.00000001 +8.69,50.425,-2.594610429,51.1082,0,10.00068718,2.095,-0.058564938,1.733010145,90.00000001 +8.7,50.425,-2.594609022,51.087,0,9.999798865,2.143125,0.045050124,1.819653338,90.00000001 +8.71,50.425,-2.594607615,51.0653,0,9.999798831,2.1896875,0.148655791,1.90470984,90.00000001 +8.72,50.425,-2.594606208,51.0432,0,10.00068708,2.2346875,0.252230403,1.988105394,90.00000001 +8.73,50.425,-2.5946048,51.0206,0,10.00068704,2.2784375,0.35575236,2.069767292,90.00000001 +8.74,50.425,-2.594603393,50.9976,0,9.999798725,2.3215625,0.459199947,2.149624316,90.00000001 +8.75,50.425,-2.594601986,50.9742,0,9.999798688,2.3646875,0.562551736,2.227606794,90.00000001 +8.76,50.425,-2.594600579,50.9503,0,10.00068693,2.4065625,0.665785953,2.303646831,90.00000001 +8.77,50.425,-2.594599171,50.926,0,10.00068689,2.44625,0.768881172,2.37767802,90.00000001 +8.78,50.425,-2.594597764,50.9014,0,9.999576506,2.485,0.871815847,2.449635847,90.00000001 +8.79,50.425,-2.594596357,50.8763,0,9.998910257,2.523125,0.974568436,2.519457515,90.00000001 +8.8,50.425,-2.59459495,50.8509,0,9.999576427,2.5596875,1.077117454,2.587082234,90.00000001 +8.81,50.425,-2.594593543,50.8251,0,10.00068673,2.5953125,1.179441585,2.652450989,90.00000001 +8.82,50.425,-2.594592135,50.799,0,10.00068669,2.63125,1.281519402,2.715506713,90.00000001 +8.83,50.425,-2.594590728,50.7725,0,9.999576304,2.6665625,1.383329534,2.776194517,90.00000001 +8.84,50.425,-2.594589321,50.7456,0,9.998687983,2.699375,1.484850837,2.834461403,90.00000001 +8.85,50.425,-2.594587914,50.7185,0,9.998687941,2.7296875,1.586061998,2.890256606,90.00000001 +8.86,50.425,-2.594586507,50.691,0,9.999576176,2.75875,1.686941989,2.943531482,90.00000001 +8.87,50.425,-2.5945851,50.6633,0,10.00068648,2.7878125,1.787469669,2.994239565,90.00000001 +8.88,50.425,-2.594583692,50.6353,0,10.00090851,2.8165625,1.887624009,3.042336564,90.00000001 +8.89,50.425,-2.594582285,50.6069,0,10.00068639,2.843125,1.987384212,3.087780654,90.00000001 +8.9,50.425,-2.594580878,50.5784,0,10.00090842,2.868125,2.086729307,3.13053213,90.00000001 +8.91,50.425,-2.59457947,50.5496,0,10.0006863,2.8934375,2.185638667,3.170553747,90.00000001 +8.92,50.425,-2.594578063,50.5205,0,9.99979798,2.9178125,2.284091552,3.207810614,90.00000001 +8.93,50.425,-2.594576656,50.4912,0,9.999797934,2.939375,2.38206745,3.242270187,90.00000001 +8.94,50.425,-2.594575249,50.4617,0,10.00068617,2.9584375,2.479545905,3.273902499,90.00000001 +8.95,50.425,-2.594573841,50.432,0,10.00068612,2.9765625,2.576506464,3.302679877,90.00000001 +8.96,50.425,-2.594572434,50.4022,0,9.999575724,2.9946875,2.672929016,3.328577283,90.00000001 +8.97,50.425,-2.594571027,50.3721,0,9.998687398,3.0115625,2.768793335,3.351572085,90.00000001 +8.98,50.425,-2.59456962,50.3419,0,9.998687351,3.02625,2.864079482,3.371644286,90.00000001 +8.99,50.425,-2.594568213,50.3116,0,9.999575583,3.0403125,2.958767461,3.388776412,90.00000001 +9,50.425,-2.594566806,50.2811,0,10.00068588,3.0546875,3.052837506,3.40295345,90.00000001 +9.01,50.425,-2.594565398,50.2505,0,10.00068584,3.0678125,3.146270077,3.414163026,90.00000001 +9.02,50.425,-2.594563991,50.2197,0,9.999575439,3.0778125,3.239045523,3.422395398,90.00000001 +9.03,50.425,-2.594562584,50.1889,0,9.998909181,3.0846875,3.331144593,3.427643462,90.00000001 +9.04,50.425,-2.594561177,50.158,0,9.999575342,3.0903125,3.422547919,3.42990252,90.00000001 +9.05,50.425,-2.59455977,50.1271,0,10.00068564,3.0965625,3.513236539,3.429170624,90.00000001 +9.06,50.425,-2.594558362,50.0961,0,10.00068559,3.103125,3.603191485,3.425448518,90.00000001 +9.07,50.425,-2.594556955,50.065,0,9.999797266,3.1078125,3.692393909,3.418739297,90.00000001 +9.08,50.425,-2.594555548,50.0339,0,9.999797218,3.1096875,3.780825247,3.409048919,90.00000001 +9.09,50.425,-2.594554141,50.0028,0,10.00068545,3.1096875,3.868466991,3.396385807,90.00000001 +9.1,50.425,-2.594552733,49.9717,0,10.0006854,3.108125,3.955300865,3.380760961,90.00000001 +9.11,50.425,-2.594551326,49.9406,0,9.999797072,3.105,4.041308763,3.362188076,90.00000001 +9.12,50.425,-2.594549919,49.9096,0,9.999797024,3.1015625,4.126472636,3.340683309,90.00000001 +9.13,50.425,-2.594548512,49.8786,0,10.00068525,3.0984375,4.210774782,3.316265394,90.00000001 +9.14,50.425,-2.594547104,49.8476,0,10.00068521,3.094375,4.294197551,3.288955647,90.00000001 +9.15,50.425,-2.594545697,49.8167,0,9.999574809,3.0878125,4.376723527,3.258777903,90.00000001 +9.16,50.425,-2.59454429,49.7858,0,9.998908552,3.078125,4.458335464,3.22575846,90.00000001 +9.17,50.425,-2.594542883,49.7551,0,9.999574713,3.0665625,4.539016344,3.189926081,90.00000001 +9.18,50.425,-2.594541476,49.7245,0,10.00068501,3.055,4.618749322,3.151312048,90.00000001 +9.19,50.425,-2.594540068,49.694,0,10.00068496,3.043125,4.697517727,3.109950053,90.00000001 +9.2,50.425,-2.594538661,49.6636,0,9.999574569,3.0296875,4.775305112,3.065876077,90.00000001 +9.21,50.425,-2.594537254,49.6334,0,9.998686243,3.0146875,4.852095208,3.01912868,90.00000001 +9.22,50.425,-2.594535847,49.6033,0,9.998686197,2.9984375,4.927872028,2.969748484,90.00000001 +9.23,50.425,-2.59453444,49.5734,0,9.999574428,2.98125,5.002619758,2.917778691,90.00000001 +9.24,50.425,-2.594533033,49.5437,0,10.00068473,2.963125,5.076322699,2.863264507,90.00000001 +9.25,50.425,-2.594531625,49.5141,0,10.00090675,2.943125,5.148965555,2.806253545,90.00000001 +9.26,50.425,-2.594530218,49.4848,0,10.00068464,2.92125,5.220533083,2.74679548,90.00000001 +9.27,50.425,-2.594528811,49.4557,0,10.00090666,2.898125,5.291010386,2.684942165,90.00000001 +9.28,50.425,-2.594527403,49.4268,0,10.00068455,2.873125,5.360382741,2.620747515,90.00000001 +9.29,50.425,-2.594525996,49.3982,0,9.999574154,2.8465625,5.428635651,2.554267566,90.00000001 +9.3,50.425,-2.594524589,49.3699,0,9.998907901,2.82,5.495754849,2.485560243,90.00000001 +9.31,50.425,-2.594523182,49.3418,0,9.999574066,2.793125,5.561726356,2.414685479,90.00000001 +9.32,50.425,-2.594521775,49.314,0,10.00068437,2.7646875,5.626536305,2.341705094,90.00000001 +9.33,50.425,-2.594520367,49.2865,0,10.00068433,2.735,5.690171289,2.266682688,90.00000001 +9.34,50.425,-2.59451896,49.2593,0,9.999573936,2.7046875,5.752617902,2.189683692,90.00000001 +9.35,50.425,-2.594517553,49.2324,0,9.998907685,2.6728125,5.813863194,2.110775257,90.00000001 +9.36,50.425,-2.594516146,49.2058,0,9.999573853,2.638125,5.873894332,2.030026195,90.00000001 +9.37,50.425,-2.594514739,49.1796,0,10.00068416,2.601875,5.932698766,1.947506922,90.00000001 +9.38,50.425,-2.594513331,49.1538,0,10.00068412,2.5665625,5.990264237,1.863289403,90.00000001 +9.39,50.425,-2.594511924,49.1283,0,9.999573732,2.53125,6.046578712,1.77744709,90.00000001 +9.4,50.425,-2.594510517,49.1031,0,9.998907483,2.493125,6.101630445,1.690054754,90.00000001 +9.41,50.425,-2.59450911,49.0784,0,9.999573653,2.453125,6.15540792,1.601188714,90.00000001 +9.42,50.425,-2.594507703,49.0541,0,10.00068396,2.4134375,6.207899906,1.510926432,90.00000001 +9.43,50.425,-2.594506295,49.0301,0,10.000906,2.3728125,6.259095462,1.419346577,90.00000001 +9.44,50.425,-2.594504888,49.0066,0,10.00068389,2.3296875,6.308983928,1.326529019,90.00000001 +9.45,50.425,-2.594503481,48.9835,0,10.00090592,2.2853125,6.357554821,1.232554716,90.00000001 +9.46,50.425,-2.594502073,48.9609,0,10.00068382,2.2415625,6.404797999,1.137505601,90.00000001 +9.47,50.425,-2.594500666,48.9387,0,9.999573436,2.198125,6.450703606,1.041464582,90.00000001 +9.48,50.425,-2.594499259,48.9169,0,9.998907193,2.1528125,6.495262076,0.944515368,90.00000001 +9.49,50.425,-2.594497852,48.8956,0,9.999573368,2.1046875,6.538464125,0.846742526,90.00000001 +9.5,50.425,-2.594496445,48.8748,0,10.00068368,2.0553125,6.580300643,0.748231314,90.00000001 +9.51,50.425,-2.594495037,48.8545,0,10.00068365,2.0065625,6.62076298,0.649067618,90.00000001 +9.52,50.425,-2.59449363,48.8347,0,9.999573273,1.958125,6.659842713,0.549337954,90.00000001 +9.53,50.425,-2.594492223,48.8153,0,9.998684964,1.908125,6.697531533,0.44912924,90.00000001 +9.54,50.425,-2.594490816,48.7965,0,9.998684935,1.85625,6.733821705,0.348528909,90.00000001 +9.55,50.425,-2.594489409,48.7782,0,9.999573184,1.8034375,6.76870561,0.247624624,90.00000001 +9.56,50.425,-2.594488002,48.7604,0,10.0006835,1.75,6.802175914,0.146504449,90.00000001 +9.57,50.425,-2.594486594,48.7432,0,10.00068348,1.6965625,6.834225741,0.045256447,90.00000001 +9.58,50.425,-2.594485187,48.7265,0,9.999573103,1.643125,6.864848272,-0.056030975,90.00000001 +9.59,50.425,-2.59448378,48.7103,0,9.99890687,1.588125,6.894037149,-0.157269524,90.00000001 +9.6,50.425,-2.594482373,48.6947,0,9.999573054,1.5315625,6.921786354,-0.258370963,90.00000001 +9.61,50.425,-2.594480966,48.6797,0,10.00090545,1.475,6.948089987,-0.359247059,90.00000001 +9.62,50.425,-2.594479558,48.6652,0,10.0017937,1.4184375,6.972942662,-0.459809918,90.00000001 +9.63,50.425,-2.594478151,48.6513,0,10.00179368,1.36125,6.99633905,-0.559971821,90.00000001 +9.64,50.425,-2.594476743,48.638,0,10.00090538,1.303125,7.018274395,-0.659645393,90.00000001 +9.65,50.425,-2.594475336,48.6252,0,9.999572945,1.2434375,7.038744057,-0.758743772,90.00000001 +9.66,50.425,-2.594473929,48.6131,0,9.998684647,1.183125,7.057743739,-0.857180499,90.00000001 +9.67,50.425,-2.594472522,48.6016,0,9.998684629,1.12375,7.075269486,-0.954869746,90.00000001 +9.68,50.425,-2.594471115,48.5906,0,9.99957289,1.0646875,7.09131769,-1.051726313,90.00000001 +9.69,50.425,-2.594469708,48.5803,0,10.00068322,1.0046875,7.10588497,-1.147665804,90.00000001 +9.7,50.425,-2.5944683,48.5705,0,10.00068321,0.9434375,7.11896829,-1.24260451,90.00000001 +9.71,50.425,-2.594466893,48.5614,0,9.999572845,0.88125,7.130564841,-1.336459638,90.00000001 +9.72,50.425,-2.594465486,48.5529,0,9.998906622,0.8184375,7.140672332,-1.429149369,90.00000001 +9.73,50.425,-2.594464079,48.545,0,9.999572819,0.755,7.149288529,-1.520592803,90.00000001 +9.74,50.425,-2.594462672,48.5378,0,10.00068316,0.691875,7.156411769,-1.610710298,90.00000001 +9.75,50.425,-2.594461264,48.5312,0,10.00068315,0.63,7.162040392,-1.699423244,90.00000001 +9.76,50.425,-2.594459857,48.5252,0,9.999572789,0.568125,7.166173366,-1.786654235,90.00000001 +9.77,50.425,-2.59445845,48.5198,0,9.998684502,0.5046875,7.168809774,-1.872327239,90.00000001 +9.78,50.425,-2.594457043,48.5151,0,9.998684494,0.44,7.169949043,-1.9563676,90.00000001 +9.79,50.425,-2.594455636,48.511,0,9.999572766,0.3753125,7.169591002,-2.038701922,90.00000001 +9.8,50.425,-2.594454229,48.5076,0,10.00090518,0.3115625,7.16773565,-2.11925847,90.00000001 +9.81,50.425,-2.594452821,48.5048,0,10.00179345,0.2484375,7.164383388,-2.197967,90.00000001 +9.82,50.425,-2.594451414,48.5026,0,10.00179345,0.1846875,7.159534962,-2.274758872,90.00000001 +9.83,50.425,-2.594450006,48.5011,0,10.00090517,0.12,7.153191403,-2.349567106,90.00000001 +9.84,50.425,-2.594448599,48.5002,0,9.99957275,0.055,7.145353913,-2.422326501,90.00000001 +9.85,50.425,-2.594447192,48.5,0,9.998906541,-0.01,7.136024269,-2.492973629,90.00000001 +9.86,50.425,-2.594445785,48.5004,0,9.99957275,-0.075,7.125204305,-2.561446784,90.00000001 +9.87,50.425,-2.594444378,48.5015,0,10.0006831,-0.1396875,7.112896369,-2.627686378,90.00000001 +9.88,50.425,-2.59444297,48.5032,0,10.0006831,-0.2034375,7.099102983,-2.691634541,90.00000001 +9.89,50.425,-2.594441563,48.5056,0,9.999572757,-0.266875,7.083827069,-2.753235583,90.00000001 +9.9,50.425,-2.594440156,48.5085,0,9.998684484,-0.3315625,7.067071721,-2.812435759,90.00000001 +9.91,50.425,-2.594438749,48.5122,0,9.99868449,-0.3965625,7.048840547,-2.869183447,90.00000001 +9.92,50.425,-2.594437342,48.5165,0,9.999572775,-0.4596875,7.029137331,-2.923429143,90.00000001 +9.93,50.425,-2.594435935,48.5214,0,10.00068313,-0.521875,7.007966139,-2.975125578,90.00000001 +9.94,50.425,-2.594434527,48.5269,0,10.00068314,-0.5853125,6.985331442,-3.02422766,90.00000001 +9.95,50.425,-2.59443312,48.5331,0,9.999572801,-0.6496875,6.961237936,-3.070692589,90.00000001 +9.96,50.425,-2.594431713,48.5399,0,9.998906603,-0.713125,6.935690722,-3.1144798,90.00000001 +9.97,50.425,-2.594430306,48.5474,0,9.999572823,-0.775,6.908695013,-3.155551134,90.00000001 +9.98,50.425,-2.594428899,48.5554,0,10.00068318,-0.8365625,6.88025654,-3.193870838,90.00000001 +9.99,50.425,-2.594427491,48.5641,0,10.00090527,-0.89875,6.850381202,-3.229405394,90.00000001 +10,50.425,-2.594426084,48.5734,0,10.00068321,-0.96125,6.819075247,-3.262123862,90.00000001 +10.01,50.425,-2.594424677,48.5833,0,10.0009053,-1.023125,6.786345205,-3.29199771,90.00000001 +10.02,50.425,-2.594423269,48.5939,0,10.00068324,-1.083125,6.752197894,-3.319000867,90.00000001 +10.03,50.425,-2.594421862,48.605,0,9.999572914,-1.141875,6.716640535,-3.343109842,90.00000001 +10.04,50.425,-2.594420455,48.6167,0,9.998906723,-1.201875,6.67968046,-3.364303551,90.00000001 +10.05,50.425,-2.594419048,48.629,0,9.99957295,-1.2628125,6.641325462,-3.382563544,90.00000001 +10.06,50.425,-2.594417641,48.642,0,10.00068332,-1.3215625,6.601583447,-3.397873893,90.00000001 +10.07,50.425,-2.594416233,48.6555,0,10.00068334,-1.378125,6.560462782,-3.410221305,90.00000001 +10.08,50.425,-2.594414826,48.6695,0,9.999573014,-1.4353125,6.51797206,-3.419594895,90.00000001 +10.09,50.425,-2.594413419,48.6842,0,9.998906828,-1.493125,6.474120162,-3.425986526,90.00000001 +10.1,50.425,-2.594412012,48.6994,0,9.999573061,-1.5496875,6.428916256,-3.429390697,90.00000001 +10.11,50.425,-2.594410605,48.7152,0,10.00068343,-1.605,6.38236968,-3.429804315,90.00000001 +10.12,50.425,-2.594409197,48.7315,0,10.00068346,-1.6596875,6.33449029,-3.427227151,90.00000001 +10.13,50.425,-2.59440779,48.7484,0,9.999573138,-1.7134375,6.285287998,-3.421661382,90.00000001 +10.14,50.425,-2.594406383,48.7658,0,9.998684887,-1.76625,6.234773059,-3.413111877,90.00000001 +10.15,50.425,-2.594404976,48.7837,0,9.998684915,-1.8184375,6.182956131,-3.401586087,90.00000001 +10.16,50.425,-2.594403569,48.8022,0,9.999573221,-1.87,6.129847929,-3.387094036,90.00000001 +10.17,50.425,-2.594402162,48.8211,0,10.00090567,-1.9215625,6.075459623,-3.369648445,90.00000001 +10.18,50.425,-2.594400754,48.8406,0,10.00179398,-1.973125,6.019802503,-3.34926444,90.00000001 +10.19,50.425,-2.594399347,48.8606,0,10.00179401,-2.023125,5.962888256,-3.32595984,90.00000001 +10.2,50.425,-2.594397939,48.8811,0,10.00090576,-2.0715625,5.904728743,-3.299754928,90.00000001 +10.21,50.425,-2.594396532,48.902,0,9.999573378,-2.1196875,5.845336052,-3.270672564,90.00000001 +10.22,50.425,-2.594395125,48.9235,0,9.998685133,-2.1665625,5.784722675,-3.238738189,90.00000001 +10.23,50.425,-2.594393718,48.9454,0,9.998685168,-2.21125,5.722901217,-3.203979532,90.00000001 +10.24,50.425,-2.594392311,48.9677,0,9.999573481,-2.255,5.659884626,-3.166426961,90.00000001 +10.25,50.425,-2.594390904,48.9905,0,10.00068386,-2.2984375,5.595686022,-3.12611325,90.00000001 +10.26,50.425,-2.594389496,49.0137,0,10.0006839,-2.3415625,5.530318815,-3.08307352,90.00000001 +10.27,50.425,-2.594388089,49.0373,0,9.99957359,-2.3846875,5.463796696,-3.037345242,90.00000001 +10.28,50.425,-2.594386682,49.0614,0,9.998907419,-2.4265625,5.396133531,-2.98896841,90.00000001 +10.29,50.425,-2.594385275,49.0859,0,9.999573666,-2.46625,5.327343474,-2.937985136,90.00000001 +10.3,50.425,-2.594383868,49.1107,0,10.00068405,-2.5046875,5.257440846,-2.884439938,90.00000001 +10.31,50.425,-2.59438246,49.136,0,10.00068409,-2.5415625,5.18644026,-2.828379399,90.00000001 +10.32,50.425,-2.594381053,49.1616,0,9.999573783,-2.5765625,5.114356555,-2.769852505,90.00000001 +10.33,50.425,-2.594379646,49.1875,0,9.998907615,-2.611875,5.041204798,-2.70891025,90.00000001 +10.34,50.425,-2.594378239,49.2138,0,9.999573866,-2.648125,4.967000232,-2.645605805,90.00000001 +10.35,50.425,-2.594376832,49.2405,0,10.00068426,-2.6828125,4.891758383,-2.579994345,90.00000001 +10.36,50.425,-2.594375424,49.2675,0,10.00090637,-2.7146875,4.815494951,-2.512133052,90.00000001 +10.37,50.425,-2.594374017,49.2948,0,10.00068434,-2.7446875,4.738225862,-2.442081169,90.00000001 +10.38,50.425,-2.59437261,49.3224,0,10.00090645,-2.7734375,4.659967276,-2.369899774,90.00000001 +10.39,50.425,-2.594371202,49.3503,0,10.00068443,-2.8015625,4.580735463,-2.295651778,90.00000001 +10.4,50.425,-2.594369795,49.3784,0,9.999574123,-2.8296875,4.500547041,-2.219401924,90.00000001 +10.41,50.425,-2.594368388,49.4069,0,9.998907959,-2.8565625,4.419418795,-2.141216734,90.00000001 +10.42,50.425,-2.594366981,49.4356,0,9.999574212,-2.88125,4.337367515,-2.061164388,90.00000001 +10.43,50.425,-2.594365574,49.4645,0,10.00068461,-2.9046875,4.254410502,-1.979314674,90.00000001 +10.44,50.425,-2.594364166,49.4937,0,10.00068465,-2.9265625,4.170565005,-1.895738925,90.00000001 +10.45,50.425,-2.594362759,49.5231,0,9.999574349,-2.9465625,4.085848496,-1.810510078,90.00000001 +10.46,50.425,-2.594361352,49.5526,0,9.998686117,-2.9665625,4.000278739,-1.723702503,90.00000001 +10.47,50.425,-2.594359945,49.5824,0,9.998686163,-2.9865625,3.91387361,-1.635391773,90.00000001 +10.48,50.425,-2.594358538,49.6124,0,9.999574489,-3.004375,3.826651042,-1.545654951,90.00000001 +10.49,50.425,-2.594357131,49.6425,0,10.00068488,-3.02,3.738629369,-1.454570304,90.00000001 +10.5,50.425,-2.594355723,49.6728,0,10.00068493,-3.0346875,3.649826927,-1.362217242,90.00000001 +10.51,50.425,-2.594354316,49.7032,0,9.999796701,-3.048125,3.560262279,-1.268676324,90.00000001 +10.52,50.425,-2.594352909,49.7338,0,9.999796749,-3.0596875,3.469954104,-1.17402914,90.00000001 +10.53,50.425,-2.594351502,49.7644,0,10.00068507,-3.07,3.378921309,-1.078358137,90.00000001 +10.54,50.425,-2.594350094,49.7952,0,10.00090719,-3.0796875,3.287182801,-0.981746795,90.00000001 +10.55,50.425,-2.594348687,49.826,0,10.00068517,-3.088125,3.194757834,-0.884279341,90.00000001 +10.56,50.425,-2.59434728,49.857,0,10.00090729,-3.095,3.101665714,-0.786040799,90.00000001 +10.57,50.425,-2.594345872,49.8879,0,10.00068527,-3.10125,3.007925808,-0.687116828,90.00000001 +10.58,50.425,-2.594344465,49.919,0,9.999574968,-3.1065625,2.913557768,-0.587593658,90.00000001 +10.59,50.425,-2.594343058,49.9501,0,9.998686738,-3.1090625,2.818581247,-0.487558092,90.00000001 +10.6,50.425,-2.594341651,49.9812,0,9.998686787,-3.1084375,2.723016127,-0.387097391,90.00000001 +10.61,50.425,-2.594340244,50.0123,0,9.999575115,-3.106875,2.626882289,-0.286299161,90.00000001 +10.62,50.425,-2.594338837,50.0433,0,10.00068551,-3.1065625,2.530199901,-0.185251235,90.00000001 +10.63,50.425,-2.594337429,50.0744,0,10.00068556,-3.10625,2.432989131,-0.084041736,90.00000001 +10.64,50.425,-2.594336022,50.1055,0,9.99957526,-3.1028125,2.335270205,0.017240988,90.00000001 +10.65,50.425,-2.594334615,50.1365,0,9.9989091,-3.0965625,2.237063635,0.1185087,90.00000001 +10.66,50.425,-2.594333208,50.1674,0,9.999575358,-3.09,2.138389874,0.21967305,90.00000001 +10.67,50.425,-2.594331801,50.1983,0,10.00068575,-3.0828125,2.039269551,0.320645861,90.00000001 +10.68,50.425,-2.594330393,50.2291,0,10.0006858,-3.073125,1.939723291,0.421339068,90.00000001 +10.69,50.425,-2.594328986,50.2598,0,9.999797571,-3.0615625,1.839772007,0.521664894,90.00000001 +10.7,50.425,-2.594327579,50.2903,0,9.999797619,-3.0496875,1.739436497,0.621535793,90.00000001 +10.71,50.425,-2.594326172,50.3208,0,10.00068595,-3.0365625,1.638737732,0.720864673,90.00000001 +10.72,50.425,-2.594324764,50.3511,0,10.00068599,-3.0215625,1.537696682,0.819564961,90.00000001 +10.73,50.425,-2.594323357,50.3812,0,9.999797762,-3.0065625,1.436334547,0.917550599,90.00000001 +10.74,50.425,-2.59432195,50.4112,0,9.999797809,-2.99125,1.334672468,1.014736101,90.00000001 +10.75,50.425,-2.594320543,50.4411,0,10.00068613,-2.9728125,1.232731645,1.111036727,90.00000001 +10.76,50.425,-2.594319135,50.4707,0,10.00068618,-2.9515625,1.130533392,1.206368539,90.00000001 +10.77,50.425,-2.594317728,50.5001,0,9.999575878,-2.9303125,1.028099024,1.300648401,90.00000001 +10.78,50.425,-2.594316321,50.5293,0,9.998909715,-2.9096875,0.925449968,1.393794035,90.00000001 +10.79,50.425,-2.594314914,50.5583,0,9.999575969,-2.8878125,0.822607596,1.485724253,90.00000001 +10.8,50.425,-2.594313507,50.5871,0,10.00068636,-2.8628125,0.719593509,1.5763589,90.00000001 +10.81,50.425,-2.594312099,50.6156,0,10.00068641,-2.835,0.616429077,1.665618964,90.00000001 +10.82,50.425,-2.594310692,50.6438,0,9.999576103,-2.806875,0.513135959,1.753426579,90.00000001 +10.83,50.425,-2.594309285,50.6717,0,9.998687868,-2.7796875,0.409735641,1.8397052,90.00000001 +10.84,50.425,-2.594307878,50.6994,0,9.998687911,-2.75125,0.30624978,1.924379538,90.00000001 +10.85,50.425,-2.594306471,50.7268,0,9.999576232,-2.7196875,0.202699977,2.007375798,90.00000001 +10.86,50.425,-2.594305064,50.7538,0,10.00068662,-2.686875,0.099107833,2.088621557,90.00000001 +10.87,50.425,-2.594303656,50.7805,0,10.00090873,-2.6546875,-0.004505053,2.168046055,90.00000001 +10.88,50.425,-2.594302249,50.8069,0,10.00068671,-2.6215625,-0.108116964,2.245579965,90.00000001 +10.89,50.425,-2.594300842,50.833,0,10.00090882,-2.58625,-0.211706301,2.321155733,90.00000001 +10.9,50.425,-2.594299434,50.8586,0,10.00068679,-2.5496875,-0.315251406,2.394707414,90.00000001 +10.91,50.425,-2.594298027,50.884,0,9.999798547,-2.511875,-0.418730677,2.466170836,90.00000001 +10.92,50.425,-2.59429662,50.9089,0,9.999798586,-2.4728125,-0.522122516,2.535483717,90.00000001 +10.93,50.425,-2.594295213,50.9334,0,10.0006869,-2.4334375,-0.62540532,2.60258567,90.00000001 +10.94,50.425,-2.594293805,50.9576,0,10.00068694,-2.393125,-0.728557548,2.667418079,90.00000001 +10.95,50.425,-2.594292398,50.9813,0,9.99957663,-2.35125,-0.83155754,2.729924451,90.00000001 +10.96,50.425,-2.594290991,51.0046,0,9.998688387,-2.3084375,-0.934383927,2.790050356,90.00000001 +10.97,50.425,-2.594289584,51.0275,0,9.998688423,-2.265,-1.037015164,2.847743252,90.00000001 +10.98,50.425,-2.594288177,51.0499,0,9.999576738,-2.22125,-1.13942988,2.902952835,90.00000001 +10.99,50.425,-2.59428677,51.0719,0,10.00068712,-2.1765625,-1.241606589,2.955631033,90.00000001 +11,50.425,-2.594285362,51.0935,0,10.00068715,-2.1296875,-1.343524036,3.005731895,90.00000001 +11.01,50.425,-2.594283955,51.1145,0,9.999576839,-2.0815625,-1.445160904,3.053211704,90.00000001 +11.02,50.425,-2.594282548,51.1351,0,9.998910661,-2.033125,-1.546495939,3.098029093,90.00000001 +11.03,50.425,-2.594281141,51.1552,0,9.999576902,-1.983125,-1.647507997,3.140144929,90.00000001 +11.04,50.425,-2.594279734,51.1748,0,10.00068728,-1.931875,-1.748176051,3.179522485,90.00000001 +11.05,50.425,-2.594278326,51.1938,0,10.00090938,-1.8815625,-1.84847896,3.216127498,90.00000001 +11.06,50.425,-2.594276919,51.2124,0,10.00068734,-1.8315625,-1.948395866,3.249927997,90.00000001 +11.07,50.425,-2.594275512,51.2305,0,10.00090944,-1.779375,-2.047905916,3.280894475,90.00000001 +11.08,50.425,-2.594274104,51.248,0,10.0006874,-1.725,-2.146988195,3.308999946,90.00000001 +11.09,50.425,-2.594272697,51.265,0,9.999577074,-1.67,-2.245622192,3.334220001,90.00000001 +11.1,50.425,-2.59427129,51.2814,0,9.998910891,-1.615,-2.343787165,3.356532524,90.00000001 +11.11,50.425,-2.594269883,51.2973,0,9.999577125,-1.56,-2.441462718,3.375918093,90.00000001 +11.12,50.425,-2.594268476,51.3126,0,10.0006875,-1.5046875,-2.538628339,3.392359804,90.00000001 +11.13,50.425,-2.594267068,51.3274,0,10.00068752,-1.4484375,-2.635263859,3.405843335,90.00000001 +11.14,50.425,-2.594265661,51.3416,0,9.999577194,-1.39125,-2.731348996,3.416356938,90.00000001 +11.15,50.425,-2.594264254,51.3552,0,9.998911006,-1.3334375,-2.826863753,3.423891391,90.00000001 +11.16,50.425,-2.594262847,51.3683,0,9.999577235,-1.2746875,-2.921788135,3.42844016,90.00000001 +11.17,50.425,-2.59426144,51.3807,0,10.0006876,-1.215,-3.016102317,3.42999935,90.00000001 +11.18,50.425,-2.594260032,51.3926,0,10.00068762,-1.155,-3.109786646,3.428567471,90.00000001 +11.19,50.425,-2.594258625,51.4038,0,9.999577292,-1.095,-3.202821584,3.424145841,90.00000001 +11.2,50.425,-2.594257218,51.4145,0,9.998689029,-1.035,-3.295187595,3.416738299,90.00000001 +11.21,50.425,-2.594255811,51.4245,0,9.998689045,-0.9746875,-3.386865483,3.406351319,90.00000001 +11.22,50.425,-2.594254404,51.434,0,9.999577338,-0.9134375,-3.477836055,3.392993897,90.00000001 +11.23,50.425,-2.594252997,51.4428,0,10.00090977,-0.85125,-3.568080288,3.376677778,90.00000001 +11.24,50.425,-2.594251589,51.451,0,10.00179806,-0.7884375,-3.657579447,3.357417171,90.00000001 +11.25,50.425,-2.594250182,51.4586,0,10.00179807,-0.725,-3.746314681,3.335228808,90.00000001 +11.26,50.425,-2.594248774,51.4655,0,10.00090981,-0.661875,-3.834267599,3.31013211,90.00000001 +11.27,50.425,-2.594247367,51.4718,0,9.999577398,-0.6,-3.921419808,3.282148909,90.00000001 +11.28,50.425,-2.59424596,51.4775,0,9.998689128,-0.5378125,-4.007753031,3.251303611,90.00000001 +11.29,50.425,-2.594244553,51.4826,0,9.998689135,-0.4734375,-4.093249278,3.217623147,90.00000001 +11.3,50.425,-2.594243146,51.487,0,9.999577421,-0.4084375,-4.177890728,3.181136851,90.00000001 +11.31,50.425,-2.594241739,51.4907,0,10.00068778,-0.345,-4.261659679,3.141876579,90.00000001 +11.32,50.425,-2.594240331,51.4939,0,10.00068778,-0.2815625,-4.344538654,3.099876538,90.00000001 +11.33,50.425,-2.594238924,51.4964,0,9.999577436,-0.2165625,-4.426510294,3.05517334,90.00000001 +11.34,50.425,-2.594237517,51.4982,0,9.998911229,-0.151875,-4.507557523,3.007806002,90.00000001 +11.35,50.425,-2.59423611,51.4994,0,9.99957744,-0.088125,-4.587663383,2.957815836,90.00000001 +11.36,50.425,-2.594234703,51.5,0,10.00068779,-0.0234375,-4.666811199,2.905246385,90.00000001 +11.37,50.425,-2.594233295,51.4999,0,10.00068779,0.041875,-4.744984415,2.850143487,90.00000001 +11.38,50.425,-2.594231888,51.4991,0,9.999577441,0.10625,-4.8221667,2.79255527,90.00000001 +11.39,50.425,-2.594230481,51.4978,0,9.998689159,0.17,-4.898341955,2.732531867,90.00000001 +11.4,50.425,-2.594229074,51.4957,0,9.998689155,0.23375,-4.973494193,2.670125705,90.00000001 +11.41,50.425,-2.594227667,51.4931,0,9.99957743,0.298125,-5.047607831,2.6053911,90.00000001 +11.42,50.425,-2.59422626,51.4898,0,10.00090984,0.3634375,-5.120667341,2.538384603,90.00000001 +11.43,50.425,-2.594224852,51.4858,0,10.00179812,0.4278125,-5.192657425,2.46916454,90.00000001 +11.44,50.425,-2.594223445,51.4812,0,10.00179811,0.49,-5.26356313,2.39779136,90.00000001 +11.45,50.425,-2.594222037,51.476,0,10.00090982,0.551875,-5.333369557,2.324327284,90.00000001 +11.46,50.425,-2.59422063,51.4702,0,9.999577395,0.6153125,-5.402062212,2.248836313,90.00000001 +11.47,50.425,-2.594219223,51.4637,0,9.998911176,0.68,-5.469626713,2.171384394,90.00000001 +11.48,50.425,-2.594217816,51.4566,0,9.999577374,0.744375,-5.536048966,2.092038964,90.00000001 +11.49,50.425,-2.594216409,51.4488,0,10.00068771,0.8065625,-5.601315104,2.010869236,90.00000001 +11.5,50.425,-2.594215001,51.4404,0,10.0006877,0.866875,-5.665411434,1.927945971,90.00000001 +11.51,50.425,-2.594213594,51.4315,0,9.999577334,0.9284375,-5.728324663,1.843341534,90.00000001 +11.52,50.425,-2.594212187,51.4219,0,9.99868904,0.9915625,-5.790041557,1.75712972,90.00000001 +11.53,50.425,-2.59421078,51.4116,0,9.998689025,1.0528125,-5.850549281,1.669385588,90.00000001 +11.54,50.425,-2.594209373,51.4008,0,9.999577287,1.1115625,-5.909835229,1.5801858,90.00000001 +11.55,50.425,-2.594207966,51.3894,0,10.00068762,1.1703125,-5.967886912,1.489607991,90.00000001 +11.56,50.425,-2.594206558,51.3774,0,10.0006876,1.23,-6.024692354,1.397731286,90.00000001 +11.57,50.425,-2.594205151,51.3648,0,9.99957723,1.29,-6.080239581,1.304635728,90.00000001 +11.58,50.425,-2.594203744,51.3516,0,9.998911001,1.3496875,-6.134517019,1.210402448,90.00000001 +11.59,50.425,-2.594202337,51.3378,0,9.999577188,1.408125,-6.18751338,1.115113723,90.00000001 +11.6,50.425,-2.59420093,51.3234,0,10.00090958,1.4646875,-6.239217493,1.018852631,90.00000001 +11.61,50.425,-2.594199522,51.3085,0,10.00179784,1.52,-6.289618699,0.921703053,90.00000001 +11.62,50.425,-2.594198115,51.293,0,10.00179781,1.575,-6.338706343,0.82374973,90.00000001 +11.63,50.425,-2.594196707,51.277,0,10.00090951,1.63,-6.386470282,0.72507809,90.00000001 +11.64,50.425,-2.5941953,51.2604,0,9.999577067,1.685,-6.432900432,0.625774191,90.00000001 +11.65,50.425,-2.594193893,51.2433,0,9.998688762,1.7396875,-6.477987169,0.525924606,90.00000001 +11.66,50.425,-2.594192486,51.2256,0,9.998688734,1.793125,-6.521721095,0.42561637,90.00000001 +11.67,50.425,-2.594191079,51.2074,0,9.999576983,1.845,-6.564093043,0.324937028,90.00000001 +11.68,50.425,-2.594189672,51.1887,0,10.0006873,1.8965625,-6.605094132,0.223974301,90.00000001 +11.69,50.425,-2.594188264,51.1695,0,10.00068727,1.948125,-6.644715825,0.122816311,90.00000001 +11.7,50.425,-2.594186857,51.1497,0,9.999576894,1.998125,-6.682949871,0.021551177,90.00000001 +11.71,50.425,-2.59418545,51.1295,0,9.998910653,2.04625,-6.71978825,-0.079732749,90.00000001 +11.72,50.425,-2.594184043,51.1088,0,9.999576829,2.0934375,-6.755223341,-0.180947119,90.00000001 +11.73,50.425,-2.594182636,51.0876,0,10.00068714,2.14,-6.789247637,-0.282003696,90.00000001 +11.74,50.425,-2.594181228,51.066,0,10.00068711,2.1865625,-6.821854092,-0.38281436,90.00000001 +11.75,50.425,-2.594179821,51.0439,0,9.999576728,2.233125,-6.853035888,-0.483291218,90.00000001 +11.76,50.425,-2.594178414,51.0213,0,9.998688414,2.278125,-6.882786549,-0.583346666,90.00000001 +11.77,50.425,-2.594177007,50.9983,0,9.998688378,2.32125,-6.911099832,-0.682893385,90.00000001 +11.78,50.425,-2.5941756,50.9749,0,9.99957662,2.3634375,-6.937969776,-0.781844628,90.00000001 +11.79,50.425,-2.594174193,50.951,0,10.000909,2.4046875,-6.963390825,-0.880114109,90.00000001 +11.8,50.425,-2.594172785,50.9268,0,10.00179724,2.4446875,-6.98735765,-0.977616056,90.00000001 +11.81,50.425,-2.594171378,50.9021,0,10.0017972,2.4834375,-7.009865323,-1.074265556,90.00000001 +11.82,50.425,-2.59416997,50.8771,0,10.00090889,2.52125,-7.030908974,-1.169978271,90.00000001 +11.83,50.425,-2.594168563,50.8517,0,9.999576427,2.5584375,-7.050484363,-1.264670776,90.00000001 +11.84,50.425,-2.594167156,50.8259,0,9.998910178,2.5946875,-7.068587366,-1.358260453,90.00000001 +11.85,50.425,-2.594165749,50.7998,0,9.999576347,2.63,-7.085214143,-1.450665654,90.00000001 +11.86,50.425,-2.594164342,50.7733,0,10.00068665,2.6646875,-7.100361313,-1.541805935,90.00000001 +11.87,50.425,-2.594162934,50.7465,0,10.00068661,2.698125,-7.114025612,-1.631601657,90.00000001 +11.88,50.425,-2.594161527,50.7193,0,9.99957622,2.7296875,-7.126204288,-1.719974668,90.00000001 +11.89,50.425,-2.59416012,50.6919,0,9.998687898,2.7596875,-7.136894707,-1.806847789,90.00000001 +11.9,50.425,-2.594158713,50.6641,0,9.998687855,2.7884375,-7.14609469,-1.892145334,90.00000001 +11.91,50.425,-2.594157306,50.6361,0,9.99957609,2.81625,-7.15380229,-1.975792875,90.00000001 +11.92,50.425,-2.594155899,50.6078,0,10.00068639,2.843125,-7.16001596,-2.057717531,90.00000001 +11.93,50.425,-2.594154491,50.5792,0,10.00068635,2.868125,-7.164734325,-2.137847799,90.00000001 +11.94,50.425,-2.594153084,50.5504,0,9.999575956,2.8915625,-7.16795641,-2.216113891,90.00000001 +11.95,50.425,-2.594151677,50.5214,0,9.998909702,2.915,-7.169681586,-2.292447454,90.00000001 +11.96,50.425,-2.59415027,50.4921,0,9.999575865,2.9378125,-7.169909394,-2.366781967,90.00000001 +11.97,50.425,-2.594148863,50.4626,0,10.00068617,2.958125,-7.168639949,-2.439052571,90.00000001 +11.98,50.425,-2.594147455,50.4329,0,10.00090819,2.9765625,-7.165873365,-2.509196357,90.00000001 +11.99,50.425,-2.594146048,50.4031,0,10.00068607,2.9946875,-7.16161033,-2.577152016,90.00000001 +12,50.425,-2.594144641,50.373,0,10.0009081,3.0115625,-7.155851646,-2.64286042,90.00000001 +12.01,50.425,-2.594143233,50.3428,0,10.00068598,3.02625,-7.148598573,-2.706264216,90.00000001 +12.02,50.425,-2.594141826,50.3125,0,9.999575585,3.04,-7.139852601,-2.767308056,90.00000001 +12.03,50.425,-2.594140419,50.282,0,9.998909328,3.053125,-7.129615564,-2.82593877,90.00000001 +12.04,50.425,-2.594139012,50.2514,0,9.999575489,3.0646875,-7.117889582,-2.88210525,90.00000001 +12.05,50.425,-2.594137605,50.2207,0,10.00068579,3.075,-7.104677118,-2.935758508,90.00000001 +12.06,50.425,-2.594136197,50.1899,0,10.00068574,3.0846875,-7.08998098,-2.986851732,90.00000001 +12.07,50.425,-2.59413479,50.159,0,9.999575344,3.0928125,-7.073804147,-3.035340349,90.00000001 +12.08,50.425,-2.594133383,50.128,0,9.998909087,3.098125,-7.056150056,-3.081182129,90.00000001 +12.09,50.425,-2.594131976,50.097,0,9.999575247,3.1015625,-7.037022376,-3.124337023,90.00000001 +12.1,50.425,-2.594130569,50.066,0,10.00068555,3.105,-7.016425059,-3.164767504,90.00000001 +12.11,50.425,-2.594129161,50.0349,0,10.0006855,3.108125,-6.994362517,-3.202438218,90.00000001 +12.12,50.425,-2.594127754,50.0038,0,9.999575101,3.1096875,-6.970839276,-3.237316394,90.00000001 +12.13,50.425,-2.594126347,49.9727,0,9.998686775,3.1096875,-6.945860265,-3.269371549,90.00000001 +12.14,50.425,-2.59412494,49.9416,0,9.998686726,3.108125,-6.919430695,-3.298575838,90.00000001 +12.15,50.425,-2.594123533,49.9105,0,9.999574955,3.1046875,-6.89155607,-3.32490365,90.00000001 +12.16,50.425,-2.594122126,49.8795,0,10.00090732,3.0996875,-6.862242231,-3.348332123,90.00000001 +12.17,50.425,-2.594120718,49.8485,0,10.00179556,3.0934375,-6.831495368,-3.368840746,90.00000001 +12.18,50.425,-2.594119311,49.8176,0,10.00179551,3.08625,-6.799321782,-3.386411758,90.00000001 +12.19,50.425,-2.594117903,49.7868,0,10.00090718,3.078125,-6.765728235,-3.401029745,90.00000001 +12.2,50.425,-2.594116496,49.756,0,9.999574713,3.068125,-6.730721774,-3.412681987,90.00000001 +12.21,50.425,-2.594115089,49.7254,0,9.998686387,3.05625,-6.694309676,-3.421358344,90.00000001 +12.22,50.425,-2.594113682,49.6949,0,9.998686339,3.0434375,-6.656499561,-3.427051196,90.00000001 +12.23,50.425,-2.594112275,49.6645,0,9.999574571,3.0296875,-6.617299336,-3.429755614,90.00000001 +12.24,50.425,-2.594110868,49.6343,0,10.00068487,3.015,-6.576717136,-3.429469192,90.00000001 +12.25,50.425,-2.59410946,49.6042,0,10.00068482,2.9996875,-6.5347615,-3.426192275,90.00000001 +12.26,50.425,-2.594108053,49.5743,0,9.999574429,2.9828125,-6.491441135,-3.419927669,90.00000001 +12.27,50.425,-2.594106646,49.5445,0,9.998908173,2.963125,-6.446765152,-3.410680818,90.00000001 +12.28,50.425,-2.594105239,49.515,0,9.999574337,2.9415625,-6.400742832,-3.3984598,90.00000001 +12.29,50.425,-2.594103832,49.4857,0,10.00068464,2.92,-6.353383803,-3.383275272,90.00000001 +12.3,50.425,-2.594102424,49.4566,0,10.00068459,2.898125,-6.304697917,-3.36514047,90.00000001 +12.31,50.425,-2.594101017,49.4277,0,9.9995742,2.8746875,-6.254695432,-3.344071208,90.00000001 +12.32,50.425,-2.59409961,49.3991,0,9.998907946,2.8496875,-6.203386718,-3.320085934,90.00000001 +12.33,50.425,-2.594098203,49.3707,0,9.999574111,2.823125,-6.150782489,-3.293205447,90.00000001 +12.34,50.425,-2.594096796,49.3426,0,10.00068442,2.7946875,-6.096893745,-3.263453239,90.00000001 +12.35,50.425,-2.594095388,49.3148,0,10.00090644,2.765,-6.041731775,-3.230855206,90.00000001 +12.36,50.425,-2.594093981,49.2873,0,10.00068433,2.735,-5.985308037,-3.195439883,90.00000001 +12.37,50.425,-2.594092574,49.2601,0,10.00090636,2.7046875,-5.927634335,-3.157238093,90.00000001 +12.38,50.425,-2.594091166,49.2332,0,10.00068424,2.673125,-5.868722757,-3.116283128,90.00000001 +12.39,50.425,-2.594089759,49.2066,0,9.999573854,2.6396875,-5.808585508,-3.07261068,90.00000001 +12.4,50.425,-2.594088352,49.1804,0,9.998907605,2.6046875,-5.747235307,-3.02625891,90.00000001 +12.41,50.425,-2.594086945,49.1545,0,9.999573773,2.568125,-5.684684817,-2.977268211,90.00000001 +12.42,50.425,-2.594085538,49.129,0,10.00068408,2.53,-5.620947101,-2.925681269,90.00000001 +12.43,50.425,-2.59408413,49.1039,0,10.00068404,2.4915625,-5.556035624,-2.871543059,90.00000001 +12.44,50.425,-2.594082723,49.0792,0,9.999573655,2.4534375,-5.489963793,-2.814900853,90.00000001 +12.45,50.425,-2.594081316,49.0548,0,9.998685339,2.4146875,-5.422745416,-2.755803981,90.00000001 +12.46,50.425,-2.594079909,49.0309,0,9.998685302,2.374375,-5.354394587,-2.694304066,90.00000001 +12.47,50.425,-2.594078502,49.0073,0,9.999573543,2.331875,-5.284925632,-2.630454623,90.00000001 +12.48,50.425,-2.594077095,48.9842,0,10.00068385,2.2878125,-5.214352931,-2.564311401,90.00000001 +12.49,50.425,-2.594075687,48.9616,0,10.00068382,2.2434375,-5.142691266,-2.495932097,90.00000001 +12.5,50.425,-2.59407428,48.9393,0,9.999795506,2.198125,-5.069955649,-2.425376241,90.00000001 +12.51,50.425,-2.594072873,48.9176,0,9.999795472,2.1515625,-4.996161206,-2.352705483,90.00000001 +12.52,50.425,-2.594071466,48.8963,0,10.00068372,2.105,-4.921323349,-2.277983077,90.00000001 +12.53,50.425,-2.594070058,48.8755,0,10.00090575,2.058125,-4.845457836,-2.201274284,90.00000001 +12.54,50.425,-2.594068651,48.8551,0,10.00068365,2.0096875,-4.768580307,-2.122645911,90.00000001 +12.55,50.425,-2.594067244,48.8353,0,10.00090569,1.9596875,-4.690706977,-2.042166597,90.00000001 +12.56,50.425,-2.594065836,48.8159,0,10.00068359,1.9084375,-4.611854062,-1.959906417,90.00000001 +12.57,50.425,-2.594064429,48.7971,0,9.999573214,1.8565625,-4.532038004,-1.875937217,90.00000001 +12.58,50.425,-2.594063022,48.7788,0,9.998684906,1.805,-4.451275478,-1.790332166,90.00000001 +12.59,50.425,-2.594061615,48.761,0,9.998684879,1.753125,-4.369583385,-1.703165919,90.00000001 +12.6,50.425,-2.594060208,48.7437,0,9.999573131,1.6996875,-4.286978741,-1.614514509,90.00000001 +12.61,50.425,-2.594058801,48.727,0,10.00068345,1.645,-4.203478794,-1.524455169,90.00000001 +12.62,50.425,-2.594057393,48.7108,0,10.00068343,1.59,-4.119101019,-1.43306651,90.00000001 +12.63,50.425,-2.594055986,48.6952,0,9.999573054,1.5346875,-4.033863062,-1.340428173,90.00000001 +12.64,50.425,-2.594054579,48.6801,0,9.998906821,1.478125,-3.947782627,-1.246621001,90.00000001 +12.65,50.425,-2.594053172,48.6656,0,9.999573008,1.42,-3.860877821,-1.151726757,90.00000001 +12.66,50.425,-2.594051765,48.6517,0,10.00068333,1.3615625,-3.773166635,-1.055828176,90.00000001 +12.67,50.425,-2.594050357,48.6384,0,10.00068331,1.3034375,-3.684667516,-0.959008851,90.00000001 +12.68,50.425,-2.59404895,48.6256,0,9.999795016,1.245,-3.595398916,-0.861353294,90.00000001 +12.69,50.425,-2.594047543,48.6135,0,9.999794996,1.18625,-3.505379454,-0.762946647,90.00000001 +12.7,50.425,-2.594046136,48.6019,0,10.00068326,1.126875,-3.414627924,-0.663874681,90.00000001 +12.71,50.425,-2.594044728,48.5909,0,10.00068324,1.06625,-3.32316329,-0.564223798,90.00000001 +12.72,50.425,-2.594043321,48.5806,0,9.999794945,1.005,-3.231004691,-0.464080917,90.00000001 +12.73,50.425,-2.594041914,48.5708,0,9.999794929,0.9434375,-3.138171261,-0.363533356,90.00000001 +12.74,50.425,-2.594040507,48.5617,0,10.00068319,0.8815625,-3.04468254,-0.262668777,90.00000001 +12.75,50.425,-2.594039099,48.5532,0,10.00068318,0.82,-2.95055795,-0.16157513,90.00000001 +12.76,50.425,-2.594037692,48.5453,0,9.99957282,0.7584375,-2.855817201,-0.060340592,90.00000001 +12.77,50.425,-2.594036285,48.538,0,9.9989066,0.69625,-2.760480004,0.040946543,90.00000001 +12.78,50.425,-2.594034878,48.5314,0,9.999572798,0.6334375,-2.664566353,0.142197983,90.00000001 +12.79,50.425,-2.594033471,48.5253,0,10.00068314,0.57,-2.568096189,0.243325435,90.00000001 +12.8,50.425,-2.594032063,48.52,0,10.00068313,0.50625,-2.471089736,0.344240664,90.00000001 +12.81,50.425,-2.594030656,48.5152,0,9.999572773,0.4421875,-2.373567277,0.444855777,90.00000001 +12.82,50.425,-2.594029249,48.5111,0,9.998684488,0.3778125,-2.275549095,0.545082883,90.00000001 +12.83,50.425,-2.594027842,48.5077,0,9.998684483,0.31375,-2.177055645,0.64483472,90.00000001 +12.84,50.425,-2.594026435,48.5048,0,9.999572757,0.25,-2.07810761,0.744024257,90.00000001 +12.85,50.425,-2.594025028,48.5027,0,10.0006831,0.18625,-1.978725559,0.842564976,90.00000001 +12.86,50.425,-2.59402362,48.5011,0,10.00090517,0.121875,-1.878930291,0.940370992,90.00000001 +12.87,50.425,-2.594022213,48.5002,0,10.0006831,0.05625,-1.778742605,1.03735699,90.00000001 +12.88,50.425,-2.594020806,48.5,0,10.00090517,-0.009375,-1.67818347,1.133438346,90.00000001 +12.89,50.425,-2.594019398,48.5004,0,10.0006831,-0.0734375,-1.577273914,1.228531349,90.00000001 +12.9,50.425,-2.594017991,48.5015,0,9.999572751,-0.1365625,-1.476034907,1.322553093,90.00000001 +12.91,50.425,-2.594016584,48.5031,0,9.998906545,-0.2003125,-1.374487649,1.41542153,90.00000001 +12.92,50.425,-2.594015177,48.5055,0,9.999572757,-0.265,-1.272653396,1.507055701,90.00000001 +12.93,50.425,-2.59401377,48.5084,0,10.00068311,-0.3296875,-1.170553291,1.59737568,90.00000001 +12.94,50.425,-2.594012362,48.5121,0,10.00068312,-0.3934375,-1.068208762,1.68630274,90.00000001 +12.95,50.425,-2.594010955,48.5163,0,9.999572775,-0.4565625,-0.965641181,1.773759304,90.00000001 +12.96,50.425,-2.594009548,48.5212,0,9.998906573,-0.5203125,-0.862871918,1.859669112,90.00000001 +12.97,50.425,-2.594008141,48.5267,0,9.999572791,-0.5846875,-0.759922461,1.943957277,90.00000001 +12.98,50.425,-2.594006734,48.5329,0,10.00068315,-0.6484375,-0.656814294,2.026550289,90.00000001 +12.99,50.425,-2.594005326,48.5397,0,10.00068316,-0.71125,-0.553568961,2.107376127,90.00000001 +13,50.425,-2.594003919,48.5471,0,9.999572823,-0.7734375,-0.450208005,2.186364261,90.00000001 +13.01,50.425,-2.594002512,48.5552,0,9.998906627,-0.835,-0.346753084,2.263445877,90.00000001 +13.02,50.425,-2.594001105,48.5638,0,9.999572848,-0.8965625,-0.243225683,2.338553769,90.00000001 +13.03,50.425,-2.593999698,48.5731,0,10.00068321,-0.9584375,-0.139647519,2.411622389,90.00000001 +13.04,50.425,-2.59399829,48.583,0,10.0009053,-1.02,-0.036040191,2.482588025,90.00000001 +13.05,50.425,-2.593996883,48.5935,0,10.00068324,-1.0815625,0.067574642,2.551388797,90.00000001 +13.06,50.425,-2.593995476,48.6046,0,10.00090533,-1.143125,0.171175381,2.617964716,90.00000001 +13.07,50.425,-2.593994068,48.6164,0,10.00068328,-1.2028125,0.274740425,2.682257743,90.00000001 +13.08,50.425,-2.593992661,48.6287,0,9.99957295,-1.26,0.378248001,2.744211841,90.00000001 +13.09,50.425,-2.593991254,48.6416,0,9.998906762,-1.316875,0.481676623,2.803772867,90.00000001 +13.1,50.425,-2.593989847,48.655,0,9.999572992,-1.375,0.585004691,2.860889024,90.00000001 +13.11,50.425,-2.59398844,48.6691,0,10.00068336,-1.4334375,0.688210547,2.915510408,90.00000001 +13.12,50.425,-2.593987032,48.6837,0,10.00068338,-1.49125,0.791272706,2.967589464,90.00000001 +13.13,50.425,-2.593985625,48.6989,0,9.99957306,-1.548125,0.894169566,3.017080699,90.00000001 +13.14,50.425,-2.593984218,48.7147,0,9.998684807,-1.603125,0.996879757,3.063941027,90.00000001 +13.15,50.425,-2.593982811,48.731,0,9.998684832,-1.656875,1.099381734,3.108129537,90.00000001 +13.16,50.425,-2.593981404,48.7478,0,9.999573137,-1.7115625,1.201654128,3.149607671,90.00000001 +13.17,50.425,-2.593979997,48.7652,0,10.00068351,-1.7665625,1.303675508,3.188339388,90.00000001 +13.18,50.425,-2.593978589,48.7832,0,10.00068354,-1.819375,1.405424734,3.224290771,90.00000001 +13.19,50.425,-2.593977182,48.8016,0,9.99957322,-1.87,1.506880376,3.257430478,90.00000001 +13.2,50.425,-2.593975775,48.8206,0,9.998907041,-1.9203125,1.60802135,3.287729747,90.00000001 +13.21,50.425,-2.593974368,48.84,0,9.999573281,-1.97125,1.708826513,3.315161992,90.00000001 +13.22,50.425,-2.593972961,48.86,0,10.00090573,-2.0215625,1.809274838,3.339703436,90.00000001 +13.23,50.425,-2.593971553,48.8805,0,10.00179404,-2.0696875,1.90934524,3.361332593,90.00000001 +13.24,50.425,-2.593970146,48.9014,0,10.00179407,-2.1165625,2.009016978,3.380030555,90.00000001 +13.25,50.425,-2.593968738,48.9228,0,10.00090583,-2.1634375,2.108269139,3.395781165,90.00000001 +13.26,50.425,-2.593967331,48.9447,0,9.999573445,-2.2096875,2.207080982,3.408570557,90.00000001 +13.27,50.425,-2.593965924,48.967,0,9.998685201,-2.2546875,2.305431938,3.418387616,90.00000001 +13.28,50.425,-2.593964517,48.9898,0,9.998685236,-2.2984375,2.403301437,3.425223804,90.00000001 +13.29,50.425,-2.59396311,49.013,0,9.999573551,-2.34125,2.500669026,3.429073164,90.00000001 +13.3,50.425,-2.593961703,49.0366,0,10.00068394,-2.3834375,2.597514363,3.429932314,90.00000001 +13.31,50.425,-2.593960295,49.0607,0,10.00068397,-2.4246875,2.693817281,3.42780051,90.00000001 +13.32,50.425,-2.593958888,49.0851,0,9.999573665,-2.4646875,2.789557612,3.422679585,90.00000001 +13.33,50.425,-2.593957481,49.11,0,9.998907494,-2.503125,2.884715359,3.414574066,90.00000001 +13.34,50.425,-2.593956074,49.1352,0,9.999573742,-2.5396875,2.979270699,3.403490942,90.00000001 +13.35,50.425,-2.593954667,49.1608,0,10.00068413,-2.5753125,3.073203863,3.389439954,90.00000001 +13.36,50.425,-2.593953259,49.1867,0,10.00068417,-2.6115625,3.166495201,3.372433364,90.00000001 +13.37,50.425,-2.593951852,49.213,0,9.999573865,-2.6478125,3.259125287,3.352485895,90.00000001 +13.38,50.425,-2.593950445,49.2397,0,9.998685628,-2.68125,3.3510747,3.329615024,90.00000001 +13.39,50.425,-2.593949038,49.2667,0,9.99868567,-2.7115625,3.442324302,3.30384069,90.00000001 +13.4,50.425,-2.593947631,49.2939,0,9.999573991,-2.741875,3.532855015,3.275185409,90.00000001 +13.41,50.425,-2.593946224,49.3215,0,10.00090645,-2.773125,3.622647986,3.243674048,90.00000001 +13.42,50.425,-2.593944816,49.3494,0,10.00179477,-2.8028125,3.711684367,3.209334166,90.00000001 +13.43,50.425,-2.593943409,49.3776,0,10.00179482,-2.8296875,3.799945593,3.17219573,90.00000001 +13.44,50.425,-2.593942001,49.406,0,10.00090658,-2.855,3.887413273,3.132291053,90.00000001 +13.45,50.425,-2.593940594,49.4347,0,9.999574211,-2.88,3.974069129,3.089654971,90.00000001 +13.46,50.425,-2.593939187,49.4636,0,9.998908047,-2.904375,4.059895055,3.044324728,90.00000001 +13.47,50.425,-2.59393778,49.4928,0,9.999574302,-2.9265625,4.144873119,2.996339742,90.00000001 +13.48,50.425,-2.593936373,49.5222,0,10.0006847,-2.9465625,4.228985558,2.945741896,90.00000001 +13.49,50.425,-2.593934965,49.5517,0,10.00068474,-2.9665625,4.312214839,2.892575309,90.00000001 +13.5,50.425,-2.593933558,49.5815,0,9.99957444,-2.9865625,4.394543603,2.836886389,90.00000001 +13.51,50.425,-2.593932151,49.6115,0,9.998686209,-3.004375,4.475954546,2.77872361,90.00000001 +13.52,50.425,-2.593930744,49.6416,0,9.998686256,-3.0196875,4.556430823,2.718137792,90.00000001 +13.53,50.425,-2.593929337,49.6719,0,9.999574583,-3.0334375,4.635955474,2.655181706,90.00000001 +13.54,50.425,-2.59392793,49.7023,0,10.00068498,-3.04625,4.714511999,2.589910239,90.00000001 +13.55,50.425,-2.593926522,49.7328,0,10.00068503,-3.0584375,4.79208401,2.522380345,90.00000001 +13.56,50.425,-2.593925115,49.7635,0,9.999574725,-3.0696875,4.868655178,2.452650923,90.00000001 +13.57,50.425,-2.593923708,49.7942,0,9.998908564,-3.0796875,4.944209633,2.380782706,90.00000001 +13.58,50.425,-2.593922301,49.8251,0,9.999574822,-3.088125,5.01873156,2.306838435,90.00000001 +13.59,50.425,-2.593920894,49.856,0,10.00090729,-3.0946875,5.092205319,2.230882623,90.00000001 +13.6,50.425,-2.593919486,49.887,0,10.00179562,-3.1,5.164615725,2.152981391,90.00000001 +13.61,50.425,-2.593918079,49.918,0,10.00179566,-3.1046875,5.235947538,2.07320269,90.00000001 +13.62,50.425,-2.593916671,49.9491,0,10.00090743,-3.108125,5.306185861,1.991616193,90.00000001 +13.63,50.425,-2.593915264,49.9802,0,9.999575064,-3.1096875,5.375316084,1.908292946,90.00000001 +13.64,50.425,-2.593913857,50.0113,0,9.998686835,-3.1096875,5.44332371,1.823305658,90.00000001 +13.65,50.425,-2.59391245,50.0424,0,9.998686883,-3.108125,5.510194589,1.736728412,90.00000001 +13.66,50.425,-2.593911043,50.0735,0,9.99957521,-3.105,5.575914739,1.648636667,90.00000001 +13.67,50.425,-2.593909636,50.1045,0,10.00068561,-3.10125,5.640470409,1.55910737,90.00000001 +13.68,50.425,-2.593908228,50.1355,0,10.00068566,-3.0965625,5.703848193,1.468218445,90.00000001 +13.69,50.425,-2.593906821,50.1665,0,9.999575356,-3.0896875,5.76603474,1.376049245,90.00000001 +13.7,50.425,-2.593905414,50.1973,0,9.998909195,-3.0815625,5.827017159,1.2826801,90.00000001 +13.71,50.425,-2.593904007,50.2281,0,9.999575452,-3.0734375,5.886782673,1.188192427,90.00000001 +13.72,50.425,-2.5939026,50.2588,0,10.00068585,-3.064375,5.945318792,1.092668617,90.00000001 +13.73,50.425,-2.593901192,50.2894,0,10.0006859,-3.0528125,6.002613311,0.996192035,90.00000001 +13.74,50.425,-2.593899785,50.3199,0,9.999575596,-3.038125,6.058654313,0.898846735,90.00000001 +13.75,50.425,-2.593898378,50.3502,0,9.998687365,-3.021875,6.113429995,0.800717571,90.00000001 +13.76,50.425,-2.593896971,50.3803,0,9.998687412,-3.0065625,6.166928955,0.701890259,90.00000001 +13.77,50.425,-2.593895564,50.4103,0,9.999575738,-2.99125,6.21914002,0.602450855,90.00000001 +13.78,50.425,-2.593894157,50.4402,0,10.0009082,-2.9728125,6.270052363,0.502486106,90.00000001 +13.79,50.425,-2.593892749,50.4698,0,10.00179653,-2.9515625,6.31965521,0.402083159,90.00000001 +13.8,50.425,-2.593891342,50.4992,0,10.00179657,-2.9303125,6.367938363,0.30132962,90.00000001 +13.81,50.425,-2.593889934,50.5284,0,10.00090834,-2.9096875,6.414891567,0.200313264,90.00000001 +13.82,50.425,-2.593888527,50.5574,0,9.999575967,-2.8878125,6.460505138,0.099122272,90.00000001 +13.83,50.425,-2.59388712,50.5862,0,9.998687733,-2.863125,6.504769508,-0.002155123,90.00000001 +13.84,50.425,-2.593885713,50.6147,0,9.998687778,-2.8365625,6.547675453,-0.103430685,90.00000001 +13.85,50.425,-2.593884306,50.6429,0,9.999576102,-2.8096875,6.589214033,-0.204616063,90.00000001 +13.86,50.425,-2.593882899,50.6709,0,10.00068649,-2.7815625,6.629376484,-0.305622964,90.00000001 +13.87,50.425,-2.593881491,50.6986,0,10.00068654,-2.75125,6.668154497,-0.406363383,90.00000001 +13.88,50.425,-2.593880084,50.7259,0,9.99957623,-2.72,6.705539936,-0.506749428,90.00000001 +13.89,50.425,-2.593878677,50.753,0,9.998910063,-2.6884375,6.741525066,-0.606693607,90.00000001 +13.9,50.425,-2.59387727,50.7797,0,9.999576315,-2.65625,6.776102266,-0.706108775,90.00000001 +13.91,50.425,-2.593875863,50.8061,0,10.00068671,-2.623125,6.809264376,-0.804908127,90.00000001 +13.92,50.425,-2.593874455,50.8322,0,10.00068675,-2.5878125,6.841004404,-0.903005607,90.00000001 +13.93,50.425,-2.593873048,50.8579,0,9.999576438,-2.55,6.87131582,-1.00031567,90.00000001 +13.94,50.425,-2.593871641,50.8832,0,9.998910267,-2.511875,6.900192262,-1.096753462,90.00000001 +13.95,50.425,-2.593870234,50.9081,0,9.999576515,-2.4746875,6.927627716,-1.192234874,90.00000001 +13.96,50.425,-2.593868827,50.9327,0,10.0006869,-2.43625,6.953616337,-1.286676596,90.00000001 +13.97,50.425,-2.593867419,50.9569,0,10.00090901,-2.3946875,6.978152853,-1.379996352,90.00000001 +13.98,50.425,-2.593866012,50.9806,0,10.00068698,-2.351875,7.001232052,-1.472112724,90.00000001 +13.99,50.425,-2.593864605,51.0039,0,10.00090908,-2.31,7.022849119,-1.562945328,90.00000001 +14,50.425,-2.593863197,51.0268,0,10.00068705,-2.2678125,7.042999586,-1.652415094,90.00000001 +14.01,50.425,-2.59386179,51.0493,0,9.999576737,-2.223125,7.061679214,-1.740443929,90.00000001 +14.02,50.425,-2.593860383,51.0713,0,9.998910562,-2.1765625,7.078884048,-1.826955055,90.00000001 +14.03,50.425,-2.593858976,51.0928,0,9.999576805,-2.13,7.094610593,-1.911873015,90.00000001 +14.04,50.425,-2.593857569,51.1139,0,10.00068719,-2.083125,7.108855527,-1.99512384,90.00000001 +14.05,50.425,-2.593856161,51.1345,0,10.00068722,-2.0346875,7.121615813,-2.076634879,90.00000001 +14.06,50.425,-2.593854754,51.1546,0,9.999576901,-1.985,7.132888872,-2.156335027,90.00000001 +14.07,50.425,-2.593853347,51.1742,0,9.998688653,-1.9346875,7.142672356,-2.234154842,90.00000001 +14.08,50.425,-2.59385194,51.1933,0,9.998688683,-1.8834375,7.150964144,-2.310026487,90.00000001 +14.09,50.425,-2.593850533,51.2119,0,9.999576991,-1.8315625,7.157762517,-2.383883669,90.00000001 +14.1,50.425,-2.593849126,51.2299,0,10.00068737,-1.7796875,7.163066158,-2.45566216,90.00000001 +14.11,50.425,-2.593847718,51.2475,0,10.00068739,-1.7265625,7.166873807,-2.525299221,90.00000001 +14.12,50.425,-2.593846311,51.2645,0,9.999577073,-1.6715625,7.169184775,-2.592734176,90.00000001 +14.13,50.425,-2.593844904,51.2809,0,9.99891089,-1.616875,7.169998604,-2.65790824,90.00000001 +14.14,50.425,-2.593843497,51.2968,0,9.999577124,-1.563125,7.169315008,-2.720764575,90.00000001 +14.15,50.425,-2.59384209,51.3122,0,10.00090957,-1.5078125,7.167134216,-2.781248349,90.00000001 +14.16,50.425,-2.593840682,51.327,0,10.00179787,-1.45,7.163456629,-2.83930685,90.00000001 +14.17,50.425,-2.593839275,51.3412,0,10.00179789,-1.3915625,7.158283107,-2.894889428,90.00000001 +14.18,50.425,-2.593837867,51.3548,0,10.00090963,-1.3334375,7.151614623,-2.947947612,90.00000001 +14.19,50.425,-2.59383646,51.3679,0,9.999577235,-1.275,7.14345261,-2.998435163,90.00000001 +14.2,50.425,-2.593835053,51.3803,0,9.998688975,-1.2165625,7.133798787,-3.046308021,90.00000001 +14.21,50.425,-2.593833646,51.3922,0,9.998688993,-1.158125,7.122655159,-3.091524475,90.00000001 +14.22,50.425,-2.593832239,51.4035,0,9.999577291,-1.098125,7.110024075,-3.134045048,90.00000001 +14.23,50.425,-2.593830832,51.4142,0,10.00068766,-1.0365625,7.095908171,-3.17383267,90.00000001 +14.24,50.425,-2.593829424,51.4242,0,10.00068767,-0.975,7.080310312,-3.210852676,90.00000001 +14.25,50.425,-2.593828017,51.4337,0,9.999577338,-0.9134375,7.063233877,-3.245072753,90.00000001 +14.26,50.425,-2.59382661,51.4425,0,9.998911142,-0.8515625,7.044682363,-3.276463105,90.00000001 +14.27,50.425,-2.593825203,51.4507,0,9.999577364,-0.79,7.024659608,-3.304996346,90.00000001 +14.28,50.425,-2.593823796,51.4583,0,10.00068773,-0.728125,7.00316991,-3.330647552,90.00000001 +14.29,50.425,-2.593822388,51.4653,0,10.00068774,-0.665,6.980217679,-3.353394434,90.00000001 +14.3,50.425,-2.593820981,51.4716,0,9.999577398,-0.6015625,6.955807671,-3.373217055,90.00000001 +14.31,50.425,-2.593819574,51.4773,0,9.998911197,-0.5384375,6.929945101,-3.390098168,90.00000001 +14.32,50.425,-2.593818167,51.4824,0,9.999577414,-0.475,6.90263524,-3.404023105,90.00000001 +14.33,50.425,-2.59381676,51.4868,0,10.00068777,-0.4115625,6.873883874,-3.414979663,90.00000001 +14.34,50.425,-2.593815352,51.4906,0,10.00090984,-0.3484375,6.84369702,-3.422958329,90.00000001 +14.35,50.425,-2.593813945,51.4938,0,10.00068778,-0.2846875,6.812080922,-3.427952115,90.00000001 +14.36,50.425,-2.593812538,51.4963,0,10.00090985,-0.2196875,6.77904217,-3.429956665,90.00000001 +14.37,50.425,-2.59381113,51.4982,0,10.00068779,-0.15375,6.744587754,-3.428970261,90.00000001 +14.38,50.425,-2.593809723,51.4994,0,9.999577441,-0.0884375,6.708724779,-3.424993704,90.00000001 +14.39,50.425,-2.593808316,51.4999,0,9.998911233,-0.025,6.671460807,-3.418030548,90.00000001 +14.4,50.425,-2.593806909,51.4999,0,9.999577442,0.0384375,6.632803574,-3.408086808,90.00000001 +14.41,50.425,-2.593805502,51.4992,0,10.00068779,0.1034375,6.592761158,-3.395171136,90.00000001 +14.42,50.425,-2.593804094,51.4978,0,10.00068779,0.168125,6.551341924,-3.379294877,90.00000001 +14.43,50.425,-2.593802687,51.4958,0,9.999577435,0.2315625,6.508554525,-3.360471781,90.00000001 +14.44,50.425,-2.59380128,51.4932,0,9.998689152,0.2953125,6.464407897,-3.338718292,90.00000001 +14.45,50.425,-2.593799873,51.4899,0,9.998689147,0.36,6.418911324,-3.314053433,90.00000001 +14.46,50.425,-2.593798466,51.486,0,9.99957742,0.425,6.372074144,-3.286498633,90.00000001 +14.47,50.425,-2.593797059,51.4814,0,10.00068776,0.4896875,6.323906327,-3.256077954,90.00000001 +14.48,50.425,-2.593795651,51.4762,0,10.00068775,0.553125,6.274417785,-3.222817983,90.00000001 +14.49,50.425,-2.593794244,51.4703,0,9.999799465,0.615,6.223618889,-3.186747597,90.00000001 +14.5,50.425,-2.593792837,51.4639,0,9.999799455,0.676875,6.171520352,-3.147898366,90.00000001 +14.51,50.425,-2.59379143,51.4568,0,10.00068772,0.7403125,6.11813289,-3.106304094,90.00000001 +14.52,50.425,-2.593790022,51.4491,0,10.00090978,0.804375,6.063467789,-3.062001106,90.00000001 +14.53,50.425,-2.593788615,51.4407,0,10.0006877,0.8665625,6.007536394,-3.015028021,90.00000001 +14.54,50.425,-2.593787208,51.4317,0,10.00090975,0.9265625,5.950350393,-2.965425747,90.00000001 +14.55,50.425,-2.5937858,51.4222,0,10.00068767,0.986875,5.891921761,-2.913237599,90.00000001 +14.56,50.425,-2.593784393,51.412,0,9.999577305,1.0484375,5.832262645,-2.858509014,90.00000001 +14.57,50.425,-2.593782986,51.4012,0,9.998689008,1.1096875,5.771385536,-2.801287834,90.00000001 +14.58,50.425,-2.593781579,51.3898,0,9.99868899,1.17,5.709303209,-2.741623848,90.00000001 +14.59,50.425,-2.593780172,51.3778,0,9.99957725,1.23,5.646028501,-2.679569138,90.00000001 +14.6,50.425,-2.593778765,51.3652,0,10.00068758,1.2896875,5.581574702,-2.615177792,90.00000001 +14.61,50.425,-2.593777357,51.352,0,10.00068756,1.348125,5.515955278,-2.548506017,90.00000001 +14.62,50.425,-2.59377595,51.3382,0,9.999577189,1.405,5.449183923,-2.479611853,90.00000001 +14.63,50.425,-2.593774543,51.3239,0,9.998910957,1.4615625,5.381274559,-2.40855546,90.00000001 +14.64,50.425,-2.593773136,51.309,0,9.999577142,1.5184375,5.312241395,-2.335398777,90.00000001 +14.65,50.425,-2.593771729,51.2935,0,10.00068747,1.5746875,5.242098813,-2.260205572,90.00000001 +14.66,50.425,-2.593770321,51.2775,0,10.00068744,1.63,5.170861481,-2.183041449,90.00000001 +14.67,50.425,-2.593768914,51.2609,0,9.999799138,1.6846875,5.098544352,-2.103973675,90.00000001 +14.68,50.425,-2.593767507,51.2438,0,9.999799111,1.738125,5.025162381,-2.023071175,90.00000001 +14.69,50.425,-2.5937661,51.2261,0,10.00068736,1.79,4.950730981,-1.940404595,90.00000001 +14.7,50.425,-2.593764692,51.208,0,10.00068733,1.841875,4.875265736,-1.856045899,90.00000001 +14.71,50.425,-2.593763285,51.1893,0,9.999799025,1.895,4.798782287,-1.770068711,90.00000001 +14.72,50.425,-2.593761878,51.1701,0,9.999798995,1.9478125,4.721296736,-1.682548033,90.00000001 +14.73,50.425,-2.593760471,51.1503,0,10.00068724,1.9978125,4.642825181,-1.593560067,90.00000001 +14.74,50.425,-2.593759063,51.1301,0,10.00068721,2.045,4.56338401,-1.503182564,90.00000001 +14.75,50.425,-2.593757656,51.1094,0,9.99957683,2.091875,4.482989838,-1.411494248,90.00000001 +14.76,50.425,-2.593756249,51.0883,0,9.998910588,2.1396875,4.401659453,-1.318575104,90.00000001 +14.77,50.425,-2.593754842,51.0666,0,9.999576764,2.1865625,4.319409871,-1.224506091,90.00000001 +14.78,50.425,-2.593753435,51.0445,0,10.00068708,2.23125,4.236258226,-1.129369314,90.00000001 +14.79,50.425,-2.593752027,51.022,0,10.00068704,2.275,4.152221875,-1.033247737,90.00000001 +14.8,50.425,-2.59375062,50.999,0,9.999576657,2.3184375,4.067318354,-0.936225127,90.00000001 +14.81,50.425,-2.593749213,50.9756,0,9.998688342,2.36125,3.981565479,-0.838386109,90.00000001 +14.82,50.425,-2.593747806,50.9518,0,9.998688305,2.403125,3.894981071,-0.739816054,90.00000001 +14.83,50.425,-2.593746399,50.9275,0,9.999576547,2.443125,3.807583293,-0.640600849,90.00000001 +14.84,50.425,-2.593744992,50.9029,0,10.00068686,2.4815625,3.719390306,-0.54082701,90.00000001 +14.85,50.425,-2.593743584,50.8779,0,10.00090889,2.52,3.63042056,-0.440581569,90.00000001 +14.86,50.425,-2.593742177,50.8525,0,10.00068678,2.558125,3.540692676,-0.339951903,90.00000001 +14.87,50.425,-2.59374077,50.8267,0,10.00090881,2.5946875,3.450225333,-0.239025845,90.00000001 +14.88,50.425,-2.593739362,50.8006,0,10.0006867,2.6296875,3.359037496,-0.137891289,90.00000001 +14.89,50.425,-2.593737955,50.7741,0,9.999576307,2.6634375,3.267148186,-0.036636583,90.00000001 +14.9,50.425,-2.593736548,50.7473,0,9.998910055,2.69625,3.174576541,0.064650151,90.00000001 +14.91,50.425,-2.593735141,50.7202,0,9.999576221,2.728125,3.081341927,0.165880449,90.00000001 +14.92,50.425,-2.593733734,50.6927,0,10.00068653,2.758125,2.987463766,0.266966132,90.00000001 +14.93,50.425,-2.593732326,50.665,0,10.00068648,2.7865625,2.892961769,0.367819023,90.00000001 +14.94,50.425,-2.593730919,50.637,0,9.999576092,2.815,2.797855588,0.468351172,90.00000001 +14.95,50.425,-2.593729512,50.6087,0,9.998909839,2.8428125,2.702165161,0.568474916,90.00000001 +14.96,50.425,-2.593728105,50.5801,0,9.999576002,2.868125,2.605910372,0.668102937,90.00000001 +14.97,50.425,-2.593726698,50.5513,0,10.00068631,2.8915625,2.509111387,0.767148318,90.00000001 +14.98,50.425,-2.59372529,50.5223,0,10.00068626,2.915,2.411788375,0.86552477,90.00000001 +14.99,50.425,-2.593723883,50.493,0,9.999575867,2.9378125,2.313961733,0.963146465,90.00000001 +15,50.425,-2.593722476,50.4635,0,9.998909612,2.958125,2.215651858,1.059928319,90.00000001 +15.01,50.425,-2.593721069,50.4338,0,9.999575774,2.9765625,2.116879263,1.15578582,90.00000001 +15.02,50.425,-2.593719662,50.404,0,10.00068608,2.9946875,2.017664573,1.250635545,90.00000001 +15.03,50.425,-2.593718254,50.3739,0,10.0009081,3.0115625,1.91802853,1.344394645,90.00000001 +15.04,50.425,-2.593716847,50.3437,0,10.00068598,3.02625,1.817991875,1.436981416,90.00000001 +15.05,50.425,-2.59371544,50.3134,0,10.000908,3.04,1.717575636,1.528315128,90.00000001 +15.06,50.425,-2.593714032,50.2829,0,10.00068589,3.053125,1.616800668,1.618316141,90.00000001 +15.07,50.425,-2.593712625,50.2523,0,9.999575489,3.0646875,1.515688055,1.706905901,90.00000001 +15.08,50.425,-2.593711218,50.2216,0,9.998909233,3.0746875,1.414258884,1.794007289,90.00000001 +15.09,50.425,-2.593709811,50.1908,0,9.999575394,3.0834375,1.31253441,1.879544216,90.00000001 +15.1,50.425,-2.593708404,50.1599,0,10.00068569,3.09125,1.210535776,1.963442196,90.00000001 +15.11,50.425,-2.593706996,50.129,0,10.00068565,3.098125,1.10828441,2.045628007,90.00000001 +15.12,50.425,-2.593705589,50.0979,0,9.999575248,3.103125,1.005801512,2.126029972,90.00000001 +15.13,50.425,-2.593704182,50.0669,0,9.998686921,3.10625,0.903108624,2.204578074,90.00000001 +15.14,50.425,-2.593702775,50.0358,0,9.998686872,3.1084375,0.80022712,2.281203673,90.00000001 +15.15,50.425,-2.593701368,50.0047,0,9.999575103,3.109375,0.697178483,2.355840077,90.00000001 +15.16,50.425,-2.593699961,49.9736,0,10.0006854,3.1084375,0.593984258,2.428422142,90.00000001 +15.17,50.425,-2.593698553,49.9425,0,10.00068535,3.10625,0.490665987,2.498886611,90.00000001 +15.18,50.425,-2.593697146,49.9115,0,9.999574956,3.1034375,0.387245271,2.567172008,90.00000001 +15.19,50.425,-2.593695739,49.8804,0,9.998908699,3.0996875,0.283743654,2.633218744,90.00000001 +15.2,50.425,-2.593694332,49.8495,0,9.99957486,3.094375,0.180182793,2.696969294,90.00000001 +15.21,50.425,-2.593692925,49.8185,0,10.00090723,3.086875,0.076584289,2.758368081,90.00000001 +15.22,50.425,-2.593691517,49.7877,0,10.00179546,3.0778125,-0.027030201,2.817361535,90.00000001 +15.23,50.425,-2.59369011,49.757,0,10.00179541,3.0684375,-0.130639018,2.873898145,90.00000001 +15.24,50.425,-2.593688702,49.7263,0,10.00090709,3.0578125,-0.23422062,2.927928753,90.00000001 +15.25,50.425,-2.593687295,49.6958,0,9.999574619,3.0446875,-0.337753234,2.979406089,90.00000001 +15.26,50.425,-2.593685888,49.6654,0,9.998686294,3.03,-0.441215375,3.028285347,90.00000001 +15.27,50.425,-2.593684481,49.6352,0,9.998686247,3.015,-0.544585326,3.074523958,90.00000001 +15.28,50.425,-2.593683074,49.6051,0,9.999574478,2.9996875,-0.647841545,3.11808147,90.00000001 +15.29,50.425,-2.593681667,49.5752,0,10.00068478,2.9828125,-0.750962547,3.158920011,90.00000001 +15.3,50.425,-2.593680259,49.5454,0,10.00068473,2.963125,-0.853926615,3.197003943,90.00000001 +15.31,50.425,-2.593678852,49.5159,0,9.999574338,2.9415625,-0.956712436,3.232299976,90.00000001 +15.32,50.425,-2.593677445,49.4866,0,9.998908084,2.92,-1.059298409,3.264777459,90.00000001 +15.33,50.425,-2.593676038,49.4575,0,9.999574247,2.898125,-1.161663163,3.294407971,90.00000001 +15.34,50.425,-2.593674631,49.4286,0,10.00068455,2.8746875,-1.263785327,3.321165673,90.00000001 +15.35,50.425,-2.593673223,49.4,0,10.0006845,2.8496875,-1.365643587,3.34502736,90.00000001 +15.36,50.425,-2.593671816,49.3716,0,9.999574113,2.8234375,-1.467216628,3.365972061,90.00000001 +15.37,50.425,-2.593670409,49.3435,0,9.99868579,2.79625,-1.568483251,3.383981615,90.00000001 +15.38,50.425,-2.593669002,49.3157,0,9.998685746,2.768125,-1.669422372,3.399040263,90.00000001 +15.39,50.425,-2.593667595,49.2881,0,9.999573981,2.738125,-1.770012791,3.411134944,90.00000001 +15.4,50.425,-2.593666188,49.2609,0,10.00090636,2.70625,-1.870233594,3.420255,90.00000001 +15.41,50.425,-2.59366478,49.234,0,10.00179459,2.6734375,-1.970063812,3.426392581,90.00000001 +15.42,50.425,-2.593663373,49.2074,0,10.00179455,2.6396875,-2.069482647,3.429542302,90.00000001 +15.43,50.425,-2.593661965,49.1812,0,10.00090623,2.6046875,-2.168469242,3.429701412,90.00000001 +15.44,50.425,-2.593660558,49.1553,0,9.999573774,2.5684375,-2.267003028,3.426869797,90.00000001 +15.45,50.425,-2.593659151,49.1298,0,9.998907525,2.5315625,-2.365063323,3.421049864,90.00000001 +15.46,50.425,-2.593657744,49.1047,0,9.999573695,2.4946875,-2.462629727,3.412246711,90.00000001 +15.47,50.425,-2.593656337,49.0799,0,10.00068401,2.4565625,-2.559681845,3.400468017,90.00000001 +15.48,50.425,-2.593654929,49.0555,0,10.00068397,2.41625,-2.65619945,3.385724094,90.00000001 +15.49,50.425,-2.593653522,49.0316,0,9.999573581,2.375,-2.752162261,3.368027777,90.00000001 +15.5,50.425,-2.593652115,49.008,0,9.998685265,2.333125,-2.847550394,3.347394478,90.00000001 +15.51,50.425,-2.593650708,48.9849,0,9.998685228,2.2896875,-2.942343798,3.323842245,90.00000001 +15.52,50.425,-2.593649301,48.9622,0,9.999573472,2.245,-3.036522762,3.297391477,90.00000001 +15.53,50.425,-2.593647894,48.94,0,10.00068379,2.1996875,-3.130067575,3.268065434,90.00000001 +15.54,50.425,-2.593646486,48.9182,0,10.00068375,2.1534375,-3.222958702,3.2358895,90.00000001 +15.55,50.425,-2.593645079,48.8969,0,9.99957337,2.10625,-3.315176774,3.200891862,90.00000001 +15.56,50.425,-2.593643672,48.8761,0,9.998907128,2.0584375,-3.406702485,3.163103004,90.00000001 +15.57,50.425,-2.593642265,48.8557,0,9.999573305,2.01,-3.497516811,3.122555869,90.00000001 +15.58,50.425,-2.593640858,48.8359,0,10.00068362,1.96125,-3.587600674,3.079285868,90.00000001 +15.59,50.425,-2.59363945,48.8165,0,10.00090566,1.9115625,-3.676935336,3.033330642,90.00000001 +15.6,50.425,-2.593638043,48.7976,0,10.00068356,1.8596875,-3.765502121,2.984730299,90.00000001 +15.61,50.425,-2.593636636,48.7793,0,10.0009056,1.8065625,-3.853282464,2.933527181,90.00000001 +15.62,50.425,-2.593635228,48.7615,0,10.00068351,1.7534375,-3.940258202,2.879766035,90.00000001 +15.63,50.425,-2.593633821,48.7442,0,9.999573131,1.6996875,-4.026411001,2.82349373,90.00000001 +15.64,50.425,-2.593632414,48.7275,0,9.998906896,1.645,-4.111722927,2.764759254,90.00000001 +15.65,50.425,-2.593631007,48.7113,0,9.99957308,1.59,-4.196176218,2.703613828,90.00000001 +15.66,50.425,-2.5936296,48.6957,0,10.0006834,1.535,-4.279753171,2.640110853,90.00000001 +15.67,50.425,-2.593628192,48.6806,0,10.00068338,1.4796875,-4.362436309,2.574305676,90.00000001 +15.68,50.425,-2.593626785,48.6661,0,9.999573009,1.423125,-4.444208502,2.506255651,90.00000001 +15.69,50.425,-2.593625378,48.6521,0,9.998906778,1.365,-4.525052503,2.436020135,90.00000001 +15.7,50.425,-2.593623971,48.6388,0,9.999572966,1.3065625,-4.604951525,2.363660378,90.00000001 +15.71,50.425,-2.593622564,48.626,0,10.00068329,1.248125,-4.683888837,2.289239463,90.00000001 +15.72,50.425,-2.593621156,48.6138,0,10.00068328,1.188125,-4.761848053,2.212822306,90.00000001 +15.73,50.425,-2.593619749,48.6022,0,9.999572909,1.126875,-4.838812729,2.134475484,90.00000001 +15.74,50.425,-2.593618342,48.5913,0,9.998684614,1.066875,-4.914766936,2.054267466,90.00000001 +15.75,50.425,-2.593616935,48.5809,0,9.998684598,1.008125,-4.989694747,1.972268038,90.00000001 +15.76,50.425,-2.593615528,48.5711,0,9.99957286,0.9478125,-5.063580519,1.888548763,90.00000001 +15.77,50.425,-2.593614121,48.5619,0,10.00090526,0.885,-5.136408841,1.803182635,90.00000001 +15.78,50.425,-2.593612713,48.5534,0,10.00179353,0.821875,-5.208164471,1.716244139,90.00000001 +15.79,50.425,-2.593611306,48.5455,0,10.00179352,0.76,-5.278832455,1.62780902,90.00000001 +15.8,50.425,-2.593609898,48.5382,0,10.00090523,0.698125,-5.348398011,1.537954456,90.00000001 +15.81,50.425,-2.593608491,48.5315,0,9.999572798,0.6346875,-5.416846643,1.446758712,90.00000001 +15.82,50.425,-2.593607084,48.5255,0,9.99868451,0.5703125,-5.484164028,1.354301429,90.00000001 +15.83,50.425,-2.593605677,48.5201,0,9.998684502,0.5065625,-5.550336069,1.260663166,90.00000001 +15.84,50.425,-2.59360427,48.5154,0,9.999572773,0.4434375,-5.615349075,1.165925568,90.00000001 +15.85,50.425,-2.593602863,48.5112,0,10.00068311,0.38,-5.67918935,1.070171315,90.00000001 +15.86,50.425,-2.593601455,48.5078,0,10.00068311,0.31625,-5.741843545,0.973483827,90.00000001 +15.87,50.425,-2.593600048,48.5049,0,9.999572757,0.251875,-5.803298712,0.875947446,90.00000001 +15.88,50.425,-2.593598641,48.5027,0,9.998906544,0.1865625,-5.863541901,0.777647197,90.00000001 +15.89,50.425,-2.593597234,48.5012,0,9.999572751,0.121875,-5.922560565,0.678668852,90.00000001 +15.9,50.425,-2.593595827,48.5003,0,10.0006831,0.0584375,-5.980342384,0.579098699,90.00000001 +15.91,50.425,-2.593594419,48.5,0,10.0006831,-0.0053125,-6.03687527,0.479023599,90.00000001 +15.92,50.425,-2.593593012,48.5004,0,9.99957275,-0.07,-6.09214742,0.378530755,90.00000001 +15.93,50.425,-2.593591605,48.5014,0,9.998906542,-0.1346875,-6.146147317,0.277707773,90.00000001 +15.94,50.425,-2.593590198,48.5031,0,9.999572753,-0.1984375,-6.198863674,0.176642716,90.00000001 +15.95,50.425,-2.593588791,48.5054,0,10.00068311,-0.261875,-6.250285491,0.075423534,90.00000001 +15.96,50.425,-2.593587383,48.5083,0,10.00090518,-0.326875,-6.300401994,-0.025861367,90.00000001 +15.97,50.425,-2.593585976,48.5119,0,10.00068312,-0.393125,-6.349202758,-0.127123693,90.00000001 +15.98,50.425,-2.593584569,48.5162,0,10.00090519,-0.4578125,-6.396677582,-0.228275209,90.00000001 +15.99,50.425,-2.593583161,48.5211,0,10.00068313,-0.52,-6.442816498,-0.329227622,90.00000001 +16,50.425,-2.593581754,48.5266,0,9.999572791,-0.581875,-6.487609938,-0.429892984,90.00000001 +16.01,50.425,-2.593580347,48.5327,0,9.998906592,-0.645,-6.531048561,-0.530183459,90.00000001 +16.02,50.425,-2.59357894,48.5395,0,9.999572811,-0.7084375,-6.573123201,-0.630011615,90.00000001 +16.03,50.425,-2.593577533,48.5469,0,10.00068317,-0.77125,-6.613825149,-0.729290361,90.00000001 +16.04,50.425,-2.593576125,48.5549,0,10.00068318,-0.8334375,-6.653145925,-0.827933181,90.00000001 +16.05,50.425,-2.593574718,48.5636,0,9.999572848,-0.895,-6.69107722,-0.925854075,90.00000001 +16.06,50.425,-2.593573311,48.5728,0,9.998684584,-0.9565625,-6.727611187,-1.022967556,90.00000001 +16.07,50.425,-2.593571904,48.5827,0,9.9986846,-1.0184375,-6.762740146,-1.119189,90.00000001 +16.08,50.425,-2.593570497,48.5932,0,9.999572895,-1.0796875,-6.796456879,-1.214434467,90.00000001 +16.09,50.425,-2.59356909,48.6043,0,10.00068326,-1.14,-6.828754166,-1.308620994,90.00000001 +16.1,50.425,-2.593567682,48.616,0,10.00068328,-1.1996875,-6.859625418,-1.401666303,90.00000001 +16.11,50.425,-2.593566275,48.6283,0,9.999795019,-1.2584375,-6.889064104,-1.493489379,90.00000001 +16.12,50.425,-2.593564868,48.6412,0,9.99979504,-1.3165625,-6.917064093,-1.584010121,90.00000001 +16.13,50.425,-2.593563461,48.6546,0,10.00068334,-1.375,-6.943619541,-1.673149577,90.00000001 +16.14,50.425,-2.593562053,48.6687,0,10.00090543,-1.433125,-6.96872489,-1.760830053,90.00000001 +16.15,50.425,-2.593560646,48.6833,0,10.00068338,-1.4896875,-6.992374926,-1.846975003,90.00000001 +16.16,50.425,-2.593559239,48.6985,0,10.00090548,-1.545,-7.014564722,-1.931509425,90.00000001 +16.17,50.425,-2.593557831,48.7142,0,10.00068343,-1.6,-7.03528958,-2.014359466,90.00000001 +16.18,50.425,-2.593556424,48.7305,0,9.99957311,-1.655,-7.054545202,-2.09545299,90.00000001 +16.19,50.425,-2.593555017,48.7473,0,9.998684858,-1.7096875,-7.072327577,-2.174719295,90.00000001 +16.2,50.425,-2.59355361,48.7647,0,9.998684885,-1.7634375,-7.088632982,-2.252089166,90.00000001 +16.21,50.425,-2.593552203,48.7826,0,9.999573191,-1.81625,-7.103458036,-2.327495168,90.00000001 +16.22,50.425,-2.593550796,48.801,0,10.00068357,-1.8684375,-7.116799644,-2.400871581,90.00000001 +16.23,50.425,-2.593549388,48.82,0,10.0006836,-1.9196875,-7.128655001,-2.472154406,90.00000001 +16.24,50.425,-2.593547981,48.8394,0,9.99957328,-1.97,-7.139021583,-2.54128142,90.00000001 +16.25,50.425,-2.593546574,48.8594,0,9.998907103,-2.02,-7.147897273,-2.608192463,90.00000001 +16.26,50.425,-2.593545167,48.8798,0,9.999573343,-2.069375,-7.155280235,-2.672829092,90.00000001 +16.27,50.425,-2.59354376,48.9008,0,10.00068372,-2.1165625,-7.161168923,-2.735134986,90.00000001 +16.28,50.425,-2.593542352,48.9222,0,10.00068376,-2.1615625,-7.165562077,-2.795055829,90.00000001 +16.29,50.425,-2.593540945,48.944,0,9.999573444,-2.206875,-7.16845878,-2.85253931,90.00000001 +16.3,50.425,-2.593539538,48.9663,0,9.99890727,-2.253125,-7.169858458,-2.907535294,90.00000001 +16.31,50.425,-2.593538131,48.9891,0,9.999573514,-2.2978125,-7.169760826,-2.95999594,90.00000001 +16.32,50.425,-2.593536724,49.0123,0,10.0006839,-2.34,-7.168165826,-3.009875411,90.00000001 +16.33,50.425,-2.593535316,49.0359,0,10.000906,-2.3815625,-7.165073917,-3.057130163,90.00000001 +16.34,50.425,-2.593533909,49.0599,0,10.00068397,-2.423125,-7.160485614,-3.101719113,90.00000001 +16.35,50.425,-2.593532502,49.0844,0,10.00090608,-2.463125,-7.154401948,-3.143603302,90.00000001 +16.36,50.425,-2.593531094,49.1092,0,10.00068405,-2.50125,-7.14682418,-3.182746232,90.00000001 +16.37,50.425,-2.593529687,49.1344,0,9.999573741,-2.5384375,-7.137753914,-3.219113754,90.00000001 +16.38,50.425,-2.59352828,49.16,0,9.998907573,-2.575,-7.127192984,-3.252674126,90.00000001 +16.39,50.425,-2.593526873,49.1859,0,9.999573823,-2.61125,-7.115143682,-3.283398186,90.00000001 +16.4,50.425,-2.593525466,49.2122,0,10.00068421,-2.6465625,-7.101608413,-3.311259004,90.00000001 +16.41,50.425,-2.593524058,49.2389,0,10.00068425,-2.6796875,-7.086590101,-3.3362324,90.00000001 +16.42,50.425,-2.593522651,49.2658,0,9.999573947,-2.7115625,-7.070091838,-3.358296547,90.00000001 +16.43,50.425,-2.593521244,49.2931,0,9.99868571,-2.743125,-7.052117064,-3.377432191,90.00000001 +16.44,50.425,-2.593519837,49.3207,0,9.998685754,-2.7728125,-7.032669558,-3.393622661,90.00000001 +16.45,50.425,-2.59351843,49.3486,0,9.999574077,-2.8,-7.01175339,-3.40685386,90.00000001 +16.46,50.425,-2.593517023,49.3767,0,10.00068447,-2.8265625,-6.989372857,-3.417114217,90.00000001 +16.47,50.425,-2.593515615,49.4051,0,10.00068451,-2.8534375,-6.965532713,-3.424394849,90.00000001 +16.48,50.425,-2.593514208,49.4338,0,9.999796279,-2.8796875,-6.940237887,-3.428689282,90.00000001 +16.49,50.425,-2.593512801,49.4627,0,9.999796325,-2.904375,-6.913493707,-3.429993907,90.00000001 +16.5,50.425,-2.593511394,49.4919,0,10.00068465,-2.9265625,-6.88530573,-3.42830752,90.00000001 +16.51,50.425,-2.593509986,49.5213,0,10.0006847,-2.9465625,-6.855679859,-3.423631554,90.00000001 +16.52,50.425,-2.593508579,49.5508,0,9.999796462,-2.9665625,-6.824622223,-3.415970192,90.00000001 +16.53,50.425,-2.593507172,49.5806,0,9.999796509,-2.98625,-6.792139355,-3.405329965,90.00000001 +16.54,50.425,-2.593505765,49.6106,0,10.00068483,-3.003125,-6.758238073,-3.391720326,90.00000001 +16.55,50.425,-2.593504357,49.6407,0,10.00068488,-3.018125,-6.722925423,-3.375153022,90.00000001 +16.56,50.425,-2.59350295,49.6709,0,9.999574581,-3.0334375,-6.686208741,-3.355642549,90.00000001 +16.57,50.425,-2.593501543,49.7014,0,9.998908419,-3.0478125,-6.64809576,-3.333205866,90.00000001 +16.58,50.425,-2.593500136,49.7319,0,9.999574676,-3.0596875,-6.608594388,-3.307862624,90.00000001 +16.59,50.425,-2.593498729,49.7626,0,10.00068507,-3.07,-6.567712875,-3.279634827,90.00000001 +16.6,50.425,-2.593497321,49.7933,0,10.00068512,-3.0796875,-6.525459816,-3.248547169,90.00000001 +16.61,50.425,-2.593495914,49.8242,0,9.99957482,-3.088125,-6.481843977,-3.214626749,90.00000001 +16.62,50.425,-2.593494507,49.8551,0,9.99890866,-3.0946875,-6.436874525,-3.177903134,90.00000001 +16.63,50.425,-2.5934931,49.8861,0,9.999574918,-3.1,-6.390560742,-3.138408294,90.00000001 +16.64,50.425,-2.593491693,49.9171,0,10.00068531,-3.1046875,-6.342912426,-3.096176721,90.00000001 +16.65,50.425,-2.593490285,49.9482,0,10.00068536,-3.108125,-6.293939489,-3.051245256,90.00000001 +16.66,50.425,-2.593488878,49.9793,0,9.999797132,-3.109375,-6.243652129,-3.003653032,90.00000001 +16.67,50.425,-2.593487471,50.0104,0,9.999797182,-3.1084375,-6.192060832,-2.953441647,90.00000001 +16.68,50.425,-2.593486064,50.0415,0,10.00068551,-3.1065625,-6.139176426,-2.900654759,90.00000001 +16.69,50.425,-2.593484656,50.0725,0,10.00068556,-3.1046875,-6.085009913,-2.845338434,90.00000001 +16.7,50.425,-2.593483249,50.1036,0,9.999797327,-3.1015625,-6.029572637,-2.787540972,90.00000001 +16.71,50.425,-2.593481842,50.1346,0,9.999797376,-3.09625,-5.972876171,-2.727312737,90.00000001 +16.72,50.425,-2.593480435,50.1655,0,10.0006857,-3.09,-5.914932376,-2.664706212,90.00000001 +16.73,50.425,-2.593479027,50.1964,0,10.00068575,-3.083125,-5.855753285,-2.599776056,90.00000001 +16.74,50.425,-2.59347762,50.2272,0,9.99957545,-3.074375,-5.795351272,-2.532578879,90.00000001 +16.75,50.425,-2.593476213,50.2579,0,9.998687219,-3.0634375,-5.733739,-2.463173178,90.00000001 +16.76,50.425,-2.593474806,50.2885,0,9.998687268,-3.05125,-5.670929304,-2.39161963,90.00000001 +16.77,50.425,-2.593473399,50.3189,0,9.999575595,-3.038125,-5.606935304,-2.317980516,90.00000001 +16.78,50.425,-2.593471992,50.3493,0,10.00068599,-3.0234375,-5.541770407,-2.242320064,90.00000001 +16.79,50.425,-2.593470584,50.3794,0,10.00068604,-3.0078125,-5.475448136,-2.164704336,90.00000001 +16.8,50.425,-2.593469177,50.4094,0,9.999575735,-2.9915625,-5.407982413,-2.085200942,90.00000001 +16.81,50.425,-2.59346777,50.4393,0,9.998909573,-2.973125,-5.339387276,-2.003879208,90.00000001 +16.82,50.425,-2.593466363,50.4689,0,9.999575829,-2.953125,-5.269677105,-1.920810011,90.00000001 +16.83,50.425,-2.593464956,50.4983,0,10.00068622,-2.933125,-5.198866397,-1.836065886,90.00000001 +16.84,50.425,-2.593463548,50.5276,0,10.00090834,-2.91125,-5.126969991,-1.749720688,90.00000001 +16.85,50.425,-2.593462141,50.5566,0,10.00068631,-2.8865625,-5.054002899,-1.661849704,90.00000001 +16.86,50.425,-2.593460734,50.5853,0,10.00090843,-2.8615625,-4.979980305,-1.572529594,90.00000001 +16.87,50.425,-2.593459326,50.6138,0,10.0006864,-2.8365625,-4.904917734,-1.481838167,90.00000001 +16.88,50.425,-2.593457919,50.6421,0,9.9995761,-2.8096875,-4.82883083,-1.389854549,90.00000001 +16.89,50.425,-2.593456512,50.67,0,9.998909934,-2.7815625,-4.75173552,-1.29665901,90.00000001 +16.9,50.425,-2.593455105,50.6977,0,9.999576187,-2.753125,-4.673647789,-1.202332739,90.00000001 +16.91,50.425,-2.593453698,50.7251,0,10.00068658,-2.7228125,-4.594584083,-1.106958013,90.00000001 +16.92,50.425,-2.59345229,50.7522,0,10.00068662,-2.69,-4.514560843,-1.010617967,90.00000001 +16.93,50.425,-2.593450883,50.7789,0,9.999576314,-2.6565625,-4.433594802,-0.913396712,90.00000001 +16.94,50.425,-2.593449476,50.8053,0,9.998910146,-2.623125,-4.351702861,-0.815378931,90.00000001 +16.95,50.425,-2.593448069,50.8314,0,9.999576396,-2.588125,-4.268902152,-0.71665011,90.00000001 +16.96,50.425,-2.593446662,50.8571,0,10.00068678,-2.5515625,-4.185209863,-0.617296363,90.00000001 +16.97,50.425,-2.593445254,50.8824,0,10.00068682,-2.5146875,-4.100643584,-0.517404323,90.00000001 +16.98,50.425,-2.593443847,50.9074,0,9.999576515,-2.4765625,-4.015220963,-0.417061136,90.00000001 +16.99,50.425,-2.59344244,50.932,0,9.998688274,-2.43625,-3.928959818,-0.316354235,90.00000001 +17,50.425,-2.593441033,50.9561,0,9.998688312,-2.395,-3.84187814,-0.215371455,90.00000001 +17.01,50.425,-2.593439626,50.9799,0,9.999576628,-2.3534375,-3.753994092,-0.114200916,90.00000001 +17.02,50.425,-2.593438219,51.0032,0,10.00090908,-2.31125,-3.665326123,-0.012930741,90.00000001 +17.03,50.425,-2.593436811,51.0261,0,10.0017974,-2.2684375,-3.575892682,0.088350665,90.00000001 +17.04,50.425,-2.593435404,51.0486,0,10.00179743,-2.224375,-3.485712448,0.189555065,90.00000001 +17.05,50.425,-2.593433996,51.0706,0,10.00090919,-2.178125,-3.394804329,0.29059411,90.00000001 +17.06,50.425,-2.593432589,51.0922,0,9.999576804,-2.1303125,-3.303187174,0.39137985,90.00000001 +17.07,50.425,-2.593431182,51.1132,0,9.998910627,-2.083125,-3.210880236,0.491824221,90.00000001 +17.08,50.425,-2.593429775,51.1338,0,9.999576868,-2.0365625,-3.117902707,0.591839734,90.00000001 +17.09,50.425,-2.593428368,51.154,0,10.00068725,-1.9878125,-3.02427407,0.691339183,90.00000001 +17.1,50.425,-2.59342696,51.1736,0,10.00068728,-1.9365625,-2.930013861,0.79023571,90.00000001 +17.11,50.425,-2.593425553,51.1927,0,9.999576961,-1.885,-2.835141733,0.888443197,90.00000001 +17.12,50.425,-2.593424146,51.2113,0,9.998688711,-1.8334375,-2.739677568,0.98587593,90.00000001 +17.13,50.425,-2.593422739,51.2294,0,9.998688739,-1.78125,-2.64364119,1.082448998,90.00000001 +17.14,50.425,-2.593421332,51.2469,0,9.999577046,-1.7284375,-2.547052767,1.178078118,90.00000001 +17.15,50.425,-2.593419925,51.264,0,10.00068742,-1.6746875,-2.44993241,1.272679924,90.00000001 +17.16,50.425,-2.593418517,51.2804,0,10.00068745,-1.6196875,-2.352300401,1.366171969,90.00000001 +17.17,50.425,-2.59341711,51.2964,0,9.999577123,-1.56375,-2.254177196,1.458472662,90.00000001 +17.18,50.425,-2.593415703,51.3117,0,9.998910938,-1.5078125,-2.155583192,1.549501561,90.00000001 +17.19,50.425,-2.593414296,51.3265,0,9.99957717,-1.451875,-2.056539015,1.639179253,90.00000001 +17.2,50.425,-2.593412889,51.3408,0,10.00090961,-1.3946875,-1.957065405,1.727427588,90.00000001 +17.21,50.425,-2.593411481,51.3544,0,10.00179791,-1.3365625,-1.857183048,1.814169559,90.00000001 +17.22,50.425,-2.593410074,51.3675,0,10.00179793,-1.2784375,-1.756912798,1.899329537,90.00000001 +17.23,50.425,-2.593408666,51.38,0,10.00090967,-1.2196875,-1.656275741,1.982833323,90.00000001 +17.24,50.425,-2.593407259,51.3919,0,9.999577272,-1.1596875,-1.555292732,2.064607979,90.00000001 +17.25,50.425,-2.593405852,51.4032,0,9.998689012,-1.0984375,-1.453984913,2.144582288,90.00000001 +17.26,50.425,-2.593404445,51.4139,0,9.998689029,-1.036875,-1.352373483,2.222686519,90.00000001 +17.27,50.425,-2.593403038,51.4239,0,9.999577323,-0.9765625,-1.250479586,2.298852549,90.00000001 +17.28,50.425,-2.593401631,51.4334,0,10.00068769,-0.9165625,-1.148324534,2.373013857,90.00000001 +17.29,50.425,-2.593400223,51.4423,0,10.0006877,-0.8546875,-1.045929699,2.445105928,90.00000001 +17.3,50.425,-2.593398816,51.4505,0,9.999577365,-0.791875,-0.943316453,2.515065851,90.00000001 +17.31,50.425,-2.593397409,51.4581,0,9.998911167,-0.73,-0.840506167,2.582832549,90.00000001 +17.32,50.425,-2.593396002,51.4651,0,9.999577387,-0.668125,-0.737520384,2.648347007,90.00000001 +17.33,50.425,-2.593394595,51.4715,0,10.00068775,-0.6046875,-0.63438059,2.711552044,90.00000001 +17.34,50.425,-2.593393187,51.4772,0,10.00068775,-0.54,-0.53110827,2.772392598,90.00000001 +17.35,50.425,-2.59339178,51.4823,0,9.999577414,-0.4753125,-0.427725083,2.830815558,90.00000001 +17.36,50.425,-2.593390373,51.4867,0,9.998689142,-0.4115625,-0.324252515,2.886770043,90.00000001 +17.37,50.425,-2.593388966,51.4905,0,9.998689148,-0.3484375,-0.220712281,2.940207181,90.00000001 +17.38,50.425,-2.593387559,51.4937,0,9.999577432,-0.2846875,-0.117125923,2.99108039,90.00000001 +17.39,50.425,-2.593386152,51.4962,0,10.00090985,-0.22,-0.0135151,3.039345381,90.00000001 +17.4,50.425,-2.593384744,51.4981,0,10.00179814,-0.1553125,0.09009853,3.084960041,90.00000001 +17.41,50.425,-2.593383337,51.4993,0,10.00179814,-0.0915625,0.19369331,3.127884492,90.00000001 +17.42,50.425,-2.593381929,51.4999,0,10.00090986,-0.0284375,0.297247697,3.168081434,90.00000001 +17.43,50.425,-2.593380522,51.4999,0,9.999577442,0.0353125,0.400739975,3.205515746,90.00000001 +17.44,50.425,-2.593379115,51.4992,0,9.998911231,0.1,0.504148543,3.240154827,90.00000001 +17.45,50.425,-2.593377708,51.4979,0,9.999577438,0.165,0.60745186,3.271968423,90.00000001 +17.46,50.425,-2.593376301,51.4959,0,10.00068778,0.23,0.710628323,3.300928804,90.00000001 +17.47,50.425,-2.593374893,51.4933,0,10.00068778,0.295,0.813656391,3.327010759,90.00000001 +17.48,50.425,-2.593373486,51.49,0,9.999577426,0.36,0.916514519,3.350191486,90.00000001 +17.49,50.425,-2.593372079,51.4861,0,9.998689141,0.4246875,1.019181222,3.370450758,90.00000001 +17.5,50.425,-2.593370672,51.4815,0,9.998689133,0.488125,1.121635129,3.387770985,90.00000001 +17.51,50.425,-2.593369265,51.4763,0,9.999577404,0.55,1.223854753,3.402137043,90.00000001 +17.52,50.425,-2.593367858,51.4705,0,10.00068774,0.611875,1.325818838,3.413536382,90.00000001 +17.53,50.425,-2.59336645,51.4641,0,10.00068773,0.675,1.427506012,3.421959033,90.00000001 +17.54,50.425,-2.593365043,51.457,0,9.999577375,0.7384375,1.528895019,3.427397721,90.00000001 +17.55,50.425,-2.593363636,51.4493,0,9.998911153,0.80125,1.629964831,3.429847688,90.00000001 +17.56,50.425,-2.593362229,51.441,0,9.999577349,0.8634375,1.730694192,3.429306701,90.00000001 +17.57,50.425,-2.593360822,51.432,0,10.00068768,0.925,1.831062131,3.425775391,90.00000001 +17.58,50.425,-2.593359414,51.4225,0,10.00090974,0.9865625,1.931047678,3.419256678,90.00000001 +17.59,50.425,-2.593358007,51.4123,0,10.00068765,1.0484375,2.03062992,3.40975635,90.00000001 +17.6,50.425,-2.5933566,51.4015,0,10.00090971,1.1096875,2.129788116,3.397282715,90.00000001 +17.61,50.425,-2.593355192,51.3901,0,10.00068762,1.1696875,2.228501582,3.381846545,90.00000001 +17.62,50.425,-2.593353785,51.3781,0,9.999577251,1.2284375,2.326749578,3.36346136,90.00000001 +17.63,50.425,-2.593352378,51.3655,0,9.998911022,1.2865625,2.424511705,3.342143205,90.00000001 +17.64,50.425,-2.593350971,51.3524,0,9.999577211,1.345,2.521767509,3.317910585,90.00000001 +17.65,50.425,-2.593349564,51.3386,0,10.00068754,1.403125,2.61849665,3.290784758,90.00000001 +17.66,50.425,-2.593348156,51.3243,0,10.00068752,1.4596875,2.714678961,3.260789329,90.00000001 +17.67,50.425,-2.593346749,51.3094,0,9.999577143,1.5153125,2.81029433,3.227950425,90.00000001 +17.68,50.425,-2.593345342,51.294,0,9.99891091,1.5715625,2.905322818,3.192296693,90.00000001 +17.69,50.425,-2.593343935,51.278,0,9.999577095,1.628125,2.999744543,3.153859247,90.00000001 +17.7,50.425,-2.593342528,51.2614,0,10.00068742,1.683125,3.093539854,3.112671603,90.00000001 +17.71,50.425,-2.59334112,51.2443,0,10.00068739,1.7365625,3.186689098,3.068769628,90.00000001 +17.72,50.425,-2.593339713,51.2267,0,9.999577014,1.79,3.279172851,3.022191655,90.00000001 +17.73,50.425,-2.593338306,51.2085,0,9.998688707,1.843125,3.370971748,2.972978247,90.00000001 +17.74,50.425,-2.593336899,51.1898,0,9.998688678,1.894375,3.462066709,2.921172434,90.00000001 +17.75,50.425,-2.593335492,51.1706,0,9.999576927,1.9434375,3.552438655,2.866819252,90.00000001 +17.76,50.425,-2.593334085,51.1509,0,10.00090931,1.991875,3.642068734,2.809966197,90.00000001 +17.77,50.425,-2.593332677,51.1308,0,10.00179756,2.0415625,3.730938155,2.750662773,90.00000001 +17.78,50.425,-2.59333127,51.1101,0,10.00179753,2.0915625,3.819028468,2.688960776,90.00000001 +17.79,50.425,-2.593329862,51.0889,0,10.00090922,2.139375,3.906321224,2.624913949,90.00000001 +17.8,50.425,-2.593328455,51.0673,0,9.999576765,2.185,3.992798145,2.558578156,90.00000001 +17.81,50.425,-2.593327048,51.0452,0,9.998688452,2.23,4.078441298,2.490011209,90.00000001 +17.82,50.425,-2.593325641,51.0227,0,9.998688416,2.2746875,4.163232692,2.41927298,90.00000001 +17.83,50.425,-2.593324234,50.9997,0,9.999576659,2.318125,4.247154622,2.346425063,90.00000001 +17.84,50.425,-2.593322827,50.9763,0,10.00068697,2.36,4.330189614,2.271531057,90.00000001 +17.85,50.425,-2.593321419,50.9525,0,10.00068693,2.4015625,4.412320249,2.194656278,90.00000001 +17.86,50.425,-2.593320012,50.9283,0,9.999576548,2.443125,4.493529511,2.115867706,90.00000001 +17.87,50.425,-2.593318605,50.9036,0,9.998910299,2.4828125,4.573800325,2.035234037,90.00000001 +17.88,50.425,-2.593317198,50.8786,0,9.999576469,2.5196875,4.653115904,1.952825632,90.00000001 +17.89,50.425,-2.593315791,50.8532,0,10.00068678,2.5553125,4.731459804,1.868714339,90.00000001 +17.9,50.425,-2.593314383,50.8275,0,10.00068674,2.5915625,4.80881558,1.782973497,90.00000001 +17.91,50.425,-2.593312976,50.8014,0,9.999576349,2.628125,4.885167077,1.695677877,90.00000001 +17.92,50.425,-2.593311569,50.7749,0,9.998910099,2.6628125,4.960498422,1.606903567,90.00000001 +17.93,50.425,-2.593310162,50.7481,0,9.999576265,2.695,5.034793802,1.516728031,90.00000001 +17.94,50.425,-2.593308755,50.721,0,10.00068657,2.7265625,5.10803769,1.425229937,90.00000001 +17.95,50.425,-2.593307347,50.6936,0,10.0009086,2.758125,5.180214902,1.332488983,90.00000001 +17.96,50.425,-2.59330594,50.6658,0,10.00068649,2.7878125,5.251310255,1.238586071,90.00000001 +17.97,50.425,-2.593304533,50.6378,0,10.00090851,2.8146875,5.32130891,1.143603075,90.00000001 +17.98,50.425,-2.593303125,50.6095,0,10.0006864,2.84,5.390196314,1.047622847,90.00000001 +17.99,50.425,-2.593301718,50.581,0,9.999576004,2.865,5.457958027,0.950729095,90.00000001 +18,50.425,-2.593300311,50.5522,0,9.99890975,2.89,5.524579955,0.85300633,90.00000001 +18.01,50.425,-2.593298904,50.5232,0,9.999575914,2.914375,5.590048118,0.754539694,90.00000001 +18.02,50.425,-2.593297497,50.4939,0,10.00068622,2.9365625,5.654348879,0.655415074,90.00000001 +18.03,50.425,-2.593296089,50.4644,0,10.00068617,2.95625,5.717468775,0.555718927,90.00000001 +18.04,50.425,-2.593294682,50.4348,0,9.999575775,2.975,5.779394684,0.455538174,90.00000001 +18.05,50.425,-2.593293275,50.4049,0,9.998687449,2.9934375,5.840113599,0.354960246,90.00000001 +18.06,50.425,-2.593291868,50.3749,0,9.998687403,3.01125,5.899612917,0.254072748,90.00000001 +18.07,50.425,-2.593290461,50.3447,0,9.999575635,3.0278125,5.957880147,0.152963688,90.00000001 +18.08,50.425,-2.593289054,50.3143,0,10.00068594,3.0415625,6.014903198,0.051721244,90.00000001 +18.09,50.425,-2.593287646,50.2838,0,10.00068589,3.053125,6.070670097,-0.04956635,90.00000001 +18.1,50.425,-2.593286239,50.2533,0,9.999797561,3.0646875,6.125169213,-0.150810628,90.00000001 +18.11,50.425,-2.593284832,50.2225,0,9.999797513,3.075,6.178389142,-0.251923469,90.00000001 +18.12,50.425,-2.593283425,50.1917,0,10.00068574,3.0828125,6.230318771,-0.352816581,90.00000001 +18.13,50.425,-2.593282017,50.1609,0,10.00090777,3.0903125,6.280947327,-0.453402072,90.00000001 +18.14,50.425,-2.59328061,50.1299,0,10.00068565,3.0978125,6.330264154,-0.553592165,90.00000001 +18.15,50.425,-2.593279203,50.0989,0,10.00090767,3.1028125,6.378259052,-0.653299541,90.00000001 +18.16,50.425,-2.593277795,50.0678,0,10.00068555,3.105,6.424921881,-0.752437168,90.00000001 +18.17,50.425,-2.593276388,50.0368,0,9.999575153,3.1065625,6.470242957,-0.850918701,90.00000001 +18.18,50.425,-2.593274981,50.0057,0,9.998686826,3.1084375,6.514212769,-0.948658254,90.00000001 +18.19,50.425,-2.593273574,49.9746,0,9.998686777,3.109375,6.556822208,-1.045570512,90.00000001 +18.2,50.425,-2.593272167,49.9435,0,9.999575007,3.108125,6.598062335,-1.141571023,90.00000001 +18.21,50.425,-2.59327076,49.9124,0,10.00068531,3.1046875,6.637924556,-1.236576077,90.00000001 +18.22,50.425,-2.593269352,49.8814,0,10.00068526,3.1,6.676400505,-1.330502825,90.00000001 +18.23,50.425,-2.593267945,49.8504,0,9.999574861,3.0946875,6.713482162,-1.423269333,90.00000001 +18.24,50.425,-2.593266538,49.8195,0,9.998908604,3.0878125,6.749161848,-1.514794757,90.00000001 +18.25,50.425,-2.593265131,49.7886,0,9.999574764,3.0784375,6.783432001,-1.604999284,90.00000001 +18.26,50.425,-2.593263724,49.7579,0,10.00068506,3.068125,6.816285573,-1.69380419,90.00000001 +18.27,50.425,-2.593262316,49.7273,0,10.00068502,3.058125,6.847715631,-1.781132068,90.00000001 +18.28,50.425,-2.593260909,49.6967,0,9.999796691,3.04625,6.877715586,-1.866906772,90.00000001 +18.29,50.425,-2.593259502,49.6663,0,9.999796644,3.03125,6.906279309,-1.951053474,90.00000001 +18.3,50.425,-2.593258095,49.6361,0,10.00068487,3.0153125,6.933400667,-2.033498892,90.00000001 +18.31,50.425,-2.593256687,49.606,0,10.00068483,2.9996875,6.959074104,-2.114171063,90.00000001 +18.32,50.425,-2.59325528,49.5761,0,9.999796501,2.9828125,6.983294233,-2.192999628,90.00000001 +18.33,50.425,-2.593253873,49.5463,0,9.999796455,2.9634375,7.006055955,-2.269915831,90.00000001 +18.34,50.425,-2.593252466,49.5168,0,10.00068469,2.9428125,7.027354573,-2.344852695,90.00000001 +18.35,50.425,-2.593251058,49.4875,0,10.00068464,2.921875,7.047185616,-2.417744787,90.00000001 +18.36,50.425,-2.593249651,49.4583,0,9.999574248,2.8996875,7.06554496,-2.488528508,90.00000001 +18.37,50.425,-2.593248244,49.4295,0,9.998907993,2.87625,7.082428766,-2.557142267,90.00000001 +18.38,50.425,-2.593246837,49.4008,0,9.999574158,2.8515625,7.097833481,-2.623526131,90.00000001 +18.39,50.425,-2.59324543,49.3724,0,10.00068446,2.824375,7.111755897,-2.687622289,90.00000001 +18.4,50.425,-2.593244022,49.3443,0,10.00068442,2.7953125,7.124193092,-2.749374764,90.00000001 +18.41,50.425,-2.593242615,49.3165,0,9.999574026,2.7665625,7.135142544,-2.808729754,90.00000001 +18.42,50.425,-2.593241208,49.289,0,9.998685704,2.738125,7.144601848,-2.865635464,90.00000001 +18.43,50.425,-2.593239801,49.2617,0,9.998685661,2.7078125,7.152569113,-2.920042333,90.00000001 +18.44,50.425,-2.593238394,49.2348,0,9.999573898,2.6746875,7.159042677,-2.971902862,90.00000001 +18.45,50.425,-2.593236987,49.2082,0,10.00068421,2.64,7.164021164,-3.021171847,90.00000001 +18.46,50.425,-2.593235579,49.182,0,10.00090623,2.605,7.167503545,-3.067806314,90.00000001 +18.47,50.425,-2.593234172,49.1561,0,10.00068412,2.57,7.169489072,-3.111765642,90.00000001 +18.48,50.425,-2.593232765,49.1306,0,10.00090615,2.534375,7.169977347,-3.153011441,90.00000001 +18.49,50.425,-2.593231357,49.1054,0,10.00068404,2.4965625,7.168968254,-3.19150773,90.00000001 +18.5,50.425,-2.59322995,49.0806,0,9.999573658,2.4565625,7.166462022,-3.227221049,90.00000001 +18.51,50.425,-2.593228543,49.0563,0,9.99890741,2.4165625,7.162459167,-3.260120114,90.00000001 +18.52,50.425,-2.593227136,49.0323,0,9.999573582,2.3765625,7.156960548,-3.290176391,90.00000001 +18.53,50.425,-2.593225729,49.0087,0,10.00068389,2.334375,7.149967254,-3.317363525,90.00000001 +18.54,50.425,-2.593224321,48.9856,0,10.00068386,2.29,7.141480775,-3.341657852,90.00000001 +18.55,50.425,-2.593222914,48.9629,0,9.999573473,2.245,7.131502945,-3.363038231,90.00000001 +18.56,50.425,-2.593221507,48.9407,0,9.99890723,2.2,7.12003571,-3.381485982,90.00000001 +18.57,50.425,-2.5932201,48.9189,0,9.999573405,2.155,7.107081593,-3.396985064,90.00000001 +18.58,50.425,-2.593218693,48.8976,0,10.00068372,2.109375,7.092643285,-3.409521896,90.00000001 +18.59,50.425,-2.593217285,48.8767,0,10.00068369,2.0615625,7.07672371,-3.419085593,90.00000001 +18.6,50.425,-2.593215878,48.8563,0,9.999573306,2.0115625,7.059326305,-3.425667789,90.00000001 +18.61,50.425,-2.593214471,48.8365,0,9.998907067,1.9615625,7.040454623,-3.429262698,90.00000001 +18.62,50.425,-2.593213064,48.8171,0,9.999573245,1.911875,7.020112615,-3.429867283,90.00000001 +18.63,50.425,-2.593211657,48.7982,0,10.00068356,1.86125,6.998304524,-3.427480971,90.00000001 +18.64,50.425,-2.593210249,48.7799,0,10.00068353,1.8096875,6.975034989,-3.422105882,90.00000001 +18.65,50.425,-2.593208842,48.762,0,9.999795229,1.7565625,6.950308766,-3.4137466,90.00000001 +18.66,50.425,-2.593207435,48.7447,0,9.999795202,1.7015625,6.924131069,-3.402410516,90.00000001 +18.67,50.425,-2.593206028,48.728,0,10.00068345,1.646875,6.896507399,-3.388107484,90.00000001 +18.68,50.425,-2.59320462,48.7118,0,10.00068343,1.593125,6.867443427,-3.370849937,90.00000001 +18.69,50.425,-2.593203213,48.6961,0,9.999795125,1.538125,6.836945285,-3.350653003,90.00000001 +18.7,50.425,-2.593201806,48.681,0,9.999795101,1.48125,6.805019332,-3.327534214,90.00000001 +18.71,50.425,-2.593200399,48.6665,0,10.00068336,1.4234375,6.771672271,-3.301513794,90.00000001 +18.72,50.425,-2.593198991,48.6525,0,10.00068334,1.365,6.736911036,-3.272614375,90.00000001 +18.73,50.425,-2.593197584,48.6392,0,9.999572967,1.3065625,6.700742846,-3.240861226,90.00000001 +18.74,50.425,-2.593196177,48.6264,0,9.998684668,1.2484375,6.663175322,-3.206281963,90.00000001 +18.75,50.425,-2.59319477,48.6142,0,9.998684649,1.1896875,6.624216254,-3.16890678,90.00000001 +18.76,50.425,-2.593193363,48.6026,0,9.99957291,1.13,6.58387378,-3.128768279,90.00000001 +18.77,50.425,-2.593191956,48.5916,0,10.00068324,1.07,6.542156437,-3.085901468,90.00000001 +18.78,50.425,-2.593190548,48.5812,0,10.00068322,1.0096875,6.499072761,-3.040343645,90.00000001 +18.79,50.425,-2.593189141,48.5714,0,9.999572861,0.9484375,6.454631862,-2.992134632,90.00000001 +18.8,50.425,-2.593187734,48.5622,0,9.998906637,0.8865625,6.408843023,-2.941316427,90.00000001 +18.81,50.425,-2.593186327,48.5537,0,9.999572833,0.825,6.361715755,-2.887933377,90.00000001 +18.82,50.425,-2.59318492,48.5457,0,10.00068317,0.763125,6.313259912,-2.832031947,90.00000001 +18.83,50.425,-2.593183512,48.5384,0,10.00090523,0.6996875,6.263485636,-2.773661012,90.00000001 +18.84,50.425,-2.593182105,48.5317,0,10.00068315,0.6353125,6.212403355,-2.712871336,90.00000001 +18.85,50.425,-2.593180698,48.5257,0,10.00090521,0.5715625,6.16002361,-2.649716032,90.00000001 +18.86,50.425,-2.59317929,48.5203,0,10.00068313,0.5084375,6.106357461,-2.584250161,90.00000001 +18.87,50.425,-2.593177883,48.5155,0,9.999572773,0.445,6.05141608,-2.516530732,90.00000001 +18.88,50.425,-2.593176476,48.5114,0,9.998906558,0.3815625,5.995210983,-2.446616875,90.00000001 +18.89,50.425,-2.593175069,48.5079,0,9.999572761,0.3184375,5.937753801,-2.374569552,90.00000001 +18.9,50.425,-2.593173662,48.505,0,10.0006831,0.2546875,5.879056624,-2.300451502,90.00000001 +18.91,50.425,-2.593172254,48.5028,0,10.0006831,0.19,5.819131656,-2.22432747,90.00000001 +18.92,50.425,-2.593170847,48.5012,0,9.999572751,0.125,5.757991444,-2.146263804,90.00000001 +18.93,50.425,-2.59316944,48.5003,0,9.998906541,0.06,5.695648766,-2.066328571,90.00000001 +18.94,50.425,-2.593168033,48.5,0,9.999572749,-0.0046875,5.632116627,-1.984591444,90.00000001 +18.95,50.425,-2.593166626,48.5004,0,10.0006831,-0.0684375,5.567408321,-1.901123754,90.00000001 +18.96,50.425,-2.593165218,48.5014,0,10.0006831,-0.131875,5.501537254,-1.815998211,90.00000001 +18.97,50.425,-2.593163811,48.503,0,9.999572754,-0.1965625,5.434517292,-1.729289128,90.00000001 +18.98,50.425,-2.593162404,48.5053,0,9.998684479,-0.2615625,5.366362415,-1.641072019,90.00000001 +18.99,50.425,-2.593160997,48.5083,0,9.998684484,-0.325,5.29708689,-1.551423949,90.00000001 +19,50.425,-2.59315959,48.5118,0,9.999572768,-0.3884375,5.226705041,-1.460422953,90.00000001 +19.01,50.425,-2.593158183,48.516,0,10.00090519,-0.4534375,5.155231708,-1.368148501,90.00000001 +19.02,50.425,-2.593156775,48.5209,0,10.00179348,-0.518125,5.082681786,-1.274680979,90.00000001 +19.03,50.425,-2.593155368,48.5264,0,10.00179349,-0.5815625,5.009070403,-1.180101919,90.00000001 +19.04,50.425,-2.59315396,48.5325,0,10.00090522,-0.645,4.934412914,-1.08449377,90.00000001 +19.05,50.425,-2.593152553,48.5393,0,9.999572811,-0.708125,4.85872496,-0.987939953,90.00000001 +19.06,50.425,-2.593151146,48.5467,0,9.998906614,-0.7696875,4.782022298,-0.890524638,90.00000001 +19.07,50.425,-2.593149739,48.5547,0,9.999572834,-0.8303125,4.704321027,-0.792332735,90.00000001 +19.08,50.425,-2.593148332,48.5633,0,10.0006832,-0.891875,4.625637249,-0.693449903,90.00000001 +19.09,50.425,-2.593146924,48.5725,0,10.00068321,-0.955,4.545987521,-0.593962428,90.00000001 +19.1,50.425,-2.593145517,48.5824,0,9.999572878,-1.0178125,4.465388402,-0.493956999,90.00000001 +19.11,50.425,-2.59314411,48.5929,0,9.998684616,-1.078125,4.383856737,-0.393520821,90.00000001 +19.12,50.425,-2.593142703,48.604,0,9.998684633,-1.136875,4.301409543,-0.292741441,90.00000001 +19.13,50.425,-2.593141296,48.6156,0,9.999572929,-1.1965625,4.218064065,-0.191706865,90.00000001 +19.14,50.425,-2.593139889,48.6279,0,10.0006833,-1.2565625,4.133837722,-0.090505044,90.00000001 +19.15,50.425,-2.593138481,48.6408,0,10.00068332,-1.3146875,4.048748047,0.010775617,90.00000001 +19.16,50.425,-2.593137074,48.6542,0,9.999572991,-1.371875,3.962812915,0.112046939,90.00000001 +19.17,50.425,-2.593135667,48.6682,0,9.998906804,-1.43,3.876050145,0.213220571,90.00000001 +19.18,50.425,-2.59313426,48.6828,0,9.999573035,-1.488125,3.7884779,0.314208221,90.00000001 +19.19,50.425,-2.593132853,48.698,0,10.00068341,-1.5446875,3.700114458,0.414921883,90.00000001 +19.2,50.425,-2.593131445,48.7137,0,10.0009055,-1.6,3.610978383,0.515273779,90.00000001 +19.21,50.425,-2.593130038,48.73,0,10.00068346,-1.655,3.521088123,0.615176305,90.00000001 +19.22,50.425,-2.593128631,48.7468,0,10.00090555,-1.7096875,3.430462529,0.71454237,90.00000001 +19.23,50.425,-2.593127223,48.7642,0,10.00068351,-1.763125,3.339120566,0.813285401,90.00000001 +19.24,50.425,-2.593125816,48.7821,0,9.999573191,-1.8146875,3.247081256,0.911319224,90.00000001 +19.25,50.425,-2.593124409,48.8005,0,9.998907011,-1.8653125,3.154363851,1.008558298,90.00000001 +19.26,50.425,-2.593123002,48.8194,0,9.999573249,-1.9165625,3.060987658,1.104917939,90.00000001 +19.27,50.425,-2.593121595,48.8388,0,10.00068363,-1.968125,2.966972274,1.200314094,90.00000001 +19.28,50.425,-2.593120187,48.8588,0,10.00068366,-2.018125,2.872337236,1.294663513,90.00000001 +19.29,50.425,-2.59311878,48.8792,0,9.999573342,-2.06625,2.777102369,1.387884032,90.00000001 +19.3,50.425,-2.593117373,48.9001,0,9.998907166,-2.1134375,2.681287496,1.479894236,90.00000001 +19.31,50.425,-2.593115966,48.9215,0,9.999573409,-2.16,2.584912729,1.570613967,90.00000001 +19.32,50.425,-2.593114559,48.9433,0,10.00068379,-2.2065625,2.487998064,1.659964099,90.00000001 +19.33,50.425,-2.593113151,48.9656,0,10.00068383,-2.253125,2.390563898,1.747866711,90.00000001 +19.34,50.425,-2.593111744,48.9884,0,9.999573513,-2.2978125,2.292630457,1.834245198,90.00000001 +19.35,50.425,-2.593110337,49.0116,0,9.998685271,-2.3396875,2.194218194,1.919024159,90.00000001 +19.36,50.425,-2.59310893,49.0352,0,9.998685308,-2.38,2.095347738,2.002129682,90.00000001 +19.37,50.425,-2.593107523,49.0592,0,9.999573624,-2.42,1.996039656,2.083489345,90.00000001 +19.38,50.425,-2.593106116,49.0836,0,10.00090608,-2.46,1.896314748,2.163032159,90.00000001 +19.39,50.425,-2.593104708,49.1084,0,10.0017944,-2.5,1.796193868,2.240688796,90.00000001 +19.4,50.425,-2.593103301,49.1336,0,10.00179444,-2.539375,1.695697816,2.316391532,90.00000001 +19.41,50.425,-2.593101893,49.1592,0,10.0009062,-2.5765625,1.594847675,2.390074306,90.00000001 +19.42,50.425,-2.593100486,49.1852,0,9.999573821,-2.61125,1.493664417,2.461672945,90.00000001 +19.43,50.425,-2.593099079,49.2114,0,9.998685584,-2.645,1.392169241,2.531124941,90.00000001 +19.44,50.425,-2.593097672,49.2381,0,9.998685625,-2.6784375,1.290383346,2.598369732,90.00000001 +19.45,50.425,-2.593096265,49.265,0,9.999573945,-2.7109375,1.188327989,2.663348761,90.00000001 +19.46,50.425,-2.593094858,49.2923,0,10.00068434,-2.741875,1.086024484,2.726005248,90.00000001 +19.47,50.425,-2.59309345,49.3199,0,10.00068438,-2.77125,0.983494145,2.786284648,90.00000001 +19.48,50.425,-2.593092043,49.3477,0,9.999574076,-2.7996875,0.8807584,2.844134363,90.00000001 +19.49,50.425,-2.593090636,49.3759,0,9.99890791,-2.826875,0.777838736,2.899503973,90.00000001 +19.5,50.425,-2.593089229,49.4043,0,9.999574163,-2.8528125,0.674756582,2.952345177,90.00000001 +19.51,50.425,-2.593087822,49.4329,0,10.00068456,-2.8784375,0.571533594,3.002611853,90.00000001 +19.52,50.425,-2.593086414,49.4619,0,10.0006846,-2.9028125,0.468191202,3.050260227,90.00000001 +19.53,50.425,-2.593085007,49.491,0,9.9995743,-2.9246875,0.364751063,3.095248701,90.00000001 +19.54,50.425,-2.5930836,49.5204,0,9.998908137,-2.945,0.261234721,3.137538086,90.00000001 +19.55,50.425,-2.593082193,49.5499,0,9.999574391,-2.965,0.157663833,3.177091539,90.00000001 +19.56,50.425,-2.593080786,49.5797,0,10.00068479,-2.9846875,0.05406,3.213874456,90.00000001 +19.57,50.425,-2.593079378,49.6096,0,10.0009069,-3.0028125,-0.049555062,3.247854864,90.00000001 +19.58,50.425,-2.593077971,49.6398,0,10.00068488,-3.0184375,-0.153159869,3.279003084,90.00000001 +19.59,50.425,-2.593076564,49.67,0,10.000907,-3.0328125,-0.25673259,3.307291958,90.00000001 +19.6,50.425,-2.593075156,49.7004,0,10.00068497,-3.046875,-0.36025174,3.33269685,90.00000001 +19.61,50.425,-2.593073749,49.731,0,9.999574674,-3.059375,-0.46369566,3.355195585,90.00000001 +19.62,50.425,-2.593072342,49.7616,0,9.998908514,-3.0696875,-0.567042751,3.37476851,90.00000001 +19.63,50.425,-2.593070935,49.7924,0,9.999574771,-3.0784375,-0.670271411,3.391398553,90.00000001 +19.64,50.425,-2.593069528,49.8232,0,10.00068517,-3.0865625,-0.773360097,3.405071332,90.00000001 +19.65,50.425,-2.59306812,49.8541,0,10.00068522,-3.0946875,-0.876287267,3.415774756,90.00000001 +19.66,50.425,-2.593066713,49.8851,0,9.999574915,-3.10125,-0.979031434,3.423499602,90.00000001 +19.67,50.425,-2.593065306,49.9162,0,9.998686685,-3.1046875,-1.081571169,3.428239109,90.00000001 +19.68,50.425,-2.593063899,49.9472,0,9.998686734,-3.1065625,-1.183885045,3.429989151,90.00000001 +19.69,50.425,-2.593062492,49.9783,0,9.999575062,-3.1084375,-1.285951632,3.428748182,90.00000001 +19.7,50.425,-2.593061085,50.0094,0,10.00068546,-3.109375,-1.387749674,3.42451729,90.00000001 +19.71,50.425,-2.593059677,50.0405,0,10.00068551,-3.1084375,-1.489257913,3.417300199,90.00000001 +19.72,50.425,-2.59305827,50.0716,0,9.999575207,-3.10625,-1.590455152,3.407103154,90.00000001 +19.73,50.425,-2.593056863,50.1026,0,9.998909047,-3.103125,-1.691320246,3.393935037,90.00000001 +19.74,50.425,-2.593055456,50.1337,0,9.999575305,-3.098125,-1.791832112,3.377807421,90.00000001 +19.75,50.425,-2.593054049,50.1646,0,10.00090777,-3.09125,-1.891969779,3.358734229,90.00000001 +19.76,50.425,-2.593052641,50.1955,0,10.0017961,-3.083125,-1.991712335,3.336732192,90.00000001 +19.77,50.425,-2.593051234,50.2263,0,10.00179615,-3.073125,-2.091038923,3.311820502,90.00000001 +19.78,50.425,-2.593049826,50.257,0,10.00090792,-3.0615625,-2.18992886,3.284020877,90.00000001 +19.79,50.425,-2.593048419,50.2875,0,9.999575545,-3.05,-2.288361463,3.253357493,90.00000001 +19.8,50.425,-2.593047012,50.318,0,9.998687314,-3.038125,-2.386316161,3.219857109,90.00000001 +19.81,50.425,-2.593045605,50.3483,0,9.998687362,-3.0246875,-2.4837725,3.183549003,90.00000001 +19.82,50.425,-2.593044198,50.3785,0,9.999575687,-3.0096875,-2.580710084,3.144464802,90.00000001 +19.83,50.425,-2.593042791,50.4085,0,10.00068608,-2.993125,-2.6771088,3.102638539,90.00000001 +19.84,50.425,-2.593041383,50.4384,0,10.00068613,-2.9746875,-2.772948425,3.058106769,90.00000001 +19.85,50.425,-2.593039976,50.468,0,9.999575827,-2.9546875,-2.868208903,3.010908282,90.00000001 +19.86,50.425,-2.593038569,50.4975,0,9.998909665,-2.9334375,-2.962870412,2.961084216,90.00000001 +19.87,50.425,-2.593037162,50.5267,0,9.999575919,-2.91125,-3.056913184,2.908678058,90.00000001 +19.88,50.425,-2.593035755,50.5557,0,10.00068631,-2.888125,-3.150317565,2.853735474,90.00000001 +19.89,50.425,-2.593034347,50.5845,0,10.00068636,-2.863125,-3.24306402,2.796304419,90.00000001 +19.9,50.425,-2.59303294,50.613,0,9.999576054,-2.8365625,-3.335133238,2.736434913,90.00000001 +19.91,50.425,-2.593031533,50.6412,0,9.99890989,-2.81,-3.426505912,2.67417921,90.00000001 +19.92,50.425,-2.593030126,50.6692,0,9.999576142,-2.783125,-3.517163018,2.609591568,90.00000001 +19.93,50.425,-2.593028719,50.6969,0,10.00068653,-2.754375,-3.60708565,2.542728368,90.00000001 +19.94,50.425,-2.593027311,50.7243,0,10.00090865,-2.723125,-3.696254957,2.47364782,90.00000001 +19.95,50.425,-2.593025904,50.7514,0,10.00068662,-2.69,-3.784652318,2.402410259,90.00000001 +19.96,50.425,-2.593024497,50.7781,0,10.00090873,-2.6565625,-3.872259341,2.329077734,90.00000001 +19.97,50.425,-2.593023089,50.8045,0,10.0006867,-2.6234375,-3.959057692,2.253714189,90.00000001 +19.98,50.425,-2.593021682,50.8306,0,9.999576394,-2.589375,-4.045029207,2.176385399,90.00000001 +19.99,50.425,-2.593020275,50.8563,0,9.998910225,-2.553125,-4.13015601,2.0971588,90.00000001 +20,50.425,-2.593018868,50.8817,0,9.999576475,-2.515,-4.214420283,2.016103435,90.00000001 +20.01,50.425,-2.593017461,50.9066,0,10.00068686,-2.4765625,-4.297804378,1.933289949,90.00000001 +20.02,50.425,-2.593016053,50.9312,0,10.0006869,-2.438125,-4.380290992,1.848790649,90.00000001 +20.03,50.425,-2.593014646,50.9554,0,9.99957659,-2.3978125,-4.461862821,1.76267916,90.00000001 +20.04,50.425,-2.593013239,50.9792,0,9.998688348,-2.355,-4.542502792,1.675030598,90.00000001 +20.05,50.425,-2.593011832,51.0025,0,9.998688384,-2.3115625,-4.622194174,1.585921394,90.00000001 +20.06,50.425,-2.593010425,51.0254,0,9.999576699,-2.2684375,-4.700920294,1.495429242,90.00000001 +20.07,50.425,-2.593009018,51.0479,0,10.00068708,-2.2246875,-4.778664651,1.403633038,90.00000001 +20.08,50.425,-2.59300761,51.0699,0,10.00068712,-2.1796875,-4.855411029,1.310612824,90.00000001 +20.09,50.425,-2.593006203,51.0915,0,9.999798872,-2.1334375,-4.931143445,1.216449789,90.00000001 +20.1,50.425,-2.593004796,51.1126,0,9.999798905,-2.08625,-5.005846026,1.121225922,90.00000001 +20.11,50.425,-2.593003389,51.1332,0,10.00068722,-2.038125,-5.079503246,1.025024418,90.00000001 +20.12,50.425,-2.593001981,51.1534,0,10.00090932,-1.988125,-5.152099634,0.927928984,90.00000001 +20.13,50.425,-2.593000574,51.173,0,10.00068728,-1.9365625,-5.223620122,0.83002442,90.00000001 +20.14,50.425,-2.592999167,51.1921,0,10.00090938,-1.8853125,-5.294049698,0.731396095,90.00000001 +20.15,50.425,-2.592997759,51.2107,0,10.00068734,-1.835,-5.363373638,0.632129954,90.00000001 +20.16,50.425,-2.592996352,51.2288,0,9.999577018,-1.784375,-5.43157756,0.53231257,90.00000001 +20.17,50.425,-2.592994945,51.2464,0,9.998688767,-1.7315625,-5.49864714,0.432031033,90.00000001 +20.18,50.425,-2.592993538,51.2635,0,9.998688793,-1.6765625,-5.564568398,0.331372776,90.00000001 +20.19,50.425,-2.592992131,51.2799,0,9.999577097,-1.6215625,-5.629327583,0.23042552,90.00000001 +20.2,50.425,-2.592990724,51.2959,0,10.00068747,-1.5665625,-5.692911173,0.129277327,90.00000001 +20.21,50.425,-2.592989316,51.3113,0,10.00068749,-1.5096875,-5.755305819,0.028016433,90.00000001 +20.22,50.425,-2.592987909,51.3261,0,9.999577169,-1.451875,-5.816498571,-0.073268926,90.00000001 +20.23,50.425,-2.592986502,51.3403,0,9.998910983,-1.395,-5.876476652,-0.1744904,90.00000001 +20.24,50.425,-2.592985095,51.354,0,9.999577213,-1.338125,-5.935227458,-0.275559697,90.00000001 +20.25,50.425,-2.592983688,51.3671,0,10.00068758,-1.2796875,-5.992738784,-0.376388695,90.00000001 +20.26,50.425,-2.59298228,51.3796,0,10.0006876,-1.22,-6.048998599,-0.476889446,90.00000001 +20.27,50.425,-2.592980873,51.3915,0,9.999799342,-1.16,-6.103995156,-0.576974401,90.00000001 +20.28,50.425,-2.592979466,51.4028,0,9.99979936,-1.1,-6.157716997,-0.676556185,90.00000001 +20.29,50.425,-2.592978059,51.4135,0,10.00068766,-1.04,-6.210152834,-0.775548051,90.00000001 +20.3,50.425,-2.592976651,51.4236,0,10.00068767,-0.98,-6.261291781,-0.873863598,90.00000001 +20.31,50.425,-2.592975244,51.4331,0,9.999799406,-0.9196875,-6.311123181,-0.971417111,90.00000001 +20.32,50.425,-2.592973837,51.442,0,9.99979942,-0.858125,-6.359636548,-1.068123563,90.00000001 +20.33,50.425,-2.59297243,51.4503,0,10.00068771,-0.795,-6.406821743,-1.163898558,90.00000001 +20.34,50.425,-2.592971022,51.4579,0,10.00068772,-0.7315625,-6.452669023,-1.258658616,90.00000001 +20.35,50.425,-2.592969615,51.4649,0,9.999577387,-0.6684375,-6.497168707,-1.352321172,90.00000001 +20.36,50.425,-2.592968208,51.4713,0,9.998911187,-0.605,-6.54031157,-1.44480441,90.00000001 +20.37,50.425,-2.592966801,51.477,0,9.999577405,-0.5415625,-6.582088558,-1.536027771,90.00000001 +20.38,50.425,-2.592965394,51.4821,0,10.00068776,-0.4784375,-6.622490906,-1.625911728,90.00000001 +20.39,50.425,-2.592963986,51.4866,0,10.00068777,-0.415,-6.661510306,-1.714377844,90.00000001 +20.4,50.425,-2.592962579,51.4904,0,9.999577427,-0.3515625,-6.699138507,-1.801348998,90.00000001 +20.41,50.425,-2.592961172,51.4936,0,9.998689153,-0.288125,-6.735367717,-1.886749332,90.00000001 +20.42,50.425,-2.592959765,51.4962,0,9.998689156,-0.223125,-6.770190259,-1.970504417,90.00000001 +20.43,50.425,-2.592958358,51.4981,0,9.999577438,-0.156875,-6.803598969,-2.052541144,90.00000001 +20.44,50.425,-2.592956951,51.4993,0,10.00068779,-0.091875,-6.835586859,-2.132788066,90.00000001 +20.45,50.425,-2.592955543,51.4999,0,10.00090986,-0.0284375,-6.866147225,-2.211175167,90.00000001 +20.46,50.425,-2.592954136,51.4999,0,10.00068779,0.0353125,-6.895273649,-2.287634093,90.00000001 +20.47,50.425,-2.592952729,51.4992,0,10.00090986,0.1,-6.922960058,-2.362098152,90.00000001 +20.48,50.425,-2.592951321,51.4979,0,10.00068779,0.1646875,-6.94920078,-2.434502484,90.00000001 +20.49,50.425,-2.592949914,51.4959,0,9.999577435,0.2284375,-6.9739902,-2.504783837,90.00000001 +20.5,50.425,-2.592948507,51.4933,0,9.998911222,0.2915625,-6.997323162,-2.572880959,90.00000001 +20.51,50.425,-2.5929471,51.4901,0,9.999577426,0.3553125,-7.019194852,-2.638734551,90.00000001 +20.52,50.425,-2.592945693,51.4862,0,10.00068777,0.42,-7.039600686,-2.702287087,90.00000001 +20.53,50.425,-2.592944285,51.4817,0,10.00068776,0.4846875,-7.058536426,-2.763483162,90.00000001 +20.54,50.425,-2.592942878,51.4765,0,9.999577405,0.5484375,-7.075998002,-2.822269491,90.00000001 +20.55,50.425,-2.592941471,51.4707,0,9.998911187,0.6115625,-7.091981863,-2.878594738,90.00000001 +20.56,50.425,-2.592940064,51.4643,0,9.999577386,0.675,-7.106484685,-2.932409856,90.00000001 +20.57,50.425,-2.592938657,51.4572,0,10.00068772,0.738125,-7.119503432,-2.983667806,90.00000001 +20.58,50.425,-2.592937249,51.4495,0,10.00068771,0.7996875,-7.131035297,-3.032323955,90.00000001 +20.59,50.425,-2.592935842,51.4412,0,9.99957735,0.8603125,-7.141077986,-3.078335904,90.00000001 +20.6,50.425,-2.592934435,51.4323,0,9.998911127,0.921875,-7.149629324,-3.121663488,90.00000001 +20.61,50.425,-2.592933028,51.4228,0,9.999577321,0.9846875,-7.156687534,-3.162268949,90.00000001 +20.62,50.425,-2.592931621,51.4126,0,10.00068765,1.0465625,-7.162251183,-3.200116822,90.00000001 +20.63,50.425,-2.592930213,51.4018,0,10.00090971,1.1065625,-7.166319126,-3.235174162,90.00000001 +20.64,50.425,-2.592928806,51.3905,0,10.00068762,1.1665625,-7.168890446,-3.267410372,90.00000001 +20.65,50.425,-2.592927399,51.3785,0,10.00090967,1.2265625,-7.169964627,-3.296797377,90.00000001 +20.66,50.425,-2.592925991,51.3659,0,10.00068758,1.2846875,-7.169541441,-3.323309567,90.00000001 +20.67,50.425,-2.592924584,51.3528,0,9.999577212,1.341875,-7.167621001,-3.346923678,90.00000001 +20.68,50.425,-2.592923177,51.3391,0,9.998910981,1.4,-7.164203709,-3.367619315,90.00000001 +20.69,50.425,-2.59292177,51.3248,0,9.999577167,1.458125,-7.159290252,-3.385378314,90.00000001 +20.7,50.425,-2.592920363,51.3099,0,10.00068749,1.515,-7.152881662,-3.400185147,90.00000001 +20.71,50.425,-2.592918955,51.2945,0,10.00068747,1.5715625,-7.144979313,-3.412027039,90.00000001 +20.72,50.425,-2.592917548,51.2785,0,9.999577095,1.628125,-7.135584811,-3.420893561,90.00000001 +20.73,50.425,-2.592916141,51.2619,0,9.99868879,1.6828125,-7.124700102,-3.426777035,90.00000001 +20.74,50.425,-2.592914734,51.2448,0,9.998688763,1.735,-7.112327537,-3.429672306,90.00000001 +20.75,50.425,-2.592913327,51.2272,0,9.999577014,1.786875,-7.098469636,-3.429576851,90.00000001 +20.76,50.425,-2.59291192,51.2091,0,10.00068734,1.8396875,-7.083129321,-3.426490728,90.00000001 +20.77,50.425,-2.592910512,51.1904,0,10.00068731,1.8915625,-7.066309744,-3.420416688,90.00000001 +20.78,50.425,-2.592909105,51.1712,0,9.999576928,1.9415625,-7.048014514,-3.411360002,90.00000001 +20.79,50.425,-2.592907698,51.1516,0,9.998910687,1.9915625,-7.028247356,-3.399328518,90.00000001 +20.8,50.425,-2.592906291,51.1314,0,9.999576864,2.0415625,-7.007012451,-3.38433278,90.00000001 +20.81,50.425,-2.592904884,51.1107,0,10.00090925,2.0896875,-6.984314212,-3.366385851,90.00000001 +20.82,50.425,-2.592903476,51.0896,0,10.0017975,2.1365625,-6.960157395,-3.345503431,90.00000001 +20.83,50.425,-2.592902069,51.068,0,10.00179746,2.1834375,-6.934547041,-3.321703623,90.00000001 +20.84,50.425,-2.592900661,51.0459,0,10.00090915,2.2296875,-6.907488536,-3.295007285,90.00000001 +20.85,50.425,-2.592899254,51.0234,0,9.999576696,2.2746875,-6.878987438,-3.265437621,90.00000001 +20.86,50.425,-2.592897847,51.0004,0,9.998688381,2.318125,-6.849049763,-3.233020471,90.00000001 +20.87,50.425,-2.59289644,50.977,0,9.998688345,2.3596875,-6.817681756,-3.197784025,90.00000001 +20.88,50.425,-2.592895033,50.9532,0,9.999576587,2.4,-6.784889949,-3.159759108,90.00000001 +20.89,50.425,-2.592893626,50.929,0,10.0006869,2.44,-6.750681218,-3.118978837,90.00000001 +20.9,50.425,-2.592892218,50.9044,0,10.00068686,2.4796875,-6.715062666,-3.075478735,90.00000001 +20.91,50.425,-2.592890811,50.8794,0,9.99957647,2.5184375,-6.6780418,-3.02929679,90.00000001 +20.92,50.425,-2.592889404,50.854,0,9.998910222,2.55625,-6.639626298,-2.98047328,90.00000001 +20.93,50.425,-2.592887997,50.8283,0,9.999576391,2.593125,-6.59982418,-2.929050719,90.00000001 +20.94,50.425,-2.59288659,50.8021,0,10.0006867,2.628125,-6.558643813,-2.875074026,90.00000001 +20.95,50.425,-2.592885182,50.7757,0,10.00068666,2.66125,-6.516093732,-2.818590185,90.00000001 +20.96,50.425,-2.592883775,50.7489,0,9.999576266,2.6934375,-6.47218282,-2.75964847,90.00000001 +20.97,50.425,-2.592882368,50.7218,0,9.998687945,2.7246875,-6.4269203,-2.698300332,90.00000001 +20.98,50.425,-2.592880961,50.6944,0,9.998687903,2.755,-6.380315627,-2.634599285,90.00000001 +20.99,50.425,-2.592879554,50.6667,0,9.999576139,2.7846875,-6.332378482,-2.568600735,90.00000001 +21,50.425,-2.592878147,50.6387,0,10.00090851,2.813125,-6.283118894,-2.500362379,90.00000001 +21.01,50.425,-2.592876739,50.6104,0,10.00179675,2.84,-6.232547176,-2.429943688,90.00000001 +21.02,50.425,-2.592875332,50.5819,0,10.0017967,2.86625,-6.180673869,-2.357406028,90.00000001 +21.03,50.425,-2.592873924,50.5531,0,10.00090838,2.8915625,-6.127509802,-2.282812653,90.00000001 +21.04,50.425,-2.592872517,50.524,0,9.999575916,2.914375,-6.073066035,-2.20622865,90.00000001 +21.05,50.425,-2.59287111,50.4948,0,9.998909661,2.935,-6.017354025,-2.12772077,90.00000001 +21.06,50.425,-2.592869703,50.4653,0,9.999575823,2.955,-5.960385405,-2.04735748,90.00000001 +21.07,50.425,-2.592868296,50.4357,0,10.00068612,2.9746875,-5.902171976,-1.965208912,90.00000001 +21.08,50.425,-2.592866888,50.4058,0,10.00068608,2.9934375,-5.842726,-1.881346626,90.00000001 +21.09,50.425,-2.592865481,50.3758,0,9.999575683,3.0109375,-5.782059797,-1.795843791,90.00000001 +21.1,50.425,-2.592864074,50.3456,0,9.998687357,3.0265625,-5.720186142,-1.70877489,90.00000001 +21.11,50.425,-2.592862667,50.3152,0,9.998687309,3.0396875,-5.65711787,-1.620215955,90.00000001 +21.12,50.425,-2.59286126,50.2848,0,9.99957554,3.0515625,-5.592868159,-1.53024422,90.00000001 +21.13,50.425,-2.592859853,50.2542,0,10.00068584,3.0634375,-5.527450473,-1.43893801,90.00000001 +21.14,50.425,-2.592858445,50.2235,0,10.00068579,3.0746875,-5.46087845,-1.346377079,90.00000001 +21.15,50.425,-2.592857038,50.1927,0,9.999575397,3.0846875,-5.393166011,-1.252642043,90.00000001 +21.16,50.425,-2.592855631,50.1618,0,9.99890914,3.0928125,-5.324327252,-1.15781472,90.00000001 +21.17,50.425,-2.592854224,50.1308,0,9.9995753,3.098125,-5.254376554,-1.061977732,90.00000001 +21.18,50.425,-2.592852817,50.0998,0,10.0006856,3.1015625,-5.183328584,-0.965214728,90.00000001 +21.19,50.425,-2.592851409,50.0688,0,10.00090762,3.105,-5.111198125,-0.867609993,90.00000001 +21.2,50.425,-2.592850002,50.0377,0,10.0006855,3.108125,-5.038000303,-0.769248724,90.00000001 +21.21,50.425,-2.592848595,50.0066,0,10.00090752,3.1096875,-4.963750301,-0.670216636,90.00000001 +21.22,50.425,-2.592847187,49.9755,0,10.00068541,3.1096875,-4.888463704,-0.570600131,90.00000001 +21.23,50.425,-2.59284578,49.9444,0,9.999575008,3.108125,-4.812156211,-0.470486012,90.00000001 +21.24,50.425,-2.592844373,49.9133,0,9.998908751,3.1046875,-4.73484375,-0.369961656,90.00000001 +21.25,50.425,-2.592842966,49.8823,0,9.999574911,3.0996875,-4.656542478,-0.269114724,90.00000001 +21.26,50.425,-2.592841559,49.8513,0,10.00068521,3.0934375,-4.577268782,-0.168033051,90.00000001 +21.27,50.425,-2.592840151,49.8204,0,10.00068516,3.08625,-4.497039164,-0.066804874,90.00000001 +21.28,50.425,-2.592838744,49.7896,0,9.999574766,3.078125,-4.41587041,0.034481517,90.00000001 +21.29,50.425,-2.592837337,49.7588,0,9.998908509,3.068125,-4.333779424,0.135737884,90.00000001 +21.3,50.425,-2.59283593,49.7282,0,9.99957467,3.0565625,-4.250783393,0.236875879,90.00000001 +21.31,50.425,-2.592834523,49.6977,0,10.00068497,3.045,-4.166899679,0.337807322,90.00000001 +21.32,50.425,-2.592833115,49.6673,0,10.00068492,3.0328125,-4.082145699,0.438444207,90.00000001 +21.33,50.425,-2.592831708,49.637,0,9.999574528,3.018125,-3.996539273,0.538698701,90.00000001 +21.34,50.425,-2.592830301,49.6069,0,9.998686202,3.00125,-3.910098162,0.638483483,90.00000001 +21.35,50.425,-2.592828894,49.577,0,9.998686155,2.9834375,-3.822840528,0.737711465,90.00000001 +21.36,50.425,-2.592827487,49.5472,0,9.999574387,2.9646875,-3.734784536,0.836296188,90.00000001 +21.37,50.425,-2.59282608,49.5177,0,10.00090676,2.9446875,-3.645948575,0.93415165,90.00000001 +21.38,50.425,-2.592824672,49.4883,0,10.00179499,2.923125,-3.556351154,1.031192537,90.00000001 +21.39,50.425,-2.592823265,49.4592,0,10.00179495,2.8996875,-3.466011123,1.127334168,90.00000001 +21.4,50.425,-2.592821857,49.4303,0,10.00090662,2.875,-3.374947216,1.222492717,90.00000001 +21.41,50.425,-2.59282045,49.4017,0,9.99957416,2.85,-3.283178457,1.316585279,90.00000001 +21.42,50.425,-2.592819043,49.3733,0,9.998685837,2.8246875,-3.190724096,1.409529805,90.00000001 +21.43,50.425,-2.592817636,49.3452,0,9.998685793,2.798125,-3.097603386,1.501245107,90.00000001 +21.44,50.425,-2.592816229,49.3173,0,9.999574027,2.7696875,-3.003835806,1.591651373,90.00000001 +21.45,50.425,-2.592814822,49.2898,0,10.00068433,2.7396875,-2.909440837,1.680669648,90.00000001 +21.46,50.425,-2.592813414,49.2625,0,10.00068429,2.708125,-2.814438361,1.768222355,90.00000001 +21.47,50.425,-2.592812007,49.2356,0,9.9995739,2.6746875,-2.718848088,1.854233175,90.00000001 +21.48,50.425,-2.5928106,49.209,0,9.99890765,2.6403125,-2.622690014,1.938627051,90.00000001 +21.49,50.425,-2.592809193,49.1828,0,9.999573817,2.60625,-2.525984192,2.021330472,90.00000001 +21.5,50.425,-2.592807786,49.1569,0,10.00068412,2.5715625,-2.428750905,2.102271188,90.00000001 +21.51,50.425,-2.592806378,49.1313,0,10.00068408,2.5346875,-2.331010378,2.181378726,90.00000001 +21.52,50.425,-2.592804971,49.1062,0,9.999573697,2.4965625,-2.232783067,2.258584044,90.00000001 +21.53,50.425,-2.592803564,49.0814,0,9.99890745,2.4584375,-2.134089425,2.333819877,90.00000001 +21.54,50.425,-2.592802157,49.057,0,9.99957362,2.419375,-2.034950137,2.407020564,90.00000001 +21.55,50.425,-2.59280075,49.033,0,10.00068393,2.378125,-1.935385886,2.478122334,90.00000001 +21.56,50.425,-2.592799342,49.0094,0,10.00090596,2.335,-1.835417413,2.54706308,90.00000001 +21.57,50.425,-2.592797935,48.9863,0,10.00068386,2.2915625,-1.735065688,2.613782812,90.00000001 +21.58,50.425,-2.592796528,48.9636,0,10.00090589,2.248125,-1.634351568,2.678223261,90.00000001 +21.59,50.425,-2.59279512,48.9413,0,10.00068379,2.203125,-1.533296194,2.740328219,90.00000001 +21.6,50.425,-2.592793713,48.9195,0,9.999573405,2.1565625,-1.431920537,2.800043656,90.00000001 +21.61,50.425,-2.592792306,48.8982,0,9.998907162,2.1096875,-1.330245911,2.85731732,90.00000001 +21.62,50.425,-2.592790899,48.8773,0,9.999573339,2.0615625,-1.228293457,2.912099419,90.00000001 +21.63,50.425,-2.592789492,48.8569,0,10.00068366,2.0115625,-1.12608449,2.964342111,90.00000001 +21.64,50.425,-2.592788084,48.8371,0,10.00068363,1.961875,-1.023640323,3.013999848,90.00000001 +21.65,50.425,-2.592786677,48.8177,0,9.999573246,1.913125,-0.920982387,3.061029312,90.00000001 +21.66,50.425,-2.59278527,48.7988,0,9.998684937,1.8628125,-0.818132165,3.105389538,90.00000001 +21.67,50.425,-2.592783863,48.7804,0,9.998684909,1.81,-0.715111031,3.147041851,90.00000001 +21.68,50.425,-2.592782456,48.7626,0,9.99957316,1.7565625,-0.611940583,3.185949868,90.00000001 +21.69,50.425,-2.592781049,48.7453,0,10.00068348,1.7034375,-0.508642366,3.22207967,90.00000001 +21.7,50.425,-2.592779641,48.7285,0,10.00068346,1.6496875,-0.405237865,3.255399801,90.00000001 +21.71,50.425,-2.592778234,48.7123,0,9.999573081,1.595,-0.301748796,3.285881156,90.00000001 +21.72,50.425,-2.592776827,48.6966,0,9.998906847,1.5396875,-0.198196701,3.313497149,90.00000001 +21.73,50.425,-2.59277542,48.6815,0,9.999573033,1.483125,-0.094603181,3.338223773,90.00000001 +21.74,50.425,-2.592774013,48.6669,0,10.00090543,1.425,0.009010105,3.36003937,90.00000001 +21.75,50.425,-2.592772605,48.653,0,10.00179368,1.366875,0.112621444,3.378924975,90.00000001 +21.76,50.425,-2.592771198,48.6396,0,10.00179366,1.31,0.216209348,3.394864146,90.00000001 +21.77,50.425,-2.59276979,48.6268,0,10.00090536,1.2528125,0.319752046,3.4078429,90.00000001 +21.78,50.425,-2.592768383,48.6145,0,9.999572928,1.193125,0.423227938,3.417850009,90.00000001 +21.79,50.425,-2.592766976,48.6029,0,9.998684632,1.1315625,0.526615536,3.424876649,90.00000001 +21.8,50.425,-2.592765569,48.5919,0,9.998684615,1.0703125,0.62989307,3.428916746,90.00000001 +21.81,50.425,-2.592764162,48.5815,0,9.999572877,1.01,0.733039109,3.429966806,90.00000001 +21.82,50.425,-2.592762755,48.5717,0,10.00068321,0.9496875,0.836032054,3.428025912,90.00000001 +21.83,50.425,-2.592761347,48.5625,0,10.00068319,0.8884375,0.938850362,3.423095667,90.00000001 +21.84,50.425,-2.59275994,48.5539,0,9.999572833,0.8265625,1.041472661,3.415180484,90.00000001 +21.85,50.425,-2.592758533,48.546,0,9.998906613,0.7646875,1.143877465,3.404287181,90.00000001 +21.86,50.425,-2.592757126,48.5386,0,9.99957281,0.701875,1.246043345,3.39042527,90.00000001 +21.87,50.425,-2.592755719,48.5319,0,10.00068315,0.638125,1.347948989,3.373606896,90.00000001 +21.88,50.425,-2.592754311,48.5259,0,10.00068314,0.575,1.449573195,3.35384667,90.00000001 +21.89,50.425,-2.592752904,48.5204,0,9.999572781,0.5115625,1.55089465,3.331161839,90.00000001 +21.9,50.425,-2.592751497,48.5156,0,9.998906565,0.4465625,1.651892213,3.305572226,90.00000001 +21.91,50.425,-2.59275009,48.5115,0,9.999572768,0.3821875,1.752544797,3.277100062,90.00000001 +21.92,50.425,-2.592748683,48.508,0,10.00068311,0.3196875,1.852831376,3.245770214,90.00000001 +21.93,50.425,-2.592747275,48.5051,0,10.00090517,0.2565625,1.952731037,3.211610012,90.00000001 +21.94,50.425,-2.592745868,48.5028,0,10.0006831,0.1915625,2.052222866,3.17464925,90.00000001 +21.95,50.425,-2.592744461,48.5013,0,10.00090517,0.126875,2.151286123,3.134920127,90.00000001 +21.96,50.425,-2.592743053,48.5003,0,10.0006831,0.0634375,2.249900124,3.092457365,90.00000001 +21.97,50.425,-2.592741646,48.5,0,9.999572749,-0.000625,2.348044242,3.047297863,90.00000001 +21.98,50.425,-2.592740239,48.5003,0,9.99890654,-0.06625,2.445698022,2.999481097,90.00000001 +21.99,50.425,-2.592738832,48.5013,0,9.999572751,-0.131875,2.542841068,2.949048779,90.00000001 +22,50.425,-2.592737425,48.503,0,10.0006831,-0.19625,2.63945304,2.896044797,90.00000001 +22.01,50.425,-2.592736017,48.5052,0,10.00068311,-0.26,2.735513826,2.840515447,90.00000001 +22.02,50.425,-2.59273461,48.5082,0,9.999572763,-0.3234375,2.831003316,2.782509085,90.00000001 +22.03,50.425,-2.592733203,48.5117,0,9.998684489,-0.3865625,2.925901571,2.722076362,90.00000001 +22.04,50.425,-2.592731796,48.5159,0,9.998684495,-0.4503125,3.020188823,2.659269931,90.00000001 +22.05,50.425,-2.592730389,48.5207,0,9.999572781,-0.515,3.113845307,2.594144626,90.00000001 +22.06,50.425,-2.592728982,48.5262,0,10.00068314,-0.5796875,3.20685154,2.526757112,90.00000001 +22.07,50.425,-2.592727574,48.5323,0,10.00068315,-0.643125,3.299188043,2.457166288,90.00000001 +22.08,50.425,-2.592726167,48.5391,0,9.99979488,-0.705,3.390835565,2.385432774,90.00000001 +22.09,50.425,-2.59272476,48.5464,0,9.999794891,-0.766875,3.481774968,2.31161908,90.00000001 +22.1,50.425,-2.592723353,48.5544,0,10.00068318,-0.83,3.57198723,2.235789663,90.00000001 +22.11,50.425,-2.592721945,48.563,0,10.0006832,-0.8928125,3.661453501,2.158010585,90.00000001 +22.12,50.425,-2.592720538,48.5723,0,9.999794932,-0.9534375,3.75015516,2.078349742,90.00000001 +22.13,50.425,-2.592719131,48.5821,0,9.999794947,-1.0134375,3.838073643,1.996876461,90.00000001 +22.14,50.425,-2.592717724,48.5925,0,10.00068324,-1.075,3.925190558,1.913661962,90.00000001 +22.15,50.425,-2.592716316,48.6036,0,10.00068326,-1.1365625,4.011487799,1.828778665,90.00000001 +22.16,50.425,-2.592714909,48.6153,0,9.999572929,-1.19625,4.096947262,1.742300656,90.00000001 +22.17,50.425,-2.592713502,48.6275,0,9.99890674,-1.255,4.181551127,1.654303334,90.00000001 +22.18,50.425,-2.592712095,48.6404,0,9.999572969,-1.3134375,4.265281746,1.564863419,90.00000001 +22.19,50.425,-2.592710688,48.6538,0,10.00068334,-1.37125,4.348121589,1.474058947,90.00000001 +22.2,50.425,-2.59270928,48.6678,0,10.00068336,-1.4284375,4.430053407,1.381969103,90.00000001 +22.21,50.425,-2.592707873,48.6824,0,9.999573034,-1.485,4.511060071,1.288674098,90.00000001 +22.22,50.425,-2.592706466,48.6975,0,9.998906849,-1.5415625,4.591124678,1.194255352,90.00000001 +22.23,50.425,-2.592705059,48.7132,0,9.999573083,-1.598125,4.67023044,1.098795255,90.00000001 +22.24,50.425,-2.592703652,48.7295,0,10.00068346,-1.653125,4.748360913,1.002376943,90.00000001 +22.25,50.425,-2.592702244,48.7463,0,10.00068348,-1.7065625,4.82549971,0.905084584,90.00000001 +22.26,50.425,-2.592700837,48.7636,0,9.999795231,-1.76,4.90163079,0.807002918,90.00000001 +22.27,50.425,-2.59269943,48.7815,0,9.999795259,-1.813125,4.976738223,0.708217603,90.00000001 +22.28,50.425,-2.592698023,48.7999,0,10.00068357,-1.865,5.050806368,0.60881464,90.00000001 +22.29,50.425,-2.592696615,48.8188,0,10.0006836,-1.9165625,5.123819698,0.508880831,90.00000001 +22.3,50.425,-2.592695208,48.8382,0,9.999795348,-1.968125,5.195762971,0.408503266,90.00000001 +22.31,50.425,-2.592693801,48.8582,0,9.999795379,-2.0178125,5.26662112,0.307769494,90.00000001 +22.32,50.425,-2.592692394,48.8786,0,10.00068369,-2.065,5.336379476,0.20676729,90.00000001 +22.33,50.425,-2.592690986,48.8995,0,10.00068372,-2.111875,5.405023373,0.105584834,90.00000001 +22.34,50.425,-2.592689579,48.9208,0,9.999573408,-2.1596875,5.472538542,0.004310247,90.00000001 +22.35,50.425,-2.592688172,48.9427,0,9.998685163,-2.2065625,5.538910775,-0.096968065,90.00000001 +22.36,50.425,-2.592686765,48.965,0,9.998685198,-2.25125,5.604126321,-0.198161808,90.00000001 +22.37,50.425,-2.592685358,48.9877,0,9.999573512,-2.295,5.668171486,-0.299182747,90.00000001 +22.38,50.425,-2.592683951,49.0109,0,10.0006839,-2.338125,5.731032978,-0.399942818,90.00000001 +22.39,50.425,-2.592682543,49.0345,0,10.00068393,-2.3796875,5.79269756,-0.50035413,90.00000001 +22.4,50.425,-2.592681136,49.0585,0,9.999573623,-2.42,5.8531524,-0.600329078,90.00000001 +22.41,50.425,-2.592679729,49.0829,0,9.998907452,-2.4596875,5.912384949,-0.699780571,90.00000001 +22.42,50.425,-2.592678322,49.1077,0,9.999573699,-2.4984375,5.970382716,-0.798621864,90.00000001 +22.43,50.425,-2.592676915,49.1329,0,10.00068409,-2.53625,6.02713367,-0.896766727,90.00000001 +22.44,50.425,-2.592675507,49.1584,0,10.0009062,-2.573125,6.08262595,-0.994129559,90.00000001 +22.45,50.425,-2.5926741,49.1844,0,10.00068417,-2.6084375,6.136847926,-1.090625564,90.00000001 +22.46,50.425,-2.592672693,49.2106,0,10.00090628,-2.643125,6.189788309,-1.186170459,90.00000001 +22.47,50.425,-2.592671285,49.2372,0,10.00068425,-2.678125,6.241436043,-1.280681051,90.00000001 +22.48,50.425,-2.592669878,49.2642,0,9.999573944,-2.71125,6.291780355,-1.374074833,90.00000001 +22.49,50.425,-2.592668471,49.2915,0,9.998907779,-2.74125,6.340810645,-1.466270446,90.00000001 +22.5,50.425,-2.592667064,49.319,0,9.999574031,-2.77,6.388516773,-1.557187389,90.00000001 +22.51,50.425,-2.592665657,49.3469,0,10.00068442,-2.7984375,6.434888768,-1.646746479,90.00000001 +22.52,50.425,-2.592664249,49.375,0,10.00068447,-2.82625,6.479916891,-1.734869622,90.00000001 +22.53,50.425,-2.592662842,49.4034,0,9.999574162,-2.853125,6.523591745,-1.821479871,90.00000001 +22.54,50.425,-2.592661435,49.4321,0,9.998907998,-2.878125,6.565904219,-1.906501765,90.00000001 +22.55,50.425,-2.592660028,49.461,0,9.999574253,-2.90125,6.606845549,-1.989861166,90.00000001 +22.56,50.425,-2.592658621,49.4901,0,10.00068465,-2.9234375,6.646407081,-2.071485421,90.00000001 +22.57,50.425,-2.592657213,49.5195,0,10.00068469,-2.9446875,6.684580624,-2.151303255,90.00000001 +22.58,50.425,-2.592655806,49.549,0,9.999574389,-2.9646875,6.721358154,-2.229245167,90.00000001 +22.59,50.425,-2.592654399,49.5788,0,9.998686157,-2.9834375,6.756732053,-2.305243091,90.00000001 +22.6,50.425,-2.592652992,49.6087,0,9.998686204,-3.00125,6.790694871,-2.37923085,90.00000001 +22.61,50.425,-2.592651585,49.6388,0,9.999574531,-3.018125,6.823239504,-2.451143872,90.00000001 +22.62,50.425,-2.592650178,49.6691,0,10.000907,-3.033125,6.854359248,-2.520919474,90.00000001 +22.63,50.425,-2.59264877,49.6995,0,10.00179532,-3.04625,6.884047515,-2.588496752,90.00000001 +22.64,50.425,-2.592647363,49.73,0,10.00179537,-3.0584375,6.912298116,-2.653816863,90.00000001 +22.65,50.425,-2.592645955,49.7607,0,10.00090714,-3.0696875,6.939105207,-2.716822797,90.00000001 +22.66,50.425,-2.592644548,49.7914,0,9.999574769,-3.0796875,6.964463173,-2.777459608,90.00000001 +22.67,50.425,-2.592643141,49.8223,0,9.998908609,-3.088125,6.988366628,-2.835674469,90.00000001 +22.68,50.425,-2.592641734,49.8532,0,9.999574866,-3.0946875,7.010810703,-2.891416559,90.00000001 +22.69,50.425,-2.592640327,49.8842,0,10.00068526,-3.1,7.031790641,-2.944637233,90.00000001 +22.7,50.425,-2.592638919,49.9152,0,10.00068531,-3.1046875,7.051302146,-2.995290198,90.00000001 +22.71,50.425,-2.592637512,49.9463,0,9.999575011,-3.108125,7.069340977,-3.043331219,90.00000001 +22.72,50.425,-2.592636105,49.9774,0,9.998686781,-3.1096875,7.085903526,-3.088718414,90.00000001 +22.73,50.425,-2.592634698,50.0085,0,9.99868683,-3.1096875,7.100986296,-3.131412193,90.00000001 +22.74,50.425,-2.592633291,50.0396,0,9.999575157,-3.108125,7.114586079,-3.171375369,90.00000001 +22.75,50.425,-2.592631884,50.0707,0,10.00068555,-3.105,7.126700069,-3.208573049,90.00000001 +22.76,50.425,-2.592630476,50.1017,0,10.0006856,-3.10125,7.137325743,-3.242972748,90.00000001 +22.77,50.425,-2.592629069,50.1327,0,9.999575304,-3.0965625,7.146460867,-3.274544556,90.00000001 +22.78,50.425,-2.592627662,50.1637,0,9.998909143,-3.0896875,7.154103551,-3.303260914,90.00000001 +22.79,50.425,-2.592626255,50.1945,0,9.9995754,-3.0815625,7.160252191,-3.329096841,90.00000001 +22.8,50.425,-2.592624848,50.2253,0,10.00090787,-3.0734375,7.164905525,-3.352029649,90.00000001 +22.81,50.425,-2.59262344,50.256,0,10.00179619,-3.064375,7.168062522,-3.372039512,90.00000001 +22.82,50.425,-2.592622033,50.2866,0,10.00179624,-3.053125,7.16972261,-3.389108842,90.00000001 +22.83,50.425,-2.592620625,50.3171,0,10.00090801,-3.0396875,7.169885387,-3.403222855,90.00000001 +22.84,50.425,-2.592619218,50.3474,0,9.999575638,-3.025,7.168550797,-3.414369233,90.00000001 +22.85,50.425,-2.592617811,50.3776,0,9.998687407,-3.0096875,7.165719125,-3.422538179,90.00000001 +22.86,50.425,-2.592616404,50.4076,0,9.998687454,-2.993125,7.161391059,-3.427722645,90.00000001 +22.87,50.425,-2.592614997,50.4375,0,9.99957578,-2.9746875,7.155567344,-3.429918105,90.00000001 +22.88,50.425,-2.59261359,50.4671,0,10.00068617,-2.9546875,7.148249355,-3.429122553,90.00000001 +22.89,50.425,-2.592612182,50.4966,0,10.00068622,-2.9334375,7.139438467,-3.425336849,90.00000001 +22.9,50.425,-2.592610775,50.5258,0,9.999575918,-2.91125,7.129136686,-3.418564144,90.00000001 +22.91,50.425,-2.592609368,50.5548,0,9.998909754,-2.8884375,7.117346017,-3.408810397,90.00000001 +22.92,50.425,-2.592607961,50.5836,0,9.999576008,-2.8646875,7.104068981,-3.396084145,90.00000001 +22.93,50.425,-2.592606554,50.6121,0,10.0006864,-2.8396875,7.089308385,-3.380396446,90.00000001 +22.94,50.425,-2.592605146,50.6404,0,10.00068645,-2.813125,7.073067266,-3.361760993,90.00000001 +22.95,50.425,-2.592603739,50.6684,0,9.999576141,-2.784375,7.055349004,-3.340194003,90.00000001 +22.96,50.425,-2.592602332,50.6961,0,9.998687905,-2.7534375,7.036157382,-3.315714381,90.00000001 +22.97,50.425,-2.592600925,50.7235,0,9.998687948,-2.7215625,7.015496294,-3.288343327,90.00000001 +22.98,50.425,-2.592599518,50.7505,0,9.999576269,-2.69,6.993370097,-3.25810485,90.00000001 +22.99,50.425,-2.592598111,50.7773,0,10.00090873,-2.6584375,6.969783487,-3.225025246,90.00000001 +23,50.425,-2.592596703,50.8037,0,10.00179705,-2.6259375,6.944741278,-3.189133336,90.00000001 +23.01,50.425,-2.592595296,50.8298,0,10.00179709,-2.5915625,6.918248741,-3.150460518,90.00000001 +23.02,50.425,-2.592593888,50.8556,0,10.00090885,-2.5546875,6.890311433,-3.109040368,90.00000001 +23.03,50.425,-2.592592481,50.8809,0,9.999576473,-2.5165625,6.8609352,-3.064909153,90.00000001 +23.04,50.425,-2.592591074,50.9059,0,9.998910303,-2.4784375,6.830126113,-3.018105262,90.00000001 +23.05,50.425,-2.592589667,50.9305,0,9.999576551,-2.439375,6.797890648,-2.968669547,90.00000001 +23.06,50.425,-2.59258826,50.9547,0,10.00068694,-2.3984375,6.764235508,-2.916645151,90.00000001 +23.07,50.425,-2.592586852,50.9785,0,10.00068697,-2.35625,6.729167798,-2.862077338,90.00000001 +23.08,50.425,-2.592585445,51.0018,0,9.999576662,-2.3134375,6.692694737,-2.805013779,90.00000001 +23.09,50.425,-2.592584038,51.0248,0,9.99868842,-2.27,6.654824061,-2.745504205,90.00000001 +23.1,50.425,-2.592582631,51.0472,0,9.998688455,-2.22625,6.61556356,-2.683600469,90.00000001 +23.11,50.425,-2.592581224,51.0693,0,9.999576768,-2.1815625,6.574921487,-2.61935666,90.00000001 +23.12,50.425,-2.592579817,51.0909,0,10.00068715,-2.1346875,6.53290632,-2.552828697,90.00000001 +23.13,50.425,-2.592578409,51.112,0,10.00068718,-2.0865625,6.489526825,-2.484074621,90.00000001 +23.14,50.425,-2.592577002,51.1326,0,9.999576867,-2.0384375,6.444792114,-2.413154421,90.00000001 +23.15,50.425,-2.592575595,51.1528,0,9.998910689,-1.9896875,6.398711468,-2.340129861,90.00000001 +23.16,50.425,-2.592574188,51.1724,0,9.999576929,-1.9396875,6.351294569,-2.265064712,90.00000001 +23.17,50.425,-2.592572781,51.1916,0,10.00068731,-1.8884375,6.302551216,-2.188024406,90.00000001 +23.18,50.425,-2.592571373,51.2102,0,10.00090941,-1.83625,6.252491722,-2.109076093,90.00000001 +23.19,50.425,-2.592569966,51.2283,0,10.00068737,-1.78375,6.201126399,-2.028288643,90.00000001 +23.2,50.425,-2.592568559,51.2459,0,10.00090946,-1.73125,6.148466135,-1.945732472,90.00000001 +23.21,50.425,-2.592567151,51.2629,0,10.00068742,-1.678125,6.094521815,-1.861479659,90.00000001 +23.22,50.425,-2.592565744,51.2795,0,9.999577096,-1.623125,6.039304726,-1.775603541,90.00000001 +23.23,50.425,-2.592564337,51.2954,0,9.998910912,-1.5665625,5.982826385,-1.688179062,90.00000001 +23.24,50.425,-2.59256293,51.3108,0,9.999577146,-1.5103125,5.925098596,-1.59928254,90.00000001 +23.25,50.425,-2.592561523,51.3256,0,10.00068752,-1.4546875,5.866133446,-1.508991325,90.00000001 +23.26,50.425,-2.592560115,51.3399,0,10.00068754,-1.398125,5.805943256,-1.417384311,90.00000001 +23.27,50.425,-2.592558708,51.3536,0,9.999577213,-1.34,5.744540572,-1.324541314,90.00000001 +23.28,50.425,-2.592557301,51.3667,0,9.998688954,-1.2815625,5.681938172,-1.23054329,90.00000001 +23.29,50.425,-2.592555894,51.3792,0,9.998688973,-1.223125,5.618149177,-1.135472231,90.00000001 +23.3,50.425,-2.592554487,51.3912,0,9.999577271,-1.163125,5.553186935,-1.039410987,90.00000001 +23.31,50.425,-2.59255308,51.4025,0,10.00068764,-1.101875,5.48706497,-0.94244338,90.00000001 +23.32,50.425,-2.592551672,51.4132,0,10.00068765,-1.0415625,5.419797089,-0.844653923,90.00000001 +23.33,50.425,-2.592550265,51.4233,0,9.999577322,-0.9815625,5.351397388,-0.746127929,90.00000001 +23.34,50.425,-2.592548858,51.4329,0,9.998911127,-0.92,5.281880075,-0.646951341,90.00000001 +23.35,50.425,-2.592547451,51.4417,0,9.99957735,-0.858125,5.211259703,-0.547210562,90.00000001 +23.36,50.425,-2.592546044,51.45,0,10.00090978,-0.796875,5.139551056,-0.446992623,90.00000001 +23.37,50.425,-2.592544636,51.4577,0,10.00179807,-0.734375,5.066769087,-0.346384844,90.00000001 +23.38,50.425,-2.592543229,51.4647,0,10.00179808,-0.6703125,4.992928979,-0.245475058,90.00000001 +23.39,50.425,-2.592541821,51.4711,0,10.00090981,-0.606875,4.918046145,-0.144351216,90.00000001 +23.4,50.425,-2.592540414,51.4768,0,9.999577405,-0.5446875,4.842136228,-0.043101495,90.00000001 +23.41,50.425,-2.592539007,51.482,0,9.998689135,-0.4815625,4.765215097,0.058185812,90.00000001 +23.42,50.425,-2.5925376,51.4865,0,9.998689142,-0.4165625,4.687298852,0.159422355,90.00000001 +23.43,50.425,-2.592536193,51.4903,0,9.999577426,-0.351875,4.60840371,0.260519899,90.00000001 +23.44,50.425,-2.592534786,51.4935,0,10.00068778,-0.2884375,4.528546113,0.361390264,90.00000001 +23.45,50.425,-2.592533378,51.4961,0,10.00068778,-0.2246875,4.447742849,0.461945503,90.00000001 +23.46,50.425,-2.592531971,51.498,0,9.999577438,-0.16,4.366010706,0.562097896,90.00000001 +23.47,50.425,-2.592530564,51.4993,0,9.998911231,-0.0953125,4.283366815,0.66176018,90.00000001 +23.48,50.425,-2.592529157,51.4999,0,9.999577441,-0.0315625,4.199828308,0.760845324,90.00000001 +23.49,50.425,-2.59252775,51.4999,0,10.00068779,0.031875,4.115412775,0.859267097,90.00000001 +23.5,50.425,-2.592526342,51.4993,0,10.00068779,0.096875,4.030137805,0.956939499,90.00000001 +23.51,50.425,-2.592524935,51.498,0,9.999577438,0.163125,3.944021217,1.053777445,90.00000001 +23.52,50.425,-2.592523528,51.496,0,9.998689157,0.228125,3.857080887,1.149696481,90.00000001 +23.53,50.425,-2.592522121,51.4934,0,9.998689153,0.2915625,3.769335094,1.244613014,90.00000001 +23.54,50.425,-2.592520714,51.4902,0,9.999577427,0.355,3.680802171,1.338444192,90.00000001 +23.55,50.425,-2.592519307,51.4863,0,10.00090984,0.4184375,3.591500511,1.431108198,90.00000001 +23.56,50.425,-2.592517899,51.4818,0,10.00179811,0.4815625,3.501448791,1.522524301,90.00000001 +23.57,50.425,-2.592516492,51.4767,0,10.0017981,0.5453125,3.410665863,1.61261269,90.00000001 +23.58,50.425,-2.592515084,51.4709,0,10.00090981,0.6096875,3.319170691,1.701294926,90.00000001 +23.59,50.425,-2.592513677,51.4645,0,9.999577386,0.673125,3.226982298,1.788493544,90.00000001 +23.6,50.425,-2.59251227,51.4574,0,9.998911165,0.735,3.134120049,1.874132629,90.00000001 +23.61,50.425,-2.592510863,51.4498,0,9.999577363,0.796875,3.040603252,1.958137409,90.00000001 +23.62,50.425,-2.592509456,51.4415,0,10.0006877,0.86,2.946451447,2.040434661,90.00000001 +23.63,50.425,-2.592508048,51.4326,0,10.00068769,0.9228125,2.851684342,2.120952591,90.00000001 +23.64,50.425,-2.592506641,51.423,0,9.999577321,0.9834375,2.756321705,2.199621072,90.00000001 +23.65,50.425,-2.592505234,51.4129,0,9.998689026,1.043125,2.660383417,2.276371461,90.00000001 +23.66,50.425,-2.592503827,51.4022,0,9.998689009,1.10375,2.563889533,2.351136781,90.00000001 +23.67,50.425,-2.59250242,51.3908,0,9.99957727,1.1646875,2.466860219,2.423851886,90.00000001 +23.68,50.425,-2.592501013,51.3789,0,10.0006876,1.2246875,2.369315758,2.49445335,90.00000001 +23.69,50.425,-2.592499605,51.3663,0,10.00068758,1.2834375,2.271276492,2.562879637,90.00000001 +23.7,50.425,-2.592498198,51.3532,0,9.999577213,1.34125,2.172762873,2.629070987,90.00000001 +23.71,50.425,-2.592496791,51.3395,0,9.998910982,1.39875,2.073795529,2.692969819,90.00000001 +23.72,50.425,-2.592495384,51.3252,0,9.999577168,1.45625,1.974395087,2.754520326,90.00000001 +23.73,50.425,-2.592493977,51.3104,0,10.00090956,1.5134375,1.874582344,2.813668822,90.00000001 +23.74,50.425,-2.592492569,51.2949,0,10.00179782,1.5696875,1.774378042,2.870363798,90.00000001 +23.75,50.425,-2.592491162,51.279,0,10.00179779,1.6246875,1.673803265,2.92455575,90.00000001 +23.76,50.425,-2.592489754,51.2624,0,10.00090949,1.67875,1.572878926,2.976197468,90.00000001 +23.77,50.425,-2.592488347,51.2454,0,9.999577042,1.7328125,1.471626054,3.025243858,90.00000001 +23.78,50.425,-2.59248694,51.2278,0,9.998688737,1.786875,1.370065904,3.071652236,90.00000001 +23.79,50.425,-2.592485533,51.2096,0,9.998688709,1.839375,1.26821962,3.115382094,90.00000001 +23.8,50.425,-2.592484126,51.191,0,9.999576959,1.89,1.166108456,3.156395215,90.00000001 +23.81,50.425,-2.592482719,51.1718,0,10.00068728,1.9403125,1.063753786,3.194655962,90.00000001 +23.82,50.425,-2.592481311,51.1522,0,10.00068725,1.99125,0.96117698,3.23013093,90.00000001 +23.83,50.425,-2.592479904,51.132,0,9.999576865,2.0415625,0.858399467,3.262789181,90.00000001 +23.84,50.425,-2.592478497,51.1113,0,9.998910625,2.089375,0.755442618,3.292602237,90.00000001 +23.85,50.425,-2.59247709,51.0902,0,9.999576801,2.135,0.652328034,3.319544031,90.00000001 +23.86,50.425,-2.592475683,51.0686,0,10.00068712,2.1803125,0.549077258,3.343591184,90.00000001 +23.87,50.425,-2.592474275,51.0466,0,10.00068708,2.22625,0.445711776,3.36472267,90.00000001 +23.88,50.425,-2.592472868,51.0241,0,9.999576697,2.2715625,0.342253245,3.382920096,90.00000001 +23.89,50.425,-2.592471461,51.0011,0,9.998910452,2.3146875,0.238723209,3.398167534,90.00000001 +23.9,50.425,-2.592470054,50.9778,0,9.999576625,2.356875,0.135143326,3.410451692,90.00000001 +23.91,50.425,-2.592468647,50.954,0,10.00068694,2.3996875,0.031535196,3.419761912,90.00000001 +23.92,50.425,-2.592467239,50.9298,0,10.00090897,2.44125,-0.072079466,3.426090059,90.00000001 +23.93,50.425,-2.592465832,50.9051,0,10.00068686,2.48,-0.175679116,3.429430632,90.00000001 +23.94,50.425,-2.592464425,50.8802,0,10.00090889,2.518125,-0.279242097,3.429780652,90.00000001 +23.95,50.425,-2.592463017,50.8548,0,10.00068678,2.5565625,-0.382746693,3.427139832,90.00000001 +23.96,50.425,-2.59246161,50.829,0,9.999576392,2.5928125,-0.48617142,3.421510522,90.00000001 +23.97,50.425,-2.592460203,50.8029,0,9.998910142,2.6265625,-0.589494618,3.412897591,90.00000001 +23.98,50.425,-2.592458796,50.7765,0,9.99957631,2.66,-0.69269463,3.401308603,90.00000001 +23.99,50.425,-2.592457389,50.7497,0,10.00068662,2.693125,-0.795750085,3.386753584,90.00000001 +24,50.425,-2.592455981,50.7226,0,10.00068657,2.7246875,-0.898639267,3.369245255,90.00000001 +24.01,50.425,-2.592454574,50.6952,0,9.999576183,2.7546875,-1.001340863,3.348798912,90.00000001 +24.02,50.425,-2.592453167,50.6675,0,9.998687861,2.7834375,-1.103833273,3.325432375,90.00000001 +24.03,50.425,-2.59245176,50.6395,0,9.998687817,2.8115625,-1.206095181,3.299166042,90.00000001 +24.04,50.425,-2.592450353,50.6113,0,9.999576051,2.8396875,-1.308105217,3.270022715,90.00000001 +24.05,50.425,-2.592448946,50.5827,0,10.00068635,2.86625,-1.409842067,3.23802795,90.00000001 +24.06,50.425,-2.592447538,50.5539,0,10.00068631,2.8896875,-1.511284531,3.203209534,90.00000001 +24.07,50.425,-2.592446131,50.5249,0,9.999797986,2.9115625,-1.612411353,3.165597834,90.00000001 +24.08,50.425,-2.592444724,50.4957,0,9.99979794,2.9334375,-1.71320139,3.125225738,90.00000001 +24.09,50.425,-2.592443317,50.4662,0,10.00068617,2.9546875,-1.813633729,3.082128426,90.00000001 +24.1,50.425,-2.592441909,50.4366,0,10.00068613,2.9746875,-1.913687286,3.036343426,90.00000001 +24.11,50.425,-2.592440502,50.4067,0,9.999797801,2.993125,-2.013341148,2.987910673,90.00000001 +24.12,50.425,-2.592439095,50.3767,0,9.999797754,3.0096875,-2.112574631,2.936872395,90.00000001 +24.13,50.425,-2.592437688,50.3465,0,10.00068599,3.025,-2.211366879,2.883273167,90.00000001 +24.14,50.425,-2.59243628,50.3162,0,10.00068594,3.0396875,-2.309697322,2.827159686,90.00000001 +24.15,50.425,-2.592434873,50.2857,0,9.999575542,3.053125,-2.407545393,2.768580825,90.00000001 +24.16,50.425,-2.592433466,50.2551,0,9.998909285,3.0646875,-2.504890693,2.707587749,90.00000001 +24.17,50.425,-2.592432059,50.2244,0,9.999575447,3.0746875,-2.601712883,2.644233628,90.00000001 +24.18,50.425,-2.592430652,50.1936,0,10.00068575,3.083125,-2.697991737,2.578573696,90.00000001 +24.19,50.425,-2.592429244,50.1627,0,10.0006857,3.09,-2.793707144,2.510665191,90.00000001 +24.2,50.425,-2.592427837,50.1318,0,9.999575301,3.0965625,-2.888839166,2.440567357,90.00000001 +24.21,50.425,-2.59242643,50.1008,0,9.998909044,3.103125,-2.983367805,2.368341329,90.00000001 +24.22,50.425,-2.592425023,50.0697,0,9.999575204,3.1078125,-3.077273468,2.294050074,90.00000001 +24.23,50.425,-2.592423616,50.0386,0,10.0006855,3.1096875,-3.170536501,2.217758337,90.00000001 +24.24,50.425,-2.592422208,50.0075,0,10.00068546,3.1096875,-3.263137367,2.139532696,90.00000001 +24.25,50.425,-2.592420801,49.9764,0,9.999797128,3.108125,-3.355056757,2.05944139,90.00000001 +24.26,50.425,-2.592419394,49.9453,0,9.999797079,3.105,-3.446275534,1.977554147,90.00000001 +24.27,50.425,-2.592417987,49.9143,0,10.00068531,3.1015625,-3.536774562,1.89394253,90.00000001 +24.28,50.425,-2.592416579,49.8833,0,10.00068526,3.0984375,-3.626534989,1.808679306,90.00000001 +24.29,50.425,-2.592415172,49.8523,0,9.999796935,3.094375,-3.715538081,1.7218389,90.00000001 +24.3,50.425,-2.592413765,49.8214,0,9.999796886,3.088125,-3.803765216,1.633497059,90.00000001 +24.31,50.425,-2.592412358,49.7905,0,10.00068512,3.0796875,-3.891197946,1.54373073,90.00000001 +24.32,50.425,-2.59241095,49.7598,0,10.00068507,3.0696875,-3.977818106,1.452618294,90.00000001 +24.33,50.425,-2.592409543,49.7291,0,9.999574672,3.0584375,-4.063607535,1.360239105,90.00000001 +24.34,50.425,-2.592408136,49.6986,0,9.998686346,3.04625,-4.148548299,1.266673779,90.00000001 +24.35,50.425,-2.592406729,49.6682,0,9.998686298,3.033125,-4.232622694,1.172003906,90.00000001 +24.36,50.425,-2.592405322,49.6379,0,9.999574529,3.018125,-4.315813186,1.076312047,90.00000001 +24.37,50.425,-2.592403915,49.6078,0,10.00068483,3.00125,-4.398102416,0.979681626,90.00000001 +24.38,50.425,-2.592402507,49.5779,0,10.00068478,2.9834375,-4.47947308,0.882196868,90.00000001 +24.39,50.425,-2.5924011,49.5481,0,9.999574388,2.9646875,-4.559908333,0.783942857,90.00000001 +24.4,50.425,-2.592399693,49.5186,0,9.998908133,2.9446875,-4.639391273,0.68500525,90.00000001 +24.41,50.425,-2.592398286,49.4892,0,9.999574296,2.9234375,-4.717905284,0.585470277,90.00000001 +24.42,50.425,-2.592396879,49.4601,0,10.0006846,2.9009375,-4.795434094,0.485424741,90.00000001 +24.43,50.425,-2.592395471,49.4312,0,10.00090662,2.876875,-4.871961431,0.384955961,90.00000001 +24.44,50.425,-2.592394064,49.4025,0,10.00068451,2.85125,-4.94747131,0.284151486,90.00000001 +24.45,50.425,-2.592392657,49.3742,0,10.00090653,2.825,-5.021947973,0.183099206,90.00000001 +24.46,50.425,-2.592391249,49.346,0,10.00068442,2.798125,-5.095375838,0.081887243,90.00000001 +24.47,50.425,-2.592389842,49.3182,0,9.999574028,2.7696875,-5.167739605,-0.019396111,90.00000001 +24.48,50.425,-2.592388435,49.2906,0,9.998907777,2.74,-5.239024207,-0.120662505,90.00000001 +24.49,50.425,-2.592387028,49.2634,0,9.999573943,2.709375,-5.309214688,-0.221823762,90.00000001 +24.5,50.425,-2.592385621,49.2364,0,10.00068425,2.6765625,-5.378296381,-0.32279153,90.00000001 +24.51,50.425,-2.592384213,49.2098,0,10.00068421,2.6415625,-5.446254905,-0.423477805,90.00000001 +24.52,50.425,-2.592382806,49.1836,0,9.999573818,2.606875,-5.513076051,-0.523794865,90.00000001 +24.53,50.425,-2.592381399,49.1577,0,9.998907568,2.573125,-5.578745838,-0.623655106,90.00000001 +24.54,50.425,-2.592379992,49.1321,0,9.999573738,2.5378125,-5.643250572,-0.722971553,90.00000001 +24.55,50.425,-2.592378585,49.1069,0,10.00068405,2.4996875,-5.70657679,-0.821657517,90.00000001 +24.56,50.425,-2.592377177,49.0821,0,10.00068401,2.4596875,-5.768711312,-0.919626998,90.00000001 +24.57,50.425,-2.59237577,49.0577,0,9.999573621,2.4184375,-5.829641077,-1.016794566,90.00000001 +24.58,50.425,-2.592374363,49.0337,0,9.998685305,2.3765625,-5.889353363,-1.113075483,90.00000001 +24.59,50.425,-2.592372956,49.0102,0,9.998685268,2.335,-5.947835796,-1.208385752,90.00000001 +24.6,50.425,-2.592371549,48.987,0,9.999573511,2.293125,-6.005076055,-1.302642294,90.00000001 +24.61,50.425,-2.592370142,48.9643,0,10.00090589,2.2496875,-6.061062225,-1.395762947,90.00000001 +24.62,50.425,-2.592368734,48.942,0,10.00179414,2.2046875,-6.115782674,-1.487666409,90.00000001 +24.63,50.425,-2.592367327,48.9202,0,10.0017941,2.158125,-6.169225885,-1.578272636,90.00000001 +24.64,50.425,-2.592365919,48.8988,0,10.00090579,2.1103125,-6.221380687,-1.66750262,90.00000001 +24.65,50.425,-2.592364512,48.878,0,9.99957334,2.063125,-6.272236306,-1.755278493,90.00000001 +24.66,50.425,-2.592363105,48.8576,0,9.9989071,2.0165625,-6.321782029,-1.84152371,90.00000001 +24.67,50.425,-2.592361698,48.8376,0,9.999573277,1.9675,-6.370007486,-1.926163156,90.00000001 +24.68,50.425,-2.592360291,48.8182,0,10.00068359,1.915,-6.416902706,-2.009122918,90.00000001 +24.69,50.425,-2.592358883,48.7993,0,10.00068357,1.861875,-6.462457835,-2.09033069,90.00000001 +24.7,50.425,-2.592357476,48.781,0,9.999573189,1.81,-6.506663306,-2.169715654,90.00000001 +24.71,50.425,-2.592356069,48.7631,0,9.998684883,1.7584375,-6.549510006,-2.247208597,90.00000001 +24.72,50.425,-2.592354662,48.7458,0,9.998684856,1.7059375,-6.590988885,-2.322741967,90.00000001 +24.73,50.425,-2.592353255,48.729,0,9.999573107,1.651875,-6.631091347,-2.396249874,90.00000001 +24.74,50.425,-2.592351848,48.7127,0,10.00068343,1.59625,-6.66980897,-2.467668204,90.00000001 +24.75,50.425,-2.59235044,48.6971,0,10.00068341,1.54,-6.707133675,-2.536934676,90.00000001 +24.76,50.425,-2.592349033,48.6819,0,9.999573034,1.4834375,-6.743057728,-2.603988901,90.00000001 +24.77,50.425,-2.592347626,48.6674,0,9.998906802,1.4265625,-6.777573565,-2.668772436,90.00000001 +24.78,50.425,-2.592346219,48.6534,0,9.999572989,1.37,-6.810673967,-2.731228732,90.00000001 +24.79,50.425,-2.592344812,48.64,0,10.00068332,1.3128125,-6.842352058,-2.791303357,90.00000001 +24.8,50.425,-2.592343404,48.6271,0,10.00090537,1.2534375,-6.872601251,-2.848943942,90.00000001 +24.81,50.425,-2.592341997,48.6149,0,10.00068328,1.193125,-6.901415126,-2.904100183,90.00000001 +24.82,50.425,-2.59234059,48.6033,0,10.00090533,1.1334375,-6.928787784,-2.956724007,90.00000001 +24.83,50.425,-2.592339182,48.5922,0,10.00068324,1.073125,-6.954713379,-3.006769579,90.00000001 +24.84,50.425,-2.592337775,48.5818,0,9.999572877,1.0115625,-6.979186641,-3.054193124,90.00000001 +24.85,50.425,-2.592336368,48.572,0,9.998906653,0.9503125,-7.002202356,-3.098953446,90.00000001 +24.86,50.425,-2.592334961,48.5628,0,9.999572847,0.89,-7.023755768,-3.141011356,90.00000001 +24.87,50.425,-2.592333554,48.5542,0,10.00068318,0.8296875,-7.04384235,-3.180330298,90.00000001 +24.88,50.425,-2.592332146,48.5462,0,10.00068317,0.768125,-7.062457921,-3.216875953,90.00000001 +24.89,50.425,-2.592330739,48.5388,0,9.99957281,0.7046875,-7.079598583,-3.250616463,90.00000001 +24.9,50.425,-2.592329332,48.5321,0,9.99890659,0.64,-7.095260786,-3.281522322,90.00000001 +24.91,50.425,-2.592327925,48.526,0,9.999572789,0.5753125,-7.109441205,-3.309566716,90.00000001 +24.92,50.425,-2.592326518,48.5206,0,10.00068313,0.5115625,-7.122136918,-3.334725063,90.00000001 +24.93,50.425,-2.59232511,48.5158,0,10.00068312,0.4484375,-7.133345233,-3.356975478,90.00000001 +24.94,50.425,-2.592323703,48.5116,0,9.999572768,0.385,-7.143063858,-3.376298594,90.00000001 +24.95,50.425,-2.592322296,48.5081,0,9.998684483,0.3215625,-7.151290787,-3.39267751,90.00000001 +24.96,50.425,-2.592320889,48.5052,0,9.998684478,0.2584375,-7.158024244,-3.406097957,90.00000001 +24.97,50.425,-2.592319482,48.5029,0,9.999572753,0.1946875,-7.163262797,-3.416548249,90.00000001 +24.98,50.425,-2.592318075,48.5013,0,10.00090517,0.13,-7.167005415,-3.424019275,90.00000001 +24.99,50.425,-2.592316667,48.5003,0,10.00179345,0.065,-7.169251295,-3.428504503,90.00000001 +25,50.425,-2.59231526,48.5,0,10.00179345,-5.55E-17,-7.169999979,-3.42999998,90.00000001 +25.01,50.425,-2.592313852,48.5003,0,10.00090517,-0.065,-7.169251295,-3.428504503,90.00000001 +25.02,50.425,-2.592312445,48.5013,0,9.999572751,-0.13,-7.167005415,-3.424019275,90.00000001 +25.03,50.425,-2.592311038,48.5029,0,9.998684475,-0.1946875,-7.163262797,-3.416548249,90.00000001 +25.04,50.425,-2.592309631,48.5052,0,9.998684479,-0.2584375,-7.158024244,-3.406097957,90.00000001 +25.05,50.425,-2.592308224,48.5081,0,9.999572762,-0.3215625,-7.151290787,-3.39267751,90.00000001 +25.06,50.425,-2.592306817,48.5116,0,10.00068312,-0.385,-7.143063858,-3.376298594,90.00000001 +25.07,50.425,-2.592305409,48.5158,0,10.00068312,-0.4484375,-7.133345233,-3.356975478,90.00000001 +25.08,50.425,-2.592304002,48.5206,0,9.999572781,-0.5115625,-7.122136918,-3.334725063,90.00000001 +25.09,50.425,-2.592302595,48.526,0,9.998906581,-0.5753125,-7.109441205,-3.309566716,90.00000001 +25.1,50.425,-2.592301188,48.5321,0,9.999572799,-0.64,-7.095260786,-3.281522322,90.00000001 +25.11,50.425,-2.592299781,48.5388,0,10.00068316,-0.7046875,-7.079598583,-3.250616463,90.00000001 +25.12,50.425,-2.592298373,48.5462,0,10.00068317,-0.768125,-7.062457921,-3.216875953,90.00000001 +25.13,50.425,-2.592296966,48.5542,0,9.999572834,-0.8296875,-7.04384235,-3.180330298,90.00000001 +25.14,50.425,-2.592295559,48.5628,0,9.998906639,-0.89,-7.023755768,-3.141011356,90.00000001 +25.15,50.425,-2.592294152,48.572,0,9.999572862,-0.9503125,-7.002202356,-3.098953446,90.00000001 +25.16,50.425,-2.592292745,48.5818,0,10.00068323,-1.0115625,-6.979186641,-3.054193124,90.00000001 +25.17,50.425,-2.592291337,48.5922,0,10.00090531,-1.073125,-6.954713379,-3.006769579,90.00000001 +25.18,50.425,-2.59228993,48.6033,0,10.00068326,-1.1334375,-6.928787784,-2.956724007,90.00000001 +25.19,50.425,-2.592288523,48.6149,0,10.00090535,-1.193125,-6.901415126,-2.904100183,90.00000001 +25.2,50.425,-2.592287115,48.6271,0,10.0006833,-1.2534375,-6.872601251,-2.848943942,90.00000001 +25.21,50.425,-2.592285708,48.64,0,9.999572969,-1.3128125,-6.842352058,-2.791303357,90.00000001 +25.22,50.425,-2.592284301,48.6534,0,9.99890678,-1.37,-6.810673967,-2.731228732,90.00000001 +25.23,50.425,-2.592282894,48.6674,0,9.999573011,-1.4265625,-6.777573565,-2.668772436,90.00000001 +25.24,50.425,-2.592281487,48.6819,0,10.00068338,-1.4834375,-6.743057728,-2.603988901,90.00000001 +25.25,50.425,-2.592280079,48.6971,0,10.00068341,-1.54,-6.707133675,-2.536934676,90.00000001 +25.26,50.425,-2.592278672,48.7127,0,9.999573082,-1.59625,-6.66980897,-2.467668204,90.00000001 +25.27,50.425,-2.592277265,48.729,0,9.998684829,-1.651875,-6.631091347,-2.396249874,90.00000001 +25.28,50.425,-2.592275858,48.7458,0,9.998684854,-1.7059375,-6.590988885,-2.322741967,90.00000001 +25.29,50.425,-2.592274451,48.7631,0,9.99957316,-1.7584375,-6.549510006,-2.247208597,90.00000001 +25.3,50.425,-2.592273044,48.781,0,10.00068354,-1.81,-6.506663306,-2.169715654,90.00000001 +25.31,50.425,-2.592271636,48.7993,0,10.00068357,-1.861875,-6.462457835,-2.09033069,90.00000001 +25.32,50.425,-2.592270229,48.8182,0,9.999573247,-1.915,-6.416902706,-2.009122918,90.00000001 +25.33,50.425,-2.592268822,48.8376,0,9.998907068,-1.9675,-6.370007486,-1.926163156,90.00000001 +25.34,50.425,-2.592267415,48.8576,0,9.999573308,-2.0165625,-6.321782029,-1.84152371,90.00000001 +25.35,50.425,-2.592266008,48.878,0,10.00090576,-2.063125,-6.272236306,-1.755278493,90.00000001 +25.36,50.425,-2.5922646,48.8988,0,10.00179407,-2.1103125,-6.221380687,-1.66750262,90.00000001 +25.37,50.425,-2.592263193,48.9202,0,10.0017941,-2.158125,-6.169225885,-1.578272636,90.00000001 +25.38,50.425,-2.592261785,48.942,0,10.00090586,-2.2046875,-6.115782674,-1.487666409,90.00000001 +25.39,50.425,-2.592260378,48.9643,0,9.999573475,-2.2496875,-6.061062225,-1.395762947,90.00000001 +25.4,50.425,-2.592258971,48.987,0,9.998685232,-2.293125,-6.005076055,-1.302642294,90.00000001 +25.41,50.425,-2.592257564,49.0102,0,9.998685269,-2.335,-5.947835796,-1.208385752,90.00000001 +25.42,50.425,-2.592256157,49.0337,0,9.999573584,-2.3765625,-5.889353363,-1.113075483,90.00000001 +25.43,50.425,-2.59225475,49.0577,0,10.00068397,-2.4184375,-5.829641077,-1.016794566,90.00000001 +25.44,50.425,-2.592253342,49.0821,0,10.00068401,-2.4596875,-5.768711312,-0.919626998,90.00000001 +25.45,50.425,-2.592251935,49.1069,0,9.999573698,-2.4996875,-5.70657679,-0.821657517,90.00000001 +25.46,50.425,-2.592250528,49.1321,0,9.998907529,-2.5378125,-5.643250572,-0.722971553,90.00000001 +25.47,50.425,-2.592249121,49.1577,0,9.999573778,-2.573125,-5.578745838,-0.623655106,90.00000001 +25.48,50.425,-2.592247714,49.1836,0,10.00068417,-2.606875,-5.513076051,-0.523794865,90.00000001 +25.49,50.425,-2.592246306,49.2098,0,10.00068421,-2.6415625,-5.446254905,-0.423477805,90.00000001 +25.5,50.425,-2.592244899,49.2364,0,9.999573901,-2.6765625,-5.378296381,-0.32279153,90.00000001 +25.51,50.425,-2.592243492,49.2634,0,9.998907734,-2.709375,-5.309214688,-0.221823762,90.00000001 +25.52,50.425,-2.592242085,49.2906,0,9.999573987,-2.74,-5.239024207,-0.120662505,90.00000001 +25.53,50.425,-2.592240678,49.3182,0,10.00068438,-2.7696875,-5.167739605,-0.019396111,90.00000001 +25.54,50.425,-2.59223927,49.346,0,10.00090649,-2.798125,-5.095375838,0.081887243,90.00000001 +25.55,50.425,-2.592237863,49.3742,0,10.00068446,-2.825,-5.021947973,0.183099206,90.00000001 +25.56,50.425,-2.592236456,49.4025,0,10.00090658,-2.85125,-4.94747131,0.284151486,90.00000001 +25.57,50.425,-2.592235048,49.4312,0,10.00068455,-2.876875,-4.871961431,0.384955961,90.00000001 +25.58,50.425,-2.592233641,49.4601,0,9.999574251,-2.9009375,-4.795434094,0.485424741,90.00000001 +25.59,50.425,-2.592232234,49.4892,0,9.998908088,-2.9234375,-4.717905284,0.585470277,90.00000001 +25.6,50.425,-2.592230827,49.5186,0,9.999574343,-2.9446875,-4.639391273,0.68500525,90.00000001 +25.61,50.425,-2.59222942,49.5481,0,10.00068474,-2.9646875,-4.559908333,0.783942857,90.00000001 +25.62,50.425,-2.592228012,49.5779,0,10.00068478,-2.9834375,-4.47947308,0.882196868,90.00000001 +25.63,50.425,-2.592226605,49.6078,0,9.999574482,-3.00125,-4.398102416,0.979681626,90.00000001 +25.64,50.425,-2.592225198,49.6379,0,9.998686251,-3.018125,-4.315813186,1.076312047,90.00000001 +25.65,50.425,-2.592223791,49.6682,0,9.998686298,-3.033125,-4.232622694,1.172003906,90.00000001 +25.66,50.425,-2.592222384,49.6986,0,9.999574623,-3.04625,-4.148548299,1.266673779,90.00000001 +25.67,50.425,-2.592220977,49.7291,0,10.00068502,-3.0584375,-4.063607535,1.360239105,90.00000001 +25.68,50.425,-2.592219569,49.7598,0,10.00068507,-3.0696875,-3.977818106,1.452618294,90.00000001 +25.69,50.425,-2.592218162,49.7905,0,9.999796838,-3.0796875,-3.891197946,1.54373073,90.00000001 +25.7,50.425,-2.592216755,49.8214,0,9.999796886,-3.088125,-3.803765216,1.633497059,90.00000001 +25.71,50.425,-2.592215348,49.8523,0,10.00068521,-3.094375,-3.715538081,1.7218389,90.00000001 +25.72,50.425,-2.59221394,49.8833,0,10.00090733,-3.0984375,-3.626534989,1.808679306,90.00000001 +25.73,50.425,-2.592212533,49.9143,0,10.00068531,-3.1015625,-3.536774562,1.89394253,90.00000001 +25.74,50.425,-2.592211126,49.9453,0,10.00090743,-3.105,-3.446275534,1.977554147,90.00000001 +25.75,50.425,-2.592209718,49.9764,0,10.00068541,-3.108125,-3.355056757,2.05944139,90.00000001 +25.76,50.425,-2.592208311,50.0075,0,9.999575107,-3.1096875,-3.263137367,2.139532696,90.00000001 +25.77,50.425,-2.592206904,50.0386,0,9.998686877,-3.1096875,-3.170536501,2.217758337,90.00000001 +25.78,50.425,-2.592205497,50.0697,0,9.998686926,-3.1078125,-3.077273468,2.294050074,90.00000001 +25.79,50.425,-2.59220409,50.1008,0,9.999575253,-3.103125,-2.983367805,2.368341329,90.00000001 +25.8,50.425,-2.592202683,50.1318,0,10.00068565,-3.0965625,-2.888839166,2.440567357,90.00000001 +25.81,50.425,-2.592201275,50.1627,0,10.0006857,-3.09,-2.793707144,2.510665191,90.00000001 +25.82,50.425,-2.592199868,50.1936,0,9.999575398,-3.083125,-2.697991737,2.578573696,90.00000001 +25.83,50.425,-2.592198461,50.2244,0,9.998909237,-3.0746875,-2.601712883,2.644233628,90.00000001 +25.84,50.425,-2.592197054,50.2551,0,9.999575494,-3.0646875,-2.504890693,2.707587749,90.00000001 +25.85,50.425,-2.592195647,50.2857,0,10.00068589,-3.053125,-2.407545393,2.768580825,90.00000001 +25.86,50.425,-2.592194239,50.3162,0,10.00068594,-3.0396875,-2.309697322,2.827159686,90.00000001 +25.87,50.425,-2.592192832,50.3465,0,9.999575637,-3.025,-2.211366879,2.883273167,90.00000001 +25.88,50.425,-2.592191425,50.3767,0,9.998909475,-3.0096875,-2.112574631,2.936872395,90.00000001 +25.89,50.425,-2.592190018,50.4067,0,9.999575731,-2.993125,-2.013341148,2.987910673,90.00000001 +25.9,50.425,-2.592188611,50.4366,0,10.00068613,-2.9746875,-1.913687286,3.036343426,90.00000001 +25.91,50.425,-2.592187203,50.4662,0,10.00090824,-2.9546875,-1.813633729,3.082128426,90.00000001 +25.92,50.425,-2.592185796,50.4957,0,10.00068622,-2.9334375,-1.71320139,3.125225738,90.00000001 +25.93,50.425,-2.592184389,50.5249,0,10.00090833,-2.9115625,-1.612411353,3.165597834,90.00000001 +25.94,50.425,-2.592182981,50.5539,0,10.00068631,-2.8896875,-1.511284531,3.203209534,90.00000001 +25.95,50.425,-2.592181574,50.5827,0,9.999576007,-2.86625,-1.409842067,3.23802795,90.00000001 +25.96,50.425,-2.592180167,50.6113,0,9.998687773,-2.8396875,-1.308105217,3.270022715,90.00000001 +25.97,50.425,-2.59217876,50.6395,0,9.998687817,-2.8115625,-1.206095181,3.299166042,90.00000001 +25.98,50.425,-2.592177353,50.6675,0,9.999576139,-2.7834375,-1.103833273,3.325432375,90.00000001 +25.99,50.425,-2.592175946,50.6952,0,10.00068653,-2.7546875,-1.001340863,3.348798912,90.00000001 +26,50.425,-2.592174538,50.7226,0,10.00068657,-2.7246875,-0.898639267,3.369245255,90.00000001 +26.01,50.425,-2.592173131,50.7497,0,9.999576268,-2.693125,-0.795750085,3.386753584,90.00000001 +26.02,50.425,-2.592171724,50.7765,0,9.998910101,-2.66,-0.69269463,3.401308603,90.00000001 +26.03,50.425,-2.592170317,50.8029,0,9.999576352,-2.6265625,-0.589494618,3.412897591,90.00000001 +26.04,50.425,-2.59216891,50.829,0,10.00068674,-2.5928125,-0.48617142,3.421510522,90.00000001 +26.05,50.425,-2.592167502,50.8548,0,10.00068678,-2.5565625,-0.382746693,3.427139832,90.00000001 +26.06,50.425,-2.592166095,50.8802,0,9.999798542,-2.518125,-0.279242097,3.429780652,90.00000001 +26.07,50.425,-2.592164688,50.9051,0,9.999798581,-2.48,-0.175679116,3.429430632,90.00000001 +26.08,50.425,-2.592163281,50.9298,0,10.0006869,-2.44125,-0.072079466,3.426090059,90.00000001 +26.09,50.425,-2.592161873,50.954,0,10.00068694,-2.3996875,0.031535196,3.419761912,90.00000001 +26.1,50.425,-2.592160466,50.9778,0,9.999798694,-2.356875,0.135143326,3.410451692,90.00000001 +26.11,50.425,-2.592159059,51.0011,0,9.999798731,-2.3146875,0.238723209,3.398167534,90.00000001 +26.12,50.425,-2.592157652,51.0241,0,10.00068705,-2.2715625,0.342253245,3.382920096,90.00000001 +26.13,50.425,-2.592156244,51.0466,0,10.00068708,-2.22625,0.445711776,3.36472267,90.00000001 +26.14,50.425,-2.592154837,51.0686,0,9.999576766,-2.1803125,0.549077258,3.343591184,90.00000001 +26.15,50.425,-2.59215343,51.0902,0,9.998910591,-2.135,0.652328034,3.319544031,90.00000001 +26.16,50.425,-2.592152023,51.1113,0,9.999576833,-2.089375,0.755442618,3.292602237,90.00000001 +26.17,50.425,-2.592150616,51.132,0,10.00068721,-2.0415625,0.858399467,3.262789181,90.00000001 +26.18,50.425,-2.592149208,51.1522,0,10.00068725,-1.99125,0.96117698,3.23013093,90.00000001 +26.19,50.425,-2.592147801,51.1718,0,9.999576929,-1.9403125,1.063753786,3.194655962,90.00000001 +26.2,50.425,-2.592146394,51.191,0,9.998688679,-1.89,1.166108456,3.156395215,90.00000001 +26.21,50.425,-2.592144987,51.2096,0,9.998688708,-1.839375,1.26821962,3.115382094,90.00000001 +26.22,50.425,-2.59214358,51.2278,0,9.999577016,-1.786875,1.370065904,3.071652236,90.00000001 +26.23,50.425,-2.592142173,51.2454,0,10.00068739,-1.7328125,1.471626054,3.025243858,90.00000001 +26.24,50.425,-2.592140765,51.2624,0,10.00090949,-1.67875,1.572878926,2.976197468,90.00000001 +26.25,50.425,-2.592139358,51.279,0,10.00068744,-1.6246875,1.673803265,2.92455575,90.00000001 +26.26,50.425,-2.592137951,51.2949,0,10.00090954,-1.5696875,1.774378042,2.870363798,90.00000001 +26.27,50.425,-2.592136543,51.3104,0,10.00068749,-1.5134375,1.874582344,2.813668822,90.00000001 +26.28,50.425,-2.592135136,51.3252,0,9.999799238,-1.45625,1.974395087,2.754520326,90.00000001 +26.29,50.425,-2.592133729,51.3395,0,9.99979926,-1.39875,2.073795529,2.692969819,90.00000001 +26.3,50.425,-2.592132322,51.3532,0,10.00068756,-1.34125,2.172762873,2.629070987,90.00000001 +26.31,50.425,-2.592130914,51.3663,0,10.00068758,-1.2834375,2.271276492,2.562879637,90.00000001 +26.32,50.425,-2.592129507,51.3789,0,9.999577252,-1.2246875,2.369315758,2.49445335,90.00000001 +26.33,50.425,-2.5921281,51.3908,0,9.998688992,-1.1646875,2.466860219,2.423851886,90.00000001 +26.34,50.425,-2.592126693,51.4022,0,9.99868901,-1.10375,2.563889533,2.351136781,90.00000001 +26.35,50.425,-2.592125286,51.4129,0,9.999577305,-1.043125,2.660383417,2.276371461,90.00000001 +26.36,50.425,-2.592123879,51.423,0,10.00068767,-0.9834375,2.756321705,2.199621072,90.00000001 +26.37,50.425,-2.592122471,51.4326,0,10.00068768,-0.9228125,2.851684342,2.120952591,90.00000001 +26.38,50.425,-2.592121064,51.4415,0,9.99957735,-0.86,2.946451447,2.040434661,90.00000001 +26.39,50.425,-2.592119657,51.4498,0,9.998911154,-0.796875,3.040603252,1.958137409,90.00000001 +26.4,50.425,-2.59211825,51.4574,0,9.999577375,-0.735,3.134120049,1.874132629,90.00000001 +26.41,50.425,-2.592116843,51.4645,0,10.00068773,-0.673125,3.226982298,1.788493544,90.00000001 +26.42,50.425,-2.592115435,51.4709,0,10.00090981,-0.6096875,3.319170691,1.701294926,90.00000001 +26.43,50.425,-2.592114028,51.4767,0,10.00068775,-0.5453125,3.410665863,1.61261269,90.00000001 +26.44,50.425,-2.592112621,51.4818,0,10.00090983,-0.4815625,3.501448791,1.522524301,90.00000001 +26.45,50.425,-2.592111213,51.4863,0,10.00068777,-0.4184375,3.591500511,1.431108198,90.00000001 +26.46,50.425,-2.592109806,51.4902,0,9.999577426,-0.355,3.680802171,1.338444192,90.00000001 +26.47,50.425,-2.592108399,51.4934,0,9.998911221,-0.2915625,3.769335094,1.244613014,90.00000001 +26.48,50.425,-2.592106992,51.496,0,9.999577435,-0.228125,3.857080887,1.149696481,90.00000001 +26.49,50.425,-2.592105585,51.498,0,10.00068779,-0.163125,3.944021217,1.053777445,90.00000001 +26.5,50.425,-2.592104177,51.4993,0,10.00068779,-0.096875,4.030137805,0.956939499,90.00000001 +26.51,50.425,-2.59210277,51.4999,0,9.999577441,-0.031875,4.115412775,0.859267097,90.00000001 +26.52,50.425,-2.592101363,51.4999,0,9.998911232,0.0315625,4.199828308,0.760845324,90.00000001 +26.53,50.425,-2.592099956,51.4993,0,9.99957744,0.0953125,4.283366815,0.66176018,90.00000001 +26.54,50.425,-2.592098549,51.498,0,10.00068779,0.16,4.366010706,0.562097896,90.00000001 +26.55,50.425,-2.592097141,51.4961,0,10.00068778,0.2246875,4.447742849,0.461945503,90.00000001 +26.56,50.425,-2.592095734,51.4935,0,9.999577432,0.2884375,4.528546113,0.361390264,90.00000001 +26.57,50.425,-2.592094327,51.4903,0,9.998689148,0.351875,4.60840371,0.260519899,90.00000001 +26.58,50.425,-2.59209292,51.4865,0,9.998689141,0.4165625,4.687298852,0.159422355,90.00000001 +26.59,50.425,-2.592091513,51.482,0,9.999577413,0.4815625,4.765215097,0.058185812,90.00000001 +26.6,50.425,-2.592090106,51.4768,0,10.00090982,0.5446875,4.842136228,-0.043101495,90.00000001 +26.61,50.425,-2.592088698,51.4711,0,10.00179809,0.606875,4.918046145,-0.144351216,90.00000001 +26.62,50.425,-2.592087291,51.4647,0,10.00179808,0.6703125,4.992928979,-0.245475058,90.00000001 +26.63,50.425,-2.592085883,51.4577,0,10.00090979,0.734375,5.066769087,-0.346384844,90.00000001 +26.64,50.425,-2.592084476,51.45,0,9.999577363,0.796875,5.139551056,-0.446992623,90.00000001 +26.65,50.425,-2.592083069,51.4417,0,9.998911142,0.858125,5.211259703,-0.547210562,90.00000001 +26.66,50.425,-2.592081662,51.4329,0,9.999577337,0.92,5.281880075,-0.646951341,90.00000001 +26.67,50.425,-2.592080255,51.4233,0,10.00068767,0.9815625,5.351397388,-0.746127929,90.00000001 +26.68,50.425,-2.592078847,51.4132,0,10.00068765,1.0415625,5.419797089,-0.844653923,90.00000001 +26.69,50.425,-2.59207744,51.4025,0,9.999577289,1.101875,5.48706497,-0.94244338,90.00000001 +26.7,50.425,-2.592076033,51.3912,0,9.998688993,1.163125,5.553186935,-1.039410987,90.00000001 +26.71,50.425,-2.592074626,51.3792,0,9.998688974,1.223125,5.618149177,-1.135472231,90.00000001 +26.72,50.425,-2.592073219,51.3667,0,9.999577233,1.2815625,5.681938172,-1.23054329,90.00000001 +26.73,50.425,-2.592071812,51.3536,0,10.00068756,1.34,5.744540572,-1.324541314,90.00000001 +26.74,50.425,-2.592070404,51.3399,0,10.00068754,1.398125,5.805943256,-1.417384311,90.00000001 +26.75,50.425,-2.592068997,51.3256,0,9.999577169,1.4546875,5.866133446,-1.508991325,90.00000001 +26.76,50.425,-2.59206759,51.3108,0,9.998910937,1.5103125,5.925098596,-1.59928254,90.00000001 +26.77,50.425,-2.592066183,51.2954,0,9.999577122,1.5665625,5.982826385,-1.688179062,90.00000001 +26.78,50.425,-2.592064776,51.2795,0,10.00068745,1.623125,6.039304726,-1.775603541,90.00000001 +26.79,50.425,-2.592063368,51.2629,0,10.00090949,1.678125,6.094521815,-1.861479659,90.00000001 +26.8,50.425,-2.592061961,51.2459,0,10.00068739,1.73125,6.148466135,-1.945732472,90.00000001 +26.81,50.425,-2.592060554,51.2283,0,10.00090944,1.78375,6.201126399,-2.028288643,90.00000001 +26.82,50.425,-2.592059146,51.2102,0,10.00068734,1.83625,6.252491722,-2.109076093,90.00000001 +26.83,50.425,-2.592057739,51.1916,0,9.999576959,1.8884375,6.302551216,-2.188024406,90.00000001 +26.84,50.425,-2.592056332,51.1724,0,9.99891072,1.9396875,6.351294569,-2.265064712,90.00000001 +26.85,50.425,-2.592054925,51.1528,0,9.999576898,1.9896875,6.398711468,-2.340129861,90.00000001 +26.86,50.425,-2.592053518,51.1326,0,10.00068722,2.0384375,6.444792114,-2.413154421,90.00000001 +26.87,50.425,-2.59205211,51.112,0,10.00068718,2.0865625,6.489526825,-2.484074621,90.00000001 +26.88,50.425,-2.592050703,51.0909,0,9.999576802,2.1346875,6.53290632,-2.552828697,90.00000001 +26.89,50.425,-2.592049296,51.0693,0,9.998910559,2.1815625,6.574921487,-2.61935666,90.00000001 +26.9,50.425,-2.592047889,51.0472,0,9.999576733,2.22625,6.61556356,-2.683600469,90.00000001 +26.91,50.425,-2.592046482,51.0248,0,10.00068705,2.27,6.654824061,-2.745504205,90.00000001 +26.92,50.425,-2.592045074,51.0018,0,10.00068701,2.3134375,6.692694737,-2.805013779,90.00000001 +26.93,50.425,-2.592043667,50.9785,0,9.999576626,2.35625,6.729167798,-2.862077338,90.00000001 +26.94,50.425,-2.59204226,50.9547,0,9.99868831,2.3984375,6.764235508,-2.916645151,90.00000001 +26.95,50.425,-2.592040853,50.9305,0,9.998688272,2.439375,6.797890648,-2.968669547,90.00000001 +26.96,50.425,-2.592039446,50.9059,0,9.999576512,2.4784375,6.830126113,-3.018105262,90.00000001 +26.97,50.425,-2.592038039,50.8809,0,10.00090889,2.5165625,6.8609352,-3.064909153,90.00000001 +26.98,50.425,-2.592036631,50.8556,0,10.00179713,2.5546875,6.890311433,-3.109040368,90.00000001 +26.99,50.425,-2.592035224,50.8298,0,10.00179709,2.5915625,6.918248741,-3.150460518,90.00000001 +27,50.425,-2.592033816,50.8037,0,10.00090877,2.6259375,6.944741278,-3.189133336,90.00000001 +27.01,50.425,-2.592032409,50.7773,0,9.999576311,2.6584375,6.969783487,-3.225025246,90.00000001 +27.02,50.425,-2.592031002,50.7505,0,9.998687991,2.69,6.993370097,-3.25810485,90.00000001 +27.03,50.425,-2.592029595,50.7235,0,9.998687949,2.7215625,7.015496294,-3.288343327,90.00000001 +27.04,50.425,-2.592028188,50.6961,0,9.999576184,2.7534375,7.036157382,-3.315714381,90.00000001 +27.05,50.425,-2.592026781,50.6684,0,10.00068649,2.784375,7.055349004,-3.340194003,90.00000001 +27.06,50.425,-2.592025373,50.6404,0,10.00068645,2.813125,7.073067266,-3.361760993,90.00000001 +27.07,50.425,-2.592023966,50.6121,0,9.999576053,2.8396875,7.089308385,-3.380396446,90.00000001 +27.08,50.425,-2.592022559,50.5836,0,9.998909799,2.8646875,7.104068981,-3.396084145,90.00000001 +27.09,50.425,-2.592021152,50.5548,0,9.999575963,2.8884375,7.117346017,-3.408810397,90.00000001 +27.1,50.425,-2.592019745,50.5258,0,10.00068627,2.91125,7.129136686,-3.418564144,90.00000001 +27.11,50.425,-2.592018337,50.4966,0,10.00068622,2.9334375,7.139438467,-3.425336849,90.00000001 +27.12,50.425,-2.59201693,50.4671,0,9.999575826,2.9546875,7.148249355,-3.429122553,90.00000001 +27.13,50.425,-2.592015523,50.4375,0,9.998909571,2.9746875,7.155567344,-3.429918105,90.00000001 +27.14,50.425,-2.592014116,50.4076,0,9.999575734,2.993125,7.161391059,-3.427722645,90.00000001 +27.15,50.425,-2.592012709,50.3776,0,10.00068604,3.0096875,7.165719125,-3.422538179,90.00000001 +27.16,50.425,-2.592011301,50.3474,0,10.00090806,3.025,7.168550797,-3.414369233,90.00000001 +27.17,50.425,-2.592009894,50.3171,0,10.00068594,3.0396875,7.169885387,-3.403222855,90.00000001 +27.18,50.425,-2.592008487,50.2866,0,10.00090796,3.053125,7.16972261,-3.389108842,90.00000001 +27.19,50.425,-2.592007079,50.256,0,10.00068584,3.064375,7.168062522,-3.372039512,90.00000001 +27.2,50.425,-2.592005672,50.2253,0,9.999575448,3.0734375,7.164905525,-3.352029649,90.00000001 +27.21,50.425,-2.592004265,50.1945,0,9.998909191,3.0815625,7.160252191,-3.329096841,90.00000001 +27.22,50.425,-2.592002858,50.1637,0,9.999575351,3.0896875,7.154103551,-3.303260914,90.00000001 +27.23,50.425,-2.592001451,50.1327,0,10.00068565,3.0965625,7.146460867,-3.274544556,90.00000001 +27.24,50.425,-2.592000043,50.1017,0,10.0006856,3.10125,7.137325743,-3.242972748,90.00000001 +27.25,50.425,-2.591998636,50.0707,0,9.999575206,3.105,7.126700069,-3.208573049,90.00000001 +27.26,50.425,-2.591997229,50.0396,0,9.998686879,3.108125,7.114586079,-3.171375369,90.00000001 +27.27,50.425,-2.591995822,50.0085,0,9.99868683,3.1096875,7.100986296,-3.131412193,90.00000001 +27.28,50.425,-2.591994415,49.9774,0,9.999575059,3.1096875,7.085903526,-3.088718414,90.00000001 +27.29,50.425,-2.591993008,49.9463,0,10.00068536,3.108125,7.069340977,-3.043331219,90.00000001 +27.3,50.425,-2.5919916,49.9152,0,10.00068531,3.1046875,7.051302146,-2.995290198,90.00000001 +27.31,50.425,-2.591990193,49.8842,0,9.999574915,3.1,7.031790641,-2.944637233,90.00000001 +27.32,50.425,-2.591988786,49.8532,0,9.998908657,3.0946875,7.010810703,-2.891416559,90.00000001 +27.33,50.425,-2.591987379,49.8223,0,9.999574817,3.088125,6.988366628,-2.835674469,90.00000001 +27.34,50.425,-2.591985972,49.7914,0,10.00090719,3.0796875,6.964463173,-2.777459608,90.00000001 +27.35,50.425,-2.591984564,49.7607,0,10.00179542,3.0696875,6.939105207,-2.716822797,90.00000001 +27.36,50.425,-2.591983157,49.73,0,10.00179537,3.0584375,6.912298116,-2.653816863,90.00000001 +27.37,50.425,-2.591981749,49.6995,0,10.00090704,3.04625,6.884047515,-2.588496752,90.00000001 +27.38,50.425,-2.591980342,49.6691,0,9.999574577,3.033125,6.854359248,-2.520919474,90.00000001 +27.39,50.425,-2.591978935,49.6388,0,9.998686251,3.018125,6.823239504,-2.451143872,90.00000001 +27.4,50.425,-2.591977528,49.6087,0,9.998686204,3.00125,6.790694871,-2.37923085,90.00000001 +27.41,50.425,-2.591976121,49.5788,0,9.999574437,2.9834375,6.756732053,-2.305243091,90.00000001 +27.42,50.425,-2.591974714,49.549,0,10.00068474,2.9646875,6.721358154,-2.229245167,90.00000001 +27.43,50.425,-2.591973306,49.5195,0,10.00068469,2.9446875,6.684580624,-2.151303255,90.00000001 +27.44,50.425,-2.591971899,49.4901,0,9.999574297,2.9234375,6.646407081,-2.071485421,90.00000001 +27.45,50.425,-2.591970492,49.461,0,9.998908043,2.90125,6.606845549,-1.989861166,90.00000001 +27.46,50.425,-2.591969085,49.4321,0,9.999574207,2.878125,6.565904219,-1.906501765,90.00000001 +27.47,50.425,-2.591967678,49.4034,0,10.00068451,2.853125,6.523591745,-1.821479871,90.00000001 +27.48,50.425,-2.59196627,49.375,0,10.00068447,2.82625,6.479916891,-1.734869622,90.00000001 +27.49,50.425,-2.591964863,49.3469,0,9.999574073,2.7984375,6.434888768,-1.646746479,90.00000001 +27.5,50.425,-2.591963456,49.319,0,9.998907821,2.77,6.388516773,-1.557187389,90.00000001 +27.51,50.425,-2.591962049,49.2915,0,9.999573987,2.74125,6.340810645,-1.466270446,90.00000001 +27.52,50.425,-2.591960642,49.2642,0,10.00068429,2.71125,6.291780355,-1.374074833,90.00000001 +27.53,50.425,-2.591959234,49.2372,0,10.00090632,2.678125,6.241436043,-1.280681051,90.00000001 +27.54,50.425,-2.591957827,49.2106,0,10.00068421,2.643125,6.189788309,-1.186170459,90.00000001 +27.55,50.425,-2.59195642,49.1844,0,10.00090624,2.6084375,6.136847926,-1.090625564,90.00000001 +27.56,50.425,-2.591955012,49.1584,0,10.00068413,2.573125,6.08262595,-0.994129559,90.00000001 +27.57,50.425,-2.591953605,49.1329,0,9.999573739,2.53625,6.02713367,-0.896766727,90.00000001 +27.58,50.425,-2.591952198,49.1077,0,9.998907491,2.4984375,5.970382716,-0.798621864,90.00000001 +27.59,50.425,-2.591950791,49.0829,0,9.999573661,2.4596875,5.912384949,-0.699780571,90.00000001 +27.6,50.425,-2.591949384,49.0585,0,10.00068397,2.42,5.8531524,-0.600329078,90.00000001 +27.61,50.425,-2.591947976,49.0345,0,10.00068393,2.3796875,5.79269756,-0.50035413,90.00000001 +27.62,50.425,-2.591946569,49.0109,0,9.999573549,2.338125,5.731032978,-0.399942818,90.00000001 +27.63,50.425,-2.591945162,48.9877,0,9.998685234,2.295,5.668171486,-0.299182747,90.00000001 +27.64,50.425,-2.591943755,48.965,0,9.998685198,2.25125,5.604126321,-0.198161808,90.00000001 +27.65,50.425,-2.591942348,48.9427,0,9.999573442,2.2065625,5.538910775,-0.096968065,90.00000001 +27.66,50.425,-2.591940941,48.9208,0,10.00068376,2.1596875,5.472538542,0.004310247,90.00000001 +27.67,50.425,-2.591939533,48.8995,0,10.00068372,2.111875,5.405023373,0.105584834,90.00000001 +27.68,50.425,-2.591938126,48.8786,0,9.999795411,2.065,5.336379476,0.20676729,90.00000001 +27.69,50.425,-2.591936719,48.8582,0,9.999795379,2.0178125,5.26662112,0.307769494,90.00000001 +27.7,50.425,-2.591935312,48.8382,0,10.00068363,1.968125,5.195762971,0.408503266,90.00000001 +27.71,50.425,-2.591933904,48.8188,0,10.0006836,1.9165625,5.123819698,0.508880831,90.00000001 +27.72,50.425,-2.591932497,48.7999,0,9.999795287,1.865,5.050806368,0.60881464,90.00000001 +27.73,50.425,-2.59193109,48.7815,0,9.999795259,1.813125,4.976738223,0.708217603,90.00000001 +27.74,50.425,-2.591929683,48.7636,0,10.00068351,1.76,4.90163079,0.807002918,90.00000001 +27.75,50.425,-2.591928275,48.7463,0,10.00068348,1.7065625,4.82549971,0.905084584,90.00000001 +27.76,50.425,-2.591926868,48.7295,0,9.999573108,1.653125,4.748360913,1.002376943,90.00000001 +27.77,50.425,-2.591925461,48.7132,0,9.998906873,1.598125,4.67023044,1.098795255,90.00000001 +27.78,50.425,-2.591924054,48.6975,0,9.999573058,1.5415625,4.591124678,1.194255352,90.00000001 +27.79,50.425,-2.591922647,48.6824,0,10.00068338,1.485,4.511060071,1.288674098,90.00000001 +27.8,50.425,-2.591921239,48.6678,0,10.00068336,1.4284375,4.430053407,1.381969103,90.00000001 +27.81,50.425,-2.591919832,48.6538,0,9.99957299,1.37125,4.348121589,1.474058947,90.00000001 +27.82,50.425,-2.591918425,48.6404,0,9.998906759,1.3134375,4.265281746,1.564863419,90.00000001 +27.83,50.425,-2.591917018,48.6275,0,9.999572948,1.255,4.181551127,1.654303334,90.00000001 +27.84,50.425,-2.591915611,48.6153,0,10.00068328,1.19625,4.096947262,1.742300656,90.00000001 +27.85,50.425,-2.591914203,48.6036,0,10.00068326,1.1365625,4.011487799,1.828778665,90.00000001 +27.86,50.425,-2.591912796,48.5925,0,9.999794964,1.075,3.925190558,1.913661962,90.00000001 +27.87,50.425,-2.591911389,48.5821,0,9.999794948,1.0134375,3.838073643,1.996876461,90.00000001 +27.88,50.425,-2.591909982,48.5723,0,10.00068321,0.9534375,3.75015516,2.078349742,90.00000001 +27.89,50.425,-2.591908574,48.563,0,10.0006832,0.8928125,3.661453501,2.158010585,90.00000001 +27.9,50.425,-2.591907167,48.5544,0,9.999794904,0.83,3.57198723,2.235789663,90.00000001 +27.91,50.425,-2.59190576,48.5464,0,9.999794892,0.766875,3.481774968,2.31161908,90.00000001 +27.92,50.425,-2.591904353,48.5391,0,10.00068316,0.705,3.390835565,2.385432774,90.00000001 +27.93,50.425,-2.591902945,48.5323,0,10.00068315,0.643125,3.299188043,2.457166288,90.00000001 +27.94,50.425,-2.591901538,48.5262,0,9.99957279,0.5796875,3.20685154,2.526757112,90.00000001 +27.95,50.425,-2.591900131,48.5207,0,9.998684503,0.515,3.113845307,2.594144626,90.00000001 +27.96,50.425,-2.591898724,48.5159,0,9.998684496,0.4503125,3.020188823,2.659269931,90.00000001 +27.97,50.425,-2.591897317,48.5117,0,9.999572768,0.3865625,2.925901571,2.722076362,90.00000001 +27.98,50.425,-2.59189591,48.5082,0,10.00068311,0.3234375,2.831003316,2.782509085,90.00000001 +27.99,50.425,-2.591894502,48.5052,0,10.0006831,0.26,2.735513826,2.840515447,90.00000001 +28,50.425,-2.591893095,48.503,0,9.999572754,0.19625,2.63945304,2.896044797,90.00000001 +28.01,50.425,-2.591891688,48.5013,0,9.998906543,0.131875,2.542841068,2.949048779,90.00000001 +28.02,50.425,-2.591890281,48.5003,0,9.99957275,0.06625,2.445698022,2.999481097,90.00000001 +28.03,50.425,-2.591888874,48.5,0,10.0006831,0.000625,2.348044242,3.047297863,90.00000001 +28.04,50.425,-2.591887466,48.5003,0,10.00090517,-0.0634375,2.249900124,3.092457365,90.00000001 +28.05,50.425,-2.591886059,48.5013,0,10.0006831,-0.126875,2.151286123,3.134920127,90.00000001 +28.06,50.425,-2.591884652,48.5028,0,10.00090517,-0.1915625,2.052222866,3.17464925,90.00000001 +28.07,50.425,-2.591883244,48.5051,0,10.00068311,-0.2565625,1.952731037,3.211610012,90.00000001 +28.08,50.425,-2.591881837,48.508,0,9.999572762,-0.3196875,1.852831376,3.245770214,90.00000001 +28.09,50.425,-2.59188043,48.5115,0,9.998906558,-0.3821875,1.752544797,3.277100062,90.00000001 +28.1,50.425,-2.591879023,48.5156,0,9.999572773,-0.4465625,1.651892213,3.305572226,90.00000001 +28.11,50.425,-2.591877616,48.5204,0,10.00068313,-0.5115625,1.55089465,3.331161839,90.00000001 +28.12,50.425,-2.591876208,48.5259,0,10.00068314,-0.575,1.449573195,3.35384667,90.00000001 +28.13,50.425,-2.591874801,48.5319,0,9.999572799,-0.638125,1.347948989,3.373606896,90.00000001 +28.14,50.425,-2.591873394,48.5386,0,9.9989066,-0.701875,1.246043345,3.39042527,90.00000001 +28.15,50.425,-2.591871987,48.546,0,9.99957282,-0.7646875,1.143877465,3.404287181,90.00000001 +28.16,50.425,-2.59187058,48.5539,0,10.00068318,-0.8265625,1.041472661,3.415180484,90.00000001 +28.17,50.425,-2.591869172,48.5625,0,10.0006832,-0.8884375,0.938850362,3.423095667,90.00000001 +28.18,50.425,-2.591867765,48.5717,0,9.999572862,-0.9496875,0.836032054,3.428025912,90.00000001 +28.19,50.425,-2.591866358,48.5815,0,9.998684598,-1.01,0.733039109,3.429966806,90.00000001 +28.2,50.425,-2.591864951,48.5919,0,9.998684614,-1.0703125,0.62989307,3.428916746,90.00000001 +28.21,50.425,-2.591863544,48.6029,0,9.99957291,-1.1315625,0.526615536,3.424876649,90.00000001 +28.22,50.425,-2.591862137,48.6145,0,10.00068328,-1.193125,0.423227938,3.417850009,90.00000001 +28.23,50.425,-2.591860729,48.6268,0,10.00090537,-1.2528125,0.319752046,3.4078429,90.00000001 +28.24,50.425,-2.591859322,48.6396,0,10.00068332,-1.31,0.216209348,3.394864146,90.00000001 +28.25,50.425,-2.591857915,48.653,0,10.00090541,-1.366875,0.112621444,3.378924975,90.00000001 +28.26,50.425,-2.591856507,48.6669,0,10.00068336,-1.425,0.009010105,3.36003937,90.00000001 +28.27,50.425,-2.5918551,48.6815,0,9.999795103,-1.483125,-0.094603181,3.338223773,90.00000001 +28.28,50.425,-2.591853693,48.6966,0,9.999795126,-1.5396875,-0.198196701,3.313497149,90.00000001 +28.29,50.425,-2.591852286,48.7123,0,10.00068343,-1.595,-0.301748796,3.285881156,90.00000001 +28.3,50.425,-2.591850878,48.7285,0,10.00068345,-1.6496875,-0.405237865,3.255399801,90.00000001 +28.31,50.425,-2.591849471,48.7453,0,9.999573132,-1.7034375,-0.508642366,3.22207967,90.00000001 +28.32,50.425,-2.591848064,48.7626,0,9.998684881,-1.7565625,-0.611940583,3.185949868,90.00000001 +28.33,50.425,-2.591846657,48.7804,0,9.99868491,-1.81,-0.715111031,3.147041851,90.00000001 +28.34,50.425,-2.59184525,48.7988,0,9.999573217,-1.8628125,-0.818132165,3.105389538,90.00000001 +28.35,50.425,-2.591843843,48.8177,0,10.00068359,-1.913125,-0.920982387,3.061029312,90.00000001 +28.36,50.425,-2.591842435,48.8371,0,10.00068362,-1.961875,-1.023640323,3.013999848,90.00000001 +28.37,50.425,-2.591841028,48.8569,0,9.999573307,-2.0115625,-1.12608449,2.964342111,90.00000001 +28.38,50.425,-2.591839621,48.8773,0,9.998907131,-2.0615625,-1.228293457,2.912099419,90.00000001 +28.39,50.425,-2.591838214,48.8982,0,9.999573372,-2.1096875,-1.330245911,2.85731732,90.00000001 +28.4,50.425,-2.591836807,48.9195,0,10.00068375,-2.1565625,-1.431920537,2.800043656,90.00000001 +28.41,50.425,-2.591835399,48.9413,0,10.00090586,-2.203125,-1.533296194,2.740328219,90.00000001 +28.42,50.425,-2.591833992,48.9636,0,10.00068382,-2.248125,-1.634351568,2.678223261,90.00000001 +28.43,50.425,-2.591832585,48.9863,0,10.00090593,-2.2915625,-1.735065688,2.613782812,90.00000001 +28.44,50.425,-2.591831177,49.0094,0,10.00068389,-2.335,-1.835417413,2.54706308,90.00000001 +28.45,50.425,-2.59182977,49.033,0,9.999573583,-2.378125,-1.935385886,2.478122334,90.00000001 +28.46,50.425,-2.591828363,49.057,0,9.998907412,-2.419375,-2.034950137,2.407020564,90.00000001 +28.47,50.425,-2.591826956,49.0814,0,9.999573658,-2.4584375,-2.134089425,2.333819877,90.00000001 +28.48,50.425,-2.591825549,49.1062,0,10.00068404,-2.4965625,-2.232783067,2.258584044,90.00000001 +28.49,50.425,-2.591824141,49.1313,0,10.00068409,-2.5346875,-2.331010378,2.181378726,90.00000001 +28.5,50.425,-2.591822734,49.1569,0,9.999573777,-2.5715625,-2.428750905,2.102271188,90.00000001 +28.51,50.425,-2.591821327,49.1828,0,9.998907608,-2.60625,-2.525984192,2.021330472,90.00000001 +28.52,50.425,-2.59181992,49.209,0,9.999573858,-2.6403125,-2.622690014,1.938627051,90.00000001 +28.53,50.425,-2.591818513,49.2356,0,10.00068425,-2.6746875,-2.718848088,1.854233175,90.00000001 +28.54,50.425,-2.591817105,49.2625,0,10.00068429,-2.708125,-2.814438361,1.768222355,90.00000001 +28.55,50.425,-2.591815698,49.2898,0,9.999573985,-2.7396875,-2.909440837,1.680669648,90.00000001 +28.56,50.425,-2.591814291,49.3173,0,9.998685749,-2.7696875,-3.003835806,1.591651373,90.00000001 +28.57,50.425,-2.591812884,49.3452,0,9.998685792,-2.798125,-3.097603386,1.501245107,90.00000001 +28.58,50.425,-2.591811477,49.3733,0,9.999574115,-2.8246875,-3.190724096,1.409529805,90.00000001 +28.59,50.425,-2.59181007,49.4017,0,10.00090658,-2.85,-3.283178457,1.316585279,90.00000001 +28.6,50.425,-2.591808662,49.4303,0,10.0017949,-2.875,-3.374947216,1.222492717,90.00000001 +28.61,50.425,-2.591807255,49.4592,0,10.00179495,-2.8996875,-3.466011123,1.127334168,90.00000001 +28.62,50.425,-2.591805847,49.4883,0,10.00090671,-2.923125,-3.556351154,1.031192537,90.00000001 +28.63,50.425,-2.59180444,49.5177,0,9.99957434,-2.9446875,-3.645948575,0.93415165,90.00000001 +28.64,50.425,-2.591803033,49.5472,0,9.998686108,-2.9646875,-3.734784536,0.836296188,90.00000001 +28.65,50.425,-2.591801626,49.577,0,9.998686155,-2.9834375,-3.822840528,0.737711465,90.00000001 +28.66,50.425,-2.591800219,49.6069,0,9.999574481,-3.00125,-3.910098162,0.638483483,90.00000001 +28.67,50.425,-2.591798812,49.637,0,10.00068488,-3.018125,-3.996539273,0.538698701,90.00000001 +28.68,50.425,-2.591797404,49.6673,0,10.00068492,-3.0328125,-4.082145699,0.438444207,90.00000001 +28.69,50.425,-2.591795997,49.6977,0,9.999574622,-3.045,-4.166899679,0.337807322,90.00000001 +28.7,50.425,-2.59179459,49.7282,0,9.998908461,-3.0565625,-4.250783393,0.236875879,90.00000001 +28.71,50.425,-2.591793183,49.7588,0,9.999574718,-3.068125,-4.333779424,0.135737884,90.00000001 +28.72,50.425,-2.591791776,49.7896,0,10.00068512,-3.078125,-4.41587041,0.034481517,90.00000001 +28.73,50.425,-2.591790368,49.8204,0,10.00068516,-3.08625,-4.497039164,-0.066804874,90.00000001 +28.74,50.425,-2.591788961,49.8513,0,9.999574862,-3.0934375,-4.577268782,-0.168033051,90.00000001 +28.75,50.425,-2.591787554,49.8823,0,9.998908702,-3.0996875,-4.656542478,-0.269114724,90.00000001 +28.76,50.425,-2.591786147,49.9133,0,9.99957496,-3.1046875,-4.73484375,-0.369961656,90.00000001 +28.77,50.425,-2.59178474,49.9444,0,10.00068536,-3.108125,-4.812156211,-0.470486012,90.00000001 +28.78,50.425,-2.591783332,49.9755,0,10.00090748,-3.1096875,-4.888463704,-0.570600131,90.00000001 +28.79,50.425,-2.591781925,50.0066,0,10.00068545,-3.1096875,-4.963750301,-0.670216636,90.00000001 +28.8,50.425,-2.591780518,50.0377,0,10.00090757,-3.108125,-5.038000303,-0.769248724,90.00000001 +28.81,50.425,-2.59177911,50.0688,0,10.00068555,-3.105,-5.111198125,-0.867609993,90.00000001 +28.82,50.425,-2.591777703,50.0998,0,9.999575252,-3.1015625,-5.183328584,-0.965214728,90.00000001 +28.83,50.425,-2.591776296,50.1308,0,9.998909091,-3.098125,-5.254376554,-1.061977732,90.00000001 +28.84,50.425,-2.591774889,50.1618,0,9.999575348,-3.0928125,-5.324327252,-1.15781472,90.00000001 +28.85,50.425,-2.591773482,50.1927,0,10.00068574,-3.0846875,-5.393166011,-1.252642043,90.00000001 +28.86,50.425,-2.591772074,50.2235,0,10.00068579,-3.0746875,-5.46087845,-1.346377079,90.00000001 +28.87,50.425,-2.591770667,50.2542,0,9.999575493,-3.0634375,-5.527450473,-1.43893801,90.00000001 +28.88,50.425,-2.59176926,50.2848,0,9.998687262,-3.0515625,-5.592868159,-1.53024422,90.00000001 +28.89,50.425,-2.591767853,50.3152,0,9.99868731,-3.0396875,-5.65711787,-1.620215955,90.00000001 +28.9,50.425,-2.591766446,50.3456,0,9.999575635,-3.0265625,-5.720186142,-1.70877489,90.00000001 +28.91,50.425,-2.591765039,50.3758,0,10.00068603,-3.0109375,-5.782059797,-1.795843791,90.00000001 +28.92,50.425,-2.591763631,50.4058,0,10.00068608,-2.9934375,-5.842726,-1.881346626,90.00000001 +28.93,50.425,-2.591762224,50.4357,0,9.999575778,-2.9746875,-5.902171976,-1.965208912,90.00000001 +28.94,50.425,-2.591760817,50.4653,0,9.998909615,-2.955,-5.960385405,-2.04735748,90.00000001 +28.95,50.425,-2.59175941,50.4948,0,9.999575869,-2.935,-6.017354025,-2.12772077,90.00000001 +28.96,50.425,-2.591758003,50.524,0,10.00090833,-2.914375,-6.073066035,-2.20622865,90.00000001 +28.97,50.425,-2.591756595,50.5531,0,10.00179666,-2.8915625,-6.127509802,-2.282812653,90.00000001 +28.98,50.425,-2.591755188,50.5819,0,10.0017967,-2.86625,-6.180673869,-2.357406028,90.00000001 +28.99,50.425,-2.59175378,50.6104,0,10.00090847,-2.84,-6.232547176,-2.429943688,90.00000001 +29,50.425,-2.591752373,50.6387,0,9.999576094,-2.813125,-6.283118894,-2.500362379,90.00000001 +29.01,50.425,-2.591750966,50.6667,0,9.998687859,-2.7846875,-6.332378482,-2.568600735,90.00000001 +29.02,50.425,-2.591749559,50.6944,0,9.998687903,-2.755,-6.380315627,-2.634599285,90.00000001 +29.03,50.425,-2.591748152,50.7218,0,9.999576225,-2.7246875,-6.4269203,-2.698300332,90.00000001 +29.04,50.425,-2.591746745,50.7489,0,10.00068662,-2.6934375,-6.47218282,-2.75964847,90.00000001 +29.05,50.425,-2.591745337,50.7757,0,10.00068666,-2.66125,-6.516093732,-2.818590185,90.00000001 +29.06,50.425,-2.59174393,50.8021,0,9.999576349,-2.628125,-6.558643813,-2.875074026,90.00000001 +29.07,50.425,-2.591742523,50.8283,0,9.998910181,-2.593125,-6.59982418,-2.929050719,90.00000001 +29.08,50.425,-2.591741116,50.854,0,9.999576431,-2.55625,-6.639626298,-2.98047328,90.00000001 +29.09,50.425,-2.591739709,50.8794,0,10.00068682,-2.5184375,-6.6780418,-3.02929679,90.00000001 +29.1,50.425,-2.591738301,50.9044,0,10.00068686,-2.4796875,-6.715062666,-3.075478735,90.00000001 +29.11,50.425,-2.591736894,50.929,0,9.999576548,-2.44,-6.750681218,-3.118978837,90.00000001 +29.12,50.425,-2.591735487,50.9532,0,9.998688307,-2.4,-6.784889949,-3.159759108,90.00000001 +29.13,50.425,-2.59173408,50.977,0,9.998688344,-2.3596875,-6.817681756,-3.197784025,90.00000001 +29.14,50.425,-2.591732673,51.0004,0,9.99957666,-2.318125,-6.849049763,-3.233020471,90.00000001 +29.15,50.425,-2.591731266,51.0234,0,10.00090911,-2.2746875,-6.878987438,-3.265437621,90.00000001 +29.16,50.425,-2.591729858,51.0459,0,10.00179743,-2.2296875,-6.907488536,-3.295007285,90.00000001 +29.17,50.425,-2.591728451,51.068,0,10.00179746,-2.1834375,-6.934547041,-3.321703623,90.00000001 +29.18,50.425,-2.591727043,51.0896,0,10.00090922,-2.1365625,-6.960157395,-3.345503431,90.00000001 +29.19,50.425,-2.591725636,51.1107,0,9.999576833,-2.0896875,-6.984314212,-3.366385851,90.00000001 +29.2,50.425,-2.591724229,51.1314,0,9.998910656,-2.0415625,-7.007012451,-3.38433278,90.00000001 +29.21,50.425,-2.591722822,51.1516,0,9.999576897,-1.9915625,-7.028247356,-3.399328518,90.00000001 +29.22,50.425,-2.591721415,51.1712,0,10.00068728,-1.9415625,-7.048014514,-3.411360002,90.00000001 +29.23,50.425,-2.591720007,51.1904,0,10.00068731,-1.8915625,-7.066309744,-3.420416688,90.00000001 +29.24,50.425,-2.5917186,51.2091,0,9.999576987,-1.8396875,-7.083129321,-3.426490728,90.00000001 +29.25,50.425,-2.591717193,51.2272,0,9.998688737,-1.786875,-7.098469636,-3.429576851,90.00000001 +29.26,50.425,-2.591715786,51.2448,0,9.998688764,-1.735,-7.112327537,-3.429672306,90.00000001 +29.27,50.425,-2.591714379,51.2619,0,9.999577069,-1.6828125,-7.124700102,-3.426777035,90.00000001 +29.28,50.425,-2.591712972,51.2785,0,10.00068744,-1.628125,-7.135584811,-3.420893561,90.00000001 +29.29,50.425,-2.591711564,51.2945,0,10.00068747,-1.5715625,-7.144979313,-3.412027039,90.00000001 +29.3,50.425,-2.591710157,51.3099,0,9.999577144,-1.515,-7.152881662,-3.400185147,90.00000001 +29.31,50.425,-2.59170875,51.3248,0,9.998910959,-1.458125,-7.159290252,-3.385378314,90.00000001 +29.32,50.425,-2.591707343,51.3391,0,9.99957719,-1.4,-7.164203709,-3.367619315,90.00000001 +29.33,50.425,-2.591705936,51.3528,0,10.00090963,-1.341875,-7.167621001,-3.346923678,90.00000001 +29.34,50.425,-2.591704528,51.3659,0,10.00179793,-1.2846875,-7.169541441,-3.323309567,90.00000001 +29.35,50.425,-2.591703121,51.3785,0,10.00179795,-1.2265625,-7.169964627,-3.296797377,90.00000001 +29.36,50.425,-2.591701713,51.3905,0,10.00090969,-1.1665625,-7.168890446,-3.267410372,90.00000001 +29.37,50.425,-2.591700306,51.4018,0,9.999577288,-1.1065625,-7.166319126,-3.235174162,90.00000001 +29.38,50.425,-2.591698899,51.4126,0,9.998689025,-1.0465625,-7.162251183,-3.200116822,90.00000001 +29.39,50.425,-2.591697492,51.4228,0,9.998689042,-0.9846875,-7.156687534,-3.162268949,90.00000001 +29.4,50.425,-2.591696085,51.4323,0,9.999577336,-0.921875,-7.149629324,-3.121663488,90.00000001 +29.41,50.425,-2.591694678,51.4412,0,10.0006877,-0.8603125,-7.141077986,-3.078335904,90.00000001 +29.42,50.425,-2.59169327,51.4495,0,10.00068771,-0.7996875,-7.131035297,-3.032323955,90.00000001 +29.43,50.425,-2.591691863,51.4572,0,9.999577375,-0.738125,-7.119503432,-2.983667806,90.00000001 +29.44,50.425,-2.591690456,51.4643,0,9.998911176,-0.675,-7.106484685,-2.932409856,90.00000001 +29.45,50.425,-2.591689049,51.4707,0,9.999577395,-0.6115625,-7.091981863,-2.878594738,90.00000001 +29.46,50.425,-2.591687642,51.4765,0,10.00068775,-0.5484375,-7.075998002,-2.822269491,90.00000001 +29.47,50.425,-2.591686234,51.4817,0,10.00068776,-0.4846875,-7.058536426,-2.763483162,90.00000001 +29.48,50.425,-2.591684827,51.4862,0,9.99957742,-0.42,-7.039600686,-2.702287087,90.00000001 +29.49,50.425,-2.59168342,51.4901,0,9.998911217,-0.3553125,-7.019194852,-2.638734551,90.00000001 +29.5,50.425,-2.591682013,51.4933,0,9.999577431,-0.2915625,-6.997323162,-2.572880959,90.00000001 +29.51,50.425,-2.591680606,51.4959,0,10.00068778,-0.2284375,-6.9739902,-2.504783837,90.00000001 +29.52,50.425,-2.591679198,51.4979,0,10.00090986,-0.1646875,-6.94920078,-2.434502484,90.00000001 +29.53,50.425,-2.591677791,51.4992,0,10.00068779,-0.1,-6.922960058,-2.362098152,90.00000001 +29.54,50.425,-2.591676384,51.4999,0,10.00090986,-0.0353125,-6.895273649,-2.287634093,90.00000001 +29.55,50.425,-2.591674976,51.4999,0,10.00068779,0.0284375,-6.866147225,-2.211175167,90.00000001 +29.56,50.425,-2.591673569,51.4993,0,9.999577441,0.091875,-6.835586859,-2.132788066,90.00000001 +29.57,50.425,-2.591672162,51.4981,0,9.99891123,0.156875,-6.803598969,-2.052541144,90.00000001 +29.58,50.425,-2.591670755,51.4962,0,9.999577436,0.223125,-6.770190259,-1.970504417,90.00000001 +29.59,50.425,-2.591669348,51.4936,0,10.00068778,0.288125,-6.735367717,-1.886749332,90.00000001 +29.6,50.425,-2.59166794,51.4904,0,10.00068777,0.3515625,-6.699138507,-1.801348998,90.00000001 +29.61,50.425,-2.591666533,51.4866,0,9.99957742,0.415,-6.661510306,-1.714377844,90.00000001 +29.62,50.425,-2.591665126,51.4821,0,9.998689134,0.4784375,-6.622490906,-1.625911728,90.00000001 +29.63,50.425,-2.591663719,51.477,0,9.998689127,0.5415625,-6.582088558,-1.536027771,90.00000001 +29.64,50.425,-2.591662312,51.4713,0,9.999577397,0.605,-6.54031157,-1.44480441,90.00000001 +29.65,50.425,-2.591660905,51.4649,0,10.00068774,0.6684375,-6.497168707,-1.352321172,90.00000001 +29.66,50.425,-2.591659497,51.4579,0,10.00068772,0.7315625,-6.452669023,-1.258658616,90.00000001 +29.67,50.425,-2.59165809,51.4503,0,9.999799433,0.795,-6.406821743,-1.163898558,90.00000001 +29.68,50.425,-2.591656683,51.442,0,9.999799421,0.858125,-6.359636548,-1.068123563,90.00000001 +29.69,50.425,-2.591655276,51.4331,0,10.00068769,0.9196875,-6.311123181,-0.971417111,90.00000001 +29.7,50.425,-2.591653868,51.4236,0,10.00068767,0.98,-6.261291781,-0.873863598,90.00000001 +29.71,50.425,-2.591652461,51.4135,0,9.999799376,1.04,-6.210152834,-0.775548051,90.00000001 +29.72,50.425,-2.591651054,51.4028,0,9.999799359,1.1,-6.157716997,-0.676556185,90.00000001 +29.73,50.425,-2.591649647,51.3915,0,10.00068762,1.16,-6.103995156,-0.576974401,90.00000001 +29.74,50.425,-2.591648239,51.3796,0,10.0006876,1.22,-6.048998599,-0.476889446,90.00000001 +29.75,50.425,-2.591646832,51.3671,0,9.999577234,1.2796875,-5.992738784,-0.376388695,90.00000001 +29.76,50.425,-2.591645425,51.354,0,9.998911003,1.338125,-5.935227458,-0.275559697,90.00000001 +29.77,50.425,-2.591644018,51.3403,0,9.999577191,1.395,-5.876476652,-0.1744904,90.00000001 +29.78,50.425,-2.591642611,51.3261,0,10.00068752,1.451875,-5.816498571,-0.073268926,90.00000001 +29.79,50.425,-2.591641203,51.3113,0,10.0006875,1.5096875,-5.755305819,0.028016433,90.00000001 +29.8,50.425,-2.591639796,51.2959,0,9.999577123,1.5665625,-5.692911173,0.129277327,90.00000001 +29.81,50.425,-2.591638389,51.2799,0,9.998910888,1.6215625,-5.629327583,0.23042552,90.00000001 +29.82,50.425,-2.591636982,51.2635,0,9.999577071,1.6765625,-5.564568398,0.331372776,90.00000001 +29.83,50.425,-2.591635575,51.2464,0,10.00068739,1.7315625,-5.49864714,0.432031033,90.00000001 +29.84,50.425,-2.591634167,51.2288,0,10.00068737,1.784375,-5.43157756,0.53231257,90.00000001 +29.85,50.425,-2.59163276,51.2107,0,9.999799059,1.835,-5.363373638,0.632129954,90.00000001 +29.86,50.425,-2.591631353,51.1921,0,9.99979903,1.8853125,-5.294049698,0.731396095,90.00000001 +29.87,50.425,-2.591629946,51.173,0,10.00068728,1.9365625,-5.223620122,0.83002442,90.00000001 +29.88,50.425,-2.591628538,51.1534,0,10.00068725,1.988125,-5.152099634,0.927928984,90.00000001 +29.89,50.425,-2.591627131,51.1332,0,9.999798938,2.038125,-5.079503246,1.025024418,90.00000001 +29.9,50.425,-2.591625724,51.1126,0,9.999798906,2.08625,-5.005846026,1.121225922,90.00000001 +29.91,50.425,-2.591624317,51.0915,0,10.00068715,2.1334375,-4.931143445,1.216449789,90.00000001 +29.92,50.425,-2.591622909,51.0699,0,10.00068712,2.1796875,-4.855411029,1.310612824,90.00000001 +29.93,50.425,-2.591621502,51.0479,0,9.999576734,2.2246875,-4.778664651,1.403633038,90.00000001 +29.94,50.425,-2.591620095,51.0254,0,9.998688421,2.2684375,-4.700920294,1.495429242,90.00000001 +29.95,50.425,-2.591618688,51.0025,0,9.998688385,2.3115625,-4.622194174,1.585921394,90.00000001 +29.96,50.425,-2.591617281,50.9792,0,9.999576627,2.355,-4.542502792,1.675030598,90.00000001 +29.97,50.425,-2.591615874,50.9554,0,10.00068694,2.3978125,-4.461862821,1.76267916,90.00000001 +29.98,50.425,-2.591614466,50.9312,0,10.0006869,2.438125,-4.380290992,1.848790649,90.00000001 +29.99,50.425,-2.591613059,50.9066,0,9.999576513,2.4765625,-4.297804378,1.933289949,90.00000001 +30,50.425,-2.591611652,50.8817,0,9.998910265,2.515,-4.214420283,2.016103435,90.00000001 +30.01,50.425,-2.591610245,50.8563,0,9.999576435,2.553125,-4.13015601,2.0971588,90.00000001 +30.02,50.425,-2.591608838,50.8306,0,10.00068674,2.589375,-4.045029207,2.176385399,90.00000001 +30.03,50.425,-2.59160743,50.8045,0,10.00090877,2.6234375,-3.959057692,2.253714189,90.00000001 +30.04,50.425,-2.591606023,50.7781,0,10.00068666,2.6565625,-3.872259341,2.329077734,90.00000001 +30.05,50.425,-2.591604616,50.7514,0,10.00090869,2.69,-3.784652318,2.402410259,90.00000001 +30.06,50.425,-2.591603208,50.7243,0,10.00068658,2.723125,-3.696254957,2.47364782,90.00000001 +30.07,50.425,-2.591601801,50.6969,0,9.999576186,2.754375,-3.60708565,2.542728368,90.00000001 +30.08,50.425,-2.591600394,50.6692,0,9.998909933,2.783125,-3.517163018,2.609591568,90.00000001 +30.09,50.425,-2.591598987,50.6412,0,9.999576098,2.81,-3.426505912,2.67417921,90.00000001 +30.1,50.425,-2.59159758,50.613,0,10.0006864,2.8365625,-3.335133238,2.736434913,90.00000001 +30.11,50.425,-2.591596172,50.5845,0,10.00068636,2.863125,-3.24306402,2.796304419,90.00000001 +30.12,50.425,-2.591594765,50.5557,0,9.999575965,2.888125,-3.150317565,2.853735474,90.00000001 +30.13,50.425,-2.591593358,50.5267,0,9.99890971,2.91125,-3.056913184,2.908678058,90.00000001 +30.14,50.425,-2.591591951,50.4975,0,9.999575873,2.9334375,-2.962870412,2.961084216,90.00000001 +30.15,50.425,-2.591590544,50.468,0,10.00068618,2.9546875,-2.868208903,3.010908282,90.00000001 +30.16,50.425,-2.591589136,50.4384,0,10.00068613,2.9746875,-2.772948425,3.058106769,90.00000001 +30.17,50.425,-2.591587729,50.4085,0,9.999575735,2.993125,-2.6771088,3.102638539,90.00000001 +30.18,50.425,-2.591586322,50.3785,0,9.998687409,3.0096875,-2.580710084,3.144464802,90.00000001 +30.19,50.425,-2.591584915,50.3483,0,9.998687362,3.0246875,-2.4837725,3.183549003,90.00000001 +30.2,50.425,-2.591583508,50.318,0,9.999575593,3.038125,-2.386316161,3.219857109,90.00000001 +30.21,50.425,-2.591582101,50.2875,0,10.00090796,3.05,-2.288361463,3.253357493,90.00000001 +30.22,50.425,-2.591580693,50.257,0,10.00179619,3.0615625,-2.18992886,3.284020877,90.00000001 +30.23,50.425,-2.591579286,50.2263,0,10.00179615,3.073125,-2.091038923,3.311820502,90.00000001 +30.24,50.425,-2.591577878,50.1955,0,10.00090782,3.083125,-1.991712335,3.336732192,90.00000001 +30.25,50.425,-2.591576471,50.1646,0,9.999575352,3.09125,-1.891969779,3.358734229,90.00000001 +30.26,50.425,-2.591575064,50.1337,0,9.998909095,3.098125,-1.791832112,3.377807421,90.00000001 +30.27,50.425,-2.591573657,50.1026,0,9.999575256,3.103125,-1.691320246,3.393935037,90.00000001 +30.28,50.425,-2.59157225,50.0716,0,10.00068556,3.10625,-1.590455152,3.407103154,90.00000001 +30.29,50.425,-2.591570842,50.0405,0,10.00068551,3.1084375,-1.489257913,3.417300199,90.00000001 +30.3,50.425,-2.591569435,50.0094,0,9.99957511,3.109375,-1.387749674,3.42451729,90.00000001 +30.31,50.425,-2.591568028,49.9783,0,9.998686782,3.1084375,-1.285951632,3.428748182,90.00000001 +30.32,50.425,-2.591566621,49.9472,0,9.998686734,3.1065625,-1.183885045,3.429989151,90.00000001 +30.33,50.425,-2.591565214,49.9162,0,9.999574964,3.1046875,-1.081571169,3.428239109,90.00000001 +30.34,50.425,-2.591563807,49.8851,0,10.00068526,3.10125,-0.979031434,3.423499602,90.00000001 +30.35,50.425,-2.591562399,49.8541,0,10.00068522,3.0946875,-0.876287267,3.415774756,90.00000001 +30.36,50.425,-2.591560992,49.8232,0,9.999574819,3.0865625,-0.773360097,3.405071332,90.00000001 +30.37,50.425,-2.591559585,49.7924,0,9.998908561,3.0784375,-0.670271411,3.391398553,90.00000001 +30.38,50.425,-2.591558178,49.7616,0,9.999574722,3.0696875,-0.567042751,3.37476851,90.00000001 +30.39,50.425,-2.591556771,49.731,0,10.00068502,3.059375,-0.46369566,3.355195585,90.00000001 +30.4,50.425,-2.591555363,49.7004,0,10.00090704,3.046875,-0.36025174,3.33269685,90.00000001 +30.41,50.425,-2.591553956,49.67,0,10.00068493,3.0328125,-0.25673259,3.307291958,90.00000001 +30.42,50.425,-2.591552549,49.6398,0,10.00090695,3.0184375,-0.153159869,3.279003084,90.00000001 +30.43,50.425,-2.591551141,49.6096,0,10.00068483,3.0028125,-0.049555062,3.247854864,90.00000001 +30.44,50.425,-2.591549734,49.5797,0,9.999574439,2.9846875,0.05406,3.213874456,90.00000001 +30.45,50.425,-2.591548327,49.5499,0,9.998908183,2.965,0.157663833,3.177091539,90.00000001 +30.46,50.425,-2.59154692,49.5204,0,9.999574345,2.945,0.261234721,3.137538086,90.00000001 +30.47,50.425,-2.591545513,49.491,0,10.00068465,2.9246875,0.364751063,3.095248701,90.00000001 +30.48,50.425,-2.591544105,49.4619,0,10.0006846,2.9028125,0.468191202,3.050260227,90.00000001 +30.49,50.425,-2.591542698,49.4329,0,9.999574208,2.8784375,0.571533594,3.002611853,90.00000001 +30.5,50.425,-2.591541291,49.4043,0,9.998907955,2.8528125,0.674756582,2.952345177,90.00000001 +30.51,50.425,-2.591539884,49.3759,0,9.999574119,2.826875,0.777838736,2.899503973,90.00000001 +30.52,50.425,-2.591538477,49.3477,0,10.00068442,2.7996875,0.8807584,2.844134363,90.00000001 +30.53,50.425,-2.591537069,49.3199,0,10.00068438,2.77125,0.983494145,2.786284648,90.00000001 +30.54,50.425,-2.591535662,49.2923,0,9.999573988,2.741875,1.086024484,2.726005248,90.00000001 +30.55,50.425,-2.591534255,49.265,0,9.998685667,2.7109375,1.188327989,2.663348761,90.00000001 +30.56,50.425,-2.591532848,49.2381,0,9.998685625,2.6784375,1.290383346,2.598369732,90.00000001 +30.57,50.425,-2.591531441,49.2114,0,9.999573862,2.645,1.392169241,2.531124941,90.00000001 +30.58,50.425,-2.591530034,49.1852,0,10.00090624,2.61125,1.493664417,2.461672945,90.00000001 +30.59,50.425,-2.591528626,49.1592,0,10.00179448,2.5765625,1.594847675,2.390074306,90.00000001 +30.6,50.425,-2.591527219,49.1336,0,10.00179444,2.539375,1.695697816,2.316391532,90.00000001 +30.61,50.425,-2.591525811,49.1084,0,10.00090612,2.5,1.796193868,2.240688796,90.00000001 +30.62,50.425,-2.591524404,49.0836,0,9.999573661,2.46,1.896314748,2.163032159,90.00000001 +30.63,50.425,-2.591522997,49.0592,0,9.998685345,2.42,1.996039656,2.083489345,90.00000001 +30.64,50.425,-2.59152159,49.0352,0,9.998685307,2.38,2.095347738,2.002129682,90.00000001 +30.65,50.425,-2.591520183,49.0116,0,9.99957355,2.3396875,2.194218194,1.919024159,90.00000001 +30.66,50.425,-2.591518776,48.9884,0,10.00068386,2.2978125,2.292630457,1.834245198,90.00000001 +30.67,50.425,-2.591517368,48.9656,0,10.00068383,2.253125,2.390563898,1.747866711,90.00000001 +30.68,50.425,-2.591515961,48.9433,0,9.999573442,2.2065625,2.487998064,1.659964099,90.00000001 +30.69,50.425,-2.591514554,48.9215,0,9.998907199,2.16,2.584912729,1.570613967,90.00000001 +30.7,50.425,-2.591513147,48.9001,0,9.999573375,2.1134375,2.681287496,1.479894236,90.00000001 +30.71,50.425,-2.59151174,48.8792,0,10.00068369,2.06625,2.777102369,1.387884032,90.00000001 +30.72,50.425,-2.591510332,48.8588,0,10.00068366,2.018125,2.872337236,1.294663513,90.00000001 +30.73,50.425,-2.591508925,48.8388,0,9.99957328,1.968125,2.966972274,1.200314094,90.00000001 +30.74,50.425,-2.591507518,48.8194,0,9.99890704,1.9165625,3.060987658,1.104917939,90.00000001 +30.75,50.425,-2.591506111,48.8005,0,9.999573219,1.8653125,3.154363851,1.008558298,90.00000001 +30.76,50.425,-2.591504704,48.7821,0,10.00068354,1.8146875,3.247081256,0.911319224,90.00000001 +30.77,50.425,-2.591503296,48.7642,0,10.00090558,1.763125,3.339120566,0.813285401,90.00000001 +30.78,50.425,-2.591501889,48.7468,0,10.00068348,1.7096875,3.430462529,0.71454237,90.00000001 +30.79,50.425,-2.591500482,48.73,0,10.00090553,1.655,3.521088123,0.615176305,90.00000001 +30.8,50.425,-2.591499074,48.7137,0,10.00068343,1.6,3.610978383,0.515273779,90.00000001 +30.81,50.425,-2.591497667,48.698,0,9.999573059,1.5446875,3.700114458,0.414921883,90.00000001 +30.82,50.425,-2.59149626,48.6828,0,9.998906827,1.488125,3.7884779,0.314208221,90.00000001 +30.83,50.425,-2.591494853,48.6682,0,9.999573013,1.43,3.876050145,0.213220571,90.00000001 +30.84,50.425,-2.591493446,48.6542,0,10.00068334,1.371875,3.962812915,0.112046939,90.00000001 +30.85,50.425,-2.591492038,48.6408,0,10.00068332,1.3146875,4.048748047,0.010775617,90.00000001 +30.86,50.425,-2.591490631,48.6279,0,9.999572949,1.2565625,4.133837722,-0.090505044,90.00000001 +30.87,50.425,-2.591489224,48.6156,0,9.998684652,1.1965625,4.218064065,-0.191706865,90.00000001 +30.88,50.425,-2.591487817,48.604,0,9.998684634,1.136875,4.301409543,-0.292741441,90.00000001 +30.89,50.425,-2.59148641,48.5929,0,9.999572894,1.078125,4.383856737,-0.393520821,90.00000001 +30.9,50.425,-2.591485003,48.5824,0,10.00068323,1.0178125,4.465388402,-0.493956999,90.00000001 +30.91,50.425,-2.591483595,48.5725,0,10.00068321,0.955,4.545987521,-0.593962428,90.00000001 +30.92,50.425,-2.591482188,48.5633,0,9.999572848,0.891875,4.625637249,-0.693449903,90.00000001 +30.93,50.425,-2.591480781,48.5547,0,9.998906626,0.8303125,4.704321027,-0.792332735,90.00000001 +30.94,50.425,-2.591479374,48.5467,0,9.999572822,0.7696875,4.782022298,-0.890524638,90.00000001 +30.95,50.425,-2.591477967,48.5393,0,10.00090523,0.708125,4.85872496,-0.987939953,90.00000001 +30.96,50.425,-2.591476559,48.5325,0,10.0017935,0.645,4.934412914,-1.08449377,90.00000001 +30.97,50.425,-2.591475152,48.5264,0,10.00179349,0.5815625,5.009070403,-1.180101919,90.00000001 +30.98,50.425,-2.591473744,48.5209,0,10.0009052,0.518125,5.082681786,-1.274680979,90.00000001 +30.99,50.425,-2.591472337,48.516,0,9.999572774,0.4534375,5.155231708,-1.368148501,90.00000001 +31,50.425,-2.59147093,48.5118,0,9.998684488,0.3884375,5.226705041,-1.460422953,90.00000001 +31.01,50.425,-2.591469523,48.5083,0,9.998684483,0.325,5.29708689,-1.551423949,90.00000001 +31.02,50.425,-2.591468116,48.5053,0,9.999572757,0.2615625,5.366362415,-1.641072019,90.00000001 +31.03,50.425,-2.591466709,48.503,0,10.0006831,0.1965625,5.434517292,-1.729289128,90.00000001 +31.04,50.425,-2.591465301,48.5014,0,10.0006831,0.131875,5.501537254,-1.815998211,90.00000001 +31.05,50.425,-2.591463894,48.5004,0,9.99957275,0.0684375,5.567408321,-1.901123754,90.00000001 +31.06,50.425,-2.591462487,48.5,0,9.99890654,0.0046875,5.632116627,-1.984591444,90.00000001 +31.07,50.425,-2.59146108,48.5003,0,9.999572749,-0.06,5.695648766,-2.066328571,90.00000001 +31.08,50.425,-2.591459673,48.5012,0,10.0006831,-0.125,5.757991444,-2.146263804,90.00000001 +31.09,50.425,-2.591458265,48.5028,0,10.0006831,-0.19,5.819131656,-2.22432747,90.00000001 +31.1,50.425,-2.591456858,48.505,0,9.999572757,-0.2546875,5.879056624,-2.300451502,90.00000001 +31.11,50.425,-2.591455451,48.5079,0,9.998684483,-0.3184375,5.937753801,-2.374569552,90.00000001 +31.12,50.425,-2.591454044,48.5114,0,9.998684488,-0.3815625,5.995210983,-2.446616875,90.00000001 +31.13,50.425,-2.591452637,48.5155,0,9.999572773,-0.445,6.05141608,-2.516530732,90.00000001 +31.14,50.425,-2.59145123,48.5203,0,10.0009052,-0.5084375,6.106357461,-2.584250161,90.00000001 +31.15,50.425,-2.591449822,48.5257,0,10.00179349,-0.5715625,6.16002361,-2.649716032,90.00000001 +31.16,50.425,-2.591448415,48.5317,0,10.00179349,-0.6353125,6.212403355,-2.712871336,90.00000001 +31.17,50.425,-2.591447007,48.5384,0,10.00090523,-0.6996875,6.263485636,-2.773661012,90.00000001 +31.18,50.425,-2.5914456,48.5457,0,9.999572821,-0.763125,6.313259912,-2.832031947,90.00000001 +31.19,50.425,-2.591444193,48.5537,0,9.998906625,-0.825,6.361715755,-2.887933377,90.00000001 +31.2,50.425,-2.591442786,48.5622,0,9.999572847,-0.8865625,6.408843023,-2.941316427,90.00000001 +31.21,50.425,-2.591441379,48.5714,0,10.00068321,-0.9484375,6.454631862,-2.992134632,90.00000001 +31.22,50.425,-2.591439971,48.5812,0,10.00068322,-1.0096875,6.499072761,-3.040343645,90.00000001 +31.23,50.425,-2.591438564,48.5916,0,9.999572892,-1.07,6.542156437,-3.085901468,90.00000001 +31.24,50.425,-2.591437157,48.6026,0,9.998684631,-1.13,6.58387378,-3.128768279,90.00000001 +31.25,50.425,-2.59143575,48.6142,0,9.99868465,-1.1896875,6.624216254,-3.16890678,90.00000001 +31.26,50.425,-2.591434343,48.6264,0,9.999572947,-1.2484375,6.663175322,-3.206281963,90.00000001 +31.27,50.425,-2.591432936,48.6392,0,10.00068331,-1.3065625,6.700742846,-3.240861226,90.00000001 +31.28,50.425,-2.591431528,48.6525,0,10.00068334,-1.365,6.736911036,-3.272614375,90.00000001 +31.29,50.425,-2.591430121,48.6665,0,9.999573009,-1.4234375,6.771672271,-3.301513794,90.00000001 +31.3,50.425,-2.591428714,48.681,0,9.998906824,-1.48125,6.805019332,-3.327534214,90.00000001 +31.31,50.425,-2.591427307,48.6961,0,9.999573056,-1.538125,6.836945285,-3.350653003,90.00000001 +31.32,50.425,-2.5914259,48.7118,0,10.00068343,-1.593125,6.867443427,-3.370849937,90.00000001 +31.33,50.425,-2.591424492,48.728,0,10.00090552,-1.646875,6.896507399,-3.388107484,90.00000001 +31.34,50.425,-2.591423085,48.7447,0,10.00068348,-1.7015625,6.924131069,-3.402410516,90.00000001 +31.35,50.425,-2.591421678,48.762,0,10.00090558,-1.7565625,6.950308766,-3.4137466,90.00000001 +31.36,50.425,-2.59142027,48.7799,0,10.00068354,-1.8096875,6.975034989,-3.422105882,90.00000001 +31.37,50.425,-2.591418863,48.7982,0,9.999573216,-1.86125,6.998304524,-3.427480971,90.00000001 +31.38,50.425,-2.591417456,48.8171,0,9.998907036,-1.911875,7.020112615,-3.429867283,90.00000001 +31.39,50.425,-2.591416049,48.8365,0,9.999573275,-1.9615625,7.040454623,-3.429262698,90.00000001 +31.4,50.425,-2.591414642,48.8563,0,10.00068365,-2.0115625,7.059326305,-3.425667789,90.00000001 +31.41,50.425,-2.591413234,48.8767,0,10.00068369,-2.0615625,7.07672371,-3.419085593,90.00000001 +31.42,50.425,-2.591411827,48.8976,0,9.999573371,-2.109375,7.092643285,-3.409521896,90.00000001 +31.43,50.425,-2.59141042,48.9189,0,9.998907195,-2.155,7.107081593,-3.396985064,90.00000001 +31.44,50.425,-2.591409013,48.9407,0,9.999573438,-2.2,7.12003571,-3.381485982,90.00000001 +31.45,50.425,-2.591407606,48.9629,0,10.00068382,-2.245,7.131502945,-3.363038231,90.00000001 +31.46,50.425,-2.591406198,48.9856,0,10.00068386,-2.29,7.141480775,-3.341657852,90.00000001 +31.47,50.425,-2.591404791,49.0087,0,9.999573545,-2.334375,7.149967254,-3.317363525,90.00000001 +31.48,50.425,-2.591403384,49.0323,0,9.998907373,-2.3765625,7.156960548,-3.290176391,90.00000001 +31.49,50.425,-2.591401977,49.0563,0,9.999573619,-2.4165625,7.162459167,-3.260120114,90.00000001 +31.5,50.425,-2.59140057,49.0806,0,10.00068401,-2.4565625,7.166462022,-3.227221049,90.00000001 +31.51,50.425,-2.591399162,49.1054,0,10.00090611,-2.4965625,7.168968254,-3.19150773,90.00000001 +31.52,50.425,-2.591397755,49.1306,0,10.00068408,-2.534375,7.169977347,-3.153011441,90.00000001 +31.53,50.425,-2.591396348,49.1561,0,10.00090619,-2.57,7.169489072,-3.111765642,90.00000001 +31.54,50.425,-2.59139494,49.182,0,10.00068416,-2.605,7.167503545,-3.067806314,90.00000001 +31.55,50.425,-2.591393533,49.2082,0,9.999573856,-2.64,7.164021164,-3.021171847,90.00000001 +31.56,50.425,-2.591392126,49.2348,0,9.99868562,-2.6746875,7.159042677,-2.971902862,90.00000001 +31.57,50.425,-2.591390719,49.2617,0,9.998685662,-2.7078125,7.152569113,-2.920042333,90.00000001 +31.58,50.425,-2.591389312,49.289,0,9.999573983,-2.738125,7.144601848,-2.865635464,90.00000001 +31.59,50.425,-2.591387905,49.3165,0,10.00068437,-2.7665625,7.135142544,-2.808729754,90.00000001 +31.6,50.425,-2.591386497,49.3443,0,10.00068442,-2.7953125,7.124193092,-2.749374764,90.00000001 +31.61,50.425,-2.59138509,49.3724,0,9.999574113,-2.824375,7.111755897,-2.687622289,90.00000001 +31.62,50.425,-2.591383683,49.4008,0,9.998907949,-2.8515625,7.097833481,-2.623526131,90.00000001 +31.63,50.425,-2.591382276,49.4295,0,9.999574204,-2.87625,7.082428766,-2.557142267,90.00000001 +31.64,50.425,-2.591380869,49.4583,0,10.0006846,-2.8996875,7.06554496,-2.488528508,90.00000001 +31.65,50.425,-2.591379461,49.4875,0,10.00068464,-2.921875,7.047185616,-2.417744787,90.00000001 +31.66,50.425,-2.591378054,49.5168,0,9.999796409,-2.9428125,7.027354573,-2.344852695,90.00000001 +31.67,50.425,-2.591376647,49.5463,0,9.999796456,-2.9634375,7.006055955,-2.269915831,90.00000001 +31.68,50.425,-2.59137524,49.5761,0,10.00068478,-2.9828125,6.983294233,-2.192999628,90.00000001 +31.69,50.425,-2.591373832,49.606,0,10.00068483,-2.9996875,6.959074104,-2.114171063,90.00000001 +31.7,50.425,-2.591372425,49.6361,0,9.999796596,-3.0153125,6.933400667,-2.033498892,90.00000001 +31.71,50.425,-2.591371018,49.6663,0,9.999796643,-3.03125,6.906279309,-1.951053474,90.00000001 +31.72,50.425,-2.591369611,49.6967,0,10.00068497,-3.04625,6.877715586,-1.866906772,90.00000001 +31.73,50.425,-2.591368203,49.7273,0,10.00068502,-3.058125,6.847715631,-1.781132068,90.00000001 +31.74,50.425,-2.591366796,49.7579,0,9.999574717,-3.068125,6.816285573,-1.69380419,90.00000001 +31.75,50.425,-2.591365389,49.7886,0,9.998908556,-3.0784375,6.783432001,-1.604999284,90.00000001 +31.76,50.425,-2.591363982,49.8195,0,9.999574813,-3.0878125,6.749161848,-1.514794757,90.00000001 +31.77,50.425,-2.591362575,49.8504,0,10.00068521,-3.0946875,6.713482162,-1.423269333,90.00000001 +31.78,50.425,-2.591361167,49.8814,0,10.00068526,-3.1,6.676400505,-1.330502825,90.00000001 +31.79,50.425,-2.59135976,49.9124,0,9.999574959,-3.1046875,6.637924556,-1.236576077,90.00000001 +31.8,50.425,-2.591358353,49.9435,0,9.998686729,-3.108125,6.598062335,-1.141571023,90.00000001 +31.81,50.425,-2.591356946,49.9746,0,9.998686777,-3.109375,6.556822208,-1.045570512,90.00000001 +31.82,50.425,-2.591355539,50.0057,0,9.999575104,-3.1084375,6.514212769,-0.948658254,90.00000001 +31.83,50.425,-2.591354132,50.0368,0,10.0006855,-3.1065625,6.470242957,-0.850918701,90.00000001 +31.84,50.425,-2.591352724,50.0678,0,10.00090762,-3.105,6.424921881,-0.752437168,90.00000001 +31.85,50.425,-2.591351317,50.0989,0,10.0006856,-3.1028125,6.378259052,-0.653299541,90.00000001 +31.86,50.425,-2.59134991,50.1299,0,10.00090772,-3.0978125,6.330264154,-0.553592165,90.00000001 +31.87,50.425,-2.591348502,50.1609,0,10.0006857,-3.0903125,6.280947327,-0.453402072,90.00000001 +31.88,50.425,-2.591347095,50.1917,0,9.999797465,-3.0828125,6.230318771,-0.352816581,90.00000001 +31.89,50.425,-2.591345688,50.2225,0,9.999797513,-3.075,6.178389142,-0.251923469,90.00000001 +31.9,50.425,-2.591344281,50.2533,0,10.00068584,-3.0646875,6.125169213,-0.150810628,90.00000001 +31.91,50.425,-2.591342873,50.2838,0,10.00068589,-3.053125,6.070670097,-0.04956635,90.00000001 +31.92,50.425,-2.591341466,50.3143,0,9.999575586,-3.0415625,6.014903198,0.051721244,90.00000001 +31.93,50.425,-2.591340059,50.3447,0,9.998687355,-3.0278125,5.957880147,0.152963688,90.00000001 +31.94,50.425,-2.591338652,50.3749,0,9.998687403,-3.01125,5.899612917,0.254072748,90.00000001 +31.95,50.425,-2.591337245,50.4049,0,9.999575729,-2.9934375,5.840113599,0.354960246,90.00000001 +31.96,50.425,-2.591335838,50.4348,0,10.00068612,-2.975,5.779394684,0.455538174,90.00000001 +31.97,50.425,-2.59133443,50.4644,0,10.00068617,-2.95625,5.717468775,0.555718927,90.00000001 +31.98,50.425,-2.591333023,50.4939,0,9.999575867,-2.9365625,5.654348879,0.655415074,90.00000001 +31.99,50.425,-2.591331616,50.5232,0,9.998909704,-2.914375,5.590048118,0.754539694,90.00000001 +32,50.425,-2.591330209,50.5522,0,9.999575959,-2.89,5.524579955,0.85300633,90.00000001 +32.01,50.425,-2.591328802,50.581,0,10.00068635,-2.865,5.457958027,0.950729095,90.00000001 +32.02,50.425,-2.591327394,50.6095,0,10.00090847,-2.84,5.390196314,1.047622847,90.00000001 +32.03,50.425,-2.591325987,50.6378,0,10.00068644,-2.8146875,5.32130891,1.143603075,90.00000001 +32.04,50.425,-2.59132458,50.6658,0,10.00090855,-2.7878125,5.251310255,1.238586071,90.00000001 +32.05,50.425,-2.591323172,50.6936,0,10.00068653,-2.758125,5.180214902,1.332488983,90.00000001 +32.06,50.425,-2.591321765,50.721,0,9.999576223,-2.7265625,5.10803769,1.425229937,90.00000001 +32.07,50.425,-2.591320358,50.7481,0,9.998910057,-2.695,5.034793802,1.516728031,90.00000001 +32.08,50.425,-2.591318951,50.7749,0,9.999576308,-2.6628125,4.960498422,1.606903567,90.00000001 +32.09,50.425,-2.591317544,50.8014,0,10.0006867,-2.628125,4.885167077,1.695677877,90.00000001 +32.1,50.425,-2.591316136,50.8275,0,10.00068674,-2.5915625,4.80881558,1.782973497,90.00000001 +32.11,50.425,-2.591314729,50.8532,0,9.99957643,-2.5553125,4.731459804,1.868714339,90.00000001 +32.12,50.425,-2.591313322,50.8786,0,9.998910261,-2.5196875,4.653115904,1.952825632,90.00000001 +32.13,50.425,-2.591311915,50.9036,0,9.999576509,-2.4828125,4.573800325,2.035234037,90.00000001 +32.14,50.425,-2.591310508,50.9283,0,10.0006869,-2.443125,4.493529511,2.115867706,90.00000001 +32.15,50.425,-2.5913091,50.9525,0,10.00068693,-2.4015625,4.412320249,2.194656278,90.00000001 +32.16,50.425,-2.591307693,50.9763,0,9.999576622,-2.36,4.330189614,2.271531057,90.00000001 +32.17,50.425,-2.591306286,50.9997,0,9.998688381,-2.318125,4.247154622,2.346425063,90.00000001 +32.18,50.425,-2.591304879,51.0227,0,9.998688417,-2.2746875,4.163232692,2.41927298,90.00000001 +32.19,50.425,-2.591303472,51.0452,0,9.99957673,-2.23,4.078441298,2.490011209,90.00000001 +32.2,50.425,-2.591302065,51.0673,0,10.00090918,-2.185,3.992798145,2.558578156,90.00000001 +32.21,50.425,-2.591300657,51.0889,0,10.0017975,-2.139375,3.906321224,2.624913949,90.00000001 +32.22,50.425,-2.59129925,51.1101,0,10.00179753,-2.0915625,3.819028468,2.688960776,90.00000001 +32.23,50.425,-2.591297842,51.1308,0,10.00090928,-2.0415625,3.730938155,2.750662773,90.00000001 +32.24,50.425,-2.591296435,51.1509,0,9.999576896,-1.991875,3.642068734,2.809966197,90.00000001 +32.25,50.425,-2.591295028,51.1706,0,9.998910717,-1.9434375,3.552438655,2.866819252,90.00000001 +32.26,50.425,-2.591293621,51.1898,0,9.999576956,-1.894375,3.462066709,2.921172434,90.00000001 +32.27,50.425,-2.591292214,51.2085,0,10.00068733,-1.843125,3.370971748,2.972978247,90.00000001 +32.28,50.425,-2.591290806,51.2267,0,10.00068736,-1.79,3.279172851,3.022191655,90.00000001 +32.29,50.425,-2.591289399,51.2443,0,9.999577042,-1.7365625,3.186689098,3.068769628,90.00000001 +32.3,50.425,-2.591287992,51.2614,0,9.998688789,-1.683125,3.093539854,3.112671603,90.00000001 +32.31,50.425,-2.591286585,51.278,0,9.998688815,-1.628125,2.999744543,3.153859247,90.00000001 +32.32,50.425,-2.591285178,51.294,0,9.999577119,-1.5715625,2.905322818,3.192296693,90.00000001 +32.33,50.425,-2.591283771,51.3094,0,10.00068749,-1.5153125,2.81029433,3.227950425,90.00000001 +32.34,50.425,-2.591282363,51.3243,0,10.00068752,-1.4596875,2.714678961,3.260789329,90.00000001 +32.35,50.425,-2.591280956,51.3386,0,9.999577189,-1.403125,2.61849665,3.290784758,90.00000001 +32.36,50.425,-2.591279549,51.3524,0,9.998911001,-1.345,2.521767509,3.317910585,90.00000001 +32.37,50.425,-2.591278142,51.3655,0,9.999577231,-1.2865625,2.424511705,3.342143205,90.00000001 +32.38,50.425,-2.591276735,51.3781,0,10.0006876,-1.2284375,2.326749578,3.36346136,90.00000001 +32.39,50.425,-2.591275327,51.3901,0,10.00090969,-1.1696875,2.228501582,3.381846545,90.00000001 +32.4,50.425,-2.59127392,51.4015,0,10.00068764,-1.1096875,2.129788116,3.397282715,90.00000001 +32.41,50.425,-2.591272513,51.4123,0,10.00090972,-1.0484375,2.03062992,3.40975635,90.00000001 +32.42,50.425,-2.591271105,51.4225,0,10.00068767,-0.9865625,1.931047678,3.419256678,90.00000001 +32.43,50.425,-2.591269698,51.432,0,9.999577335,-0.925,1.831062131,3.425775391,90.00000001 +32.44,50.425,-2.591268291,51.441,0,9.99891114,-0.8634375,1.730694192,3.429306701,90.00000001 +32.45,50.425,-2.591266884,51.4493,0,9.999577362,-0.80125,1.629964831,3.429847688,90.00000001 +32.46,50.425,-2.591265477,51.457,0,10.00068772,-0.7384375,1.528895019,3.427397721,90.00000001 +32.47,50.425,-2.591264069,51.4641,0,10.00068773,-0.675,1.427506012,3.421959033,90.00000001 +32.48,50.425,-2.591262662,51.4705,0,9.999577395,-0.611875,1.325818838,3.413536382,90.00000001 +32.49,50.425,-2.591261255,51.4763,0,9.998911195,-0.55,1.223854753,3.402137043,90.00000001 +32.5,50.425,-2.591259848,51.4815,0,9.999577413,-0.488125,1.121635129,3.387770985,90.00000001 +32.51,50.425,-2.591258441,51.4861,0,10.00068777,-0.4246875,1.019181222,3.370450758,90.00000001 +32.52,50.425,-2.591257033,51.49,0,10.00068777,-0.36,0.916514519,3.350191486,90.00000001 +32.53,50.425,-2.591255626,51.4933,0,9.999577431,-0.295,0.813656391,3.327010759,90.00000001 +32.54,50.425,-2.591254219,51.4959,0,9.998689157,-0.23,0.710628323,3.300928804,90.00000001 +32.55,50.425,-2.591252812,51.4979,0,9.99868916,-0.165,0.60745186,3.271968423,90.00000001 +32.56,50.425,-2.591251405,51.4992,0,9.99957744,-0.1,0.504148543,3.240154827,90.00000001 +32.57,50.425,-2.591249998,51.4999,0,10.00090986,-0.0353125,0.400739975,3.205515746,90.00000001 +32.58,50.425,-2.59124859,51.4999,0,10.00179814,0.0284375,0.297247697,3.168081434,90.00000001 +32.59,50.425,-2.591247183,51.4993,0,10.00179814,0.0915625,0.19369331,3.127884492,90.00000001 +32.6,50.425,-2.591245775,51.4981,0,10.00090986,0.1553125,0.09009853,3.084960041,90.00000001 +32.61,50.425,-2.591244368,51.4962,0,9.999577436,0.22,-0.0135151,3.039345381,90.00000001 +32.62,50.425,-2.591242961,51.4937,0,9.998689153,0.2846875,-0.117125923,2.99108039,90.00000001 +32.63,50.425,-2.591241554,51.4905,0,9.998689147,0.3484375,-0.220712281,2.940207181,90.00000001 +32.64,50.425,-2.591240147,51.4867,0,9.99957742,0.4115625,-0.324252515,2.886770043,90.00000001 +32.65,50.425,-2.59123874,51.4823,0,10.00068776,0.4753125,-0.427725083,2.830815558,90.00000001 +32.66,50.425,-2.591237332,51.4772,0,10.00068776,0.54,-0.53110827,2.772392598,90.00000001 +32.67,50.425,-2.591235925,51.4715,0,9.999577397,0.6046875,-0.63438059,2.711552044,90.00000001 +32.68,50.425,-2.591234518,51.4651,0,9.998911178,0.668125,-0.737520384,2.648347007,90.00000001 +32.69,50.425,-2.591233111,51.4581,0,9.999577376,0.73,-0.840506167,2.582832549,90.00000001 +32.7,50.425,-2.591231704,51.4505,0,10.00068771,0.791875,-0.943316453,2.515065851,90.00000001 +32.71,50.425,-2.591230296,51.4423,0,10.0006877,0.8546875,-1.045929699,2.445105928,90.00000001 +32.72,50.425,-2.591228889,51.4334,0,9.999577338,0.9165625,-1.148324534,2.373013857,90.00000001 +32.73,50.425,-2.591227482,51.4239,0,9.998689044,0.9765625,-1.250479586,2.298852549,90.00000001 +32.74,50.425,-2.591226075,51.4139,0,9.998689027,1.036875,-1.352373483,2.222686519,90.00000001 +32.75,50.425,-2.591224668,51.4032,0,9.99957729,1.0984375,-1.453984913,2.144582288,90.00000001 +32.76,50.425,-2.591223261,51.3919,0,10.00090969,1.1596875,-1.555292732,2.064607979,90.00000001 +32.77,50.425,-2.591221853,51.38,0,10.00179795,1.2196875,-1.656275741,1.982833323,90.00000001 +32.78,50.425,-2.591220446,51.3675,0,10.00179793,1.2784375,-1.756912798,1.899329537,90.00000001 +32.79,50.425,-2.591219038,51.3544,0,10.00090963,1.3365625,-1.857183048,1.814169559,90.00000001 +32.8,50.425,-2.591217631,51.3408,0,9.999577192,1.3946875,-1.957065405,1.727427588,90.00000001 +32.81,50.425,-2.591216224,51.3265,0,9.998910961,1.451875,-2.056539015,1.639179253,90.00000001 +32.82,50.425,-2.591214817,51.3117,0,9.999577147,1.5078125,-2.155583192,1.549501561,90.00000001 +32.83,50.425,-2.59121341,51.2964,0,10.00068747,1.56375,-2.254177196,1.458472662,90.00000001 +32.84,50.425,-2.591212002,51.2804,0,10.00068745,1.6196875,-2.352300401,1.366171969,90.00000001 +32.85,50.425,-2.591210595,51.264,0,9.999577072,1.6746875,-2.44993241,1.272679924,90.00000001 +32.86,50.425,-2.591209188,51.2469,0,9.998688767,1.7284375,-2.547052767,1.178078118,90.00000001 +32.87,50.425,-2.591207781,51.2294,0,9.998688739,1.78125,-2.64364119,1.082448998,90.00000001 +32.88,50.425,-2.591206374,51.2113,0,9.99957699,1.8334375,-2.739677568,0.98587593,90.00000001 +32.89,50.425,-2.591204967,51.1927,0,10.00068731,1.885,-2.835141733,0.888443197,90.00000001 +32.9,50.425,-2.591203559,51.1736,0,10.00068728,1.9365625,-2.930013861,0.79023571,90.00000001 +32.91,50.425,-2.591202152,51.154,0,9.9995769,1.9878125,-3.02427407,0.691339183,90.00000001 +32.92,50.425,-2.591200745,51.1338,0,9.99891066,2.0365625,-3.117902707,0.591839734,90.00000001 +32.93,50.425,-2.591199338,51.1132,0,9.999576837,2.083125,-3.210880236,0.491824221,90.00000001 +32.94,50.425,-2.591197931,51.0922,0,10.00090922,2.1303125,-3.303187174,0.39137985,90.00000001 +32.95,50.425,-2.591196523,51.0706,0,10.00179747,2.178125,-3.394804329,0.29059411,90.00000001 +32.96,50.425,-2.591195116,51.0486,0,10.00179743,2.224375,-3.485712448,0.189555065,90.00000001 +32.97,50.425,-2.591193708,51.0261,0,10.00090912,2.2684375,-3.575892682,0.088350665,90.00000001 +32.98,50.425,-2.591192301,51.0032,0,9.999576665,2.31125,-3.665326123,-0.012930741,90.00000001 +32.99,50.425,-2.591190894,50.9799,0,9.998688349,2.3534375,-3.753994092,-0.114200916,90.00000001 +33,50.425,-2.591189487,50.9561,0,9.998688312,2.395,-3.84187814,-0.215371455,90.00000001 +33.01,50.425,-2.59118808,50.932,0,9.999576553,2.43625,-3.928959818,-0.316354235,90.00000001 +33.02,50.425,-2.591186673,50.9074,0,10.00068686,2.4765625,-4.015220963,-0.417061136,90.00000001 +33.03,50.425,-2.591185265,50.8824,0,10.00068682,2.5146875,-4.100643584,-0.517404323,90.00000001 +33.04,50.425,-2.591183858,50.8571,0,9.999576436,2.5515625,-4.185209863,-0.617296363,90.00000001 +33.05,50.425,-2.591182451,50.8314,0,9.998910187,2.588125,-4.268902152,-0.71665011,90.00000001 +33.06,50.425,-2.591181044,50.8053,0,9.999576355,2.623125,-4.351702861,-0.815378931,90.00000001 +33.07,50.425,-2.591179637,50.7789,0,10.00068666,2.6565625,-4.433594802,-0.913396712,90.00000001 +33.08,50.425,-2.591178229,50.7522,0,10.00068662,2.69,-4.514560843,-1.010617967,90.00000001 +33.09,50.425,-2.591176822,50.7251,0,9.99957623,2.7228125,-4.594584083,-1.106958013,90.00000001 +33.1,50.425,-2.591175415,50.6977,0,9.998687908,2.753125,-4.673647789,-1.202332739,90.00000001 +33.11,50.425,-2.591174008,50.67,0,9.998687865,2.7815625,-4.75173552,-1.29665901,90.00000001 +33.12,50.425,-2.591172601,50.6421,0,9.999576099,2.8096875,-4.82883083,-1.389854549,90.00000001 +33.13,50.425,-2.591171194,50.6138,0,10.00090847,2.8365625,-4.904917734,-1.481838167,90.00000001 +33.14,50.425,-2.591169786,50.5853,0,10.00179671,2.8615625,-4.979980305,-1.572529594,90.00000001 +33.15,50.425,-2.591168379,50.5566,0,10.00179666,2.8865625,-5.054002899,-1.661849704,90.00000001 +33.16,50.425,-2.591166971,50.5276,0,10.00090834,2.91125,-5.126969991,-1.749720688,90.00000001 +33.17,50.425,-2.591165564,50.4983,0,9.999575874,2.933125,-5.198866397,-1.836065886,90.00000001 +33.18,50.425,-2.591164157,50.4689,0,9.99890962,2.953125,-5.269677105,-1.920810011,90.00000001 +33.19,50.425,-2.59116275,50.4393,0,9.999575783,2.973125,-5.339387276,-2.003879208,90.00000001 +33.2,50.425,-2.591161343,50.4094,0,10.00068608,2.9915625,-5.407982413,-2.085200942,90.00000001 +33.21,50.425,-2.591159935,50.3794,0,10.00068604,3.0078125,-5.475448136,-2.164704336,90.00000001 +33.22,50.425,-2.591158528,50.3493,0,9.999575642,3.0234375,-5.541770407,-2.242320064,90.00000001 +33.23,50.425,-2.591157121,50.3189,0,9.998687315,3.038125,-5.606935304,-2.317980516,90.00000001 +33.24,50.425,-2.591155714,50.2885,0,9.998687268,3.05125,-5.670929304,-2.39161963,90.00000001 +33.25,50.425,-2.591154307,50.2579,0,9.999575499,3.0634375,-5.733739,-2.463173178,90.00000001 +33.26,50.425,-2.5911529,50.2272,0,10.0006858,3.074375,-5.795351272,-2.532578879,90.00000001 +33.27,50.425,-2.591151492,50.1964,0,10.00068575,3.083125,-5.855753285,-2.599776056,90.00000001 +33.28,50.425,-2.591150085,50.1655,0,9.999575354,3.09,-5.914932376,-2.664706212,90.00000001 +33.29,50.425,-2.591148678,50.1346,0,9.998909097,3.09625,-5.972876171,-2.727312737,90.00000001 +33.3,50.425,-2.591147271,50.1036,0,9.999575258,3.1015625,-6.029572637,-2.787540972,90.00000001 +33.31,50.425,-2.591145864,50.0725,0,10.00068556,3.1046875,-6.085009913,-2.845338434,90.00000001 +33.32,50.425,-2.591144456,50.0415,0,10.00090758,3.1065625,-6.139176426,-2.900654759,90.00000001 +33.33,50.425,-2.591143049,50.0104,0,10.00068546,3.1084375,-6.192060832,-2.953441647,90.00000001 +33.34,50.425,-2.591141642,49.9793,0,10.00090748,3.109375,-6.243652129,-3.003653032,90.00000001 +33.35,50.425,-2.591140234,49.9482,0,10.00068536,3.108125,-6.293939489,-3.051245256,90.00000001 +33.36,50.425,-2.591138827,49.9171,0,9.999574966,3.1046875,-6.342912426,-3.096176721,90.00000001 +33.37,50.425,-2.59113742,49.8861,0,9.998908708,3.1,-6.390560742,-3.138408294,90.00000001 +33.38,50.425,-2.591136013,49.8551,0,9.999574869,3.0946875,-6.436874525,-3.177903134,90.00000001 +33.39,50.425,-2.591134606,49.8242,0,10.00068517,3.088125,-6.481843977,-3.214626749,90.00000001 +33.4,50.425,-2.591133198,49.7933,0,10.00068512,3.0796875,-6.525459816,-3.248547169,90.00000001 +33.41,50.425,-2.591131791,49.7626,0,9.999574724,3.07,-6.567712875,-3.279634827,90.00000001 +33.42,50.425,-2.591130384,49.7319,0,9.998908467,3.0596875,-6.608594388,-3.307862624,90.00000001 +33.43,50.425,-2.591128977,49.7014,0,9.999574629,3.0478125,-6.64809576,-3.333205866,90.00000001 +33.44,50.425,-2.59112757,49.6709,0,10.00068493,3.0334375,-6.686208741,-3.355642549,90.00000001 +33.45,50.425,-2.591126162,49.6407,0,10.00068488,3.018125,-6.722925423,-3.375153022,90.00000001 +33.46,50.425,-2.591124755,49.6106,0,9.999574486,3.003125,-6.758238073,-3.391720326,90.00000001 +33.47,50.425,-2.591123348,49.5806,0,9.99890823,2.98625,-6.792139355,-3.405329965,90.00000001 +33.48,50.425,-2.591121941,49.5508,0,9.999574393,2.9665625,-6.824622223,-3.415970192,90.00000001 +33.49,50.425,-2.591120534,49.5213,0,10.00068469,2.9465625,-6.855679859,-3.423631554,90.00000001 +33.5,50.425,-2.591119126,49.4919,0,10.00090672,2.9265625,-6.88530573,-3.42830752,90.00000001 +33.51,50.425,-2.591117719,49.4627,0,10.0006846,2.904375,-6.913493707,-3.429993907,90.00000001 +33.52,50.425,-2.591116312,49.4338,0,10.00090663,2.8796875,-6.940237887,-3.428689282,90.00000001 +33.53,50.425,-2.591114904,49.4051,0,10.00068451,2.8534375,-6.965532713,-3.424394849,90.00000001 +33.54,50.425,-2.591113497,49.3767,0,9.99957412,2.8265625,-6.989372857,-3.417114217,90.00000001 +33.55,50.425,-2.59111209,49.3486,0,9.998685797,2.8,-7.01175339,-3.40685386,90.00000001 +33.56,50.425,-2.591110683,49.3207,0,9.998685754,2.7728125,-7.032669558,-3.393622661,90.00000001 +33.57,50.425,-2.591109276,49.2931,0,9.99957399,2.743125,-7.052117064,-3.377432191,90.00000001 +33.58,50.425,-2.591107869,49.2658,0,10.0006843,2.7115625,-7.070091838,-3.358296547,90.00000001 +33.59,50.425,-2.591106461,49.2389,0,10.00068425,2.6796875,-7.086590101,-3.3362324,90.00000001 +33.6,50.425,-2.591105054,49.2122,0,9.999573863,2.6465625,-7.101608413,-3.311259004,90.00000001 +33.61,50.425,-2.591103647,49.1859,0,9.998907612,2.61125,-7.115143682,-3.283398186,90.00000001 +33.62,50.425,-2.59110224,49.16,0,9.999573781,2.575,-7.127192984,-3.252674126,90.00000001 +33.63,50.425,-2.591100833,49.1344,0,10.00068409,2.5384375,-7.137753914,-3.219113754,90.00000001 +33.64,50.425,-2.591099425,49.1092,0,10.00068405,2.50125,-7.14682418,-3.182746232,90.00000001 +33.65,50.425,-2.591098018,49.0844,0,9.999795732,2.463125,-7.154401948,-3.143603302,90.00000001 +33.66,50.425,-2.591096611,49.0599,0,9.999795694,2.423125,-7.160485614,-3.101719113,90.00000001 +33.67,50.425,-2.591095204,49.0359,0,10.00068394,2.3815625,-7.165073917,-3.057130163,90.00000001 +33.68,50.425,-2.591093796,49.0123,0,10.0006839,2.34,-7.168165826,-3.009875411,90.00000001 +33.69,50.425,-2.591092389,48.9891,0,9.999795584,2.2978125,-7.169760826,-2.95999594,90.00000001 +33.7,50.425,-2.591090982,48.9663,0,9.999795548,2.253125,-7.169858458,-2.907535294,90.00000001 +33.71,50.425,-2.591089575,48.944,0,10.00068379,2.206875,-7.16845878,-2.85253931,90.00000001 +33.72,50.425,-2.591088167,48.9222,0,10.00068376,2.1615625,-7.165562077,-2.795055829,90.00000001 +33.73,50.425,-2.59108676,48.9008,0,9.999573376,2.1165625,-7.161168923,-2.735134986,90.00000001 +33.74,50.425,-2.591085353,48.8798,0,9.998907135,2.069375,-7.155280235,-2.672829092,90.00000001 +33.75,50.425,-2.591083946,48.8594,0,9.999573311,2.02,-7.147897273,-2.608192463,90.00000001 +33.76,50.425,-2.591082539,48.8394,0,10.00068363,1.97,-7.139021583,-2.54128142,90.00000001 +33.77,50.425,-2.591081131,48.82,0,10.0006836,1.9196875,-7.128655001,-2.472154406,90.00000001 +33.78,50.425,-2.591079724,48.801,0,9.99957322,1.8684375,-7.116799644,-2.400871581,90.00000001 +33.79,50.425,-2.591078317,48.7826,0,9.998684913,1.81625,-7.103458036,-2.327495168,90.00000001 +33.8,50.425,-2.59107691,48.7647,0,9.998684885,1.7634375,-7.088632982,-2.252089166,90.00000001 +33.81,50.425,-2.591075503,48.7473,0,9.999573136,1.7096875,-7.072327577,-2.174719295,90.00000001 +33.82,50.425,-2.591074096,48.7305,0,10.00068346,1.655,-7.054545202,-2.09545299,90.00000001 +33.83,50.425,-2.591072688,48.7142,0,10.0009055,1.6,-7.03528958,-2.014359466,90.00000001 +33.84,50.425,-2.591071281,48.6985,0,10.00068341,1.545,-7.014564722,-1.931509425,90.00000001 +33.85,50.425,-2.591069874,48.6833,0,10.00090545,1.4896875,-6.992374926,-1.846975003,90.00000001 +33.86,50.425,-2.591068466,48.6687,0,10.00068336,1.433125,-6.96872489,-1.760830053,90.00000001 +33.87,50.425,-2.591067059,48.6546,0,9.99979506,1.375,-6.943619541,-1.673149577,90.00000001 +33.88,50.425,-2.591065652,48.6412,0,9.999795039,1.3165625,-6.917064093,-1.584010121,90.00000001 +33.89,50.425,-2.591064245,48.6283,0,10.0006833,1.2584375,-6.889064104,-1.493489379,90.00000001 +33.9,50.425,-2.591062837,48.616,0,10.00068328,1.1996875,-6.859625418,-1.401666303,90.00000001 +33.91,50.425,-2.59106143,48.6043,0,9.999572912,1.14,-6.828754166,-1.308620994,90.00000001 +33.92,50.425,-2.591060023,48.5932,0,9.998684616,1.0796875,-6.796456879,-1.214434467,90.00000001 +33.93,50.425,-2.591058616,48.5827,0,9.9986846,1.0184375,-6.762740146,-1.119189,90.00000001 +33.94,50.425,-2.591057209,48.5728,0,9.999572863,0.9565625,-6.727611187,-1.022967556,90.00000001 +33.95,50.425,-2.591055802,48.5636,0,10.0006832,0.895,-6.69107722,-0.925854075,90.00000001 +33.96,50.425,-2.591054394,48.5549,0,10.00068318,0.8334375,-6.653145925,-0.827933181,90.00000001 +33.97,50.425,-2.591052987,48.5469,0,9.999572822,0.77125,-6.613825149,-0.729290361,90.00000001 +33.98,50.425,-2.59105158,48.5395,0,9.998906601,0.7084375,-6.573123201,-0.630011615,90.00000001 +33.99,50.425,-2.591050173,48.5327,0,9.9995728,0.645,-6.531048561,-0.530183459,90.00000001 +34,50.425,-2.591048766,48.5266,0,10.00068314,0.581875,-6.487609938,-0.429892984,90.00000001 +34.01,50.425,-2.591047358,48.5211,0,10.0009052,0.52,-6.442816498,-0.329227622,90.00000001 +34.02,50.425,-2.591045951,48.5162,0,10.00068312,0.4578125,-6.396677582,-0.228275209,90.00000001 +34.03,50.425,-2.591044544,48.5119,0,10.00090519,0.393125,-6.349202758,-0.127123693,90.00000001 +34.04,50.425,-2.591043136,48.5083,0,10.00068311,0.326875,-6.300401994,-0.025861367,90.00000001 +34.05,50.425,-2.591041729,48.5054,0,9.999572757,0.261875,-6.250285491,0.075423534,90.00000001 +34.06,50.425,-2.591040322,48.5031,0,9.998906546,0.1984375,-6.198863674,0.176642716,90.00000001 +34.07,50.425,-2.591038915,48.5014,0,9.999572751,0.1346875,-6.146147317,0.277707773,90.00000001 +34.08,50.425,-2.591037508,48.5004,0,10.0006831,0.07,-6.09214742,0.378530755,90.00000001 +34.09,50.425,-2.5910361,48.5,0,10.0006831,0.0053125,-6.03687527,0.479023599,90.00000001 +34.1,50.425,-2.591034693,48.5003,0,9.99957275,-0.0584375,-5.980342384,0.579098699,90.00000001 +34.11,50.425,-2.591033286,48.5012,0,9.998906543,-0.121875,-5.922560565,0.678668852,90.00000001 +34.12,50.425,-2.591031879,48.5027,0,9.999572753,-0.1865625,-5.863541901,0.777647197,90.00000001 +34.13,50.425,-2.591030472,48.5049,0,10.0006831,-0.251875,-5.803298712,0.875947446,90.00000001 +34.14,50.425,-2.591029064,48.5078,0,10.00068311,-0.31625,-5.741843545,0.973483827,90.00000001 +34.15,50.425,-2.591027657,48.5112,0,9.999572767,-0.38,-5.67918935,1.070171315,90.00000001 +34.16,50.425,-2.59102625,48.5154,0,9.998684495,-0.4434375,-5.615349075,1.165925568,90.00000001 +34.17,50.425,-2.591024843,48.5201,0,9.998684502,-0.5065625,-5.550336069,1.260663166,90.00000001 +34.18,50.425,-2.591023436,48.5255,0,9.999572789,-0.5703125,-5.484164028,1.354301429,90.00000001 +34.19,50.425,-2.591022029,48.5315,0,10.00090522,-0.6346875,-5.416846643,1.446758712,90.00000001 +34.2,50.425,-2.591020621,48.5382,0,10.00179351,-0.698125,-5.348398011,1.537954456,90.00000001 +34.21,50.425,-2.591019214,48.5455,0,10.00179352,-0.76,-5.278832455,1.62780902,90.00000001 +34.22,50.425,-2.591017806,48.5534,0,10.00090525,-0.821875,-5.208164471,1.716244139,90.00000001 +34.23,50.425,-2.591016399,48.5619,0,9.999572846,-0.885,-5.136408841,1.803182635,90.00000001 +34.24,50.425,-2.591014992,48.5711,0,9.998684582,-0.9478125,-5.063580519,1.888548763,90.00000001 +34.25,50.425,-2.591013585,48.5809,0,9.998684596,-1.008125,-4.989694747,1.972268038,90.00000001 +34.26,50.425,-2.591012178,48.5913,0,9.999572891,-1.066875,-4.914766936,2.054267466,90.00000001 +34.27,50.425,-2.591010771,48.6022,0,10.00068326,-1.126875,-4.838812729,2.134475484,90.00000001 +34.28,50.425,-2.591009363,48.6138,0,10.00068328,-1.188125,-4.761848053,2.212822306,90.00000001 +34.29,50.425,-2.591007956,48.626,0,9.999572946,-1.248125,-4.683888837,2.289239463,90.00000001 +34.3,50.425,-2.591006549,48.6388,0,9.998906757,-1.3065625,-4.604951525,2.363660378,90.00000001 +34.31,50.425,-2.591005142,48.6521,0,9.999572987,-1.365,-4.525052503,2.436020135,90.00000001 +34.32,50.425,-2.591003735,48.6661,0,10.00068336,-1.423125,-4.444208502,2.506255651,90.00000001 +34.33,50.425,-2.591002327,48.6806,0,10.00068338,-1.4796875,-4.362436309,2.574305676,90.00000001 +34.34,50.425,-2.59100092,48.6957,0,9.999573055,-1.535,-4.279753171,2.640110853,90.00000001 +34.35,50.425,-2.590999513,48.7113,0,9.998906871,-1.59,-4.196176218,2.703613828,90.00000001 +34.36,50.425,-2.590998106,48.7275,0,9.999573104,-1.645,-4.111722927,2.764759254,90.00000001 +34.37,50.425,-2.590996699,48.7442,0,10.00068348,-1.6996875,-4.026411001,2.82349373,90.00000001 +34.38,50.425,-2.590995291,48.7615,0,10.00090558,-1.7534375,-3.940258202,2.879766035,90.00000001 +34.39,50.425,-2.590993884,48.7793,0,10.00068353,-1.8065625,-3.853282464,2.933527181,90.00000001 +34.4,50.425,-2.590992477,48.7976,0,10.00090563,-1.8596875,-3.765502121,2.984730299,90.00000001 +34.41,50.425,-2.590991069,48.8165,0,10.00068359,-1.9115625,-3.676935336,3.033330642,90.00000001 +34.42,50.425,-2.590989662,48.8359,0,9.999573274,-1.96125,-3.587600674,3.079285868,90.00000001 +34.43,50.425,-2.590988255,48.8557,0,9.998907097,-2.01,-3.497516811,3.122555869,90.00000001 +34.44,50.425,-2.590986848,48.8761,0,9.999573338,-2.0584375,-3.406702485,3.163103004,90.00000001 +34.45,50.425,-2.590985441,48.8969,0,10.00068372,-2.10625,-3.315176774,3.200891862,90.00000001 +34.46,50.425,-2.590984033,48.9182,0,10.00068375,-2.1534375,-3.222958702,3.2358895,90.00000001 +34.47,50.425,-2.590982626,48.94,0,9.999573437,-2.1996875,-3.130067575,3.268065434,90.00000001 +34.48,50.425,-2.590981219,48.9622,0,9.998685194,-2.245,-3.036522762,3.297391477,90.00000001 +34.49,50.425,-2.590979812,48.9849,0,9.99868523,-2.2896875,-2.942343798,3.323842245,90.00000001 +34.5,50.425,-2.590978405,49.008,0,9.999573544,-2.333125,-2.847550394,3.347394478,90.00000001 +34.51,50.425,-2.590976998,49.0316,0,10.00068393,-2.375,-2.752162261,3.368027777,90.00000001 +34.52,50.425,-2.59097559,49.0555,0,10.00068397,-2.41625,-2.65619945,3.385724094,90.00000001 +34.53,50.425,-2.590974183,49.0799,0,9.999573657,-2.4565625,-2.559681845,3.400468017,90.00000001 +34.54,50.425,-2.590972776,49.1047,0,9.998907487,-2.4946875,-2.462629727,3.412246711,90.00000001 +34.55,50.425,-2.590971369,49.1298,0,9.999573735,-2.5315625,-2.365063323,3.421049864,90.00000001 +34.56,50.425,-2.590969962,49.1553,0,10.00090619,-2.5684375,-2.267003028,3.426869797,90.00000001 +34.57,50.425,-2.590968554,49.1812,0,10.00179451,-2.6046875,-2.168469242,3.429701412,90.00000001 +34.58,50.425,-2.590967147,49.2074,0,10.00179455,-2.6396875,-2.069482647,3.429542302,90.00000001 +34.59,50.425,-2.590965739,49.234,0,10.00090631,-2.6734375,-1.970063812,3.426392581,90.00000001 +34.6,50.425,-2.590964332,49.2609,0,9.99957394,-2.70625,-1.870233594,3.420255,90.00000001 +34.61,50.425,-2.590962925,49.2881,0,9.998685704,-2.738125,-1.770012791,3.411134944,90.00000001 +34.62,50.425,-2.590961518,49.3157,0,9.998685747,-2.768125,-1.669422372,3.399040263,90.00000001 +34.63,50.425,-2.590960111,49.3435,0,9.999574068,-2.79625,-1.568483251,3.383981615,90.00000001 +34.64,50.425,-2.590958704,49.3716,0,10.00068446,-2.8234375,-1.467216628,3.365972061,90.00000001 +34.65,50.425,-2.590957296,49.4,0,10.00068451,-2.8496875,-1.365643587,3.34502736,90.00000001 +34.66,50.425,-2.590955889,49.4286,0,9.999574202,-2.8746875,-1.263785327,3.321165673,90.00000001 +34.67,50.425,-2.590954482,49.4575,0,9.998908038,-2.898125,-1.161663163,3.294407971,90.00000001 +34.68,50.425,-2.590953075,49.4866,0,9.999574292,-2.92,-1.059298409,3.264777459,90.00000001 +34.69,50.425,-2.590951668,49.5159,0,10.00068469,-2.9415625,-0.956712436,3.232299976,90.00000001 +34.7,50.425,-2.59095026,49.5454,0,10.00068473,-2.963125,-0.853926615,3.197003943,90.00000001 +34.71,50.425,-2.590948853,49.5752,0,9.999574431,-2.9828125,-0.750962547,3.158920011,90.00000001 +34.72,50.425,-2.590947446,49.6051,0,9.998686199,-2.9996875,-0.647841545,3.11808147,90.00000001 +34.73,50.425,-2.590946039,49.6352,0,9.998686246,-3.015,-0.544585326,3.074523958,90.00000001 +34.74,50.425,-2.590944632,49.6654,0,9.999574572,-3.03,-0.441215375,3.028285347,90.00000001 +34.75,50.425,-2.590943225,49.6958,0,10.00090704,-3.0446875,-0.337753234,2.979406089,90.00000001 +34.76,50.425,-2.590941817,49.7263,0,10.00179536,-3.0578125,-0.23422062,2.927928753,90.00000001 +34.77,50.425,-2.59094041,49.757,0,10.00179541,-3.0684375,-0.130639018,2.873898145,90.00000001 +34.78,50.425,-2.590939002,49.7877,0,10.00090718,-3.0778125,-0.027030201,2.817361535,90.00000001 +34.79,50.425,-2.590937595,49.8185,0,9.999574811,-3.086875,0.076584289,2.758368081,90.00000001 +34.8,50.425,-2.590936188,49.8495,0,9.998908651,-3.094375,0.180182793,2.696969294,90.00000001 +34.81,50.425,-2.590934781,49.8804,0,9.999574909,-3.0996875,0.283743654,2.633218744,90.00000001 +34.82,50.425,-2.590933374,49.9115,0,10.00068531,-3.1034375,0.387245271,2.567172008,90.00000001 +34.83,50.425,-2.590931966,49.9425,0,10.00068535,-3.10625,0.490665987,2.498886611,90.00000001 +34.84,50.425,-2.590930559,49.9736,0,9.999575054,-3.1084375,0.593984258,2.428422142,90.00000001 +34.85,50.425,-2.590929152,50.0047,0,9.998686823,-3.109375,0.697178483,2.355840077,90.00000001 +34.86,50.425,-2.590927745,50.0358,0,9.998686872,-3.1084375,0.80022712,2.281203673,90.00000001 +34.87,50.425,-2.590926338,50.0669,0,9.9995752,-3.10625,0.903108624,2.204578074,90.00000001 +34.88,50.425,-2.590924931,50.0979,0,10.0006856,-3.103125,1.005801512,2.126029972,90.00000001 +34.89,50.425,-2.590923523,50.129,0,10.00068565,-3.098125,1.10828441,2.045628007,90.00000001 +34.9,50.425,-2.590922116,50.1599,0,9.999575345,-3.09125,1.210535776,1.963442196,90.00000001 +34.91,50.425,-2.590920709,50.1908,0,9.998909185,-3.0834375,1.31253441,1.879544216,90.00000001 +34.92,50.425,-2.590919302,50.2216,0,9.999575443,-3.0746875,1.414258884,1.794007289,90.00000001 +34.93,50.425,-2.590917895,50.2523,0,10.00090791,-3.0646875,1.515688055,1.706905901,90.00000001 +34.94,50.425,-2.590916487,50.2829,0,10.00179624,-3.053125,1.616800668,1.618316141,90.00000001 +34.95,50.425,-2.59091508,50.3134,0,10.00179628,-3.04,1.717575636,1.528315128,90.00000001 +34.96,50.425,-2.590913672,50.3437,0,10.00090805,-3.02625,1.817991875,1.436981416,90.00000001 +34.97,50.425,-2.590912265,50.3739,0,9.99957568,-3.0115625,1.91802853,1.344394645,90.00000001 +34.98,50.425,-2.590910858,50.404,0,9.998687449,-2.9946875,2.017664573,1.250635545,90.00000001 +34.99,50.425,-2.590909451,50.4338,0,9.998687496,-2.9765625,2.116879263,1.15578582,90.00000001 +35,50.425,-2.590908044,50.4635,0,9.99957582,-2.958125,2.215651858,1.059928319,90.00000001 +35.01,50.425,-2.590906637,50.493,0,10.00068621,-2.9378125,2.313961733,0.963146465,90.00000001 +35.02,50.425,-2.590905229,50.5223,0,10.00068626,-2.915,2.411788375,0.86552477,90.00000001 +35.03,50.425,-2.590903822,50.5513,0,9.999575958,-2.8915625,2.509111387,0.767148318,90.00000001 +35.04,50.425,-2.590902415,50.5801,0,9.998909794,-2.868125,2.605910372,0.668102937,90.00000001 +35.05,50.425,-2.590901008,50.6087,0,9.999576047,-2.8428125,2.702165161,0.568474916,90.00000001 +35.06,50.425,-2.590899601,50.637,0,10.00068644,-2.815,2.797855588,0.468351172,90.00000001 +35.07,50.425,-2.590898193,50.665,0,10.00068648,-2.7865625,2.892961769,0.367819023,90.00000001 +35.08,50.425,-2.590896786,50.6927,0,9.999576179,-2.758125,2.987463766,0.266966132,90.00000001 +35.09,50.425,-2.590895379,50.7202,0,9.998910013,-2.728125,3.081341927,0.165880449,90.00000001 +35.1,50.425,-2.590893972,50.7473,0,9.999576264,-2.69625,3.174576541,0.064650151,90.00000001 +35.11,50.425,-2.590892565,50.7741,0,10.00068665,-2.6634375,3.267148186,-0.036636583,90.00000001 +35.12,50.425,-2.590891157,50.8006,0,10.00090877,-2.6296875,3.359037496,-0.137891289,90.00000001 +35.13,50.425,-2.59088975,50.8267,0,10.00068674,-2.5946875,3.450225333,-0.239025845,90.00000001 +35.14,50.425,-2.590888343,50.8525,0,10.00090885,-2.558125,3.540692676,-0.339951903,90.00000001 +35.15,50.425,-2.590886935,50.8779,0,10.00068682,-2.52,3.63042056,-0.440581569,90.00000001 +35.16,50.425,-2.590885528,50.9029,0,9.999576507,-2.4815625,3.719390306,-0.54082701,90.00000001 +35.17,50.425,-2.590884121,50.9275,0,9.998910336,-2.443125,3.807583293,-0.640600849,90.00000001 +35.18,50.425,-2.590882714,50.9518,0,9.999576584,-2.403125,3.894981071,-0.739816054,90.00000001 +35.19,50.425,-2.590881307,50.9756,0,10.00068697,-2.36125,3.981565479,-0.838386109,90.00000001 +35.2,50.425,-2.590879899,50.999,0,10.00068701,-2.3184375,4.067318354,-0.936225127,90.00000001 +35.21,50.425,-2.590878492,51.022,0,9.999576694,-2.275,4.152221875,-1.033247737,90.00000001 +35.22,50.425,-2.590877085,51.0445,0,9.99868845,-2.23125,4.236258226,-1.129369314,90.00000001 +35.23,50.425,-2.590875678,51.0666,0,9.998688484,-2.1865625,4.319409871,-1.224506091,90.00000001 +35.24,50.425,-2.590874271,51.0883,0,9.999576797,-2.1396875,4.401659453,-1.318575104,90.00000001 +35.25,50.425,-2.590872864,51.1094,0,10.00068718,-2.091875,4.482989838,-1.411494248,90.00000001 +35.26,50.425,-2.590871456,51.1301,0,10.00068721,-2.045,4.56338401,-1.503182564,90.00000001 +35.27,50.425,-2.590870049,51.1503,0,9.999798964,-1.9978125,4.642825181,-1.593560067,90.00000001 +35.28,50.425,-2.590868642,51.1701,0,9.999798995,-1.9478125,4.721296736,-1.682548033,90.00000001 +35.29,50.425,-2.590867235,51.1893,0,10.0006873,-1.895,4.798782287,-1.770068711,90.00000001 +35.3,50.425,-2.590865827,51.208,0,10.00068733,-1.841875,4.875265736,-1.856045899,90.00000001 +35.31,50.425,-2.59086442,51.2261,0,9.999799083,-1.79,4.950730981,-1.940404595,90.00000001 +35.32,50.425,-2.590863013,51.2438,0,9.999799111,-1.738125,5.025162381,-2.023071175,90.00000001 +35.33,50.425,-2.590861606,51.2609,0,10.00068742,-1.6846875,5.098544352,-2.103973675,90.00000001 +35.34,50.425,-2.590860198,51.2775,0,10.00068744,-1.63,5.170861481,-2.183041449,90.00000001 +35.35,50.425,-2.590858791,51.2935,0,9.999577119,-1.5746875,5.242098813,-2.260205572,90.00000001 +35.36,50.425,-2.590857384,51.309,0,9.998910934,-1.5184375,5.312241395,-2.335398777,90.00000001 +35.37,50.425,-2.590855977,51.3239,0,9.999577166,-1.4615625,5.381274559,-2.40855546,90.00000001 +35.38,50.425,-2.59085457,51.3382,0,10.00068754,-1.405,5.449183923,-2.479611853,90.00000001 +35.39,50.425,-2.590853162,51.352,0,10.00068756,-1.348125,5.515955278,-2.548506017,90.00000001 +35.4,50.425,-2.590851755,51.3652,0,9.999577231,-1.2896875,5.581574702,-2.615177792,90.00000001 +35.41,50.425,-2.590850348,51.3778,0,9.998688972,-1.23,5.646028501,-2.679569138,90.00000001 +35.42,50.425,-2.590848941,51.3898,0,9.998688991,-1.17,5.709303209,-2.741623848,90.00000001 +35.43,50.425,-2.590847534,51.4012,0,9.999577287,-1.1096875,5.771385536,-2.801287834,90.00000001 +35.44,50.425,-2.590846127,51.412,0,10.00068765,-1.0484375,5.832262645,-2.858509014,90.00000001 +35.45,50.425,-2.590844719,51.4222,0,10.00068767,-0.986875,5.891921761,-2.913237599,90.00000001 +35.46,50.425,-2.590843312,51.4317,0,9.999799405,-0.9265625,5.950350393,-2.965425747,90.00000001 +35.47,50.425,-2.590841905,51.4407,0,9.999799419,-0.8665625,6.007536394,-3.015028021,90.00000001 +35.48,50.425,-2.590840498,51.4491,0,10.00068771,-0.804375,6.063467789,-3.062001106,90.00000001 +35.49,50.425,-2.59083909,51.4568,0,10.00090979,-0.7403125,6.11813289,-3.106304094,90.00000001 +35.5,50.425,-2.590837683,51.4639,0,10.00068773,-0.676875,6.171520352,-3.147898366,90.00000001 +35.51,50.425,-2.590836276,51.4703,0,10.00090981,-0.615,6.223618889,-3.186747597,90.00000001 +35.52,50.425,-2.590834868,51.4762,0,10.00068775,-0.553125,6.274417785,-3.222817983,90.00000001 +35.53,50.425,-2.590833461,51.4814,0,9.999577413,-0.4896875,6.323906327,-3.256077954,90.00000001 +35.54,50.425,-2.590832054,51.486,0,9.99868914,-0.425,6.372074144,-3.286498633,90.00000001 +35.55,50.425,-2.590830647,51.4899,0,9.998689146,-0.36,6.418911324,-3.314053433,90.00000001 +35.56,50.425,-2.59082924,51.4932,0,9.999577431,-0.2953125,6.464407897,-3.338718292,90.00000001 +35.57,50.425,-2.590827833,51.4958,0,10.00068778,-0.2315625,6.508554525,-3.360471781,90.00000001 +35.58,50.425,-2.590826425,51.4978,0,10.00068779,-0.168125,6.551341924,-3.379294877,90.00000001 +35.59,50.425,-2.590825018,51.4992,0,9.99957744,-0.1034375,6.592761158,-3.395171136,90.00000001 +35.6,50.425,-2.590823611,51.4999,0,9.998911232,-0.0384375,6.632803574,-3.408086808,90.00000001 +35.61,50.425,-2.590822204,51.4999,0,9.999577441,0.025,6.671460807,-3.418030548,90.00000001 +35.62,50.425,-2.590820797,51.4994,0,10.00068779,0.0884375,6.708724779,-3.424993704,90.00000001 +35.63,50.425,-2.590819389,51.4982,0,10.00068779,0.15375,6.744587754,-3.428970261,90.00000001 +35.64,50.425,-2.590817982,51.4963,0,9.999799506,0.2196875,6.77904217,-3.429956665,90.00000001 +35.65,50.425,-2.590816575,51.4938,0,9.999799502,0.2846875,6.812080922,-3.427952115,90.00000001 +35.66,50.425,-2.590815168,51.4906,0,10.00068778,0.3484375,6.84369702,-3.422958329,90.00000001 +35.67,50.425,-2.59081376,51.4868,0,10.00068777,0.4115625,6.873883874,-3.414979663,90.00000001 +35.68,50.425,-2.590812353,51.4824,0,9.999799484,0.475,6.90263524,-3.404023105,90.00000001 +35.69,50.425,-2.590810946,51.4773,0,9.999799476,0.5384375,6.929945101,-3.390098168,90.00000001 +35.7,50.425,-2.590809539,51.4716,0,10.00068775,0.6015625,6.955807671,-3.373217055,90.00000001 +35.71,50.425,-2.590808131,51.4653,0,10.00068774,0.665,6.980217679,-3.353394434,90.00000001 +35.72,50.425,-2.590806724,51.4583,0,9.999577376,0.728125,7.00316991,-3.330647552,90.00000001 +35.73,50.425,-2.590805317,51.4507,0,9.998911155,0.79,7.024659608,-3.304996346,90.00000001 +35.74,50.425,-2.59080391,51.4425,0,9.999577352,0.8515625,7.044682363,-3.276463105,90.00000001 +35.75,50.425,-2.590802503,51.4337,0,10.00068769,0.9134375,7.063233877,-3.245072753,90.00000001 +35.76,50.425,-2.590801095,51.4242,0,10.00068767,0.975,7.080310312,-3.210852676,90.00000001 +35.77,50.425,-2.590799688,51.4142,0,9.999577307,1.0365625,7.095908171,-3.17383267,90.00000001 +35.78,50.425,-2.590798281,51.4035,0,9.998689012,1.098125,7.110024075,-3.134045048,90.00000001 +35.79,50.425,-2.590796874,51.3922,0,9.998688995,1.158125,7.122655159,-3.091524475,90.00000001 +35.8,50.425,-2.590795467,51.3803,0,9.999577255,1.2165625,7.133798787,-3.046308021,90.00000001 +35.81,50.425,-2.59079406,51.3679,0,10.00068758,1.275,7.14345261,-2.998435163,90.00000001 +35.82,50.425,-2.590792652,51.3548,0,10.00090963,1.3334375,7.151614623,-2.947947612,90.00000001 +35.83,50.425,-2.590791245,51.3412,0,10.00068754,1.3915625,7.158283107,-2.894889428,90.00000001 +35.84,50.425,-2.590789838,51.327,0,10.00090959,1.45,7.163456629,-2.83930685,90.00000001 +35.85,50.425,-2.59078843,51.3122,0,10.0006875,1.5078125,7.167134216,-2.781248349,90.00000001 +35.86,50.425,-2.590787023,51.2968,0,9.999799193,1.563125,7.169315008,-2.720764575,90.00000001 +35.87,50.425,-2.590785616,51.2809,0,9.999799168,1.616875,7.169998604,-2.65790824,90.00000001 +35.88,50.425,-2.590784209,51.2645,0,10.00068742,1.6715625,7.169184775,-2.592734176,90.00000001 +35.89,50.425,-2.590782801,51.2475,0,10.0006874,1.7265625,7.166873807,-2.525299221,90.00000001 +35.9,50.425,-2.590781394,51.2299,0,9.999577019,1.7796875,7.163066158,-2.45566216,90.00000001 +35.91,50.425,-2.590779987,51.2119,0,9.998688712,1.8315625,7.157762517,-2.383883669,90.00000001 +35.92,50.425,-2.59077858,51.1933,0,9.998688683,1.8834375,7.150964144,-2.310026487,90.00000001 +35.93,50.425,-2.590777173,51.1742,0,9.999576931,1.9346875,7.142672356,-2.234154842,90.00000001 +35.94,50.425,-2.590775766,51.1546,0,10.00068725,1.985,7.132888872,-2.156335027,90.00000001 +35.95,50.425,-2.590774358,51.1345,0,10.00068722,2.0346875,7.121615813,-2.076634879,90.00000001 +35.96,50.425,-2.590772951,51.1139,0,9.999576838,2.083125,7.108855527,-1.99512384,90.00000001 +35.97,50.425,-2.590771544,51.0928,0,9.998910596,2.13,7.094610593,-1.911873015,90.00000001 +35.98,50.425,-2.590770137,51.0713,0,9.999576771,2.1765625,7.078884048,-1.826955055,90.00000001 +35.99,50.425,-2.59076873,51.0493,0,10.00068708,2.223125,7.061679214,-1.740443929,90.00000001 +36,50.425,-2.590767322,51.0268,0,10.00090912,2.2678125,7.042999586,-1.652415094,90.00000001 +36.01,50.425,-2.590765915,51.0039,0,10.00068701,2.31,7.022849119,-1.562945328,90.00000001 +36.02,50.425,-2.590764508,50.9806,0,10.00090905,2.351875,7.001232052,-1.472112724,90.00000001 +36.03,50.425,-2.5907631,50.9569,0,10.00068694,2.3946875,6.978152853,-1.379996352,90.00000001 +36.04,50.425,-2.590761693,50.9327,0,9.999576555,2.43625,6.953616337,-1.286676596,90.00000001 +36.05,50.425,-2.590760286,50.9081,0,9.998910307,2.4746875,6.927627716,-1.192234874,90.00000001 +36.06,50.425,-2.590758879,50.8832,0,9.999576477,2.511875,6.900192262,-1.096753462,90.00000001 +36.07,50.425,-2.590757472,50.8579,0,10.00068679,2.55,6.87131582,-1.00031567,90.00000001 +36.08,50.425,-2.590756064,50.8322,0,10.00068675,2.5878125,6.841004404,-0.903005607,90.00000001 +36.09,50.425,-2.590754657,50.8061,0,9.999576356,2.623125,6.809264376,-0.804908127,90.00000001 +36.1,50.425,-2.59075325,50.7797,0,9.998910106,2.65625,6.776102266,-0.706108775,90.00000001 +36.11,50.425,-2.590751843,50.753,0,9.999576273,2.6884375,6.741525066,-0.606693607,90.00000001 +36.12,50.425,-2.590750436,50.7259,0,10.00068658,2.72,6.705539936,-0.506749428,90.00000001 +36.13,50.425,-2.590749028,50.6986,0,10.00068654,2.75125,6.668154497,-0.406363383,90.00000001 +36.14,50.425,-2.590747621,50.6709,0,9.999576144,2.7815625,6.629376484,-0.305622964,90.00000001 +36.15,50.425,-2.590746214,50.6429,0,9.998687822,2.8096875,6.589214033,-0.204616063,90.00000001 +36.16,50.425,-2.590744807,50.6147,0,9.998687778,2.8365625,6.547675453,-0.103430685,90.00000001 +36.17,50.425,-2.5907434,50.5862,0,9.999576012,2.863125,6.504769508,-0.002155123,90.00000001 +36.18,50.425,-2.590741993,50.5574,0,10.00090839,2.8878125,6.460505138,0.099122272,90.00000001 +36.19,50.425,-2.590740585,50.5284,0,10.00179662,2.9096875,6.414891567,0.200313264,90.00000001 +36.2,50.425,-2.590739178,50.4992,0,10.00179657,2.9303125,6.367938363,0.30132962,90.00000001 +36.21,50.425,-2.59073777,50.4698,0,10.00090825,2.9515625,6.31965521,0.402083159,90.00000001 +36.22,50.425,-2.590736363,50.4402,0,9.999575784,2.9728125,6.270052363,0.502486106,90.00000001 +36.23,50.425,-2.590734956,50.4103,0,9.998687459,2.99125,6.21914002,0.602450855,90.00000001 +36.24,50.425,-2.590733549,50.3803,0,9.998687411,3.0065625,6.166928955,0.701890259,90.00000001 +36.25,50.425,-2.590732142,50.3502,0,9.999575643,3.021875,6.113429995,0.800717571,90.00000001 +36.26,50.425,-2.590730735,50.3199,0,10.00068594,3.038125,6.058654313,0.898846735,90.00000001 +36.27,50.425,-2.590729327,50.2894,0,10.0006859,3.0528125,6.002613311,0.996192035,90.00000001 +36.28,50.425,-2.59072792,50.2588,0,9.999575501,3.064375,5.945318792,1.092668617,90.00000001 +36.29,50.425,-2.590726513,50.2281,0,9.998909243,3.0734375,5.886782673,1.188192427,90.00000001 +36.3,50.425,-2.590725106,50.1973,0,9.999575403,3.0815625,5.827017159,1.2826801,90.00000001 +36.31,50.425,-2.590723699,50.1665,0,10.0006857,3.0896875,5.76603474,1.376049245,90.00000001 +36.32,50.425,-2.590722291,50.1355,0,10.00068566,3.0965625,5.703848193,1.468218445,90.00000001 +36.33,50.425,-2.590720884,50.1045,0,9.999575259,3.10125,5.640470409,1.55910737,90.00000001 +36.34,50.425,-2.590719477,50.0735,0,9.998909002,3.105,5.575914739,1.648636667,90.00000001 +36.35,50.425,-2.59071807,50.0424,0,9.999575162,3.108125,5.510194589,1.736728412,90.00000001 +36.36,50.425,-2.590716663,50.0113,0,10.00068546,3.1096875,5.44332371,1.823305658,90.00000001 +36.37,50.425,-2.590715255,49.9802,0,10.00090748,3.1096875,5.375316084,1.908292946,90.00000001 +36.38,50.425,-2.590713848,49.9491,0,10.00068536,3.108125,5.306185861,1.991616193,90.00000001 +36.39,50.425,-2.590712441,49.918,0,10.00090739,3.1046875,5.235947538,2.07320269,90.00000001 +36.4,50.425,-2.590711033,49.887,0,10.00068527,3.1,5.164615725,2.152981391,90.00000001 +36.41,50.425,-2.590709626,49.856,0,9.99957487,3.0946875,5.092205319,2.230882623,90.00000001 +36.42,50.425,-2.590708219,49.8251,0,9.998908613,3.088125,5.01873156,2.306838435,90.00000001 +36.43,50.425,-2.590706812,49.7942,0,9.999574774,3.0796875,4.944209633,2.380782706,90.00000001 +36.44,50.425,-2.590705405,49.7635,0,10.00068507,3.0696875,4.868655178,2.452650923,90.00000001 +36.45,50.425,-2.590703997,49.7328,0,10.00068503,3.0584375,4.79208401,2.522380345,90.00000001 +36.46,50.425,-2.59070259,49.7023,0,9.999574629,3.04625,4.714511999,2.589910239,90.00000001 +36.47,50.425,-2.590701183,49.6719,0,9.998686303,3.0334375,4.635955474,2.655181706,90.00000001 +36.48,50.425,-2.590699776,49.6416,0,9.998686256,3.0196875,4.556430823,2.718137792,90.00000001 +36.49,50.425,-2.590698369,49.6115,0,9.999574488,3.004375,4.475954546,2.77872361,90.00000001 +36.5,50.425,-2.590696962,49.5815,0,10.00068479,2.9865625,4.394543603,2.836886389,90.00000001 +36.51,50.425,-2.590695554,49.5517,0,10.00068474,2.9665625,4.312214839,2.892575309,90.00000001 +36.52,50.425,-2.590694147,49.5222,0,9.999574347,2.9465625,4.228985558,2.945741896,90.00000001 +36.53,50.425,-2.59069274,49.4928,0,9.998908092,2.9265625,4.144873119,2.996339742,90.00000001 +36.54,50.425,-2.590691333,49.4636,0,9.999574256,2.904375,4.059895055,3.044324728,90.00000001 +36.55,50.425,-2.590689926,49.4347,0,10.00090663,2.88,3.974069129,3.089654971,90.00000001 +36.56,50.425,-2.590688518,49.406,0,10.00179486,2.855,3.887413273,3.132291053,90.00000001 +36.57,50.425,-2.590687111,49.3776,0,10.00179482,2.8296875,3.799945593,3.17219573,90.00000001 +36.58,50.425,-2.590685703,49.3494,0,10.0009065,2.8028125,3.711684367,3.209334166,90.00000001 +36.59,50.425,-2.590684296,49.3215,0,9.999574034,2.773125,3.622647986,3.243674048,90.00000001 +36.6,50.425,-2.590682889,49.2939,0,9.998685713,2.741875,3.532855015,3.275185409,90.00000001 +36.61,50.425,-2.590681482,49.2667,0,9.99868567,2.7115625,3.442324302,3.30384069,90.00000001 +36.62,50.425,-2.590680075,49.2397,0,9.999573906,2.68125,3.3510747,3.329615024,90.00000001 +36.63,50.425,-2.590678668,49.213,0,10.00068421,2.6478125,3.259125287,3.352485895,90.00000001 +36.64,50.425,-2.59067726,49.1867,0,10.00068417,2.6115625,3.166495201,3.372433364,90.00000001 +36.65,50.425,-2.590675853,49.1608,0,9.999573783,2.5753125,3.073203863,3.389439954,90.00000001 +36.66,50.425,-2.590674446,49.1352,0,9.998907534,2.5396875,2.979270699,3.403490942,90.00000001 +36.67,50.425,-2.590673039,49.11,0,9.999573703,2.503125,2.884715359,3.414574066,90.00000001 +36.68,50.425,-2.590671632,49.0851,0,10.00068401,2.4646875,2.789557612,3.422679585,90.00000001 +36.69,50.425,-2.590670224,49.0607,0,10.00068397,2.4246875,2.693817281,3.42780051,90.00000001 +36.7,50.425,-2.590668817,49.0366,0,9.999573589,2.3834375,2.597514363,3.429932314,90.00000001 +36.71,50.425,-2.59066741,49.013,0,9.998685273,2.34125,2.500669026,3.429073164,90.00000001 +36.72,50.425,-2.590666003,48.9898,0,9.998685237,2.2984375,2.403301437,3.425223804,90.00000001 +36.73,50.425,-2.590664596,48.967,0,9.99957348,2.2546875,2.305431938,3.418387616,90.00000001 +36.74,50.425,-2.590663189,48.9447,0,10.00090586,2.2096875,2.207080982,3.408570557,90.00000001 +36.75,50.425,-2.590661781,48.9228,0,10.00179411,2.1634375,2.108269139,3.395781165,90.00000001 +36.76,50.425,-2.590660374,48.9014,0,10.00179407,2.1165625,2.009016978,3.380030555,90.00000001 +36.77,50.425,-2.590658966,48.8805,0,10.00090576,2.0696875,1.90934524,3.361332593,90.00000001 +36.78,50.425,-2.590657559,48.86,0,9.999573312,2.0215625,1.809274838,3.339703436,90.00000001 +36.79,50.425,-2.590656152,48.84,0,9.998907072,1.97125,1.708826513,3.315161992,90.00000001 +36.8,50.425,-2.590654745,48.8206,0,9.999573251,1.9203125,1.60802135,3.287729747,90.00000001 +36.81,50.425,-2.590653338,48.8016,0,10.00068357,1.87,1.506880376,3.257430478,90.00000001 +36.82,50.425,-2.59065193,48.7832,0,10.00068354,1.819375,1.405424734,3.224290771,90.00000001 +36.83,50.425,-2.590650523,48.7652,0,9.999573164,1.7665625,1.303675508,3.188339388,90.00000001 +36.84,50.425,-2.590649116,48.7478,0,9.998684858,1.7115625,1.201654128,3.149607671,90.00000001 +36.85,50.425,-2.590647709,48.731,0,9.998684832,1.656875,1.099381734,3.108129537,90.00000001 +36.86,50.425,-2.590646302,48.7147,0,9.999573085,1.603125,0.996879757,3.063941027,90.00000001 +36.87,50.425,-2.590644895,48.6989,0,10.00068341,1.548125,0.894169566,3.017080699,90.00000001 +36.88,50.425,-2.590643487,48.6837,0,10.00068339,1.49125,0.791272706,2.967589464,90.00000001 +36.89,50.425,-2.59064208,48.6691,0,9.999573014,1.4334375,0.688210547,2.915510408,90.00000001 +36.9,50.425,-2.590640673,48.655,0,9.998906782,1.375,0.585004691,2.860889024,90.00000001 +36.91,50.425,-2.590639266,48.6416,0,9.99957297,1.316875,0.481676623,2.803772867,90.00000001 +36.92,50.425,-2.590637859,48.6287,0,10.0006833,1.26,0.378248001,2.744211841,90.00000001 +36.93,50.425,-2.590636451,48.6164,0,10.00090535,1.2028125,0.274740425,2.682257743,90.00000001 +36.94,50.425,-2.590635044,48.6046,0,10.00068326,1.143125,0.171175381,2.617964716,90.00000001 +36.95,50.425,-2.590633637,48.5935,0,10.00090531,1.0815625,0.067574642,2.551388797,90.00000001 +36.96,50.425,-2.590632229,48.583,0,10.00068323,1.02,-0.036040191,2.482588025,90.00000001 +36.97,50.425,-2.590630822,48.5731,0,9.999572863,0.9584375,-0.139647519,2.411622389,90.00000001 +36.98,50.425,-2.590629415,48.5638,0,9.99890664,0.8965625,-0.243225683,2.338553769,90.00000001 +36.99,50.425,-2.590628008,48.5552,0,9.999572835,0.835,-0.346753084,2.263445877,90.00000001 +37,50.425,-2.590626601,48.5471,0,10.00068317,0.7734375,-0.450208005,2.186364261,90.00000001 +37.01,50.425,-2.590625193,48.5397,0,10.00068316,0.71125,-0.553568961,2.107376127,90.00000001 +37.02,50.425,-2.590623786,48.5329,0,9.999572801,0.6484375,-0.656814294,2.026550289,90.00000001 +37.03,50.425,-2.590622379,48.5267,0,9.998906582,0.5846875,-0.759922461,1.943957277,90.00000001 +37.04,50.425,-2.590620972,48.5212,0,9.999572782,0.5203125,-0.862871918,1.859669112,90.00000001 +37.05,50.425,-2.590619565,48.5163,0,10.00068312,0.4565625,-0.965641181,1.773759304,90.00000001 +37.06,50.425,-2.590618157,48.5121,0,10.00068312,0.3934375,-1.068208762,1.68630274,90.00000001 +37.07,50.425,-2.59061675,48.5084,0,9.999572762,0.3296875,-1.170553291,1.59737568,90.00000001 +37.08,50.425,-2.590615343,48.5055,0,9.998906549,0.265,-1.272653396,1.507055701,90.00000001 +37.09,50.425,-2.590613936,48.5031,0,9.999572754,0.2003125,-1.374487649,1.41542153,90.00000001 +37.1,50.425,-2.590612529,48.5015,0,10.0006831,0.1365625,-1.476034907,1.322553093,90.00000001 +37.11,50.425,-2.590611121,48.5004,0,10.00090517,0.0734375,-1.577273914,1.228531349,90.00000001 +37.12,50.425,-2.590609714,48.5,0,10.0006831,0.009375,-1.67818347,1.133438346,90.00000001 +37.13,50.425,-2.590608307,48.5002,0,10.00090517,-0.05625,-1.778742605,1.03735699,90.00000001 +37.14,50.425,-2.590606899,48.5011,0,10.0006831,-0.121875,-1.878930291,0.940370992,90.00000001 +37.15,50.425,-2.590605492,48.5027,0,9.999572753,-0.18625,-1.978725559,0.842564976,90.00000001 +37.16,50.425,-2.590604085,48.5048,0,9.998684478,-0.25,-2.07810761,0.744024257,90.00000001 +37.17,50.425,-2.590602678,48.5077,0,9.998684482,-0.31375,-2.177055645,0.64483472,90.00000001 +37.18,50.425,-2.590601271,48.5111,0,9.999572766,-0.3778125,-2.275549095,0.545082883,90.00000001 +37.19,50.425,-2.590599864,48.5152,0,10.00068312,-0.4421875,-2.373567277,0.444855777,90.00000001 +37.2,50.425,-2.590598456,48.52,0,10.00068313,-0.50625,-2.471089736,0.344240664,90.00000001 +37.21,50.425,-2.590597049,48.5253,0,9.999572789,-0.57,-2.568096189,0.243325435,90.00000001 +37.22,50.425,-2.590595642,48.5314,0,9.998906589,-0.6334375,-2.664566353,0.142197983,90.00000001 +37.23,50.425,-2.590594235,48.538,0,9.999572809,-0.69625,-2.760480004,0.040946543,90.00000001 +37.24,50.425,-2.590592828,48.5453,0,10.00068317,-0.7584375,-2.855817201,-0.060340592,90.00000001 +37.25,50.425,-2.59059142,48.5532,0,10.00068318,-0.82,-2.95055795,-0.16157513,90.00000001 +37.26,50.425,-2.590590013,48.5617,0,9.999794916,-0.8815625,-3.04468254,-0.262668777,90.00000001 +37.27,50.425,-2.590588606,48.5708,0,9.99979493,-0.9434375,-3.138171261,-0.363533356,90.00000001 +37.28,50.425,-2.590587199,48.5806,0,10.00068322,-1.005,-3.231004691,-0.464080917,90.00000001 +37.29,50.425,-2.590585791,48.5909,0,10.00068324,-1.06625,-3.32316329,-0.564223798,90.00000001 +37.3,50.425,-2.590584384,48.6019,0,9.999794978,-1.126875,-3.414627924,-0.663874681,90.00000001 +37.31,50.425,-2.590582977,48.6135,0,9.999794996,-1.18625,-3.505379454,-0.762946647,90.00000001 +37.32,50.425,-2.59058157,48.6256,0,10.00068329,-1.245,-3.595398916,-0.861353294,90.00000001 +37.33,50.425,-2.590580162,48.6384,0,10.00068331,-1.3034375,-3.684667516,-0.959008851,90.00000001 +37.34,50.425,-2.590578755,48.6517,0,9.999572986,-1.3615625,-3.773166635,-1.055828176,90.00000001 +37.35,50.425,-2.590577348,48.6656,0,9.9989068,-1.42,-3.860877821,-1.151726757,90.00000001 +37.36,50.425,-2.590575941,48.6801,0,9.999573031,-1.478125,-3.947782627,-1.246621001,90.00000001 +37.37,50.425,-2.590574534,48.6952,0,10.0006834,-1.5346875,-4.033863062,-1.340428173,90.00000001 +37.38,50.425,-2.590573126,48.7108,0,10.00068343,-1.59,-4.119101019,-1.43306651,90.00000001 +37.39,50.425,-2.590571719,48.727,0,9.999573104,-1.645,-4.203478794,-1.524455169,90.00000001 +37.4,50.425,-2.590570312,48.7437,0,9.998684852,-1.6996875,-4.286978741,-1.614514509,90.00000001 +37.41,50.425,-2.590568905,48.761,0,9.998684879,-1.753125,-4.369583385,-1.703165919,90.00000001 +37.42,50.425,-2.590567498,48.7788,0,9.999573185,-1.805,-4.451275478,-1.790332166,90.00000001 +37.43,50.425,-2.590566091,48.7971,0,10.00068356,-1.8565625,-4.532038004,-1.875937217,90.00000001 +37.44,50.425,-2.590564683,48.8159,0,10.00090566,-1.9084375,-4.611854062,-1.959906417,90.00000001 +37.45,50.425,-2.590563276,48.8353,0,10.00068362,-1.9596875,-4.690706977,-2.042166597,90.00000001 +37.46,50.425,-2.590561869,48.8551,0,10.00090572,-2.0096875,-4.768580307,-2.122645911,90.00000001 +37.47,50.425,-2.590560461,48.8755,0,10.00068369,-2.058125,-4.845457836,-2.201274284,90.00000001 +37.48,50.425,-2.590559054,48.8963,0,9.999795439,-2.105,-4.921323349,-2.277983077,90.00000001 +37.49,50.425,-2.590557647,48.9176,0,9.999795471,-2.1515625,-4.996161206,-2.352705483,90.00000001 +37.5,50.425,-2.59055624,48.9393,0,10.00068378,-2.198125,-5.069955649,-2.425376241,90.00000001 +37.51,50.425,-2.590554832,48.9616,0,10.00068382,-2.2434375,-5.142691266,-2.495932097,90.00000001 +37.52,50.425,-2.590553425,48.9842,0,9.999573507,-2.2878125,-5.214352931,-2.564311401,90.00000001 +37.53,50.425,-2.590552018,49.0073,0,9.998685264,-2.331875,-5.284925632,-2.630454623,90.00000001 +37.54,50.425,-2.590550611,49.0309,0,9.9986853,-2.374375,-5.354394587,-2.694304066,90.00000001 +37.55,50.425,-2.590549204,49.0548,0,9.999573616,-2.4146875,-5.422745416,-2.755803981,90.00000001 +37.56,50.425,-2.590547797,49.0792,0,10.000684,-2.4534375,-5.489963793,-2.814900853,90.00000001 +37.57,50.425,-2.590546389,49.1039,0,10.00068404,-2.4915625,-5.556035624,-2.871543059,90.00000001 +37.58,50.425,-2.590544982,49.129,0,9.999573733,-2.53,-5.620947101,-2.925681269,90.00000001 +37.59,50.425,-2.590543575,49.1545,0,9.998907564,-2.568125,-5.684684817,-2.977268211,90.00000001 +37.6,50.425,-2.590542168,49.1804,0,9.999573813,-2.6046875,-5.747235307,-3.02625891,90.00000001 +37.61,50.425,-2.590540761,49.2066,0,10.0006842,-2.6396875,-5.808585508,-3.07261068,90.00000001 +37.62,50.425,-2.590539353,49.2332,0,10.00090631,-2.673125,-5.868722757,-3.116283128,90.00000001 +37.63,50.425,-2.590537946,49.2601,0,10.00068429,-2.7046875,-5.927634335,-3.157238093,90.00000001 +37.64,50.425,-2.590536539,49.2873,0,10.0009064,-2.735,-5.985308037,-3.195439883,90.00000001 +37.65,50.425,-2.590535131,49.3148,0,10.00068437,-2.765,-6.041731775,-3.230855206,90.00000001 +37.66,50.425,-2.590533724,49.3426,0,9.999574067,-2.7946875,-6.096893745,-3.263453239,90.00000001 +37.67,50.425,-2.590532317,49.3707,0,9.998907902,-2.823125,-6.150782489,-3.293205447,90.00000001 +37.68,50.425,-2.59053091,49.3991,0,9.999574156,-2.8496875,-6.203386718,-3.320085934,90.00000001 +37.69,50.425,-2.590529503,49.4277,0,10.00068455,-2.8746875,-6.254695432,-3.344071208,90.00000001 +37.7,50.425,-2.590528095,49.4566,0,10.00068459,-2.898125,-6.304697917,-3.36514047,90.00000001 +37.71,50.425,-2.590526688,49.4857,0,9.99957429,-2.92,-6.353383803,-3.383275272,90.00000001 +37.72,50.425,-2.590525281,49.515,0,9.998908128,-2.9415625,-6.400742832,-3.3984598,90.00000001 +37.73,50.425,-2.590523874,49.5445,0,9.999574383,-2.963125,-6.446765152,-3.410680818,90.00000001 +37.74,50.425,-2.590522467,49.5743,0,10.00068478,-2.9828125,-6.491441135,-3.419927669,90.00000001 +37.75,50.425,-2.590521059,49.6042,0,10.00068482,-2.9996875,-6.5347615,-3.426192275,90.00000001 +37.76,50.425,-2.590519652,49.6343,0,9.999574523,-3.015,-6.576717136,-3.429469192,90.00000001 +37.77,50.425,-2.590518245,49.6645,0,9.998686292,-3.0296875,-6.617299336,-3.429755614,90.00000001 +37.78,50.425,-2.590516838,49.6949,0,9.99868634,-3.0434375,-6.656499561,-3.427051196,90.00000001 +37.79,50.425,-2.590515431,49.7254,0,9.999574666,-3.05625,-6.694309676,-3.421358344,90.00000001 +37.8,50.425,-2.590514024,49.756,0,10.00090713,-3.068125,-6.730721774,-3.412681987,90.00000001 +37.81,50.425,-2.590512616,49.7868,0,10.00179546,-3.078125,-6.765728235,-3.401029745,90.00000001 +37.82,50.425,-2.590511209,49.8176,0,10.00179551,-3.08625,-6.799321782,-3.386411758,90.00000001 +37.83,50.425,-2.590509801,49.8485,0,10.00090728,-3.0934375,-6.831495368,-3.368840746,90.00000001 +37.84,50.425,-2.590508394,49.8795,0,9.999574908,-3.0996875,-6.862242231,-3.348332123,90.00000001 +37.85,50.425,-2.590506987,49.9105,0,9.998686677,-3.1046875,-6.89155607,-3.32490365,90.00000001 +37.86,50.425,-2.59050558,49.9416,0,9.998686725,-3.108125,-6.919430695,-3.298575838,90.00000001 +37.87,50.425,-2.590504173,49.9727,0,9.999575052,-3.1096875,-6.945860265,-3.269371549,90.00000001 +37.88,50.425,-2.590502766,50.0038,0,10.00068545,-3.1096875,-6.970839276,-3.237316394,90.00000001 +37.89,50.425,-2.590501358,50.0349,0,10.0006855,-3.108125,-6.994362517,-3.202438218,90.00000001 +37.9,50.425,-2.590499951,50.066,0,9.999575199,-3.105,-7.016425059,-3.164767504,90.00000001 +37.91,50.425,-2.590498544,50.097,0,9.998909038,-3.1015625,-7.037022376,-3.124337023,90.00000001 +37.92,50.425,-2.590497137,50.128,0,9.999575295,-3.098125,-7.056150056,-3.081182129,90.00000001 +37.93,50.425,-2.59049573,50.159,0,10.00068569,-3.0928125,-7.073804147,-3.035340349,90.00000001 +37.94,50.425,-2.590494322,50.1899,0,10.00068574,-3.0846875,-7.08998098,-2.986851732,90.00000001 +37.95,50.425,-2.590492915,50.2207,0,9.999575441,-3.075,-7.104677118,-2.935758508,90.00000001 +37.96,50.425,-2.590491508,50.2514,0,9.99890928,-3.0646875,-7.117889582,-2.88210525,90.00000001 +37.97,50.425,-2.590490101,50.282,0,9.999575536,-3.053125,-7.129615564,-2.82593877,90.00000001 +37.98,50.425,-2.590488694,50.3125,0,10.00068593,-3.04,-7.139852601,-2.767308056,90.00000001 +37.99,50.425,-2.590487286,50.3428,0,10.00090805,-3.02625,-7.148598573,-2.706264216,90.00000001 +38,50.425,-2.590485879,50.373,0,10.00068603,-3.0115625,-7.155851646,-2.64286042,90.00000001 +38.01,50.425,-2.590484472,50.4031,0,10.00090814,-2.9946875,-7.16161033,-2.577152016,90.00000001 +38.02,50.425,-2.590483064,50.4329,0,10.00068612,-2.9765625,-7.165873365,-2.509196357,90.00000001 +38.03,50.425,-2.590481657,50.4626,0,9.999575818,-2.958125,-7.168639949,-2.439052571,90.00000001 +38.04,50.425,-2.59048025,50.4921,0,9.998909656,-2.9378125,-7.169909394,-2.366781967,90.00000001 +38.05,50.425,-2.590478843,50.5214,0,9.999575911,-2.915,-7.169681586,-2.292447454,90.00000001 +38.06,50.425,-2.590477436,50.5504,0,10.00068631,-2.8915625,-7.16795641,-2.216113891,90.00000001 +38.07,50.425,-2.590476028,50.5792,0,10.00068635,-2.868125,-7.164734325,-2.137847799,90.00000001 +38.08,50.425,-2.590474621,50.6078,0,9.999576046,-2.843125,-7.16001596,-2.057717531,90.00000001 +38.09,50.425,-2.590473214,50.6361,0,9.998687811,-2.81625,-7.15380229,-1.975792875,90.00000001 +38.1,50.425,-2.590471807,50.6641,0,9.998687856,-2.7884375,-7.14609469,-1.892145334,90.00000001 +38.11,50.425,-2.5904704,50.6919,0,9.999576178,-2.7596875,-7.136894707,-1.806847789,90.00000001 +38.12,50.425,-2.590468993,50.7193,0,10.00068657,-2.7296875,-7.126204288,-1.719974668,90.00000001 +38.13,50.425,-2.590467585,50.7465,0,10.00068661,-2.698125,-7.114025612,-1.631601657,90.00000001 +38.14,50.425,-2.590466178,50.7733,0,9.999576304,-2.6646875,-7.100361313,-1.541805935,90.00000001 +38.15,50.425,-2.590464771,50.7998,0,9.998910137,-2.63,-7.085214143,-1.450665654,90.00000001 +38.16,50.425,-2.590463364,50.8259,0,9.999576387,-2.5946875,-7.068587366,-1.358260453,90.00000001 +38.17,50.425,-2.590461957,50.8517,0,10.00090885,-2.5584375,-7.050484363,-1.264670776,90.00000001 +38.18,50.425,-2.590460549,50.8771,0,10.00179716,-2.52125,-7.030908974,-1.169978271,90.00000001 +38.19,50.425,-2.590459142,50.9021,0,10.0017972,-2.4834375,-7.009865323,-1.074265556,90.00000001 +38.2,50.425,-2.590457734,50.9268,0,10.00090896,-2.4446875,-6.98735765,-0.977616056,90.00000001 +38.21,50.425,-2.590456327,50.951,0,9.999576583,-2.4046875,-6.963390825,-0.880114109,90.00000001 +38.22,50.425,-2.59045492,50.9749,0,9.998688342,-2.3634375,-6.937969776,-0.781844628,90.00000001 +38.23,50.425,-2.590453513,50.9983,0,9.998688379,-2.32125,-6.911099832,-0.682893385,90.00000001 +38.24,50.425,-2.590452106,51.0213,0,9.999576693,-2.278125,-6.882786549,-0.583346666,90.00000001 +38.25,50.425,-2.590450699,51.0439,0,10.00068708,-2.233125,-6.853035888,-0.483291218,90.00000001 +38.26,50.425,-2.590449291,51.066,0,10.00068711,-2.1865625,-6.821854092,-0.38281436,90.00000001 +38.27,50.425,-2.590447884,51.0876,0,9.999576797,-2.14,-6.789247637,-0.282003696,90.00000001 +38.28,50.425,-2.590446477,51.1088,0,9.998910621,-2.0934375,-6.755223341,-0.180947119,90.00000001 +38.29,50.425,-2.59044507,51.1295,0,9.999576862,-2.04625,-6.71978825,-0.079732749,90.00000001 +38.3,50.425,-2.590443663,51.1497,0,10.00068724,-1.998125,-6.682949871,0.021551177,90.00000001 +38.31,50.425,-2.590442255,51.1695,0,10.00068727,-1.948125,-6.644715825,0.122816311,90.00000001 +38.32,50.425,-2.590440848,51.1887,0,9.999576955,-1.8965625,-6.605094132,0.223974301,90.00000001 +38.33,50.425,-2.590439441,51.2074,0,9.998688705,-1.845,-6.564093043,0.324937028,90.00000001 +38.34,50.425,-2.590438034,51.2256,0,9.998688734,-1.793125,-6.521721095,0.42561637,90.00000001 +38.35,50.425,-2.590436627,51.2433,0,9.99957704,-1.7396875,-6.477987169,0.525924606,90.00000001 +38.36,50.425,-2.59043522,51.2604,0,10.00090948,-1.685,-6.432900432,0.625774191,90.00000001 +38.37,50.425,-2.590433812,51.277,0,10.00179779,-1.63,-6.386470282,0.72507809,90.00000001 +38.38,50.425,-2.590432405,51.293,0,10.00179782,-1.575,-6.338706343,0.82374973,90.00000001 +38.39,50.425,-2.590430997,51.3085,0,10.00090956,-1.52,-6.289618699,0.921703053,90.00000001 +38.4,50.425,-2.59042959,51.3234,0,9.999577165,-1.4646875,-6.239217493,1.018852631,90.00000001 +38.41,50.425,-2.590428183,51.3378,0,9.998910978,-1.408125,-6.18751338,1.115113723,90.00000001 +38.42,50.425,-2.590426776,51.3516,0,9.999577209,-1.3496875,-6.134517019,1.210402448,90.00000001 +38.43,50.425,-2.590425369,51.3648,0,10.00068758,-1.29,-6.080239581,1.304635728,90.00000001 +38.44,50.425,-2.590423961,51.3774,0,10.0006876,-1.23,-6.024692354,1.397731286,90.00000001 +38.45,50.425,-2.590422554,51.3894,0,9.999577269,-1.1703125,-5.967886912,1.489607991,90.00000001 +38.46,50.425,-2.590421147,51.4008,0,9.998689007,-1.1115625,-5.909835229,1.5801858,90.00000001 +38.47,50.425,-2.59041974,51.4116,0,9.998689024,-1.0528125,-5.850549281,1.669385588,90.00000001 +38.48,50.425,-2.590418333,51.4219,0,9.999577319,-0.9915625,-5.790041557,1.75712972,90.00000001 +38.49,50.425,-2.590416926,51.4315,0,10.00068768,-0.9284375,-5.728324663,1.843341534,90.00000001 +38.5,50.425,-2.590415518,51.4404,0,10.0006877,-0.866875,-5.665411434,1.927945971,90.00000001 +38.51,50.425,-2.590414111,51.4488,0,9.999577361,-0.8065625,-5.601315104,2.010869236,90.00000001 +38.52,50.425,-2.590412704,51.4566,0,9.998911164,-0.744375,-5.536048966,2.092038964,90.00000001 +38.53,50.425,-2.590411297,51.4637,0,9.999577384,-0.68,-5.469626713,2.171384394,90.00000001 +38.54,50.425,-2.59040989,51.4702,0,10.00090981,-0.6153125,-5.402062212,2.248836313,90.00000001 +38.55,50.425,-2.590408482,51.476,0,10.0017981,-0.551875,-5.333369557,2.324327284,90.00000001 +38.56,50.425,-2.590407075,51.4812,0,10.00179811,-0.49,-5.26356313,2.39779136,90.00000001 +38.57,50.425,-2.590405667,51.4858,0,10.00090984,-0.4278125,-5.192657425,2.46916454,90.00000001 +38.58,50.425,-2.59040426,51.4898,0,9.999577426,-0.3634375,-5.120667341,2.538384603,90.00000001 +38.59,50.425,-2.590402853,51.4931,0,9.998689152,-0.298125,-5.047607831,2.6053911,90.00000001 +38.6,50.425,-2.590401446,51.4957,0,9.998689156,-0.23375,-4.973494193,2.670125705,90.00000001 +38.61,50.425,-2.590400039,51.4978,0,9.999577438,-0.17,-4.898341955,2.732531867,90.00000001 +38.62,50.425,-2.590398632,51.4991,0,10.00068779,-0.10625,-4.8221667,2.79255527,90.00000001 +38.63,50.425,-2.590397224,51.4999,0,10.00068779,-0.041875,-4.744984415,2.850143487,90.00000001 +38.64,50.425,-2.590395817,51.5,0,9.999577442,0.0234375,-4.666811199,2.905246385,90.00000001 +38.65,50.425,-2.59039441,51.4994,0,9.998911232,0.088125,-4.587663383,2.957815836,90.00000001 +38.66,50.425,-2.590393003,51.4982,0,9.999577439,0.151875,-4.507557523,3.007806002,90.00000001 +38.67,50.425,-2.590391596,51.4964,0,10.00068778,0.2165625,-4.426510294,3.05517334,90.00000001 +38.68,50.425,-2.590390188,51.4939,0,10.00068778,0.2815625,-4.344538654,3.099876538,90.00000001 +38.69,50.425,-2.590388781,51.4907,0,9.999577427,0.345,-4.261659679,3.141876579,90.00000001 +38.7,50.425,-2.590387374,51.487,0,9.998689143,0.4084375,-4.177890728,3.181136851,90.00000001 +38.71,50.425,-2.590385967,51.4826,0,9.998689136,0.4734375,-4.093249278,3.217623147,90.00000001 +38.72,50.425,-2.59038456,51.4775,0,9.999577406,0.5378125,-4.007753031,3.251303611,90.00000001 +38.73,50.425,-2.590383153,51.4718,0,10.00090982,0.6,-3.921419808,3.282148909,90.00000001 +38.74,50.425,-2.590381745,51.4655,0,10.00179808,0.661875,-3.834267599,3.31013211,90.00000001 +38.75,50.425,-2.590380338,51.4586,0,10.00179807,0.725,-3.746314681,3.335228808,90.00000001 +38.76,50.425,-2.59037893,51.451,0,10.00090978,0.7884375,-3.657579447,3.357417171,90.00000001 +38.77,50.425,-2.590377523,51.4428,0,9.999577352,0.85125,-3.568080288,3.376677778,90.00000001 +38.78,50.425,-2.590376116,51.434,0,9.998911129,0.9134375,-3.477836055,3.392993897,90.00000001 +38.79,50.425,-2.590374709,51.4245,0,9.999577323,0.9746875,-3.386865483,3.406351319,90.00000001 +38.8,50.425,-2.590373302,51.4145,0,10.00068766,1.035,-3.295187595,3.416738299,90.00000001 +38.81,50.425,-2.590371894,51.4038,0,10.00068764,1.095,-3.202821584,3.424145841,90.00000001 +38.82,50.425,-2.590370487,51.3926,0,9.999577274,1.155,-3.109786646,3.428567471,90.00000001 +38.83,50.425,-2.59036908,51.3807,0,9.998688976,1.215,-3.016102317,3.42999935,90.00000001 +38.84,50.425,-2.590367673,51.3683,0,9.998688956,1.2746875,-2.921788135,3.42844016,90.00000001 +38.85,50.425,-2.590366266,51.3552,0,9.999577215,1.3334375,-2.826863753,3.423891391,90.00000001 +38.86,50.425,-2.590364859,51.3416,0,10.00068754,1.39125,-2.731348996,3.416356938,90.00000001 +38.87,50.425,-2.590363451,51.3274,0,10.00068752,1.4484375,-2.635263859,3.405843335,90.00000001 +38.88,50.425,-2.590362044,51.3126,0,9.999577149,1.5046875,-2.538628339,3.392359804,90.00000001 +38.89,50.425,-2.590360637,51.2973,0,9.998910915,1.56,-2.441462718,3.375918093,90.00000001 +38.9,50.425,-2.59035923,51.2814,0,9.999577099,1.615,-2.343787165,3.356532524,90.00000001 +38.91,50.425,-2.590357823,51.265,0,10.00068742,1.67,-2.245622192,3.334220001,90.00000001 +38.92,50.425,-2.590356415,51.248,0,10.00090947,1.725,-2.146988195,3.308999946,90.00000001 +38.93,50.425,-2.590355008,51.2305,0,10.00068737,1.779375,-2.047905916,3.280894475,90.00000001 +38.94,50.425,-2.590353601,51.2124,0,10.00090941,1.8315625,-1.948395866,3.249927997,90.00000001 +38.95,50.425,-2.590352193,51.1938,0,10.00068731,1.8815625,-1.84847896,3.216127498,90.00000001 +38.96,50.425,-2.590350786,51.1748,0,9.999576933,1.931875,-1.748176051,3.179522485,90.00000001 +38.97,50.425,-2.590349379,51.1552,0,9.998910693,1.983125,-1.647507997,3.140144929,90.00000001 +38.98,50.425,-2.590347972,51.1351,0,9.999576871,2.033125,-1.546495939,3.098029093,90.00000001 +38.99,50.425,-2.590346565,51.1145,0,10.00068719,2.0815625,-1.445160904,3.053211704,90.00000001 +39,50.425,-2.590345157,51.0935,0,10.00068715,2.1296875,-1.343524036,3.005731895,90.00000001 +39.01,50.425,-2.59034375,51.0719,0,9.999576771,2.1765625,-1.241606589,2.955631033,90.00000001 +39.02,50.425,-2.590342343,51.0499,0,9.998910528,2.22125,-1.13942988,2.902952835,90.00000001 +39.03,50.425,-2.590340936,51.0275,0,9.999576703,2.265,-1.037015164,2.847743252,90.00000001 +39.04,50.425,-2.590339529,51.0046,0,10.00068702,2.3084375,-0.934383927,2.790050356,90.00000001 +39.05,50.425,-2.590338121,50.9813,0,10.00068698,2.35125,-0.83155754,2.729924451,90.00000001 +39.06,50.425,-2.590336714,50.9576,0,9.999576593,2.393125,-0.728557548,2.667418079,90.00000001 +39.07,50.425,-2.590335307,50.9334,0,9.998910346,2.4334375,-0.62540532,2.60258567,90.00000001 +39.08,50.425,-2.5903339,50.9089,0,9.999576517,2.4728125,-0.522122516,2.535483717,90.00000001 +39.09,50.425,-2.590332493,50.884,0,10.00068683,2.511875,-0.418730677,2.466170836,90.00000001 +39.1,50.425,-2.590331085,50.8586,0,10.00090886,2.5496875,-0.315251406,2.394707414,90.00000001 +39.11,50.425,-2.590329678,50.833,0,10.00068675,2.58625,-0.211706301,2.321155733,90.00000001 +39.12,50.425,-2.590328271,50.8069,0,10.00090878,2.6215625,-0.108116964,2.245579965,90.00000001 +39.13,50.425,-2.590326863,50.7805,0,10.00068666,2.6546875,-0.004505053,2.168046055,90.00000001 +39.14,50.425,-2.590325456,50.7538,0,9.999576275,2.686875,0.099107833,2.088621557,90.00000001 +39.15,50.425,-2.590324049,50.7268,0,9.998687954,2.7196875,0.202699977,2.007375798,90.00000001 +39.16,50.425,-2.590322642,50.6994,0,9.99868791,2.75125,0.30624978,1.924379538,90.00000001 +39.17,50.425,-2.590321235,50.6717,0,9.999576146,2.7796875,0.409735641,1.8397052,90.00000001 +39.18,50.425,-2.590319828,50.6438,0,10.00068645,2.806875,0.513135959,1.753426579,90.00000001 +39.19,50.425,-2.59031842,50.6156,0,10.00068641,2.835,0.616429077,1.665618964,90.00000001 +39.2,50.425,-2.590317013,50.5871,0,9.999576014,2.8628125,0.719593509,1.5763589,90.00000001 +39.21,50.425,-2.590315606,50.5583,0,9.99890976,2.8878125,0.822607596,1.485724253,90.00000001 +39.22,50.425,-2.590314199,50.5293,0,9.999575923,2.9096875,0.925449968,1.393794035,90.00000001 +39.23,50.425,-2.590312792,50.5001,0,10.00068623,2.9303125,1.028099024,1.300648401,90.00000001 +39.24,50.425,-2.590311384,50.4707,0,10.00068618,2.9515625,1.130533392,1.206368539,90.00000001 +39.25,50.425,-2.590309977,50.4411,0,9.999797856,2.9728125,1.232731645,1.111036727,90.00000001 +39.26,50.425,-2.59030857,50.4112,0,9.999797808,2.99125,1.334672468,1.014736101,90.00000001 +39.27,50.425,-2.590307163,50.3812,0,10.00068604,3.0065625,1.436334547,0.917550599,90.00000001 +39.28,50.425,-2.590305755,50.3511,0,10.00068599,3.0215625,1.537696682,0.819564961,90.00000001 +39.29,50.425,-2.590304348,50.3208,0,9.999797667,3.0365625,1.638737732,0.720864673,90.00000001 +39.3,50.425,-2.590302941,50.2903,0,9.99979762,3.0496875,1.739436497,0.621535793,90.00000001 +39.31,50.425,-2.590301534,50.2598,0,10.00068585,3.0615625,1.839772007,0.521664894,90.00000001 +39.32,50.425,-2.590300126,50.2291,0,10.0006858,3.073125,1.939723291,0.421339068,90.00000001 +39.33,50.425,-2.590298719,50.1983,0,9.999575405,3.0828125,2.039269551,0.320645861,90.00000001 +39.34,50.425,-2.590297312,50.1674,0,9.998909148,3.09,2.138389874,0.21967305,90.00000001 +39.35,50.425,-2.590295905,50.1365,0,9.999575309,3.0965625,2.237063635,0.1185087,90.00000001 +39.36,50.425,-2.590294498,50.1055,0,10.00068561,3.1028125,2.335270205,0.017240988,90.00000001 +39.37,50.425,-2.59029309,50.0744,0,10.00068556,3.10625,2.432989131,-0.084041736,90.00000001 +39.38,50.425,-2.590291683,50.0433,0,9.999575163,3.1065625,2.530199901,-0.185251235,90.00000001 +39.39,50.425,-2.590290276,50.0123,0,9.998686835,3.106875,2.626882289,-0.286299161,90.00000001 +39.4,50.425,-2.590288869,49.9812,0,9.998686787,3.1084375,2.723016127,-0.387097391,90.00000001 +39.41,50.425,-2.590287462,49.9501,0,9.999575017,3.1090625,2.818581247,-0.487558092,90.00000001 +39.42,50.425,-2.590286055,49.919,0,10.00068532,3.1065625,2.913557768,-0.587593658,90.00000001 +39.43,50.425,-2.590284647,49.8879,0,10.00090734,3.10125,3.007925808,-0.687116828,90.00000001 +39.44,50.425,-2.59028324,49.857,0,10.00068522,3.095,3.101665714,-0.786040799,90.00000001 +39.45,50.425,-2.590281833,49.826,0,10.00090724,3.088125,3.194757834,-0.884279341,90.00000001 +39.46,50.425,-2.590280425,49.7952,0,10.00068512,3.0796875,3.287182801,-0.981746795,90.00000001 +39.47,50.425,-2.590279018,49.7644,0,9.999796797,3.07,3.378921309,-1.078358137,90.00000001 +39.48,50.425,-2.590277611,49.7338,0,9.999796749,3.0596875,3.469954104,-1.17402914,90.00000001 +39.49,50.425,-2.590276204,49.7032,0,10.00068498,3.048125,3.560262279,-1.268676324,90.00000001 +39.5,50.425,-2.590274796,49.6728,0,10.00068493,3.0346875,3.649826927,-1.362217242,90.00000001 +39.51,50.425,-2.590273389,49.6425,0,9.999574536,3.02,3.738629369,-1.454570304,90.00000001 +39.52,50.425,-2.590271982,49.6124,0,9.998686211,3.004375,3.826651042,-1.545654951,90.00000001 +39.53,50.425,-2.590270575,49.5824,0,9.998686164,2.9865625,3.91387361,-1.635391773,90.00000001 +39.54,50.425,-2.590269168,49.5526,0,9.999574396,2.9665625,4.000278739,-1.723702503,90.00000001 +39.55,50.425,-2.590267761,49.5231,0,10.0006847,2.9465625,4.085848496,-1.810510078,90.00000001 +39.56,50.425,-2.590266353,49.4937,0,10.00068465,2.9265625,4.170565005,-1.895738925,90.00000001 +39.57,50.425,-2.590264946,49.4645,0,9.999574258,2.9046875,4.254410502,-1.979314674,90.00000001 +39.58,50.425,-2.590263539,49.4356,0,9.998908004,2.88125,4.337367515,-2.061164388,90.00000001 +39.59,50.425,-2.590262132,49.4069,0,9.999574168,2.8565625,4.419418795,-2.141216734,90.00000001 +39.6,50.425,-2.590260725,49.3784,0,10.00068447,2.8296875,4.500547041,-2.219401924,90.00000001 +39.61,50.425,-2.590259317,49.3503,0,10.0009065,2.8015625,4.580735463,-2.295651778,90.00000001 +39.62,50.425,-2.59025791,49.3224,0,10.00068438,2.7734375,4.659967276,-2.369899774,90.00000001 +39.63,50.425,-2.590256503,49.2948,0,10.00090641,2.7446875,4.738225862,-2.442081169,90.00000001 +39.64,50.425,-2.590255095,49.2675,0,10.0006843,2.7146875,4.815494951,-2.512133052,90.00000001 +39.65,50.425,-2.590253688,49.2405,0,9.999573907,2.6828125,4.891758383,-2.579994345,90.00000001 +39.66,50.425,-2.590252281,49.2138,0,9.998907657,2.648125,4.967000232,-2.645605805,90.00000001 +39.67,50.425,-2.590250874,49.1875,0,9.999573825,2.611875,5.041204798,-2.70891025,90.00000001 +39.68,50.425,-2.590249467,49.1616,0,10.00068413,2.5765625,5.114356555,-2.769852505,90.00000001 +39.69,50.425,-2.590248059,49.136,0,10.00068409,2.5415625,5.18644026,-2.828379399,90.00000001 +39.7,50.425,-2.590246652,49.1107,0,9.999573704,2.5046875,5.257440846,-2.884439938,90.00000001 +39.71,50.425,-2.590245245,49.0859,0,9.998907456,2.46625,5.327343474,-2.937985136,90.00000001 +39.72,50.425,-2.590243838,49.0614,0,9.999573628,2.4265625,5.396133531,-2.98896841,90.00000001 +39.73,50.425,-2.590242431,49.0373,0,10.00068394,2.3846875,5.463796696,-3.037345242,90.00000001 +39.74,50.425,-2.590241023,49.0137,0,10.0006839,2.3415625,5.530318815,-3.08307352,90.00000001 +39.75,50.425,-2.590239616,48.9905,0,9.999573516,2.2984375,5.595686022,-3.12611325,90.00000001 +39.76,50.425,-2.590238209,48.9677,0,9.998685202,2.255,5.659884626,-3.166426961,90.00000001 +39.77,50.425,-2.590236802,48.9454,0,9.998685167,2.21125,5.722901217,-3.203979532,90.00000001 +39.78,50.425,-2.590235395,48.9235,0,9.999573411,2.1665625,5.784722675,-3.238738189,90.00000001 +39.79,50.425,-2.590233988,48.902,0,10.0009058,2.1196875,5.845336052,-3.270672564,90.00000001 +39.8,50.425,-2.59023258,48.8811,0,10.00179404,2.0715625,5.904728743,-3.299754928,90.00000001 +39.81,50.425,-2.590231173,48.8606,0,10.00179401,2.023125,5.962888256,-3.32595984,90.00000001 +39.82,50.425,-2.590229765,48.8406,0,10.0009057,1.973125,6.019802503,-3.34926444,90.00000001 +39.83,50.425,-2.590228358,48.8211,0,9.999573251,1.9215625,6.075459623,-3.369648445,90.00000001 +39.84,50.425,-2.590226951,48.8022,0,9.998684943,1.87,6.129847929,-3.387094036,90.00000001 +39.85,50.425,-2.590225544,48.7837,0,9.998684915,1.8184375,6.182956131,-3.401586087,90.00000001 +39.86,50.425,-2.590224137,48.7658,0,9.999573165,1.76625,6.234773059,-3.413111877,90.00000001 +39.87,50.425,-2.59022273,48.7484,0,10.00068349,1.7134375,6.285287998,-3.421661382,90.00000001 +39.88,50.425,-2.590221322,48.7315,0,10.00068346,1.6596875,6.33449029,-3.427227151,90.00000001 +39.89,50.425,-2.590219915,48.7152,0,9.999573086,1.605,6.38236968,-3.429804315,90.00000001 +39.9,50.425,-2.590218508,48.6994,0,9.998906852,1.5496875,6.428916256,-3.429390697,90.00000001 +39.91,50.425,-2.590217101,48.6842,0,9.999573037,1.493125,6.474120162,-3.425986526,90.00000001 +39.92,50.425,-2.590215694,48.6695,0,10.00068336,1.4353125,6.51797206,-3.419594895,90.00000001 +39.93,50.425,-2.590214286,48.6555,0,10.00068334,1.378125,6.560462782,-3.410221305,90.00000001 +39.94,50.425,-2.590212879,48.642,0,9.999572971,1.3215625,6.601583447,-3.397873893,90.00000001 +39.95,50.425,-2.590211472,48.629,0,9.998906742,1.2628125,6.641325462,-3.382563544,90.00000001 +39.96,50.425,-2.590210065,48.6167,0,9.999572932,1.201875,6.67968046,-3.364303551,90.00000001 +39.97,50.425,-2.590208658,48.605,0,10.00068326,1.141875,6.716640535,-3.343109842,90.00000001 +39.98,50.425,-2.59020725,48.5939,0,10.00090531,1.083125,6.752197894,-3.319000867,90.00000001 +39.99,50.425,-2.590205843,48.5833,0,10.00068323,1.023125,6.786345205,-3.29199771,90.00000001 +40,50.425,-2.590204436,48.5734,0,10.00090528,0.96125,6.819075247,-3.262123862,90.00000001 +40.01,50.425,-2.590203028,48.5641,0,10.0006832,0.89875,6.850381202,-3.229405394,90.00000001 +40.02,50.425,-2.590201621,48.5554,0,9.999572836,0.8365625,6.88025654,-3.193870838,90.00000001 +40.03,50.425,-2.590200214,48.5474,0,9.998906614,0.775,6.908695013,-3.155551134,90.00000001 +40.04,50.425,-2.590198807,48.5399,0,9.999572811,0.713125,6.935690722,-3.1144798,90.00000001 +40.05,50.425,-2.5901974,48.5331,0,10.00068315,0.6496875,6.961237936,-3.070692589,90.00000001 +40.06,50.425,-2.590195992,48.5269,0,10.00068314,0.5853125,6.985331442,-3.02422766,90.00000001 +40.07,50.425,-2.590194585,48.5214,0,9.999572783,0.521875,7.007966139,-2.975125578,90.00000001 +40.08,50.425,-2.590193178,48.5165,0,9.998684496,0.4596875,7.029137331,-2.923429143,90.00000001 +40.09,50.425,-2.590191771,48.5122,0,9.99868449,0.3965625,7.048840547,-2.869183447,90.00000001 +40.1,50.425,-2.590190364,48.5085,0,9.999572762,0.3315625,7.067071721,-2.812435759,90.00000001 +40.11,50.425,-2.590188957,48.5056,0,10.00068311,0.266875,7.083827069,-2.753235583,90.00000001 +40.12,50.425,-2.590187549,48.5032,0,10.0006831,0.2034375,7.099102983,-2.691634541,90.00000001 +40.13,50.425,-2.590186142,48.5015,0,9.999572752,0.1396875,7.112896369,-2.627686378,90.00000001 +40.14,50.425,-2.590184735,48.5004,0,9.998906541,0.075,7.125204305,-2.561446784,90.00000001 +40.15,50.425,-2.590183328,48.5,0,9.999572749,0.01,7.136024269,-2.492973629,90.00000001 +40.16,50.425,-2.590181921,48.5002,0,10.00090517,-0.055,7.145353913,-2.422326501,90.00000001 +40.17,50.425,-2.590180513,48.5011,0,10.00179345,-0.12,7.153191403,-2.349567106,90.00000001 +40.18,50.425,-2.590179106,48.5026,0,10.00179345,-0.1846875,7.159534962,-2.274758872,90.00000001 +40.19,50.425,-2.590177698,48.5048,0,10.00090517,-0.2484375,7.164383388,-2.197967,90.00000001 +40.2,50.425,-2.590176291,48.5076,0,9.999572761,-0.3115625,7.16773565,-2.11925847,90.00000001 +40.21,50.425,-2.590174884,48.511,0,9.998684488,-0.3753125,7.169591002,-2.038701922,90.00000001 +40.22,50.425,-2.590173477,48.5151,0,9.998684495,-0.44,7.169949043,-1.9563676,90.00000001 +40.23,50.425,-2.59017207,48.5198,0,9.99957278,-0.5046875,7.168809774,-1.872327239,90.00000001 +40.24,50.425,-2.590170663,48.5252,0,10.00068314,-0.568125,7.166173366,-1.786654235,90.00000001 +40.25,50.425,-2.590169255,48.5312,0,10.00068315,-0.63,7.162040392,-1.699423244,90.00000001 +40.26,50.425,-2.590167848,48.5378,0,9.999572808,-0.691875,7.156411769,-1.610710298,90.00000001 +40.27,50.425,-2.590166441,48.545,0,9.998906611,-0.755,7.149288529,-1.520592803,90.00000001 +40.28,50.425,-2.590165034,48.5529,0,9.999572832,-0.8184375,7.140672332,-1.429149369,90.00000001 +40.29,50.425,-2.590163627,48.5614,0,10.00068319,-0.88125,7.130564841,-1.336459638,90.00000001 +40.3,50.425,-2.590162219,48.5705,0,10.00068321,-0.9434375,7.11896829,-1.24260451,90.00000001 +40.31,50.425,-2.590160812,48.5803,0,9.999572875,-1.0046875,7.10588497,-1.147665804,90.00000001 +40.32,50.425,-2.590159405,48.5906,0,9.998684613,-1.0646875,7.09131769,-1.051726313,90.00000001 +40.33,50.425,-2.590157998,48.6016,0,9.99868463,-1.12375,7.075269486,-0.954869746,90.00000001 +40.34,50.425,-2.590156591,48.6131,0,9.999572926,-1.183125,7.057743739,-0.857180499,90.00000001 +40.35,50.425,-2.590155184,48.6252,0,10.00090536,-1.2434375,7.038744057,-0.758743772,90.00000001 +40.36,50.425,-2.590153776,48.638,0,10.00179366,-1.303125,7.018274395,-0.659645393,90.00000001 +40.37,50.425,-2.590152369,48.6513,0,10.00179368,-1.36125,6.99633905,-0.559971821,90.00000001 +40.38,50.425,-2.590150961,48.6652,0,10.00090543,-1.4184375,6.972942662,-0.459809918,90.00000001 +40.39,50.425,-2.590149554,48.6797,0,9.99957303,-1.475,6.948089987,-0.359247059,90.00000001 +40.4,50.425,-2.590148147,48.6947,0,9.998906845,-1.5315625,6.921786354,-0.258370963,90.00000001 +40.41,50.425,-2.59014674,48.7103,0,9.999573078,-1.588125,6.894037149,-0.157269524,90.00000001 +40.42,50.425,-2.590145333,48.7265,0,10.00068345,-1.643125,6.864848272,-0.056030975,90.00000001 +40.43,50.425,-2.590143925,48.7432,0,10.00068348,-1.6965625,6.834225741,0.045256447,90.00000001 +40.44,50.425,-2.590142518,48.7604,0,9.999573157,-1.75,6.802175914,0.146504449,90.00000001 +40.45,50.425,-2.590141111,48.7782,0,9.998684906,-1.8034375,6.76870561,0.247624624,90.00000001 +40.46,50.425,-2.590139704,48.7965,0,9.998684934,-1.85625,6.733821705,0.348528909,90.00000001 +40.47,50.425,-2.590138297,48.8153,0,9.999573242,-1.908125,6.697531533,0.44912924,90.00000001 +40.48,50.425,-2.59013689,48.8347,0,10.00068362,-1.958125,6.659842713,0.549337954,90.00000001 +40.49,50.425,-2.590135482,48.8545,0,10.00068365,-2.0065625,6.62076298,0.649067618,90.00000001 +40.5,50.425,-2.590134075,48.8748,0,9.999573336,-2.0553125,6.580300643,0.748231314,90.00000001 +40.51,50.425,-2.590132668,48.8956,0,9.998907159,-2.1046875,6.538464125,0.846742526,90.00000001 +40.52,50.425,-2.590131261,48.9169,0,9.999573401,-2.1528125,6.495262076,0.944515368,90.00000001 +40.53,50.425,-2.590129854,48.9387,0,10.00068378,-2.198125,6.450703606,1.041464582,90.00000001 +40.54,50.425,-2.590128446,48.9609,0,10.00090589,-2.2415625,6.404797999,1.137505601,90.00000001 +40.55,50.425,-2.590127039,48.9835,0,10.00068385,-2.2853125,6.357554821,1.232554716,90.00000001 +40.56,50.425,-2.590125632,49.0066,0,10.00090596,-2.3296875,6.308983928,1.326529019,90.00000001 +40.57,50.425,-2.590124224,49.0301,0,10.00068393,-2.3728125,6.259095462,1.419346577,90.00000001 +40.58,50.425,-2.590122817,49.0541,0,9.999573616,-2.4134375,6.207899906,1.510926432,90.00000001 +40.59,50.425,-2.59012141,49.0784,0,9.998907445,-2.453125,6.15540792,1.601188714,90.00000001 +40.6,50.425,-2.590120003,49.1031,0,9.999573693,-2.493125,6.101630445,1.690054754,90.00000001 +40.61,50.425,-2.590118596,49.1283,0,10.00068408,-2.53125,6.046578712,1.77744709,90.00000001 +40.62,50.425,-2.590117188,49.1538,0,10.00068412,-2.5665625,5.990264237,1.863289403,90.00000001 +40.63,50.425,-2.590115781,49.1796,0,9.999573812,-2.601875,5.932698766,1.947506922,90.00000001 +40.64,50.425,-2.590114374,49.2058,0,9.998907644,-2.638125,5.873894332,2.030026195,90.00000001 +40.65,50.425,-2.590112967,49.2324,0,9.999573895,-2.6728125,5.813863194,2.110775257,90.00000001 +40.66,50.425,-2.59011156,49.2593,0,10.00068429,-2.7046875,5.752617902,2.189683692,90.00000001 +40.67,50.425,-2.590110152,49.2865,0,10.00068433,-2.735,5.690171289,2.266682688,90.00000001 +40.68,50.425,-2.590108745,49.314,0,9.999574022,-2.7646875,5.626536305,2.341705094,90.00000001 +40.69,50.425,-2.590107338,49.3418,0,9.998685787,-2.793125,5.561726356,2.414685479,90.00000001 +40.7,50.425,-2.590105931,49.3699,0,9.998685831,-2.82,5.495754849,2.485560243,90.00000001 +40.71,50.425,-2.590104524,49.3982,0,9.999574154,-2.8465625,5.428635651,2.554267566,90.00000001 +40.72,50.425,-2.590103117,49.4268,0,10.00090662,-2.873125,5.360382741,2.620747515,90.00000001 +40.73,50.425,-2.590101709,49.4557,0,10.00179494,-2.898125,5.291010386,2.684942165,90.00000001 +40.74,50.425,-2.590100302,49.4848,0,10.00179499,-2.92125,5.220533083,2.74679548,90.00000001 +40.75,50.425,-2.590098894,49.5141,0,10.00090675,-2.943125,5.148965555,2.806253545,90.00000001 +40.76,50.425,-2.590097487,49.5437,0,9.999574382,-2.963125,5.076322699,2.863264507,90.00000001 +40.77,50.425,-2.59009608,49.5734,0,9.99868615,-2.98125,5.002619758,2.917778691,90.00000001 +40.78,50.425,-2.590094673,49.6033,0,9.998686196,-2.9984375,4.927872028,2.969748484,90.00000001 +40.79,50.425,-2.590093266,49.6334,0,9.999574521,-3.0146875,4.852095208,3.01912868,90.00000001 +40.8,50.425,-2.590091859,49.6636,0,10.00068492,-3.0296875,4.775305112,3.065876077,90.00000001 +40.81,50.425,-2.590090451,49.694,0,10.00068497,-3.043125,4.697517727,3.109950053,90.00000001 +40.82,50.425,-2.590089044,49.7245,0,9.999574665,-3.055,4.618749322,3.151312048,90.00000001 +40.83,50.425,-2.590087637,49.7551,0,9.998908503,-3.0665625,4.539016344,3.189926081,90.00000001 +40.84,50.425,-2.59008623,49.7858,0,9.99957476,-3.078125,4.458335464,3.22575846,90.00000001 +40.85,50.425,-2.590084823,49.8167,0,10.00068516,-3.0878125,4.376723527,3.258777903,90.00000001 +40.86,50.425,-2.590083415,49.8476,0,10.00068521,-3.094375,4.294197551,3.288955647,90.00000001 +40.87,50.425,-2.590082008,49.8786,0,9.999574906,-3.0984375,4.210774782,3.316265394,90.00000001 +40.88,50.425,-2.590080601,49.9096,0,9.998908745,-3.1015625,4.126472636,3.340683309,90.00000001 +40.89,50.425,-2.590079194,49.9406,0,9.999575003,-3.105,4.041308763,3.362188076,90.00000001 +40.9,50.425,-2.590077787,49.9717,0,10.0006854,-3.108125,3.955300865,3.380760961,90.00000001 +40.91,50.425,-2.590076379,50.0028,0,10.00090752,-3.1096875,3.868466991,3.396385807,90.00000001 +40.92,50.425,-2.590074972,50.0339,0,10.0006855,-3.1096875,3.780825247,3.409048919,90.00000001 +40.93,50.425,-2.590073565,50.065,0,10.00090762,-3.1078125,3.692393909,3.418739297,90.00000001 +40.94,50.425,-2.590072157,50.0961,0,10.00068559,-3.103125,3.603191485,3.425448518,90.00000001 +40.95,50.425,-2.59007075,50.1271,0,9.999575294,-3.0965625,3.513236539,3.429170624,90.00000001 +40.96,50.425,-2.590069343,50.158,0,9.998909134,-3.0903125,3.422547919,3.42990252,90.00000001 +40.97,50.425,-2.590067936,50.1889,0,9.999575392,-3.0846875,3.331144593,3.427643462,90.00000001 +40.98,50.425,-2.590066529,50.2197,0,10.00068579,-3.0778125,3.239045523,3.422395398,90.00000001 +40.99,50.425,-2.590065121,50.2505,0,10.00068584,-3.0678125,3.146270077,3.414163026,90.00000001 +41,50.425,-2.590063714,50.2811,0,9.999575534,-3.0546875,3.052837506,3.40295345,90.00000001 +41.01,50.425,-2.590062307,50.3116,0,9.998687303,-3.0403125,2.958767461,3.388776412,90.00000001 +41.02,50.425,-2.5900609,50.3419,0,9.998687352,-3.02625,2.864079482,3.371644286,90.00000001 +41.03,50.425,-2.590059493,50.3721,0,9.999575678,-3.0115625,2.768793335,3.351572085,90.00000001 +41.04,50.425,-2.590058086,50.4022,0,10.00068607,-2.9946875,2.672929016,3.328577283,90.00000001 +41.05,50.425,-2.590056678,50.432,0,10.00068612,-2.9765625,2.576506464,3.302679877,90.00000001 +41.06,50.425,-2.590055271,50.4617,0,9.999797887,-2.9584375,2.479545905,3.273902499,90.00000001 +41.07,50.425,-2.590053864,50.4912,0,9.999797934,-2.939375,2.38206745,3.242270187,90.00000001 +41.08,50.425,-2.590052457,50.5205,0,10.00068626,-2.9178125,2.284091552,3.207810614,90.00000001 +41.09,50.425,-2.590051049,50.5496,0,10.00090837,-2.8934375,2.185638667,3.170553747,90.00000001 +41.1,50.425,-2.590049642,50.5784,0,10.00068635,-2.868125,2.086729307,3.13053213,90.00000001 +41.11,50.425,-2.590048235,50.6069,0,10.00090846,-2.843125,1.987384212,3.087780654,90.00000001 +41.12,50.425,-2.590046827,50.6353,0,10.00068644,-2.8165625,1.887624009,3.042336564,90.00000001 +41.13,50.425,-2.59004542,50.6633,0,9.999576133,-2.7878125,1.787469669,2.994239565,90.00000001 +41.14,50.425,-2.590044013,50.691,0,9.998687898,-2.75875,1.686941989,2.943531482,90.00000001 +41.15,50.425,-2.590042606,50.7185,0,9.998687941,-2.7296875,1.586061998,2.890256606,90.00000001 +41.16,50.425,-2.590041199,50.7456,0,9.999576262,-2.699375,1.484850837,2.834461403,90.00000001 +41.17,50.425,-2.590039792,50.7725,0,10.00068665,-2.6665625,1.383329534,2.776194517,90.00000001 +41.18,50.425,-2.590038384,50.799,0,10.00068669,-2.63125,1.281519402,2.715506713,90.00000001 +41.19,50.425,-2.590036977,50.8251,0,9.999576386,-2.5953125,1.179441585,2.652450989,90.00000001 +41.2,50.425,-2.59003557,50.8509,0,9.998910217,-2.5596875,1.077117454,2.587082234,90.00000001 +41.21,50.425,-2.590034163,50.8763,0,9.999576466,-2.523125,0.974568436,2.519457515,90.00000001 +41.22,50.425,-2.590032756,50.9014,0,10.00068685,-2.485,0.871815847,2.449635847,90.00000001 +41.23,50.425,-2.590031348,50.926,0,10.00068689,-2.44625,0.768881172,2.37767802,90.00000001 +41.24,50.425,-2.590029941,50.9503,0,9.999798651,-2.4065625,0.665785953,2.303646831,90.00000001 +41.25,50.425,-2.590028534,50.9742,0,9.999798689,-2.3646875,0.562551736,2.227606794,90.00000001 +41.26,50.425,-2.590027127,50.9976,0,10.000687,-2.3215625,0.459199947,2.149624316,90.00000001 +41.27,50.425,-2.590025719,51.0206,0,10.00068704,-2.2784375,0.35575236,2.069767292,90.00000001 +41.28,50.425,-2.590024312,51.0432,0,9.999798796,-2.2346875,0.252230403,1.988105394,90.00000001 +41.29,50.425,-2.590022905,51.0653,0,9.999798831,-2.1896875,0.148655791,1.90470984,90.00000001 +41.3,50.425,-2.590021498,51.087,0,10.00068714,-2.143125,0.045050124,1.819653338,90.00000001 +41.31,50.425,-2.59002009,51.1082,0,10.00068718,-2.095,-0.058564938,1.733010145,90.00000001 +41.32,50.425,-2.590018683,51.1289,0,9.999576861,-2.0465625,-0.16216774,1.644855661,90.00000001 +41.33,50.425,-2.590017276,51.1491,0,9.998910683,-1.998125,-0.265736737,1.555266891,90.00000001 +41.34,50.425,-2.590015869,51.1689,0,9.999576924,-1.9484375,-0.369250157,1.464321873,90.00000001 +41.35,50.425,-2.590014462,51.1881,0,10.0006873,-1.8978125,-0.472686514,1.372099962,90.00000001 +41.36,50.425,-2.590013054,51.2068,0,10.00068733,-1.846875,-0.576024151,1.278681542,90.00000001 +41.37,50.425,-2.590011647,51.2251,0,9.999577011,-1.7946875,-0.679241523,1.18414809,90.00000001 +41.38,50.425,-2.59001024,51.2427,0,9.99868876,-1.7415625,-0.782317032,1.088582053,90.00000001 +41.39,50.425,-2.590008833,51.2599,0,9.998688787,-1.6884375,-0.885229133,0.992066739,90.00000001 +41.4,50.425,-2.590007426,51.2765,0,9.999577092,-1.634375,-0.987956397,0.894686374,90.00000001 +41.41,50.425,-2.590006019,51.2926,0,10.00068747,-1.5784375,-1.090477283,0.796525812,90.00000001 +41.42,50.425,-2.590004611,51.3081,0,10.00090956,-1.5215625,-1.192770532,0.697670654,90.00000001 +41.43,50.425,-2.590003204,51.323,0,10.00068751,-1.465,-1.294814602,0.598207128,90.00000001 +41.44,50.425,-2.590001797,51.3374,0,10.00090961,-1.408125,-1.396588293,0.498221925,90.00000001 +41.45,50.425,-2.590000389,51.3512,0,10.00068756,-1.3496875,-1.498070348,0.397802305,90.00000001 +41.46,50.425,-2.589998982,51.3644,0,9.999799299,-1.2903125,-1.599239511,0.29703576,90.00000001 +41.47,50.425,-2.589997575,51.377,0,9.999799319,-1.2315625,-1.700074697,0.196010237,90.00000001 +41.48,50.425,-2.589996168,51.389,0,10.00068762,-1.1734375,-1.800554879,0.094813743,90.00000001 +41.49,50.425,-2.58999476,51.4005,0,10.00068763,-1.1146875,-1.900659028,-0.00646537,90.00000001 +41.5,50.425,-2.589993353,51.4113,0,9.999577303,-1.0546875,-2.000366232,-0.107738927,90.00000001 +41.51,50.425,-2.589991946,51.4216,0,9.998689041,-0.9934375,-2.099655693,-0.20891846,90.00000001 +41.52,50.425,-2.589990539,51.4312,0,9.998689056,-0.93125,-2.198506669,-0.309915851,90.00000001 +41.53,50.425,-2.589989132,51.4402,0,9.999577348,-0.86875,-2.296898534,-0.410642977,90.00000001 +41.54,50.425,-2.589987725,51.4486,0,10.00068771,-0.8065625,-2.394810661,-0.511012005,90.00000001 +41.55,50.425,-2.589986317,51.4563,0,10.00068772,-0.7446875,-2.492222711,-0.610935443,90.00000001 +41.56,50.425,-2.58998491,51.4635,0,9.999577385,-0.681875,-2.589114286,-0.710326145,90.00000001 +41.57,50.425,-2.589983503,51.47,0,9.998911186,-0.618125,-2.685465161,-0.809097423,90.00000001 +41.58,50.425,-2.589982096,51.4758,0,9.999577404,-0.5553125,-2.781255224,-0.90716316,90.00000001 +41.59,50.425,-2.589980689,51.4811,0,10.00068776,-0.493125,-2.876464423,-1.004437815,90.00000001 +41.6,50.425,-2.589979281,51.4857,0,10.00090984,-0.4296875,-2.971072933,-1.100836589,90.00000001 +41.61,50.425,-2.589977874,51.4897,0,10.00068777,-0.365,-3.06506093,-1.196275429,90.00000001 +41.62,50.425,-2.589976467,51.493,0,10.00090985,-0.3,-3.158408875,-1.290671085,90.00000001 +41.63,50.425,-2.589975059,51.4957,0,10.00068778,-0.2353125,-3.251097232,-1.383941281,90.00000001 +41.64,50.425,-2.589973652,51.4977,0,9.999577438,-0.1715625,-3.343106634,-1.476004655,90.00000001 +41.65,50.425,-2.589972245,51.4991,0,9.998911231,-0.108125,-3.434417829,-1.566780879,90.00000001 +41.66,50.425,-2.589970838,51.4999,0,9.999577441,-0.043125,-3.525011795,-1.656190886,90.00000001 +41.67,50.425,-2.589969431,51.5,0,10.00068779,0.023125,-3.614869683,-1.744156695,90.00000001 +41.68,50.425,-2.589968023,51.4994,0,10.00068779,0.088125,-3.703972584,-1.830601531,90.00000001 +41.69,50.425,-2.589966616,51.4982,0,9.999577439,0.1515625,-3.792301935,-1.915450106,90.00000001 +41.7,50.425,-2.589965209,51.4964,0,9.998911226,0.215,-3.879839401,-1.998628337,90.00000001 +41.71,50.425,-2.589963802,51.4939,0,9.999577432,0.2784375,-3.966566533,-2.080063745,90.00000001 +41.72,50.425,-2.589962395,51.4908,0,10.00068778,0.3415625,-4.05246534,-2.159685341,90.00000001 +41.73,50.425,-2.589960987,51.4871,0,10.00068777,0.4053125,-4.13751783,-2.237423624,90.00000001 +41.74,50.425,-2.58995958,51.4827,0,9.999577415,0.47,-4.221706243,-2.313210814,90.00000001 +41.75,50.425,-2.589958173,51.4777,0,9.998689128,0.5346875,-4.305012989,-2.386980906,90.00000001 +41.76,50.425,-2.589956766,51.472,0,9.998689118,0.5984375,-4.387420764,-2.4586695,90.00000001 +41.77,50.425,-2.589955359,51.4657,0,9.999577387,0.6615625,-4.468912207,-2.528214086,90.00000001 +41.78,50.425,-2.589953952,51.4588,0,10.0009098,0.725,-4.549470417,-2.595553988,90.00000001 +41.79,50.425,-2.589952544,51.4512,0,10.00179806,0.788125,-4.629078491,-2.660630591,90.00000001 +41.8,50.425,-2.589951137,51.443,0,10.00179805,0.8496875,-4.70771987,-2.72338706,90.00000001 +41.81,50.425,-2.589949729,51.4342,0,10.00090976,0.91,-4.785378112,-2.783768733,90.00000001 +41.82,50.425,-2.589948322,51.4248,0,9.999577324,0.9703125,-4.862036942,-2.841722841,90.00000001 +41.83,50.425,-2.589946915,51.4148,0,9.99868903,1.0315625,-4.937680435,-2.897198964,90.00000001 +41.84,50.425,-2.589945508,51.4042,0,9.998689013,1.093125,-5.012292775,-2.950148744,90.00000001 +41.85,50.425,-2.589944101,51.3929,0,9.999577274,1.1534375,-5.085858321,-3.000525886,90.00000001 +41.86,50.425,-2.589942694,51.3811,0,10.0006876,1.213125,-5.158361776,-3.048286502,90.00000001 +41.87,50.425,-2.589941286,51.3687,0,10.00068758,1.2734375,-5.229787955,-3.093389052,90.00000001 +41.88,50.425,-2.589939879,51.3556,0,9.999577216,1.3328125,-5.300121962,-3.135794059,90.00000001 +41.89,50.425,-2.589938472,51.342,0,9.998910985,1.3896875,-5.36934913,-3.175464626,90.00000001 +41.9,50.425,-2.589937065,51.3278,0,9.999577172,1.4453125,-5.437454961,-3.212366087,90.00000001 +41.91,50.425,-2.589935658,51.3131,0,10.0006875,1.5015625,-5.504425248,-3.246466415,90.00000001 +41.92,50.425,-2.58993425,51.2978,0,10.00068747,1.5584375,-5.570245952,-3.277735701,90.00000001 +41.93,50.425,-2.589932843,51.2819,0,9.9995771,1.6146875,-5.634903437,-3.306146788,90.00000001 +41.94,50.425,-2.589931436,51.2655,0,9.998910866,1.6696875,-5.698384181,-3.331674865,90.00000001 +41.95,50.425,-2.589930029,51.2485,0,9.999577049,1.7234375,-5.760674835,-3.354297645,90.00000001 +41.96,50.425,-2.589928622,51.231,0,10.00068737,1.7765625,-5.821762449,-3.373995418,90.00000001 +41.97,50.425,-2.589927214,51.213,0,10.00090941,1.8296875,-5.881634304,-3.390751054,90.00000001 +41.98,50.425,-2.589925807,51.1944,0,10.00068731,1.8815625,-5.940277795,-3.404549883,90.00000001 +41.99,50.425,-2.5899244,51.1753,0,10.00090935,1.9315625,-5.997680775,-3.415379931,90.00000001 +42,50.425,-2.589922992,51.1558,0,10.00068725,1.9815625,-6.053831211,-3.423231687,90.00000001 +42.01,50.425,-2.589921585,51.1357,0,9.999576873,2.0315625,-6.108717417,-3.428098333,90.00000001 +42.02,50.425,-2.589920178,51.1151,0,9.998910631,2.0796875,-6.162327817,-3.42997563,90.00000001 +42.03,50.425,-2.589918771,51.0941,0,9.999576806,2.1265625,-6.214651355,-3.428861914,90.00000001 +42.04,50.425,-2.589917364,51.0726,0,10.00068712,2.1734375,-6.265677028,-3.424758219,90.00000001 +42.05,50.425,-2.589915956,51.0506,0,10.00068709,2.2196875,-6.31539418,-3.417668095,90.00000001 +42.06,50.425,-2.589914549,51.0282,0,9.999576704,2.2646875,-6.36379244,-3.407597674,90.00000001 +42.07,50.425,-2.589913142,51.0053,0,9.998688389,2.308125,-6.410861725,-3.39455578,90.00000001 +42.08,50.425,-2.589911735,50.982,0,9.998688352,2.35,-6.45659218,-3.378553813,90.00000001 +42.09,50.425,-2.589910328,50.9583,0,9.999576594,2.3915625,-6.500974236,-3.359605641,90.00000001 +42.1,50.425,-2.589908921,50.9342,0,10.00068691,2.433125,-6.543998668,-3.337727878,90.00000001 +42.11,50.425,-2.589907513,50.9096,0,10.00068687,2.473125,-6.585656481,-3.312939603,90.00000001 +42.12,50.425,-2.589906106,50.8847,0,9.999576479,2.51125,-6.625938966,-3.285262361,90.00000001 +42.13,50.425,-2.589904699,50.8594,0,9.99891023,2.5484375,-6.664837644,-3.254720273,90.00000001 +42.14,50.425,-2.589903292,50.8337,0,9.999576399,2.5846875,-6.70234455,-3.221340096,90.00000001 +42.15,50.425,-2.589901885,50.8077,0,10.00090878,2.6196875,-6.738451663,-3.185150821,90.00000001 +42.16,50.425,-2.589900477,50.7813,0,10.00179701,2.6534375,-6.773151591,-3.146184076,90.00000001 +42.17,50.425,-2.58989907,50.7546,0,10.00179697,2.68625,-6.806437058,-3.10447378,90.00000001 +42.18,50.425,-2.589897662,50.7276,0,10.00090865,2.7184375,-6.838301018,-3.060056373,90.00000001 +42.19,50.425,-2.589896255,50.7002,0,9.99957619,2.7496875,-6.868736937,-3.012970529,90.00000001 +42.2,50.425,-2.589894848,50.6726,0,9.998687868,2.7796875,-6.897738399,-2.96325733,90.00000001 +42.21,50.425,-2.589893441,50.6446,0,9.998687825,2.808125,-6.92529933,-2.910960092,90.00000001 +42.22,50.425,-2.589892034,50.6164,0,9.99957606,2.8346875,-6.951414059,-2.856124536,90.00000001 +42.23,50.425,-2.589890627,50.5879,0,10.00068636,2.86,-6.976077027,-2.798798332,90.00000001 +42.24,50.425,-2.589889219,50.5592,0,10.00068632,2.8846875,-6.999283136,-2.739031558,90.00000001 +42.25,50.425,-2.589887812,50.5302,0,9.999575924,2.908125,-7.021027572,-2.676876294,90.00000001 +42.26,50.425,-2.589886405,50.501,0,9.99890967,2.93,-7.041305694,-2.612386743,90.00000001 +42.27,50.425,-2.589884998,50.4716,0,9.999575833,2.95125,-7.060113377,-2.545619169,90.00000001 +42.28,50.425,-2.589883591,50.442,0,10.00068614,2.9715625,-7.077446611,-2.476631785,90.00000001 +42.29,50.425,-2.589882183,50.4121,0,10.00068609,2.9896875,-7.093301843,-2.40548475,90.00000001 +42.3,50.425,-2.589880776,50.3822,0,9.999575693,3.0065625,-7.107675693,-2.332240118,90.00000001 +42.31,50.425,-2.589879369,50.352,0,9.998687367,3.023125,-7.120565238,-2.256961657,90.00000001 +42.32,50.425,-2.589877962,50.3217,0,9.99868732,3.0378125,-7.131967728,-2.179715143,90.00000001 +42.33,50.425,-2.589876555,50.2912,0,9.999575551,3.05,-7.141880815,-2.100567899,90.00000001 +42.34,50.425,-2.589875148,50.2607,0,10.00090792,3.0615625,-7.150302377,-2.019588909,90.00000001 +42.35,50.425,-2.58987374,50.23,0,10.00179615,3.073125,-7.157230698,-1.936848819,90.00000001 +42.36,50.425,-2.589872333,50.1992,0,10.0017961,3.0828125,-7.162664343,-1.852419763,90.00000001 +42.37,50.425,-2.589870925,50.1683,0,10.00090778,3.0896875,-7.16660211,-1.766375311,90.00000001 +42.38,50.425,-2.589869518,50.1374,0,9.999575311,3.095,-7.169043254,-1.678790633,90.00000001 +42.39,50.425,-2.589868111,50.1064,0,9.998909053,3.1,-7.169987259,-1.589741991,90.00000001 +42.4,50.425,-2.589866704,50.0754,0,9.999575214,3.1046875,-7.169433897,-1.499307077,90.00000001 +42.41,50.425,-2.589865297,50.0443,0,10.00068551,3.108125,-7.167383281,-1.407564732,90.00000001 +42.42,50.425,-2.589863889,50.0132,0,10.00068546,3.1096875,-7.163835812,-1.314594995,90.00000001 +42.43,50.425,-2.589862482,49.9821,0,9.999575067,3.1096875,-7.158792294,-1.220478885,90.00000001 +42.44,50.425,-2.589861075,49.951,0,9.998686741,3.108125,-7.152253814,-1.125298506,90.00000001 +42.45,50.425,-2.589859668,49.9199,0,9.998686692,3.1046875,-7.144221576,-1.029136879,90.00000001 +42.46,50.425,-2.589858261,49.8889,0,9.999574921,3.1,-7.134697414,-0.932077829,90.00000001 +42.47,50.425,-2.589856854,49.8579,0,10.00068522,3.095,-7.123683274,-0.834205923,90.00000001 +42.48,50.425,-2.589855446,49.827,0,10.00068517,3.089375,-7.111181392,-0.735606648,90.00000001 +42.49,50.425,-2.589854039,49.7961,0,9.999574777,3.0815625,-7.097194461,-0.636365888,90.00000001 +42.5,50.425,-2.589852632,49.7653,0,9.998908519,3.07125,-7.081725403,-0.53657022,90.00000001 +42.51,50.425,-2.589851225,49.7347,0,9.99957468,3.06,-7.064777368,-0.436306616,90.00000001 +42.52,50.425,-2.589849818,49.7041,0,10.00068498,3.048125,-7.046353968,-0.335662626,90.00000001 +42.53,50.425,-2.58984841,49.6737,0,10.000907,3.0346875,-7.02645904,-0.234725854,90.00000001 +42.54,50.425,-2.589847003,49.6434,0,10.00068489,3.02,-7.005096709,-0.133584422,90.00000001 +42.55,50.425,-2.589845596,49.6133,0,10.00090691,3.0046875,-6.982271446,-0.032326508,90.00000001 +42.56,50.425,-2.589844188,49.5833,0,10.00068479,2.9878125,-6.957988062,0.068959596,90.00000001 +42.57,50.425,-2.589842781,49.5535,0,9.999574397,2.968125,-6.932251543,0.170185539,90.00000001 +42.58,50.425,-2.589841374,49.5239,0,9.998908142,2.946875,-6.905067331,0.271263144,90.00000001 +42.59,50.425,-2.589839967,49.4946,0,9.999574305,2.9265625,-6.876441099,0.372104174,90.00000001 +42.6,50.425,-2.58983856,49.4654,0,10.00068461,2.90625,-6.846378806,0.472620681,90.00000001 +42.61,50.425,-2.589837152,49.4364,0,10.00068456,2.8828125,-6.814886696,0.572725117,90.00000001 +42.62,50.425,-2.589835745,49.4077,0,9.999574168,2.8565625,-6.781971417,0.672330105,90.00000001 +42.63,50.425,-2.589834338,49.3793,0,9.998907915,2.83,-6.747639786,0.771348786,90.00000001 +42.64,50.425,-2.589832931,49.3511,0,9.99957408,2.803125,-6.711899022,0.869694872,90.00000001 +42.65,50.425,-2.589831524,49.3232,0,10.00068439,2.7746875,-6.674756575,0.967282533,90.00000001 +42.66,50.425,-2.589830116,49.2956,0,10.00068434,2.745,-6.636220178,1.064026743,90.00000001 +42.67,50.425,-2.589828709,49.2683,0,9.99957395,2.7146875,-6.596297912,1.159843106,90.00000001 +42.68,50.425,-2.589827302,49.2413,0,9.998685629,2.683125,-6.554998025,1.254648083,90.00000001 +42.69,50.425,-2.589825895,49.2146,0,9.998685588,2.6496875,-6.512329285,1.34835894,90.00000001 +42.7,50.425,-2.589824488,49.1883,0,9.999573826,2.6146875,-6.468300515,1.44089403,90.00000001 +42.71,50.425,-2.589823081,49.1623,0,10.0009062,2.5784375,-6.422920883,1.532172681,90.00000001 +42.72,50.425,-2.589821673,49.1367,0,10.00179444,2.5415625,-6.376199899,1.622115195,90.00000001 +42.73,50.425,-2.589820266,49.1115,0,10.0017944,2.5046875,-6.328147361,1.710643248,90.00000001 +42.74,50.425,-2.589818858,49.0866,0,10.00090608,2.4665625,-6.278773296,1.797679548,90.00000001 +42.75,50.425,-2.589817451,49.0621,0,9.999573628,2.42625,-6.22808796,1.883148292,90.00000001 +42.76,50.425,-2.589816044,49.0381,0,9.998685312,2.385,-6.176101952,1.966974825,90.00000001 +42.77,50.425,-2.589814637,49.0144,0,9.998685275,2.3434375,-6.122826159,2.049086209,90.00000001 +42.78,50.425,-2.58981323,48.9912,0,9.999573517,2.30125,-6.068271696,2.129410709,90.00000001 +42.79,50.425,-2.589811823,48.9684,0,10.00068383,2.258125,-6.012449965,2.207878368,90.00000001 +42.8,50.425,-2.589810415,48.946,0,10.00068379,2.213125,-5.955372597,2.284420716,90.00000001 +42.81,50.425,-2.589809008,48.9241,0,9.999573413,2.1665625,-5.897051509,2.358971005,90.00000001 +42.82,50.425,-2.589807601,48.9027,0,9.998907171,2.12,-5.837498907,2.431464204,90.00000001 +42.83,50.425,-2.589806194,48.8817,0,9.999573347,2.073125,-5.776727221,2.501837172,90.00000001 +42.84,50.425,-2.589804787,48.8612,0,10.00068366,2.0246875,-5.714749173,2.570028489,90.00000001 +42.85,50.425,-2.589803379,48.8412,0,10.00068363,1.9746875,-5.651577654,2.635978739,90.00000001 +42.86,50.425,-2.589801972,48.8217,0,9.999573252,1.9234375,-5.587225842,2.699630339,90.00000001 +42.87,50.425,-2.589800565,48.8027,0,9.998907014,1.8715625,-5.521707259,2.760927828,90.00000001 +42.88,50.425,-2.589799158,48.7843,0,9.999573194,1.82,-5.455035483,2.819817747,90.00000001 +42.89,50.425,-2.589797751,48.7663,0,10.00068351,1.768125,-5.387224553,2.876248705,90.00000001 +42.9,50.425,-2.589796343,48.7489,0,10.00090556,1.7146875,-5.318288506,2.930171596,90.00000001 +42.91,50.425,-2.589794936,48.732,0,10.00068346,1.6603125,-5.248241837,2.981539325,90.00000001 +42.92,50.425,-2.589793529,48.7157,0,10.0009055,1.60625,-5.177099157,3.030307086,90.00000001 +42.93,50.425,-2.589792121,48.6999,0,10.00068341,1.5515625,-5.104875249,3.076432366,90.00000001 +42.94,50.425,-2.589790714,48.6846,0,9.999573037,1.4946875,-5.031585295,3.119874943,90.00000001 +42.95,50.425,-2.589789307,48.67,0,9.998906806,1.436875,-4.957244594,3.160596944,90.00000001 +42.96,50.425,-2.5897879,48.6559,0,9.999572993,1.38,-4.881868559,3.198562904,90.00000001 +42.97,50.425,-2.589786493,48.6424,0,10.00068332,1.323125,-4.805473059,3.233739647,90.00000001 +42.98,50.425,-2.589785085,48.6294,0,10.0006833,1.2646875,-4.728073967,3.266096522,90.00000001 +42.99,50.425,-2.589783678,48.6171,0,9.999572933,1.205,-4.649687496,3.295605281,90.00000001 +43,50.425,-2.589782271,48.6053,0,9.998684635,1.145,-4.570330034,3.322240255,90.00000001 +43.01,50.425,-2.589780864,48.5942,0,9.998684617,1.0846875,-4.490018024,3.345978183,90.00000001 +43.02,50.425,-2.589779457,48.5836,0,9.99957288,1.0234375,-4.408768426,3.366798324,90.00000001 +43.03,50.425,-2.58977805,48.5737,0,10.00068321,0.9615625,-4.326598085,3.384682628,90.00000001 +43.04,50.425,-2.589776642,48.5644,0,10.0006832,0.9003125,-4.243524133,3.399615398,90.00000001 +43.05,50.425,-2.589775235,48.5557,0,9.999794905,0.8396875,-4.159564043,3.411583684,90.00000001 +43.06,50.425,-2.589773828,48.5476,0,9.999794893,0.778125,-4.074735235,3.420577002,90.00000001 +43.07,50.425,-2.589772421,48.5401,0,10.00068316,0.715,-3.989055528,3.426587558,90.00000001 +43.08,50.425,-2.589771013,48.5333,0,10.00090522,0.6515625,-3.902542682,3.429610025,90.00000001 +43.09,50.425,-2.589769606,48.5271,0,10.00068314,0.5884375,-3.815214919,3.429641824,90.00000001 +43.1,50.425,-2.589768199,48.5215,0,10.0009052,0.525,-3.727090343,3.426682956,90.00000001 +43.11,50.425,-2.589766791,48.5166,0,10.00068312,0.4615625,-3.638187404,3.420735998,90.00000001 +43.12,50.425,-2.589765384,48.5123,0,9.999572768,0.398125,-3.548524723,3.411806049,90.00000001 +43.13,50.425,-2.589763977,48.5086,0,9.998684484,0.3334375,-3.458120978,3.39990096,90.00000001 +43.14,50.425,-2.58976257,48.5056,0,9.99868448,0.268125,-3.36699502,3.385031101,90.00000001 +43.15,50.425,-2.589761163,48.5033,0,9.999572754,0.20375,-3.275165928,3.367209478,90.00000001 +43.16,50.425,-2.589759756,48.5015,0,10.0006831,0.14,-3.18265284,3.346451618,90.00000001 +43.17,50.425,-2.589758348,48.5005,0,10.0006831,0.07625,-3.089475063,3.32277557,90.00000001 +43.18,50.425,-2.589756941,48.5,0,9.999572749,0.011875,-2.995652135,3.296201959,90.00000001 +43.19,50.425,-2.589755534,48.5002,0,9.998906541,-0.0534375,-2.901203595,3.266754106,90.00000001 +43.2,50.425,-2.589754127,48.5011,0,9.999572751,-0.118125,-2.806149209,3.234457564,90.00000001 +43.21,50.425,-2.58975272,48.5026,0,10.0006831,-0.1815625,-2.710508745,3.199340465,90.00000001 +43.22,50.425,-2.589751312,48.5047,0,10.0006831,-0.2453125,-2.614302255,3.161433577,90.00000001 +43.23,50.425,-2.589749905,48.5075,0,9.99979483,-0.31,-2.517549795,3.120769845,90.00000001 +43.24,50.425,-2.589748498,48.5109,0,9.999794836,-0.3746875,-2.420271531,3.077384736,90.00000001 +43.25,50.425,-2.589747091,48.515,0,10.00068312,-0.4384375,-2.32248786,3.031316122,90.00000001 +43.26,50.425,-2.589745683,48.5197,0,10.00068313,-0.5015625,-2.224219181,2.98260411,90.00000001 +43.27,50.425,-2.589744276,48.525,0,9.999794857,-0.565,-2.125486005,2.93129127,90.00000001 +43.28,50.425,-2.589742869,48.531,0,9.999794867,-0.6284375,-2.026308959,2.877422294,90.00000001 +43.29,50.425,-2.589741462,48.5376,0,10.00068316,-0.69125,-1.926708726,2.821044164,90.00000001 +43.3,50.425,-2.589740054,48.5448,0,10.00068317,-0.7534375,-1.826706105,2.762206039,90.00000001 +43.31,50.425,-2.589738647,48.5527,0,9.999572831,-0.8153125,-1.726322009,2.700959257,90.00000001 +43.32,50.425,-2.58973724,48.5611,0,9.998906635,-0.878125,-1.625577407,2.63735716,90.00000001 +43.33,50.425,-2.589735833,48.5702,0,9.999572858,-0.9415625,-1.524493328,2.571455268,90.00000001 +43.34,50.425,-2.589734426,48.58,0,10.00068322,-1.0028125,-1.423090856,2.503310991,90.00000001 +43.35,50.425,-2.589733018,48.5903,0,10.00068324,-1.061875,-1.321391192,2.432983802,90.00000001 +43.36,50.425,-2.589731611,48.6012,0,9.999572908,-1.121875,-1.21941559,2.360535065,90.00000001 +43.37,50.425,-2.589730204,48.6127,0,9.998684647,-1.183125,-1.117185309,2.286027863,90.00000001 +43.38,50.425,-2.589728797,48.6249,0,9.998684665,-1.243125,-1.01472172,2.209527226,90.00000001 +43.39,50.425,-2.58972739,48.6376,0,9.999572964,-1.30125,-0.91204625,2.131099846,90.00000001 +43.4,50.425,-2.589725983,48.6509,0,10.00068333,-1.35875,-0.809180273,2.050814078,90.00000001 +43.41,50.425,-2.589724575,48.6648,0,10.00090543,-1.41625,-0.70614533,1.968739993,90.00000001 +43.42,50.425,-2.589723168,48.6792,0,10.00068338,-1.4734375,-0.602962907,1.884949156,90.00000001 +43.43,50.425,-2.589721761,48.6943,0,10.00090547,-1.53,-0.499654549,1.799514617,90.00000001 +43.44,50.425,-2.589720353,48.7098,0,10.00068342,-1.58625,-0.396241912,1.712510861,90.00000001 +43.45,50.425,-2.589718946,48.726,0,9.999573103,-1.641875,-0.292746426,1.624013805,90.00000001 +43.46,50.425,-2.589717539,48.7427,0,9.99890692,-1.69625,-0.189189862,1.534100513,90.00000001 +43.47,50.425,-2.589716132,48.7599,0,9.999573156,-1.75,-0.085593821,1.442849535,90.00000001 +43.48,50.425,-2.589714725,48.7777,0,10.00068353,-1.803125,0.018020153,1.350340343,90.00000001 +43.49,50.425,-2.589713317,48.796,0,10.00068356,-1.8546875,0.121630346,1.256653607,90.00000001 +43.5,50.425,-2.58971191,48.8148,0,9.999573242,-1.905,0.225215156,1.16187109,90.00000001 +43.51,50.425,-2.589710503,48.8341,0,9.998907063,-1.955,0.328752927,1.066075354,90.00000001 +43.52,50.425,-2.589709096,48.8539,0,9.999573303,-2.005,0.432222,0.969350051,90.00000001 +43.53,50.425,-2.589707689,48.8742,0,10.00068368,-2.0546875,0.535600832,0.871779407,90.00000001 +43.54,50.425,-2.589706281,48.895,0,10.00068371,-2.103125,0.638867823,0.773448562,90.00000001 +43.55,50.425,-2.589704874,48.9163,0,9.9995734,-2.1496875,0.742001372,0.674443288,90.00000001 +43.56,50.425,-2.589703467,48.938,0,9.998907225,-2.195,0.844979993,0.574849874,90.00000001 +43.57,50.425,-2.58970206,48.9602,0,9.999573469,-2.24,0.947782144,0.474755178,90.00000001 +43.58,50.425,-2.589700653,48.9828,0,10.00068385,-2.2846875,1.050386394,0.374246521,90.00000001 +43.59,50.425,-2.589699245,49.0059,0,10.00090596,-2.3284375,1.152771202,0.273411449,90.00000001 +43.6,50.425,-2.589697838,49.0294,0,10.00068393,-2.37125,1.25491531,0.172338027,90.00000001 +43.61,50.425,-2.589696431,49.0533,0,10.00090603,-2.413125,1.356797348,0.071114261,90.00000001 +43.62,50.425,-2.589695023,49.0777,0,10.000684,-2.453125,1.458396057,-0.030171442,90.00000001 +43.63,50.425,-2.589693616,49.1024,0,9.999573692,-2.49125,1.559690183,-0.131430903,90.00000001 +43.64,50.425,-2.589692209,49.1275,0,9.998907522,-2.5284375,1.660658582,-0.232575716,90.00000001 +43.65,50.425,-2.589690802,49.153,0,9.99957377,-2.565,1.761280169,-0.333517759,90.00000001 +43.66,50.425,-2.589689395,49.1788,0,10.00068416,-2.60125,1.861533975,-0.434168911,90.00000001 +43.67,50.425,-2.589687987,49.205,0,10.0006842,-2.6365625,1.961398972,-0.534441509,90.00000001 +43.68,50.425,-2.58968658,49.2316,0,9.999573894,-2.6696875,2.060854361,-0.634248065,90.00000001 +43.69,50.425,-2.589685173,49.2584,0,9.998685657,-2.7015625,2.159879401,-0.733501543,90.00000001 +43.7,50.425,-2.589683766,49.2856,0,9.998685699,-2.7334375,2.258453352,-0.832115372,90.00000001 +43.71,50.425,-2.589682359,49.3131,0,9.99957402,-2.7646875,2.356555644,-0.930003607,90.00000001 +43.72,50.425,-2.589680952,49.3409,0,10.00068441,-2.7946875,2.454165823,-1.02708082,90.00000001 +43.73,50.425,-2.589679544,49.369,0,10.00068446,-2.8228125,2.551263491,-1.123262443,90.00000001 +43.74,50.425,-2.589678137,49.3974,0,9.999574153,-2.848125,2.647828308,-1.218464595,90.00000001 +43.75,50.425,-2.58967673,49.426,0,9.998907989,-2.8715625,2.743840221,-1.312604196,90.00000001 +43.76,50.425,-2.589675323,49.4548,0,9.999574242,-2.8953125,2.839279061,-1.405599143,90.00000001 +43.77,50.425,-2.589673916,49.4839,0,10.00090671,-2.9196875,2.934125005,-1.497368475,90.00000001 +43.78,50.425,-2.589672508,49.5132,0,10.00179503,-2.9428125,3.02835817,-1.587831979,90.00000001 +43.79,50.425,-2.589671101,49.5428,0,10.00179508,-2.9628125,3.121958905,-1.676910931,90.00000001 +43.8,50.425,-2.589669693,49.5725,0,10.00090684,-2.98,3.214907671,-1.764527579,90.00000001 +43.81,50.425,-2.589668286,49.6024,0,9.999574473,-2.996875,3.307185045,-1.85060555,90.00000001 +43.82,50.425,-2.589666879,49.6324,0,9.998686242,-3.0146875,3.398771718,-1.935069785,90.00000001 +43.83,50.425,-2.589665472,49.6627,0,9.99868629,-3.03125,3.489648611,-2.017846544,90.00000001 +43.84,50.425,-2.589664065,49.6931,0,9.999574616,-3.044375,3.579796759,-2.098863751,90.00000001 +43.85,50.425,-2.589662658,49.7236,0,10.00068501,-3.055,3.669197312,-2.178050701,90.00000001 +43.86,50.425,-2.58966125,49.7542,0,10.00068506,-3.065,3.757831591,-2.25533841,90.00000001 +43.87,50.425,-2.589659843,49.7849,0,9.999574758,-3.075,3.84568109,-2.330659384,90.00000001 +43.88,50.425,-2.589658436,49.8157,0,9.998908598,-3.0846875,3.932727474,-2.403947963,90.00000001 +43.89,50.425,-2.589657029,49.8466,0,9.999574856,-3.093125,4.01895258,-2.475140318,90.00000001 +43.9,50.425,-2.589655622,49.8776,0,10.00068525,-3.0996875,4.10433836,-2.544174284,90.00000001 +43.91,50.425,-2.589654214,49.9086,0,10.0006853,-3.1046875,4.188866996,-2.6109897,90.00000001 +43.92,50.425,-2.589652807,49.9397,0,9.999575001,-3.108125,4.272520839,-2.675528296,90.00000001 +43.93,50.425,-2.5896514,49.9708,0,9.99868677,-3.1096875,4.355282415,-2.737733808,90.00000001 +43.94,50.425,-2.589649993,50.0019,0,9.998686819,-3.1096875,4.437134478,-2.79755192,90.00000001 +43.95,50.425,-2.589648586,50.033,0,9.999575147,-3.108125,4.518059839,-2.854930549,90.00000001 +43.96,50.425,-2.589647179,50.0641,0,10.00090761,-3.105,4.598041711,-2.909819677,90.00000001 +43.97,50.425,-2.589645771,50.0951,0,10.00179594,-3.1015625,4.677063362,-2.962171346,90.00000001 +43.98,50.425,-2.589644364,50.1261,0,10.00179599,-3.098125,4.755108236,-3.011940007,90.00000001 +43.99,50.425,-2.589642956,50.1571,0,10.00090776,-3.0928125,4.832160058,-3.059082173,90.00000001 +44,50.425,-2.589641549,50.188,0,9.99957539,-3.0846875,4.90820273,-3.103556818,90.00000001 +44.01,50.425,-2.589640142,50.2188,0,9.998909229,-3.075,4.983220438,-3.14532504,90.00000001 +44.02,50.425,-2.589638735,50.2495,0,9.999575486,-3.065,5.057197426,-3.184350571,90.00000001 +44.03,50.425,-2.589637328,50.2801,0,10.00068588,-3.0546875,5.13011828,-3.220599261,90.00000001 +44.04,50.425,-2.58963592,50.3106,0,10.00068593,-3.043125,5.201967818,-3.254039542,90.00000001 +44.05,50.425,-2.589634513,50.341,0,9.999575629,-3.029375,5.27273097,-3.284642249,90.00000001 +44.06,50.425,-2.589633106,50.3712,0,9.998687397,-3.013125,5.342392955,-3.312380683,90.00000001 +44.07,50.425,-2.589631699,50.4013,0,9.998687444,-2.995,5.410939276,-3.337230722,90.00000001 +44.08,50.425,-2.589630292,50.4311,0,9.999575769,-2.9765625,5.478355611,-3.359170594,90.00000001 +44.09,50.425,-2.589628885,50.4608,0,10.00068616,-2.9584375,5.544627805,-3.378181276,90.00000001 +44.1,50.425,-2.589627477,50.4903,0,10.00068621,-2.939375,5.60974211,-3.394246096,90.00000001 +44.11,50.425,-2.58962607,50.5196,0,9.999575908,-2.918125,5.673684887,-3.407351073,90.00000001 +44.12,50.425,-2.589624663,50.5487,0,9.998909745,-2.8946875,5.736442788,-3.417484806,90.00000001 +44.13,50.425,-2.589623256,50.5775,0,9.999575999,-2.8696875,5.798002691,-3.42463847,90.00000001 +44.14,50.425,-2.589621849,50.6061,0,10.00090846,-2.8434375,5.858351763,-3.428805764,90.00000001 +44.15,50.425,-2.589620441,50.6344,0,10.00179678,-2.8165625,5.917477398,-3.429983078,90.00000001 +44.16,50.425,-2.589619034,50.6624,0,10.00179683,-2.7896875,5.975367277,-3.42816938,90.00000001 +44.17,50.425,-2.589617626,50.6902,0,10.00090859,-2.7615625,6.032009254,-3.423366332,90.00000001 +44.18,50.425,-2.589616219,50.7177,0,9.999576217,-2.73125,6.087391527,-3.415578002,90.00000001 +44.19,50.425,-2.589614812,50.7448,0,9.998687981,-2.6996875,6.141502463,-3.404811266,90.00000001 +44.2,50.425,-2.589613405,50.7717,0,9.998688023,-2.6665625,6.194330891,-3.391075462,90.00000001 +44.21,50.425,-2.589611998,50.7982,0,9.999576344,-2.6315625,6.245865694,-3.374382623,90.00000001 +44.22,50.425,-2.589610591,50.8243,0,10.00068673,-2.5965625,6.296096159,-3.354747245,90.00000001 +44.23,50.425,-2.589609183,50.8501,0,10.00068677,-2.5615625,6.345011743,-3.332186516,90.00000001 +44.24,50.425,-2.589607776,50.8756,0,9.999576464,-2.5246875,6.392602248,-3.306720032,90.00000001 +44.25,50.425,-2.589606369,50.9006,0,9.998910295,-2.4865625,6.438857704,-3.278370023,90.00000001 +44.26,50.425,-2.589604962,50.9253,0,9.999576543,-2.448125,6.483768542,-3.247161241,90.00000001 +44.27,50.425,-2.589603555,50.9496,0,10.00068693,-2.4078125,6.52732531,-3.213120902,90.00000001 +44.28,50.425,-2.589602147,50.9735,0,10.00068697,-2.365,6.569518896,-3.176278684,90.00000001 +44.29,50.425,-2.58960074,50.9969,0,9.999576655,-2.321875,6.610340592,-3.136666674,90.00000001 +44.3,50.425,-2.589599333,51.0199,0,9.998688412,-2.2796875,6.649781746,-3.094319478,90.00000001 +44.31,50.425,-2.589597926,51.0425,0,9.998688447,-2.23625,6.687834222,-3.049273995,90.00000001 +44.32,50.425,-2.589596519,51.0647,0,9.999576761,-2.19,6.724489999,-3.001569471,90.00000001 +44.33,50.425,-2.589595112,51.0863,0,10.00090921,-2.143125,6.759741457,-2.951247505,90.00000001 +44.34,50.425,-2.589593704,51.1075,0,10.00179753,-2.096875,6.793581203,-2.898352041,90.00000001 +44.35,50.425,-2.589592297,51.1283,0,10.00179756,-2.049375,6.826002249,-2.842929203,90.00000001 +44.36,50.425,-2.589590889,51.1485,0,10.00090931,-2,6.856997719,-2.785027235,90.00000001 +44.37,50.425,-2.589589482,51.1683,0,9.999576923,-1.95,6.886561253,-2.724696727,90.00000001 +44.38,50.425,-2.589588075,51.1875,0,9.998910744,-1.8996875,6.914686548,-2.661990163,90.00000001 +44.39,50.425,-2.589586668,51.2063,0,9.999576982,-1.8484375,6.941367874,-2.596962375,90.00000001 +44.4,50.425,-2.589585261,51.2245,0,10.00068736,-1.79625,6.966599503,-2.529669972,90.00000001 +44.41,50.425,-2.589583853,51.2422,0,10.00068739,-1.7434375,6.990376335,-2.460171681,90.00000001 +44.42,50.425,-2.589582446,51.2594,0,9.999577066,-1.6896875,7.01269327,-2.388528064,90.00000001 +44.43,50.425,-2.589581039,51.276,0,9.998688813,-1.6346875,7.033545668,-2.314801631,90.00000001 +44.44,50.425,-2.589579632,51.2921,0,9.998688838,-1.5784375,7.052929232,-2.239056668,90.00000001 +44.45,50.425,-2.589578225,51.3076,0,9.999577141,-1.521875,7.070839892,-2.161359179,90.00000001 +44.46,50.425,-2.589576818,51.3225,0,10.00068751,-1.4665625,7.087273869,-2.081776946,90.00000001 +44.47,50.425,-2.58957541,51.3369,0,10.00068753,-1.41125,7.102227781,-2.00037941,90.00000001 +44.48,50.425,-2.589574003,51.3508,0,9.999577208,-1.353125,7.115698477,-1.917237505,90.00000001 +44.49,50.425,-2.589572596,51.364,0,9.99891102,-1.293125,7.12768315,-1.832423708,90.00000001 +44.5,50.425,-2.589571189,51.3766,0,9.999577249,-1.23375,7.138179278,-1.746012047,90.00000001 +44.51,50.425,-2.589569782,51.3887,0,10.00068762,-1.175,7.147184742,-1.658077808,90.00000001 +44.52,50.425,-2.589568374,51.4001,0,10.0009097,-1.11625,7.154697537,-1.568697767,90.00000001 +44.53,50.425,-2.589566967,51.411,0,10.00068765,-1.0565625,7.160716229,-1.477949732,90.00000001 +44.54,50.425,-2.58956556,51.4213,0,10.00090974,-0.9946875,7.165239444,-1.385912943,90.00000001 +44.55,50.425,-2.589564152,51.4309,0,10.00068768,-0.931875,7.168266323,-1.292667557,90.00000001 +44.56,50.425,-2.589562745,51.4399,0,9.999577347,-0.8703125,7.169796178,-1.198294991,90.00000001 +44.57,50.425,-2.589561338,51.4483,0,9.998911151,-0.8096875,7.169828722,-1.102877464,90.00000001 +44.58,50.425,-2.589559931,51.4561,0,9.999577373,-0.748125,7.168363955,-1.006498228,90.00000001 +44.59,50.425,-2.589558524,51.4633,0,10.00068773,-0.6846875,7.165402164,-0.909241336,90.00000001 +44.6,50.425,-2.589557116,51.4698,0,10.00068774,-0.6203125,7.16094398,-0.811191584,90.00000001 +44.61,50.425,-2.589555709,51.4757,0,9.999577403,-0.5565625,7.154990318,-0.712434401,90.00000001 +44.62,50.425,-2.589554302,51.4809,0,9.998911202,-0.4934375,7.147542382,-0.613056017,90.00000001 +44.63,50.425,-2.589552895,51.4856,0,9.999577418,-0.43,7.138601834,-0.513143007,90.00000001 +44.64,50.425,-2.589551488,51.4895,0,10.00068777,-0.3665625,7.12817045,-0.412782516,90.00000001 +44.65,50.425,-2.58955008,51.4929,0,10.00068778,-0.3034375,7.116250464,-0.312062093,90.00000001 +44.66,50.425,-2.589548673,51.4956,0,9.999577435,-0.239375,7.102844341,-0.211069573,90.00000001 +44.67,50.425,-2.589547266,51.4977,0,9.998911229,-0.17375,7.087954829,-0.109892961,90.00000001 +44.68,50.425,-2.589545859,51.4991,0,9.99957744,-0.1084375,7.071585138,-0.008620494,90.00000001 +44.69,50.425,-2.589544452,51.4998,0,10.00068779,-0.045,7.053738592,0.092659422,90.00000001 +44.7,50.425,-2.589543044,51.5,0,10.00090986,0.0184375,7.034419028,0.193858551,90.00000001 +44.71,50.425,-2.589541637,51.4995,0,10.00068779,0.08375,7.013630343,0.294888657,90.00000001 +44.72,50.425,-2.58954023,51.4983,0,10.00090986,0.1496875,6.991377006,0.39566162,90.00000001 +44.73,50.425,-2.589538822,51.4965,0,10.00068778,0.2146875,6.9676636,0.496089548,90.00000001 +44.74,50.425,-2.589537415,51.494,0,9.999577432,0.2784375,6.942495054,0.596084893,90.00000001 +44.75,50.425,-2.589536008,51.4909,0,9.998689149,0.3415625,6.915876696,0.69556045,90.00000001 +44.76,50.425,-2.589534601,51.4872,0,9.998689143,0.405,6.887814025,0.794429417,90.00000001 +44.77,50.425,-2.589533194,51.4828,0,9.999577415,0.4684375,6.858312944,0.892605678,90.00000001 +44.78,50.425,-2.589531787,51.4778,0,10.00068776,0.5315625,6.827379583,0.990003518,90.00000001 +44.79,50.425,-2.589530379,51.4722,0,10.00068775,0.595,6.795020359,1.08653814,90.00000001 +44.8,50.425,-2.589528972,51.4659,0,9.999577388,0.6584375,6.761242148,1.182125205,90.00000001 +44.81,50.425,-2.589527565,51.459,0,9.998911169,0.7215625,6.726051882,1.276681519,90.00000001 +44.82,50.425,-2.589526158,51.4515,0,9.999577366,0.785,6.68945701,1.370124461,90.00000001 +44.83,50.425,-2.589524751,51.4433,0,10.0006877,0.848125,6.651465153,1.462372728,90.00000001 +44.84,50.425,-2.589523343,51.4345,0,10.00068769,0.9096875,6.612084159,1.553345706,90.00000001 +44.85,50.425,-2.589521936,51.4251,0,9.999799395,0.97,6.571322338,1.642964155,90.00000001 +44.86,50.425,-2.589520529,51.4151,0,9.999799379,1.03,6.529188225,1.73114998,90.00000001 +44.87,50.425,-2.589519122,51.4045,0,10.00068764,1.0903125,6.485690529,1.817826119,90.00000001 +44.88,50.425,-2.589517714,51.3933,0,10.00068762,1.1515625,6.440838419,1.902917169,90.00000001 +44.89,50.425,-2.589516307,51.3815,0,9.999799325,1.213125,6.394641176,1.98634882,90.00000001 +44.9,50.425,-2.5895149,51.369,0,9.999799306,1.2728125,6.347108482,2.068048304,90.00000001 +44.91,50.425,-2.589513493,51.356,0,10.00068756,1.3296875,6.298250309,2.147944461,90.00000001 +44.92,50.425,-2.589512085,51.3424,0,10.00068754,1.3853125,6.248076853,2.225967562,90.00000001 +44.93,50.425,-2.589510678,51.3283,0,9.999577173,1.441875,6.196598543,2.302049654,90.00000001 +44.94,50.425,-2.589509271,51.3136,0,9.998910941,1.5,6.143826151,2.376124216,90.00000001 +44.95,50.425,-2.589507864,51.2983,0,9.999577126,1.558125,6.089770677,2.448126848,90.00000001 +44.96,50.425,-2.589506457,51.2824,0,10.00068745,1.6146875,6.034443466,2.517994639,90.00000001 +44.97,50.425,-2.589505049,51.266,0,10.00068742,1.6696875,5.977855977,2.585666684,90.00000001 +44.98,50.425,-2.589503642,51.249,0,9.999577049,1.723125,5.920020184,2.651084026,90.00000001 +44.99,50.425,-2.589502235,51.2315,0,9.998688743,1.775,5.860948006,2.71418954,90.00000001 +45,50.425,-2.589500828,51.2135,0,9.998688714,1.8265625,5.800651876,2.77492828,90.00000001 +45.01,50.425,-2.589499421,51.195,0,9.999576964,1.8784375,5.739144284,2.833247248,90.00000001 +45.02,50.425,-2.589498014,51.1759,0,10.00068728,1.9296875,5.676438236,2.889095564,90.00000001 +45.03,50.425,-2.589496606,51.1564,0,10.00068725,1.98,5.612546681,2.942424528,90.00000001 +45.04,50.425,-2.589495199,51.1363,0,9.999798943,2.03,5.547483026,2.993187672,90.00000001 +45.05,50.425,-2.589493792,51.1158,0,9.99979891,2.079375,5.481260908,3.041340706,90.00000001 +45.06,50.425,-2.589492385,51.0947,0,10.00068716,2.1265625,5.41389402,3.086841634,90.00000001 +45.07,50.425,-2.589490977,51.0732,0,10.00090919,2.1715625,5.345396572,3.129650806,90.00000001 +45.08,50.425,-2.58948957,51.0513,0,10.00068709,2.216875,5.275782772,3.169730923,90.00000001 +45.09,50.425,-2.589488163,51.0289,0,10.00090912,2.263125,5.205067176,3.207046919,90.00000001 +45.1,50.425,-2.589486755,51.006,0,10.00068702,2.3078125,5.133264563,3.241566366,90.00000001 +45.11,50.425,-2.589485348,50.9827,0,9.999576632,2.3496875,5.060390004,3.273259068,90.00000001 +45.12,50.425,-2.589483941,50.959,0,9.998688316,2.39,4.986458567,3.302097466,90.00000001 +45.13,50.425,-2.589482534,50.9349,0,9.998688279,2.43,4.911485836,3.328056407,90.00000001 +45.14,50.425,-2.589481127,50.9104,0,9.99957652,2.47,4.835487339,3.351113203,90.00000001 +45.15,50.425,-2.58947972,50.8855,0,10.00068683,2.5096875,4.758479061,3.371247799,90.00000001 +45.16,50.425,-2.589478312,50.8602,0,10.00068679,2.548125,4.680477045,3.388442607,90.00000001 +45.17,50.425,-2.589476905,50.8345,0,9.9995764,2.5846875,4.601497506,3.40268267,90.00000001 +45.18,50.425,-2.589475498,50.8085,0,9.998910151,2.6196875,4.521557059,3.4139555,90.00000001 +45.19,50.425,-2.589474091,50.7821,0,9.999576319,2.653125,4.440672321,3.422251299,90.00000001 +45.2,50.425,-2.589472684,50.7554,0,10.00068663,2.685,4.35886025,3.427562904,90.00000001 +45.21,50.425,-2.589471276,50.7284,0,10.00068658,2.7165625,4.276137864,3.429885561,90.00000001 +45.22,50.425,-2.589469869,50.7011,0,9.999798261,2.748125,4.192522409,3.429217377,90.00000001 +45.23,50.425,-2.589468462,50.6734,0,9.999798218,2.778125,4.108031474,3.425558813,90.00000001 +45.24,50.425,-2.589467055,50.6455,0,10.00068645,2.80625,4.022682592,3.418913132,90.00000001 +45.25,50.425,-2.589465647,50.6173,0,10.00068641,2.8334375,3.936493583,3.409286066,90.00000001 +45.26,50.425,-2.58946424,50.5888,0,9.999798086,2.8596875,3.84948255,3.396686094,90.00000001 +45.27,50.425,-2.589462833,50.5601,0,9.999798041,2.8846875,3.761667601,3.381124159,90.00000001 +45.28,50.425,-2.589461426,50.5311,0,10.00068627,2.908125,3.673067069,3.362613841,90.00000001 +45.29,50.425,-2.589460018,50.5019,0,10.00068623,2.9296875,3.583699404,3.341171239,90.00000001 +45.3,50.425,-2.589458611,50.4725,0,9.999575835,2.95,3.493583399,3.31681509,90.00000001 +45.31,50.425,-2.589457204,50.4429,0,9.998909579,2.97,3.402737789,3.28956665,90.00000001 +45.32,50.425,-2.589455797,50.4131,0,9.999575741,2.9896875,3.31118154,3.259449639,90.00000001 +45.33,50.425,-2.58945439,50.3831,0,10.00068604,3.0078125,3.218933845,3.226490356,90.00000001 +45.34,50.425,-2.589452982,50.3529,0,10.000686,3.023125,3.126013842,3.190717564,90.00000001 +45.35,50.425,-2.589451575,50.3226,0,9.9995756,3.0365625,3.032441067,3.152162375,90.00000001 +45.36,50.425,-2.589450168,50.2922,0,9.998687274,3.05,2.938235003,3.11085842,90.00000001 +45.37,50.425,-2.589448761,50.2616,0,9.998687226,3.0628125,2.843415301,3.066841797,90.00000001 +45.38,50.425,-2.589447354,50.2309,0,9.999575456,3.073125,2.748001785,3.020150836,90.00000001 +45.39,50.425,-2.589445947,50.2001,0,10.00068576,3.08125,2.652014395,2.970826275,90.00000001 +45.4,50.425,-2.589444539,50.1693,0,10.00090778,3.0884375,2.555473184,2.918911085,90.00000001 +45.41,50.425,-2.589443132,50.1383,0,10.00068566,3.095,2.458398262,2.864450529,90.00000001 +45.42,50.425,-2.589441725,50.1074,0,10.00090768,3.10125,2.360809971,2.807492165,90.00000001 +45.43,50.425,-2.589440317,50.0763,0,10.00068556,3.1065625,2.262728591,2.748085666,90.00000001 +45.44,50.425,-2.58943891,50.0452,0,9.999575166,3.109375,2.164174751,2.686282714,90.00000001 +45.45,50.425,-2.589437503,50.0141,0,9.998908909,3.1096875,2.065168905,2.622137339,90.00000001 +45.46,50.425,-2.589436096,49.983,0,9.999575069,3.1084375,1.965731793,2.555705403,90.00000001 +45.47,50.425,-2.589434689,49.9519,0,10.00068537,3.1065625,1.865884157,2.487044891,90.00000001 +45.48,50.425,-2.589433281,49.9209,0,10.00068532,3.1046875,1.765646852,2.41621562,90.00000001 +45.49,50.425,-2.589431874,49.8898,0,9.999574922,3.1015625,1.665040792,2.343279353,90.00000001 +45.5,50.425,-2.589430467,49.8588,0,9.998908665,3.0959375,1.564087061,2.268299689,90.00000001 +45.51,50.425,-2.58942906,49.8279,0,9.999574826,3.0884375,1.462806629,2.191342061,90.00000001 +45.52,50.425,-2.589427653,49.797,0,10.00068513,3.0796875,1.361220754,2.112473561,90.00000001 +45.53,50.425,-2.589426245,49.7663,0,10.00068508,3.07,1.259350577,2.031762944,90.00000001 +45.54,50.425,-2.589424838,49.7356,0,9.999574681,3.06,1.157217412,1.949280628,90.00000001 +45.55,50.425,-2.589423431,49.7051,0,9.998908424,3.049375,1.054842574,1.86509846,90.00000001 +45.56,50.425,-2.589422024,49.6746,0,9.999574586,3.0365625,0.95224749,1.779289894,90.00000001 +45.57,50.425,-2.589420617,49.6443,0,10.00068489,3.02125,0.849453476,1.691929816,90.00000001 +45.58,50.425,-2.589419209,49.6142,0,10.00090691,3.005,0.746482131,1.603094314,90.00000001 +45.59,50.425,-2.589417802,49.5842,0,10.00068479,2.988125,0.643354828,1.51286091,90.00000001 +45.6,50.425,-2.589416395,49.5544,0,10.00090682,2.969375,0.540093222,1.42130827,90.00000001 +45.61,50.425,-2.589414987,49.5248,0,10.0006847,2.9484375,0.436718745,1.328516208,90.00000001 +45.62,50.425,-2.58941358,49.4954,0,9.999574306,2.9265625,0.333253167,1.234565626,90.00000001 +45.63,50.425,-2.589412173,49.4663,0,9.998908052,2.9046875,0.229717917,1.13953857,90.00000001 +45.64,50.425,-2.589410766,49.4373,0,9.999574215,2.8815625,0.126134711,1.043517719,90.00000001 +45.65,50.425,-2.589409359,49.4086,0,10.00068452,2.85625,0.022525205,0.946587011,90.00000001 +45.66,50.425,-2.589407951,49.3802,0,10.00068447,2.8303125,-0.081089055,0.848830786,90.00000001 +45.67,50.425,-2.589406544,49.352,0,9.999574082,2.8046875,-0.184686356,0.750334413,90.00000001 +45.68,50.425,-2.589405137,49.3241,0,9.99868576,2.7778125,-0.288245097,0.651183723,90.00000001 +45.69,50.425,-2.58940373,49.2964,0,9.998685717,2.748125,-0.391743678,0.551465174,90.00000001 +45.7,50.425,-2.589402323,49.2691,0,9.999573952,2.71625,-0.495160382,0.451265742,90.00000001 +45.71,50.425,-2.589400916,49.2421,0,10.00068426,2.6834375,-0.598473726,0.350672802,90.00000001 +45.72,50.425,-2.589399508,49.2154,0,10.00068422,2.6496875,-0.701662049,0.249774075,90.00000001 +45.73,50.425,-2.589398101,49.1891,0,9.999573828,2.615,-0.804703868,0.148657567,90.00000001 +45.74,50.425,-2.589396694,49.1631,0,9.998907578,2.5796875,-0.907577638,0.047411398,90.00000001 +45.75,50.425,-2.589395287,49.1375,0,9.999573746,2.543125,-1.010261816,-0.053876081,90.00000001 +45.76,50.425,-2.58939388,49.1122,0,10.00090612,2.505,-1.112735089,-0.155116635,90.00000001 +45.77,50.425,-2.589392472,49.0874,0,10.00179436,2.4665625,-1.214975912,-0.256221856,90.00000001 +45.78,50.425,-2.589391065,49.0629,0,10.00179433,2.428125,-1.31696303,-0.357103738,90.00000001 +45.79,50.425,-2.589389657,49.0388,0,10.00090601,2.3878125,-1.418675128,-0.45767416,90.00000001 +45.8,50.425,-2.58938825,49.0151,0,9.999573554,2.345,-1.52009095,-0.55784546,90.00000001 +45.81,50.425,-2.589386843,48.9919,0,9.99868524,2.3015625,-1.621189353,-0.657530376,90.00000001 +45.82,50.425,-2.589385436,48.9691,0,9.998685204,2.2584375,-1.721949137,-0.756641876,90.00000001 +45.83,50.425,-2.589384029,48.9467,0,9.999573448,2.2146875,-1.822349334,-0.855093558,90.00000001 +45.84,50.425,-2.589382622,48.9248,0,10.00068376,2.1696875,-1.922368972,-0.952799592,90.00000001 +45.85,50.425,-2.589381214,48.9033,0,10.00068373,2.123125,-2.021987139,-1.049674838,90.00000001 +45.86,50.425,-2.589379807,48.8823,0,9.999573347,2.0746875,-2.121183035,-1.145634669,90.00000001 +45.87,50.425,-2.5893784,48.8618,0,9.998907106,2.025,-2.219935978,-1.240595548,90.00000001 +45.88,50.425,-2.589376993,48.8418,0,9.999573284,1.975,-2.318225283,-1.334474568,90.00000001 +45.89,50.425,-2.589375586,48.8223,0,10.0006836,1.925,-2.41603044,-1.427189911,90.00000001 +45.9,50.425,-2.589374178,48.8033,0,10.00068357,1.8746875,-2.513331049,-1.518660732,90.00000001 +45.91,50.425,-2.589372771,48.7848,0,9.999573195,1.823125,-2.610106829,-1.608807276,90.00000001 +45.92,50.425,-2.589371364,48.7668,0,9.998684887,1.77,-2.706337497,-1.697550876,90.00000001 +45.93,50.425,-2.589369957,48.7494,0,9.99868486,1.7165625,-2.802002943,-1.784814239,90.00000001 +45.94,50.425,-2.58936855,48.7325,0,9.999573113,1.663125,-2.897083283,-1.870521162,90.00000001 +45.95,50.425,-2.589367143,48.7161,0,10.00090551,1.608125,-2.991558581,-1.954596989,90.00000001 +45.96,50.425,-2.589365735,48.7003,0,10.00179376,1.5515625,-3.085409125,-2.036968381,90.00000001 +45.97,50.425,-2.589364328,48.6851,0,10.00179373,1.495,-3.178615321,-2.117563489,90.00000001 +45.98,50.425,-2.58936292,48.6704,0,10.00090543,1.4384375,-3.271157688,-2.196312069,90.00000001 +45.99,50.425,-2.589361513,48.6563,0,9.999572994,1.3815625,-3.363016917,-2.273145423,90.00000001 +46,50.425,-2.589360106,48.6428,0,9.998906764,1.3246875,-3.454173872,-2.347996572,90.00000001 +46.01,50.425,-2.589358699,48.6298,0,9.999572952,1.2665625,-3.544609416,-2.420800199,90.00000001 +46.02,50.425,-2.589357292,48.6174,0,10.00068328,1.20625,-3.634304698,-2.491492935,90.00000001 +46.03,50.425,-2.589355884,48.6057,0,10.00068326,1.1453125,-3.72324104,-2.560012957,90.00000001 +46.04,50.425,-2.589354477,48.5945,0,9.999572897,1.085,-3.811399822,-2.626300679,90.00000001 +46.05,50.425,-2.58935307,48.584,0,9.998684602,1.025,-3.89876265,-2.690298174,90.00000001 +46.06,50.425,-2.589351663,48.574,0,9.998684587,0.965,-3.985311306,-2.751949693,90.00000001 +46.07,50.425,-2.589350256,48.5647,0,9.99957285,0.904375,-4.071027625,-2.811201494,90.00000001 +46.08,50.425,-2.589348849,48.5559,0,10.00068318,0.841875,-4.15589379,-2.868001894,90.00000001 +46.09,50.425,-2.589347441,48.5478,0,10.00068317,0.778125,-4.239892038,-2.922301333,90.00000001 +46.1,50.425,-2.589346034,48.5404,0,9.999572812,0.7153125,-4.323004838,-2.974052486,90.00000001 +46.11,50.425,-2.589344627,48.5335,0,9.998906593,0.6534375,-4.405214828,-3.023210259,90.00000001 +46.12,50.425,-2.58934322,48.5273,0,9.999572792,0.59125,-4.486504819,-3.069731682,90.00000001 +46.13,50.425,-2.589341813,48.5217,0,10.00068313,0.528125,-4.56685791,-3.113576303,90.00000001 +46.14,50.425,-2.589340405,48.5167,0,10.00090519,0.4634375,-4.646257255,-3.154705792,90.00000001 +46.15,50.425,-2.589338998,48.5124,0,10.00068312,0.3984375,-4.724686297,-3.193084396,90.00000001 +46.16,50.425,-2.589337591,48.5088,0,10.00090518,0.335,-4.802128647,-3.228678539,90.00000001 +46.17,50.425,-2.589336183,48.5057,0,10.00068311,0.2715625,-4.878568093,-3.261457226,90.00000001 +46.18,50.425,-2.589334776,48.5033,0,9.999572754,0.2065625,-4.953988762,-3.291391864,90.00000001 +46.19,50.425,-2.589333369,48.5016,0,9.998906542,0.141875,-5.028374841,-3.318456385,90.00000001 +46.2,50.425,-2.589331962,48.5005,0,9.99957275,0.0784375,-5.101710803,-3.342627182,90.00000001 +46.21,50.425,-2.589330555,48.5,0,10.0006831,0.0146875,-5.17398135,-3.363883114,90.00000001 +46.22,50.425,-2.589329147,48.5002,0,10.0006831,-0.05,-5.245171356,-3.382205732,90.00000001 +46.23,50.425,-2.58932774,48.501,0,9.999572751,-0.115,-5.315265982,-3.397578992,90.00000001 +46.24,50.425,-2.589326333,48.5025,0,9.998906543,-0.18,-5.384250616,-3.409989487,90.00000001 +46.25,50.425,-2.589324926,48.5046,0,9.999572756,-0.2446875,-5.452110763,-3.419426445,90.00000001 +46.26,50.425,-2.589323519,48.5074,0,10.00068311,-0.3084375,-5.518832329,-3.425881617,90.00000001 +46.27,50.425,-2.589322111,48.5108,0,10.00068311,-0.3715625,-5.58440139,-3.429349387,90.00000001 +46.28,50.425,-2.589320704,48.5148,0,9.999572773,-0.4353125,-5.648804195,-3.429826661,90.00000001 +46.29,50.425,-2.589319297,48.5195,0,9.998684501,-0.5,-5.71202728,-3.427313095,90.00000001 +46.3,50.425,-2.58931789,48.5248,0,9.998684509,-0.5646875,-5.774057524,-3.421810924,90.00000001 +46.31,50.425,-2.589316483,48.5308,0,9.999572797,-0.628125,-5.834881922,-3.413324789,90.00000001 +46.32,50.425,-2.589315076,48.5374,0,10.00090523,-0.69,-5.89448781,-3.401862252,90.00000001 +46.33,50.425,-2.589313668,48.5446,0,10.00179351,-0.751875,-5.952862698,-3.387433227,90.00000001 +46.34,50.425,-2.589312261,48.5524,0,10.00179353,-0.815,-6.009994382,-3.37005026,90.00000001 +46.35,50.425,-2.589310853,48.5609,0,10.00090526,-0.878125,-6.065870945,-3.349728593,90.00000001 +46.36,50.425,-2.589309446,48.57,0,9.999572859,-0.9396875,-6.120480756,-3.32648593,90.00000001 +46.37,50.425,-2.589308039,48.5797,0,9.998684596,-1,-6.173812355,-3.300342496,90.00000001 +46.38,50.425,-2.589306632,48.59,0,9.998684612,-1.06,-6.225854685,-3.271321152,90.00000001 +46.39,50.425,-2.589305225,48.6009,0,9.999572907,-1.12,-6.276596801,-3.239447109,90.00000001 +46.4,50.425,-2.589303818,48.6124,0,10.00068327,-1.18,-6.326028105,-3.204748269,90.00000001 +46.41,50.425,-2.58930241,48.6245,0,10.00068329,-1.2396875,-6.374138282,-3.167254828,90.00000001 +46.42,50.425,-2.589301003,48.6372,0,9.999572964,-1.2984375,-6.420917364,-3.126999501,90.00000001 +46.43,50.425,-2.589299596,48.6505,0,9.998906776,-1.3565625,-6.466355495,-3.084017353,90.00000001 +46.44,50.425,-2.589298189,48.6643,0,9.999573006,-1.415,-6.510443223,-3.038345913,90.00000001 +46.45,50.425,-2.589296782,48.6788,0,10.00068338,-1.473125,-6.553171264,-2.990025002,90.00000001 +46.46,50.425,-2.589295374,48.6938,0,10.0006834,-1.5296875,-6.594530852,-2.939096732,90.00000001 +46.47,50.425,-2.589293967,48.7094,0,9.999573077,-1.585,-6.634513165,-2.885605564,90.00000001 +46.48,50.425,-2.58929256,48.7255,0,9.998906894,-1.6396875,-6.673110009,-2.829598022,90.00000001 +46.49,50.425,-2.589291153,48.7422,0,9.999573129,-1.6934375,-6.710313247,-2.771123096,90.00000001 +46.5,50.425,-2.589289746,48.7594,0,10.0006835,-1.7465625,-6.746115088,-2.71023172,90.00000001 +46.51,50.425,-2.589288338,48.7771,0,10.0009056,-1.8,-6.78050814,-2.64697695,90.00000001 +46.52,50.425,-2.589286931,48.7954,0,10.00068356,-1.853125,-6.813485127,-2.581413962,90.00000001 +46.53,50.425,-2.589285524,48.8142,0,10.00090566,-1.9046875,-6.84503923,-2.513599938,90.00000001 +46.54,50.425,-2.589284116,48.8335,0,10.00068362,-1.955,-6.875163862,-2.443594064,90.00000001 +46.55,50.425,-2.589282709,48.8533,0,9.999573302,-2.0046875,-6.903852661,-2.371457303,90.00000001 +46.56,50.425,-2.589281302,48.8736,0,9.998907124,-2.053125,-6.931099669,-2.297252622,90.00000001 +46.57,50.425,-2.589279895,48.8944,0,9.999573365,-2.1,-6.956899271,-2.221044651,90.00000001 +46.58,50.425,-2.589278488,48.9156,0,10.00068375,-2.1465625,-6.981245966,-2.142899969,90.00000001 +46.59,50.425,-2.58927708,48.9373,0,10.00068378,-2.1934375,-7.004134713,-2.062886585,90.00000001 +46.6,50.425,-2.589275673,48.9595,0,9.999573468,-2.2396875,-7.025560699,-1.9810744,90.00000001 +46.61,50.425,-2.589274266,48.9821,0,9.998685225,-2.2846875,-7.045519569,-1.897534632,90.00000001 +46.62,50.425,-2.589272859,49.0052,0,9.99868526,-2.328125,-7.064007027,-1.812340162,90.00000001 +46.63,50.425,-2.589271452,49.0287,0,9.999573576,-2.3696875,-7.081019232,-1.725565361,90.00000001 +46.64,50.425,-2.589270045,49.0526,0,10.00068396,-2.41,-7.096552691,-1.637285857,90.00000001 +46.65,50.425,-2.589268637,49.0769,0,10.000684,-2.45,-7.110604137,-1.547578543,90.00000001 +46.66,50.425,-2.58926723,49.1016,0,9.99979576,-2.4896875,-7.123170649,-1.456521798,90.00000001 +46.67,50.425,-2.589265823,49.1267,0,9.999795799,-2.528125,-7.134249532,-1.364194863,90.00000001 +46.68,50.425,-2.589264416,49.1522,0,10.00068412,-2.565,-7.143838497,-1.270678411,90.00000001 +46.69,50.425,-2.589263008,49.178,0,10.00090623,-2.60125,-7.151935594,-1.176053858,90.00000001 +46.7,50.425,-2.589261601,49.2042,0,10.0006842,-2.6365625,-7.158539104,-1.080403768,90.00000001 +46.71,50.425,-2.589260194,49.2308,0,10.00090631,-2.6696875,-7.163647653,-0.983811563,90.00000001 +46.72,50.425,-2.589258786,49.2576,0,10.00068428,-2.7015625,-7.167260152,-0.886361469,90.00000001 +46.73,50.425,-2.589257379,49.2848,0,9.999573976,-2.7334375,-7.169375856,-0.788138398,90.00000001 +46.74,50.425,-2.589255972,49.3123,0,9.998685741,-2.764375,-7.169994364,-0.68922812,90.00000001 +46.75,50.425,-2.589254565,49.3401,0,9.998685785,-2.793125,-7.169115447,-0.589716811,90.00000001 +46.76,50.425,-2.589253158,49.3682,0,9.999574108,-2.82,-7.166739391,-0.489691271,90.00000001 +46.77,50.425,-2.589251751,49.3965,0,10.0006845,-2.84625,-7.162866654,-0.389238706,90.00000001 +46.78,50.425,-2.589250343,49.4251,0,10.00068454,-2.8715625,-7.15749804,-0.288446721,90.00000001 +46.79,50.425,-2.589248936,49.454,0,9.999574241,-2.895,-7.150634693,-0.18740315,90.00000001 +46.8,50.425,-2.589247529,49.483,0,9.998908078,-2.918125,-7.142277989,-0.086196229,90.00000001 +46.81,50.425,-2.589246122,49.5123,0,9.999574333,-2.9415625,-7.132429704,0.015085864,90.00000001 +46.82,50.425,-2.589244715,49.5419,0,10.00068473,-2.9625,-7.121091958,0.116354837,90.00000001 +46.83,50.425,-2.589243307,49.5716,0,10.00068477,-2.98,-7.108267042,0.217522338,90.00000001 +46.84,50.425,-2.5892419,49.6015,0,9.999796541,-2.9965625,-7.093957593,0.318500134,90.00000001 +46.85,50.425,-2.589240493,49.6315,0,9.999796589,-3.013125,-7.078166762,0.419200216,90.00000001 +46.86,50.425,-2.589239086,49.6618,0,10.00068492,-3.0284375,-7.060897699,0.519534695,90.00000001 +46.87,50.425,-2.589237678,49.6921,0,10.00068496,-3.0428125,-7.042154015,0.619416193,90.00000001 +46.88,50.425,-2.589236271,49.7226,0,9.999796731,-3.0565625,-7.021939721,0.718757506,90.00000001 +46.89,50.425,-2.589234864,49.7533,0,9.999796779,-3.0678125,-7.000258998,0.817472118,90.00000001 +46.9,50.425,-2.589233457,49.784,0,10.00068511,-3.0765625,-6.977116315,0.915473799,90.00000001 +46.91,50.425,-2.589232049,49.8148,0,10.00068515,-3.085,-6.952516602,1.012677234,90.00000001 +46.92,50.425,-2.589230642,49.8457,0,9.999574854,-3.093125,-6.926464898,1.10899757,90.00000001 +46.93,50.425,-2.589229235,49.8767,0,9.998908694,-3.099375,-6.898966706,1.204350868,90.00000001 +46.94,50.425,-2.589227828,49.9077,0,9.999574951,-3.103125,-6.870027753,1.298653934,90.00000001 +46.95,50.425,-2.589226421,49.9388,0,10.00068535,-3.105,-6.839654057,1.39182455,90.00000001 +46.96,50.425,-2.589225013,49.9698,0,10.0006854,-3.1065625,-6.807852035,1.483781525,90.00000001 +46.97,50.425,-2.589223606,50.0009,0,9.999575097,-3.1084375,-6.774628275,1.574444534,90.00000001 +46.98,50.425,-2.589222199,50.032,0,9.998686867,-3.109375,-6.739989711,1.663734677,90.00000001 +46.99,50.425,-2.589220792,50.0631,0,9.998686915,-3.108125,-6.703943561,1.751573978,90.00000001 +47,50.425,-2.589219385,50.0942,0,9.999575242,-3.1046875,-6.666497388,1.837885887,90.00000001 +47.01,50.425,-2.589217978,50.1252,0,10.00068564,-3.0996875,-6.627659043,1.922595176,90.00000001 +47.02,50.425,-2.58921657,50.1562,0,10.00090776,-3.093125,-6.587436546,2.005627876,90.00000001 +47.03,50.425,-2.589215163,50.1871,0,10.00068574,-3.0846875,-6.545838378,2.086911679,90.00000001 +47.04,50.425,-2.589213756,50.2179,0,10.00090785,-3.075,-6.50287319,2.166375654,90.00000001 +47.05,50.425,-2.589212348,50.2486,0,10.00068583,-3.065,-6.45854992,2.243950473,90.00000001 +47.06,50.425,-2.589210941,50.2792,0,9.999797602,-3.0546875,-6.412877907,2.319568583,90.00000001 +47.07,50.425,-2.589209534,50.3097,0,9.99979765,-3.043125,-6.365866662,2.393163981,90.00000001 +47.08,50.425,-2.589208127,50.3401,0,10.00068598,-3.029375,-6.317525984,2.464672494,90.00000001 +47.09,50.425,-2.589206719,50.3703,0,10.00068602,-3.013125,-6.267865898,2.534031785,90.00000001 +47.1,50.425,-2.589205312,50.4004,0,9.999575721,-2.995,-6.216896948,2.60118135,90.00000001 +47.11,50.425,-2.589203905,50.4302,0,9.998687489,-2.9765625,-6.164629618,2.66606269,90.00000001 +47.12,50.425,-2.589202498,50.4599,0,9.998687536,-2.9584375,-6.111074909,2.728619139,90.00000001 +47.13,50.425,-2.589201091,50.4894,0,9.999575861,-2.939375,-6.056243937,2.788796208,90.00000001 +47.14,50.425,-2.589199684,50.5187,0,10.00068626,-2.918125,-6.000148275,2.846541416,90.00000001 +47.15,50.425,-2.589198276,50.5478,0,10.0006863,-2.8946875,-5.942799497,2.901804398,90.00000001 +47.16,50.425,-2.589196869,50.5766,0,9.999575997,-2.87,-5.884209635,2.954536913,90.00000001 +47.17,50.425,-2.589195462,50.6052,0,9.998909833,-2.845,-5.82439095,3.004693065,90.00000001 +47.18,50.425,-2.589194055,50.6335,0,9.999576086,-2.819375,-5.763355933,3.052229082,90.00000001 +47.19,50.425,-2.589192648,50.6616,0,10.00068648,-2.7915625,-5.701117304,3.097103537,90.00000001 +47.2,50.425,-2.58919124,50.6894,0,10.00090859,-2.7615625,-5.637688069,3.139277242,90.00000001 +47.21,50.425,-2.589189833,50.7168,0,10.00068656,-2.7315625,-5.573081462,3.178713411,90.00000001 +47.22,50.425,-2.589188426,50.744,0,10.00090868,-2.70125,-5.507311007,3.215377782,90.00000001 +47.23,50.425,-2.589187018,50.7709,0,10.00068665,-2.668125,-5.440390396,3.249238213,90.00000001 +47.24,50.425,-2.589185611,50.7974,0,9.999576343,-2.633125,-5.372333667,3.28026531,90.00000001 +47.25,50.425,-2.589184204,50.8235,0,9.998910175,-2.5984375,-5.303154972,3.308431973,90.00000001 +47.26,50.425,-2.589182797,50.8494,0,9.999576424,-2.563125,-5.232868749,3.333713563,90.00000001 +47.27,50.425,-2.58918139,50.8748,0,10.00068681,-2.52625,-5.161489724,3.356088196,90.00000001 +47.28,50.425,-2.589179982,50.8999,0,10.00068685,-2.488125,-5.089032851,3.375536217,90.00000001 +47.29,50.425,-2.589178575,50.9246,0,9.999576541,-2.448125,-5.015513142,3.392040724,90.00000001 +47.3,50.425,-2.589177168,50.9489,0,9.998688301,-2.4065625,-4.940946008,3.405587337,90.00000001 +47.31,50.425,-2.589175761,50.9727,0,9.998688338,-2.365,-4.865347034,3.416164195,90.00000001 +47.32,50.425,-2.589174354,50.9962,0,9.999576654,-2.3234375,-4.788731977,3.423762132,90.00000001 +47.33,50.425,-2.589172947,51.0192,0,10.00068704,-2.28125,-4.71111688,3.428374499,90.00000001 +47.34,50.425,-2.589171539,51.0418,0,10.00068707,-2.238125,-4.632517899,3.429997287,90.00000001 +47.35,50.425,-2.589170132,51.064,0,9.99957676,-2.193125,-4.552951479,3.428629064,90.00000001 +47.36,50.425,-2.589168725,51.0857,0,9.998910584,-2.14625,-4.472434293,3.424270975,90.00000001 +47.37,50.425,-2.589167318,51.1069,0,9.999576827,-2.0984375,-4.390983014,3.416926917,90.00000001 +47.38,50.425,-2.589165911,51.1277,0,10.00090928,-2.05,-4.308614774,3.406603249,90.00000001 +47.39,50.425,-2.589164503,51.1479,0,10.00179759,-2.00125,-4.22534676,3.393308966,90.00000001 +47.4,50.425,-2.589163096,51.1677,0,10.00179762,-1.951875,-4.141196277,3.377055643,90.00000001 +47.41,50.425,-2.589161688,51.187,0,10.00090937,-1.90125,-4.056180971,3.357857547,90.00000001 +47.42,50.425,-2.589160281,51.2057,0,9.999576981,-1.85,-3.970318604,3.335731292,90.00000001 +47.43,50.425,-2.589158874,51.224,0,9.99868873,-1.798125,-3.883627111,3.310696245,90.00000001 +47.44,50.425,-2.589157467,51.2417,0,9.998688758,-1.7446875,-3.796124538,3.282774178,90.00000001 +47.45,50.425,-2.58915606,51.2589,0,9.999577065,-1.69,-3.707829221,3.251989556,90.00000001 +47.46,50.425,-2.589154653,51.2755,0,10.00068744,-1.635,-3.618759551,3.218369081,90.00000001 +47.47,50.425,-2.589153245,51.2916,0,10.00068746,-1.58,-3.52893415,3.1819422,90.00000001 +47.48,50.425,-2.589151838,51.3071,0,9.999577139,-1.5246875,-3.438371753,3.142740542,90.00000001 +47.49,50.425,-2.589150431,51.3221,0,9.998910954,-1.4684375,-3.347091326,3.100798427,90.00000001 +47.5,50.425,-2.589149024,51.3365,0,9.999577186,-1.4115625,-3.25511189,3.056152353,90.00000001 +47.51,50.425,-2.589147617,51.3503,0,10.00068756,-1.3546875,-3.16245264,3.00884128,90.00000001 +47.52,50.425,-2.589146209,51.3636,0,10.00068758,-1.2965625,-3.069132998,2.958906461,90.00000001 +47.53,50.425,-2.589144802,51.3763,0,9.999577248,-1.2365625,-2.975172389,2.906391441,90.00000001 +47.54,50.425,-2.589143395,51.3883,0,9.998688988,-1.1765625,-2.880590464,2.851341943,90.00000001 +47.55,50.425,-2.589141988,51.3998,0,9.998689005,-1.116875,-2.785406934,2.793806094,90.00000001 +47.56,50.425,-2.589140581,51.4107,0,9.999577301,-1.05625,-2.689641736,2.733833971,90.00000001 +47.57,50.425,-2.589139174,51.4209,0,10.00090974,-0.9953125,-2.593314869,2.671477943,90.00000001 +47.58,50.425,-2.589137766,51.4306,0,10.00179803,-0.935,-2.496446384,2.606792326,90.00000001 +47.59,50.425,-2.589136359,51.4396,0,10.00179804,-0.874375,-2.399056508,2.539833498,90.00000001 +47.6,50.425,-2.589134951,51.4481,0,10.00090978,-0.811875,-2.301165694,2.47065996,90.00000001 +47.61,50.425,-2.589133544,51.4559,0,9.999577373,-0.748125,-2.202794284,2.399331928,90.00000001 +47.62,50.425,-2.589132137,51.463,0,9.998911175,-0.6853125,-2.103962846,2.325911684,90.00000001 +47.63,50.425,-2.58913073,51.4696,0,9.999577394,-0.623125,-2.004692006,2.250463169,90.00000001 +47.64,50.425,-2.589129323,51.4755,0,10.00068775,-0.5596875,-1.905002507,2.173052274,90.00000001 +47.65,50.425,-2.589127915,51.4808,0,10.00068776,-0.4953125,-1.804915202,2.093746378,90.00000001 +47.66,50.425,-2.589126508,51.4854,0,9.999577419,-0.4315625,-1.704450949,2.012614752,90.00000001 +47.67,50.425,-2.589125101,51.4894,0,9.998689147,-0.3684375,-1.603630774,1.929728099,90.00000001 +47.68,50.425,-2.589123694,51.4928,0,9.998689152,-0.3046875,-1.502475649,1.845158669,90.00000001 +47.69,50.425,-2.589122287,51.4955,0,9.999577435,-0.24,-1.401006771,1.758980202,90.00000001 +47.7,50.425,-2.58912088,51.4976,0,10.00068779,-0.1753125,-1.299245341,1.671267926,90.00000001 +47.71,50.425,-2.589119472,51.499,0,10.00068779,-0.1115625,-1.197212559,1.582098276,90.00000001 +47.72,50.425,-2.589118065,51.4998,0,9.999577441,-0.048125,-1.094929738,1.491549,90.00000001 +47.73,50.425,-2.589116658,51.5,0,9.998911232,0.016875,-0.992418249,1.399699052,90.00000001 +47.74,50.425,-2.589115251,51.4995,0,9.999577441,0.083125,-0.889699521,1.30662859,90.00000001 +47.75,50.425,-2.589113844,51.4983,0,10.00090986,0.148125,-0.786794983,1.212418687,90.00000001 +47.76,50.425,-2.589112436,51.4965,0,10.00179813,0.2115625,-0.683726179,1.117151562,90.00000001 +47.77,50.425,-2.589111029,51.4941,0,10.00179813,0.275,-0.580514535,1.020910294,90.00000001 +47.78,50.425,-2.589109621,51.491,0,10.00090985,0.3384375,-0.477181712,0.923778707,90.00000001 +47.79,50.425,-2.589108214,51.4873,0,9.999577422,0.4015625,-0.373749193,0.825841656,90.00000001 +47.8,50.425,-2.589106807,51.483,0,9.998689136,0.4653125,-0.270238638,0.727184397,90.00000001 +47.81,50.425,-2.5891054,51.478,0,9.998689128,0.53,-0.166671589,0.627893046,90.00000001 +47.82,50.425,-2.589103993,51.4724,0,9.999577398,0.5946875,-0.063069819,0.528054119,90.00000001 +47.83,50.425,-2.589102586,51.4661,0,10.00068774,0.658125,0.040545186,0.427754763,90.00000001 +47.84,50.425,-2.589101178,51.4592,0,10.00068773,0.72,0.144151712,0.327082411,90.00000001 +47.85,50.425,-2.589099771,51.4517,0,9.999577366,0.781875,0.2477281,0.226124784,90.00000001 +47.86,50.425,-2.589098364,51.4436,0,9.998911144,0.845,0.35125275,0.124970002,90.00000001 +47.87,50.425,-2.589096957,51.4348,0,9.999577339,0.908125,0.454704062,0.023706243,90.00000001 +47.88,50.425,-2.58909555,51.4254,0,10.00068767,0.9696875,0.558060434,-0.077578142,90.00000001 +47.89,50.425,-2.589094142,51.4154,0,10.00068766,1.03,0.661300267,-0.178794918,90.00000001 +47.9,50.425,-2.589092735,51.4048,0,9.999577293,1.09,0.764401959,-0.279855792,90.00000001 +47.91,50.425,-2.589091328,51.3936,0,9.998688996,1.15,0.867344026,-0.380672643,90.00000001 +47.92,50.425,-2.589089921,51.3818,0,9.998688977,1.2096875,0.970104981,-0.481157523,90.00000001 +47.93,50.425,-2.589088514,51.3694,0,9.999577237,1.2684375,1.072663337,-0.581222769,90.00000001 +47.94,50.425,-2.589087107,51.3564,0,10.00090964,1.3265625,1.174997667,-0.680781233,90.00000001 +47.95,50.425,-2.589085699,51.3429,0,10.00179789,1.385,1.277086657,-0.779746056,90.00000001 +47.96,50.425,-2.589084292,51.3287,0,10.00179787,1.443125,1.378908878,-0.878030949,90.00000001 +47.97,50.425,-2.589082884,51.314,0,10.00090957,1.4996875,1.480443187,-0.975550142,90.00000001 +47.98,50.425,-2.589081477,51.2987,0,9.999577127,1.555,1.581668271,-1.072218665,90.00000001 +47.99,50.425,-2.58908007,51.2829,0,9.998910893,1.61,1.682563102,-1.167952177,90.00000001 +48,50.425,-2.589078663,51.2665,0,9.999577077,1.665,1.783106481,-1.2626672,90.00000001 +48.01,50.425,-2.589077256,51.2496,0,10.0006874,1.7196875,1.883277551,-1.356281227,90.00000001 +48.02,50.425,-2.589075848,51.2321,0,10.00068737,1.7734375,1.983055287,-1.448712498,90.00000001 +48.03,50.425,-2.589074441,51.2141,0,9.999576994,1.82625,2.082418888,-1.539880453,90.00000001 +48.04,50.425,-2.589073034,51.1956,0,9.998688686,1.8784375,2.181347614,-1.629705683,90.00000001 +48.05,50.425,-2.589071627,51.1765,0,9.998688657,1.9296875,2.279820782,-1.718109747,90.00000001 +48.06,50.425,-2.58907022,51.157,0,9.999576905,1.9796875,2.377817822,-1.805015585,90.00000001 +48.07,50.425,-2.589068813,51.1369,0,10.00068722,2.0284375,2.475318336,-1.890347392,90.00000001 +48.08,50.425,-2.589067405,51.1164,0,10.00068719,2.07625,2.572301871,-1.974030858,90.00000001 +48.09,50.425,-2.589065998,51.0954,0,9.999576809,2.1234375,2.6687482,-2.055992871,90.00000001 +48.1,50.425,-2.589064591,51.0739,0,9.998910567,2.17,2.764637214,-2.1361621,90.00000001 +48.11,50.425,-2.589063184,51.052,0,9.999576741,2.21625,2.859948857,-2.214468528,90.00000001 +48.12,50.425,-2.589061777,51.0296,0,10.00068705,2.2615625,2.954663307,-2.290843917,90.00000001 +48.13,50.425,-2.589060369,51.0067,0,10.00090909,2.3046875,3.048760624,-2.365221631,90.00000001 +48.14,50.425,-2.589058962,50.9835,0,10.00068698,2.346875,3.142221271,-2.437536812,90.00000001 +48.15,50.425,-2.589057555,50.9598,0,10.00090902,2.39,3.235025709,-2.507726491,90.00000001 +48.16,50.425,-2.589056147,50.9357,0,10.00068691,2.4325,3.327154572,-2.575729362,90.00000001 +48.17,50.425,-2.58905474,50.9111,0,9.999576521,2.4715625,3.418588609,-2.641486181,90.00000001 +48.18,50.425,-2.589053333,50.8862,0,9.998910272,2.508125,3.509308684,-2.704939538,90.00000001 +48.19,50.425,-2.589051926,50.861,0,9.999576442,2.5453125,3.599295888,-2.766034199,90.00000001 +48.2,50.425,-2.589050519,50.8353,0,10.00068675,2.583125,3.688531429,-2.824716823,90.00000001 +48.21,50.425,-2.589049111,50.8093,0,10.00068671,2.619375,3.776996686,-2.880936244,90.00000001 +48.22,50.425,-2.589047704,50.7829,0,9.99957632,2.653125,3.864673151,-2.934643417,90.00000001 +48.23,50.425,-2.589046297,50.7562,0,9.998910069,2.6846875,3.951542548,-2.985791589,90.00000001 +48.24,50.425,-2.58904489,50.7292,0,9.999576235,2.7153125,4.037586714,-3.034336068,90.00000001 +48.25,50.425,-2.589043483,50.7019,0,10.00068654,2.7465625,4.122787658,-3.080234571,90.00000001 +48.26,50.425,-2.589042075,50.6743,0,10.0006865,2.7778125,4.207127619,-3.123447105,90.00000001 +48.27,50.425,-2.589040668,50.6463,0,9.999576107,2.8065625,4.290588948,-3.163935913,90.00000001 +48.28,50.425,-2.589039261,50.6181,0,9.998687784,2.8328125,4.373154287,-3.201665699,90.00000001 +48.29,50.425,-2.589037854,50.5897,0,9.998687739,2.8584375,4.45480633,-3.236603577,90.00000001 +48.3,50.425,-2.589036447,50.5609,0,9.999575972,2.883125,4.535528062,-3.268719122,90.00000001 +48.31,50.425,-2.58903504,50.532,0,10.00090835,2.90625,4.61530258,-3.297984316,90.00000001 +48.32,50.425,-2.589033632,50.5028,0,10.00179658,2.9284375,4.694113269,-3.324373607,90.00000001 +48.33,50.425,-2.589032225,50.4734,0,10.00179653,2.9496875,4.771943626,-3.347863959,90.00000001 +48.34,50.425,-2.589030817,50.4438,0,10.00090821,2.97,4.848777439,-3.36843492,90.00000001 +48.35,50.425,-2.58902941,50.414,0,9.999575742,2.9896875,4.924598663,-3.386068613,90.00000001 +48.36,50.425,-2.589028003,50.384,0,9.998687417,3.0078125,4.999391427,-3.400749568,90.00000001 +48.37,50.425,-2.589026596,50.3538,0,9.99868737,3.023125,5.073140148,-3.412465008,90.00000001 +48.38,50.425,-2.589025189,50.3235,0,9.999575602,3.03625,5.145829413,-3.421204734,90.00000001 +48.39,50.425,-2.589023782,50.2931,0,10.0006859,3.0484375,5.217444038,-3.426961127,90.00000001 +48.4,50.425,-2.589022374,50.2625,0,10.00068585,3.06,5.287969069,-3.4297292,90.00000001 +48.41,50.425,-2.589020967,50.2319,0,9.999575458,3.07125,5.357389724,-3.429506434,90.00000001 +48.42,50.425,-2.58901956,50.2011,0,9.998909201,3.0815625,5.425691622,-3.426293115,90.00000001 +48.43,50.425,-2.589018153,50.1702,0,9.999575362,3.0896875,5.492860381,-3.420091993,90.00000001 +48.44,50.425,-2.589016746,50.1393,0,10.00068566,3.09625,5.558882079,-3.410908568,90.00000001 +48.45,50.425,-2.589015338,50.1083,0,10.00068561,3.1015625,5.623742849,-3.39875069,90.00000001 +48.46,50.425,-2.589013931,50.0772,0,9.999575216,3.1046875,5.687429171,-3.383629131,90.00000001 +48.47,50.425,-2.589012524,50.0462,0,9.998908959,3.1065625,5.749927751,-3.365556953,90.00000001 +48.48,50.425,-2.589011117,50.0151,0,9.999575119,3.1084375,5.811225526,-3.344549971,90.00000001 +48.49,50.425,-2.58900971,49.984,0,10.00068542,3.109375,5.871309662,-3.320626463,90.00000001 +48.5,50.425,-2.589008302,49.9529,0,10.00090744,3.108125,5.930167725,-3.293807339,90.00000001 +48.51,50.425,-2.589006895,49.9218,0,10.00068532,3.105,5.987787283,-3.264115979,90.00000001 +48.52,50.425,-2.589005488,49.8908,0,10.00090734,3.10125,6.044156418,-3.231578221,90.00000001 +48.53,50.425,-2.58900408,49.8598,0,10.00068522,3.0965625,6.09926327,-3.196222543,90.00000001 +48.54,50.425,-2.589002673,49.8288,0,9.999574828,3.0896875,6.153096436,-3.158079654,90.00000001 +48.55,50.425,-2.589001266,49.798,0,9.998908571,3.08125,6.205644515,-3.1171829,90.00000001 +48.56,50.425,-2.588999859,49.7672,0,9.999574731,3.071875,6.256896679,-3.073567921,90.00000001 +48.57,50.425,-2.588998452,49.7365,0,10.00068503,3.0609375,6.306842155,-3.027272759,90.00000001 +48.58,50.425,-2.588997044,49.706,0,10.00068498,3.0484375,6.355470572,-2.978337751,90.00000001 +48.59,50.425,-2.588995637,49.6755,0,9.999574588,3.035,6.402771676,-2.926805584,90.00000001 +48.6,50.425,-2.58899423,49.6453,0,9.998686262,3.02125,6.448735668,-2.872721175,90.00000001 +48.61,50.425,-2.588992823,49.6151,0,9.998686215,3.0065625,6.493352923,-2.816131738,90.00000001 +48.62,50.425,-2.588991416,49.5851,0,9.999574446,2.989375,6.536614101,-2.757086604,90.00000001 +48.63,50.425,-2.588990009,49.5553,0,10.00068475,2.97,6.578510208,-2.695637224,90.00000001 +48.64,50.425,-2.588988601,49.5257,0,10.0006847,2.9496875,6.619032476,-2.631837228,90.00000001 +48.65,50.425,-2.588987194,49.4963,0,9.999796377,2.928125,6.658172426,-2.565742192,90.00000001 +48.66,50.425,-2.588985787,49.4671,0,9.999796331,2.905,6.695921922,-2.497409813,90.00000001 +48.67,50.425,-2.58898438,49.4382,0,10.00068456,2.8815625,6.732273058,-2.426899678,90.00000001 +48.68,50.425,-2.588982972,49.4095,0,10.00090659,2.858125,6.767218269,-2.354273267,90.00000001 +48.69,50.425,-2.588981565,49.381,0,10.00068448,2.8328125,6.800750166,-2.279593833,90.00000001 +48.7,50.425,-2.588980158,49.3528,0,10.0009065,2.805,6.832861872,-2.20292658,90.00000001 +48.71,50.425,-2.58897875,49.3249,0,10.00068439,2.7765625,6.863546627,-2.124338371,90.00000001 +48.72,50.425,-2.588977343,49.2973,0,9.999573996,2.7478125,6.892797956,-2.043897675,90.00000001 +48.73,50.425,-2.588975936,49.2699,0,9.998685674,2.7165625,6.9206099,-1.961674679,90.00000001 +48.74,50.425,-2.588974529,49.2429,0,9.998685632,2.683125,6.946976501,-1.877741117,90.00000001 +48.75,50.425,-2.588973122,49.2163,0,9.99957387,2.65,6.971892316,-1.7921701,90.00000001 +48.76,50.425,-2.588971715,49.1899,0,10.00068418,2.6165625,6.995352187,-1.705036283,90.00000001 +48.77,50.425,-2.588970307,49.1639,0,10.00068414,2.58125,7.017351131,-1.61641564,90.00000001 +48.78,50.425,-2.5889689,49.1383,0,9.999573747,2.545,7.037884563,-1.526385464,90.00000001 +48.79,50.425,-2.588967493,49.113,0,9.998907498,2.508125,7.056948301,-1.43502425,90.00000001 +48.8,50.425,-2.588966086,49.0881,0,9.999573669,2.4696875,7.07453822,-1.342411695,90.00000001 +48.81,50.425,-2.588964679,49.0636,0,10.00068398,2.4296875,7.09065071,-1.248628531,90.00000001 +48.82,50.425,-2.588963271,49.0395,0,10.00068394,2.3884375,7.105282448,-1.153756518,90.00000001 +48.83,50.425,-2.588961864,49.0158,0,9.999795625,2.34625,7.11843034,-1.057878448,90.00000001 +48.84,50.425,-2.588960457,48.9926,0,9.999795589,2.3034375,7.130091635,-0.961077859,90.00000001 +48.85,50.425,-2.58895905,48.9697,0,10.00068383,2.2596875,7.14026387,-0.863439204,90.00000001 +48.86,50.425,-2.588957642,48.9474,0,10.0006838,2.2146875,7.148944983,-0.765047626,90.00000001 +48.87,50.425,-2.588956235,48.9254,0,9.999795485,2.1684375,7.156133082,-0.665988952,90.00000001 +48.88,50.425,-2.588954828,48.904,0,9.999795451,2.1215625,7.161826793,-0.566349472,90.00000001 +48.89,50.425,-2.588953421,48.883,0,10.0006837,2.075,7.166024798,-0.466216159,90.00000001 +48.9,50.425,-2.588952013,48.8625,0,10.00068366,2.0278125,7.168726294,-0.365676275,90.00000001 +48.91,50.425,-2.588950606,48.8424,0,9.999573285,1.978125,7.169930651,-0.264817483,90.00000001 +48.92,50.425,-2.588949199,48.8229,0,9.998907045,1.9265625,7.169637698,-0.163727847,90.00000001 +48.93,50.425,-2.588947792,48.8039,0,9.999573224,1.8753125,7.167847434,-0.062495372,90.00000001 +48.94,50.425,-2.588946385,48.7854,0,10.00068354,1.8246875,7.16456026,0.038791535,90.00000001 +48.95,50.425,-2.588944977,48.7674,0,10.00068352,1.773125,7.159776865,0.140044693,90.00000001 +48.96,50.425,-2.58894357,48.7499,0,9.99957314,1.7196875,7.153498279,0.241175698,90.00000001 +48.97,50.425,-2.588942163,48.733,0,9.998684836,1.665,7.145725705,0.342096369,90.00000001 +48.98,50.425,-2.588940756,48.7166,0,9.99868481,1.61,7.13646092,0.442718759,90.00000001 +48.99,50.425,-2.588939349,48.7008,0,9.999573063,1.5546875,7.1257057,0.542955032,90.00000001 +49,50.425,-2.588937942,48.6855,0,10.00068339,1.498125,7.113462394,0.642717928,90.00000001 +49.01,50.425,-2.588936534,48.6708,0,10.00090543,1.44,7.099733581,0.741920299,90.00000001 +49.02,50.425,-2.588935127,48.6567,0,10.00068334,1.381875,7.08452201,0.840475743,90.00000001 +49.03,50.425,-2.58893372,48.6432,0,10.00090539,1.325,7.067830947,0.93829826,90.00000001 +49.04,50.425,-2.588932312,48.6302,0,10.0006833,1.268125,7.049663888,1.035302536,90.00000001 +49.05,50.425,-2.588930905,48.6178,0,9.999572933,1.209375,7.030024556,1.131404059,90.00000001 +49.06,50.425,-2.588929498,48.606,0,9.998906705,1.1484375,7.008917135,1.226519006,90.00000001 +49.07,50.425,-2.588928091,48.5948,0,9.999572897,1.086875,6.986345921,1.320564356,90.00000001 +49.08,50.425,-2.588926684,48.5843,0,10.00068323,1.0265625,6.962315784,1.413458175,90.00000001 +49.09,50.425,-2.588925276,48.5743,0,10.00068321,0.9665625,6.936831596,1.505119448,90.00000001 +49.1,50.425,-2.588923869,48.5649,0,9.99957285,0.9046875,6.909898798,1.595468188,90.00000001 +49.11,50.425,-2.588922462,48.5562,0,9.998906628,0.841875,6.881522891,1.684425673,90.00000001 +49.12,50.425,-2.588921055,48.5481,0,9.999572824,0.78,6.851709892,1.77191438,90.00000001 +49.13,50.425,-2.588919648,48.5406,0,10.00068316,0.718125,6.820465987,1.857857878,90.00000001 +49.14,50.425,-2.58891824,48.5337,0,10.00068315,0.655,6.787797767,1.942181337,90.00000001 +49.15,50.425,-2.588916833,48.5275,0,9.999572792,0.591875,6.753711935,2.024811133,90.00000001 +49.16,50.425,-2.588915426,48.5219,0,9.998906574,0.5296875,6.71821571,2.105675302,90.00000001 +49.17,50.425,-2.588914019,48.5169,0,9.999572775,0.4665625,6.681316483,2.184703314,90.00000001 +49.18,50.425,-2.588912612,48.5125,0,10.00068312,0.4015625,6.643021932,2.261826183,90.00000001 +49.19,50.425,-2.588911204,48.5089,0,10.00090518,0.336875,6.603340079,2.336976702,90.00000001 +49.2,50.425,-2.588909797,48.5058,0,10.00068311,0.2734375,6.56227923,2.410089383,90.00000001 +49.21,50.425,-2.58890839,48.5034,0,10.00090517,0.2096875,6.519847867,2.481100454,90.00000001 +49.22,50.425,-2.588906982,48.5016,0,10.0006831,0.145,6.476054983,2.549947922,90.00000001 +49.23,50.425,-2.588905575,48.5005,0,9.99957275,0.08,6.430909633,2.616571799,90.00000001 +49.24,50.425,-2.588904168,48.5,0,9.99890654,0.015,6.384421213,2.680913985,90.00000001 +49.25,50.425,-2.588902761,48.5002,0,9.999572749,-0.05,6.336599577,2.742918389,90.00000001 +49.26,50.425,-2.588901354,48.501,0,10.0006831,-0.1146875,6.287454581,2.802530923,90.00000001 +49.27,50.425,-2.588899946,48.5025,0,10.0006831,-0.1784375,6.236996537,2.859699621,90.00000001 +49.28,50.425,-2.588898539,48.5046,0,9.999572756,-0.2415625,6.185235988,2.914374577,90.00000001 +49.29,50.425,-2.588897132,48.5073,0,9.998684482,-0.3053125,6.132183706,2.966508178,90.00000001 +49.3,50.425,-2.588895725,48.5107,0,9.998684488,-0.37,6.077850805,3.016054933,90.00000001 +49.31,50.425,-2.588894318,48.5147,0,9.999572773,-0.4346875,6.022248632,3.062971639,90.00000001 +49.32,50.425,-2.588892911,48.5194,0,10.00068313,-0.4984375,5.965388759,3.107217446,90.00000001 +49.33,50.425,-2.588891503,48.5247,0,10.00068314,-0.5615625,5.907283103,3.148753677,90.00000001 +49.34,50.425,-2.588890096,48.5306,0,9.999572797,-0.625,5.847943813,3.187544123,90.00000001 +49.35,50.425,-2.588888689,48.5372,0,9.998906599,-0.688125,5.787383262,3.223554979,90.00000001 +49.36,50.425,-2.588887282,48.5444,0,9.999572819,-0.75,5.725614057,3.256754904,90.00000001 +49.37,50.425,-2.588885875,48.5522,0,10.00090525,-0.811875,5.662649147,3.287114849,90.00000001 +49.38,50.425,-2.588884467,48.5606,0,10.00179354,-0.8746875,5.598501652,3.314608343,90.00000001 +49.39,50.425,-2.58888306,48.5697,0,10.00179355,-0.9365625,5.533184979,3.339211495,90.00000001 +49.4,50.425,-2.588881652,48.5794,0,10.00090529,-0.9965625,5.466712822,3.360902817,90.00000001 +49.41,50.425,-2.588880245,48.5896,0,9.99957289,-1.056875,5.399098932,3.379663403,90.00000001 +49.42,50.425,-2.588878838,48.6005,0,9.998684628,-1.1184375,5.330357575,3.395476809,90.00000001 +49.43,50.425,-2.588877431,48.612,0,9.998684645,-1.1796875,5.260503019,3.408329341,90.00000001 +49.44,50.425,-2.588876024,48.6241,0,9.999572943,-1.2396875,5.189549874,3.418209769,90.00000001 +49.45,50.425,-2.588874617,48.6368,0,10.00068331,-1.298125,5.117512922,3.425109442,90.00000001 +49.46,50.425,-2.588873209,48.6501,0,10.00068333,-1.355,5.044407289,3.4290224,90.00000001 +49.47,50.425,-2.588871802,48.6639,0,9.999573006,-1.411875,4.970248215,3.429945148,90.00000001 +49.48,50.425,-2.588870395,48.6783,0,9.998906819,-1.47,4.895051114,3.427877,90.00000001 +49.49,50.425,-2.588868988,48.6933,0,9.999573051,-1.528125,4.818831799,3.422819616,90.00000001 +49.5,50.425,-2.588867581,48.7089,0,10.00068342,-1.584375,4.741606084,3.414777523,90.00000001 +49.51,50.425,-2.588866173,48.725,0,10.00068345,-1.6384375,4.663390126,3.403757711,90.00000001 +49.52,50.425,-2.588864766,48.7417,0,9.999573127,-1.6915625,4.584200368,3.389769749,90.00000001 +49.53,50.425,-2.588863359,48.7588,0,9.998684875,-1.745,4.504053199,3.37282584,90.00000001 +49.54,50.425,-2.588861952,48.7766,0,9.998684903,-1.7984375,4.422965404,3.352940824,90.00000001 +49.55,50.425,-2.588860545,48.7948,0,9.99957321,-1.85125,4.340953944,3.330131947,90.00000001 +49.56,50.425,-2.588859138,48.8136,0,10.00090566,-1.9034375,4.25803595,3.304419205,90.00000001 +49.57,50.425,-2.58885773,48.8329,0,10.00179397,-1.954375,4.174228669,3.275824887,90.00000001 +49.58,50.425,-2.588856323,48.8527,0,10.001794,-2.0034375,4.089549689,3.244374031,90.00000001 +49.59,50.425,-2.588854915,48.873,0,10.00090575,-2.0515625,4.004016659,3.21009408,90.00000001 +49.6,50.425,-2.588853508,48.8937,0,9.999573365,-2.0996875,3.917647454,3.17301483,90.00000001 +49.61,50.425,-2.588852101,48.915,0,9.99890719,-2.146875,3.830460122,3.133168652,90.00000001 +49.62,50.425,-2.588850694,48.9367,0,9.999573433,-2.1928125,3.74247277,3.090590325,90.00000001 +49.63,50.425,-2.588849287,48.9588,0,10.00068382,-2.2384375,3.653703903,3.045316976,90.00000001 +49.64,50.425,-2.588847879,48.9815,0,10.00068385,-2.283125,3.564172028,2.997388025,90.00000001 +49.65,50.425,-2.588846472,49.0045,0,9.999573538,-2.32625,3.473895767,2.946845355,90.00000001 +49.66,50.425,-2.588845065,49.028,0,9.998685296,-2.3684375,3.382894026,2.89373297,90.00000001 +49.67,50.425,-2.588843658,49.0519,0,9.998685334,-2.4096875,3.291185828,2.838097164,90.00000001 +49.68,50.425,-2.588842251,49.0762,0,9.99957365,-2.4496875,3.198790368,2.779986524,90.00000001 +49.69,50.425,-2.588840844,49.1009,0,10.00068404,-2.4884375,3.105726781,2.719451699,90.00000001 +49.7,50.425,-2.588839436,49.126,0,10.00068408,-2.52625,3.012014664,2.656545517,90.00000001 +49.71,50.425,-2.588838029,49.1514,0,9.999573768,-2.5634375,2.917673496,2.591322752,90.00000001 +49.72,50.425,-2.588836622,49.1773,0,9.9989076,-2.5996875,2.822723045,2.523840298,90.00000001 +49.73,50.425,-2.588835215,49.2034,0,9.99957385,-2.6346875,2.727183077,2.454156999,90.00000001 +49.74,50.425,-2.588833808,49.23,0,10.00090631,-2.6684375,2.63107359,2.382333703,90.00000001 +49.75,50.425,-2.5888324,49.2568,0,10.00179463,-2.7009375,2.534414635,2.308432919,90.00000001 +49.76,50.425,-2.588830993,49.284,0,10.00179467,-2.731875,2.437226383,2.232519163,90.00000001 +49.77,50.425,-2.588829585,49.3115,0,10.00090644,-2.76125,2.339529172,2.15465861,90.00000001 +49.78,50.425,-2.588828178,49.3392,0,9.999574062,-2.79,2.241343343,2.074919214,90.00000001 +49.79,50.425,-2.588826771,49.3673,0,9.998685827,-2.8184375,2.142689464,1.993370418,90.00000001 +49.8,50.425,-2.588825364,49.3956,0,9.998685871,-2.84625,2.043588106,1.910083382,90.00000001 +49.81,50.425,-2.588823957,49.4242,0,9.999574194,-2.8728125,1.944059951,1.8251307,90.00000001 +49.82,50.425,-2.58882255,49.4531,0,10.00068459,-2.8965625,1.844125856,1.738586514,90.00000001 +49.83,50.425,-2.588821142,49.4822,0,10.00068463,-2.918125,1.743806618,1.650526224,90.00000001 +49.84,50.425,-2.588819735,49.5114,0,9.999574331,-2.94,1.643123208,1.561026664,90.00000001 +49.85,50.425,-2.588818328,49.541,0,9.998908168,-2.96125,1.542096597,1.470165871,90.00000001 +49.86,50.425,-2.588816921,49.5707,0,9.999574423,-2.979375,1.440747983,1.378023028,90.00000001 +49.87,50.425,-2.588815514,49.6006,0,10.00068482,-2.9953125,1.33909851,1.284678577,90.00000001 +49.88,50.425,-2.588814106,49.6306,0,10.00068487,-3.0115625,1.237169375,1.190213879,90.00000001 +49.89,50.425,-2.588812699,49.6608,0,9.999574565,-3.028125,1.134981837,1.094711269,90.00000001 +49.9,50.425,-2.588811292,49.6912,0,9.998686334,-3.043125,1.032557323,0.998254053,90.00000001 +49.91,50.425,-2.588809885,49.7217,0,9.998686382,-3.05625,0.929917148,0.900926343,90.00000001 +49.92,50.425,-2.588808478,49.7523,0,9.999574708,-3.068125,0.82708274,0.80281305,90.00000001 +49.93,50.425,-2.588807071,49.7831,0,10.00090717,-3.0778125,0.724075643,0.70399966,90.00000001 +49.94,50.425,-2.588805663,49.8139,0,10.0017955,-3.085,0.620917342,0.604572346,90.00000001 +49.95,50.425,-2.588804256,49.8448,0,10.00179555,-3.0915625,0.517629324,0.504617853,90.00000001 +49.96,50.425,-2.588802848,49.8757,0,10.00090732,-3.098125,0.414233245,0.404223329,90.00000001 +49.97,50.425,-2.588801441,49.9068,0,9.999574949,-3.103125,0.31075065,0.303476321,90.00000001 +49.98,50.425,-2.588800034,49.9378,0,9.99868672,-3.10625,0.207203139,0.202464721,90.00000001 +49.99,50.425,-2.588798627,49.9689,0,9.998686769,-3.1084375,0.103612427,0.101276536,90.00000001 +50,50.425,-2.58879722,50,0,9.999575096,-3.109375,0,0,90.00000001 +50.01,50.425,-2.588795813,50.0311,0,10.00068549,-3.1084375,-0.103612427,-0.101276536,90.00000001 +50.02,50.425,-2.588794405,50.0622,0,10.00068554,-3.10625,-0.207203139,-0.202464721,90.00000001 +50.03,50.425,-2.588792998,50.0932,0,9.999575241,-3.103125,-0.31075065,-0.303476321,90.00000001 +50.04,50.425,-2.588791591,50.1243,0,9.99890908,-3.098125,-0.414233245,-0.404223329,90.00000001 +50.05,50.425,-2.588790184,50.1552,0,9.999575338,-3.0915625,-0.517629324,-0.504617853,90.00000001 +50.06,50.425,-2.588788777,50.1861,0,10.00068574,-3.085,-0.620917342,-0.604572346,90.00000001 +50.07,50.425,-2.588787369,50.2169,0,10.00068578,-3.0778125,-0.724075643,-0.70399966,90.00000001 +50.08,50.425,-2.588785962,50.2477,0,9.999575482,-3.068125,-0.82708274,-0.80281305,90.00000001 +50.09,50.425,-2.588784555,50.2783,0,9.998909321,-3.05625,-0.929917148,-0.900926343,90.00000001 +50.1,50.425,-2.588783148,50.3088,0,9.999575579,-3.043125,-1.032557323,-0.998254053,90.00000001 +50.11,50.425,-2.588781741,50.3392,0,10.00068597,-3.028125,-1.134981837,-1.094711269,90.00000001 +50.12,50.425,-2.588780333,50.3694,0,10.00090809,-3.0115625,-1.237169375,-1.190213879,90.00000001 +50.13,50.425,-2.588778926,50.3994,0,10.00068607,-2.9953125,-1.33909851,-1.284678577,90.00000001 +50.14,50.425,-2.588777519,50.4293,0,10.00090818,-2.979375,-1.440747983,-1.378023028,90.00000001 +50.15,50.425,-2.588776111,50.459,0,10.00068616,-2.96125,-1.542096597,-1.470165871,90.00000001 +50.16,50.425,-2.588774704,50.4886,0,9.99957586,-2.94,-1.643123208,-1.561026664,90.00000001 +50.17,50.425,-2.588773297,50.5178,0,9.998909696,-2.918125,-1.743806618,-1.650526224,90.00000001 +50.18,50.425,-2.58877189,50.5469,0,9.999575951,-2.8965625,-1.844125856,-1.738586514,90.00000001 +50.19,50.425,-2.588770483,50.5758,0,10.00068634,-2.8728125,-1.944059951,-1.8251307,90.00000001 +50.2,50.425,-2.588769075,50.6044,0,10.00068639,-2.84625,-2.043588106,-1.910083382,90.00000001 +50.21,50.425,-2.588767668,50.6327,0,9.999576085,-2.8184375,-2.142689464,-1.993370418,90.00000001 +50.22,50.425,-2.588766261,50.6608,0,9.99868785,-2.79,-2.241343343,-2.074919214,90.00000001 +50.23,50.425,-2.588764854,50.6885,0,9.998687893,-2.76125,-2.339529172,-2.15465861,90.00000001 +50.24,50.425,-2.588763447,50.716,0,9.999576215,-2.731875,-2.437226383,-2.232519163,90.00000001 +50.25,50.425,-2.58876204,50.7432,0,10.00068661,-2.7009375,-2.534414635,-2.308432919,90.00000001 +50.26,50.425,-2.588760632,50.77,0,10.00068665,-2.6684375,-2.63107359,-2.382333703,90.00000001 +50.27,50.425,-2.588759225,50.7966,0,9.999576342,-2.6346875,-2.727183077,-2.454156999,90.00000001 +50.28,50.425,-2.588757818,50.8227,0,9.998910174,-2.5996875,-2.822723045,-2.523840298,90.00000001 +50.29,50.425,-2.588756411,50.8486,0,9.999576423,-2.5634375,-2.917673496,-2.591322752,90.00000001 +50.3,50.425,-2.588755004,50.874,0,10.00090888,-2.52625,-3.012014664,-2.656545517,90.00000001 +50.31,50.425,-2.588753596,50.8991,0,10.0017972,-2.4884375,-3.105726781,-2.719451699,90.00000001 +50.32,50.425,-2.588752189,50.9238,0,10.00179724,-2.4496875,-3.198790368,-2.779986524,90.00000001 +50.33,50.425,-2.588750781,50.9481,0,10.000909,-2.4096875,-3.291185828,-2.838097164,90.00000001 +50.34,50.425,-2.588749374,50.972,0,9.999576615,-2.3684375,-3.382894026,-2.89373297,90.00000001 +50.35,50.425,-2.588747967,50.9955,0,9.998688373,-2.32625,-3.473895767,-2.946845355,90.00000001 +50.36,50.425,-2.58874656,51.0185,0,9.99868841,-2.283125,-3.564172028,-2.997388025,90.00000001 +50.37,50.425,-2.588745153,51.0412,0,9.999576725,-2.2384375,-3.653703903,-3.045316976,90.00000001 +50.38,50.425,-2.588743746,51.0633,0,10.00068711,-2.1928125,-3.74247277,-3.090590325,90.00000001 +50.39,50.425,-2.588742338,51.085,0,10.00068714,-2.146875,-3.830460122,-3.133168652,90.00000001 +50.4,50.425,-2.588740931,51.1063,0,9.999576825,-2.0996875,-3.917647454,-3.17301483,90.00000001 +50.41,50.425,-2.588739524,51.127,0,9.998910648,-2.0515625,-4.004016659,-3.21009408,90.00000001 +50.42,50.425,-2.588738117,51.1473,0,9.999576889,-2.0034375,-4.089549689,-3.244374031,90.00000001 +50.43,50.425,-2.58873671,51.1671,0,10.00068727,-1.954375,-4.174228669,-3.275824887,90.00000001 +50.44,50.425,-2.588735302,51.1864,0,10.0006873,-1.9034375,-4.25803595,-3.304419205,90.00000001 +50.45,50.425,-2.588733895,51.2052,0,9.99957698,-1.85125,-4.340953944,-3.330131947,90.00000001 +50.46,50.425,-2.588732488,51.2234,0,9.9989108,-1.7984375,-4.422965404,-3.352940824,90.00000001 +50.47,50.425,-2.588731081,51.2412,0,9.999577037,-1.745,-4.504053199,-3.37282584,90.00000001 +50.48,50.425,-2.588729674,51.2583,0,10.00068741,-1.6915625,-4.584200368,-3.389769749,90.00000001 +50.49,50.425,-2.588728266,51.275,0,10.00090951,-1.6384375,-4.663390126,-3.403757711,90.00000001 +50.5,50.425,-2.588726859,51.2911,0,10.00068746,-1.584375,-4.741606084,-3.414777523,90.00000001 +50.51,50.425,-2.588725452,51.3067,0,10.00090956,-1.528125,-4.818831799,-3.422819616,90.00000001 +50.52,50.425,-2.588724044,51.3217,0,10.00068751,-1.47,-4.895051114,-3.427877,90.00000001 +50.53,50.425,-2.588722637,51.3361,0,9.999577186,-1.411875,-4.970248215,-3.429945148,90.00000001 +50.54,50.425,-2.58872123,51.3499,0,9.998910998,-1.355,-5.044407289,-3.4290224,90.00000001 +50.55,50.425,-2.588719823,51.3632,0,9.999577228,-1.298125,-5.117512922,-3.425109442,90.00000001 +50.56,50.425,-2.588718416,51.3759,0,10.0006876,-1.2396875,-5.189549874,-3.418209769,90.00000001 +50.57,50.425,-2.588717008,51.388,0,10.00068761,-1.1796875,-5.260503019,-3.408329341,90.00000001 +50.58,50.425,-2.588715601,51.3995,0,9.999577284,-1.1184375,-5.330357575,-3.395476809,90.00000001 +50.59,50.425,-2.588714194,51.4104,0,9.998689023,-1.056875,-5.399098932,-3.379663403,90.00000001 +50.6,50.425,-2.588712787,51.4206,0,9.998689039,-0.9965625,-5.466712822,-3.360902817,90.00000001 +50.61,50.425,-2.58871138,51.4303,0,9.999577333,-0.9365625,-5.533184979,-3.339211495,90.00000001 +50.62,50.425,-2.588709973,51.4394,0,10.0006877,-0.8746875,-5.598501652,-3.314608343,90.00000001 +50.63,50.425,-2.588708565,51.4478,0,10.00068771,-0.811875,-5.662649147,-3.287114849,90.00000001 +50.64,50.425,-2.588707158,51.4556,0,9.999799442,-0.75,-5.725614057,-3.256754904,90.00000001 +50.65,50.425,-2.588705751,51.4628,0,9.999799453,-0.688125,-5.787383262,-3.223554979,90.00000001 +50.66,50.425,-2.588704344,51.4694,0,10.00068774,-0.625,-5.847943813,-3.187544123,90.00000001 +50.67,50.425,-2.588702936,51.4753,0,10.00090982,-0.5615625,-5.907283103,-3.148753677,90.00000001 +50.68,50.425,-2.588701529,51.4806,0,10.00068776,-0.4984375,-5.965388759,-3.107217446,90.00000001 +50.69,50.425,-2.588700122,51.4853,0,10.00090984,-0.4346875,-6.022248632,-3.062971639,90.00000001 +50.7,50.425,-2.588698714,51.4893,0,10.00068777,-0.37,-6.077850805,-3.016054933,90.00000001 +50.71,50.425,-2.588697307,51.4927,0,9.99957743,-0.3053125,-6.132183706,-2.966508178,90.00000001 +50.72,50.425,-2.5886959,51.4954,0,9.998689155,-0.2415625,-6.185235988,-2.914374577,90.00000001 +50.73,50.425,-2.588694493,51.4975,0,9.998689158,-0.1784375,-6.236996537,-2.859699621,90.00000001 +50.74,50.425,-2.588693086,51.499,0,9.99957744,-0.1146875,-6.287454581,-2.802530923,90.00000001 +50.75,50.425,-2.588691679,51.4998,0,10.00068779,-0.05,-6.336599577,-2.742918389,90.00000001 +50.76,50.425,-2.588690271,51.5,0,10.00068779,0.015,-6.384421213,-2.680913985,90.00000001 +50.77,50.425,-2.588688864,51.4995,0,9.999577441,0.08,-6.430909633,-2.616571799,90.00000001 +50.78,50.425,-2.588687457,51.4984,0,9.998911229,0.145,-6.476054983,-2.549947922,90.00000001 +50.79,50.425,-2.58868605,51.4966,0,9.999577436,0.2096875,-6.519847867,-2.481100454,90.00000001 +50.8,50.425,-2.588684643,51.4942,0,10.00068778,0.2734375,-6.56227923,-2.410089383,90.00000001 +50.81,50.425,-2.588683235,51.4911,0,10.00068778,0.336875,-6.603340079,-2.336976702,90.00000001 +50.82,50.425,-2.588681828,51.4875,0,9.999799492,0.4015625,-6.643021932,-2.261826183,90.00000001 +50.83,50.425,-2.588680421,51.4831,0,9.999799485,0.4665625,-6.681316483,-2.184703314,90.00000001 +50.84,50.425,-2.588679014,51.4781,0,10.00068776,0.5296875,-6.71821571,-2.105675302,90.00000001 +50.85,50.425,-2.588677606,51.4725,0,10.00068775,0.591875,-6.753711935,-2.024811133,90.00000001 +50.86,50.425,-2.588676199,51.4663,0,9.999799459,0.655,-6.787797767,-1.942181337,90.00000001 +50.87,50.425,-2.588674792,51.4594,0,9.999799448,0.718125,-6.820465987,-1.857857878,90.00000001 +50.88,50.425,-2.588673385,51.4519,0,10.00068771,0.78,-6.851709892,-1.77191438,90.00000001 +50.89,50.425,-2.588671977,51.4438,0,10.0006877,0.841875,-6.881522891,-1.684425673,90.00000001 +50.9,50.425,-2.58867057,51.4351,0,9.99957734,0.9046875,-6.909898798,-1.595468188,90.00000001 +50.91,50.425,-2.588669163,51.4257,0,9.998911117,0.9665625,-6.936831596,-1.505119448,90.00000001 +50.92,50.425,-2.588667756,51.4157,0,9.99957731,1.0265625,-6.962315784,-1.413458175,90.00000001 +50.93,50.425,-2.588666349,51.4052,0,10.00068764,1.086875,-6.986345921,-1.320564356,90.00000001 +50.94,50.425,-2.588664941,51.394,0,10.00068762,1.1484375,-7.008917135,-1.226519006,90.00000001 +50.95,50.425,-2.588663534,51.3822,0,9.999577257,1.209375,-7.030024556,-1.131404059,90.00000001 +50.96,50.425,-2.588662127,51.3698,0,9.99868896,1.268125,-7.049663888,-1.035302536,90.00000001 +50.97,50.425,-2.58866072,51.3568,0,9.998688939,1.325,-7.067830947,-0.93829826,90.00000001 +50.98,50.425,-2.588659313,51.3433,0,9.999577196,1.381875,-7.08452201,-0.840475743,90.00000001 +50.99,50.425,-2.588657906,51.3292,0,10.00068752,1.44,-7.099733581,-0.741920299,90.00000001 +51,50.425,-2.588656498,51.3145,0,10.00090957,1.498125,-7.113462394,-0.642717928,90.00000001 +51.01,50.425,-2.588655091,51.2992,0,10.00068748,1.5546875,-7.1257057,-0.542955032,90.00000001 +51.02,50.425,-2.588653684,51.2834,0,10.00090952,1.61,-7.13646092,-0.442718759,90.00000001 +51.03,50.425,-2.588652276,51.267,0,10.00068743,1.665,-7.145725705,-0.342096369,90.00000001 +51.04,50.425,-2.588650869,51.2501,0,9.999577051,1.7196875,-7.153498279,-0.241175698,90.00000001 +51.05,50.425,-2.588649462,51.2326,0,9.998910814,1.773125,-7.159776865,-0.140044693,90.00000001 +51.06,50.425,-2.588648055,51.2146,0,9.999576995,1.8246875,-7.16456026,-0.038791535,90.00000001 +51.07,50.425,-2.588646648,51.1961,0,10.00068732,1.8753125,-7.167847434,0.062495372,90.00000001 +51.08,50.425,-2.58864524,51.1771,0,10.00068729,1.9265625,-7.169637698,0.163727847,90.00000001 +51.09,50.425,-2.588643833,51.1576,0,9.999576906,1.978125,-7.169930651,0.264817483,90.00000001 +51.1,50.425,-2.588642426,51.1375,0,9.998910665,2.0278125,-7.168726294,0.365676275,90.00000001 +51.11,50.425,-2.588641019,51.117,0,9.999576842,2.075,-7.166024798,0.466216159,90.00000001 +51.12,50.425,-2.588639612,51.096,0,10.00068716,2.1215625,-7.161826793,0.566349472,90.00000001 +51.13,50.425,-2.588638204,51.0746,0,10.00068713,2.1684375,-7.156133082,0.665988952,90.00000001 +51.14,50.425,-2.588636797,51.0526,0,9.999576742,2.2146875,-7.148944983,0.765047626,90.00000001 +51.15,50.425,-2.58863539,51.0303,0,9.998910498,2.2596875,-7.14026387,0.863439204,90.00000001 +51.16,50.425,-2.588633983,51.0074,0,9.999576671,2.3034375,-7.130091635,0.961077859,90.00000001 +51.17,50.425,-2.588632576,50.9842,0,10.00068698,2.34625,-7.11843034,1.057878448,90.00000001 +51.18,50.425,-2.588631168,50.9605,0,10.00090902,2.3884375,-7.105282448,1.153756518,90.00000001 +51.19,50.425,-2.588629761,50.9364,0,10.00068691,2.4296875,-7.09065071,1.248628531,90.00000001 +51.2,50.425,-2.588628354,50.9119,0,10.00090894,2.4696875,-7.07453822,1.342411695,90.00000001 +51.21,50.425,-2.588626946,50.887,0,10.00068683,2.508125,-7.056948301,1.43502425,90.00000001 +51.22,50.425,-2.588625539,50.8617,0,9.999576443,2.545,-7.037884563,1.526385464,90.00000001 +51.23,50.425,-2.588624132,50.8361,0,9.998910194,2.58125,-7.017351131,1.61641564,90.00000001 +51.24,50.425,-2.588622725,50.8101,0,9.999576363,2.6165625,-6.995352187,1.705036283,90.00000001 +51.25,50.425,-2.588621318,50.7837,0,10.00068667,2.65,-6.971892316,1.7921701,90.00000001 +51.26,50.425,-2.58861991,50.7571,0,10.00068663,2.683125,-6.946976501,1.877741117,90.00000001 +51.27,50.425,-2.588618503,50.7301,0,9.999576237,2.7165625,-6.9206099,1.961674679,90.00000001 +51.28,50.425,-2.588617096,50.7027,0,9.998687916,2.7478125,-6.892797956,2.043897675,90.00000001 +51.29,50.425,-2.588615689,50.6751,0,9.998687873,2.7765625,-6.863546627,2.124338371,90.00000001 +51.3,50.425,-2.588614282,50.6472,0,9.999576108,2.805,-6.832861872,2.20292658,90.00000001 +51.31,50.425,-2.588612875,50.619,0,10.00068641,2.8328125,-6.800750166,2.279593833,90.00000001 +51.32,50.425,-2.588611467,50.5905,0,10.00068637,2.858125,-6.767218269,2.354273267,90.00000001 +51.33,50.425,-2.58861006,50.5618,0,9.999575974,2.8815625,-6.732273058,2.426899678,90.00000001 +51.34,50.425,-2.588608653,50.5329,0,9.99890972,2.905,-6.695921922,2.497409813,90.00000001 +51.35,50.425,-2.588607246,50.5037,0,9.999575884,2.928125,-6.658172426,2.565742192,90.00000001 +51.36,50.425,-2.588605839,50.4743,0,10.00090826,2.9496875,-6.619032476,2.631837228,90.00000001 +51.37,50.425,-2.588604431,50.4447,0,10.00179649,2.97,-6.578510208,2.695637224,90.00000001 +51.38,50.425,-2.588603024,50.4149,0,10.00179644,2.989375,-6.536614101,2.757086604,90.00000001 +51.39,50.425,-2.588601616,50.3849,0,10.00090812,3.0065625,-6.493352923,2.816131738,90.00000001 +51.4,50.425,-2.588600209,50.3547,0,9.999575651,3.02125,-6.448735668,2.872721175,90.00000001 +51.41,50.425,-2.588598802,50.3245,0,9.998687325,3.035,-6.402771676,2.926805584,90.00000001 +51.42,50.425,-2.588597395,50.294,0,9.998687277,3.0484375,-6.355470572,2.978337751,90.00000001 +51.43,50.425,-2.588595988,50.2635,0,9.999575507,3.0609375,-6.306842155,3.027272759,90.00000001 +51.44,50.425,-2.588594581,50.2328,0,10.00068581,3.071875,-6.256896679,3.073567921,90.00000001 +51.45,50.425,-2.588593173,50.202,0,10.00068576,3.08125,-6.205644515,3.1171829,90.00000001 +51.46,50.425,-2.588591766,50.1712,0,9.999575363,3.0896875,-6.153096436,3.158079654,90.00000001 +51.47,50.425,-2.588590359,50.1402,0,9.998909105,3.0965625,-6.09926327,3.196222543,90.00000001 +51.48,50.425,-2.588588952,50.1092,0,9.999575266,3.10125,-6.044156418,3.231578221,90.00000001 +51.49,50.425,-2.588587545,50.0782,0,10.00068557,3.105,-5.987787283,3.264115979,90.00000001 +51.5,50.425,-2.588586137,50.0471,0,10.00068552,3.108125,-5.930167725,3.293807339,90.00000001 +51.51,50.425,-2.58858473,50.016,0,9.999575121,3.109375,-5.871309662,3.320626463,90.00000001 +51.52,50.425,-2.588583323,49.9849,0,9.998686793,3.1084375,-5.811225526,3.344549971,90.00000001 +51.53,50.425,-2.588581916,49.9538,0,9.998686744,3.1065625,-5.749927751,3.365556953,90.00000001 +51.54,50.425,-2.588580509,49.9228,0,9.999574974,3.1046875,-5.687429171,3.383629131,90.00000001 +51.55,50.425,-2.588579102,49.8917,0,10.00090734,3.1015625,-5.623742849,3.39875069,90.00000001 +51.56,50.425,-2.588577694,49.8607,0,10.00179557,3.09625,-5.558882079,3.410908568,90.00000001 +51.57,50.425,-2.588576287,49.8298,0,10.00179553,3.0896875,-5.492860381,3.420091993,90.00000001 +51.58,50.425,-2.588574879,49.7989,0,10.0009072,3.0815625,-5.425691622,3.426293115,90.00000001 +51.59,50.425,-2.588573472,49.7681,0,9.999574732,3.07125,-5.357389724,3.429506434,90.00000001 +51.6,50.425,-2.588572065,49.7375,0,9.998908476,3.06,-5.287969069,3.4297292,90.00000001 +51.61,50.425,-2.588570658,49.7069,0,9.999574637,3.0484375,-5.217444038,3.426961127,90.00000001 +51.62,50.425,-2.588569251,49.6765,0,10.00068494,3.03625,-5.145829413,3.421204734,90.00000001 +51.63,50.425,-2.588567843,49.6462,0,10.00068489,3.023125,-5.073140148,3.412465008,90.00000001 +51.64,50.425,-2.588566436,49.616,0,9.999574494,3.0078125,-4.999391427,3.400749568,90.00000001 +51.65,50.425,-2.588565029,49.586,0,9.998686169,2.9896875,-4.924598663,3.386068613,90.00000001 +51.66,50.425,-2.588563622,49.5562,0,9.998686122,2.97,-4.848777439,3.36843492,90.00000001 +51.67,50.425,-2.588562215,49.5266,0,9.999574355,2.9496875,-4.771943626,3.347863959,90.00000001 +51.68,50.425,-2.588560808,49.4972,0,10.00068466,2.9284375,-4.694113269,3.324373607,90.00000001 +51.69,50.425,-2.5885594,49.468,0,10.00068461,2.90625,-4.61530258,3.297984316,90.00000001 +51.7,50.425,-2.588557993,49.4391,0,9.999574218,2.883125,-4.535528062,3.268719122,90.00000001 +51.71,50.425,-2.588556586,49.4103,0,9.998907964,2.8584375,-4.45480633,3.236603577,90.00000001 +51.72,50.425,-2.588555179,49.3819,0,9.999574129,2.8328125,-4.373154287,3.201665699,90.00000001 +51.73,50.425,-2.588553772,49.3537,0,10.00068443,2.8065625,-4.290588948,3.163935913,90.00000001 +51.74,50.425,-2.588552364,49.3257,0,10.00090646,2.7778125,-4.207127619,3.123447105,90.00000001 +51.75,50.425,-2.588550957,49.2981,0,10.00068435,2.7465625,-4.122787658,3.080234571,90.00000001 +51.76,50.425,-2.58854955,49.2708,0,10.00090637,2.7153125,-4.037586714,3.034336068,90.00000001 +51.77,50.425,-2.588548142,49.2438,0,10.00068426,2.6846875,-3.951542548,2.985791589,90.00000001 +51.78,50.425,-2.588546735,49.2171,0,9.999573871,2.653125,-3.864673151,2.934643417,90.00000001 +51.79,50.425,-2.588545328,49.1907,0,9.998907621,2.619375,-3.776996686,2.880936244,90.00000001 +51.8,50.425,-2.588543921,49.1647,0,9.999573789,2.583125,-3.688531429,2.824716823,90.00000001 +51.81,50.425,-2.588542514,49.139,0,10.0006841,2.5453125,-3.599295888,2.766034199,90.00000001 +51.82,50.425,-2.588541106,49.1138,0,10.00068406,2.508125,-3.509308684,2.704939538,90.00000001 +51.83,50.425,-2.588539699,49.0889,0,9.99957367,2.4715625,-3.418588609,2.641486181,90.00000001 +51.84,50.425,-2.588538292,49.0643,0,9.998907423,2.4325,-3.327154572,2.575729362,90.00000001 +51.85,50.425,-2.588536885,49.0402,0,9.999573594,2.39,-3.235025709,2.507726491,90.00000001 +51.86,50.425,-2.588535478,49.0165,0,10.0006839,2.346875,-3.142221271,2.437536812,90.00000001 +51.87,50.425,-2.58853407,48.9933,0,10.00068387,2.3046875,-3.048760624,2.365221631,90.00000001 +51.88,50.425,-2.588532663,48.9704,0,9.999573485,2.2615625,-2.954663307,2.290843917,90.00000001 +51.89,50.425,-2.588531256,48.948,0,9.998685172,2.21625,-2.859948857,2.214468528,90.00000001 +51.9,50.425,-2.588529849,48.9261,0,9.998685137,2.17,-2.764637214,2.1361621,90.00000001 +51.91,50.425,-2.588528442,48.9046,0,9.999573382,2.1234375,-2.6687482,2.055992871,90.00000001 +51.92,50.425,-2.588527035,48.8836,0,10.00090577,2.07625,-2.572301871,1.974030858,90.00000001 +51.93,50.425,-2.588525627,48.8631,0,10.00179401,2.0284375,-2.475318336,1.890347392,90.00000001 +51.94,50.425,-2.58852422,48.843,0,10.00179398,1.9796875,-2.377817822,1.805015585,90.00000001 +51.95,50.425,-2.588522812,48.8235,0,10.00090567,1.9296875,-2.279820782,1.718109747,90.00000001 +51.96,50.425,-2.588521405,48.8044,0,9.999573225,1.8784375,-2.181347614,1.629705683,90.00000001 +51.97,50.425,-2.588519998,48.7859,0,9.998684917,1.82625,-2.082418888,1.539880453,90.00000001 +51.98,50.425,-2.588518591,48.7679,0,9.998684889,1.7734375,-1.983055287,1.448712498,90.00000001 +51.99,50.425,-2.588517184,48.7504,0,9.999573141,1.7196875,-1.883277551,1.356281227,90.00000001 +52,50.425,-2.588515777,48.7335,0,10.00068346,1.665,-1.783106481,1.2626672,90.00000001 +52.01,50.425,-2.588514369,48.7171,0,10.00068344,1.61,-1.682563102,1.167952177,90.00000001 +52.02,50.425,-2.588512962,48.7013,0,9.999573063,1.555,-1.581668271,1.072218665,90.00000001 +52.03,50.425,-2.588511555,48.686,0,9.998906831,1.4996875,-1.480443187,0.975550142,90.00000001 +52.04,50.425,-2.588510148,48.6713,0,9.999573017,1.443125,-1.378908878,0.878030949,90.00000001 +52.05,50.425,-2.588508741,48.6571,0,10.00068334,1.385,-1.277086657,0.779746056,90.00000001 +52.06,50.425,-2.588507333,48.6436,0,10.00068332,1.3265625,-1.174997667,0.680781233,90.00000001 +52.07,50.425,-2.588505926,48.6306,0,9.999572953,1.2684375,-1.072663337,0.581222769,90.00000001 +52.08,50.425,-2.588504519,48.6182,0,9.998906725,1.2096875,-0.970104981,0.481157523,90.00000001 +52.09,50.425,-2.588503112,48.6064,0,9.999572915,1.15,-0.867344026,0.380672643,90.00000001 +52.1,50.425,-2.588501705,48.5952,0,10.00068325,1.09,-0.764401959,0.279855792,90.00000001 +52.11,50.425,-2.588500297,48.5846,0,10.0009053,1.03,-0.661300267,0.178794918,90.00000001 +52.12,50.425,-2.58849889,48.5746,0,10.00068321,0.9696875,-0.558060434,0.077578142,90.00000001 +52.13,50.425,-2.588497483,48.5652,0,10.00090527,0.908125,-0.454704062,-0.023706243,90.00000001 +52.14,50.425,-2.588496075,48.5564,0,10.00068319,0.845,-0.35125275,-0.124970002,90.00000001 +52.15,50.425,-2.588494668,48.5483,0,9.999572825,0.781875,-0.2477281,-0.226124784,90.00000001 +52.16,50.425,-2.588493261,48.5408,0,9.998906604,0.72,-0.144151712,-0.327082411,90.00000001 +52.17,50.425,-2.588491854,48.5339,0,9.999572803,0.658125,-0.040545186,-0.427754763,90.00000001 +52.18,50.425,-2.588490447,48.5276,0,10.00068314,0.5946875,0.063069819,-0.528054119,90.00000001 +52.19,50.425,-2.588489039,48.522,0,10.00068313,0.53,0.166671589,-0.627893046,90.00000001 +52.2,50.425,-2.588487632,48.517,0,9.999572776,0.4653125,0.270238638,-0.727184397,90.00000001 +52.21,50.425,-2.588486225,48.5127,0,9.998684491,0.4015625,0.373749193,-0.825841656,90.00000001 +52.22,50.425,-2.588484818,48.509,0,9.998684485,0.3384375,0.477181712,-0.923778707,90.00000001 +52.23,50.425,-2.588483411,48.5059,0,9.999572758,0.275,0.580514535,-1.020910294,90.00000001 +52.24,50.425,-2.588482004,48.5035,0,10.0006831,0.2115625,0.683726179,-1.117151562,90.00000001 +52.25,50.425,-2.588480596,48.5017,0,10.0006831,0.148125,0.786794983,-1.212418687,90.00000001 +52.26,50.425,-2.588479189,48.5005,0,9.99957275,0.083125,0.889699521,-1.30662859,90.00000001 +52.27,50.425,-2.588477782,48.5,0,9.998906541,0.016875,0.992418249,-1.399699052,90.00000001 +52.28,50.425,-2.588476375,48.5002,0,9.999572749,-0.048125,1.094929738,-1.491549,90.00000001 +52.29,50.425,-2.588474968,48.501,0,10.00090517,-0.1115625,1.197212559,-1.582098276,90.00000001 +52.3,50.425,-2.58847356,48.5024,0,10.00179345,-0.1753125,1.299245341,-1.671267926,90.00000001 +52.31,50.425,-2.588472153,48.5045,0,10.00179345,-0.24,1.401006771,-1.758980202,90.00000001 +52.32,50.425,-2.588470745,48.5072,0,10.00090518,-0.3046875,1.502475649,-1.845158669,90.00000001 +52.33,50.425,-2.588469338,48.5106,0,9.999572766,-0.3684375,1.603630774,-1.929728099,90.00000001 +52.34,50.425,-2.588467931,48.5146,0,9.998684493,-0.4315625,1.704450949,-2.012614752,90.00000001 +52.35,50.425,-2.588466524,48.5192,0,9.9986845,-0.4953125,1.804915202,-2.093746378,90.00000001 +52.36,50.425,-2.588465117,48.5245,0,9.999572787,-0.5596875,1.905002507,-2.173052274,90.00000001 +52.37,50.425,-2.58846371,48.5304,0,10.00068315,-0.623125,2.004692006,-2.250463169,90.00000001 +52.38,50.425,-2.588462302,48.537,0,10.00068316,-0.6853125,2.103962846,-2.325911684,90.00000001 +52.39,50.425,-2.588460895,48.5441,0,9.999572818,-0.748125,2.202794284,-2.399331928,90.00000001 +52.4,50.425,-2.588459488,48.5519,0,9.998906621,-0.811875,2.301165694,-2.47065996,90.00000001 +52.41,50.425,-2.588458081,48.5604,0,9.999572843,-0.874375,2.399056508,-2.539833498,90.00000001 +52.42,50.425,-2.588456674,48.5694,0,10.00068321,-0.935,2.496446384,-2.606792326,90.00000001 +52.43,50.425,-2.588455266,48.5791,0,10.00068322,-0.9953125,2.593314869,-2.671477943,90.00000001 +52.44,50.425,-2.588453859,48.5893,0,9.999572889,-1.05625,2.689641736,-2.733833971,90.00000001 +52.45,50.425,-2.588452452,48.6002,0,9.998906697,-1.116875,2.785406934,-2.793806094,90.00000001 +52.46,50.425,-2.588451045,48.6117,0,9.999572923,-1.1765625,2.880590464,-2.851341943,90.00000001 +52.47,50.425,-2.588449638,48.6237,0,10.00068329,-1.2365625,2.975172389,-2.906391441,90.00000001 +52.48,50.425,-2.58844823,48.6364,0,10.00090538,-1.2965625,3.069132998,-2.958906461,90.00000001 +52.49,50.425,-2.588446823,48.6497,0,10.00068333,-1.3546875,3.16245264,-3.00884128,90.00000001 +52.5,50.425,-2.588445416,48.6635,0,10.00090542,-1.4115625,3.25511189,-3.056152353,90.00000001 +52.51,50.425,-2.588444008,48.6779,0,10.00068338,-1.4684375,3.347091326,-3.100798427,90.00000001 +52.52,50.425,-2.588442601,48.6929,0,9.999573051,-1.5246875,3.438371753,-3.142740542,90.00000001 +52.53,50.425,-2.588441194,48.7084,0,9.998906866,-1.58,3.52893415,-3.1819422,90.00000001 +52.54,50.425,-2.588439787,48.7245,0,9.999573101,-1.635,3.618759551,-3.218369081,90.00000001 +52.55,50.425,-2.58843838,48.7411,0,10.00068347,-1.69,3.707829221,-3.251989556,90.00000001 +52.56,50.425,-2.588436972,48.7583,0,10.0006835,-1.7446875,3.796124538,-3.282774178,90.00000001 +52.57,50.425,-2.588435565,48.776,0,9.99957318,-1.798125,3.883627111,-3.310696245,90.00000001 +52.58,50.425,-2.588434158,48.7943,0,9.998684931,-1.85,3.970318604,-3.335731292,90.00000001 +52.59,50.425,-2.588432751,48.813,0,9.998684961,-1.90125,4.056180971,-3.357857547,90.00000001 +52.6,50.425,-2.588431344,48.8323,0,9.999573269,-1.951875,4.141196277,-3.377055643,90.00000001 +52.61,50.425,-2.588429937,48.8521,0,10.00068365,-2.00125,4.22534676,-3.393308966,90.00000001 +52.62,50.425,-2.588428529,48.8723,0,10.00068368,-2.05,4.308614774,-3.406603249,90.00000001 +52.63,50.425,-2.588427122,48.8931,0,9.999795434,-2.0984375,4.390983014,-3.416926917,90.00000001 +52.64,50.425,-2.588425715,48.9143,0,9.999795468,-2.14625,4.472434293,-3.424270975,90.00000001 +52.65,50.425,-2.588424308,48.936,0,10.00068378,-2.193125,4.552951479,-3.428629064,90.00000001 +52.66,50.425,-2.5884229,48.9582,0,10.00068381,-2.238125,4.632517899,-3.429997287,90.00000001 +52.67,50.425,-2.588421493,48.9808,0,9.99979557,-2.28125,4.71111688,-3.428374499,90.00000001 +52.68,50.425,-2.588420086,49.0038,0,9.999795607,-2.3234375,4.788731977,-3.423762132,90.00000001 +52.69,50.425,-2.588418679,49.0273,0,10.00068392,-2.365,4.865347034,-3.416164195,90.00000001 +52.7,50.425,-2.588417271,49.0511,0,10.00068396,-2.4065625,4.940946008,-3.405587337,90.00000001 +52.71,50.425,-2.588415864,49.0754,0,9.999573649,-2.448125,5.015513142,-3.392040724,90.00000001 +52.72,50.425,-2.588414457,49.1001,0,9.998907478,-2.488125,5.089032851,-3.375536217,90.00000001 +52.73,50.425,-2.58841305,49.1252,0,9.999573727,-2.52625,5.161489724,-3.356088196,90.00000001 +52.74,50.425,-2.588411643,49.1506,0,10.00068412,-2.563125,5.232868749,-3.333713563,90.00000001 +52.75,50.425,-2.588410235,49.1765,0,10.00068416,-2.5984375,5.303154972,-3.308431973,90.00000001 +52.76,50.425,-2.588408828,49.2026,0,9.999573849,-2.633125,5.372333667,-3.28026531,90.00000001 +52.77,50.425,-2.588407421,49.2291,0,9.998907681,-2.668125,5.440390396,-3.249238213,90.00000001 +52.78,50.425,-2.588406014,49.256,0,9.999573931,-2.70125,5.507311007,-3.215377782,90.00000001 +52.79,50.425,-2.588404607,49.2832,0,10.00068432,-2.7315625,5.573081462,-3.178713411,90.00000001 +52.8,50.425,-2.588403199,49.3106,0,10.00068437,-2.7615625,5.637688069,-3.139277242,90.00000001 +52.81,50.425,-2.588401792,49.3384,0,9.99979613,-2.7915625,5.701117304,-3.097103537,90.00000001 +52.82,50.425,-2.588400385,49.3665,0,9.999796174,-2.819375,5.763355933,-3.052229082,90.00000001 +52.83,50.425,-2.588398978,49.3948,0,10.0006845,-2.845,5.82439095,-3.004693065,90.00000001 +52.84,50.425,-2.58839757,49.4234,0,10.00068454,-2.87,5.884209635,-2.954536913,90.00000001 +52.85,50.425,-2.588396163,49.4522,0,9.999796308,-2.8946875,5.942799497,-2.901804398,90.00000001 +52.86,50.425,-2.588394756,49.4813,0,9.999796354,-2.918125,6.000148275,-2.846541416,90.00000001 +52.87,50.425,-2.588393349,49.5106,0,10.00068468,-2.939375,6.056243937,-2.788796208,90.00000001 +52.88,50.425,-2.588391941,49.5401,0,10.00068472,-2.9584375,6.111074909,-2.728619139,90.00000001 +52.89,50.425,-2.588390534,49.5698,0,9.999574422,-2.9765625,6.164629618,-2.66606269,90.00000001 +52.9,50.425,-2.588389127,49.5996,0,9.99868619,-2.995,6.216896948,-2.60118135,90.00000001 +52.91,50.425,-2.58838772,49.6297,0,9.998686238,-3.013125,6.267865898,-2.534031785,90.00000001 +52.92,50.425,-2.588386313,49.6599,0,9.999574564,-3.029375,6.317525984,-2.464672494,90.00000001 +52.93,50.425,-2.588384906,49.6903,0,10.00068496,-3.043125,6.365866662,-2.393163981,90.00000001 +52.94,50.425,-2.588383498,49.7208,0,10.00068501,-3.0546875,6.412877907,-2.319568583,90.00000001 +52.95,50.425,-2.588382091,49.7514,0,9.999574706,-3.065,6.45854992,-2.243950473,90.00000001 +52.96,50.425,-2.588380684,49.7821,0,9.998908545,-3.075,6.50287319,-2.166375654,90.00000001 +52.97,50.425,-2.588379277,49.8129,0,9.999574803,-3.0846875,6.545838378,-2.086911679,90.00000001 +52.98,50.425,-2.58837787,49.8438,0,10.0006852,-3.093125,6.587436546,-2.005627876,90.00000001 +52.99,50.425,-2.588376462,49.8748,0,10.00090732,-3.0996875,6.627659043,-1.922595176,90.00000001 +53,50.425,-2.588375055,49.9058,0,10.0006853,-3.1046875,6.666497388,-1.837885887,90.00000001 +53.01,50.425,-2.588373648,49.9369,0,10.00090741,-3.108125,6.703943561,-1.751573978,90.00000001 +53.02,50.425,-2.58837224,49.968,0,10.00068539,-3.109375,6.739989711,-1.663734677,90.00000001 +53.03,50.425,-2.588370833,49.9991,0,9.999575094,-3.1084375,6.774628275,-1.574444534,90.00000001 +53.04,50.425,-2.588369426,50.0302,0,9.998908933,-3.1065625,6.807852035,-1.483781525,90.00000001 +53.05,50.425,-2.588368019,50.0612,0,9.999575191,-3.105,6.839654057,-1.39182455,90.00000001 +53.06,50.425,-2.588366612,50.0923,0,10.00068559,-3.103125,6.870027753,-1.298653934,90.00000001 +53.07,50.425,-2.588365204,50.1233,0,10.00068564,-3.099375,6.898966706,-1.204350868,90.00000001 +53.08,50.425,-2.588363797,50.1543,0,9.999575337,-3.093125,6.926464898,-1.10899757,90.00000001 +53.09,50.425,-2.58836239,50.1852,0,9.998909176,-3.085,6.952516602,-1.012677234,90.00000001 +53.1,50.425,-2.588360983,50.216,0,9.999575433,-3.0765625,6.977116315,-0.915473799,90.00000001 +53.11,50.425,-2.588359576,50.2467,0,10.00068583,-3.0678125,7.000258998,-0.817472118,90.00000001 +53.12,50.425,-2.588358168,50.2774,0,10.00068588,-3.0565625,7.021939721,-0.718757506,90.00000001 +53.13,50.425,-2.588356761,50.3079,0,9.999575577,-3.0428125,7.042154015,-0.619416193,90.00000001 +53.14,50.425,-2.588355354,50.3382,0,9.998687346,-3.0284375,7.060897699,-0.519534695,90.00000001 +53.15,50.425,-2.588353947,50.3685,0,9.998687393,-3.013125,7.078166762,-0.419200216,90.00000001 +53.16,50.425,-2.58835254,50.3985,0,9.999575718,-2.9965625,7.093957593,-0.318500134,90.00000001 +53.17,50.425,-2.588351133,50.4284,0,10.00090818,-2.98,7.108267042,-0.217522338,90.00000001 +53.18,50.425,-2.588349725,50.4581,0,10.00179651,-2.9625,7.121091958,-0.116354837,90.00000001 +53.19,50.425,-2.588348318,50.4877,0,10.00179656,-2.9415625,7.132429704,-0.015085864,90.00000001 +53.2,50.425,-2.58834691,50.517,0,10.00090832,-2.918125,7.142277989,0.086196229,90.00000001 +53.21,50.425,-2.588345503,50.546,0,9.999575949,-2.895,7.150634693,0.18740315,90.00000001 +53.22,50.425,-2.588344096,50.5749,0,9.998909786,-2.8715625,7.15749804,0.288446721,90.00000001 +53.23,50.425,-2.588342689,50.6035,0,9.99957604,-2.84625,7.162866654,0.389238706,90.00000001 +53.24,50.425,-2.588341282,50.6318,0,10.00068643,-2.82,7.166739391,0.489691271,90.00000001 +53.25,50.425,-2.588339874,50.6599,0,10.00068648,-2.793125,7.169115447,0.589716811,90.00000001 +53.26,50.425,-2.588338467,50.6877,0,9.999576171,-2.764375,7.169994364,0.68922812,90.00000001 +53.27,50.425,-2.58833706,50.7152,0,9.998687935,-2.7334375,7.169375856,0.788138398,90.00000001 +53.28,50.425,-2.588335653,50.7424,0,9.998687978,-2.7015625,7.167260152,0.886361469,90.00000001 +53.29,50.425,-2.588334246,50.7692,0,9.999576299,-2.6696875,7.163647653,0.983811563,90.00000001 +53.3,50.425,-2.588332839,50.7958,0,10.00068669,-2.6365625,7.158539104,1.080403768,90.00000001 +53.31,50.425,-2.588331431,50.822,0,10.00068673,-2.60125,7.151935594,1.176053858,90.00000001 +53.32,50.425,-2.588330024,50.8478,0,9.999576421,-2.565,7.143838497,1.270678411,90.00000001 +53.33,50.425,-2.588328617,50.8733,0,9.998910252,-2.528125,7.134249532,1.364194863,90.00000001 +53.34,50.425,-2.58832721,50.8984,0,9.999576501,-2.4896875,7.123170649,1.456521798,90.00000001 +53.35,50.425,-2.588325803,50.9231,0,10.00090896,-2.45,7.110604137,1.547578543,90.00000001 +53.36,50.425,-2.588324395,50.9474,0,10.00179727,-2.41,7.096552691,1.637285857,90.00000001 +53.37,50.425,-2.588322988,50.9713,0,10.00179731,-2.3696875,7.081019232,1.725565361,90.00000001 +53.38,50.425,-2.58832158,50.9948,0,10.00090907,-2.328125,7.064007027,1.812340162,90.00000001 +53.39,50.425,-2.588320173,51.0179,0,9.999576688,-2.2846875,7.045519569,1.897534632,90.00000001 +53.4,50.425,-2.588318766,51.0405,0,9.998688445,-2.2396875,7.025560699,1.9810744,90.00000001 +53.41,50.425,-2.588317359,51.0627,0,9.998688479,-2.1934375,7.004134713,2.062886585,90.00000001 +53.42,50.425,-2.588315952,51.0844,0,9.999576791,-2.1465625,6.981245966,2.142899969,90.00000001 +53.43,50.425,-2.588314545,51.1056,0,10.00068717,-2.1,6.956899271,2.221044651,90.00000001 +53.44,50.425,-2.588313137,51.1264,0,10.00068721,-2.053125,6.931099669,2.297252622,90.00000001 +53.45,50.425,-2.58831173,51.1467,0,9.999576889,-2.0046875,6.903852661,2.371457303,90.00000001 +53.46,50.425,-2.588310323,51.1665,0,9.998910711,-1.955,6.875163862,2.443594064,90.00000001 +53.47,50.425,-2.588308916,51.1858,0,9.99957695,-1.9046875,6.84503923,2.513599938,90.00000001 +53.48,50.425,-2.588307509,51.2046,0,10.00068733,-1.853125,6.813485127,2.581413962,90.00000001 +53.49,50.425,-2.588306101,51.2229,0,10.00068736,-1.8,6.78050814,2.64697695,90.00000001 +53.5,50.425,-2.588304694,51.2406,0,9.999577036,-1.7465625,6.746115088,2.71023172,90.00000001 +53.51,50.425,-2.588303287,51.2578,0,9.998688784,-1.6934375,6.710313247,2.771123096,90.00000001 +53.52,50.425,-2.58830188,51.2745,0,9.998688811,-1.6396875,6.673110009,2.829598022,90.00000001 +53.53,50.425,-2.588300473,51.2906,0,9.999577114,-1.585,6.634513165,2.885605564,90.00000001 +53.54,50.425,-2.588299066,51.3062,0,10.00090956,-1.5296875,6.594530852,2.939096732,90.00000001 +53.55,50.425,-2.588297658,51.3212,0,10.00179786,-1.473125,6.553171264,2.990025002,90.00000001 +53.56,50.425,-2.588296251,51.3357,0,10.00179788,-1.415,6.510443223,3.038345913,90.00000001 +53.57,50.425,-2.588294843,51.3495,0,10.00090962,-1.3565625,6.466355495,3.084017353,90.00000001 +53.58,50.425,-2.588293436,51.3628,0,9.999577226,-1.2984375,6.420917364,3.126999501,90.00000001 +53.59,50.425,-2.588292029,51.3755,0,9.998911037,-1.2396875,6.374138282,3.167254828,90.00000001 +53.6,50.425,-2.588290622,51.3876,0,9.999577266,-1.18,6.326028105,3.204748269,90.00000001 +53.61,50.425,-2.588289215,51.3991,0,10.00068763,-1.12,6.276596801,3.239447109,90.00000001 +53.62,50.425,-2.588287807,51.41,0,10.00068765,-1.06,6.225854685,3.271321152,90.00000001 +53.63,50.425,-2.5882864,51.4203,0,9.999577317,-1,6.173812355,3.300342496,90.00000001 +53.64,50.425,-2.588284993,51.43,0,9.998689053,-0.9396875,6.120480756,3.32648593,90.00000001 +53.65,50.425,-2.588283586,51.4391,0,9.998689067,-0.878125,6.065870945,3.349728593,90.00000001 +53.66,50.425,-2.588282179,51.4476,0,9.99957736,-0.815,6.009994382,3.37005026,90.00000001 +53.67,50.425,-2.588280772,51.4554,0,10.00068772,-0.751875,5.952862698,3.387433227,90.00000001 +53.68,50.425,-2.588279364,51.4626,0,10.00068773,-0.69,5.89448781,3.401862252,90.00000001 +53.69,50.425,-2.588277957,51.4692,0,9.999577393,-0.628125,5.834881922,3.413324789,90.00000001 +53.7,50.425,-2.58827655,51.4752,0,9.998911193,-0.5646875,5.774057524,3.421810924,90.00000001 +53.71,50.425,-2.588275143,51.4805,0,9.999577411,-0.5,5.71202728,3.427313095,90.00000001 +53.72,50.425,-2.588273736,51.4852,0,10.00068777,-0.4353125,5.648804195,3.429826661,90.00000001 +53.73,50.425,-2.588272328,51.4892,0,10.00090984,-0.3715625,5.58440139,3.429349387,90.00000001 +53.74,50.425,-2.588270921,51.4926,0,10.00068778,-0.3084375,5.518832329,3.425881617,90.00000001 +53.75,50.425,-2.588269514,51.4954,0,10.00090985,-0.2446875,5.452110763,3.419426445,90.00000001 +53.76,50.425,-2.588268106,51.4975,0,10.00068779,-0.18,5.384250616,3.409989487,90.00000001 +53.77,50.425,-2.588266699,51.499,0,9.99957744,-0.115,5.315265982,3.397578992,90.00000001 +53.78,50.425,-2.588265292,51.4998,0,9.998911233,-0.05,5.245171356,3.382205732,90.00000001 +53.79,50.425,-2.588263885,51.5,0,9.999577441,0.0146875,5.17398135,3.363883114,90.00000001 +53.8,50.425,-2.588262478,51.4995,0,10.00068779,0.0784375,5.101710803,3.342627182,90.00000001 +53.81,50.425,-2.58826107,51.4984,0,10.00068779,0.141875,5.028374841,3.318456385,90.00000001 +53.82,50.425,-2.588259663,51.4967,0,9.999577437,0.2065625,4.953988762,3.291391864,90.00000001 +53.83,50.425,-2.588258256,51.4943,0,9.998911224,0.2715625,4.878568093,3.261457226,90.00000001 +53.84,50.425,-2.588256849,51.4912,0,9.999577428,0.335,4.802128647,3.228678539,90.00000001 +53.85,50.425,-2.588255442,51.4876,0,10.00068777,0.3984375,4.724686297,3.193084396,90.00000001 +53.86,50.425,-2.588254034,51.4833,0,10.00068776,0.4634375,4.646257255,3.154705792,90.00000001 +53.87,50.425,-2.588252627,51.4783,0,9.999577408,0.528125,4.56685791,3.113576303,90.00000001 +53.88,50.425,-2.58825122,51.4727,0,9.99868912,0.59125,4.486504819,3.069731682,90.00000001 +53.89,50.425,-2.588249813,51.4665,0,9.99868911,0.6534375,4.405214828,3.023210259,90.00000001 +53.9,50.425,-2.588248406,51.4596,0,9.999577378,0.7153125,4.323004838,2.974052486,90.00000001 +53.91,50.425,-2.588246999,51.4522,0,10.00090978,0.778125,4.239892038,2.922301333,90.00000001 +53.92,50.425,-2.588245591,51.4441,0,10.00179805,0.841875,4.15589379,2.868001894,90.00000001 +53.93,50.425,-2.588244184,51.4353,0,10.00179804,0.904375,4.071027625,2.811201494,90.00000001 +53.94,50.425,-2.588242776,51.426,0,10.00090974,0.965,3.985311306,2.751949693,90.00000001 +53.95,50.425,-2.588241369,51.416,0,9.99957731,1.025,3.89876265,2.690298174,90.00000001 +53.96,50.425,-2.588239962,51.4055,0,9.998689014,1.085,3.811399822,2.626300679,90.00000001 +53.97,50.425,-2.588238555,51.3943,0,9.998688997,1.1453125,3.72324104,2.560012957,90.00000001 +53.98,50.425,-2.588237148,51.3826,0,9.999577258,1.20625,3.634304698,2.491492935,90.00000001 +53.99,50.425,-2.588235741,51.3702,0,10.00068759,1.2665625,3.544609416,2.420800199,90.00000001 +54,50.425,-2.588234333,51.3572,0,10.00068757,1.3246875,3.454173872,2.347996572,90.00000001 +54.01,50.425,-2.588232926,51.3437,0,9.999577197,1.3815625,3.363016917,2.273145423,90.00000001 +54.02,50.425,-2.588231519,51.3296,0,9.998910966,1.4384375,3.271157688,2.196312069,90.00000001 +54.03,50.425,-2.588230112,51.3149,0,9.999577152,1.495,3.178615321,2.117563489,90.00000001 +54.04,50.425,-2.588228705,51.2997,0,10.00068748,1.5515625,3.085409125,2.036968381,90.00000001 +54.05,50.425,-2.588227297,51.2839,0,10.00068745,1.608125,2.991558581,1.954596989,90.00000001 +54.06,50.425,-2.58822589,51.2675,0,9.999577078,1.663125,2.897083283,1.870521162,90.00000001 +54.07,50.425,-2.588224483,51.2506,0,9.998910843,1.7165625,2.802002943,1.784814239,90.00000001 +54.08,50.425,-2.588223076,51.2332,0,9.999577024,1.77,2.706337497,1.697550876,90.00000001 +54.09,50.425,-2.588221669,51.2152,0,10.00068734,1.823125,2.610106829,1.608807276,90.00000001 +54.1,50.425,-2.588220261,51.1967,0,10.00090939,1.8746875,2.513331049,1.518660732,90.00000001 +54.11,50.425,-2.588218854,51.1777,0,10.00068729,1.925,2.41603044,1.427189911,90.00000001 +54.12,50.425,-2.588217447,51.1582,0,10.00090932,1.975,2.318225283,1.334474568,90.00000001 +54.13,50.425,-2.588216039,51.1382,0,10.00068722,2.025,2.219935978,1.240595548,90.00000001 +54.14,50.425,-2.588214632,51.1177,0,9.999576844,2.0746875,2.121183035,1.145634669,90.00000001 +54.15,50.425,-2.588213225,51.0967,0,9.998910602,2.123125,2.021987139,1.049674838,90.00000001 +54.16,50.425,-2.588211818,51.0752,0,9.999576777,2.1696875,1.922368972,0.952799592,90.00000001 +54.17,50.425,-2.588210411,51.0533,0,10.00068709,2.2146875,1.822349334,0.855093558,90.00000001 +54.18,50.425,-2.588209003,51.0309,0,10.00068706,2.2584375,1.721949137,0.756641876,90.00000001 +54.19,50.425,-2.588207596,51.0081,0,9.999576672,2.3015625,1.621189353,0.657530376,90.00000001 +54.2,50.425,-2.588206189,50.9849,0,9.998688357,2.345,1.52009095,0.55784546,90.00000001 +54.21,50.425,-2.588204782,50.9612,0,9.99868832,2.3878125,1.418675128,0.45767416,90.00000001 +54.22,50.425,-2.588203375,50.9371,0,9.999576561,2.428125,1.31696303,0.357103738,90.00000001 +54.23,50.425,-2.588201968,50.9126,0,10.00068687,2.4665625,1.214975912,0.256221856,90.00000001 +54.24,50.425,-2.58820056,50.8878,0,10.00068683,2.505,1.112735089,0.155116635,90.00000001 +54.25,50.425,-2.588199153,50.8625,0,9.999798514,2.543125,1.010261816,0.053876081,90.00000001 +54.26,50.425,-2.588197746,50.8369,0,9.999798474,2.5796875,0.907577638,-0.047411398,90.00000001 +54.27,50.425,-2.588196339,50.8109,0,10.00068671,2.615,0.804703868,-0.148657567,90.00000001 +54.28,50.425,-2.588194931,50.7846,0,10.00090874,2.6496875,0.701662049,-0.249774075,90.00000001 +54.29,50.425,-2.588193524,50.7579,0,10.00068663,2.6834375,0.598473726,-0.350672802,90.00000001 +54.3,50.425,-2.588192117,50.7309,0,10.00090866,2.71625,0.495160382,-0.451265742,90.00000001 +54.31,50.425,-2.588190709,50.7036,0,10.00068654,2.748125,0.391743678,-0.551465174,90.00000001 +54.32,50.425,-2.588189302,50.6759,0,9.999576153,2.7778125,0.288245097,-0.651183723,90.00000001 +54.33,50.425,-2.588187895,50.648,0,9.99868783,2.8046875,0.184686356,-0.750334413,90.00000001 +54.34,50.425,-2.588186488,50.6198,0,9.998687785,2.8303125,0.081089055,-0.848830786,90.00000001 +54.35,50.425,-2.588185081,50.5914,0,9.99957602,2.85625,-0.022525205,-0.946587011,90.00000001 +54.36,50.425,-2.588183674,50.5627,0,10.00068632,2.8815625,-0.126134711,-1.043517719,90.00000001 +54.37,50.425,-2.588182266,50.5337,0,10.00068628,2.9046875,-0.229717917,-1.13953857,90.00000001 +54.38,50.425,-2.588180859,50.5046,0,9.999575885,2.9265625,-0.333253167,-1.234565626,90.00000001 +54.39,50.425,-2.588179452,50.4752,0,9.998909629,2.9484375,-0.436718745,-1.328516208,90.00000001 +54.4,50.425,-2.588178045,50.4456,0,9.999575792,2.969375,-0.540093222,-1.42130827,90.00000001 +54.41,50.425,-2.588176638,50.4158,0,10.00068609,2.988125,-0.643354828,-1.51286091,90.00000001 +54.42,50.425,-2.58817523,50.3858,0,10.00068605,3.005,-0.746482131,-1.603094314,90.00000001 +54.43,50.425,-2.588173823,50.3557,0,9.999797722,3.02125,-0.849453476,-1.691929816,90.00000001 +54.44,50.425,-2.588172416,50.3254,0,9.999797674,3.0365625,-0.95224749,-1.779289894,90.00000001 +54.45,50.425,-2.588171009,50.2949,0,10.0006859,3.049375,-1.054842574,-1.86509846,90.00000001 +54.46,50.425,-2.588169601,50.2644,0,10.00068586,3.06,-1.157217412,-1.949280628,90.00000001 +54.47,50.425,-2.588168194,50.2337,0,9.999797531,3.07,-1.259350577,-2.031762944,90.00000001 +54.48,50.425,-2.588166787,50.203,0,9.999797483,3.0796875,-1.361220754,-2.112473561,90.00000001 +54.49,50.425,-2.58816538,50.1721,0,10.00068571,3.0884375,-1.462806629,-2.191342061,90.00000001 +54.5,50.425,-2.588163972,50.1412,0,10.00068566,3.0959375,-1.564087061,-2.268299689,90.00000001 +54.51,50.425,-2.588162565,50.1102,0,9.999575267,3.1015625,-1.665040792,-2.343279353,90.00000001 +54.52,50.425,-2.588161158,50.0791,0,9.99890901,3.1046875,-1.765646852,-2.41621562,90.00000001 +54.53,50.425,-2.588159751,50.0481,0,9.999575171,3.1065625,-1.865884157,-2.487044891,90.00000001 +54.54,50.425,-2.588158344,50.017,0,10.00068547,3.1084375,-1.965731793,-2.555705403,90.00000001 +54.55,50.425,-2.588156936,49.9859,0,10.00068542,3.1096875,-2.065168905,-2.622137339,90.00000001 +54.56,50.425,-2.588155529,49.9548,0,9.999575024,3.109375,-2.164174751,-2.686282714,90.00000001 +54.57,50.425,-2.588154122,49.9237,0,9.998686697,3.1065625,-2.262728591,-2.748085666,90.00000001 +54.58,50.425,-2.588152715,49.8926,0,9.998686649,3.10125,-2.360809971,-2.807492165,90.00000001 +54.59,50.425,-2.588151308,49.8617,0,9.999574879,3.095,-2.458398262,-2.864450529,90.00000001 +54.6,50.425,-2.588149901,49.8307,0,10.00068518,3.0884375,-2.555473184,-2.918911085,90.00000001 +54.61,50.425,-2.588148493,49.7999,0,10.0009072,3.08125,-2.652014395,-2.970826275,90.00000001 +54.62,50.425,-2.588147086,49.7691,0,10.00068508,3.073125,-2.748001785,-3.020150836,90.00000001 +54.63,50.425,-2.588145679,49.7384,0,10.0009071,3.0628125,-2.843415301,-3.066841797,90.00000001 +54.64,50.425,-2.588144271,49.7078,0,10.00068499,3.05,-2.938235003,-3.11085842,90.00000001 +54.65,50.425,-2.588142864,49.6774,0,9.999574591,3.0365625,-3.032441067,-3.152162375,90.00000001 +54.66,50.425,-2.588141457,49.6471,0,9.998908335,3.023125,-3.126013842,-3.190717564,90.00000001 +54.67,50.425,-2.58814005,49.6169,0,9.999574496,3.0078125,-3.218933845,-3.226490356,90.00000001 +54.68,50.425,-2.588138643,49.5869,0,10.0006848,2.9896875,-3.31118154,-3.259449639,90.00000001 +54.69,50.425,-2.588137235,49.5571,0,10.00068475,2.97,-3.402737789,-3.28956665,90.00000001 +54.7,50.425,-2.588135828,49.5275,0,9.999574357,2.95,-3.493583399,-3.31681509,90.00000001 +54.71,50.425,-2.588134421,49.4981,0,9.998908102,2.9296875,-3.583699404,-3.341171239,90.00000001 +54.72,50.425,-2.588133014,49.4689,0,9.999574265,2.908125,-3.673067069,-3.362613841,90.00000001 +54.73,50.425,-2.588131607,49.4399,0,10.00068457,2.8846875,-3.761667601,-3.381124159,90.00000001 +54.74,50.425,-2.588130199,49.4112,0,10.00068452,2.8596875,-3.84948255,-3.396686094,90.00000001 +54.75,50.425,-2.588128792,49.3827,0,9.99957413,2.8334375,-3.936493583,-3.409286066,90.00000001 +54.76,50.425,-2.588127385,49.3545,0,9.998907877,2.80625,-4.022682592,-3.418913132,90.00000001 +54.77,50.425,-2.588125978,49.3266,0,9.999574042,2.778125,-4.108031474,-3.425558813,90.00000001 +54.78,50.425,-2.588124571,49.2989,0,10.00068435,2.748125,-4.192522409,-3.429217377,90.00000001 +54.79,50.425,-2.588123163,49.2716,0,10.0006843,2.7165625,-4.276137864,-3.429885561,90.00000001 +54.8,50.425,-2.588121756,49.2446,0,9.999795983,2.685,-4.35886025,-3.427562904,90.00000001 +54.81,50.425,-2.588120349,49.2179,0,9.999795942,2.653125,-4.440672321,-3.422251299,90.00000001 +54.82,50.425,-2.588118942,49.1915,0,10.00068418,2.6196875,-4.521557059,-3.4139555,90.00000001 +54.83,50.425,-2.588117534,49.1655,0,10.00068414,2.5846875,-4.601497506,-3.40268267,90.00000001 +54.84,50.425,-2.588116127,49.1398,0,9.99979582,2.548125,-4.680477045,-3.388442607,90.00000001 +54.85,50.425,-2.58811472,49.1145,0,9.99979578,2.5096875,-4.758479061,-3.371247799,90.00000001 +54.86,50.425,-2.588113313,49.0896,0,10.00068402,2.47,-4.835487339,-3.351113203,90.00000001 +54.87,50.425,-2.588111905,49.0651,0,10.00068398,2.43,-4.911485836,-3.328056407,90.00000001 +54.88,50.425,-2.588110498,49.041,0,9.999573595,2.39,-4.986458567,-3.302097466,90.00000001 +54.89,50.425,-2.588109091,49.0173,0,9.998685279,2.3496875,-5.060390004,-3.273259068,90.00000001 +54.9,50.425,-2.588107684,48.994,0,9.998685243,2.3078125,-5.133264563,-3.241566366,90.00000001 +54.91,50.425,-2.588106277,48.9711,0,9.999573486,2.263125,-5.205067176,-3.207046919,90.00000001 +54.92,50.425,-2.58810487,48.9487,0,10.0006838,2.216875,-5.275782772,-3.169730923,90.00000001 +54.93,50.425,-2.588103462,48.9268,0,10.00068376,2.1715625,-5.345396572,-3.129650806,90.00000001 +54.94,50.425,-2.588102055,48.9053,0,9.999573383,2.1265625,-5.41389402,-3.086841634,90.00000001 +54.95,50.425,-2.588100648,48.8842,0,9.998907141,2.079375,-5.481260908,-3.041340706,90.00000001 +54.96,50.425,-2.588099241,48.8637,0,9.999573318,2.03,-5.547483026,-2.993187672,90.00000001 +54.97,50.425,-2.588097834,48.8436,0,10.00068364,1.98,-5.612546681,-2.942424528,90.00000001 +54.98,50.425,-2.588096426,48.8241,0,10.00090567,1.9296875,-5.676438236,-2.889095564,90.00000001 +54.99,50.425,-2.588095019,48.805,0,10.00068357,1.8784375,-5.739144284,-2.833247248,90.00000001 +55,50.425,-2.588093612,48.7865,0,10.00090561,1.8265625,-5.800651876,-2.77492828,90.00000001 +55.01,50.425,-2.588092204,48.7685,0,10.00068352,1.775,-5.860948006,-2.71418954,90.00000001 +55.02,50.425,-2.588090797,48.751,0,9.999573142,1.723125,-5.920020184,-2.651084026,90.00000001 +55.03,50.425,-2.58808939,48.734,0,9.998906907,1.6696875,-5.977855977,-2.585666684,90.00000001 +55.04,50.425,-2.588087983,48.7176,0,9.999573089,1.6146875,-6.034443466,-2.517994639,90.00000001 +55.05,50.425,-2.588086576,48.7017,0,10.00068341,1.558125,-6.089770677,-2.448126848,90.00000001 +55.06,50.425,-2.588085168,48.6864,0,10.00068339,1.5,-6.143826151,-2.376124216,90.00000001 +55.07,50.425,-2.588083761,48.6717,0,9.999573018,1.441875,-6.196598543,-2.302049654,90.00000001 +55.08,50.425,-2.588082354,48.6576,0,9.998906787,1.3853125,-6.248076853,-2.225967562,90.00000001 +55.09,50.425,-2.588080947,48.644,0,9.999572974,1.3296875,-6.298250309,-2.147944461,90.00000001 +55.1,50.425,-2.58807954,48.631,0,10.0006833,1.2728125,-6.347108482,-2.068048304,90.00000001 +55.11,50.425,-2.588078132,48.6185,0,10.00068328,1.213125,-6.394641176,-1.98634882,90.00000001 +55.12,50.425,-2.588076725,48.6067,0,9.999572916,1.1515625,-6.440838419,-1.902917169,90.00000001 +55.13,50.425,-2.588075318,48.5955,0,9.998684621,1.0903125,-6.485690529,-1.817826119,90.00000001 +55.14,50.425,-2.588073911,48.5849,0,9.998684604,1.03,-6.529188225,-1.73114998,90.00000001 +55.15,50.425,-2.588072504,48.5749,0,9.999572866,0.97,-6.571322338,-1.642964155,90.00000001 +55.16,50.425,-2.588071097,48.5655,0,10.00090527,0.9096875,-6.612084159,-1.553345706,90.00000001 +55.17,50.425,-2.588069689,48.5567,0,10.00179353,0.848125,-6.651465153,-1.462372728,90.00000001 +55.18,50.425,-2.588068282,48.5485,0,10.00179352,0.785,-6.68945701,-1.370124461,90.00000001 +55.19,50.425,-2.588066874,48.541,0,10.00090523,0.7215625,-6.726051882,-1.276681519,90.00000001 +55.2,50.425,-2.588065467,48.5341,0,9.999572802,0.6584375,-6.761242148,-1.182125205,90.00000001 +55.21,50.425,-2.58806406,48.5278,0,9.998906583,0.595,-6.795020359,-1.08653814,90.00000001 +55.22,50.425,-2.588062653,48.5222,0,9.999572784,0.5315625,-6.827379583,-0.990003518,90.00000001 +55.23,50.425,-2.588061246,48.5172,0,10.00068312,0.4684375,-6.858312944,-0.892605678,90.00000001 +55.24,50.425,-2.588059838,48.5128,0,10.00068312,0.405,-6.887814025,-0.794429417,90.00000001 +55.25,50.425,-2.588058431,48.5091,0,9.999572763,0.3415625,-6.915876696,-0.69556045,90.00000001 +55.26,50.425,-2.588057024,48.506,0,9.998684479,0.2784375,-6.942495054,-0.596084893,90.00000001 +55.27,50.425,-2.588055617,48.5035,0,9.998684475,0.2146875,-6.9676636,-0.496089548,90.00000001 +55.28,50.425,-2.58805421,48.5017,0,9.999572752,0.1496875,-6.991377006,-0.39566162,90.00000001 +55.29,50.425,-2.588052803,48.5005,0,10.0006831,0.08375,-7.013630343,-0.294888657,90.00000001 +55.3,50.425,-2.588051395,48.5,0,10.0006831,0.0184375,-7.034419028,-0.193858551,90.00000001 +55.31,50.425,-2.588049988,48.5002,0,9.999572749,-0.045,-7.053738592,-0.092659422,90.00000001 +55.32,50.425,-2.588048581,48.5009,0,9.998906541,-0.1084375,-7.071585138,0.008620494,90.00000001 +55.33,50.425,-2.588047174,48.5023,0,9.999572752,-0.17375,-7.087954829,0.109892961,90.00000001 +55.34,50.425,-2.588045767,48.5044,0,10.0006831,-0.239375,-7.102844341,0.211069573,90.00000001 +55.35,50.425,-2.588044359,48.5071,0,10.00090518,-0.3034375,-7.116250464,0.312062093,90.00000001 +55.36,50.425,-2.588042952,48.5105,0,10.00068311,-0.3665625,-7.12817045,0.412782516,90.00000001 +55.37,50.425,-2.588041545,48.5144,0,10.00090519,-0.43,-7.138601834,0.513143007,90.00000001 +55.38,50.425,-2.588040137,48.5191,0,10.00068313,-0.4934375,-7.147542382,0.613056017,90.00000001 +55.39,50.425,-2.58803873,48.5243,0,9.999572787,-0.5565625,-7.154990318,0.712434401,90.00000001 +55.4,50.425,-2.588037323,48.5302,0,9.998906588,-0.6203125,-7.16094398,0.811191584,90.00000001 +55.41,50.425,-2.588035916,48.5367,0,9.999572807,-0.6846875,-7.165402164,0.909241336,90.00000001 +55.42,50.425,-2.588034509,48.5439,0,10.00068317,-0.748125,-7.168363955,1.006498228,90.00000001 +55.43,50.425,-2.588033101,48.5517,0,10.00068318,-0.8096875,-7.169828722,1.102877464,90.00000001 +55.44,50.425,-2.588031694,48.5601,0,9.999572843,-0.8703125,-7.169796178,1.198294991,90.00000001 +55.45,50.425,-2.588030287,48.5691,0,9.998906649,-0.931875,-7.168266323,1.292667557,90.00000001 +55.46,50.425,-2.58802888,48.5787,0,9.999572873,-0.9946875,-7.165239444,1.385912943,90.00000001 +55.47,50.425,-2.588027473,48.589,0,10.00068324,-1.0565625,-7.160716229,1.477949732,90.00000001 +55.48,50.425,-2.588026065,48.5999,0,10.00068325,-1.11625,-7.154697537,1.568697767,90.00000001 +55.49,50.425,-2.588024658,48.6113,0,9.999572923,-1.175,-7.147184742,1.658077808,90.00000001 +55.5,50.425,-2.588023251,48.6234,0,9.998684664,-1.23375,-7.138179278,1.746012047,90.00000001 +55.51,50.425,-2.588021844,48.636,0,9.998684684,-1.293125,-7.12768315,1.832423708,90.00000001 +55.52,50.425,-2.588020437,48.6492,0,9.999572983,-1.353125,-7.115698477,1.917237505,90.00000001 +55.53,50.425,-2.58801903,48.6631,0,10.00090542,-1.41125,-7.102227781,2.00037941,90.00000001 +55.54,50.425,-2.588017622,48.6775,0,10.00179372,-1.4665625,-7.087273869,2.081776946,90.00000001 +55.55,50.425,-2.588016215,48.6924,0,10.00179375,-1.521875,-7.070839892,2.161359179,90.00000001 +55.56,50.425,-2.588014807,48.7079,0,10.00090549,-1.5784375,-7.052929232,2.239056668,90.00000001 +55.57,50.425,-2.5880134,48.724,0,9.9995731,-1.6346875,-7.033545668,2.314801631,90.00000001 +55.58,50.425,-2.588011993,48.7406,0,9.998684847,-1.6896875,-7.01269327,2.388528064,90.00000001 +55.59,50.425,-2.588010586,48.7578,0,9.998684874,-1.7434375,-6.990376335,2.460171681,90.00000001 +55.6,50.425,-2.588009179,48.7755,0,9.99957318,-1.79625,-6.966599503,2.529669972,90.00000001 +55.61,50.425,-2.588007772,48.7937,0,10.00068356,-1.8484375,-6.941367874,2.596962375,90.00000001 +55.62,50.425,-2.588006364,48.8125,0,10.00068359,-1.8996875,-6.914686548,2.661990163,90.00000001 +55.63,50.425,-2.588004957,48.8317,0,9.999573268,-1.95,-6.886561253,2.724696727,90.00000001 +55.64,50.425,-2.58800355,48.8515,0,9.998907089,-2,-6.856997719,2.785027235,90.00000001 +55.65,50.425,-2.588002143,48.8717,0,9.99957333,-2.049375,-6.826002249,2.842929203,90.00000001 +55.66,50.425,-2.588000736,48.8925,0,10.00068371,-2.096875,-6.793581203,2.898352041,90.00000001 +55.67,50.425,-2.587999328,48.9137,0,10.00068374,-2.143125,-6.759741457,2.951247505,90.00000001 +55.68,50.425,-2.587997921,48.9353,0,9.99957343,-2.19,-6.724489999,3.001569471,90.00000001 +55.69,50.425,-2.587996514,48.9575,0,9.998907256,-2.23625,-6.687834222,3.049273995,90.00000001 +55.7,50.425,-2.587995107,48.9801,0,9.9995735,-2.2796875,-6.649781746,3.094319478,90.00000001 +55.71,50.425,-2.5879937,49.0031,0,10.00068388,-2.321875,-6.610340592,3.136666674,90.00000001 +55.72,50.425,-2.587992292,49.0265,0,10.00090599,-2.365,-6.569518896,3.176278684,90.00000001 +55.73,50.425,-2.587990885,49.0504,0,10.00068396,-2.4078125,-6.52732531,3.213120902,90.00000001 +55.74,50.425,-2.587989478,49.0747,0,10.00090607,-2.448125,-6.483768542,3.247161241,90.00000001 +55.75,50.425,-2.58798807,49.0994,0,10.00068403,-2.4865625,-6.438857704,3.278370023,90.00000001 +55.76,50.425,-2.587986663,49.1244,0,9.999573726,-2.5246875,-6.392602248,3.306720032,90.00000001 +55.77,50.425,-2.587985256,49.1499,0,9.998907557,-2.5615625,-6.345011743,3.332186516,90.00000001 +55.78,50.425,-2.587983849,49.1757,0,9.999573806,-2.5965625,-6.296096159,3.354747245,90.00000001 +55.79,50.425,-2.587982442,49.2018,0,10.0006842,-2.6315625,-6.245865694,3.374382623,90.00000001 +55.8,50.425,-2.587981034,49.2283,0,10.00068424,-2.6665625,-6.194330891,3.391075462,90.00000001 +55.81,50.425,-2.587979627,49.2552,0,9.99957393,-2.6996875,-6.141502463,3.404811266,90.00000001 +55.82,50.425,-2.58797822,49.2823,0,9.998685694,-2.73125,-6.087391527,3.415578002,90.00000001 +55.83,50.425,-2.587976813,49.3098,0,9.998685737,-2.7615625,-6.032009254,3.423366332,90.00000001 +55.84,50.425,-2.587975406,49.3376,0,9.999574059,-2.7896875,-5.975367277,3.42816938,90.00000001 +55.85,50.425,-2.587973999,49.3656,0,10.00068445,-2.8165625,-5.917477398,3.429983078,90.00000001 +55.86,50.425,-2.587972591,49.3939,0,10.0006845,-2.8434375,-5.858351763,3.428805764,90.00000001 +55.87,50.425,-2.587971184,49.4225,0,9.999574192,-2.8696875,-5.798002691,3.42463847,90.00000001 +55.88,50.425,-2.587969777,49.4513,0,9.998908029,-2.8946875,-5.736442788,3.417484806,90.00000001 +55.89,50.425,-2.58796837,49.4804,0,9.999574283,-2.918125,-5.673684887,3.407351073,90.00000001 +55.9,50.425,-2.587966963,49.5097,0,10.00090675,-2.939375,-5.60974211,3.394246096,90.00000001 +55.91,50.425,-2.587965555,49.5392,0,10.00179507,-2.9584375,-5.544627805,3.378181276,90.00000001 +55.92,50.425,-2.587964148,49.5689,0,10.00179512,-2.9765625,-5.478355611,3.359170594,90.00000001 +55.93,50.425,-2.58796274,49.5987,0,10.00090689,-2.995,-5.410939276,3.337230722,90.00000001 +55.94,50.425,-2.587961333,49.6288,0,9.999574515,-3.013125,-5.342392955,3.312380683,90.00000001 +55.95,50.425,-2.587959926,49.659,0,9.998686284,-3.029375,-5.27273097,3.284642249,90.00000001 +55.96,50.425,-2.587958519,49.6894,0,9.998686331,-3.043125,-5.201967818,3.254039542,90.00000001 +55.97,50.425,-2.587957112,49.7199,0,9.999574657,-3.0546875,-5.13011828,3.220599261,90.00000001 +55.98,50.425,-2.587955705,49.7505,0,10.00068505,-3.065,-5.057197426,3.184350571,90.00000001 +55.99,50.425,-2.587954297,49.7812,0,10.0006851,-3.075,-4.983220438,3.14532504,90.00000001 +56,50.425,-2.58795289,49.812,0,9.999574801,-3.0846875,-4.90820273,3.103556818,90.00000001 +56.01,50.425,-2.587951483,49.8429,0,9.998908641,-3.0928125,-4.832160058,3.059082173,90.00000001 +56.02,50.425,-2.587950076,49.8739,0,9.999574898,-3.098125,-4.755108236,3.011940007,90.00000001 +56.03,50.425,-2.587948669,49.9049,0,10.00068529,-3.1015625,-4.677063362,2.962171346,90.00000001 +56.04,50.425,-2.587947261,49.9359,0,10.00068534,-3.105,-4.598041711,2.909819677,90.00000001 +56.05,50.425,-2.587945854,49.967,0,9.999575044,-3.108125,-4.518059839,2.854930549,90.00000001 +56.06,50.425,-2.587944447,49.9981,0,9.998908884,-3.1096875,-4.437134478,2.79755192,90.00000001 +56.07,50.425,-2.58794304,50.0292,0,9.999575141,-3.1096875,-4.355282415,2.737733808,90.00000001 +56.08,50.425,-2.587941633,50.0603,0,10.00068554,-3.108125,-4.272520839,2.675528296,90.00000001 +56.09,50.425,-2.587940225,50.0914,0,10.00090766,-3.1046875,-4.188866996,2.6109897,90.00000001 +56.1,50.425,-2.587938818,50.1224,0,10.00068564,-3.0996875,-4.10433836,2.544174284,90.00000001 +56.11,50.425,-2.587937411,50.1534,0,10.00090775,-3.093125,-4.01895258,2.475140318,90.00000001 +56.12,50.425,-2.587936003,50.1843,0,10.00068573,-3.0846875,-3.932727474,2.403947963,90.00000001 +56.13,50.425,-2.587934596,50.2151,0,9.999575431,-3.075,-3.84568109,2.330659384,90.00000001 +56.14,50.425,-2.587933189,50.2458,0,9.998909271,-3.065,-3.757831591,2.25533841,90.00000001 +56.15,50.425,-2.587931782,50.2764,0,9.999575528,-3.055,-3.669197312,2.178050701,90.00000001 +56.16,50.425,-2.587930375,50.3069,0,10.00068592,-3.044375,-3.579796759,2.098863751,90.00000001 +56.17,50.425,-2.587928967,50.3373,0,10.00068597,-3.03125,-3.489648611,2.017846544,90.00000001 +56.18,50.425,-2.58792756,50.3676,0,9.99957567,-3.0146875,-3.398771718,1.935069785,90.00000001 +56.19,50.425,-2.587926153,50.3976,0,9.998687438,-2.996875,-3.307185045,1.85060555,90.00000001 +56.2,50.425,-2.587924746,50.4275,0,9.998687485,-2.98,-3.214907671,1.764527579,90.00000001 +56.21,50.425,-2.587923339,50.4572,0,9.999575811,-2.9628125,-3.121958905,1.676910931,90.00000001 +56.22,50.425,-2.587921932,50.4868,0,10.00068621,-2.9428125,-3.02835817,1.587831979,90.00000001 +56.23,50.425,-2.587920524,50.5161,0,10.00068625,-2.9196875,-2.934125005,1.497368475,90.00000001 +56.24,50.425,-2.587919117,50.5452,0,9.999798017,-2.8953125,-2.839279061,1.405599143,90.00000001 +56.25,50.425,-2.58791771,50.574,0,9.999798063,-2.8715625,-2.743840221,1.312604196,90.00000001 +56.26,50.425,-2.587916303,50.6026,0,10.00068639,-2.848125,-2.647828308,1.218464595,90.00000001 +56.27,50.425,-2.587914895,50.631,0,10.0009085,-2.8228125,-2.551263491,1.123262443,90.00000001 +56.28,50.425,-2.587913488,50.6591,0,10.00068647,-2.7946875,-2.454165823,1.02708082,90.00000001 +56.29,50.425,-2.587912081,50.6869,0,10.00090859,-2.7646875,-2.356555644,0.930003607,90.00000001 +56.3,50.425,-2.587910673,50.7144,0,10.00068656,-2.7334375,-2.258453352,0.832115372,90.00000001 +56.31,50.425,-2.587909266,50.7416,0,9.999576255,-2.7015625,-2.159879401,0.733501543,90.00000001 +56.32,50.425,-2.587907859,50.7684,0,9.998688019,-2.6696875,-2.060854361,0.634248065,90.00000001 +56.33,50.425,-2.587906452,50.795,0,9.998688061,-2.6365625,-1.961398972,0.534441509,90.00000001 +56.34,50.425,-2.587905045,50.8212,0,9.99957638,-2.60125,-1.861533975,0.434168911,90.00000001 +56.35,50.425,-2.587903638,50.847,0,10.00068677,-2.565,-1.761280169,0.333517759,90.00000001 +56.36,50.425,-2.58790223,50.8725,0,10.00068681,-2.5284375,-1.660658582,0.232575716,90.00000001 +56.37,50.425,-2.587900823,50.8976,0,9.999576499,-2.49125,-1.559690183,0.131430903,90.00000001 +56.38,50.425,-2.587899416,50.9223,0,9.998910329,-2.453125,-1.458396057,0.030171442,90.00000001 +56.39,50.425,-2.587898009,50.9467,0,9.999576576,-2.413125,-1.356797348,-0.071114261,90.00000001 +56.4,50.425,-2.587896602,50.9706,0,10.00068696,-2.37125,-1.25491531,-0.172338027,90.00000001 +56.41,50.425,-2.587895194,50.9941,0,10.000687,-2.3284375,-1.152771202,-0.273411449,90.00000001 +56.42,50.425,-2.587893787,51.0172,0,9.999798756,-2.2846875,-1.050386394,-0.374246521,90.00000001 +56.43,50.425,-2.58789238,51.0398,0,9.999798792,-2.24,-0.947782144,-0.474755178,90.00000001 +56.44,50.425,-2.587890973,51.062,0,10.00068711,-2.195,-0.844979993,-0.574849874,90.00000001 +56.45,50.425,-2.587889565,51.0837,0,10.00068714,-2.1496875,-0.742001372,-0.674443288,90.00000001 +56.46,50.425,-2.587888158,51.105,0,9.999798893,-2.103125,-0.638867823,-0.773448562,90.00000001 +56.47,50.425,-2.587886751,51.1258,0,9.999798926,-2.0546875,-0.535600832,-0.871779407,90.00000001 +56.48,50.425,-2.587885344,51.1461,0,10.00068724,-2.005,-0.432222,-0.969350051,90.00000001 +56.49,50.425,-2.587883936,51.1659,0,10.00068727,-1.955,-0.328752927,-1.066075354,90.00000001 +56.5,50.425,-2.587882529,51.1852,0,9.999576949,-1.905,-0.225215156,-1.16187109,90.00000001 +56.51,50.425,-2.587881122,51.204,0,9.998910769,-1.8546875,-0.121630346,-1.256653607,90.00000001 +56.52,50.425,-2.587879715,51.2223,0,9.999577008,-1.803125,-0.018020153,-1.350340343,90.00000001 +56.53,50.425,-2.587878308,51.2401,0,10.00068738,-1.75,0.085593821,-1.442849535,90.00000001 +56.54,50.425,-2.5878769,51.2573,0,10.00068741,-1.69625,0.189189862,-1.534100513,90.00000001 +56.55,50.425,-2.587875493,51.274,0,9.999577088,-1.641875,0.292746426,-1.624013805,90.00000001 +56.56,50.425,-2.587874086,51.2902,0,9.998688834,-1.58625,0.396241912,-1.712510861,90.00000001 +56.57,50.425,-2.587872679,51.3057,0,9.998688858,-1.53,0.499654549,-1.799514617,90.00000001 +56.58,50.425,-2.587871272,51.3208,0,9.999577161,-1.4734375,0.602962907,-1.884949156,90.00000001 +56.59,50.425,-2.587869865,51.3352,0,10.00068753,-1.41625,0.70614533,-1.968739993,90.00000001 +56.6,50.425,-2.587868457,51.3491,0,10.00090962,-1.35875,0.809180273,-2.050814078,90.00000001 +56.61,50.425,-2.58786705,51.3624,0,10.00068757,-1.30125,0.91204625,-2.131099846,90.00000001 +56.62,50.425,-2.587865643,51.3751,0,10.00090966,-1.243125,1.01472172,-2.209527226,90.00000001 +56.63,50.425,-2.587864235,51.3873,0,10.00068761,-1.183125,1.117185309,-2.286027863,90.00000001 +56.64,50.425,-2.587862828,51.3988,0,9.999577284,-1.121875,1.21941559,-2.360535065,90.00000001 +56.65,50.425,-2.587861421,51.4097,0,9.998911092,-1.061875,1.321391192,-2.432983802,90.00000001 +56.66,50.425,-2.587860014,51.42,0,9.999577317,-1.0028125,1.423090856,-2.503310991,90.00000001 +56.67,50.425,-2.587858607,51.4298,0,10.00068768,-0.9415625,1.524493328,-2.571455268,90.00000001 +56.68,50.425,-2.587857199,51.4389,0,10.00068769,-0.878125,1.625577407,-2.63735716,90.00000001 +56.69,50.425,-2.587855792,51.4473,0,9.999577359,-0.8153125,1.726322009,-2.700959257,90.00000001 +56.7,50.425,-2.587854385,51.4552,0,9.998911162,-0.7534375,1.826706105,-2.762206039,90.00000001 +56.71,50.425,-2.587852978,51.4624,0,9.999577383,-0.69125,1.926708726,-2.821044164,90.00000001 +56.72,50.425,-2.587851571,51.469,0,10.00068774,-0.6284375,2.026308959,-2.877422294,90.00000001 +56.73,50.425,-2.587850163,51.475,0,10.00068775,-0.565,2.125486005,-2.93129127,90.00000001 +56.74,50.425,-2.587848756,51.4803,0,9.999577411,-0.5015625,2.224219181,-2.98260411,90.00000001 +56.75,50.425,-2.587847349,51.485,0,9.998689139,-0.4384375,2.32248786,-3.031316122,90.00000001 +56.76,50.425,-2.587845942,51.4891,0,9.998689146,-0.3746875,2.420271531,-3.077384736,90.00000001 +56.77,50.425,-2.587844535,51.4925,0,9.99957743,-0.31,2.517549795,-3.120769845,90.00000001 +56.78,50.425,-2.587843128,51.4953,0,10.00090985,-0.2453125,2.614302255,-3.161433577,90.00000001 +56.79,50.425,-2.58784172,51.4974,0,10.00179813,-0.1815625,2.710508745,-3.199340465,90.00000001 +56.8,50.425,-2.587840313,51.4989,0,10.00179814,-0.118125,2.806149209,-3.234457564,90.00000001 +56.81,50.425,-2.587838905,51.4998,0,10.00090986,-0.0534375,2.901203595,-3.266754106,90.00000001 +56.82,50.425,-2.587837498,51.5,0,9.999577441,0.011875,2.995652135,-3.296201959,90.00000001 +56.83,50.425,-2.587836091,51.4995,0,9.998911231,0.07625,3.089475063,-3.32277557,90.00000001 +56.84,50.425,-2.587834684,51.4985,0,9.999577439,0.14,3.18265284,-3.346451618,90.00000001 +56.85,50.425,-2.587833277,51.4967,0,10.00068779,0.20375,3.275165928,-3.367209478,90.00000001 +56.86,50.425,-2.587831869,51.4944,0,10.00068778,0.268125,3.36699502,-3.385031101,90.00000001 +56.87,50.425,-2.587830462,51.4914,0,9.999577428,0.3334375,3.458120978,-3.39990096,90.00000001 +56.88,50.425,-2.587829055,51.4877,0,9.998689143,0.398125,3.548524723,-3.411806049,90.00000001 +56.89,50.425,-2.587827648,51.4834,0,9.998689137,0.4615625,3.638187404,-3.420735998,90.00000001 +56.9,50.425,-2.587826241,51.4785,0,9.999577408,0.525,3.727090343,-3.426682956,90.00000001 +56.91,50.425,-2.587824834,51.4729,0,10.00068775,0.5884375,3.815214919,-3.429641824,90.00000001 +56.92,50.425,-2.587823426,51.4667,0,10.00068774,0.6515625,3.902542682,-3.429610025,90.00000001 +56.93,50.425,-2.587822019,51.4599,0,9.999577379,0.715,3.989055528,-3.426587558,90.00000001 +56.94,50.425,-2.587820612,51.4524,0,9.998911158,0.778125,4.074735235,-3.420577002,90.00000001 +56.95,50.425,-2.587819205,51.4443,0,9.999577354,0.8396875,4.159564043,-3.411583684,90.00000001 +56.96,50.425,-2.587817798,51.4356,0,10.00090976,0.9003125,4.243524133,-3.399615398,90.00000001 +56.97,50.425,-2.58781639,51.4263,0,10.00179802,0.9615625,4.326598085,-3.384682628,90.00000001 +56.98,50.425,-2.587814983,51.4164,0,10.00179801,1.0234375,4.408768426,-3.366798324,90.00000001 +56.99,50.425,-2.587813575,51.4058,0,10.00090971,1.0846875,4.490018024,-3.345978183,90.00000001 +57,50.425,-2.587812168,51.3947,0,9.999577277,1.145,4.570330034,-3.322240255,90.00000001 +57.01,50.425,-2.587810761,51.3829,0,9.99868898,1.205,4.649687496,-3.295605281,90.00000001 +57.02,50.425,-2.587809354,51.3706,0,9.998688961,1.2646875,4.728073967,-3.266096522,90.00000001 +57.03,50.425,-2.587807947,51.3576,0,9.999577219,1.323125,4.805473059,-3.233739647,90.00000001 +57.04,50.425,-2.58780654,51.3441,0,10.00068755,1.38,4.881868559,-3.198562904,90.00000001 +57.05,50.425,-2.587805132,51.33,0,10.00068752,1.436875,4.957244594,-3.160596944,90.00000001 +57.06,50.425,-2.587803725,51.3154,0,9.999577153,1.4946875,5.031585295,-3.119874943,90.00000001 +57.07,50.425,-2.587802318,51.3001,0,9.99891092,1.5515625,5.104875249,-3.076432366,90.00000001 +57.08,50.425,-2.587800911,51.2843,0,9.999577104,1.60625,5.177099157,-3.030307086,90.00000001 +57.09,50.425,-2.587799504,51.268,0,10.00068743,1.6603125,5.248241837,-2.981539325,90.00000001 +57.1,50.425,-2.587798096,51.2511,0,10.0006874,1.7146875,5.318288506,-2.930171596,90.00000001 +57.11,50.425,-2.587796689,51.2337,0,9.999577025,1.768125,5.387224553,-2.876248705,90.00000001 +57.12,50.425,-2.587795282,51.2157,0,9.998688718,1.82,5.455035483,-2.819817747,90.00000001 +57.13,50.425,-2.587793875,51.1973,0,9.998688689,1.8715625,5.521707259,-2.760927828,90.00000001 +57.14,50.425,-2.587792468,51.1783,0,9.999576938,1.9234375,5.587225842,-2.699630339,90.00000001 +57.15,50.425,-2.587791061,51.1588,0,10.00090933,1.9746875,5.651577654,-2.635978739,90.00000001 +57.16,50.425,-2.587789653,51.1388,0,10.00179757,2.0246875,5.714749173,-2.570028489,90.00000001 +57.17,50.425,-2.587788246,51.1183,0,10.00179754,2.073125,5.776727221,-2.501837172,90.00000001 +57.18,50.425,-2.587786838,51.0973,0,10.00090923,2.12,5.837498907,-2.431464204,90.00000001 +57.19,50.425,-2.587785431,51.0759,0,9.999576778,2.1665625,5.897051509,-2.358971005,90.00000001 +57.2,50.425,-2.587784024,51.054,0,9.998910535,2.213125,5.955372597,-2.284420716,90.00000001 +57.21,50.425,-2.587782617,51.0316,0,9.999576708,2.258125,6.012449965,-2.207878368,90.00000001 +57.22,50.425,-2.58778121,51.0088,0,10.00068702,2.30125,6.068271696,-2.129410709,90.00000001 +57.23,50.425,-2.587779802,50.9856,0,10.00068699,2.3434375,6.122826159,-2.049086209,90.00000001 +57.24,50.425,-2.587778395,50.9619,0,9.9995766,2.385,6.176101952,-1.966974825,90.00000001 +57.25,50.425,-2.587776988,50.9379,0,9.998688283,2.42625,6.22808796,-1.883148292,90.00000001 +57.26,50.425,-2.587775581,50.9134,0,9.998688245,2.4665625,6.278773296,-1.797679548,90.00000001 +57.27,50.425,-2.587774174,50.8885,0,9.999576485,2.5046875,6.328147361,-1.710643248,90.00000001 +57.28,50.425,-2.587772767,50.8633,0,10.00068679,2.5415625,6.376199899,-1.622115195,90.00000001 +57.29,50.425,-2.587771359,50.8377,0,10.00068675,2.5784375,6.422920883,-1.532172681,90.00000001 +57.3,50.425,-2.587769952,50.8117,0,9.999576365,2.6146875,6.468300515,-1.44089403,90.00000001 +57.31,50.425,-2.587768545,50.7854,0,9.998910115,2.6496875,6.512329285,-1.34835894,90.00000001 +57.32,50.425,-2.587767138,50.7587,0,9.999576282,2.683125,6.554998025,-1.254648083,90.00000001 +57.33,50.425,-2.587765731,50.7317,0,10.00068659,2.7146875,6.596297912,-1.159843106,90.00000001 +57.34,50.425,-2.587764323,50.7044,0,10.00090861,2.745,6.636220178,-1.064026743,90.00000001 +57.35,50.425,-2.587762916,50.6768,0,10.0006865,2.7746875,6.674756575,-0.967282533,90.00000001 +57.36,50.425,-2.587761509,50.6489,0,10.00090853,2.803125,6.711899022,-0.869694872,90.00000001 +57.37,50.425,-2.587760101,50.6207,0,10.00068641,2.83,6.747639786,-0.771348786,90.00000001 +57.38,50.425,-2.587758694,50.5923,0,9.999576022,2.8565625,6.781971417,-0.672330105,90.00000001 +57.39,50.425,-2.587757287,50.5636,0,9.998909768,2.8828125,6.814886696,-0.572725117,90.00000001 +57.4,50.425,-2.58775588,50.5346,0,9.999575932,2.90625,6.846378806,-0.472620681,90.00000001 +57.41,50.425,-2.587754473,50.5054,0,10.00068623,2.9265625,6.876441099,-0.372104174,90.00000001 +57.42,50.425,-2.587753065,50.4761,0,10.00068619,2.946875,6.905067331,-0.271263144,90.00000001 +57.43,50.425,-2.587751658,50.4465,0,9.999575793,2.968125,6.932251543,-0.170185539,90.00000001 +57.44,50.425,-2.587750251,50.4167,0,9.998909538,2.9878125,6.957988062,-0.068959596,90.00000001 +57.45,50.425,-2.587748844,50.3867,0,9.9995757,3.0046875,6.982271446,0.032326508,90.00000001 +57.46,50.425,-2.587747437,50.3566,0,10.000686,3.02,7.005096709,0.133584422,90.00000001 +57.47,50.425,-2.587746029,50.3263,0,10.00068595,3.0346875,7.02645904,0.234725854,90.00000001 +57.48,50.425,-2.587744622,50.2959,0,9.999575558,3.048125,7.046353968,0.335662626,90.00000001 +57.49,50.425,-2.587743215,50.2653,0,9.998687232,3.06,7.064777368,0.436306616,90.00000001 +57.5,50.425,-2.587741808,50.2347,0,9.998687184,3.07125,7.081725403,0.53657022,90.00000001 +57.51,50.425,-2.587740401,50.2039,0,9.999575415,3.0815625,7.097194461,0.636365888,90.00000001 +57.52,50.425,-2.587738994,50.173,0,10.00090778,3.089375,7.111181392,0.735606648,90.00000001 +57.53,50.425,-2.587737586,50.1421,0,10.00179601,3.095,7.123683274,0.834205923,90.00000001 +57.54,50.425,-2.587736179,50.1111,0,10.00179597,3.1,7.134697414,0.932077829,90.00000001 +57.55,50.425,-2.587734771,50.0801,0,10.00090764,3.1046875,7.144221576,1.029136879,90.00000001 +57.56,50.425,-2.587733364,50.049,0,9.999575173,3.108125,7.152253814,1.125298506,90.00000001 +57.57,50.425,-2.587731957,50.0179,0,9.998686845,3.1096875,7.158792294,1.220478885,90.00000001 +57.58,50.425,-2.58773055,49.9868,0,9.998686796,3.1096875,7.163835812,1.314594995,90.00000001 +57.59,50.425,-2.587729143,49.9557,0,9.999575026,3.108125,7.167383281,1.407564732,90.00000001 +57.6,50.425,-2.587727736,49.9246,0,10.00068533,3.1046875,7.169433897,1.499307077,90.00000001 +57.61,50.425,-2.587726328,49.8936,0,10.00068528,3.1,7.169987259,1.589741991,90.00000001 +57.62,50.425,-2.587724921,49.8626,0,9.999574881,3.095,7.169043254,1.678790633,90.00000001 +57.63,50.425,-2.587723514,49.8317,0,9.998908623,3.0896875,7.16660211,1.766375311,90.00000001 +57.64,50.425,-2.587722107,49.8008,0,9.999574783,3.0828125,7.162664343,1.852419763,90.00000001 +57.65,50.425,-2.5877207,49.77,0,10.00068508,3.073125,7.157230698,1.936848819,90.00000001 +57.66,50.425,-2.587719292,49.7393,0,10.00068504,3.0615625,7.150302377,2.019588909,90.00000001 +57.67,50.425,-2.587717885,49.7088,0,9.99957464,3.05,7.141880815,2.100567899,90.00000001 +57.68,50.425,-2.587716478,49.6783,0,9.998908384,3.0378125,7.131967728,2.179715143,90.00000001 +57.69,50.425,-2.587715071,49.648,0,9.999574545,3.023125,7.120565238,2.256961657,90.00000001 +57.7,50.425,-2.587713664,49.6178,0,10.00068485,3.0065625,7.107675693,2.332240118,90.00000001 +57.71,50.425,-2.587712256,49.5879,0,10.00090687,2.9896875,7.093301843,2.40548475,90.00000001 +57.72,50.425,-2.587710849,49.558,0,10.00068475,2.9715625,7.077446611,2.476631785,90.00000001 +57.73,50.425,-2.587709442,49.5284,0,10.00090678,2.95125,7.060113377,2.545619169,90.00000001 +57.74,50.425,-2.587708034,49.499,0,10.00068466,2.93,7.041305694,2.612386743,90.00000001 +57.75,50.425,-2.587706627,49.4698,0,9.999574266,2.908125,7.021027572,2.676876294,90.00000001 +57.76,50.425,-2.58770522,49.4408,0,9.998908012,2.8846875,6.999283136,2.739031558,90.00000001 +57.77,50.425,-2.587703813,49.4121,0,9.999574176,2.86,6.976077027,2.798798332,90.00000001 +57.78,50.425,-2.587702406,49.3836,0,10.00068448,2.8346875,6.951414059,2.856124536,90.00000001 +57.79,50.425,-2.587700998,49.3554,0,10.00068444,2.808125,6.92529933,2.910960092,90.00000001 +57.8,50.425,-2.587699591,49.3274,0,9.999574043,2.7796875,6.897738399,2.96325733,90.00000001 +57.81,50.425,-2.587698184,49.2998,0,9.998685721,2.7496875,6.868736937,3.012970529,90.00000001 +57.82,50.425,-2.587696777,49.2724,0,9.998685679,2.7184375,6.838301018,3.060056373,90.00000001 +57.83,50.425,-2.58769537,49.2454,0,9.999573916,2.68625,6.806437058,3.10447378,90.00000001 +57.84,50.425,-2.587693963,49.2187,0,10.00068422,2.6534375,6.773151591,3.146184076,90.00000001 +57.85,50.425,-2.587692555,49.1923,0,10.00068418,2.6196875,6.738451663,3.185150821,90.00000001 +57.86,50.425,-2.587691148,49.1663,0,9.999573791,2.5846875,6.70234455,3.221340096,90.00000001 +57.87,50.425,-2.587689741,49.1406,0,9.998907542,2.5484375,6.664837644,3.254720273,90.00000001 +57.88,50.425,-2.587688334,49.1153,0,9.999573712,2.51125,6.625938966,3.285262361,90.00000001 +57.89,50.425,-2.587686927,49.0904,0,10.00090609,2.473125,6.585656481,3.312939603,90.00000001 +57.9,50.425,-2.587685519,49.0658,0,10.00179433,2.433125,6.543998668,3.337727878,90.00000001 +57.91,50.425,-2.587684112,49.0417,0,10.00179429,2.3915625,6.500974236,3.359605641,90.00000001 +57.92,50.425,-2.587682704,49.018,0,10.00090598,2.35,6.45659218,3.378553813,90.00000001 +57.93,50.425,-2.587681297,48.9947,0,9.999573523,2.308125,6.410861725,3.39455578,90.00000001 +57.94,50.425,-2.58767989,48.9718,0,9.998685209,2.2646875,6.36379244,3.407597674,90.00000001 +57.95,50.425,-2.587678483,48.9494,0,9.998685174,2.2196875,6.31539418,3.417668095,90.00000001 +57.96,50.425,-2.587677076,48.9274,0,9.999573417,2.1734375,6.265677028,3.424758219,90.00000001 +57.97,50.425,-2.587675669,48.9059,0,10.00068373,2.1265625,6.214651355,3.428861914,90.00000001 +57.98,50.425,-2.587674261,48.8849,0,10.0006837,2.0796875,6.162327817,3.42997563,90.00000001 +57.99,50.425,-2.587672854,48.8643,0,9.999573319,2.0315625,6.108717417,3.428098333,90.00000001 +58,50.425,-2.587671447,48.8442,0,9.998907079,1.9815625,6.053831211,3.423231687,90.00000001 +58.01,50.425,-2.58767004,48.8247,0,9.999573257,1.9315625,5.997680775,3.415379931,90.00000001 +58.02,50.425,-2.587668633,48.8056,0,10.00068357,1.8815625,5.940277795,3.404549883,90.00000001 +58.03,50.425,-2.587667225,48.787,0,10.00068355,1.8296875,5.881634304,3.390751054,90.00000001 +58.04,50.425,-2.587665818,48.769,0,9.99957317,1.7765625,5.821762449,3.373995418,90.00000001 +58.05,50.425,-2.587664411,48.7515,0,9.998906934,1.7234375,5.760674835,3.354297645,90.00000001 +58.06,50.425,-2.587663004,48.7345,0,9.999573116,1.6696875,5.698384181,3.331674865,90.00000001 +58.07,50.425,-2.587661597,48.7181,0,10.00068344,1.6146875,5.634903437,3.306146788,90.00000001 +58.08,50.425,-2.587660189,48.7022,0,10.00090548,1.5584375,5.570245952,3.277735701,90.00000001 +58.09,50.425,-2.587658782,48.6869,0,10.00068339,1.5015625,5.504425248,3.246466415,90.00000001 +58.1,50.425,-2.587657375,48.6722,0,10.00090544,1.4453125,5.437454961,3.212366087,90.00000001 +58.11,50.425,-2.587655967,48.658,0,10.00068334,1.3896875,5.36934913,3.175464626,90.00000001 +58.12,50.425,-2.58765456,48.6444,0,9.999572974,1.3328125,5.300121962,3.135794059,90.00000001 +58.13,50.425,-2.587653153,48.6313,0,9.998906745,1.2734375,5.229787955,3.093389052,90.00000001 +58.14,50.425,-2.587651746,48.6189,0,9.999572935,1.213125,5.158361776,3.048286502,90.00000001 +58.15,50.425,-2.587650339,48.6071,0,10.00068327,1.1534375,5.085858321,3.000525886,90.00000001 +58.16,50.425,-2.587648931,48.5958,0,10.00068325,1.093125,5.012292775,2.950148744,90.00000001 +58.17,50.425,-2.587647524,48.5852,0,9.999572882,1.0315625,4.937680435,2.897198964,90.00000001 +58.18,50.425,-2.587646117,48.5752,0,9.998684588,0.9703125,4.862036942,2.841722841,90.00000001 +58.19,50.425,-2.58764471,48.5658,0,9.998684573,0.91,4.785378112,2.783768733,90.00000001 +58.2,50.425,-2.587643303,48.557,0,9.999572839,0.8496875,4.70771987,2.72338706,90.00000001 +58.21,50.425,-2.587641896,48.5488,0,10.00068317,0.788125,4.629078491,2.660630591,90.00000001 +58.22,50.425,-2.587640488,48.5412,0,10.00068316,0.725,4.549470417,2.595553988,90.00000001 +58.23,50.425,-2.587639081,48.5343,0,9.999794872,0.6615625,4.468912207,2.528214086,90.00000001 +58.24,50.425,-2.587637674,48.528,0,9.999794862,0.5984375,4.387420764,2.4586695,90.00000001 +58.25,50.425,-2.587636267,48.5223,0,10.00068313,0.5346875,4.305012989,2.386980906,90.00000001 +58.26,50.425,-2.587634859,48.5173,0,10.00068312,0.47,4.221706243,2.313210814,90.00000001 +58.27,50.425,-2.587633452,48.5129,0,9.99979484,0.4053125,4.13751783,2.237423624,90.00000001 +58.28,50.425,-2.587632045,48.5092,0,9.999794834,0.3415625,4.05246534,2.159685341,90.00000001 +58.29,50.425,-2.587630638,48.5061,0,10.00068311,0.2784375,3.966566533,2.080063745,90.00000001 +58.3,50.425,-2.58762923,48.5036,0,10.0006831,0.215,3.879839401,1.998628337,90.00000001 +58.31,50.425,-2.587627823,48.5018,0,9.999572752,0.1515625,3.792301935,1.915450106,90.00000001 +58.32,50.425,-2.587626416,48.5006,0,9.998906542,0.088125,3.703972584,1.830601531,90.00000001 +58.33,50.425,-2.587625009,48.5,0,9.999572749,0.023125,3.614869683,1.744156695,90.00000001 +58.34,50.425,-2.587623602,48.5001,0,10.0006831,-0.043125,3.525011795,1.656190886,90.00000001 +58.35,50.425,-2.587622194,48.5009,0,10.0006831,-0.108125,3.434417829,1.566780879,90.00000001 +58.36,50.425,-2.587620787,48.5023,0,9.999572753,-0.1715625,3.343106634,1.476004655,90.00000001 +58.37,50.425,-2.58761938,48.5043,0,9.998906547,-0.2353125,3.251097232,1.383941281,90.00000001 +58.38,50.425,-2.587617973,48.507,0,9.99957276,-0.3,3.158408875,1.290671085,90.00000001 +58.39,50.425,-2.587616566,48.5103,0,10.00068311,-0.365,3.06506093,1.196275429,90.00000001 +58.4,50.425,-2.587615158,48.5143,0,10.00068312,-0.4296875,2.971072933,1.100836589,90.00000001 +58.41,50.425,-2.587613751,48.5189,0,9.999794848,-0.493125,2.876464423,1.004437815,90.00000001 +58.42,50.425,-2.587612344,48.5242,0,9.999794857,-0.5553125,2.781255224,0.90716316,90.00000001 +58.43,50.425,-2.587610937,48.53,0,10.00068314,-0.618125,2.685465161,0.809097423,90.00000001 +58.44,50.425,-2.587609529,48.5365,0,10.00068315,-0.681875,2.589114286,0.710326145,90.00000001 +58.45,50.425,-2.587608122,48.5437,0,9.999794887,-0.7446875,2.492222711,0.610935443,90.00000001 +58.46,50.425,-2.587606715,48.5514,0,9.999794899,-0.8065625,2.394810661,0.511012005,90.00000001 +58.47,50.425,-2.587605308,48.5598,0,10.00068319,-0.86875,2.296898534,0.410642977,90.00000001 +58.48,50.425,-2.5876039,48.5688,0,10.00068321,-0.93125,2.198506669,0.309915851,90.00000001 +58.49,50.425,-2.587602493,48.5784,0,9.999572872,-0.9934375,2.099655693,0.20891846,90.00000001 +58.5,50.425,-2.587601086,48.5887,0,9.998684609,-1.0546875,2.000366232,0.107738927,90.00000001 +58.51,50.425,-2.587599679,48.5995,0,9.998684626,-1.1146875,1.900659028,0.00646537,90.00000001 +58.52,50.425,-2.587598272,48.611,0,9.999572923,-1.1734375,1.800554879,-0.094813743,90.00000001 +58.53,50.425,-2.587596865,48.623,0,10.00068329,-1.2315625,1.700074697,-0.196010237,90.00000001 +58.54,50.425,-2.587595457,48.6356,0,10.00068331,-1.2903125,1.599239511,-0.29703576,90.00000001 +58.55,50.425,-2.58759405,48.6488,0,9.999572982,-1.3496875,1.498070348,-0.397802305,90.00000001 +58.56,50.425,-2.587592643,48.6626,0,9.998906794,-1.408125,1.396588293,-0.498221925,90.00000001 +58.57,50.425,-2.587591236,48.677,0,9.999573025,-1.465,1.294814602,-0.598207128,90.00000001 +58.58,50.425,-2.587589829,48.6919,0,10.0006834,-1.5215625,1.192770532,-0.697670654,90.00000001 +58.59,50.425,-2.587588421,48.7074,0,10.00090549,-1.5784375,1.090477283,-0.796525812,90.00000001 +58.6,50.425,-2.587587014,48.7235,0,10.00068345,-1.634375,0.987956397,-0.894686374,90.00000001 +58.61,50.425,-2.587585607,48.7401,0,10.00090554,-1.6884375,0.885229133,-0.992066739,90.00000001 +58.62,50.425,-2.587584199,48.7573,0,10.0006835,-1.7415625,0.782317032,-1.088582053,90.00000001 +58.63,50.425,-2.587582792,48.7749,0,9.999573179,-1.7946875,0.679241523,-1.18414809,90.00000001 +58.64,50.425,-2.587581385,48.7932,0,9.998906999,-1.846875,0.576024151,-1.278681542,90.00000001 +58.65,50.425,-2.587579978,48.8119,0,9.999573237,-1.8978125,0.472686514,-1.372099962,90.00000001 +58.66,50.425,-2.587578571,48.8311,0,10.00068361,-1.9484375,0.369250157,-1.464321873,90.00000001 +58.67,50.425,-2.587577163,48.8509,0,10.00068365,-1.998125,0.265736737,-1.555266891,90.00000001 +58.68,50.425,-2.587575756,48.8711,0,9.99957333,-2.0465625,0.16216774,-1.644855661,90.00000001 +58.69,50.425,-2.587574349,48.8918,0,9.998907153,-2.095,0.058564938,-1.733010145,90.00000001 +58.7,50.425,-2.587572942,48.913,0,9.999573395,-2.143125,-0.045050124,-1.819653338,90.00000001 +58.71,50.425,-2.587571535,48.9347,0,10.00068378,-2.1896875,-0.148655791,-1.90470984,90.00000001 +58.72,50.425,-2.587570127,48.9568,0,10.00068381,-2.2346875,-0.252230403,-1.988105394,90.00000001 +58.73,50.425,-2.58756872,48.9794,0,9.999573499,-2.2784375,-0.35575236,-2.069767292,90.00000001 +58.74,50.425,-2.587567313,49.0024,0,9.998685257,-2.3215625,-0.459199947,-2.149624316,90.00000001 +58.75,50.425,-2.587565906,49.0258,0,9.998685294,-2.3646875,-0.562551736,-2.227606794,90.00000001 +58.76,50.425,-2.587564499,49.0497,0,9.999573609,-2.4065625,-0.665785953,-2.303646831,90.00000001 +58.77,50.425,-2.587563092,49.074,0,10.00090606,-2.44625,-0.768881172,-2.37767802,90.00000001 +58.78,50.425,-2.587561684,49.0986,0,10.00179438,-2.485,-0.871815847,-2.449635847,90.00000001 +58.79,50.425,-2.587560277,49.1237,0,10.00179442,-2.523125,-0.974568436,-2.519457515,90.00000001 +58.8,50.425,-2.587558869,49.1491,0,10.00090618,-2.5596875,-1.077117454,-2.587082234,90.00000001 +58.81,50.425,-2.587557462,49.1749,0,9.999573805,-2.5953125,-1.179441585,-2.652450989,90.00000001 +58.82,50.425,-2.587556055,49.201,0,9.998907637,-2.63125,-1.281519402,-2.715506713,90.00000001 +58.83,50.425,-2.587554648,49.2275,0,9.999573887,-2.6665625,-1.383329534,-2.776194517,90.00000001 +58.84,50.425,-2.587553241,49.2544,0,10.00068428,-2.699375,-1.484850837,-2.834461403,90.00000001 +58.85,50.425,-2.587551833,49.2815,0,10.00068432,-2.7296875,-1.586061998,-2.890256606,90.00000001 +58.86,50.425,-2.587550426,49.309,0,9.999574015,-2.75875,-1.686941989,-2.943531482,90.00000001 +58.87,50.425,-2.587549019,49.3367,0,9.998685779,-2.7878125,-1.787469669,-2.994239565,90.00000001 +58.88,50.425,-2.587547612,49.3647,0,9.998685823,-2.8165625,-1.887624009,-3.042336564,90.00000001 +58.89,50.425,-2.587546205,49.3931,0,9.999574146,-2.843125,-1.987384212,-3.087780654,90.00000001 +58.9,50.425,-2.587544798,49.4216,0,10.00068454,-2.868125,-2.086729307,-3.13053213,90.00000001 +58.91,50.425,-2.58754339,49.4504,0,10.00068458,-2.8934375,-2.185638667,-3.170553747,90.00000001 +58.92,50.425,-2.587541983,49.4795,0,9.999574282,-2.9178125,-2.284091552,-3.207810614,90.00000001 +58.93,50.425,-2.587540576,49.5088,0,9.998908118,-2.939375,-2.38206745,-3.242270187,90.00000001 +58.94,50.425,-2.587539169,49.5383,0,9.999574373,-2.9584375,-2.479545905,-3.273902499,90.00000001 +58.95,50.425,-2.587537762,49.568,0,10.00090684,-2.9765625,-2.576506464,-3.302679877,90.00000001 +58.96,50.425,-2.587536354,49.5978,0,10.00179516,-2.9946875,-2.672929016,-3.328577283,90.00000001 +58.97,50.425,-2.587534947,49.6279,0,10.00179521,-3.0115625,-2.768793335,-3.351572085,90.00000001 +58.98,50.425,-2.587533539,49.6581,0,10.00090698,-3.02625,-2.864079482,-3.371644286,90.00000001 +58.99,50.425,-2.587532132,49.6884,0,9.999574607,-3.0403125,-2.958767461,-3.388776412,90.00000001 +59,50.425,-2.587530725,49.7189,0,9.998686377,-3.0546875,-3.052837506,-3.40295345,90.00000001 +59.01,50.425,-2.587529318,49.7495,0,9.998686425,-3.0678125,-3.146270077,-3.414163026,90.00000001 +59.02,50.425,-2.587527911,49.7803,0,9.999574752,-3.0778125,-3.239045523,-3.422395398,90.00000001 +59.03,50.425,-2.587526504,49.8111,0,10.00068515,-3.0846875,-3.331144593,-3.427643462,90.00000001 +59.04,50.425,-2.587525096,49.842,0,10.0006852,-3.0903125,-3.422547919,-3.42990252,90.00000001 +59.05,50.425,-2.587523689,49.8729,0,9.999574896,-3.0965625,-3.513236539,-3.429170624,90.00000001 +59.06,50.425,-2.587522282,49.9039,0,9.998908736,-3.103125,-3.603191485,-3.425448518,90.00000001 +59.07,50.425,-2.587520875,49.935,0,9.999574994,-3.1078125,-3.692393909,-3.418739297,90.00000001 +59.08,50.425,-2.587519468,49.9661,0,10.00068539,-3.1096875,-3.780825247,-3.409048919,90.00000001 +59.09,50.425,-2.58751806,49.9972,0,10.00068544,-3.1096875,-3.868466991,-3.396385807,90.00000001 +59.1,50.425,-2.587516653,50.0283,0,9.999575139,-3.108125,-3.955300865,-3.380760961,90.00000001 +59.11,50.425,-2.587515246,50.0594,0,9.998686909,-3.105,-4.041308763,-3.362188076,90.00000001 +59.12,50.425,-2.587513839,50.0904,0,9.998686958,-3.1015625,-4.126472636,-3.340683309,90.00000001 +59.13,50.425,-2.587512432,50.1214,0,9.999575286,-3.0984375,-4.210774782,-3.316265394,90.00000001 +59.14,50.425,-2.587511025,50.1524,0,10.00090775,-3.094375,-4.294197551,-3.288955647,90.00000001 +59.15,50.425,-2.587509617,50.1833,0,10.00179608,-3.0878125,-4.376723527,-3.258777903,90.00000001 +59.16,50.425,-2.58750821,50.2142,0,10.00179613,-3.078125,-4.458335464,-3.22575846,90.00000001 +59.17,50.425,-2.587506802,50.2449,0,10.0009079,-3.0665625,-4.539016344,-3.189926081,90.00000001 +59.18,50.425,-2.587505395,50.2755,0,9.999575527,-3.055,-4.618749322,-3.151312048,90.00000001 +59.19,50.425,-2.587503988,50.306,0,9.998909365,-3.043125,-4.697517727,-3.109950053,90.00000001 +59.2,50.425,-2.587502581,50.3364,0,9.999575622,-3.0296875,-4.775305112,-3.065876077,90.00000001 +59.21,50.425,-2.587501174,50.3666,0,10.00068602,-3.0146875,-4.852095208,-3.01912868,90.00000001 +59.22,50.425,-2.587499766,50.3967,0,10.00068606,-2.9984375,-4.927872028,-2.969748484,90.00000001 +59.23,50.425,-2.587498359,50.4266,0,9.999575763,-2.98125,-5.002619758,-2.917778691,90.00000001 +59.24,50.425,-2.587496952,50.4563,0,9.998687531,-2.963125,-5.076322699,-2.863264507,90.00000001 +59.25,50.425,-2.587495545,50.4859,0,9.998687577,-2.943125,-5.148965555,-2.806253545,90.00000001 +59.26,50.425,-2.587494138,50.5152,0,9.999575901,-2.92125,-5.220533083,-2.74679548,90.00000001 +59.27,50.425,-2.587492731,50.5443,0,10.00068629,-2.898125,-5.291010386,-2.684942165,90.00000001 +59.28,50.425,-2.587491323,50.5732,0,10.00068634,-2.873125,-5.360382741,-2.620747515,90.00000001 +59.29,50.425,-2.587489916,50.6018,0,9.999576037,-2.8465625,-5.428635651,-2.554267566,90.00000001 +59.3,50.425,-2.587488509,50.6301,0,9.998909872,-2.82,-5.495754849,-2.485560243,90.00000001 +59.31,50.425,-2.587487102,50.6582,0,9.999576125,-2.793125,-5.561726356,-2.414685479,90.00000001 +59.32,50.425,-2.587485695,50.686,0,10.00068652,-2.7646875,-5.626536305,-2.341705094,90.00000001 +59.33,50.425,-2.587484287,50.7135,0,10.00090863,-2.735,-5.690171289,-2.266682688,90.00000001 +59.34,50.425,-2.58748288,50.7407,0,10.0006866,-2.7046875,-5.752617902,-2.189683692,90.00000001 +59.35,50.425,-2.587481473,50.7676,0,10.00090871,-2.6728125,-5.813863194,-2.110775257,90.00000001 +59.36,50.425,-2.587480065,50.7942,0,10.00068669,-2.638125,-5.873894332,-2.030026195,90.00000001 +59.37,50.425,-2.587478658,50.8204,0,9.999576378,-2.601875,-5.932698766,-1.947506922,90.00000001 +59.38,50.425,-2.587477251,50.8462,0,9.99891021,-2.5665625,-5.990264237,-1.863289403,90.00000001 +59.39,50.425,-2.587475844,50.8717,0,9.99957646,-2.53125,-6.046578712,-1.77744709,90.00000001 +59.4,50.425,-2.587474437,50.8969,0,10.00068685,-2.493125,-6.101630445,-1.690054754,90.00000001 +59.41,50.425,-2.587473029,50.9216,0,10.00068689,-2.453125,-6.15540792,-1.601188714,90.00000001 +59.42,50.425,-2.587471622,50.9459,0,9.999576574,-2.4134375,-6.207899906,-1.510926432,90.00000001 +59.43,50.425,-2.587470215,50.9699,0,9.998688333,-2.3728125,-6.259095462,-1.419346577,90.00000001 +59.44,50.425,-2.587468808,50.9934,0,9.99868837,-2.3296875,-6.308983928,-1.326529019,90.00000001 +59.45,50.425,-2.587467401,51.0165,0,9.999576686,-2.2853125,-6.357554821,-1.232554716,90.00000001 +59.46,50.425,-2.587465994,51.0391,0,10.00068707,-2.2415625,-6.404797999,-1.137505601,90.00000001 +59.47,50.425,-2.587464586,51.0613,0,10.0006871,-2.198125,-6.450703606,-1.041464582,90.00000001 +59.48,50.425,-2.587463179,51.0831,0,9.999576789,-2.1528125,-6.495262076,-0.944515368,90.00000001 +59.49,50.425,-2.587461772,51.1044,0,9.998910613,-2.1046875,-6.538464125,-0.846742526,90.00000001 +59.5,50.425,-2.587460365,51.1252,0,9.999576855,-2.0553125,-6.580300643,-0.748231314,90.00000001 +59.51,50.425,-2.587458958,51.1455,0,10.00090931,-2.0065625,-6.62076298,-0.649067618,90.00000001 +59.52,50.425,-2.58745755,51.1653,0,10.00179762,-1.958125,-6.659842713,-0.549337954,90.00000001 +59.53,50.425,-2.587456143,51.1847,0,10.00179765,-1.908125,-6.697531533,-0.44912924,90.00000001 +59.54,50.425,-2.587454735,51.2035,0,10.0009094,-1.85625,-6.733821705,-0.348528909,90.00000001 +59.55,50.425,-2.587453328,51.2218,0,9.999577006,-1.8034375,-6.76870561,-0.247624624,90.00000001 +59.56,50.425,-2.587451921,51.2396,0,9.998688756,-1.75,-6.802175914,-0.146504449,90.00000001 +59.57,50.425,-2.587450514,51.2568,0,9.998688782,-1.6965625,-6.834225741,-0.045256447,90.00000001 +59.58,50.425,-2.587449107,51.2735,0,9.999577087,-1.643125,-6.864848272,0.056030975,90.00000001 +59.59,50.425,-2.5874477,51.2897,0,10.00068746,-1.588125,-6.894037149,0.157269524,90.00000001 +59.6,50.425,-2.587446292,51.3053,0,10.00068749,-1.5315625,-6.921786354,0.258370963,90.00000001 +59.61,50.425,-2.587444885,51.3203,0,9.999577161,-1.475,-6.948089987,0.359247059,90.00000001 +59.62,50.425,-2.587443478,51.3348,0,9.998910974,-1.4184375,-6.972942662,0.459809918,90.00000001 +59.63,50.425,-2.587442071,51.3487,0,9.999577205,-1.36125,-6.99633905,0.559971821,90.00000001 +59.64,50.425,-2.587440664,51.362,0,10.00068757,-1.303125,-7.018274395,0.659645393,90.00000001 +59.65,50.425,-2.587439256,51.3748,0,10.00068759,-1.2434375,-7.038744057,0.758743772,90.00000001 +59.66,50.425,-2.587437849,51.3869,0,9.999577265,-1.183125,-7.057743739,0.857180499,90.00000001 +59.67,50.425,-2.587436442,51.3984,0,9.998689004,-1.12375,-7.075269486,0.954869746,90.00000001 +59.68,50.425,-2.587435035,51.4094,0,9.998689021,-1.0646875,-7.09131769,1.051726313,90.00000001 +59.69,50.425,-2.587433628,51.4197,0,9.999577316,-1.0046875,-7.10588497,1.147665804,90.00000001 +59.7,50.425,-2.587432221,51.4295,0,10.00090975,-0.9434375,-7.11896829,1.24260451,90.00000001 +59.71,50.425,-2.587430813,51.4386,0,10.00179804,-0.88125,-7.130564841,1.336459638,90.00000001 +59.72,50.425,-2.587429406,51.4471,0,10.00179806,-0.8184375,-7.140672332,1.429149369,90.00000001 +59.73,50.425,-2.587427998,51.455,0,10.00090979,-0.755,-7.149288529,1.520592803,90.00000001 +59.74,50.425,-2.587426591,51.4622,0,9.999577382,-0.691875,-7.156411769,1.610710298,90.00000001 +59.75,50.425,-2.587425184,51.4688,0,9.998911183,-0.63,-7.162040392,1.699423244,90.00000001 +59.76,50.425,-2.587423777,51.4748,0,9.999577402,-0.568125,-7.166173366,1.786654235,90.00000001 +59.77,50.425,-2.58742237,51.4802,0,10.00068776,-0.5046875,-7.168809774,1.872327239,90.00000001 +59.78,50.425,-2.587420962,51.4849,0,10.00068777,-0.44,-7.169949043,1.9563676,90.00000001 +59.79,50.425,-2.587419555,51.489,0,9.999577425,-0.3753125,-7.169591002,2.038701922,90.00000001 +59.8,50.425,-2.587418148,51.4924,0,9.998689151,-0.3115625,-7.16773565,2.11925847,90.00000001 +59.81,50.425,-2.587416741,51.4952,0,9.998689155,-0.2484375,-7.164383388,2.197967,90.00000001 +59.82,50.425,-2.587415334,51.4974,0,9.999577437,-0.1846875,-7.159534962,2.274758872,90.00000001 +59.83,50.425,-2.587413927,51.4989,0,10.00068779,-0.12,-7.153191403,2.349567106,90.00000001 +59.84,50.425,-2.587412519,51.4998,0,10.00068779,-0.055,-7.145353913,2.422326501,90.00000001 +59.85,50.425,-2.587411112,51.5,0,9.999577442,0.01,-7.136024269,2.492973629,90.00000001 +59.86,50.425,-2.587409705,51.4996,0,9.998911231,0.075,-7.125204305,2.561446784,90.00000001 +59.87,50.425,-2.587408298,51.4985,0,9.999577439,0.1396875,-7.112896369,2.627686378,90.00000001 +59.88,50.425,-2.587406891,51.4968,0,10.00090986,0.2034375,-7.099102983,2.691634541,90.00000001 +59.89,50.425,-2.587405483,51.4944,0,10.00179813,0.266875,-7.083827069,2.753235583,90.00000001 +59.9,50.425,-2.587404076,51.4915,0,10.00179813,0.3315625,-7.067071721,2.812435759,90.00000001 +59.91,50.425,-2.587402668,51.4878,0,10.00090984,0.3965625,-7.048840547,2.869183447,90.00000001 +59.92,50.425,-2.587401261,51.4835,0,9.999577416,0.4596875,-7.029137331,2.923429143,90.00000001 +59.93,50.425,-2.587399854,51.4786,0,9.998689129,0.521875,-7.007966139,2.975125578,90.00000001 +59.94,50.425,-2.587398447,51.4731,0,9.998689121,0.5853125,-6.985331442,3.02422766,90.00000001 +59.95,50.425,-2.58739704,51.4669,0,9.99957739,0.6496875,-6.961237936,3.070692589,90.00000001 +59.96,50.425,-2.587395633,51.4601,0,10.00068773,0.713125,-6.935690722,3.1144798,90.00000001 +59.97,50.425,-2.587394225,51.4526,0,10.00068772,0.775,-6.908695013,3.155551134,90.00000001 +59.98,50.425,-2.587392818,51.4446,0,9.999577355,0.8365625,-6.88025654,3.193870838,90.00000001 +59.99,50.425,-2.587391411,51.4359,0,9.998911132,0.89875,-6.850381202,3.229405394,90.00000001 +60,50.425,-2.587390004,51.4266,0,9.999577327,0.96125,-6.819075247,3.262123862,90.00000001 +60.01,50.425,-2.587388597,51.4167,0,10.00068766,1.023125,-6.785531376,3.29199771,89.99998746 +60.02,50.425,-2.587387189,51.4061,0,10.00068764,1.083125,-6.745687489,3.319000867,89.99989969 +60.03,50.425,-2.587385782,51.395,0,9.999577277,1.141875,-6.69466789,3.343109842,89.99966139 +60.04,50.425,-2.587384375,51.3833,0,9.99891105,1.201875,-6.627597106,3.364303551,89.9991973 +60.05,50.425,-2.587382968,51.371,0,9.99957724,1.2628125,-6.539600185,3.382563544,89.99843228 +60.06,50.425,-2.587381561,51.358,0,10.00068757,1.3215625,-6.425802173,3.397873893,89.99729095 +60.07,50.425,-2.587380153,51.3445,0,10.00090962,1.378125,-6.281328688,3.410221305,89.99569819 +60.08,50.425,-2.587378746,51.3305,0,10.00068752,1.4353125,-6.101305406,3.419594895,89.99357859 +60.09,50.425,-2.587377339,51.3158,0,10.00090957,1.493125,-5.882486063,3.425986526,89.99085704 +60.1,50.425,-2.587375931,51.3006,0,10.00068748,1.5496875,-5.628134972,3.429390697,89.98745819 +60.11,50.425,-2.587374524,51.2848,0,9.999577105,1.605,-5.343144446,3.429804315,89.98333192 +60.12,50.425,-2.587373117,51.2685,0,9.99891087,1.6596875,-5.032406917,3.427227151,89.97852842 +60.13,50.425,-2.58737171,51.2516,0,9.999577053,1.7134375,-4.700815328,3.421661382,89.97312291 +60.14,50.425,-2.587370303,51.2342,0,10.00068737,1.76625,-4.353262682,3.413111877,89.96719061 +60.15,50.425,-2.587368895,51.2163,0,10.00068735,1.8184375,-3.994642324,3.401586087,89.96080683 +60.16,50.425,-2.587367488,51.1978,0.003476192,9.999576969,1.87,-3.629847946,3.387094036,89.95404685 +60.17,50.425,-2.587366081,51.1789,0.017380961,9.99868866,1.9215625,-3.263773408,3.369648445,89.94698577 +60.18,50.425,-2.587364674,51.1594,0.034761922,9.998688629,1.973125,-2.901312915,3.34926444,89.93969901 +60.19,50.42500001,-2.587363267,51.1394,0.034761922,9.999576876,2.023125,-2.547360903,3.32595984,89.93226173 +60.2,50.42500001,-2.58736186,51.1189,0.017380961,10.00068719,2.0715625,-2.206812036,3.299754928,89.92474917 +60.21,50.42500001,-2.587360452,51.098,0.003476192,10.00068716,2.1196875,-1.884561321,3.270672564,89.91722405 +60.22,50.42500001,-2.587359045,51.0765,1.41E-13,9.999798847,2.1665625,-1.585503937,3.238738189,89.909699 +60.23,50.42500001,-2.587357638,51.0546,0.003476192,9.999798812,2.21125,-1.31453535,3.203979532,89.90217389 +60.24,50.42500001,-2.587356231,51.0323,0.01738096,10.00068706,2.255,-1.076551314,3.166426961,89.89464883 +60.25,50.42500001,-2.587354823,51.0095,0.034761921,10.00068702,2.2984375,-0.874820151,3.12611325,89.88712377 +60.26,50.42500002,-2.587353416,50.9863,0.034761921,9.999798705,2.3415625,-0.706100066,3.08307352,89.87959866 +60.27,50.42500002,-2.587352009,50.9627,0.01738096,9.999798667,2.3846875,-0.565521949,3.037345242,89.8720736 +60.28,50.42500002,-2.587350602,50.9386,0.006952384,10.00068691,2.4265625,-0.448216862,2.98896841,89.86454849 +60.29,50.42500002,-2.587349194,50.9141,0.01738096,10.00068687,2.46625,-0.349316096,2.937985136,89.85702344 +60.3,50.42500002,-2.587347787,50.8893,0.03476192,9.999576482,2.5046875,-0.263951228,2.884439938,89.84949832 +60.31,50.42500003,-2.58734638,50.864,0.038238112,9.998910233,2.5415625,-0.187254067,2.828379399,89.84197327 +60.32,50.42500003,-2.587344973,50.8384,0.03476192,9.999576401,2.5765625,-0.114356532,2.769852505,89.83444815 +60.33,50.42500003,-2.587343566,50.8125,0.038238112,10.00068671,2.611875,-0.041204775,2.70891025,89.8269231 +60.34,50.42500004,-2.587342158,50.7862,0.03476192,10.00068667,2.648125,0.032999791,2.645605805,89.81939799 +60.35,50.42500004,-2.587340751,50.7595,0.020857152,9.999576275,2.6828125,0.10824164,2.579994345,89.81187293 +60.36,50.42500004,-2.587339344,50.7325,0.020857152,9.998910023,2.7146875,0.184505072,2.512133052,89.80434782 +60.37,50.42500004,-2.587337937,50.7052,0.034761919,9.999576189,2.7446875,0.261774161,2.442081169,89.79682276 +60.38,50.42500005,-2.58733653,50.6776,0.038238111,10.00068649,2.7734375,0.340032747,2.369899774,89.78929765 +60.39,50.42500005,-2.587335122,50.6497,0.034761919,10.00068645,2.8015625,0.419264559,2.295651778,89.78177259 +60.4,50.42500005,-2.587333715,50.6216,0.041714302,9.999576056,2.8296875,0.499452925,2.219401924,89.77424748 +60.41,50.42500006,-2.587332308,50.5931,0.052142878,9.998687732,2.8565625,0.580581228,2.141216734,89.76672242 +60.42,50.42500006,-2.587330901,50.5644,0.052142878,9.998687686,2.88125,0.662632451,2.061164388,89.75919731 +60.43,50.42500007,-2.587329494,50.5355,0.0417143,9.999575919,2.9046875,0.745589463,1.979314674,89.75167225 +60.44,50.42500007,-2.587328087,50.5063,0.034761907,10.00068622,2.9265625,0.829435018,1.895738925,89.74414714 +60.45,50.42500007,-2.587326679,50.4769,0.041714279,10.00068617,2.9465625,0.914151469,1.810510078,89.73662208 +60.46,50.42500008,-2.587325272,50.4474,0.052142855,9.999575778,2.9665625,0.999721226,1.723702503,89.72909697 +60.47,50.42500008,-2.587323865,50.4176,0.055619057,9.998909522,2.9865625,1.086126413,1.635391773,89.72157192 +60.48,50.42500009,-2.587322458,50.3876,0.055619066,9.999575683,3.004375,1.173348924,1.545654951,89.7140468 +60.49,50.42500009,-2.587321051,50.3575,0.052142876,10.00068598,3.02,1.261370597,1.454570304,89.70652175 +60.5,50.4250001,-2.587319643,50.3272,0.041714301,10.000908,3.0346875,1.350173039,1.362217242,89.69899663 +60.51,50.4250001,-2.587318236,50.2968,0.038238109,10.00068589,3.048125,1.439737687,1.268676324,89.69147158 +60.52,50.4250001,-2.587316829,50.2662,0.055619067,10.00090791,3.0596875,1.530045862,1.17402914,89.68394647 +60.53,50.42500011,-2.587315421,50.2356,0.073000025,10.00068579,3.07,1.621078714,1.078358137,89.67642141 +60.54,50.42500012,-2.587314014,50.2048,0.069523833,9.999575392,3.0796875,1.712817164,0.981746795,89.6688963 +60.55,50.42500012,-2.587312607,50.174,0.059095258,9.998909133,3.088125,1.805242132,0.884279341,89.66137124 +60.56,50.42500013,-2.5873112,50.143,0.055619066,9.999575292,3.095,1.898334309,0.786040799,89.65384613 +60.57,50.42500013,-2.587309793,50.1121,0.055619066,10.00068559,3.10125,1.992074158,0.687116828,89.64632107 +60.58,50.42500014,-2.587308385,50.081,0.055619065,10.00068554,3.1065625,2.086442255,0.587593658,89.63879596 +60.59,50.42500014,-2.587306978,50.0499,0.055619065,9.999575144,3.1090625,2.181418718,0.487558092,89.6312709 +60.6,50.42500015,-2.587305571,50.0188,0.059095252,9.998908885,3.1084375,2.276983896,0.387097391,89.62374585 +60.61,50.42500015,-2.587304164,49.9877,0.069523808,9.999575044,3.106875,2.373117677,0.286299161,89.61622073 +60.62,50.42500016,-2.587302757,49.9567,0.076476169,10.00068534,3.1065625,2.469800065,0.185251235,89.60869568 +60.63,50.42500017,-2.587301349,49.9256,0.072999977,10.00068529,3.10625,2.567010892,0.084041736,89.60117056 +60.64,50.42500017,-2.587299942,49.8945,0.072999999,9.999574894,3.1028125,2.664729761,-0.017240988,89.59364551 +60.65,50.42500018,-2.587298535,49.8635,0.076476208,9.998686566,3.0965625,2.762936388,-0.1185087,89.5861204 +60.66,50.42500019,-2.587297128,49.8326,0.07300002,9.998686516,3.09,2.861610149,-0.21967305,89.57859534 +60.67,50.42500019,-2.587295721,49.8017,0.07300002,9.999574744,3.0828125,2.960730472,-0.320645861,89.57107023 +60.68,50.4250002,-2.587294314,49.7709,0.076476211,10.00046297,3.073125,3.060276675,-0.421339068,89.56354517 +60.69,50.42500021,-2.587292906,49.7402,0.073000019,9.999796715,3.0615625,3.160228016,-0.521664894,89.55602006 +60.7,50.42500021,-2.587291499,49.7097,0.07647621,9.998464248,3.0496875,3.260563526,-0.621535793,89.548495 +60.71,50.42500022,-2.587290093,49.6792,0.090380975,9.998686269,3.0365625,3.361262291,-0.720864673,89.54096989 +60.72,50.42500023,-2.587288685,49.6489,0.090380973,9.999574498,3.0215625,3.462303284,-0.819564961,89.53344483 +60.73,50.42500024,-2.587287278,49.6188,0.076476198,9.999352379,3.0065625,3.563665419,-0.917550599,89.52591972 +60.74,50.42500024,-2.587285871,49.5888,0.076476187,9.998908191,2.99125,3.665327555,-1.014736101,89.51839466 +60.75,50.42500025,-2.587284464,49.5589,0.090380951,9.999574353,2.9728125,3.767268378,-1.111036727,89.51086955 +60.76,50.42500026,-2.587283057,49.5293,0.090380962,10.00068465,2.9515625,3.869466631,-1.206368539,89.5033445 +60.77,50.42500027,-2.587281649,49.4999,0.076476206,10.00068461,2.9303125,3.971900999,-1.300648401,89.49581938 +60.78,50.42500027,-2.587280242,49.4707,0.076476207,9.999574209,2.9096875,4.074550055,-1.393794035,89.48829433 +60.79,50.42500028,-2.587278835,49.4417,0.093857163,9.998685884,2.8878125,4.17739237,-1.485724253,89.48076921 +60.8,50.42500029,-2.587277428,49.4129,0.107761928,9.998685838,2.8628125,4.280406514,-1.5763589,89.47324416 +60.81,50.4250003,-2.587276021,49.3844,0.107761927,9.99957407,2.835,4.383570889,-1.665618964,89.46571905 +60.82,50.42500031,-2.587274614,49.3562,0.093857162,10.00068437,2.806875,4.486864064,-1.753426579,89.45819399 +60.83,50.42500032,-2.587273206,49.3283,0.076476204,10.00068433,2.7796875,4.590264325,-1.8397052,89.45066888 +60.84,50.42500032,-2.587271799,49.3006,0.076476194,9.999573933,2.75125,4.693750185,-1.924379538,89.44314382 +60.85,50.42500033,-2.587270392,49.2732,0.093857138,9.998907679,2.7196875,4.797300045,-2.007375798,89.43561871 +60.86,50.42500034,-2.587268985,49.2462,0.107761903,9.999573845,2.686875,4.90089219,-2.088621557,89.42809365 +60.87,50.42500035,-2.587267578,49.2195,0.111238104,10.00068415,2.6546875,5.004505018,-2.168046055,89.42056854 +60.88,50.42500036,-2.58726617,49.1931,0.111238111,10.00068411,2.6215625,5.10811693,-2.245579965,89.41304348 +60.89,50.42500037,-2.587264763,49.167,0.111238104,9.999573715,2.58625,5.211706267,-2.321155733,89.40551837 +60.9,50.42500038,-2.587263356,49.1414,0.111238092,9.998685393,2.5496875,5.315251429,-2.394707414,89.39799331 +60.91,50.42500039,-2.587261949,49.116,0.111238092,9.998463282,2.511875,5.4187307,-2.466170836,89.3904682 +60.92,50.4250004,-2.587260542,49.0911,0.1112381,9.998463241,2.4728125,5.522122539,-2.535483717,89.38294314 +60.93,50.42500041,-2.587259135,49.0666,0.1112381,9.998463201,2.4334375,5.625405343,-2.60258567,89.37541803 +60.94,50.42500042,-2.587257728,49.0424,0.11123809,9.998685231,2.393125,5.728557513,-2.667418079,89.36789298 +60.95,50.42500043,-2.587256321,49.0187,0.11123809,9.99957347,2.35125,5.831557563,-2.729924451,89.36036792 +60.96,50.42500044,-2.587254914,48.9954,0.111238101,10.00068378,2.3084375,5.93438395,-2.790050356,89.35284281 +60.97,50.42500045,-2.587253506,48.9725,0.111238109,10.00068374,2.265,6.037015187,-2.847743252,89.34531775 +60.98,50.42500046,-2.587252099,48.9501,0.111238111,9.999573356,2.22125,6.139429846,-2.902952835,89.33779264 +60.99,50.42500047,-2.587250692,48.9281,0.11123811,9.998685042,2.1765625,6.241606612,-2.955631033,89.33026758 +61,50.42500048,-2.587249285,48.9065,0.111238108,9.998462936,2.1296875,6.343524001,-3.005731895,89.32274247 +61.01,50.42500049,-2.587247878,48.8855,0.111238099,9.998462901,2.0815625,6.44516087,-3.053211704,89.31521741 +61.02,50.4250005,-2.587246471,48.8649,0.111238087,9.998684935,2.033125,6.546495904,-3.098029093,89.3076923 +61.03,50.42500051,-2.587245064,48.8448,0.111238087,9.999573181,1.983125,6.64750802,-3.140144929,89.30016724 +61.04,50.42500052,-2.587243657,48.8252,0.114714288,10.0006835,1.931875,6.748176017,-3.179522485,89.29264213 +61.05,50.42500053,-2.587242249,48.8062,0.12861906,10.00068346,1.8815625,6.848478983,-3.216127498,89.28511708 +61.06,50.42500054,-2.587240842,48.7876,0.146000017,9.999573085,1.8315625,6.948395889,-3.249927997,89.27759196 +61.07,50.42500056,-2.587239435,48.7695,0.146000016,9.998684775,1.779375,7.047905881,-3.280894475,89.27006691 +61.08,50.42500057,-2.587238028,48.752,0.128619057,9.998462675,1.725,7.146988218,-3.308999946,89.26254179 +61.09,50.42500058,-2.587236621,48.735,0.114714276,9.998462646,1.67,7.245622157,-3.334220001,89.25501674 +61.1,50.42500059,-2.587235214,48.7186,0.114714253,9.998462619,1.615,7.343787188,-3.356532524,89.24749162 +61.11,50.4250006,-2.587233807,48.7027,0.128619016,9.998684662,1.56,7.441462684,-3.375918093,89.23996657 +61.12,50.42500061,-2.5872324,48.6874,0.145999992,9.999350843,1.5046875,7.538628362,-3.392359804,89.23244146 +61.13,50.42500063,-2.587230993,48.6726,0.14600001,9.999572887,1.4484375,7.635263825,-3.405843335,89.2249164 +61.14,50.42500064,-2.587229585,48.6584,0.132095248,9.998684584,1.39125,7.731348962,-3.416356938,89.21739129 +61.15,50.42500065,-2.587228179,48.6448,0.132095239,9.99846249,1.3334375,7.826863719,-3.423891391,89.20986623 +61.16,50.42500066,-2.587226772,48.6317,0.145999991,9.999794885,1.2746875,7.921788101,-3.42844016,89.20234112 +61.17,50.42500068,-2.587225364,48.6193,0.149476182,10.00046107,1.215,8.016102339,-3.42999935,89.19481606 +61.18,50.42500069,-2.587223957,48.6074,0.146000002,9.999572772,1.155,8.109786669,-3.428567471,89.18729095 +61.19,50.4250007,-2.58722255,48.5962,0.149476201,9.998684473,1.095,8.20282155,-3.424145841,89.17976589 +61.2,50.42500072,-2.587221143,48.5855,0.146000012,9.998462384,1.035,8.295187618,-3.416738299,89.17224078 +61.21,50.42500073,-2.587219736,48.5755,0.132095247,9.998462365,0.9746875,8.386865449,-3.406351319,89.16471572 +61.22,50.42500074,-2.587218329,48.566,0.132095235,9.998462348,0.9134375,8.47783602,-3.392993897,89.15719061 +61.23,50.42500075,-2.587216922,48.5572,0.149476169,9.998462332,0.85125,8.568080311,-3.376677778,89.14966556 +61.24,50.42500077,-2.587215515,48.549,0.163380921,9.998462316,0.7884375,8.657579412,-3.357417171,89.14214044 +61.25,50.42500078,-2.587214108,48.5414,0.163380932,9.998462302,0.725,8.746314704,-3.335228808,89.13461539 +61.26,50.4250008,-2.587212701,48.5345,0.152952379,9.998462288,0.661875,8.834267622,-3.31013211,89.12709027 +61.27,50.42500081,-2.587211294,48.5282,0.146000009,9.998462274,0.6,8.921419773,-3.282148909,89.11956522 +61.28,50.42500082,-2.587209887,48.5225,0.15295239,9.998462262,0.5378125,9.007753054,-3.251303611,89.11204016 +61.29,50.42500084,-2.58720848,48.5174,0.163380953,9.998684321,0.4734375,9.093249301,-3.217623147,89.10451505 +61.3,50.42500085,-2.587207073,48.513,0.163380942,9.999350521,0.4084375,9.177890751,-3.181136851,89.09698999 +61.31,50.42500087,-2.587205666,48.5093,0.15295237,9.999572582,0.345,9.261659702,-3.141876579,89.08946488 +61.32,50.42500088,-2.587204258,48.5061,0.145999999,9.998684295,0.2815625,9.34453862,-3.099876538,89.08193982 +61.33,50.42500089,-2.587202852,48.5036,0.152952387,9.998462219,0.2165625,9.426510259,-3.05517334,89.07441471 +61.34,50.42500091,-2.587201445,48.5018,0.163380953,9.99957256,0.151875,9.507557546,-3.007806002,89.06688966 +61.35,50.42500092,-2.587200037,48.5006,0.166857132,9.999572555,0.088125,9.587663406,-2.957815836,89.05936454 +61.36,50.42500094,-2.58719863,48.5,0.166857132,9.998462203,0.0234375,9.666811222,-2.905246385,89.05183949 +61.37,50.42500095,-2.587197224,48.5001,0.166857141,9.998462201,-0.041875,9.744984438,-2.850143487,89.04431437 +61.38,50.42500097,-2.587195816,48.5009,0.166857141,9.998684269,-0.10625,9.822166723,-2.79255527,89.03678932 +61.39,50.42500098,-2.587194409,48.5022,0.16685713,9.998240128,-0.17,9.89834192,-2.732531867,89.0292642 +61.4,50.425001,-2.587193003,48.5043,0.170333312,9.998462197,-0.23375,9.973494216,-2.670125705,89.02173915 +61.41,50.42500101,-2.587191595,48.5069,0.180761884,9.998684268,-0.298125,10.04760785,-2.6053911,89.01421404 +61.42,50.42500103,-2.587190188,48.5102,0.187714275,9.998240131,-0.3634375,10.12066731,-2.538384603,89.00668898 +61.43,50.42500105,-2.587188782,48.5142,0.180761907,9.998462203,-0.4278125,10.19265745,-2.46916454,88.99916387 +61.44,50.42500106,-2.587187374,48.5188,0.170333341,9.998684277,-0.49,10.2635631,-2.39779136,88.99163881 +61.45,50.42500108,-2.587185967,48.524,0.170333335,9.998240142,-0.551875,10.33336958,-2.324327284,88.9841137 +61.46,50.42500109,-2.587184561,48.5298,0.180761896,9.998462217,-0.6153125,10.40206224,-2.248836313,88.97658864 +61.47,50.42500111,-2.587183153,48.5363,0.187714278,9.998684293,-0.68,10.46962674,-2.171384394,88.96906353 +61.48,50.42500113,-2.587181746,48.5434,0.180761907,9.998240161,-0.744375,10.53604899,-2.092038964,88.96153847 +61.49,50.42500114,-2.58718034,48.5512,0.170333344,9.99846224,-0.8065625,10.60131507,-2.010869236,88.95401336 +61.5,50.42500116,-2.587178932,48.5596,0.170333342,9.998684321,-0.866875,10.66541146,-1.927945971,88.9464883 +61.51,50.42500117,-2.587177525,48.5685,0.184238088,9.998240192,-0.9284375,10.72832463,-1.843341534,88.93896319 +61.52,50.42500119,-2.587176119,48.5781,0.20161902,9.998462273,-0.9915625,10.79004152,-1.75712972,88.93143814 +61.53,50.42500121,-2.587174711,48.5884,0.20161902,9.998462285,-1.0528125,10.8505493,-1.669385588,88.92391302 +61.54,50.42500123,-2.587173304,48.5992,0.187714277,9.99712988,-1.1115625,10.90983519,-1.5801858,88.91638797 +61.55,50.42500124,-2.587171898,48.6106,0.184238096,9.996463685,-1.1703125,10.96788693,-1.489607991,88.90886285 +61.56,50.42500126,-2.587170491,48.6226,0.18771428,9.997351979,-1.23,11.02469232,-1.397731286,88.9013378 +61.57,50.42500128,-2.587169084,48.6352,0.18423809,9.998240274,-1.29,11.0802396,-1.304635728,88.89381268 +61.58,50.42500129,-2.587167677,48.6484,0.187714292,9.998462361,-1.3496875,11.13451704,-1.210402448,88.88628763 +61.59,50.42500131,-2.58716627,48.6622,0.201619065,9.998462379,-1.408125,11.18751335,-1.115113723,88.87876252 +61.6,50.42500133,-2.587164863,48.6766,0.201619063,9.998462398,-1.4646875,11.23921752,-1.018852631,88.87123746 +61.61,50.42500135,-2.587163456,48.6915,0.187714282,9.998462417,-1.52,11.28961872,-0.921703053,88.86371235 +61.62,50.42500136,-2.587162049,48.707,0.187714261,9.998462437,-1.575,11.33870637,-0.82374973,88.85618729 +61.63,50.42500138,-2.587160642,48.723,0.205095215,9.998462458,-1.63,11.38647025,-0.72507809,88.84866224 +61.64,50.4250014,-2.587159235,48.7396,0.218999999,9.998462481,-1.685,11.43290046,-0.625774191,88.84113712 +61.65,50.42500142,-2.587157828,48.7567,0.219000008,9.998462504,-1.7396875,11.47798719,-0.525924606,88.83361207 +61.66,50.42500144,-2.587156421,48.7744,0.205095239,9.998240458,-1.793125,11.52172112,-0.42561637,88.82608695 +61.67,50.42500146,-2.587155014,48.7926,0.187714285,9.997574274,-1.845,11.56409301,-0.324937028,88.8185619 +61.68,50.42500147,-2.587153607,48.8113,0.187714297,9.99713016,-1.8965625,11.6050941,-0.223974301,88.81103678 +61.69,50.42500149,-2.587152201,48.8305,0.205095259,9.997352255,-1.948125,11.64471585,-0.122816311,88.80351173 +61.7,50.42500151,-2.587150793,48.8503,0.219000016,9.997352282,-1.998125,11.68294989,-0.021551177,88.79598662 +61.71,50.42500153,-2.587149387,48.8705,0.222476195,9.99713024,-2.04625,11.71978827,0.079732749,88.78846156 +61.72,50.42500155,-2.58714798,48.8912,0.222476186,9.997574408,-2.0934375,11.75522331,0.180947119,88.78093645 +61.73,50.42500157,-2.587146573,48.9124,0.222476185,9.998240646,-2.14,11.78924766,0.282003696,88.77341139 +61.74,50.42500159,-2.587145166,48.934,0.222476186,9.998462746,-2.1865625,11.82185412,0.38281436,88.76588628 +61.75,50.42500161,-2.587143759,48.9561,0.222476189,9.998462776,-2.233125,11.85303591,0.483291218,88.75836122 +61.76,50.42500163,-2.587142352,48.9787,0.222476198,9.998240737,-2.278125,11.88278657,0.583346666,88.75083611 +61.77,50.42500165,-2.587140945,49.0017,0.22247621,9.99735249,-2.32125,11.9110998,0.682893385,88.74331105 +61.78,50.42500167,-2.587139538,49.0251,0.222476211,9.996242174,-2.3634375,11.9379698,0.781844628,88.73578594 +61.79,50.42500169,-2.587138132,49.049,0.222476203,9.996242207,-2.4046875,11.96339085,0.880114109,88.72826088 +61.8,50.42500171,-2.587136725,49.0732,0.222476204,9.997352589,-2.4446875,11.98735767,0.977616056,88.72073577 +61.81,50.42500173,-2.587135318,49.0979,0.222476216,9.998240902,-2.4834375,12.00986529,1.074265556,88.71321072 +61.82,50.42500175,-2.587133911,49.1229,0.222476221,9.998463007,-2.52125,12.030909,1.169978271,88.7056856 +61.83,50.42500177,-2.587132504,49.1483,0.222476206,9.998240973,-2.5584375,12.05048439,1.264670776,88.69816055 +61.84,50.42500179,-2.587131097,49.1741,0.222476185,9.997352731,-2.5946875,12.06858739,1.358260453,88.69063543 +61.85,50.42500181,-2.58712969,49.2002,0.222476186,9.996242419,-2.63,12.08521417,1.450665654,88.68311038 +61.86,50.42500183,-2.587128284,49.2267,0.222476207,9.996242455,-2.6646875,12.10036134,1.541805935,88.67558526 +61.87,50.42500185,-2.587126877,49.2535,0.222476217,9.997130772,-2.698125,12.11402563,1.631601657,88.66806021 +61.88,50.42500187,-2.58712547,49.2807,0.222476211,9.99735288,-2.7296875,12.12620431,1.719974668,88.6605351 +61.89,50.42500189,-2.587124063,49.3081,0.225952403,9.99713085,-2.7596875,12.13689473,1.806847789,88.65301004 +61.9,50.42500191,-2.587122657,49.3359,0.239857176,9.997352958,-2.7884375,12.14609471,1.892145334,88.64548493 +61.91,50.42500193,-2.587121249,49.3639,0.257238124,9.997352997,-2.81625,12.15380231,1.975792875,88.63795987 +61.92,50.42500196,-2.587119843,49.3922,0.257238105,9.997130967,-2.843125,12.16001593,2.057717531,88.63043476 +61.93,50.42500198,-2.587118436,49.4208,0.23985715,9.997575146,-2.868125,12.16473429,2.137847799,88.6229097 +61.94,50.425002,-2.587117029,49.4496,0.229428597,9.998019326,-2.8915625,12.16795638,2.216113891,88.61538459 +61.95,50.42500202,-2.587115622,49.4786,0.239857181,9.997353157,-2.915,12.16968155,2.292447454,88.60785953 +61.96,50.42500204,-2.587114215,49.5079,0.257238132,9.99624285,-2.9378125,12.16990942,2.366781967,88.60033442 +61.97,50.42500207,-2.587112809,49.5374,0.257238133,9.996242891,-2.958125,12.16863991,2.439052571,88.59280936 +61.98,50.42500209,-2.587111402,49.5671,0.239857186,9.997131212,-2.9765625,12.16587339,2.509196357,88.58528431 +61.99,50.42500211,-2.587109995,49.5969,0.229428614,9.997131255,-2.9946875,12.1616103,2.577152016,88.5777592 +62,50.42500213,-2.587108588,49.627,0.239857178,9.996243019,-3.0115625,12.15585167,2.64286042,88.57023414 +62.01,50.42500215,-2.587107182,49.6572,0.257238127,9.996243061,-3.02625,12.14859854,2.706264216,88.56270903 +62.02,50.42500218,-2.587105775,49.6875,0.260714317,9.997131383,-3.04,12.13985257,2.767308056,88.55518397 +62.03,50.4250022,-2.587104368,49.718,0.257238127,9.997131425,-3.053125,12.12961553,2.82593877,88.54765886 +62.04,50.42500222,-2.587102961,49.7486,0.260714322,9.996243189,-3.0646875,12.1178896,2.88210525,88.5401338 +62.05,50.42500225,-2.587101555,49.7793,0.26071433,9.996243232,-3.075,12.10467714,2.935758508,88.53260869 +62.06,50.42500227,-2.587100148,49.8101,0.257238144,9.997131554,-3.0846875,12.08998095,2.986851732,88.52508363 +62.07,50.42500229,-2.587098741,49.841,0.260714334,9.997131598,-3.0928125,12.07380411,3.035340349,88.51755852 +62.08,50.42500232,-2.587097334,49.872,0.260714338,9.996243363,-3.098125,12.05615002,3.081182129,88.51003346 +62.09,50.42500234,-2.587095928,49.903,0.257238154,9.996243406,-3.1015625,12.03702234,3.124337023,88.50250835 +62.1,50.42500236,-2.587094521,49.934,0.260714338,9.997353798,-3.105,12.01642508,3.164767504,88.4949833 +62.11,50.42500239,-2.587093114,49.9651,0.260714319,9.998020051,-3.108125,11.99436254,3.202438218,88.48745818 +62.12,50.42500241,-2.587091707,49.9962,0.257238129,9.997353886,-3.1096875,11.9708393,3.237316394,88.47993313 +62.13,50.42500243,-2.5870903,50.0273,0.264190534,9.996021511,-3.1096875,11.94586023,3.269371549,88.47240801 +62.14,50.42500246,-2.587088894,50.0584,0.274619118,9.995355346,-3.108125,11.91943066,3.298575838,88.46488296 +62.15,50.42500248,-2.587087487,50.0895,0.274619113,9.996021597,-3.1046875,11.89155609,3.32490365,88.45735784 +62.16,50.42500251,-2.587086081,50.1205,0.264190537,9.997131989,-3.0996875,11.86224225,3.348332123,88.44983279 +62.17,50.42500253,-2.587084673,50.1515,0.257238155,9.997132033,-3.0934375,11.83149533,3.368840746,88.44230768 +62.18,50.42500255,-2.587083267,50.1824,0.264190529,9.996021728,-3.08625,11.79932175,3.386411758,88.43478262 +62.19,50.42500258,-2.58708186,50.2132,0.274619096,9.995355563,-3.078125,11.7657282,3.401029745,88.42725751 +62.2,50.4250026,-2.587080454,50.244,0.278095298,9.995799745,-3.068125,11.73072174,3.412681987,88.41973245 +62.21,50.42500263,-2.587079047,50.2746,0.278095311,9.996243927,-3.05625,11.69430964,3.421358344,88.41220734 +62.22,50.42500265,-2.58707764,50.3051,0.278095312,9.99579983,-3.0434375,11.65649953,3.427051196,88.40468228 +62.23,50.42500268,-2.587076234,50.3355,0.278095313,9.995355733,-3.0296875,11.6172993,3.429755614,88.39715717 +62.24,50.4250027,-2.587074827,50.3657,0.278095317,9.996021983,-3.015,11.57671716,3.429469192,88.38963211 +62.25,50.42500273,-2.587073421,50.3958,0.281571505,9.997132374,-2.9996875,11.53476147,3.426192275,88.382107 +62.26,50.42500275,-2.587072013,50.4257,0.292000073,9.997132415,-2.9828125,11.49144116,3.419927669,88.37458194 +62.27,50.42500278,-2.587070607,50.4555,0.298952449,9.996022107,-2.963125,11.44676517,3.410680818,88.36705683 +62.28,50.42500281,-2.5870692,50.485,0.292000065,9.995355939,-2.9415625,11.40074286,3.3984598,88.35953178 +62.29,50.42500283,-2.587067794,50.5143,0.281571504,9.995800119,-2.92,11.35338383,3.383275272,88.35200666 +62.3,50.42500286,-2.587066387,50.5434,0.281571523,9.996244299,-2.898125,11.30469794,3.36514047,88.34448161 +62.31,50.42500288,-2.58706498,50.5723,0.292000102,9.995800199,-2.8746875,11.25469546,3.344071208,88.33695649 +62.32,50.42500291,-2.587063574,50.6009,0.298952478,9.995134029,-2.8496875,11.20338668,3.320085934,88.32943144 +62.33,50.42500294,-2.587062167,50.6293,0.295476283,9.995134068,-2.823125,11.15078251,3.293205447,88.32190638 +62.34,50.42500296,-2.587060761,50.6574,0.295476278,9.995800315,-2.7946875,11.09689377,3.263453239,88.31438127 +62.35,50.42500299,-2.587059354,50.6852,0.298952458,9.996244493,-2.765,11.04173174,3.230855206,88.30685621 +62.36,50.42500302,-2.587057947,50.7127,0.295476267,9.99602246,-2.735,10.985308,3.195439883,88.2993311 +62.37,50.42500304,-2.587056541,50.7399,0.295476282,9.996022497,-2.7046875,10.92763436,3.157238093,88.29180604 +62.38,50.42500307,-2.587055134,50.7668,0.298952482,9.996022534,-2.673125,10.86872272,3.116283128,88.28428093 +62.39,50.4250031,-2.587053727,50.7934,0.295476293,9.994912221,-2.6396875,10.80858553,3.07261068,88.27675588 +62.4,50.42500312,-2.587052321,50.8196,0.298952486,9.993801907,-2.6046875,10.74723527,3.02625891,88.26923076 +62.41,50.42500315,-2.587050915,50.8455,0.312857244,9.994024011,-2.568125,10.68468478,2.977268211,88.26170571 +62.42,50.42500318,-2.587049508,50.871,0.312857234,9.994912324,-2.53,10.62094712,2.925681269,88.25418059 +62.43,50.42500321,-2.587048102,50.8961,0.29895247,9.995800637,-2.4915625,10.55603559,2.871543059,88.24665554 +62.44,50.42500323,-2.587046695,50.9208,0.29895248,9.996244809,-2.4534375,10.48996376,2.814900853,88.23913042 +62.45,50.42500326,-2.587045288,50.9452,0.31285726,9.995800702,-2.4146875,10.42274544,2.755803981,88.23160537 +62.46,50.42500329,-2.587043882,50.9691,0.312857272,9.995134525,-2.374375,10.35439461,2.694304066,88.22408026 +62.47,50.42500332,-2.587042475,50.9927,0.298952503,9.994912487,-2.331875,10.2849256,2.630454623,88.2165552 +62.48,50.42500334,-2.587041069,51.0158,0.298952484,9.994912517,-2.2878125,10.2143529,2.564311401,88.20903009 +62.49,50.42500337,-2.587039662,51.0384,0.316333426,9.994912546,-2.2434375,10.14269123,2.495932097,88.20150503 +62.5,50.4250034,-2.587038256,51.0607,0.330238196,9.994912575,-2.198125,10.06995561,2.425376241,88.19397992 +62.51,50.42500343,-2.587036849,51.0824,0.333714407,9.995134673,-2.1515625,9.996161171,2.352705483,88.18645486 +62.52,50.42500346,-2.587035443,51.1037,0.330238229,9.995800909,-2.105,9.921323372,2.277983077,88.17892975 +62.53,50.42500349,-2.587034036,51.1245,0.316333461,9.996023005,-2.058125,9.845457801,2.201274284,88.17140469 +62.54,50.42500352,-2.587032629,51.1449,0.298952499,9.994912682,-2.0096875,9.76858033,2.122645911,88.16387958 +62.55,50.42500354,-2.587031223,51.1647,0.298952494,9.993802359,-1.9596875,9.690707,2.042166597,88.15635452 +62.56,50.42500357,-2.587029817,51.1841,0.316333442,9.993802383,-1.9084375,9.611854027,1.959906417,88.14882941 +62.57,50.4250036,-2.58702841,51.2029,0.330238212,9.993802407,-1.8565625,9.53203797,1.875937217,88.14130436 +62.58,50.42500363,-2.587027004,51.2212,0.333714418,9.993802429,-1.805,9.451275501,1.790332166,88.13377924 +62.59,50.42500366,-2.587025598,51.239,0.333714426,9.994912799,-1.753125,9.36958335,1.703165919,88.12625419 +62.6,50.42500369,-2.587024191,51.2563,0.333714429,9.995801098,-1.6996875,9.286978707,1.614514509,88.11872907 +62.61,50.42500372,-2.587022784,51.273,0.33371443,9.994912839,-1.645,9.203478817,1.524455169,88.11120402 +62.62,50.42500375,-2.587021378,51.2892,0.33371442,9.99402458,-1.59,9.119101042,1.43306651,88.1036789 +62.63,50.42500378,-2.587019972,51.3048,0.333714409,9.994912877,-1.5346875,9.033863085,1.340428173,88.09615385 +62.64,50.42500381,-2.587018565,51.3199,0.333714412,9.995801172,-1.478125,8.94778265,1.246621001,88.08862874 +62.65,50.42500384,-2.587017158,51.3344,0.333714422,9.99491291,-1.42,8.860877787,1.151726757,88.08110368 +62.66,50.42500387,-2.587015752,51.3483,0.333714432,9.993802577,-1.3615625,8.773166658,1.055828176,88.07357862 +62.67,50.4250039,-2.587014346,51.3616,0.333714437,9.993802592,-1.3034375,8.684667539,0.959008851,88.06605351 +62.68,50.42500393,-2.587012939,51.3744,0.333714433,9.993802606,-1.245,8.595398939,0.861353294,88.05852845 +62.69,50.42500396,-2.587011533,51.3865,0.333714425,9.993580549,-1.18625,8.505379419,0.762946647,88.05100334 +62.7,50.42500399,-2.587010127,51.3981,0.333714416,9.994024699,-1.126875,8.414627947,0.663874681,88.04347829 +62.71,50.42500402,-2.58700872,51.4091,0.337190605,9.994690919,-1.06625,8.323163313,0.564223798,88.03595317 +62.72,50.42500405,-2.587007314,51.4194,0.351095379,9.994690929,-1.005,8.231004656,0.464080917,88.02842812 +62.73,50.42500408,-2.587005907,51.4292,0.36847635,9.994024729,-0.9434375,8.138171284,0.363533356,88.020903 +62.74,50.42500412,-2.587004501,51.4383,0.368476357,9.993580596,-0.8815625,8.044682563,0.262668777,88.01337795 +62.75,50.42500415,-2.587003095,51.4468,0.351095392,9.994024742,-0.82,7.950557973,0.16157513,88.00585284 +62.76,50.42500418,-2.587001688,51.4547,0.33719061,9.994690957,-0.7584375,7.855817167,0.060340592,87.99832778 +62.77,50.42500421,-2.587000282,51.462,0.333714418,9.994690962,-0.69625,7.760480027,-0.040946543,87.99080267 +62.78,50.42500424,-2.586998875,51.4686,0.337190624,9.993802687,-0.6334375,7.664566319,-0.142197983,87.98327761 +62.79,50.42500427,-2.586997469,51.4747,0.3510954,9.992692342,-0.57,7.568096212,-0.243325435,87.9757525 +62.8,50.4250043,-2.586996063,51.48,0.368476362,9.992692344,-0.50625,7.471089759,-0.344240664,87.96822744 +62.81,50.42500434,-2.586994657,51.4848,0.368476356,9.993802693,-0.4421875,7.373567243,-0.444855777,87.96070233 +62.82,50.42500437,-2.58699325,51.4889,0.354571571,9.994690971,-0.3778125,7.275549061,-0.545082883,87.95317727 +62.83,50.4250044,-2.586991844,51.4923,0.354571564,9.994690969,-0.31375,7.177055668,-0.64483472,87.94565216 +62.84,50.42500443,-2.586990437,51.4952,0.368476345,9.993802688,-0.25,7.078107633,-0.744024257,87.9381271 +62.85,50.42500447,-2.586989031,51.4973,0.368476361,9.992470266,-0.18625,6.978725582,-0.842564976,87.93060199 +62.86,50.4250045,-2.586987625,51.4989,0.354571598,9.991804052,-0.121875,6.878930314,-0.940370992,87.92307693 +62.87,50.42500453,-2.586986219,51.4998,0.354571591,9.992470256,-0.05625,6.778742628,-1.03735699,87.91555182 +62.88,50.42500456,-2.586984813,51.5,0.368476345,9.993802669,0.009375,6.678183493,-1.133438346,87.90802677 +62.89,50.4250046,-2.586983406,51.4996,0.368476334,9.99469094,0.0734375,6.577273879,-1.228531349,87.90050165 +62.9,50.42500463,-2.586982,51.4985,0.354571571,9.994690931,0.1365625,6.47603493,-1.322553093,87.8929766 +62.91,50.42500466,-2.586980593,51.4969,0.354571587,9.993802643,0.2003125,6.374487672,-1.41542153,87.88545148 +62.92,50.42500469,-2.586979187,51.4945,0.371952555,9.992470214,0.265,6.272653362,-1.507055701,87.87792643 +62.93,50.42500473,-2.586977781,51.4916,0.385857324,9.991581924,0.3296875,6.170553314,-1.59737568,87.87040132 +62.94,50.42500476,-2.586976375,51.4879,0.385857318,9.991581911,0.3934375,6.068208785,-1.68630274,87.86287626 +62.95,50.4250048,-2.586974969,51.4837,0.375428725,9.992470176,0.4565625,5.965641204,-1.773759304,87.85535115 +62.96,50.42500483,-2.586973563,51.4788,0.368476333,9.993580509,0.5203125,5.862871941,-1.859669112,87.84782609 +62.97,50.42500486,-2.586972156,51.4733,0.375428729,9.993802563,0.5846875,5.759922484,-1.943957277,87.84030098 +62.98,50.4250049,-2.58697075,51.4671,0.385857318,9.993580477,0.6484375,5.656814317,-2.026550289,87.83277592 +62.99,50.42500493,-2.586969344,51.4603,0.385857316,9.993802529,0.71125,5.553568984,-2.107376127,87.82525081 +63,50.42500497,-2.586967937,51.4529,0.375428723,9.99358044,0.7734375,5.450208028,-2.186364261,87.81772575 +63.01,50.425005,-2.586966531,51.4448,0.368476331,9.992470072,0.835,5.346753049,-2.263445877,87.8102007 +63.02,50.42500503,-2.586965125,51.4362,0.375428726,9.991581773,0.8965625,5.243225706,-2.338553769,87.80267558 +63.03,50.42500507,-2.586963719,51.4269,0.385857318,9.991359682,0.9584375,5.139647542,-2.411622389,87.79515053 +63.04,50.4250051,-2.586962313,51.417,0.389333514,9.991581729,1.02,5.036040214,-2.482588025,87.78762542 +63.05,50.42500514,-2.586960907,51.4065,0.3893335,9.992469983,1.0815625,4.932425323,-2.551388797,87.78010036 +63.06,50.42500517,-2.586959501,51.3954,0.389333482,9.993580307,1.143125,4.828824584,-2.617964716,87.77257525 +63.07,50.42500521,-2.586958094,51.3836,0.389333481,9.993580281,1.2028125,4.725259598,-2.682257743,87.76505019 +63.08,50.42500524,-2.586956688,51.3713,0.389333498,9.992469906,1.26,4.621751965,-2.744211841,87.75752508 +63.09,50.42500528,-2.586955282,51.3584,0.389333511,9.9915816,1.316875,4.518323343,-2.803772867,87.75000002 +63.1,50.42500531,-2.586953876,51.345,0.389333506,9.991359502,1.375,4.414995332,-2.860889024,87.74247491 +63.11,50.42500535,-2.58695247,51.3309,0.392809681,9.991359472,1.4334375,4.311789475,-2.915510408,87.73494985 +63.12,50.42500538,-2.586951064,51.3163,0.403238244,9.991359442,1.49125,4.208727317,-2.967589464,87.72742474 +63.13,50.42500542,-2.586949658,51.3011,0.410190628,9.99135941,1.548125,4.1058304,-3.017080699,87.71989968 +63.14,50.42500546,-2.586948252,51.2853,0.403238255,9.991359379,1.603125,4.003120266,-3.063941027,87.71237457 +63.15,50.42500549,-2.586946846,51.269,0.392809691,9.991581415,1.656875,3.900618289,-3.108129537,87.70484951 +63.16,50.42500553,-2.58694544,51.2522,0.392809688,9.99246966,1.7115625,3.798345895,-3.149607671,87.6973244 +63.17,50.42500556,-2.586944034,51.2348,0.403238248,9.993579973,1.7665625,3.696324457,-3.188339388,87.68979935 +63.18,50.4250056,-2.586942627,51.2168,0.410190624,9.993579938,1.819375,3.594575289,-3.224290771,87.68227423 +63.19,50.42500564,-2.586941221,51.1984,0.40671444,9.992469553,1.87,3.493119647,-3.257430478,87.67474918 +63.2,50.42500567,-2.586939815,51.1794,0.406714448,9.991581237,1.9203125,3.391978616,-3.287729747,87.66722406 +63.21,50.42500571,-2.586938409,51.16,0.410190641,9.991359129,1.97125,3.291173452,-3.315161992,87.65969901 +63.22,50.42500575,-2.586937003,51.14,0.406714445,9.99135909,2.0215625,3.190725185,-3.339703436,87.6521739 +63.23,50.42500578,-2.586935597,51.1195,0.410190629,9.99135905,2.0696875,3.090654725,-3.361332593,87.64464884 +63.24,50.42500582,-2.586934191,51.0986,0.424095392,9.99135901,2.1165625,2.990983045,-3.380030555,87.63712373 +63.25,50.42500586,-2.586932785,51.0772,0.424095395,9.991358969,2.1634375,2.891730884,-3.395781165,87.62959867 +63.26,50.4250059,-2.586931379,51.0553,0.41019063,9.991358926,2.2096875,2.792918983,-3.408570557,87.62207356 +63.27,50.42500593,-2.586929973,51.033,0.410190621,9.991358883,2.2546875,2.694568028,-3.418387616,87.6145485 +63.28,50.42500597,-2.586928567,51.0102,0.424095379,9.99135884,2.2984375,2.596698586,-3.425223804,87.60702339 +63.29,50.42500601,-2.586927161,50.987,0.424095385,9.991358796,2.34125,2.499330997,-3.429073164,87.59949833 +63.3,50.42500605,-2.586925755,50.9634,0.41019063,9.991358752,2.3834375,2.402485603,-3.429932314,87.59197322 +63.31,50.42500608,-2.586924349,50.9393,0.410190633,9.991358707,2.4246875,2.306182742,-3.42780051,87.58444816 +63.32,50.42500612,-2.586922943,50.9149,0.427571585,9.99135866,2.4646875,2.210442411,-3.422679585,87.57692305 +63.33,50.42500616,-2.586921537,50.89,0.438000148,9.991358613,2.503125,2.115284606,-3.414574066,87.56939799 +63.34,50.4250062,-2.586920131,50.8648,0.42757156,9.991358565,2.5396875,2.020729324,-3.403490942,87.56187288 +63.35,50.42500624,-2.586918725,50.8392,0.410190598,9.991358517,2.5753125,1.92679616,-3.389439954,87.55434783 +63.36,50.42500627,-2.586917319,50.8133,0.410190607,9.991358468,2.6115625,1.833504822,-3.372433364,87.54682277 +63.37,50.42500631,-2.586915913,50.787,0.427571574,9.991136349,2.6478125,1.740874736,-3.352485895,87.53929766 +63.38,50.42500635,-2.586914507,50.7603,0.44147634,9.990248021,2.68125,1.648925323,-3.329615024,87.5317726 +63.39,50.42500639,-2.586913101,50.7333,0.444952524,9.989137622,2.7115625,1.557675663,-3.30384069,87.52424749 +63.4,50.42500643,-2.586911696,50.7061,0.444952517,9.989137571,2.741875,1.467144951,-3.275185409,87.51672243 +63.41,50.42500647,-2.58691029,50.6785,0.44495252,9.990247868,2.773125,1.377352037,-3.243674048,87.50919732 +63.42,50.42500651,-2.586908884,50.6506,0.444952522,9.991136095,2.8028125,1.288315656,-3.209334166,87.50167226 +63.43,50.42500655,-2.586907478,50.6224,0.441476322,9.991358112,2.8296875,1.200054372,-3.17219573,87.49414715 +63.44,50.42500659,-2.586906072,50.594,0.427571542,9.991135989,2.855,1.112586693,-3.132291053,87.48662209 +63.45,50.42500663,-2.586904666,50.5653,0.41019058,9.990247658,2.88,1.025930837,-3.089654971,87.47909698 +63.46,50.42500666,-2.58690326,50.5364,0.410190589,9.989137258,2.904375,0.940104968,-3.044324728,87.47157193 +63.47,50.4250067,-2.586901855,50.5072,0.427571553,9.989137204,2.9265625,0.855126904,-2.996339742,87.46404681 +63.48,50.42500674,-2.586900449,50.4778,0.441476314,9.990247498,2.9465625,0.771014465,-2.945741896,87.45652176 +63.49,50.42500678,-2.586899043,50.4483,0.4449525,9.990913653,2.9665625,0.687785184,-2.892575309,87.44899664 +63.5,50.42500682,-2.586897637,50.4185,0.444952502,9.990247389,2.9865625,0.60545642,-2.836886389,87.44147159 +63.51,50.42500686,-2.586896231,50.3885,0.448428698,9.989136985,3.004375,0.524045419,-2.77872361,87.43394647 +63.52,50.4250069,-2.586894826,50.3584,0.462333463,9.989136929,3.0196875,0.4435692,-2.718137792,87.42642142 +63.53,50.42500694,-2.58689342,50.3281,0.47971441,9.990025151,3.0334375,0.364044491,-2.655181706,87.41889631 +63.54,50.42500699,-2.586892014,50.2977,0.479714397,9.990025095,3.04625,0.285487967,-2.589910239,87.41137125 +63.55,50.42500703,-2.586890608,50.2672,0.462333437,9.989136759,3.0584375,0.207916013,-2.522380345,87.40384614 +63.56,50.42500707,-2.586889203,50.2365,0.448428679,9.989136703,3.0696875,0.131344845,-2.452650923,87.39632108 +63.57,50.42500711,-2.586887797,50.2058,0.444952491,9.990024925,3.0796875,0.05579039,-2.380782706,87.38879597 +63.58,50.42500715,-2.586886391,50.1749,0.444952483,9.990024869,3.088125,-0.018731537,-2.306838435,87.38127091 +63.59,50.42500719,-2.586884985,50.144,0.444952469,9.989136534,3.0946875,-0.092205353,-2.230882623,87.3737458 +63.6,50.42500723,-2.58688358,50.113,0.448428659,9.989136477,3.1,-0.164615702,-2.152981391,87.36622074 +63.61,50.42500727,-2.586882174,50.082,0.462333434,9.990024699,3.1046875,-0.235947515,-2.07320269,87.35869563 +63.62,50.42500731,-2.586880768,50.0509,0.479714396,9.990024641,3.108125,-0.306185838,-1.991616193,87.35117057 +63.63,50.42500736,-2.586879362,50.0198,0.479714387,9.989136304,3.1096875,-0.375316061,-1.908292946,87.34364546 +63.64,50.4250074,-2.586877957,49.9887,0.462333416,9.988914177,3.1096875,-0.443323745,-1.823305658,87.33612041 +63.65,50.42500744,-2.586876551,49.9576,0.45190484,9.989136189,3.108125,-0.510194623,-1.736728412,87.32859529 +63.66,50.42500748,-2.586875145,49.9265,0.462333423,9.988914063,3.105,-0.575914716,-1.648636667,87.32107024 +63.67,50.42500752,-2.58687374,49.8955,0.479714385,9.988914005,3.10125,-0.640470443,-1.55910737,87.31354512 +63.68,50.42500757,-2.586872334,49.8645,0.479714376,9.989136017,3.0965625,-0.70384817,-1.468218445,87.30602007 +63.69,50.42500761,-2.586870928,49.8335,0.465809597,9.988913891,3.0896875,-0.766034775,-1.376049245,87.29849495 +63.7,50.42500765,-2.586869523,49.8027,0.465809594,9.988913834,3.0815625,-0.827017136,-1.2826801,87.2909699 +63.71,50.42500769,-2.586868117,49.7719,0.479714366,9.989135846,3.0734375,-0.88678265,-1.188192427,87.28344484 +63.72,50.42500774,-2.586866711,49.7412,0.479714364,9.988913719,3.064375,-0.945318826,-1.092668617,87.27591973 +63.73,50.42500778,-2.586865306,49.7106,0.465809588,9.988913662,3.0528125,-1.002613345,-0.996192035,87.26839467 +63.74,50.42500782,-2.5868639,49.6801,0.465809585,9.989135676,3.038125,-1.05865429,-0.898846735,87.26086956 +63.75,50.42500786,-2.586862494,49.6498,0.479714359,9.98869148,3.021875,-1.113429972,-0.800717571,87.25334451 +63.76,50.42500791,-2.586861089,49.6197,0.483190555,9.988025215,3.0065625,-1.166928932,-0.701890259,87.24581939 +63.77,50.42500795,-2.586859683,49.5897,0.479714355,9.98802516,2.99125,-1.219140055,-0.602450855,87.23829434 +63.78,50.42500799,-2.586858278,49.5598,0.483190533,9.988691313,2.9728125,-1.27005234,-0.502486106,87.23076922 +63.79,50.42500804,-2.586856872,49.5302,0.483190531,9.989135397,2.9515625,-1.319655244,-0.402083159,87.22324417 +63.8,50.42500808,-2.586855466,49.5008,0.479714348,9.988691202,2.9303125,-1.36793834,-0.30132962,87.21571905 +63.81,50.42500812,-2.586854061,49.4716,0.486666735,9.988024938,2.9096875,-1.414891601,-0.200313264,87.208194 +63.82,50.42500817,-2.586852655,49.4426,0.4970953,9.987802814,2.8878125,-1.460505172,-0.099122272,87.20066889 +63.83,50.42500821,-2.58685125,49.4138,0.500571478,9.987802759,2.863125,-1.504769542,0.002155123,87.19314383 +63.84,50.42500826,-2.586849844,49.3853,0.500571476,9.987802705,2.8365625,-1.547675487,0.103430685,87.18561872 +63.85,50.4250083,-2.586848439,49.3571,0.497095291,9.987580583,2.8096875,-1.58921401,0.204616063,87.17809366 +63.86,50.42500835,-2.586847033,49.3291,0.486666716,9.986914321,2.7815625,-1.629376518,0.305622964,87.17056855 +63.87,50.42500839,-2.586845628,49.3014,0.479714322,9.98647013,2.75125,-1.668154531,0.406363383,87.16304349 +63.88,50.42500843,-2.586844223,49.2741,0.486666703,9.986914216,2.72,-1.70553997,0.506749428,87.15551838 +63.89,50.42500848,-2.586842817,49.247,0.497095285,9.987580374,2.6884375,-1.741525043,0.606693607,87.14799332 +63.9,50.42500852,-2.586841412,49.2203,0.500571481,9.987802392,2.65625,-1.776102243,0.706108775,87.14046821 +63.91,50.42500857,-2.586840006,49.1939,0.500571472,9.987802341,2.623125,-1.809264353,0.804908127,87.13294315 +63.92,50.42500861,-2.586838601,49.1678,0.500571459,9.987802291,2.5878125,-1.841004439,0.903005607,87.12541804 +63.93,50.42500866,-2.586837195,49.1421,0.504047648,9.987802242,2.55,-1.871315854,1.00031567,87.11789299 +63.94,50.4250087,-2.58683579,49.1168,0.514476226,9.987802193,2.511875,-1.900192297,1.096753462,87.11036787 +63.95,50.42500875,-2.586834384,49.0919,0.521428599,9.987802144,2.4746875,-1.927627693,1.192234874,87.10284282 +63.96,50.4250088,-2.586832979,49.0673,0.514476202,9.987802095,2.43625,-1.953616371,1.286676596,87.0953177 +63.97,50.42500884,-2.586831573,49.0431,0.504047631,9.987802048,2.3946875,-1.978152888,1.379996352,87.08779265 +63.98,50.42500889,-2.586830168,49.0194,0.500571454,9.987579932,2.351875,-2.001232086,1.472112724,87.08026753 +63.99,50.42500893,-2.586828762,48.9961,0.500571454,9.986691608,2.31,-2.022849154,1.562945328,87.07274248 +64,50.42500898,-2.586827357,48.9732,0.504047635,9.985581215,2.2678125,-2.042999564,1.652415094,87.06521737 +64.01,50.42500902,-2.586825952,48.9507,0.514476206,9.98558117,2.223125,-2.061679191,1.740443929,87.05769231 +64.02,50.42500907,-2.586824547,48.9287,0.521428597,9.986691473,2.1765625,-2.078884082,1.826955055,87.0501672 +64.03,50.42500912,-2.586823141,48.9072,0.517952411,9.987579708,2.13,-2.09461057,1.911873015,87.04264214 +64.04,50.42500916,-2.586821736,48.8861,0.517952402,9.987579665,2.083125,-2.108855504,1.99512384,87.03511709 +64.05,50.42500921,-2.58682033,48.8655,0.521428581,9.986913415,2.0346875,-2.121615847,2.076634879,87.02759197 +64.06,50.42500926,-2.586818925,48.8454,0.517952388,9.986247165,1.985,-2.132888907,2.156335027,87.02006692 +64.07,50.4250093,-2.58681752,48.8258,0.517952393,9.985802986,1.9346875,-2.142672333,2.234154842,87.0125418 +64.08,50.42500935,-2.586816114,48.8067,0.521428576,9.985358807,1.8834375,-2.150964121,2.310026487,87.00501675 +64.09,50.4250094,-2.58681471,48.7881,0.51795237,9.985358768,1.8315625,-2.157762552,2.383883669,86.99749163 +64.1,50.42500944,-2.586813304,48.7701,0.521428564,9.985802869,1.7796875,-2.163066135,2.45566216,86.98996658 +64.11,50.42500949,-2.586811899,48.7525,0.535333341,9.986246971,1.7265625,-2.166873841,2.525299221,86.98244147 +64.12,50.42500954,-2.586810494,48.7355,0.535333342,9.986691073,1.6715625,-2.169184809,2.592734176,86.97491641 +64.13,50.42500959,-2.586809088,48.7191,0.521428569,9.986691037,1.616875,-2.169998581,2.65790824,86.9673913 +64.14,50.42500963,-2.586807683,48.7032,0.521428567,9.986246863,1.563125,-2.169314985,2.720764575,86.95986624 +64.15,50.42500968,-2.586806278,48.6878,0.538809529,9.98580269,1.5078125,-2.167134193,2.781248349,86.95234113 +64.16,50.42500973,-2.586804872,48.673,0.549238098,9.985358518,1.45,-2.163456663,2.83930685,86.94481607 +64.17,50.42500978,-2.586803468,48.6588,0.538809509,9.985358485,1.3915625,-2.158283084,2.894889428,86.93729096 +64.18,50.42500983,-2.586802062,48.6452,0.521428549,9.985580523,1.3334375,-2.1516146,2.947947612,86.9297659 +64.19,50.42500987,-2.586800657,48.6321,0.521428564,9.985358423,1.275,-2.143452587,2.998435163,86.92224079 +64.2,50.42500992,-2.586799252,48.6197,0.53880953,9.985580463,1.2165625,-2.133798764,3.046308021,86.91471573 +64.21,50.42500997,-2.586797847,48.6078,0.552714288,9.986468713,1.158125,-2.122655193,3.091524475,86.90719062 +64.22,50.42501002,-2.586796441,48.5965,0.556190467,9.986468686,1.098125,-2.110024052,3.134045048,86.89966557 +64.23,50.42501007,-2.586795036,48.5858,0.552714275,9.985358311,1.0365625,-2.095908148,3.17383267,86.89214045 +64.24,50.42501012,-2.586793631,48.5758,0.53880952,9.984470006,0.975,-2.080310346,3.210852676,86.8846154 +64.25,50.42501017,-2.586792226,48.5663,0.521428563,9.984247912,0.9134375,-2.063233855,3.245072753,86.87709028 +64.26,50.42501021,-2.586790821,48.5575,0.521428547,9.984469958,0.8515625,-2.044682341,3.276463105,86.86956523 +64.27,50.42501026,-2.586789416,48.5493,0.538809495,9.985358213,0.79,-2.024659643,3.304996346,86.86204011 +64.28,50.42501031,-2.586788011,48.5417,0.552714271,9.986246469,0.728125,-2.003169887,3.330647552,86.85451506 +64.29,50.42501036,-2.586786605,48.5347,0.556190468,9.985580238,0.665,-1.980217656,3.353394434,86.84698995 +64.3,50.42501041,-2.5867852,48.5284,0.556190458,9.9842478,0.6015625,-1.955807706,3.373217055,86.83946489 +64.31,50.42501046,-2.586783796,48.5227,0.556190451,9.984469851,0.5384375,-1.929945078,3.390098168,86.83193978 +64.32,50.42501051,-2.58678239,48.5176,0.556190455,9.985358112,0.475,-1.902635274,3.404023105,86.82441472 +64.33,50.42501056,-2.586780985,48.5132,0.556190459,9.985136025,0.4115625,-1.873883908,3.414979663,86.81688961 +64.34,50.42501061,-2.58677958,48.5094,0.556190457,9.984469799,0.3484375,-1.843696997,3.422958329,86.80936455 +64.35,50.42501066,-2.586778175,48.5062,0.556190459,9.984247714,0.2846875,-1.812080899,3.427952115,86.80183944 +64.36,50.42501071,-2.58677677,48.5037,0.556190467,9.984247699,0.2196875,-1.779042204,3.429956665,86.79431438 +64.37,50.42501076,-2.586775365,48.5018,0.556190465,9.984247686,0.15375,-1.744587731,3.428970261,86.78678927 +64.38,50.42501081,-2.58677396,48.5006,0.556190449,9.984025604,0.0884375,-1.708724813,3.424993704,86.77926421 +64.39,50.42501086,-2.586772555,48.5001,0.559666636,9.983359384,0.025,-1.671460784,3.418030548,86.77173916 +64.4,50.42501091,-2.58677115,48.5001,0.57357141,9.983137304,-0.0384375,-1.632803551,3.408086808,86.76421405 +64.41,50.42501096,-2.586769746,48.5008,0.590952363,9.984247642,-0.1034375,-1.592761135,3.395171136,86.75668899 +64.42,50.42501102,-2.58676834,48.5022,0.590952352,9.985357981,-0.168125,-1.551341958,3.379294877,86.74916388 +64.43,50.42501107,-2.586766935,48.5042,0.573571403,9.985135902,-0.2315625,-1.508554559,3.360471781,86.74163882 +64.44,50.42501112,-2.58676553,48.5068,0.559666656,9.984247618,-0.2953125,-1.464407932,3.338718292,86.73411371 +64.45,50.42501117,-2.586764125,48.5101,0.556190468,9.983137265,-0.36,-1.418911301,3.314053433,86.72658865 +64.46,50.42501122,-2.58676272,48.514,0.55966665,9.982026913,-0.425,-1.372074179,3.286498633,86.71906354 +64.47,50.42501127,-2.586761316,48.5186,0.573571409,9.98202691,-0.4896875,-1.323906304,3.256077954,86.71153848 +64.48,50.42501132,-2.586759911,48.5238,0.590952359,9.983137254,-0.553125,-1.274417762,3.222817983,86.70401337 +64.49,50.42501138,-2.586758506,48.5297,0.590952353,9.98402553,-0.615,-1.223618923,3.186747597,86.69648831 +64.5,50.42501143,-2.586757101,48.5361,0.573571406,9.984247598,-0.676875,-1.171520329,3.147898366,86.6889632 +64.51,50.42501148,-2.586755696,48.5432,0.56314285,9.984025529,-0.7403125,-1.118132924,3.106304094,86.68143815 +64.52,50.42501153,-2.586754291,48.5509,0.573571423,9.983137252,-0.804375,-1.063467766,3.062001106,86.67391303 +64.53,50.42501158,-2.586752886,48.5593,0.590952362,9.982026907,-0.8665625,-1.007536371,3.015028021,86.66638798 +64.54,50.42501164,-2.586751482,48.5683,0.590952358,9.98202691,-0.9265625,-0.95035037,2.965425747,86.65886286 +64.55,50.42501169,-2.586750077,48.5778,0.577047607,9.983137262,-0.986875,-0.891921738,2.913237599,86.65133781 +64.56,50.42501174,-2.586748672,48.588,0.577047608,9.984025545,-1.0484375,-0.832262622,2.858509014,86.64381269 +64.57,50.42501179,-2.586747267,48.5988,0.590952361,9.984025551,-1.1096875,-0.77138557,2.801287834,86.63628764 +64.58,50.42501185,-2.586745862,48.6102,0.594428558,9.983137279,-1.17,-0.709303187,2.741623848,86.62876253 +64.59,50.4250119,-2.586744457,48.6222,0.590952383,9.982026939,-1.23,-0.646028478,2.679569138,86.62123747 +64.6,50.42501195,-2.586743053,48.6348,0.594428575,9.982026948,-1.2896875,-0.581574679,2.615177792,86.61371236 +64.61,50.42501201,-2.586741648,48.648,0.594428561,9.982915235,-1.348125,-0.515955255,2.548506017,86.6061873 +64.62,50.42501206,-2.586740243,48.6618,0.590952367,9.982915245,-1.405,-0.4491839,2.479611853,86.59866219 +64.63,50.42501211,-2.586738838,48.6761,0.594428573,9.982026978,-1.4615625,-0.381274536,2.40855546,86.59113713 +64.64,50.42501217,-2.586737434,48.691,0.594428581,9.981804921,-1.5184375,-0.312241372,2.335398777,86.58361202 +64.65,50.42501222,-2.586736029,48.7065,0.590952382,9.982027003,-1.5746875,-0.24209879,2.260205572,86.57608696 +64.66,50.42501227,-2.586734624,48.7225,0.594428568,9.981804947,-1.63,-0.170861515,2.183041449,86.56856185 +64.67,50.42501233,-2.58673322,48.7391,0.594428574,9.981804962,-1.6846875,-0.098544329,2.103973675,86.56103679 +64.68,50.42501238,-2.586731815,48.7562,0.590952387,9.982027047,-1.738125,-0.025162416,2.023071175,86.55351168 +64.69,50.42501243,-2.58673041,48.7739,0.597904762,9.981582924,-1.79,0.049268985,1.940404595,86.54598663 +64.7,50.42501249,-2.586729006,48.792,0.608333332,9.980916732,-1.841875,0.124734287,1.856045899,86.53846151 +64.71,50.42501254,-2.586727601,48.8107,0.611809529,9.98091675,-1.895,0.201217678,1.770068711,86.53093646 +64.72,50.4250126,-2.586726197,48.8299,0.611809528,9.981582978,-1.9478125,0.278703287,1.682548033,86.52341134 +64.73,50.42501265,-2.586724792,48.8497,0.61180953,9.982027136,-1.9978125,0.357174842,1.593560067,86.51588629 +64.74,50.42501271,-2.586723387,48.8699,0.611809545,9.981805086,-2.045,0.436616013,1.503182564,86.50836123 +64.75,50.42501276,-2.586721983,48.8906,0.611809554,9.981805107,-2.091875,0.517010128,1.411494248,86.50083612 +64.76,50.42501282,-2.586720578,48.9117,0.611809547,9.981805128,-2.1396875,0.598340513,1.318575104,86.49331106 +64.77,50.42501287,-2.586719173,48.9334,0.611809543,9.980694803,-2.1865625,0.680590151,1.224506091,86.48578595 +64.78,50.42501293,-2.586717769,48.9555,0.611809549,9.979584478,-2.23125,0.763741797,1.129369314,86.47826089 +64.79,50.42501298,-2.586716365,48.978,0.611809554,9.979806571,-2.275,0.847778147,1.033247737,86.47073578 +64.8,50.42501304,-2.58671496,49.001,0.611809547,9.980694874,-2.3184375,0.932681612,0.936225127,86.46321073 +64.81,50.42501309,-2.586713556,49.0244,0.611809545,9.981583177,-2.36125,1.018434543,0.838386109,86.45568561 +64.82,50.42501315,-2.586712151,49.0482,0.615285743,9.982027342,-2.403125,1.105018951,0.739816054,86.44816056 +64.83,50.4250132,-2.586710746,49.0725,0.625714316,9.981583229,-2.443125,1.19241673,0.640600849,86.44063544 +64.84,50.42501326,-2.586709342,49.0971,0.6326667,9.980917047,-2.4815625,1.280609717,0.54082701,86.43311039 +64.85,50.42501332,-2.586707937,49.1221,0.629190523,9.980695004,-2.52,1.369579406,0.440581569,86.42558527 +64.86,50.42501337,-2.586706533,49.1475,0.629190525,9.980472962,-2.558125,1.459307347,0.339951903,86.41806022 +64.87,50.42501343,-2.586705128,49.1733,0.632666708,9.979806782,-2.5946875,1.549774632,0.239025845,86.41053511 +64.88,50.42501349,-2.586703724,49.1994,0.625714328,9.979362672,-2.6296875,1.64096247,0.137891289,86.40301005 +64.89,50.42501354,-2.58670232,49.2259,0.61528576,9.97980684,-2.6634375,1.732851837,0.036636583,86.39548494 +64.9,50.4250136,-2.586700915,49.2527,0.615285758,9.980473079,-2.69625,1.825423482,-0.064650151,86.38795988 +64.91,50.42501365,-2.586699511,49.2798,0.62919053,9.98047311,-2.728125,1.918658096,-0.165880449,86.38043477 +64.92,50.42501371,-2.586698106,49.3073,0.646571497,9.979806932,-2.758125,2.0125362,-0.266966132,86.37290971 +64.93,50.42501377,-2.586696702,49.335,0.646571497,9.979362824,-2.7865625,2.107038197,-0.367819023,86.3653846 +64.94,50.42501383,-2.586695298,49.363,0.632666729,9.979584925,-2.815,2.202144378,-0.468351172,86.35785954 +64.95,50.42501388,-2.586693893,49.3913,0.629190538,9.979584957,-2.8428125,2.297834861,-0.568474916,86.35033443 +64.96,50.42501394,-2.586692489,49.4199,0.632666732,9.97936292,-2.868125,2.394089651,-0.668102937,86.34280937 +64.97,50.425014,-2.586691085,49.4487,0.629190544,9.979585023,-2.8915625,2.490888636,-0.767148318,86.33528426 +64.98,50.42501405,-2.58668968,49.4777,0.63266674,9.979585056,-2.915,2.588211591,-0.86552477,86.32775921 +64.99,50.42501411,-2.586688276,49.507,0.650047706,9.97936302,-2.9378125,2.686038233,-0.963146465,86.32023409 +65,50.42501417,-2.586686872,49.5365,0.660476285,9.979585124,-2.958125,2.784348165,-1.059928319,86.31270904 +65.01,50.42501423,-2.586685467,49.5662,0.650047706,9.979585158,-2.9765625,2.88312076,-1.15578582,86.30518392 +65.02,50.42501429,-2.586684063,49.596,0.632666748,9.979363123,-2.9946875,2.98233545,-1.250635545,86.29765887 +65.03,50.42501434,-2.586682659,49.6261,0.632666755,9.979585227,-3.0115625,3.081971493,-1.344394645,86.29013375 +65.04,50.4250144,-2.586681254,49.6563,0.650047713,9.979363193,-3.02625,3.18200809,-1.436981416,86.2826087 +65.05,50.42501446,-2.58667985,49.6866,0.663952481,9.97825288,-3.04,3.282424387,-1.528315128,86.27508359 +65.06,50.42501452,-2.586678446,49.7171,0.667428687,9.977586706,-3.053125,3.383199355,-1.618316141,86.26755853 +65.07,50.42501458,-2.586677042,49.7477,0.663952499,9.97825295,-3.0646875,3.484311968,-1.706905901,86.26003342 +65.08,50.42501464,-2.586675638,49.7784,0.650047725,9.979363333,-3.0746875,3.585741082,-1.794007289,86.25250836 +65.09,50.4250147,-2.586674233,49.8092,0.632666771,9.979585439,-3.0834375,3.687465613,-1.879544216,86.24498331 +65.1,50.42501475,-2.586672829,49.8401,0.632666777,9.979141336,-3.09125,3.78946419,-1.963442196,86.23745819 +65.11,50.42501481,-2.586671425,49.871,0.650047733,9.978697233,-3.098125,3.891715613,-2.045628007,86.22993314 +65.12,50.42501487,-2.58667002,49.9021,0.663952504,9.97825313,-3.103125,3.994198454,-2.126029972,86.22240802 +65.13,50.42501493,-2.586668617,49.9331,0.667428699,9.978253166,-3.10625,4.096891398,-2.204578074,86.21488297 +65.14,50.42501499,-2.586667212,49.9642,0.667428691,9.978475271,-3.1084375,4.199772903,-2.281203673,86.20735785 +65.15,50.42501505,-2.586665808,49.9953,0.667428696,9.978031168,-3.109375,4.302821483,-2.355840077,86.1998328 +65.16,50.42501511,-2.586664404,50.0264,0.667428717,9.977364995,-3.1084375,4.406015708,-2.428422142,86.19230769 +65.17,50.42501517,-2.586663,50.0575,0.667428723,9.977142961,-3.10625,4.509333979,-2.498886611,86.18478263 +65.18,50.42501523,-2.586661596,50.0885,0.667428715,9.977142997,-3.1034375,4.612754751,-2.567172008,86.17725752 +65.19,50.42501529,-2.586660192,50.1196,0.667428718,9.977143033,-3.0996875,4.716256369,-2.633218744,86.16973246 +65.2,50.42501535,-2.586658788,50.1505,0.667428724,9.977143068,-3.094375,4.81981723,-2.696969294,86.16220735 +65.21,50.42501541,-2.586657384,50.1815,0.667428722,9.977143104,-3.086875,4.923415734,-2.758368081,86.15468229 +65.22,50.42501547,-2.58665598,50.2123,0.667428728,9.97714314,-3.0778125,5.027030224,-2.817361535,86.14715718 +65.23,50.42501553,-2.586654576,50.243,0.667428731,9.977365245,-3.0684375,5.130639041,-2.873898145,86.13963212 +65.24,50.42501559,-2.586653172,50.2737,0.667428723,9.978031489,-3.0578125,5.234220586,-2.927928753,86.13210701 +65.25,50.42501565,-2.586651768,50.3042,0.667428729,9.978253593,-3.0446875,5.337753257,-2.979406089,86.12458195 +65.26,50.42501571,-2.586650363,50.3346,0.670904941,9.97714328,-3.03,5.44121534,-3.028285347,86.11705684 +65.27,50.42501577,-2.58664896,50.3648,0.684809714,9.976032967,-3.015,5.544585349,-3.074523958,86.10953179 +65.28,50.42501583,-2.586647556,50.3949,0.702190665,9.97625507,-2.9996875,5.647841568,-3.11808147,86.10200667 +65.29,50.4250159,-2.586646152,50.4248,0.702190668,9.976921313,-2.9828125,5.750962512,-3.158920011,86.09448162 +65.3,50.42501596,-2.586644748,50.4546,0.684809712,9.977143415,-2.963125,5.853926638,-3.197003943,86.0869565 +65.31,50.42501602,-2.586643344,50.4841,0.670904937,9.977143448,-2.9415625,5.956712401,-3.232299976,86.07943145 +65.32,50.42501608,-2.58664194,50.5134,0.67090494,9.976921412,-2.92,6.059298432,-3.264777459,86.07190633 +65.33,50.42501614,-2.586640536,50.5425,0.684809722,9.976255235,-2.898125,6.161663186,-3.294407971,86.06438128 +65.34,50.4250162,-2.586639132,50.5714,0.702190684,9.975811128,-2.8746875,6.26378535,-3.321165673,86.05685617 +65.35,50.42501627,-2.586637729,50.6,0.702190687,9.97603323,-2.8496875,6.36564361,-3.34502736,86.04933111 +65.36,50.42501633,-2.586636324,50.6284,0.684809742,9.976033261,-2.8234375,6.467216651,-3.365972061,86.041806 +65.37,50.42501639,-2.586634921,50.6565,0.674381167,9.975811222,-2.79625,6.568483274,-3.383981615,86.03428094 +65.38,50.42501645,-2.586633517,50.6843,0.684809728,9.976033322,-2.768125,6.669422338,-3.399040263,86.02675583 +65.39,50.42501651,-2.586632113,50.7119,0.702190689,9.975811283,-2.738125,6.770012814,-3.411134944,86.01923077 +65.4,50.42501658,-2.586630709,50.7391,0.705666894,9.974923034,-2.70625,6.870233617,-3.420255,86.01170566 +65.41,50.42501664,-2.586629306,50.766,0.702190703,9.974923062,-2.6734375,6.970063835,-3.426392581,86.0041806 +65.42,50.4250167,-2.586627902,50.7926,0.705666889,9.975811368,-2.6396875,7.069482612,-3.429542302,85.99665549 +65.43,50.42501677,-2.586626498,50.8188,0.702190702,9.975811396,-2.6046875,7.168469265,-3.429701412,85.98913043 +65.44,50.42501683,-2.586625094,50.8447,0.688285944,9.974923146,-2.5684375,7.267002994,-3.426869797,85.98160538 +65.45,50.42501689,-2.586623691,50.8702,0.688285949,9.974923172,-2.5315625,7.365063346,-3.421049864,85.97408027 +65.46,50.42501695,-2.586622287,50.8953,0.70219072,9.975811476,-2.4946875,7.46262975,-3.412246711,85.96655521 +65.47,50.42501702,-2.586620883,50.9201,0.705666915,9.975811501,-2.4565625,7.559681868,-3.400468017,85.9590301 +65.48,50.42501708,-2.586619479,50.9445,0.702190723,9.974923248,-2.41625,7.656199416,-3.385724094,85.95150504 +65.49,50.42501714,-2.586618076,50.9684,0.709143101,9.974923272,-2.375,7.752162284,-3.368027777,85.94397993 +65.5,50.42501721,-2.586616672,50.992,0.719571671,9.975811574,-2.333125,7.84755036,-3.347394478,85.93645487 +65.51,50.42501727,-2.586615268,51.0151,0.71957168,9.975811597,-2.2896875,7.942343821,-3.323842245,85.92892976 +65.52,50.42501734,-2.586613864,51.0378,0.70914312,9.97470127,-2.245,8.036522727,-3.297391477,85.9214047 +65.53,50.4250174,-2.586612461,51.06,0.702190738,9.973813013,-2.1996875,8.130067541,-3.268065434,85.91387959 +65.54,50.42501746,-2.586611057,51.0818,0.709143125,9.973813033,-2.1534375,8.222958725,-3.2358895,85.90635453 +65.55,50.42501753,-2.586609654,51.1031,0.719571715,9.974479262,-2.10625,8.315176797,-3.200891862,85.89882942 +65.56,50.42501759,-2.58660825,51.1239,0.723047907,9.97492342,-2.0584375,8.406702508,-3.163103004,85.89130436 +65.57,50.42501766,-2.586606846,51.1443,0.723047891,9.974701369,-2.01,8.497516777,-3.122555869,85.88377925 +65.58,50.42501772,-2.586605443,51.1641,0.723047892,9.974701386,-1.96125,8.587600696,-3.079285868,85.8762542 +65.59,50.42501779,-2.586604039,51.1835,0.723047905,9.974701402,-1.9115625,8.676935302,-3.033330642,85.86872908 +65.6,50.42501785,-2.586602635,51.2024,0.723047905,9.97359107,-1.8596875,8.765502087,-2.984730299,85.86120403 +65.61,50.42501792,-2.586601232,51.2207,0.723047898,9.972480738,-1.8065625,8.853282487,-2.933527181,85.85367891 +65.62,50.42501798,-2.586599829,51.2385,0.723047902,9.972702822,-1.7534375,8.940258167,-2.879766035,85.84615386 +65.63,50.42501805,-2.586598425,51.2558,0.723047911,9.973369043,-1.6996875,9.026410966,-2.82349373,85.83862875 +65.64,50.42501811,-2.586597022,51.2725,0.723047913,9.973591125,-1.645,9.11172295,-2.764759254,85.83110369 +65.65,50.42501818,-2.586595618,51.2887,0.723047906,9.973591137,-1.59,9.196176184,-2.703613828,85.82357858 +65.66,50.42501824,-2.586594215,51.3043,0.723047899,9.973591147,-1.535,9.279753136,-2.640110853,85.81605352 +65.67,50.42501831,-2.586592811,51.3194,0.726524099,9.973591157,-1.4796875,9.362436332,-2.574305676,85.80852841 +65.68,50.42501837,-2.586591408,51.3339,0.736952691,9.973591166,-1.423125,9.444208467,-2.506255651,85.80100335 +65.69,50.42501844,-2.586590004,51.3479,0.743905075,9.973591174,-1.365,9.525052526,-2.436020135,85.79347824 +65.7,50.42501851,-2.586588601,51.3612,0.736952683,9.973369111,-1.3065625,9.604951548,-2.363660378,85.78595318 +65.71,50.42501857,-2.586587197,51.374,0.72652411,9.972702908,-1.248125,9.68388886,-2.289239463,85.77842807 +65.72,50.42501864,-2.586585794,51.3862,0.726524118,9.972258774,-1.188125,9.761848018,-2.212822306,85.77090301 +65.73,50.4250187,-2.586584391,51.3978,0.736952696,9.972480848,-1.126875,9.838812751,-2.134475484,85.7633779 +65.74,50.42501877,-2.586582987,51.4087,0.743905075,9.972480851,-1.066875,9.914766959,-2.054267466,85.75585284 +65.75,50.42501884,-2.586581584,51.4191,0.740428882,9.972258784,-1.008125,9.98969477,-1.972268038,85.74832773 +65.76,50.4250189,-2.586580181,51.4289,0.743905085,9.972480855,-0.9478125,10.06358054,-1.888548763,85.74080268 +65.77,50.42501897,-2.586578777,51.4381,0.757809857,9.972480855,-0.885,10.13640886,-1.803182635,85.73327762 +65.78,50.42501904,-2.586577374,51.4466,0.757809845,9.972258785,-0.821875,10.20816449,-1.716244139,85.72575251 +65.79,50.42501911,-2.586575971,51.4545,0.74390507,9.972480853,-0.76,10.27883248,-1.62780902,85.71822745 +65.8,50.42501917,-2.586574567,51.4618,0.740428887,9.97248085,-0.698125,10.34839803,-1.537954456,85.71070234 +65.81,50.42501924,-2.586573164,51.4685,0.743905089,9.972258776,-0.6346875,10.41684661,-1.446758712,85.70317728 +65.82,50.42501931,-2.586571761,51.4745,0.740428898,9.972480841,-0.5703125,10.48416399,-1.354301429,85.69565217 +65.83,50.42501937,-2.586570357,51.4799,0.743905082,9.972258766,-0.5065625,10.55033609,-1.260663166,85.68812711 +65.84,50.42501944,-2.586568954,51.4846,0.761286035,9.971148411,-0.4434375,10.61534904,-1.165925568,85.680602 +65.85,50.42501951,-2.586567551,51.4888,0.771714619,9.970482194,-0.38,10.67918932,-1.070171315,85.67307694 +65.86,50.42501958,-2.586566148,51.4922,0.761286056,9.971148394,-0.31625,10.74184357,-0.973483827,85.66555183 +65.87,50.42501965,-2.586564745,51.4951,0.743905092,9.972258733,-0.251875,10.80329868,-0.875947446,85.65802678 +65.88,50.42501971,-2.586563341,51.4973,0.743905082,9.972258722,-0.1865625,10.86354187,-0.777647197,85.65050166 +65.89,50.42501978,-2.586561938,51.4988,0.761286039,9.971148362,-0.121875,10.92256053,-0.678668852,85.64297661 +65.9,50.42501985,-2.586560535,51.4997,0.775190813,9.97026007,-0.0584375,10.98034235,-0.579098699,85.63545149 +65.91,50.42501992,-2.586559132,51.5,0.778667017,9.970037986,0.0053125,11.03687524,-0.479023599,85.62792644 +65.92,50.42501999,-2.586557729,51.4996,0.775190826,9.970037971,0.07,11.09214744,-0.378530755,85.62040132 +65.93,50.42502006,-2.586556326,51.4986,0.761286044,9.970037955,0.1346875,11.14614734,-0.277707773,85.61287627 +65.94,50.42502013,-2.586554923,51.4969,0.743905075,9.970260008,0.1984375,11.1988637,-0.176642716,85.60535116 +65.95,50.42502019,-2.58655352,51.4946,0.743905083,9.970926199,0.261875,11.25028551,-0.075423534,85.5978261 +65.96,50.42502026,-2.586552117,51.4917,0.761286054,9.97114825,0.326875,11.30040202,0.025861367,85.59030099 +65.97,50.42502033,-2.586550713,51.4881,0.775190823,9.970037882,0.393125,11.34920278,0.127123693,85.58277593 +65.98,50.4250204,-2.586549311,51.4838,0.778667006,9.968927513,0.4578125,11.39667761,0.228275209,85.57525082 +65.99,50.42502047,-2.586547908,51.4789,0.778666996,9.96914956,0.52,11.44281652,0.329227622,85.56772576 +66,50.42502054,-2.586546505,51.4734,0.778667002,9.969815745,0.581875,11.48760996,0.429892984,85.56020065 +66.01,50.42502061,-2.586545102,51.4673,0.778667015,9.97003779,0.645,11.53104853,0.530183459,85.55267559 +66.02,50.42502068,-2.586543699,51.4605,0.77866701,9.970037765,0.7084375,11.57312322,0.630011615,85.54515048 +66.03,50.42502075,-2.586542296,51.4531,0.778666991,9.970037739,0.77125,11.61382517,0.729290361,85.53762542 +66.04,50.42502082,-2.586540893,51.4451,0.778666983,9.970037712,0.8334375,11.65314589,0.827933181,85.53010031 +66.05,50.42502089,-2.58653949,51.4364,0.778666996,9.970037684,0.895,11.69107724,0.925854075,85.52257526 +66.06,50.42502096,-2.586538087,51.4272,0.77866701,9.970037654,0.9565625,11.72761121,1.022967556,85.51505014 +66.07,50.42502103,-2.586536684,51.4173,0.778667007,9.969815555,1.0184375,11.76274017,1.119189,85.50752509 +66.08,50.4250211,-2.586535281,51.4068,0.778666994,9.969149315,1.0796875,11.79645684,1.214434467,85.49999997 +66.09,50.42502117,-2.586533878,51.3957,0.778666986,9.968705144,1.14,11.82875419,1.308620994,85.49247492 +66.1,50.42502124,-2.586532476,51.384,0.782143175,9.96892718,1.1996875,11.85962538,1.401666303,85.48494981 +66.11,50.42502131,-2.586531072,51.3717,0.796047951,9.968927146,1.2584375,11.88906407,1.493489379,85.47742475 +66.12,50.42502138,-2.58652967,51.3588,0.813428925,9.968482972,1.3165625,11.91706406,1.584010121,85.46989969 +66.13,50.42502146,-2.586528267,51.3454,0.813428921,9.968260865,1.375,11.94361956,1.673149577,85.46237458 +66.14,50.42502153,-2.586526864,51.3313,0.796047947,9.968482898,1.433125,11.96872491,1.760830053,85.45484952 +66.15,50.4250216,-2.586525462,51.3167,0.782143169,9.968927,1.4896875,11.99237495,1.846975003,85.44732441 +66.16,50.42502167,-2.586524058,51.3015,0.778666973,9.968704893,1.545,12.01456469,1.931509425,85.43979936 +66.17,50.42502174,-2.586522656,51.2858,0.782143172,9.967594505,1.6,12.03528955,2.014359466,85.43227424 +66.18,50.42502181,-2.586521253,51.2695,0.796047952,9.966928256,1.655,12.05454522,2.09545299,85.42474919 +66.19,50.42502188,-2.586519851,51.2527,0.813428907,9.967594422,1.7096875,12.0723276,2.174719295,85.41722407 +66.2,50.42502196,-2.586518448,51.2353,0.813428887,9.968704728,1.7634375,12.088633,2.252089166,85.40969902 +66.21,50.42502203,-2.586517045,51.2174,0.796047915,9.968704684,1.81625,12.10345806,2.327495168,85.4021739 +66.22,50.4250221,-2.586515642,51.199,0.78561934,9.967816363,1.8684375,12.11679967,2.400871581,85.39464885 +66.23,50.42502217,-2.58651424,51.18,0.796047921,9.967594249,1.9196875,12.12865497,2.472154406,85.38712374 +66.24,50.42502224,-2.586512837,51.1606,0.813428886,9.967816274,1.97,12.13902155,2.54128142,85.37959868 +66.25,50.42502232,-2.586511434,51.1406,0.816905087,9.967372088,2.02,12.1478973,2.608192463,85.37207357 +66.26,50.42502239,-2.586510032,51.1202,0.813428894,9.966705832,2.069375,12.15528026,2.672829092,85.36454851 +66.27,50.42502246,-2.586508629,51.0992,0.816905068,9.966705784,2.1165625,12.16116895,2.735134986,85.3570234 +66.28,50.42502254,-2.586507227,51.0778,0.813428858,9.967371943,2.1615625,12.1655621,2.795055829,85.34949834 +66.29,50.42502261,-2.586505824,51.056,0.799524087,9.967816033,2.206875,12.1684588,2.85253931,85.34197323 +66.3,50.42502268,-2.586504421,51.0337,0.799524099,9.967371845,2.253125,12.16985848,2.907535294,85.33444817 +66.31,50.42502275,-2.586503019,51.0109,0.81342888,9.966483516,2.2978125,12.16976079,2.95999594,85.32692306 +66.32,50.42502283,-2.586501616,50.9877,0.816905067,9.965595185,2.34,12.16816585,3.009875411,85.319398 +66.33,50.4250229,-2.586500214,50.9641,0.813428861,9.965373063,2.3815625,12.16507388,3.057130163,85.31187289 +66.34,50.42502297,-2.586498812,50.9401,0.820381236,9.966483358,2.423125,12.16048564,3.101719113,85.30434784 +66.35,50.42502305,-2.586497409,50.9156,0.830809804,9.967371583,2.463125,12.15440197,3.143603302,85.29682272 +66.36,50.42502312,-2.586496006,50.8908,0.830809803,9.966483251,2.50125,12.1468242,3.182746232,85.28929767 +66.37,50.4250232,-2.586494604,50.8656,0.820381235,9.965594917,2.5384375,12.13775394,3.219113754,85.28177255 +66.38,50.42502327,-2.586493202,50.84,0.813428856,9.96648314,2.575,12.12719301,3.252674126,85.2742475 +66.39,50.42502334,-2.586491799,50.8141,0.820381237,9.967371363,2.61125,12.11514365,3.283398186,85.26672238 +66.4,50.42502342,-2.586490396,50.7878,0.830809801,9.966483028,2.6465625,12.10160844,3.311259004,85.25919733 +66.41,50.42502349,-2.586488994,50.7611,0.834285976,9.965372623,2.6796875,12.08659012,3.3362324,85.25167222 +66.42,50.42502357,-2.586487592,50.7342,0.834285964,9.965372566,2.7115625,12.0700918,3.358296547,85.24414716 +66.43,50.42502364,-2.586486189,50.7069,0.83428596,9.965150438,2.743125,12.05211709,3.377432191,85.23662205 +66.44,50.42502372,-2.586484787,50.6793,0.834285965,9.9642621,2.7728125,12.03266958,3.393622661,85.22909699 +66.45,50.42502379,-2.586483385,50.6514,0.834285975,9.964262041,2.8,12.01175336,3.40685386,85.22157188 +66.46,50.42502387,-2.586481983,50.6233,0.83428598,9.965372329,2.8265625,11.98937288,3.417114217,85.21404682 +66.47,50.42502394,-2.58648058,50.5949,0.834285977,9.966260547,2.8534375,11.96553274,3.424394849,85.20652177 +66.48,50.42502402,-2.586479178,50.5662,0.834285964,9.966260487,2.8796875,11.94023791,3.428689282,85.19899665 +66.49,50.42502409,-2.586477775,50.5373,0.834285947,9.965372148,2.904375,11.91349373,3.429993907,85.1914716 +66.5,50.42502417,-2.586476373,50.5081,0.834285934,9.96403967,2.9265625,11.88530575,3.42830752,85.18394648 +66.51,50.42502424,-2.586474971,50.4787,0.83428593,9.96315133,2.9465625,11.85567982,3.423631554,85.17642143 +66.52,50.42502432,-2.586473569,50.4492,0.837762127,9.963151267,2.9665625,11.82462225,3.415970192,85.16889632 +66.53,50.42502439,-2.586472167,50.4194,0.848190712,9.964039484,2.98625,11.79213938,3.405329965,85.16137126 +66.54,50.42502447,-2.586470765,50.3894,0.855143098,9.965149769,3.003125,11.7582381,3.391720326,85.15384615 +66.55,50.42502455,-2.586469362,50.3593,0.848190704,9.965149706,3.018125,11.72292539,3.375153022,85.14632109 +66.56,50.42502462,-2.58646796,50.3291,0.837762114,9.964039295,3.0334375,11.68620871,3.355642549,85.13879598 +66.57,50.4250247,-2.586466558,50.2986,0.837762107,9.963373023,3.0478125,11.64809573,3.333205866,85.13127092 +66.58,50.42502477,-2.586465156,50.2681,0.848190681,9.964039168,3.0596875,11.60859435,3.307862624,85.12374581 +66.59,50.42502485,-2.586463754,50.2374,0.855143058,9.965149451,3.07,11.5677129,3.279634827,85.11622075 +66.6,50.42502493,-2.586462351,50.2067,0.851666862,9.965149387,3.0796875,11.52545978,3.248547169,85.10869564 +66.61,50.425025,-2.586460949,50.1758,0.855143052,9.964038976,3.088125,11.481844,3.214626749,85.10117058 +66.62,50.42502508,-2.586459547,50.1449,0.869047812,9.963150634,3.0946875,11.43687449,3.177903134,85.09364547 +66.63,50.42502516,-2.586458145,50.1139,0.86904781,9.962928499,3.1,11.39056077,3.138408294,85.08612042 +66.64,50.42502524,-2.586456743,50.0829,0.855143051,9.962928434,3.1046875,11.34291245,3.096176721,85.0785953 +66.65,50.42502531,-2.586455341,50.0518,0.851666861,9.96292837,3.108125,11.29393945,3.051245256,85.07107025 +66.66,50.42502539,-2.586453939,50.0207,0.855143042,9.962706236,3.109375,11.24365209,3.003653032,85.06354513 +66.67,50.42502547,-2.586452537,49.9896,0.851666833,9.961817893,3.1084375,11.19206085,2.953441647,85.05602008 +66.68,50.42502554,-2.586451135,49.9585,0.855143012,9.960707481,3.1065625,11.13917645,2.900654759,85.04849496 +66.69,50.42502562,-2.586449734,49.9275,0.872523965,9.960707416,3.1046875,11.08500994,2.845338434,85.04096991 +66.7,50.4250257,-2.586448332,49.8964,0.882952542,9.961817698,3.1015625,11.02957266,2.787540972,85.0334448 +66.71,50.42502578,-2.58644693,49.8654,0.87252397,9.962705912,3.09625,10.97287619,2.727312737,85.02591974 +66.72,50.42502586,-2.586445528,49.8345,0.855143015,9.962927917,3.09,10.91493234,2.664706212,85.01839463 +66.73,50.42502593,-2.586444126,49.8036,0.855143022,9.962927853,3.083125,10.85575325,2.599776056,85.01086957 +66.74,50.42502601,-2.586442724,49.7728,0.872523977,9.962705719,3.074375,10.79535129,2.532578879,85.00334446 +66.75,50.42502609,-2.586441322,49.7421,0.886428723,9.961817376,3.0634375,10.73373902,2.463173178,84.9958194 +66.76,50.42502617,-2.58643992,49.7115,0.889904895,9.960706964,3.05125,10.67092933,2.39161963,84.98829429 +66.77,50.42502625,-2.586438519,49.6811,0.886428697,9.9607069,3.038125,10.60693533,2.317980516,84.98076923 +66.78,50.42502633,-2.586437117,49.6507,0.872523934,9.961817185,3.0234375,10.54177037,2.242320064,84.97324412 +66.79,50.42502641,-2.586435715,49.6206,0.855142978,9.96248333,3.0078125,10.47544816,2.164704336,84.96571906 +66.8,50.42502648,-2.586434313,49.5906,0.855142969,9.961817058,2.9915625,10.40798238,2.085200942,84.95819395 +66.81,50.42502656,-2.586432911,49.5607,0.872523915,9.960706647,2.973125,10.3393873,2.003879208,84.9506689 +66.82,50.42502664,-2.58643151,49.5311,0.886428676,9.960706585,2.953125,10.26967707,1.920810011,84.94314384 +66.83,50.42502672,-2.586430108,49.5017,0.88990487,9.961594801,2.933125,10.19886642,1.836065886,84.93561873 +66.84,50.4250268,-2.586428706,49.4724,0.889904873,9.961594739,2.91125,10.12697001,1.749720688,84.92809367 +66.85,50.42502688,-2.586427304,49.4434,0.889904873,9.960706398,2.8865625,10.05400287,1.661849704,84.92056856 +66.86,50.42502696,-2.586425903,49.4147,0.889904873,9.960484266,2.8615625,9.979980328,1.572529594,84.9130435 +66.87,50.42502704,-2.586424501,49.3862,0.889904869,9.960706274,2.8365625,9.904917757,1.481838167,84.90551839 +66.88,50.42502712,-2.586423099,49.3579,0.889904861,9.960484145,2.8096875,9.828830853,1.389854549,84.89799333 +66.89,50.4250272,-2.586421698,49.33,0.889904853,9.960484085,2.7815625,9.751735485,1.29665901,84.89046822 +66.9,50.42502728,-2.586420296,49.3023,0.889904842,9.960706095,2.753125,9.673647812,1.202332739,84.88294316 +66.91,50.42502736,-2.586418894,49.2749,0.889904832,9.960261896,2.7228125,9.594584105,1.106958013,84.87541805 +66.92,50.42502744,-2.586417493,49.2478,0.889904828,9.959595628,2.69,9.514560866,1.010617967,84.867893 +66.93,50.42502752,-2.586416091,49.2211,0.889904831,9.9593735,2.6565625,9.433594825,0.913396712,84.86036788 +66.94,50.4250276,-2.58641469,49.1947,0.889904832,9.959373441,2.623125,9.351702884,0.815378931,84.85284283 +66.95,50.42502768,-2.586413288,49.1686,0.893381015,9.959595454,2.588125,9.268902118,0.71665011,84.84531771 +66.96,50.42502776,-2.586411887,49.1429,0.907285769,9.960261606,2.5515625,9.185209886,0.617296363,84.83779266 +66.97,50.42502784,-2.586410485,49.1176,0.924666721,9.960483619,2.5146875,9.100643607,0.517404323,84.83026754 +66.98,50.42502793,-2.586409083,49.0926,0.924666724,9.959373216,2.4765625,9.015220986,0.417061136,84.82274249 +66.99,50.42502801,-2.586407682,49.068,0.907285769,9.958262812,2.43625,8.928959783,0.316354235,84.81521738 +67,50.42502809,-2.586406281,49.0439,0.893381,9.958262757,2.395,8.841878105,0.215371455,84.80769232 +67.01,50.42502817,-2.586404879,49.0201,0.889904807,9.958262703,2.3534375,8.753994115,0.114200916,84.80016721 +67.02,50.42502825,-2.586403478,48.9968,0.893381006,9.95804058,2.31125,8.665326146,0.012930741,84.79264215 +67.03,50.42502833,-2.586402077,48.9739,0.907285774,9.958484666,2.2684375,8.575892705,-0.088350665,84.78511704 +67.04,50.42502841,-2.586400675,48.9514,0.924666719,9.959150822,2.224375,8.485712471,-0.189555065,84.77759198 +67.05,50.4250285,-2.586399274,48.9294,0.924666702,9.959150771,2.178125,8.394804295,-0.29059411,84.77006687 +67.06,50.42502858,-2.586397872,48.9078,0.910761927,9.958262443,2.1303125,8.303187197,-0.39137985,84.76254181 +67.07,50.42502866,-2.586396471,48.8868,0.910761923,9.957152046,2.083125,8.210880259,-0.491824221,84.7550167 +67.08,50.42502874,-2.58639507,48.8662,0.924666691,9.957151996,2.0365625,8.11790273,-0.591839734,84.74749164 +67.09,50.42502883,-2.586393669,48.846,0.924666693,9.958040225,1.9878125,8.024274093,-0.691339183,84.73996653 +67.1,50.42502891,-2.586392267,48.8264,0.910761922,9.958262247,1.9365625,7.930013884,-0.79023571,84.73244148 +67.11,50.42502899,-2.586390866,48.8073,0.910761912,9.958040131,1.885,7.835141756,-0.888443197,84.72491636 +67.12,50.42502907,-2.586389465,48.7887,0.924666671,9.958262154,1.8334375,7.739677533,-0.98587593,84.71739131 +67.13,50.42502916,-2.586388063,48.7706,0.924666668,9.958040038,1.78125,7.643641213,-1.082448998,84.70986619 +67.14,50.42502924,-2.586386662,48.7531,0.910761905,9.956929645,1.7284375,7.54705279,-1.178078118,84.70234114 +67.15,50.42502932,-2.586385261,48.736,0.910761909,9.956041323,1.6746875,7.449932433,-1.272679924,84.69481608 +67.16,50.4250294,-2.58638386,48.7196,0.928142865,9.956041281,1.6196875,7.352300424,-1.366171969,84.68729097 +67.17,50.42502949,-2.586382459,48.7036,0.942047622,9.956929517,1.56375,7.254177162,-1.458472662,84.67976591 +67.18,50.42502957,-2.586381058,48.6883,0.942047613,9.958039823,1.5078125,7.155583158,-1.549501561,84.6722408 +67.19,50.42502966,-2.586379656,48.6735,0.931619038,9.958039782,1.451875,7.056539038,-1.639179253,84.66471574 +67.2,50.42502974,-2.586378255,48.6592,0.924666661,9.956929395,1.3946875,6.957065371,-1.727427588,84.65719063 +67.21,50.42502982,-2.586376854,48.6456,0.928142854,9.956041079,1.3365625,6.857183014,-1.814169559,84.64966558 +67.22,50.42502991,-2.586375453,48.6325,0.928142848,9.955818971,1.2784375,6.756912821,-1.899329537,84.64214046 +67.23,50.42502999,-2.586374052,48.62,0.924666649,9.955818934,1.2196875,6.656275707,-1.982833323,84.63461541 +67.24,50.42503007,-2.586372651,48.6081,0.931619026,9.955818898,1.1596875,6.555292697,-2.064607979,84.62709029 +67.25,50.42503016,-2.58637125,48.5968,0.942047597,9.955818863,1.0984375,6.453984936,-2.144582288,84.61956524 +67.26,50.42503024,-2.586369849,48.5861,0.945523789,9.955818829,1.036875,6.352373449,-2.222686519,84.61204012 +67.27,50.42503033,-2.586368448,48.5761,0.945523794,9.955818795,0.9765625,6.250479551,-2.298852549,84.60451507 +67.28,50.42503041,-2.586367047,48.5666,0.945523797,9.955818762,0.9165625,6.148324557,-2.373013857,84.59698996 +67.29,50.4250305,-2.586365646,48.5577,0.945523791,9.955818731,0.8546875,6.045929722,-2.445105928,84.5894649 +67.3,50.42503058,-2.586364245,48.5495,0.945523783,9.9558187,0.791875,5.943316476,-2.515065851,84.58193979 +67.31,50.42503067,-2.586362844,48.5419,0.94552378,9.95581867,0.73,5.84050619,-2.582832549,84.57441473 +67.32,50.42503075,-2.586361443,48.5349,0.945523779,9.955596572,0.668125,5.737520407,-2.648347007,84.56688962 +67.33,50.42503084,-2.586360042,48.5285,0.94552378,9.954708267,0.6046875,5.634380555,-2.711552044,84.55936456 +67.34,50.42503092,-2.586358641,48.5228,0.945523786,9.953597892,0.54,5.531108293,-2.772392598,84.55183945 +67.35,50.42503101,-2.586357241,48.5177,0.94552379,9.953597867,0.4753125,5.427725049,-2.830815558,84.54431439 +67.36,50.42503109,-2.58635584,48.5133,0.945523785,9.95448612,0.4115625,5.324252538,-2.886770043,84.53678928 +67.37,50.42503118,-2.586354439,48.5095,0.948999968,9.954486096,0.3484375,5.220712304,-2.940207181,84.52926422 +67.38,50.42503126,-2.586353038,48.5063,0.959428538,9.953597795,0.2846875,5.117125946,-2.99108039,84.52173911 +67.39,50.42503135,-2.586351638,48.5038,0.966380919,9.953375704,0.22,5.013515123,-3.039345381,84.51421406 +67.4,50.42503144,-2.586350237,48.5019,0.959428539,9.953597752,0.1553125,4.909901493,-3.084960041,84.50668894 +67.41,50.42503152,-2.586348836,48.5007,0.948999974,9.953375663,0.0915625,4.806306656,-3.127884492,84.49916389 +67.42,50.42503161,-2.586347436,48.5001,0.948999978,9.953597713,0.0284375,4.702752326,-3.168081434,84.49163877 +67.43,50.42503169,-2.586346035,48.5001,0.959428546,9.954485973,-0.0353125,4.599260048,-3.205515746,84.48411372 +67.44,50.42503178,-2.586344634,48.5008,0.966380921,9.954485956,-0.1,4.495851422,-3.240154827,84.4765886 +67.45,50.42503187,-2.586343233,48.5021,0.962904728,9.953597662,-0.165,4.392548106,-3.271968423,84.46906355 +67.46,50.42503195,-2.586341833,48.5041,0.966380919,9.953597647,-0.23,4.289371642,-3.300928804,84.46153844 +67.47,50.42503204,-2.586340432,48.5067,0.980285685,9.95448591,-0.295,4.186343632,-3.327010759,84.45401338 +67.48,50.42503213,-2.586339031,48.51,0.980285692,9.954485897,-0.36,4.083485504,-3.350191486,84.44648827 +67.49,50.42503222,-2.58633763,48.5139,0.966380934,9.953375538,-0.4246875,3.980818744,-3.370450758,84.43896321 +67.5,50.4250323,-2.58633623,48.5185,0.962904739,9.95226518,-0.488125,3.878364894,-3.387770985,84.43143816 +67.51,50.42503239,-2.586334829,48.5237,0.966380924,9.951376892,-0.55,3.77614527,-3.402137043,84.42391304 +67.52,50.42503248,-2.586333429,48.5295,0.962904732,9.951154814,-0.611875,3.674181185,-3.413536382,84.41638799 +67.53,50.42503256,-2.586332029,48.5359,0.966380924,9.952265153,-0.675,3.572494011,-3.421959033,84.40886287 +67.54,50.42503265,-2.586330628,48.543,0.983761881,9.953375492,-0.7384375,3.471104947,-3.427397721,84.40133782 +67.55,50.42503274,-2.586329227,48.5507,0.994190461,9.953153416,-0.80125,3.370035192,-3.429847688,84.3938127 +67.56,50.42503283,-2.586327827,48.559,0.983761894,9.952265132,-0.8634375,3.269305831,-3.429306701,84.38628765 +67.57,50.42503292,-2.586326426,48.568,0.966380938,9.95137685,-0.925,3.168937892,-3.425775391,84.37876254 +67.58,50.425033,-2.586325026,48.5775,0.966380933,9.950932708,-0.9865625,3.068952345,-3.419256678,84.37123748 +67.59,50.42503309,-2.586323626,48.5877,0.983761886,9.951154774,-1.0484375,2.969370045,-3.40975635,84.36371237 +67.6,50.42503318,-2.586322225,48.5985,0.997666651,9.951154772,-1.1096875,2.870211849,-3.397282715,84.35618731 +67.61,50.42503327,-2.586320825,48.6099,1.001142843,9.950932702,-1.1696875,2.77149844,-3.381846545,84.3486622 +67.62,50.42503336,-2.586319425,48.6219,0.997666654,9.951376841,-1.2284375,2.673250388,-3.36346136,84.34113714 +67.63,50.42503345,-2.586318024,48.6345,0.983761895,9.952043051,-1.2865625,2.575488318,-3.342143205,84.33361203 +67.64,50.42503354,-2.586316624,48.6476,0.96638095,9.952043053,-1.345,2.478232514,-3.317910585,84.32608697 +67.65,50.42503362,-2.586315223,48.6614,0.966380956,9.951154778,-1.403125,2.381503373,-3.290784758,84.31856186 +67.66,50.42503371,-2.586313823,48.6757,0.983761908,9.949822365,-1.4596875,2.285321062,-3.260789329,84.3110368 +67.67,50.4250338,-2.586312423,48.6906,0.997666667,9.949156161,-1.5153125,2.189705693,-3.227950425,84.30351169 +67.68,50.42503389,-2.586311023,48.706,1.001142858,9.949822375,-1.5715625,2.094677205,-3.192296693,84.29598664 +67.69,50.42503398,-2.586309623,48.722,1.001142861,9.950932728,-1.628125,2.000255422,-3.153859247,84.28846152 +67.7,50.42503407,-2.586308222,48.7386,1.001142866,9.950932735,-1.683125,1.906460169,-3.112671603,84.28093647 +67.71,50.42503416,-2.586306822,48.7557,1.001142873,9.949822395,-1.7365625,1.813310925,-3.068769628,84.27341135 +67.72,50.42503425,-2.586305422,48.7733,1.001142871,9.949156196,-1.79,1.720827171,-3.022191655,84.2658863 +67.73,50.42503434,-2.586304022,48.7915,1.001142859,9.949822414,-1.843125,1.629028217,-2.972978247,84.25836118 +67.74,50.42503443,-2.586302622,48.8102,1.001142855,9.950932772,-1.894375,1.537933314,-2.921172434,84.25083613 +67.75,50.42503452,-2.586301221,48.8294,1.001142867,9.950932782,-1.9434375,1.447561368,-2.866819252,84.24331102 +67.76,50.42503461,-2.586299821,48.8491,1.001142879,9.949822446,-1.991875,1.357931288,-2.809966197,84.23578596 +67.77,50.4250347,-2.586298421,48.8692,1.001142884,9.948934181,-2.0415625,1.26906181,-2.750662773,84.22826085 +67.78,50.42503479,-2.586297021,48.8899,1.001142887,9.948712125,-2.0915625,1.180971555,-2.688960776,84.22073579 +67.79,50.42503488,-2.586295621,48.9111,1.001142891,9.948712139,-2.139375,1.093678799,-2.624913949,84.21321068 +67.8,50.42503497,-2.586294221,48.9327,1.004619085,9.948712154,-2.185,1.007201821,-2.558578156,84.20568562 +67.81,50.42503506,-2.586292821,48.9548,1.018523855,9.94871217,-2.23,0.921558725,-2.490011209,84.19816051 +67.82,50.42503515,-2.586291421,48.9773,1.03590482,9.948712185,-2.2746875,0.836767331,-2.41927298,84.19063545 +67.83,50.42503525,-2.586290021,49.0003,1.035904828,9.948712201,-2.318125,0.752845401,-2.346425063,84.18311034 +67.84,50.42503534,-2.586288621,49.0237,1.018523872,9.948712218,-2.36,0.669810409,-2.271531057,84.17558528 +67.85,50.42503543,-2.586287221,49.0475,1.004619105,9.948712236,-2.4015625,0.587679716,-2.194656278,84.16806023 +67.86,50.42503552,-2.586285821,49.0717,1.001142916,9.948490186,-2.443125,0.506470512,-2.115867706,84.16053512 +67.87,50.42503561,-2.586284421,49.0964,1.004619109,9.947601928,-2.4828125,0.426199698,-2.035234037,84.15301006 +67.88,50.4250357,-2.586283021,49.1214,1.018523868,9.9464916,-2.5196875,0.346884062,-1.952825632,84.14548495 +67.89,50.42503579,-2.586281622,49.1468,1.035904817,9.946491619,-2.5553125,0.268540219,-1.868714339,84.13795989 +67.9,50.42503589,-2.586280222,49.1725,1.035904821,9.947601987,-2.5915625,0.191184442,-1.782973497,84.13043478 +67.91,50.42503598,-2.586278822,49.1986,1.018523881,9.948490287,-2.628125,0.114832889,-1.695677877,84.12290972 +67.92,50.42503607,-2.586277422,49.2251,1.00809532,9.948490309,-2.6628125,0.039501601,-1.606903567,84.11538461 +67.93,50.42503616,-2.586276022,49.2519,1.0185239,9.947602054,-2.695,-0.034793779,-1.516728031,84.10785955 +67.94,50.42503625,-2.586274622,49.279,1.035904863,9.946491729,-2.7265625,-0.108037724,-1.425229937,84.10033444 +67.95,50.42503635,-2.586273223,49.3064,1.039381065,9.946491752,-2.758125,-0.180214879,-1.332488983,84.09280938 +67.96,50.42503644,-2.586271823,49.3342,1.035904883,9.947380054,-2.7878125,-0.251310232,-1.238586071,84.08528427 +67.97,50.42503653,-2.586270423,49.3622,1.039381074,9.947380078,-2.8146875,-0.321308945,-1.143603075,84.07775921 +67.98,50.42503663,-2.586269023,49.3905,1.035904881,9.946269755,-2.84,-0.390196348,-1.047622847,84.0702341 +67.99,50.42503672,-2.586267624,49.419,1.022000118,9.945381502,-2.865,-0.457958061,-0.950729095,84.06270905 +68,50.42503681,-2.586266224,49.4478,1.022000121,9.945381527,-2.89,-0.524579932,-0.85300633,84.05518393 +68.01,50.4250369,-2.586264825,49.4768,1.035904882,9.946047762,-2.914375,-0.590048095,-0.754539694,84.04765888 +68.02,50.425037,-2.586263425,49.5061,1.039381067,9.946491927,-2.9365625,-0.654348856,-0.655415074,84.04013376 +68.03,50.42503709,-2.586262025,49.5356,1.03590488,9.946047814,-2.95625,-0.717468752,-0.555718927,84.03260871 +68.04,50.42503718,-2.586260626,49.5652,1.042857279,9.945381632,-2.975,-0.779394661,-0.455538174,84.0250836 +68.05,50.42503728,-2.586259226,49.5951,1.053285866,9.94515959,-2.9934375,-0.840113634,-0.354960246,84.01755854 +68.06,50.42503737,-2.586257827,49.6251,1.053285874,9.945159617,-3.01125,-0.899612894,-0.254072748,84.01003343 +68.07,50.42503747,-2.586256427,49.6553,1.042857307,9.945159643,-3.0278125,-0.957880181,-0.152963688,84.00250837 +68.08,50.42503756,-2.586255028,49.6857,1.035904936,9.945159671,-3.0415625,-1.014903175,-0.051721244,83.99498326 +68.09,50.42503765,-2.586253628,49.7162,1.042857328,9.945159699,-3.053125,-1.070670074,0.04956635,83.9874582 +68.1,50.42503775,-2.586252229,49.7467,1.053285903,9.945159728,-3.0646875,-1.12516919,0.150810628,83.97993309 +68.11,50.42503784,-2.586250829,49.7775,1.05676209,9.945159755,-3.075,-1.178389119,0.251923469,83.97240803 +68.12,50.42503794,-2.58624943,49.8083,1.056762084,9.944937713,-3.0828125,-1.230318805,0.352816581,83.96488292 +68.13,50.42503803,-2.58624803,49.8391,1.056762078,9.944271533,-3.0903125,-1.280947361,0.453402072,83.95735786 +68.14,50.42503813,-2.586246631,49.8701,1.056762084,9.943827423,-3.0978125,-1.330264188,0.553592165,83.94983275 +68.15,50.42503822,-2.586245232,49.9011,1.0567621,9.94404952,-3.1028125,-1.378259029,0.653299541,83.9423077 +68.16,50.42503832,-2.586243832,49.9322,1.056762114,9.944049549,-3.105,-1.424921858,0.752437168,83.93478258 +68.17,50.42503841,-2.586242433,49.9632,1.056762121,9.943827508,-3.1065625,-1.470242934,0.850918701,83.92725753 +68.18,50.42503851,-2.586241034,49.9943,1.056762126,9.944049605,-3.1084375,-1.514212804,0.948658254,83.91973241 +68.19,50.4250386,-2.586239634,50.0254,1.056762132,9.943827564,-3.109375,-1.556822243,1.045570512,83.91220736 +68.2,50.4250387,-2.586238235,50.0565,1.056762134,9.942939315,-3.108125,-1.59806237,1.141571023,83.9046823 +68.21,50.42503879,-2.586236836,50.0876,1.056762131,9.942939344,-3.1046875,-1.637924533,1.236576077,83.89715719 +68.22,50.42503889,-2.586235437,50.1186,1.060238317,9.94382765,-3.1,-1.676400482,1.330502825,83.88963213 +68.23,50.42503898,-2.586234037,50.1496,1.070666897,9.943827678,-3.0946875,-1.713482196,1.423269333,83.88210702 +68.24,50.42503908,-2.586232638,50.1805,1.077619296,9.942717359,-3.0878125,-1.749161825,1.514794757,83.87458196 +68.25,50.42503918,-2.586231239,50.2114,1.070666927,9.941829109,-3.0784375,-1.783432035,1.604999284,83.86705685 +68.26,50.42503927,-2.58622984,50.2421,1.060238361,9.941829136,-3.068125,-1.81628555,1.69380419,83.85953179 +68.27,50.42503937,-2.586228441,50.2727,1.060238373,9.942717441,-3.058125,-1.847715608,1.781132068,83.85200668 +68.28,50.42503946,-2.586227042,50.3033,1.070666958,9.943827816,-3.04625,-1.877715621,1.866906772,83.84448163 +68.29,50.42503956,-2.586225642,50.3337,1.07761934,9.943605774,-3.03125,-1.906279286,1.951053474,83.83695651 +68.3,50.42503966,-2.586224243,50.3639,1.074143138,9.941829245,-3.0153125,-1.933400644,2.033498892,83.82943146 +68.31,50.42503975,-2.586222844,50.394,1.07414313,9.940718924,-2.9996875,-1.959074081,2.114171063,83.82190634 +68.32,50.42503985,-2.586221446,50.4239,1.077619326,9.941385158,-2.9828125,-1.98329421,2.192999628,83.81438129 +68.33,50.42503995,-2.586220046,50.4537,1.074143151,9.941829324,-2.9634375,-2.00605599,2.269915831,83.80685618 +68.34,50.42504004,-2.586218647,50.4832,1.077619356,9.941385211,-2.9428125,-2.027354607,2.344852695,83.79933112 +68.35,50.42504014,-2.586217249,50.5125,1.091524131,9.941607306,-2.921875,-2.04718565,2.417744787,83.79180601 +68.36,50.42504024,-2.586215849,50.5417,1.091524134,9.94160733,-2.8996875,-2.065544937,2.488528508,83.78428095 +68.37,50.42504034,-2.58621445,50.5705,1.077619362,9.940274937,-2.87625,-2.082428743,2.557142267,83.77675584 +68.38,50.42504043,-2.586213052,50.5992,1.077619356,9.939608753,-2.8515625,-2.097833458,2.623526131,83.76923078 +68.39,50.42504053,-2.586211653,50.6276,1.095000321,9.940497055,-2.824375,-2.111755874,2.687622289,83.76170567 +68.4,50.42504063,-2.586210254,50.6557,1.105428912,9.941385356,-2.7953125,-2.124193069,2.749374764,83.75418061 +68.41,50.42504073,-2.586208855,50.6835,1.09500035,9.941607448,-2.7665625,-2.135142522,2.808729754,83.7466555 +68.42,50.42504083,-2.586207456,50.711,1.077619397,9.941385401,-2.738125,-2.144601883,2.865635464,83.73913044 +68.43,50.42504092,-2.586206057,50.7383,1.0776194,9.940497144,-2.7078125,-2.152569147,2.920042333,83.73160533 +68.44,50.42504102,-2.586204658,50.7652,1.095000355,9.939386818,-2.6746875,-2.159042711,2.971902862,83.72408027 +68.45,50.42504112,-2.58620326,50.7918,1.108905117,9.939386839,-2.64,-2.164021199,3.021171847,83.71655516 +68.46,50.42504122,-2.586201861,50.818,1.108905121,9.940275138,-2.605,-2.167503579,3.067806314,83.70903011 +68.47,50.42504132,-2.586200462,50.8439,1.095000369,9.940275158,-2.57,-2.169489107,3.111765642,83.70150499 +68.48,50.42504142,-2.586199063,50.8694,1.077619422,9.939164829,-2.534375,-2.169977381,3.153011441,83.69397994 +68.49,50.42504151,-2.586197665,50.8946,1.077619428,9.938276569,-2.4965625,-2.168968288,3.19150773,83.68645482 +68.5,50.42504161,-2.586196266,50.9194,1.095000391,9.938054518,-2.4565625,-2.166462056,3.227221049,83.67892977 +68.51,50.42504171,-2.586194868,50.9437,1.108905154,9.938054535,-2.4165625,-2.162459201,3.260120114,83.67140466 +68.52,50.42504181,-2.586193469,50.9677,1.11238134,9.938276621,-2.3765625,-2.156960525,3.290176391,83.6638796 +68.53,50.42504191,-2.586192071,50.9913,1.112381344,9.938942845,-2.334375,-2.149967232,3.317363525,83.65635454 +68.54,50.42504201,-2.586190672,51.0144,1.112381359,9.939386999,-2.29,-2.14148081,3.341657852,83.64882943 +68.55,50.42504211,-2.586189273,51.0371,1.112381372,9.938942875,-2.245,-2.131502922,3.363038231,83.64130437 +68.56,50.42504221,-2.586187875,51.0593,1.112381376,9.938276679,-2.2,-2.120035744,3.381485982,83.63377926 +68.57,50.42504231,-2.586186476,51.0811,1.112381371,9.938276692,-2.155,-2.107081627,3.396985064,83.62625421 +68.58,50.42504241,-2.586185078,51.1024,1.112381363,9.938942913,-2.109375,-2.092643262,3.409521896,83.61872909 +68.59,50.42504251,-2.586183679,51.1233,1.112381367,9.939164995,-2.0615625,-2.076723687,3.419085593,83.61120404 +68.6,50.42504261,-2.58618228,51.1437,1.112381381,9.938054658,-2.0115625,-2.059326282,3.425667789,83.60367892 +68.61,50.42504271,-2.586180882,51.1635,1.112381394,9.93694432,-1.9615625,-2.0404546,3.429262698,83.59615387 +68.62,50.42504281,-2.586179484,51.1829,1.112381397,9.936944329,-1.911875,-2.020112592,3.429867283,83.58862875 +68.63,50.42504291,-2.586178085,51.2018,1.112381392,9.936944338,-1.86125,-1.998304558,3.427480971,83.5811037 +68.64,50.42504301,-2.586176687,51.2201,1.112381384,9.936722276,-1.8096875,-1.975034966,3.422105882,83.57357859 +68.65,50.42504311,-2.586175289,51.238,1.112381387,9.937166421,-1.7565625,-1.950308801,3.4137466,83.56605353 +68.66,50.42504321,-2.58617389,51.2553,1.115857593,9.937832636,-1.7015625,-1.924131104,3.402410516,83.55852842 +68.67,50.42504331,-2.586172492,51.272,1.129762372,9.937832641,-1.646875,-1.896507376,3.388107484,83.55100336 +68.68,50.42504341,-2.586171093,51.2882,1.14714333,9.936944367,-1.593125,-1.867443404,3.370849937,83.54347825 +68.69,50.42504352,-2.586169695,51.3039,1.147143321,9.935611952,-1.538125,-1.836945319,3.350653003,83.53595319 +68.7,50.42504362,-2.586168297,51.319,1.129762363,9.934945746,-1.48125,-1.805019366,3.327534214,83.52842808 +68.71,50.42504372,-2.586166899,51.3335,1.115857607,9.935611956,-1.4234375,-1.771672306,3.301513794,83.52090302 +68.72,50.42504382,-2.586165501,51.3475,1.112381426,9.936722304,-1.365,-1.736911014,3.272614375,83.51337791 +68.73,50.42504392,-2.586164102,51.3608,1.115857621,9.936722304,-1.3065625,-1.700742824,3.240861226,83.50585285 +68.74,50.42504402,-2.586162704,51.3736,1.129762383,9.935611955,-1.2484375,-1.663175299,3.206281963,83.49832774 +68.75,50.42504412,-2.586161306,51.3858,1.147143336,9.934723674,-1.1896875,-1.624216231,3.16890678,83.49080269 +68.76,50.42504423,-2.586159908,51.3974,1.147143338,9.934501601,-1.13,-1.583873815,3.128768279,83.48327757 +68.77,50.42504433,-2.58615851,51.4084,1.133238582,9.934723667,-1.07,-1.542156414,3.085901468,83.47575252 +68.78,50.42504443,-2.586157112,51.4188,1.133238591,9.93561194,-1.0096875,-1.499072738,3.040343645,83.4682274 +68.79,50.42504453,-2.586155714,51.4286,1.147143355,9.936722281,-0.9484375,-1.454631897,2.992134632,83.46070235 +68.8,50.42504464,-2.586154315,51.4378,1.147143346,9.936722274,-0.8865625,-1.408843,2.941316427,83.45317723 +68.81,50.42504474,-2.586152917,51.4463,1.133238578,9.935611918,-0.825,-1.361715732,2.887933377,83.44565218 +68.82,50.42504484,-2.586151519,51.4543,1.13323859,9.934723631,-0.763125,-1.313259946,2.832031947,83.43812707 +68.83,50.42504494,-2.586150121,51.4616,1.147143368,9.934279482,-0.6996875,-1.26348567,2.773661012,83.43060201 +68.84,50.42504505,-2.586148723,51.4683,1.150619555,9.933391192,-0.6353125,-1.212403332,2.712871336,83.4230769 +68.85,50.42504515,-2.586147325,51.4743,1.147143352,9.932280832,-0.5715625,-1.160023645,2.649716032,83.41555184 +68.86,50.42504525,-2.586145928,51.4797,1.150619546,9.932280819,-0.5084375,-1.106357495,2.584250161,83.40802673 +68.87,50.42504536,-2.58614453,51.4845,1.150619558,9.933391153,-0.445,-1.051416114,2.516530732,83.40050167 +68.88,50.42504546,-2.586143132,51.4886,1.147143373,9.934279416,-0.3815625,-0.99521096,2.446616875,83.39297662 +68.89,50.42504556,-2.586141734,51.4921,1.150619559,9.934501469,-0.3184375,-0.937753835,2.374569552,83.3854515 +68.9,50.42504567,-2.586140336,51.495,1.150619548,9.934279383,-0.2546875,-0.879056601,2.300451502,83.37792645 +68.91,50.42504577,-2.586138938,51.4972,1.147143356,9.933391087,-0.19,-0.81913169,2.22432747,83.37040133 +68.92,50.42504587,-2.58613754,51.4988,1.154095753,9.93205865,-0.125,-0.757991478,2.146263804,83.36287628 +68.93,50.42504598,-2.586136143,51.4997,1.164524337,9.931170351,-0.06,-0.6956488,2.066328571,83.35535117 +68.94,50.42504608,-2.586134745,51.5,1.16452433,9.93117033,0.0046875,-0.632116662,1.984591444,83.34782611 +68.95,50.42504619,-2.586133348,51.4996,1.154095742,9.932058586,0.0684375,-0.567408298,1.901123754,83.340301 +68.96,50.42504629,-2.58613195,51.4986,1.147143357,9.93316891,0.131875,-0.501537288,1.815998211,83.33277594 +68.97,50.42504639,-2.586130552,51.497,1.15409575,9.933168886,0.1965625,-0.434517326,1.729289128,83.32525083 +68.98,50.4250465,-2.586129154,51.4947,1.164524325,9.932280582,0.2615625,-0.36636245,1.641072019,83.31772577 +68.99,50.4250466,-2.586127757,51.4917,1.168000501,9.932058486,0.325,-0.297086867,1.551423949,83.31020066 +69,50.42504671,-2.586126359,51.4882,1.168000496,9.932280528,0.3884375,-0.226705076,1.460422953,83.3026756 +69.01,50.42504681,-2.586124961,51.484,1.168000511,9.931836361,0.4534375,-0.155231742,1.368148501,83.29515049 +69.02,50.42504692,-2.586123564,51.4791,1.168000523,9.931170123,0.518125,-0.082681763,1.274680979,83.28762543 +69.03,50.42504702,-2.586122166,51.4736,1.168000518,9.930948023,0.5815625,-0.00907038,1.180101919,83.28010032 +69.04,50.42504713,-2.586120769,51.4675,1.171476698,9.930947991,0.645,0.065587109,1.08449377,83.27257527 +69.05,50.42504723,-2.586119371,51.4607,1.181905274,9.930947959,0.708125,0.141275063,0.987939953,83.26505015 +69.06,50.42504734,-2.586117974,51.4533,1.188857666,9.930725856,0.7696875,0.217977668,0.890524638,83.2575251 +69.07,50.42504745,-2.586116576,51.4453,1.18190528,9.930059612,0.8303125,0.295678995,0.792332735,83.24999998 +69.08,50.42504755,-2.586115179,51.4367,1.171476692,9.929615437,0.891875,0.374362717,0.693449903,83.24247493 +69.09,50.42504766,-2.586113782,51.4275,1.171476691,9.93005954,0.955,0.454012502,0.593962428,83.23494981 +69.1,50.42504776,-2.586112384,51.4176,1.181905277,9.930725712,1.0178125,0.534611621,0.493956999,83.22742476 +69.11,50.42504787,-2.586110987,51.4071,1.188857666,9.930947743,1.078125,0.616143286,0.393520821,83.21989965 +69.12,50.42504798,-2.586109589,51.396,1.181905273,9.930947703,1.136875,0.698590423,0.292741441,83.21237459 +69.13,50.42504808,-2.586108192,51.3844,1.171476683,9.930725593,1.1965625,0.7819359,0.191706865,83.20484948 +69.14,50.42504819,-2.586106794,51.3721,1.171476681,9.929837275,1.2565625,0.8661623,0.090505044,83.19732442 +69.15,50.42504829,-2.586105397,51.3592,1.185381454,9.928726885,1.3146875,0.951251919,-0.010775617,83.18979931 +69.16,50.4250484,-2.586104,51.3458,1.202762406,9.928726842,1.371875,1.037187108,-0.112046939,83.18227425 +69.17,50.42504851,-2.586102603,51.3318,1.202762391,9.929615075,1.43,1.123949878,-0.213220571,83.17474914 +69.18,50.42504862,-2.586101205,51.3172,1.188857623,9.929615029,1.488125,1.211522123,-0.314208221,83.16722408 +69.19,50.42504872,-2.586099808,51.302,1.185381444,9.928504636,1.5446875,1.299885507,-0.414921883,83.15969897 +69.2,50.42504883,-2.586098411,51.2863,1.188857635,9.927616312,1.6,1.38902164,-0.515273779,83.15217391 +69.21,50.42504894,-2.586097014,51.27,1.185381431,9.927616264,1.655,1.4789119,-0.615176305,83.1446488 +69.22,50.42504904,-2.586095617,51.2532,1.18885762,9.928504494,1.7096875,1.569537436,-0.71454237,83.13712375 +69.23,50.42504915,-2.58609422,51.2358,1.202762395,9.929614791,1.763125,1.6608794,-0.813285401,83.12959869 +69.24,50.42504926,-2.586092822,51.2179,1.202762391,9.929392672,1.8146875,1.752918709,-0.911319224,83.12207358 +69.25,50.42504937,-2.586091425,51.1995,1.18885761,9.927616065,1.8653125,1.845636172,-1.008558298,83.11454852 +69.26,50.42504947,-2.586090028,51.1806,1.188857604,9.926505666,1.9165625,1.939012307,-1.104917939,83.10702341 +69.27,50.42504958,-2.586088632,51.1612,1.206238564,9.927393891,1.968125,2.033027749,-1.200314094,83.09949835 +69.28,50.42504969,-2.586087234,51.1412,1.220143325,9.928282115,2.018125,2.127662787,-1.294663513,83.09197324 +69.29,50.4250498,-2.586085837,51.1208,1.220143316,9.927171713,2.06625,2.222897654,-1.387884032,83.08444818 +69.3,50.42504991,-2.58608444,51.0999,1.206238548,9.925395102,2.1134375,2.31871247,-1.479894236,83.07692307 +69.31,50.42505002,-2.586083044,51.0785,1.188857588,9.925172977,2.16,2.415087294,-1.570613967,83.06939801 +69.32,50.42505012,-2.586081647,51.0567,1.188857581,9.926283268,2.2065625,2.512001902,-1.659964099,83.0618729 +69.33,50.42505023,-2.58608025,51.0344,1.20623854,9.927171488,2.253125,2.609436125,-1.747866711,83.05434785 +69.34,50.42505034,-2.586078853,51.0116,1.220143313,9.9273935,2.2978125,2.707369566,-1.834245198,83.04682273 +69.35,50.42505045,-2.586077456,50.9884,1.223619501,9.927393442,2.3396875,2.805781829,-1.919024159,83.03929768 +69.36,50.42505056,-2.586076059,50.9648,1.223619488,9.927171312,2.38,2.904652285,-2.002129682,83.03177256 +69.37,50.42505067,-2.586074662,50.9408,1.223619483,9.926282974,2.42,3.003960309,-2.083489345,83.02424751 +69.38,50.42505078,-2.586073265,50.9164,1.223619487,9.925172566,2.46,3.103685218,-2.163032159,83.01672239 +69.39,50.42505089,-2.586071869,50.8916,1.223619483,9.924950434,2.5,3.203806155,-2.240688796,83.00919734 +69.4,50.425051,-2.586070472,50.8664,1.223619469,9.925172441,2.539375,3.304302207,-2.316391532,83.00167223 +69.41,50.42505111,-2.586069075,50.8408,1.22361946,9.924950309,2.5765625,3.405152348,-2.390074306,82.99414717 +69.42,50.42505122,-2.586067679,50.8148,1.22361945,9.924950247,2.61125,3.506335548,-2.461672945,82.98662206 +69.43,50.42505133,-2.586066282,50.7886,1.223619438,9.925172253,2.645,3.607830725,-2.531124941,82.979097 +69.44,50.42505144,-2.586064885,50.7619,1.22361944,9.924950119,2.6784375,3.70961662,-2.598369732,82.97157189 +69.45,50.42505155,-2.586063489,50.735,1.22361945,9.924950053,2.7109375,3.811671977,-2.663348761,82.96404683 +69.46,50.42505166,-2.586062092,50.7077,1.223619447,9.925172058,2.741875,3.913975539,-2.726005248,82.95652172 +69.47,50.42505177,-2.586060695,50.6801,1.223619433,9.924727853,2.77125,4.016505878,-2.786284648,82.94899666 +69.48,50.42505188,-2.586059299,50.6523,1.223619426,9.924061579,2.7996875,4.119241623,-2.844134363,82.94147155 +69.49,50.42505199,-2.586057902,50.6241,1.223619423,9.923839442,2.826875,4.222161287,-2.899503973,82.93394649 +69.5,50.4250521,-2.586056506,50.5957,1.223619413,9.923839375,2.8528125,4.325243384,-2.952345177,82.92642138 +69.51,50.42505221,-2.586055109,50.5671,1.223619403,9.923839307,2.8784375,4.428466429,-3.002611853,82.91889633 +69.52,50.42505232,-2.586053713,50.5381,1.223619402,9.92383924,2.9028125,4.531808821,-3.050260227,82.91137121 +69.53,50.42505243,-2.586052316,50.509,1.223619401,9.923839172,2.9246875,4.63524896,-3.095248701,82.90384616 +69.54,50.42505254,-2.58605092,50.4796,1.227095585,9.923617034,2.945,4.738765302,-3.137538086,82.89632104 +69.55,50.42505265,-2.586049523,50.4501,1.241000346,9.922950756,2.965,4.84233619,-3.177091539,82.88879599 +69.56,50.42505276,-2.586048127,50.4203,1.258381301,9.922506547,2.9846875,4.945939965,-3.213874456,82.88127087 +69.57,50.42505288,-2.586046731,50.3904,1.258381294,9.922728547,3.0028125,5.049555085,-3.247854864,82.87374582 +69.58,50.42505299,-2.586045334,50.3602,1.241000331,9.922728477,3.0184375,5.153159835,-3.279003084,82.86622076 +69.59,50.4250531,-2.586043938,50.33,1.227095565,9.922506338,3.0328125,5.256732613,-3.307291958,82.85869565 +69.6,50.42505321,-2.586042542,50.2996,1.227095552,9.922728337,3.046875,5.360251763,-3.33269685,82.85117059 +69.61,50.42505332,-2.586041145,50.269,1.2410003,9.922506196,3.059375,5.463695683,-3.355195585,82.84364548 +69.62,50.42505343,-2.586039749,50.2384,1.258381255,9.921395777,3.0696875,5.567042774,-3.37476851,82.83612043 +69.63,50.42505355,-2.586038353,50.2076,1.258381258,9.920507429,3.0784375,5.670271434,-3.391398553,82.82859531 +69.64,50.42505366,-2.586036957,50.1768,1.244476485,9.920507358,3.0865625,5.77336012,-3.405071332,82.82107026 +69.65,50.42505377,-2.586035561,50.1459,1.244476479,9.921173495,3.0946875,5.87628729,-3.415774756,82.81354514 +69.66,50.42505388,-2.586034165,50.1149,1.258381241,9.921617562,3.10125,5.979031457,-3.423499602,82.80602009 +69.67,50.425054,-2.586032768,50.0838,1.258381233,9.921395421,3.1046875,6.081571192,-3.428239109,82.79849497 +69.68,50.42505411,-2.586031373,50.0528,1.244476459,9.921395349,3.1065625,6.183885011,-3.429989151,82.79096992 +69.69,50.42505422,-2.586029976,50.0217,1.244476448,9.921617347,3.1084375,6.285951655,-3.428748182,82.78344481 +69.7,50.42505433,-2.58602858,49.9906,1.258381201,9.921173136,3.109375,6.387749697,-3.42451729,82.77591975 +69.71,50.42505445,-2.586027184,49.9595,1.261857392,9.920506855,3.1084375,6.489257936,-3.417300199,82.76839464 +69.72,50.42505456,-2.586025788,49.9284,1.258381203,9.920284715,3.10625,6.590455174,-3.407103154,82.76086958 +69.73,50.42505467,-2.586024392,49.8974,1.265333579,9.920284643,3.103125,6.691320212,-3.393935037,82.75334447 +69.74,50.42505479,-2.586022996,49.8663,1.275762148,9.920284571,3.098125,6.791832078,-3.377807421,82.74581941 +69.75,50.4250549,-2.5860216,49.8354,1.275762142,9.920284499,3.09125,6.891969745,-3.358734229,82.7382943 +69.76,50.42505502,-2.586020204,49.8045,1.265333552,9.920062358,3.083125,6.991712301,-3.336732192,82.73076924 +69.77,50.42505513,-2.586018808,49.7737,1.258381159,9.919174009,3.073125,7.091038946,-3.311820502,82.72324413 +69.78,50.42505524,-2.586017412,49.743,1.265333542,9.91806359,3.0615625,7.189928883,-3.284020877,82.71571907 +69.79,50.42505536,-2.586016017,49.7125,1.275762115,9.918063519,3.05,7.288361428,-3.253357493,82.70819396 +69.8,50.42505547,-2.586014621,49.682,1.275762113,9.918951725,3.038125,7.386316126,-3.219857109,82.70066891 +69.81,50.42505559,-2.586013225,49.6517,1.265333542,9.918951655,3.0246875,7.483772466,-3.183549003,82.69314379 +69.82,50.4250557,-2.586011829,49.6215,1.258381153,9.918063307,3.0096875,7.580710107,-3.144464802,82.68561874 +69.83,50.42505581,-2.586010434,49.5915,1.265333519,9.917841167,2.993125,7.677108823,-3.102638539,82.67809362 +69.84,50.42505593,-2.586009038,49.5616,1.275762076,9.918063165,2.9746875,7.77294839,-3.058106769,82.67056857 +69.85,50.42505604,-2.586007642,49.532,1.279238255,9.917841026,2.9546875,7.868208926,-3.010908282,82.66304345 +69.86,50.42505616,-2.586006247,49.5025,1.279238251,9.918063026,2.9334375,7.962870435,-2.961084216,82.6555184 +69.87,50.42505627,-2.586004851,49.4733,1.279238254,9.918951234,2.91125,8.056913206,-2.908678058,82.64799329 +69.88,50.42505639,-2.586003455,49.4443,1.279238253,9.918729096,2.888125,8.150317588,-2.853735474,82.64046823 +69.89,50.4250565,-2.586002059,49.4155,1.279238247,9.916952472,2.863125,8.243064043,-2.796304419,82.63294312 +69.9,50.42505662,-2.586000664,49.387,1.282714428,9.915842057,2.8365625,8.335133204,-2.736434913,82.62541806 +69.91,50.42505673,-2.585999269,49.3588,1.29314299,9.916730267,2.81,8.426505935,-2.67417921,82.61789301 +69.92,50.42505685,-2.585997873,49.3308,1.300095371,9.917840546,2.783125,8.517163041,-2.609591568,82.61036789 +69.93,50.42505697,-2.585996477,49.3031,1.293142992,9.917618409,2.754375,8.607085616,-2.542728368,82.60284284 +69.94,50.42505708,-2.585995082,49.2757,1.282714413,9.916952134,2.723125,8.696254923,-2.47364782,82.59531772 +69.95,50.4250572,-2.585993686,49.2486,1.282714407,9.916729999,2.69,8.784652341,-2.402410259,82.58779267 +69.96,50.42505731,-2.585992291,49.2219,1.293142975,9.916729933,2.6565625,8.872259307,-2.329077734,82.58026755 +69.97,50.42505743,-2.585990895,49.1955,1.300095343,9.916729868,2.6234375,8.959057658,-2.253714189,82.5727425 +69.98,50.42505755,-2.5859895,49.1694,1.296619143,9.916507734,2.589375,9.04502923,-2.176385399,82.56521739 +69.99,50.42505766,-2.585988104,49.1437,1.296619144,9.915841462,2.553125,9.130155976,-2.0971588,82.55769233 +70,50.42505778,-2.585986709,49.1183,1.300095332,9.915397259,2.515,9.214420249,-2.016103435,82.55016722 +70.01,50.4250579,-2.585985314,49.0934,1.296619132,9.915619265,2.4765625,9.297804401,-1.933289949,82.54264216 +70.02,50.42505801,-2.585983918,49.0688,1.296619127,9.915397133,2.438125,9.380290957,-1.848790649,82.53511705 +70.03,50.42505813,-2.585982523,49.0446,1.300095317,9.914286725,2.3978125,9.461862787,-1.76267916,82.52759199 +70.04,50.42505825,-2.585981128,49.0208,1.296619119,9.913398387,2.355,9.542502815,-1.675030598,82.52006688 +70.05,50.42505836,-2.585979733,48.9975,1.300095299,9.913176256,2.3115625,9.622194197,-1.585921394,82.51254182 +70.06,50.42505848,-2.585978338,48.9746,1.314000062,9.913398265,2.2684375,9.700920259,-1.495429242,82.50501671 +70.07,50.4250586,-2.585976943,48.9521,1.314000067,9.914286483,2.2246875,9.778664616,-1.403633038,82.49749165 +70.08,50.42505872,-2.585975548,48.9301,1.300095296,9.915396772,2.1796875,9.855411052,-1.310612824,82.48996654 +70.09,50.42505883,-2.585974152,48.9085,1.300095285,9.915396714,2.1334375,9.931143468,-1.216449789,82.48244149 +70.1,50.42505895,-2.585972757,48.8874,1.314000042,9.914286309,2.08625,10.00584605,-1.121225922,82.47491637 +70.11,50.42505907,-2.585971362,48.8668,1.314000038,9.913397975,2.038125,10.07950327,-1.025024418,82.46739132 +70.12,50.42505919,-2.585969967,48.8466,1.30009527,9.913175849,1.988125,10.15209966,-0.927928984,82.4598662 +70.13,50.4250593,-2.585968572,48.827,1.300095269,9.913175794,1.9365625,10.22362009,-0.83002442,82.45234115 +70.14,50.42505942,-2.585967177,48.8079,1.317476226,9.913175741,1.8853125,10.29404966,-0.731396095,82.44481603 +70.15,50.42505954,-2.585965782,48.7893,1.331380988,9.913175688,1.835,10.36337366,-0.632129954,82.43729098 +70.16,50.42505966,-2.585964387,48.7712,1.334857164,9.913175635,1.784375,10.43157758,-0.53231257,82.42976587 +70.17,50.42505978,-2.585962992,48.7536,1.331380959,9.913175583,1.7315625,10.49864716,-0.432031033,82.42224081 +70.18,50.4250599,-2.585961597,48.7365,1.317476196,9.913175531,1.6765625,10.56456842,-0.331372776,82.4147157 +70.19,50.42506002,-2.585960202,48.7201,1.300095251,9.912953411,1.6215625,10.62932761,-0.23042552,82.40719064 +70.2,50.42506013,-2.585958807,48.7041,1.300095253,9.912065085,1.5665625,10.69291114,-0.129277327,82.39966553 +70.21,50.42506025,-2.585957412,48.6887,1.317476195,9.910954689,1.5096875,10.75530584,-0.028016433,82.39214047 +70.22,50.42506037,-2.585956018,48.6739,1.331380951,9.910954641,1.451875,10.81649859,0.073268926,82.38461536 +70.23,50.42506049,-2.585954623,48.6597,1.334857145,9.911842872,1.395,10.87647662,0.1744904,82.3770903 +70.24,50.42506061,-2.585953228,48.646,1.334857145,9.911842826,1.338125,10.93522748,0.275559697,82.36956519 +70.25,50.42506073,-2.585951833,48.6329,1.334857135,9.910954504,1.2796875,10.99273881,0.376388695,82.36204013 +70.26,50.42506085,-2.585950439,48.6204,1.334857126,9.910954459,1.22,11.04899862,0.476889446,82.35451508 +70.27,50.42506097,-2.585949044,48.6085,1.334857126,9.911842693,1.16,11.10399518,0.576974401,82.34698997 +70.28,50.42506109,-2.585947649,48.5972,1.334857132,9.91184265,1.1,11.15771696,0.676556185,82.33946491 +70.29,50.42506121,-2.585946254,48.5865,1.334857132,9.910732261,1.04,11.21015286,0.775548051,82.3319398 +70.3,50.42506133,-2.58594486,48.5764,1.334857124,9.909843944,0.98,11.2612918,0.873863598,82.32441474 +70.31,50.42506145,-2.585943465,48.5669,1.334857115,9.909621835,0.9196875,11.31112315,0.971417111,82.31688963 +70.32,50.42506157,-2.585942071,48.558,1.334857115,9.909399727,0.858125,11.35963651,1.068123563,82.30936457 +70.33,50.42506169,-2.585940676,48.5497,1.334857123,9.90873348,0.795,11.40682177,1.163898558,82.30183946 +70.34,50.42506181,-2.585939282,48.5421,1.334857123,9.908511374,0.7315625,11.45266899,1.258658616,82.2943144 +70.35,50.42506193,-2.585937888,48.5351,1.334857115,9.909621685,0.6684375,11.49716873,1.352321172,82.28678929 +70.36,50.42506205,-2.585936493,48.5287,1.334857107,9.910509928,0.605,11.54031154,1.44480441,82.27926423 +70.37,50.42506217,-2.585935098,48.523,1.338333299,9.909621617,0.5415625,11.58208852,1.536027771,82.27173912 +70.38,50.42506229,-2.585933704,48.5179,1.35223807,9.908511237,0.4784375,11.62249093,1.625911728,82.26421407 +70.39,50.42506241,-2.58593231,48.5134,1.369619025,9.908511204,0.415,11.66151033,1.714377844,82.25668895 +70.4,50.42506254,-2.585930915,48.5096,1.369619018,9.908511172,0.3515625,11.69913853,1.801348998,82.2491639 +70.41,50.42506266,-2.585929521,48.5064,1.352238057,9.908289073,0.288125,11.73536768,1.886749332,82.24163878 +70.42,50.42506278,-2.585928127,48.5038,1.338333295,9.908733182,0.223125,11.77019028,1.970504417,82.23411373 +70.43,50.4250629,-2.585926732,48.5019,1.334857113,9.909399362,0.156875,11.80359899,2.052541144,82.22658861 +70.44,50.42506302,-2.585925338,48.5007,1.338333306,9.909399335,0.091875,11.83558688,2.132788066,82.21906356 +70.45,50.42506314,-2.585923943,48.5001,1.352238062,9.908511032,0.0284375,11.86614719,2.211175167,82.21153845 +70.46,50.42506326,-2.585922549,48.5001,1.369619007,9.907178591,-0.0353125,11.89527361,2.287634093,82.20401339 +70.47,50.42506339,-2.585921155,48.5008,1.369619003,9.906290289,-0.1,11.92296008,2.362098152,82.19648828 +70.48,50.42506351,-2.585919761,48.5021,1.355714247,9.906068195,-0.1646875,11.94920075,2.434502484,82.18896322 +70.49,50.42506363,-2.585918367,48.5041,1.35571426,9.906068173,-0.2284375,11.97399017,2.504783837,82.18143811 +70.5,50.42506375,-2.585916973,48.5067,1.369619028,9.906290221,-0.2915625,11.99732318,2.572880959,82.17391305 +70.51,50.42506388,-2.585915579,48.5099,1.369619018,9.907178478,-0.3553125,12.01919487,2.638734551,82.16638794 +70.52,50.425064,-2.585914185,48.5138,1.355714245,9.908288805,-0.42,12.03960071,2.702287087,82.15886288 +70.53,50.42506412,-2.58591279,48.5183,1.355714246,9.908066717,-0.4846875,12.05853639,2.763483162,82.15133777 +70.54,50.42506424,-2.585911396,48.5235,1.36961901,9.906068075,-0.5484375,12.07599802,2.822269491,82.14381271 +70.55,50.42506437,-2.585910002,48.5293,1.373095202,9.904069434,-0.6115625,12.09198189,2.878594738,82.1362876 +70.56,50.42506449,-2.585908609,48.5357,1.369619024,9.90384735,-0.675,12.10648471,2.932409856,82.12876255 +70.57,50.42506461,-2.585907215,48.5428,1.373095227,9.904957682,-0.738125,12.1195034,2.983667806,82.12123743 +70.58,50.42506474,-2.585905821,48.5505,1.373095224,9.905845945,-0.7996875,12.13103532,3.032323955,82.11371238 +70.59,50.42506486,-2.585904427,48.5588,1.369619022,9.906068001,-0.8603125,12.14107795,3.078335904,82.10618726 +70.6,50.42506498,-2.585903033,48.5677,1.373095208,9.90606799,-0.921875,12.14962929,3.121663488,82.09866221 +70.61,50.42506511,-2.585901639,48.5772,1.373095215,9.90584591,-0.9846875,12.15668756,3.162268949,82.09113715 +70.62,50.42506523,-2.585900245,48.5874,1.369619035,9.904957622,-1.0465625,12.16225121,3.200116822,82.08361204 +70.63,50.42506535,-2.585898851,48.5982,1.376571426,9.903625197,-1.1065625,12.16631909,3.235174162,82.07608698 +70.64,50.42506548,-2.585897458,48.6095,1.386999998,9.902958981,-1.1665625,12.16889041,3.267410372,82.06856187 +70.65,50.4250656,-2.585896064,48.6215,1.390476183,9.903625181,-1.2265625,12.16996459,3.296797377,82.06103681 +70.66,50.42506573,-2.585894671,48.6341,1.390476181,9.904735521,-1.2846875,12.16954146,3.323309567,82.0535117 +70.67,50.42506585,-2.585893276,48.6472,1.386999991,9.904735515,-1.341875,12.16762102,3.346923678,82.04598664 +70.68,50.42506598,-2.585891883,48.6609,1.376571419,9.903625165,-1.4,12.16420373,3.367619315,82.03846153 +70.69,50.4250661,-2.585890489,48.6752,1.369619045,9.902736884,-1.458125,12.15929027,3.385378314,82.03093648 +70.7,50.42506622,-2.585889096,48.6901,1.376571437,9.902514811,-1.515,12.15288168,3.400185147,82.02341136 +70.71,50.42506635,-2.585887702,48.7055,1.390476204,9.902736879,-1.5715625,12.14497928,3.412027039,82.01588631 +70.72,50.42506647,-2.585886309,48.7215,1.404380964,9.903403085,-1.628125,12.13558478,3.420893561,82.00836119 +70.73,50.4250666,-2.585884915,48.7381,1.411333345,9.903847223,-1.6828125,12.12470013,3.426777035,82.00083614 +70.74,50.42506673,-2.585883521,48.7552,1.404380969,9.903403085,-1.735,12.1123275,3.429672306,81.99331103 +70.75,50.42506685,-2.585882128,48.7728,1.393952403,9.902514808,-1.786875,12.0984696,3.429576851,81.98578597 +70.76,50.42506698,-2.585880734,48.7909,1.39047622,9.901626533,-1.8396875,12.08312929,3.426490728,81.97826086 +70.77,50.4250671,-2.585879341,48.8096,1.390476233,9.901182398,-1.8915625,12.06630977,3.420416688,81.9707358 +70.78,50.42506723,-2.585877948,48.8288,1.390476239,9.90162654,-1.9415625,12.04801448,3.411360002,81.96321069 +70.79,50.42506735,-2.585876554,48.8484,1.390476237,9.902292752,-1.9915625,12.02824732,3.399328518,81.95568563 +70.8,50.42506748,-2.585875161,48.8686,1.393952424,9.902292757,-2.0415625,12.00701247,3.38433278,81.94816052 +70.81,50.4250676,-2.585873767,48.8893,1.404380997,9.901404486,-2.0896875,11.98431424,3.366385851,81.94063546 +70.82,50.42506773,-2.585872374,48.9104,1.411333386,9.900072076,-2.1365625,11.96015742,3.345503431,81.93311035 +70.83,50.42506786,-2.585870981,48.932,1.407857199,9.899405875,-2.1834375,11.93454706,3.321703623,81.92558529 +70.84,50.42506798,-2.585869588,48.9541,1.407857202,9.900072091,-2.2296875,11.9074885,3.295007285,81.91806018 +70.85,50.42506811,-2.585868195,48.9766,1.411333403,9.901182446,-2.2746875,11.8789874,3.265437621,81.91053512 +70.86,50.42506824,-2.585866801,48.9996,1.407857223,9.901182455,-2.318125,11.84904973,3.233020471,81.90301001 +70.87,50.42506836,-2.585865408,49.023,1.407857229,9.900072118,-2.3596875,11.81768172,3.197784025,81.89548496 +70.88,50.42506849,-2.585864015,49.0468,1.411333418,9.899183852,-2.4,11.78488997,3.159759108,81.88795984 +70.89,50.42506862,-2.585862622,49.071,1.407857228,9.899183863,-2.44,11.75068124,3.118978837,81.88043479 +70.9,50.42506874,-2.585861229,49.0956,1.411333427,9.899850082,-2.4796875,11.71506269,3.075478735,81.87290967 +70.91,50.42506887,-2.585859836,49.1206,1.425238197,9.900072164,-2.5184375,11.67804182,3.02929679,81.86538462 +70.92,50.425069,-2.585858442,49.146,1.4252382,9.89896183,-2.55625,11.63962632,2.98047328,81.85785951 +70.93,50.42506913,-2.58585705,49.1717,1.411333444,9.897851496,-2.593125,11.5998242,2.929050719,81.85033445 +70.94,50.42506925,-2.585855657,49.1979,1.41133345,9.89807358,-2.628125,11.55864378,2.875074026,81.84280934 +70.95,50.42506938,-2.585854264,49.2243,1.425238218,9.898739802,-2.66125,11.5160937,2.818590185,81.83528428 +70.96,50.42506951,-2.585852871,49.2511,1.42523823,9.898961886,-2.6934375,11.47218284,2.75964847,81.82775922 +70.97,50.42506964,-2.585851478,49.2782,1.411333485,9.898961902,-2.7246875,11.42692032,2.698300332,81.82023411 +70.98,50.42506976,-2.585850085,49.3056,1.411333496,9.898739848,-2.755,11.38031565,2.634599285,81.81270906 +70.99,50.42506989,-2.585848692,49.3333,1.428714447,9.897851588,-2.7846875,11.33237851,2.568600735,81.80518394 +71,50.42507002,-2.585847299,49.3613,1.442619205,9.896741257,-2.813125,11.28311892,2.500362379,81.79765889 +71.01,50.42507015,-2.585845907,49.3896,1.442619205,9.896741274,-2.84,11.23254714,2.429943688,81.79013377 +71.02,50.42507028,-2.585844514,49.4181,1.428714444,9.897851638,-2.86625,11.18067383,2.357406028,81.78260872 +71.03,50.42507041,-2.585843121,49.4469,1.411333503,9.898517864,-2.8915625,11.12750977,2.282812653,81.7750836 +71.04,50.42507053,-2.585841728,49.476,1.411333525,9.897851674,-2.914375,11.07306606,2.20622865,81.76755855 +71.05,50.42507066,-2.585840335,49.5052,1.428714492,9.896741346,-2.935,11.01735405,2.12772077,81.76003344 +71.06,50.42507079,-2.585838943,49.5347,1.442619258,9.896519295,-2.955,10.96038537,2.04735748,81.75250838 +71.07,50.42507092,-2.58583755,49.5643,1.446095447,9.896741384,-2.9746875,10.902172,1.965208912,81.74498327 +71.08,50.42507105,-2.585836157,49.5942,1.446095449,9.896297264,-2.9934375,10.84272597,1.881346626,81.73745821 +71.09,50.42507118,-2.585834765,49.6242,1.446095458,9.895631075,-3.0109375,10.78205982,1.795843791,81.7299331 +71.1,50.42507131,-2.585833372,49.6544,1.446095463,9.895409026,-3.0265625,10.72018611,1.70877489,81.72240804 +71.11,50.42507144,-2.58583198,49.6848,1.446095461,9.895409047,-3.0396875,10.65711784,1.620215955,81.71488293 +71.12,50.42507157,-2.585830587,49.7152,1.446095466,9.895409066,-3.0515625,10.59286818,1.53024422,81.70735787 +71.13,50.4250717,-2.585829195,49.7458,1.446095477,9.895409086,-3.0634375,10.5274505,1.43893801,81.69983276 +71.14,50.42507183,-2.585827802,49.7765,1.446095488,9.895409107,-3.0746875,10.46087847,1.346377079,81.6923077 +71.15,50.42507196,-2.58582641,49.8073,1.4460955,9.895187058,-3.0846875,10.39316598,1.252642043,81.68478259 +71.16,50.42507209,-2.585825017,49.8382,1.446095507,9.894520871,-3.0928125,10.32432722,1.15781472,81.67725754 +71.17,50.42507222,-2.585823625,49.8692,1.446095512,9.894076753,-3.098125,10.25437658,1.061977732,81.66973242 +71.18,50.42507235,-2.585822233,49.9002,1.446095521,9.894298843,-3.1015625,10.18332861,0.965214728,81.66220737 +71.19,50.42507248,-2.58582084,49.9312,1.446095528,9.894298864,-3.105,10.11119815,0.867609993,81.65468225 +71.2,50.42507261,-2.585819448,49.9623,1.446095533,9.894076816,-3.108125,10.03800027,0.769248724,81.6471572 +71.21,50.42507274,-2.585818056,49.9934,1.446095542,9.894298906,-3.1096875,9.963750324,0.670216636,81.63963208 +71.22,50.42507287,-2.585816663,50.0245,1.446095549,9.894076858,-3.1096875,9.888463727,0.570600131,81.63210703 +71.23,50.425073,-2.585815271,50.0556,1.446095554,9.892966533,-3.108125,9.812156234,0.470486012,81.62458192 +71.24,50.42507313,-2.585813879,50.0867,1.449571755,9.892078276,-3.1046875,9.734843773,0.369961656,81.61705686 +71.25,50.42507326,-2.585812487,50.1177,1.463476529,9.891856227,-3.0996875,9.656542501,0.269114724,81.60953175 +71.26,50.42507339,-2.585811095,50.1487,1.480857492,9.891856248,-3.0934375,9.577268805,0.168033051,81.60200669 +71.27,50.42507353,-2.585809703,50.1796,1.480857504,9.892078337,-3.08625,9.497039187,0.066804874,81.59448158 +71.28,50.42507366,-2.585808311,50.2104,1.463476559,9.892744565,-3.078125,9.415870376,-0.034481517,81.58695652 +71.29,50.42507379,-2.585806919,50.2412,1.449571799,9.893188724,-3.068125,9.333779447,-0.135737884,81.57943147 +71.3,50.42507392,-2.585805526,50.2718,1.4495718,9.892744606,-3.0565625,9.250783416,-0.236875879,81.57190635 +71.31,50.42507405,-2.585804135,50.3023,1.463476567,9.891856349,-3.045,9.166899645,-0.337807322,81.5643813 +71.32,50.42507418,-2.585802742,50.3327,1.480857529,9.890968091,-3.0328125,9.082145722,-0.438444207,81.55685618 +71.33,50.42507432,-2.585801351,50.363,1.480857531,9.890523971,-3.018125,8.996539239,-0.538698701,81.54933113 +71.34,50.42507445,-2.585799959,50.3931,1.466952773,9.890968128,-3.00125,8.910098185,-0.638483483,81.54180602 +71.35,50.42507458,-2.585798567,50.423,1.466952789,9.891634356,-2.9834375,8.822840494,-0.737711465,81.53428096 +71.36,50.42507471,-2.585797175,50.4528,1.480857565,9.891856444,-2.9646875,8.734784501,-0.836296188,81.52675585 +71.37,50.42507485,-2.585795783,50.4823,1.48085757,9.891856462,-2.9446875,8.645948541,-0.93415165,81.51923079 +71.38,50.42507498,-2.585794391,50.5117,1.466952811,9.89163441,-2.923125,8.556351177,-1.031192537,81.51170568 +71.39,50.42507511,-2.585792999,50.5408,1.466952818,9.89074615,-2.8996875,8.466011088,-1.127334168,81.50418062 +71.4,50.42507524,-2.585791607,50.5697,1.48085759,9.88963582,-2.875,8.374947182,-1.222492717,81.49665551 +71.41,50.42507538,-2.585790216,50.5983,1.484333791,9.889413768,-2.85,8.28317848,-1.316585279,81.48913045 +71.42,50.42507551,-2.585788824,50.6267,1.480857604,9.889635853,-2.8246875,8.190724119,-1.409529805,81.48160534 +71.43,50.42507564,-2.585787432,50.6548,1.484333793,9.88919173,-2.798125,8.097603409,-1.501245107,81.47408028 +71.44,50.42507578,-2.585786041,50.6827,1.484333798,9.888525537,-2.7696875,8.003835771,-1.591651373,81.46655517 +71.45,50.42507591,-2.585784649,50.7102,1.480857617,9.888525552,-2.7396875,7.90944086,-1.680669648,81.45903012 +71.46,50.42507604,-2.585783258,50.7375,1.484333819,9.889191775,-2.708125,7.814438327,-1.768222355,81.451505 +71.47,50.42507618,-2.585781866,50.7644,1.48433383,9.889635928,-2.6746875,7.718848054,-1.854233175,81.44397995 +71.48,50.42507631,-2.585780474,50.791,1.480857644,9.889191803,-2.6403125,7.622689979,-1.938627051,81.43645483 +71.49,50.42507644,-2.585779083,50.8172,1.487810032,9.888303538,-2.60625,7.525984215,-2.021330472,81.42892978 +71.5,50.42507658,-2.585777691,50.8431,1.498238617,9.887415272,-2.5715625,7.42875087,-2.102271188,81.42140466 +71.51,50.42507671,-2.5857763,50.8687,1.501714812,9.886971145,-2.5346875,7.331010344,-2.181378726,81.41387961 +71.52,50.42507685,-2.585774909,50.8938,1.50171481,9.887193225,-2.4965625,7.232783033,-2.258584044,81.4063545 +71.53,50.42507698,-2.585773517,50.9186,1.501714813,9.887193235,-2.4584375,7.134089448,-2.333819877,81.39882944 +71.54,50.42507712,-2.585772126,50.943,1.501714823,9.886971175,-2.419375,7.03495016,-2.407020564,81.39130433 +71.55,50.42507725,-2.585770735,50.967,1.501714834,9.887193254,-2.378125,6.935385851,-2.478122334,81.38377927 +71.56,50.42507739,-2.585769343,50.9906,1.501714844,9.887193263,-2.335,6.835417436,-2.54706308,81.37625416 +71.57,50.42507752,-2.585767952,51.0137,1.501714849,9.8869712,-2.2915625,6.735065654,-2.613782812,81.3687291 +71.58,50.42507766,-2.585766561,51.0364,1.50171485,9.887193276,-2.248125,6.634351591,-2.678223261,81.36120399 +71.59,50.42507779,-2.585765169,51.0587,1.501714851,9.886971213,-2.203125,6.53329616,-2.740328219,81.35367893 +71.6,50.42507793,-2.585763778,51.0805,1.501714852,9.885860873,-2.1565625,6.43192056,-2.800043656,81.34615382 +71.61,50.42507806,-2.585762387,51.1018,1.501714859,9.884972601,-2.1096875,6.330245933,-2.85731732,81.33862876 +71.62,50.4250782,-2.585760996,51.1227,1.501714873,9.884750536,-2.0615625,6.228293422,-2.912099419,81.33110365 +71.63,50.42507833,-2.585759605,51.1431,1.501714875,9.884972608,-2.0115625,6.126084455,-2.964342111,81.3235786 +71.64,50.42507847,-2.585758214,51.1629,1.505191057,9.885860887,-1.961875,6.023640346,-3.013999848,81.31605354 +71.65,50.4250786,-2.585756823,51.1823,1.515619634,9.886749167,-1.913125,5.92098241,-3.061029312,81.30852843 +71.66,50.42507874,-2.585755431,51.2012,1.522572038,9.885860891,-1.8628125,5.818132188,-3.105389538,81.30100337 +71.67,50.42507888,-2.58575404,51.2196,1.515619673,9.883862267,-1.81,5.715111053,-3.147041851,81.29347826 +71.68,50.42507901,-2.58575265,51.2374,1.505191103,9.883640196,-1.7565625,5.611940606,-3.185949868,81.2859532 +71.69,50.42507915,-2.585751259,51.2547,1.505191099,9.884750541,-1.7034375,5.508642389,-3.22207967,81.27842809 +71.7,50.42507928,-2.585749867,51.2715,1.515619666,9.884528469,-1.6496875,5.405237888,-3.255399801,81.27090303 +71.71,50.42507942,-2.585748477,51.2877,1.522572048,9.883640189,-1.595,5.301748819,-3.285881156,81.26337792 +71.72,50.42507956,-2.585747086,51.3034,1.519095864,9.883862254,-1.5396875,5.198196667,-3.313497149,81.25585286 +71.73,50.42507969,-2.585745695,51.3185,1.519095874,9.884528457,-1.483125,5.094603204,-3.338223773,81.24832775 +71.74,50.42507983,-2.585744304,51.3331,1.522572074,9.884528451,-1.425,4.990989918,-3.36003937,81.2408027 +71.75,50.42507997,-2.585742913,51.347,1.519095888,9.883640166,-1.366875,4.887378522,-3.378924975,81.23327758 +71.76,50.4250801,-2.585741522,51.3604,1.522572077,9.882307742,-1.31,4.783790675,-3.394864146,81.22575253 +71.77,50.42508024,-2.585740132,51.3732,1.536476842,9.881419457,-1.2528125,4.680247977,-3.4078429,81.21822741 +71.78,50.42508038,-2.585738741,51.3855,1.536476852,9.881419448,-1.193125,4.576772028,-3.417850009,81.21070236 +71.79,50.42508052,-2.585737351,51.3971,1.522572092,9.882307715,-1.1315625,4.473384487,-3.424876649,81.20317724 +71.8,50.42508065,-2.58573596,51.4081,1.522572092,9.88341805,-1.0703125,4.370106896,-3.428916746,81.19565219 +71.81,50.42508079,-2.585734569,51.4185,1.539953052,9.883418037,-1.01,4.266960914,-3.429966806,81.18812708 +71.82,50.42508093,-2.585733178,51.4283,1.550381627,9.882307676,-0.9496875,4.163967969,-3.428025912,81.18060202 +71.83,50.42508107,-2.585731788,51.4375,1.539953055,9.881197315,-0.8884375,4.061149604,-3.423095667,81.17307691 +71.84,50.42508121,-2.585730397,51.4461,1.522572104,9.880309022,-0.8265625,3.958527362,-3.415180484,81.16555185 +71.85,50.42508134,-2.585729007,51.454,1.522572104,9.880086937,-0.7646875,3.856122558,-3.404287181,81.15802674 +71.86,50.42508148,-2.585727617,51.4614,1.539953052,9.881197266,-0.701875,3.753956678,-3.39042527,81.15050168 +71.87,50.42508162,-2.585726226,51.4681,1.553857819,9.882085524,-0.638125,3.652050977,-3.373606896,81.14297657 +71.88,50.42508176,-2.585724835,51.4741,1.553857836,9.881197227,-0.575,3.550426828,-3.35384667,81.13545151 +71.89,50.4250819,-2.585723445,51.4796,1.539953083,9.88008686,-0.5115625,3.449105373,-3.331161839,81.1279264 +71.9,50.42508204,-2.585722055,51.4844,1.522572122,9.880086839,-0.4465625,3.34810781,-3.305572226,81.12040134 +71.91,50.42508217,-2.585720664,51.4885,1.522572108,9.879864748,-0.3821875,3.247455226,-3.277100062,81.11287623 +71.92,50.42508231,-2.585719274,51.492,1.539953055,9.878976447,-0.3196875,3.147168647,-3.245770214,81.10535118 +71.93,50.42508245,-2.585717884,51.4949,1.553857828,9.878976423,-0.2565625,3.047268986,-3.211610012,81.09782606 +71.94,50.42508259,-2.585716494,51.4972,1.557334029,9.879864675,-0.1915625,2.947777157,-3.17464925,81.09030101 +71.95,50.42508273,-2.585715103,51.4987,1.55733403,9.879864648,-0.126875,2.8487139,-3.134920127,81.08277589 +71.96,50.42508287,-2.585713713,51.4997,1.557334032,9.878754273,-0.0634375,2.750099899,-3.092457365,81.07525084 +71.97,50.42508301,-2.585712323,51.5,1.557334041,9.877865967,0.000625,2.651955724,-3.047297863,81.06772572 +71.98,50.42508315,-2.585710933,51.4997,1.557334039,9.877643869,0.06625,2.554301943,-2.999481097,81.06020067 +71.99,50.42508329,-2.585709543,51.4987,1.557334023,9.877643838,0.131875,2.457158954,-2.949048779,81.05267561 +72,50.42508343,-2.585708153,51.497,1.557334019,9.877643806,0.19625,2.360546983,-2.896044797,81.0451505 +72.01,50.42508357,-2.585706763,51.4948,1.557334029,9.877643774,0.26,2.264486197,-2.840515447,81.03762544 +72.02,50.42508371,-2.585705373,51.4918,1.557334031,9.87764374,0.3234375,2.168996707,-2.782509085,81.03010033 +72.03,50.42508385,-2.585703983,51.4883,1.557334025,9.877643705,0.3865625,2.074098452,-2.722076362,81.02257528 +72.04,50.42508399,-2.585702593,51.4841,1.557334029,9.87764367,0.4503125,1.9798112,-2.659269931,81.01505016 +72.05,50.42508413,-2.585701203,51.4793,1.557334028,9.877643633,0.515,1.886154659,-2.594144626,81.00752511 +72.06,50.42508427,-2.585699813,51.4738,1.557334022,9.877643596,0.5796875,1.793148483,-2.526757112,80.99999999 +72.07,50.42508441,-2.585698423,51.4677,1.557334027,9.877643557,0.643125,1.70081198,-2.457166288,80.99247494 +72.08,50.42508455,-2.585697033,51.4609,1.560810224,9.877421448,0.705,1.609164458,-2.385432774,80.98494982 +72.09,50.42508469,-2.585695643,51.4536,1.57471499,9.87653313,0.766875,1.518225055,-2.31161908,80.97742477 +72.1,50.42508483,-2.585694253,51.4456,1.592095946,9.875422742,0.83,1.428012793,-2.235789663,80.96989966 +72.11,50.42508498,-2.585692864,51.437,1.592095937,9.875422699,0.8928125,1.338546522,-2.158010585,80.9623746 +72.12,50.42508512,-2.585691474,51.4277,1.574714966,9.876310932,0.9534375,1.249844863,-2.078349742,80.95484949 +72.13,50.42508526,-2.585690084,51.4179,1.560810194,9.876088818,1.0134375,1.16192638,-1.996876461,80.94732443 +72.14,50.4250854,-2.585688694,51.4075,1.560810198,9.874312218,1.075,1.074809408,-1.913661962,80.93979932 +72.15,50.42508554,-2.585687305,51.3964,1.574714969,9.873201825,1.1365625,0.988512224,-1.828778665,80.93227426 +72.16,50.42508568,-2.585685916,51.3847,1.592095926,9.874090055,1.19625,0.903052761,-1.742300656,80.92474915 +72.17,50.42508583,-2.585684526,51.3725,1.592095923,9.875200353,1.255,0.818448839,-1.654303334,80.91722409 +72.18,50.42508597,-2.585683136,51.3596,1.574714958,9.874978234,1.3134375,0.734718277,-1.564863419,80.90969898 +72.19,50.42508611,-2.585681747,51.3462,1.564286369,9.874089907,1.37125,0.651878377,-1.474058947,80.90217392 +72.2,50.42508625,-2.585680357,51.3322,1.574714941,9.873201579,1.4284375,0.569946558,-1.381969103,80.89464881 +72.21,50.42508639,-2.585678968,51.3176,1.59209591,9.872757388,1.485,0.488939894,-1.288674098,80.88712376 +72.22,50.42508654,-2.585677579,51.3025,1.592095908,9.873201473,1.5415625,0.408875345,-1.194255352,80.87959864 +72.23,50.42508668,-2.585676189,51.2868,1.578191131,9.873867627,1.598125,0.329769583,-1.098795255,80.87207359 +72.24,50.42508682,-2.5856748,51.2705,1.578191131,9.874089641,1.653125,0.25163911,-1.002376943,80.86454847 +72.25,50.42508696,-2.58567341,51.2537,1.592095896,9.874089586,1.7065625,0.174500255,-0.905084584,80.85702342 +72.26,50.42508711,-2.585672021,51.2364,1.59557208,9.873867461,1.76,0.098369176,-0.807002918,80.8494983 +72.27,50.42508725,-2.585670631,51.2185,1.592095887,9.872979127,1.813125,0.023261743,-0.708217603,80.84197325 +72.28,50.42508739,-2.585669242,51.2001,1.595572073,9.871646653,1.865,-0.050806345,-0.60881464,80.83444814 +72.29,50.42508754,-2.585667853,51.1812,1.595572057,9.870980385,1.9165625,-0.123819675,-0.508880831,80.82692308 +72.3,50.42508768,-2.585666464,51.1618,1.592095862,9.871424463,1.968125,-0.195762948,-0.408503266,80.81939797 +72.31,50.42508782,-2.585665075,51.1418,1.595572058,9.871868542,2.0178125,-0.266621154,-0.307769494,80.81187291 +72.32,50.42508797,-2.585663685,51.1214,1.595572051,9.871646411,2.065,-0.336379511,-0.20676729,80.8043478 +72.33,50.42508811,-2.585662297,51.1005,1.592095847,9.871646349,2.111875,-0.405023407,-0.105584834,80.79682274 +72.34,50.42508825,-2.585660907,51.0792,1.599048226,9.871868356,2.1596875,-0.472538519,-0.004310247,80.78929769 +72.35,50.4250884,-2.585659518,51.0573,1.609476804,9.871424153,2.2065625,-0.538910752,0.096968065,80.78177257 +72.36,50.42508854,-2.585658129,51.035,1.612952995,9.870757881,2.25125,-0.604126298,0.198161808,80.77424752 +72.37,50.42508869,-2.58565674,51.0123,1.612952987,9.870535746,2.295,-0.66817152,0.299182747,80.7667224 +72.38,50.42508883,-2.585655351,50.9891,1.609476789,9.870313611,2.338125,-0.731032955,0.399942818,80.75919735 +72.39,50.42508898,-2.585653962,50.9655,1.599048207,9.869425268,2.3796875,-0.792697537,0.50035413,80.75167224 +72.4,50.42508912,-2.585652573,50.9415,1.592095808,9.868314855,2.42,-0.853152434,0.600329078,80.74414718 +72.41,50.42508926,-2.585651185,50.9171,1.599048183,9.868314787,2.4596875,-0.912384926,0.699780571,80.73662207 +72.42,50.42508941,-2.585649796,50.8923,1.609476765,9.869425065,2.4984375,-0.97038275,0.798621864,80.72909701 +72.43,50.42508955,-2.585648407,50.8671,1.61295295,9.870313273,2.53625,-1.027133704,0.896766727,80.7215719 +72.44,50.4250897,-2.585647018,50.8416,1.612952933,9.870313203,2.573125,-1.082625927,0.994129559,80.71404684 +72.45,50.42508984,-2.585645629,50.8156,1.612952929,9.869424856,2.6084375,-1.13684796,1.090625564,80.70652173 +72.46,50.42508999,-2.58564424,50.7894,1.616429121,9.868314439,2.643125,-1.189788344,1.186170459,80.69899667 +72.47,50.42509013,-2.585642852,50.7628,1.626857683,9.868092299,2.678125,-1.24143602,1.280681051,80.69147156 +72.48,50.42509028,-2.585641463,50.7358,1.633810058,9.868314296,2.71125,-1.291780332,1.374074833,80.6839465 +72.49,50.42509043,-2.585640074,50.7085,1.626857678,9.867870085,2.74125,-1.340810679,1.466270446,80.67642139 +72.5,50.42509057,-2.585638686,50.681,1.616429098,9.867203804,2.77,-1.388516807,1.557187389,80.66889634 +72.51,50.42509072,-2.585637297,50.6531,1.616429086,9.866981661,2.7984375,-1.434888745,1.646746479,80.66137122 +72.52,50.42509086,-2.585635909,50.625,1.626857659,9.866981587,2.82625,-1.479916868,1.734869622,80.65384617 +72.53,50.42509101,-2.58563452,50.5966,1.633810032,9.866981513,2.853125,-1.523591722,1.821479871,80.64632105 +72.54,50.42509116,-2.585633132,50.5679,1.626857623,9.866981439,2.878125,-1.565904254,1.906501765,80.638796 +72.55,50.4250913,-2.585631743,50.539,1.61642904,9.866981364,2.90125,-1.606845526,1.989861166,80.63127088 +72.56,50.42509145,-2.585630355,50.5099,1.61642905,9.86675922,2.9234375,-1.646407116,2.071485421,80.62374583 +72.57,50.42509159,-2.585628966,50.4805,1.630333812,9.865870867,2.9446875,-1.684580601,2.151303255,80.61622072 +72.58,50.42509174,-2.585627578,50.451,1.647714753,9.864760445,2.9646875,-1.721358189,2.229245167,80.60869566 +72.59,50.42509189,-2.58562619,50.4212,1.647714748,9.864760368,2.9834375,-1.75673203,2.305243091,80.60117055 +72.6,50.42509204,-2.585624802,50.3913,1.633809982,9.865648568,3.00125,-1.790694848,2.37923085,80.59364549 +72.61,50.42509218,-2.585623413,50.3612,1.63033378,9.865648491,3.018125,-1.823239539,2.451143872,80.58612038 +72.62,50.42509233,-2.585622025,50.3309,1.633809957,9.864760137,3.033125,-1.854359226,2.520919474,80.57859532 +72.63,50.42509248,-2.585620637,50.3005,1.630333756,9.864760059,3.04625,-1.884047492,2.588496752,80.57107021 +72.64,50.42509262,-2.585619249,50.27,1.633809939,9.865648258,3.0584375,-1.91229815,2.653816863,80.56354515 +72.65,50.42509277,-2.58561786,50.2393,1.647714701,9.865648181,3.0696875,-1.939105184,2.716822797,80.55602004 +72.66,50.42509292,-2.585616472,50.2086,1.6477147,9.864537757,3.0796875,-1.96446315,2.777459608,80.54849498 +72.67,50.42509307,-2.585615084,50.1777,1.633809929,9.863649402,3.088125,-1.988366663,2.835674469,80.54096987 +72.68,50.42509321,-2.585613696,50.1468,1.633809917,9.863427254,3.0946875,-2.010810737,2.891416559,80.53344482 +72.69,50.42509336,-2.585612308,50.1158,1.651190861,9.863427175,3.1,-2.031790676,2.944637233,80.52591976 +72.7,50.42509351,-2.58561092,50.0848,1.661619425,9.863427097,3.1046875,-2.051302123,2.995290198,80.51839465 +72.71,50.42509366,-2.585609532,50.0537,1.651190843,9.863427018,3.108125,-2.069341012,3.043331219,80.51086959 +72.72,50.42509381,-2.585608144,50.0226,1.633809877,9.863426939,3.1096875,-2.08590356,3.088718414,80.50334448 +72.73,50.42509395,-2.585606756,49.9915,1.633809868,9.863204791,3.1096875,-2.100986273,3.131412193,80.49581942 +72.74,50.4250941,-2.585605368,49.9604,1.651190818,9.862316435,3.108125,-2.114586056,3.171375369,80.48829431 +72.75,50.42509425,-2.58560398,49.9293,1.665095577,9.86120601,3.105,-2.126700046,3.208573049,80.48076925 +72.76,50.4250944,-2.585602593,49.8983,1.66857176,9.861205932,3.10125,-2.13732572,3.242972748,80.47324414 +72.77,50.42509455,-2.585601205,49.8673,1.668571752,9.862316199,3.0965625,-2.146460844,3.274544556,80.46571908 +72.78,50.4250947,-2.585599817,49.8363,1.668571744,9.862982328,3.0896875,-2.154103528,3.303260914,80.45819397 +72.79,50.42509485,-2.585598429,49.8055,1.668571736,9.862316041,3.0815625,-2.160252225,3.329096841,80.45066892 +72.8,50.425095,-2.585597041,49.7747,1.668571728,9.860983547,3.0734375,-2.164905502,3.352029649,80.4431438 +72.81,50.42509515,-2.585595654,49.744,1.665095529,9.860095192,3.064375,-2.168062556,3.372039512,80.43561875 +72.82,50.4250953,-2.585594266,49.7134,1.651190757,9.860095114,3.053125,-2.169722587,3.389108842,80.42809363 +72.83,50.42509545,-2.585592879,49.6829,1.633809799,9.860761244,3.0396875,-2.169885364,3.403222855,80.42056858 +72.84,50.42509559,-2.585591491,49.6526,1.633809793,9.861205305,3.025,-2.168550774,3.414369233,80.41304346 +72.85,50.42509574,-2.585590103,49.6224,1.651190731,9.860761089,3.0096875,-2.165719159,3.422538179,80.40551841 +72.86,50.42509589,-2.585588716,49.5924,1.668571669,9.859872735,2.993125,-2.161391036,3.427722645,80.3979933 +72.87,50.42509604,-2.585587328,49.5625,1.68595262,9.858984381,2.9746875,-2.155567378,3.429918105,80.39046824 +72.88,50.42509619,-2.585585941,49.5329,1.703333576,9.858540165,2.9546875,-2.148249332,3.429122553,80.38294313 +72.89,50.42509635,-2.585584554,49.5034,1.703333571,9.858762157,2.9334375,-2.139438502,3.425336849,80.37541807 +72.9,50.4250965,-2.585583166,49.4742,1.685952606,9.858762081,2.91125,-2.129136663,3.418564144,80.36789296 +72.91,50.42509665,-2.585581779,49.4452,1.672047834,9.858539936,2.8884375,-2.117345994,3.408810397,80.3603679 +72.92,50.4250968,-2.585580392,49.4164,1.668571635,9.858761929,2.8646875,-2.104069015,3.396084145,80.35284279 +72.93,50.42509695,-2.585579004,49.3879,1.668571627,9.858539784,2.8396875,-2.089308362,3.380396446,80.34531773 +72.94,50.4250971,-2.585577617,49.3596,1.66857162,9.857651433,2.813125,-2.073067243,3.361760993,80.33779262 +72.95,50.42509725,-2.58557623,49.3316,1.668571613,9.857651359,2.784375,-2.055349039,3.340194003,80.33026756 +72.96,50.4250974,-2.585574843,49.3039,1.668571605,9.858539562,2.7534375,-2.036157359,3.315714381,80.32274245 +72.97,50.42509755,-2.585573455,49.2765,1.672047789,9.858539488,2.7215625,-2.015496272,3.288343327,80.3152174 +72.98,50.4250977,-2.585572068,49.2495,1.685952547,9.857429069,2.69,-1.993370131,3.25810485,80.30769228 +72.99,50.42509785,-2.585570681,49.2227,1.703333496,9.856540719,2.6584375,-1.969783464,3.225025246,80.30016723 +73,50.42509801,-2.585569294,49.1963,1.703333489,9.856318578,2.6259375,-1.944741255,3.189133336,80.29264211 +73.01,50.42509816,-2.585567907,49.1702,1.685952526,9.856318507,2.5915625,-1.918248775,3.150460518,80.28511706 +73.02,50.42509831,-2.58556652,49.1444,1.672047755,9.856318436,2.5546875,-1.890311468,3.109040368,80.277592 +73.03,50.42509846,-2.585565133,49.1191,1.672047748,9.856318365,2.5165625,-1.860935177,3.064909153,80.27006689 +73.04,50.42509861,-2.585563746,49.0941,1.685952506,9.856318294,2.4784375,-1.83012609,3.018105262,80.26254183 +73.05,50.42509876,-2.585562359,49.0695,1.703333455,9.856318225,2.439375,-1.797890625,2.968669547,80.25501672 +73.06,50.42509892,-2.585560972,49.0453,1.703333449,9.856096087,2.3984375,-1.764235543,2.916645151,80.24749166 +73.07,50.42509907,-2.585559585,49.0215,1.689428676,9.855207742,2.35625,-1.729167775,2.862077338,80.23996655 +73.08,50.42509922,-2.585558198,48.9982,1.689428663,9.854097329,2.3134375,-1.692694772,2.805013779,80.23244149 +73.09,50.42509937,-2.585556812,48.9752,1.703333419,9.854097262,2.27,-1.654824038,2.745504205,80.22491638 +73.1,50.42509953,-2.585555425,48.9528,1.706809615,9.854985472,2.22625,-1.615563537,2.683600469,80.21739133 +73.11,50.42509968,-2.585554038,48.9307,1.703333427,9.854985406,2.1815625,-1.574921464,2.61935666,80.20986621 +73.12,50.42509983,-2.585552651,48.9091,1.706809604,9.854097065,2.1346875,-1.532906297,2.552828697,80.20234116 +73.13,50.42509999,-2.585551265,48.888,1.706809589,9.853874931,2.0865625,-1.48952686,2.484074621,80.19481604 +73.14,50.42510014,-2.585549878,48.8674,1.703333402,9.854096936,2.0384375,-1.444792091,2.413154421,80.18729099 +73.15,50.42510029,-2.585548491,48.8472,1.706809596,9.853874805,1.9896875,-1.398711445,2.340129861,80.17976588 +73.16,50.42510045,-2.585547105,48.8276,1.70680958,9.853874742,1.9396875,-1.351294546,2.265064712,80.17224082 +73.17,50.4251006,-2.585545718,48.8084,1.703333368,9.853874681,1.8884375,-1.302551251,2.188024406,80.16471571 +73.18,50.42510075,-2.585544331,48.7898,1.706809561,9.852764275,1.83625,-1.252491699,2.109076093,80.15719065 +73.19,50.42510091,-2.585542945,48.7717,1.706809576,9.851653869,1.78375,-1.201126434,2.028288643,80.14966554 +73.2,50.42510106,-2.585541559,48.7541,1.703333381,9.85165381,1.73125,-1.148466112,1.945732472,80.14214048 +73.21,50.42510121,-2.585540172,48.7371,1.710285736,9.851653752,1.678125,-1.094521792,1.861479659,80.13461537 +73.22,50.42510137,-2.585538786,48.7205,1.720714291,9.851431625,1.623125,-1.039304703,1.775603541,80.12709031 +73.23,50.42510152,-2.5855374,48.7046,1.724190491,9.851653638,1.5665625,-0.982826362,1.688179062,80.1195652 +73.24,50.42510168,-2.585536013,48.6892,1.724190509,9.851431513,1.5103125,-0.92509863,1.59928254,80.11204014 +73.25,50.42510183,-2.585534627,48.6744,1.724190505,9.850543182,1.4546875,-0.866133481,1.508991325,80.10451503 +73.26,50.42510199,-2.585533241,48.6601,1.724190481,9.850543127,1.398125,-0.80594329,1.417384311,80.09698997 +73.27,50.42510214,-2.585531855,48.6464,1.724190471,9.85143135,1.34,-0.744540549,1.324541314,80.08946486 +73.28,50.4251023,-2.585530468,48.6333,1.724190483,9.851431298,1.2815625,-0.681938207,1.23054329,80.08193981 +73.29,50.42510245,-2.585529082,48.6208,1.72419049,9.850320901,1.223125,-0.618149211,1.135472231,80.07441469 +73.3,50.42510261,-2.585527696,48.6088,1.724190476,9.849432573,1.163125,-0.55318697,1.039410987,80.06688964 +73.31,50.42510276,-2.58552631,48.5975,1.724190455,9.849210455,1.101875,-0.487064947,0.94244338,80.05936452 +73.32,50.42510292,-2.585524924,48.5868,1.724190453,9.849210407,1.0415625,-0.419797124,0.844653923,80.05183947 +73.33,50.42510307,-2.585523538,48.5767,1.724190468,9.849210359,0.9815625,-0.351397365,0.746127929,80.04431436 +73.34,50.42510323,-2.585522152,48.5671,1.724190476,9.849210312,0.92,-0.281880052,0.646951341,80.0367893 +73.35,50.42510338,-2.585520766,48.5583,1.724190465,9.849210266,0.858125,-0.211259738,0.547210562,80.02926419 +73.36,50.42510354,-2.58551938,48.55,1.727666642,9.849210221,0.796875,-0.139551033,0.446992623,80.02173913 +73.37,50.42510369,-2.585517994,48.5423,1.738095213,9.849210177,0.734375,-0.066769064,0.346384844,80.01421407 +73.38,50.42510385,-2.585516608,48.5353,1.745047593,9.849210134,0.6703125,0.007071044,0.245475058,80.00668896 +73.39,50.42510401,-2.585515222,48.5289,1.738095209,9.848988022,0.606875,0.081953878,0.144351216,79.99916391 +73.4,50.42510416,-2.585513836,48.5232,1.727666646,9.848099704,0.5446875,0.157863738,0.043101495,79.99163879 +73.41,50.42510432,-2.58551245,48.518,1.727666654,9.84676725,0.4815625,0.234784869,-0.058185812,79.98411374 +73.42,50.42510447,-2.585511065,48.5135,1.738095214,9.845878934,0.4165625,0.31270117,-0.159422355,79.97658862 +73.43,50.42510463,-2.585509679,48.5097,1.745047577,9.845878896,0.351875,0.391596313,-0.260519899,79.96906357 +73.44,50.42510479,-2.585508294,48.5065,1.741571385,9.846767134,0.2884375,0.471453853,-0.361390264,79.96153846 +73.45,50.42510494,-2.585506908,48.5039,1.745047593,9.847877443,0.2246875,0.552257174,-0.461945503,79.9540134 +73.46,50.4251051,-2.585505522,48.502,1.758952367,9.847877408,0.16,0.633989259,-0.562097896,79.94648829 +73.47,50.42510526,-2.585504136,48.5007,1.758952356,9.846767028,0.0953125,0.716633207,-0.66176018,79.93896323 +73.48,50.42510542,-2.585502751,48.5001,1.745047572,9.845656649,0.0315625,0.800171657,-0.760845324,79.93143812 +73.49,50.42510557,-2.585501365,48.5001,1.741571375,9.84476834,-0.031875,0.884587191,-0.859267097,79.92391306 +73.5,50.42510573,-2.58549998,48.5007,1.745047581,9.84432417,-0.096875,0.969862161,-0.956939499,79.91638795 +73.51,50.42510589,-2.585498595,48.502,1.741571413,9.844768277,-0.163125,1.055978806,-1.053777445,79.90886289 +73.52,50.42510604,-2.585497209,48.504,1.745047605,9.845434455,-0.228125,1.142919078,-1.149696481,79.90133778 +73.53,50.4251062,-2.585495824,48.5066,1.762428537,9.845656496,-0.2915625,1.230664872,-1.244613014,79.89381272 +73.54,50.42510636,-2.585494438,48.5098,1.772857095,9.845656469,-0.355,1.319197852,-1.338444192,79.88628761 +73.55,50.42510652,-2.585493053,48.5137,1.76242853,9.845434372,-0.4184375,1.408499512,-1.431108198,79.87876255 +73.56,50.42510668,-2.585491667,48.5182,1.745047598,9.84454607,-0.4815625,1.498551174,-1.522524301,79.87123744 +73.57,50.42510683,-2.585490282,48.5233,1.74504761,9.8434357,-0.5453125,1.589334102,-1.61261269,79.86371239 +73.58,50.42510699,-2.585488897,48.5291,1.762428557,9.843213606,-0.6096875,1.680829332,-1.701294926,79.85618727 +73.59,50.42510715,-2.585487512,48.5355,1.776333311,9.843435652,-0.673125,1.773017668,-1.788493544,79.84866222 +73.6,50.42510731,-2.585486126,48.5426,1.779809504,9.843213561,-0.735,1.865879974,-1.874132629,79.8411371 +73.61,50.42510747,-2.585484742,48.5502,1.776333313,9.843213539,-0.796875,1.959396771,-1.958137409,79.83361205 +73.62,50.42510763,-2.585483356,48.5585,1.762428543,9.843435588,-0.86,2.053548519,-2.040434661,79.82608694 +73.63,50.42510779,-2.585481971,48.5674,1.745047594,9.842991431,-0.9228125,2.148315681,-2.120952591,79.81856188 +73.64,50.42510794,-2.585480586,48.577,1.745047614,9.842325206,-0.9834375,2.243678318,-2.199621072,79.81103677 +73.65,50.4251081,-2.585479201,48.5871,1.762428582,9.841881051,-1.043125,2.339616605,-2.276371461,79.80351171 +73.66,50.42510826,-2.585477816,48.5978,1.776333337,9.840992758,-1.10375,2.43611049,-2.351136781,79.7959866 +73.67,50.42510842,-2.585476431,48.6092,1.779809512,9.839882397,-1.1646875,2.533139747,-2.423851886,79.78846154 +73.68,50.42510858,-2.585475047,48.6211,1.779809506,9.839882382,-1.2246875,2.630684265,-2.49445335,79.78093643 +73.69,50.42510874,-2.585473662,48.6337,1.779809518,9.840992714,-1.2834375,2.728723531,-2.562879637,79.77341137 +73.7,50.4251089,-2.585472277,48.6468,1.779809542,9.841880978,-1.34125,2.827237093,-2.629070987,79.76588626 +73.71,50.42510906,-2.585470892,48.6605,1.779809557,9.842103035,-1.39875,2.926204494,-2.692969819,79.7583612 +73.72,50.42510922,-2.585469507,48.6748,1.77980955,9.841880954,-1.45625,3.025604936,-2.754520326,79.75083615 +73.73,50.42510938,-2.585468122,48.6896,1.779809537,9.840992667,-1.5134375,3.125417679,-2.813668822,79.74331103 +73.74,50.42510954,-2.585466737,48.7051,1.779809539,9.839660243,-1.5696875,3.225621924,-2.870363798,79.73578598 +73.75,50.4251097,-2.585465353,48.721,1.779809552,9.838771958,-1.6246875,3.326196758,-2.92455575,79.72826087 +73.76,50.42510986,-2.585463968,48.7376,1.779809559,9.838771951,-1.67875,3.427121097,-2.976197468,79.72073581 +73.77,50.42511002,-2.585462584,48.7546,1.779809564,9.839438151,-1.7328125,3.528373912,-3.025243858,79.7132107 +73.78,50.42511018,-2.585461199,48.7722,1.783285771,9.839882283,-1.786875,3.629934119,-3.071652236,79.70568564 +73.79,50.42511034,-2.585459814,48.7904,1.797190548,9.839438139,-1.839375,3.731780403,-3.115382094,79.69816053 +73.8,50.4251105,-2.58545843,48.809,1.814571497,9.838549858,-1.89,3.833891509,-3.156395215,79.69063547 +73.81,50.42511067,-2.585457045,48.8282,1.814571483,9.837439508,-1.9403125,3.936246179,-3.194655962,79.68311036 +73.82,50.42511083,-2.585455661,48.8478,1.797190523,9.83632916,-1.99125,4.038822985,-3.23013093,79.6755853 +73.83,50.42511099,-2.585454277,48.868,1.783285765,9.836551227,-2.0415625,4.141600556,-3.262789181,79.66806019 +73.84,50.42511115,-2.585452893,48.8887,1.77980959,9.838327778,-2.089375,4.244557347,-3.292602237,79.66053513 +73.85,50.42511131,-2.585451508,48.9098,1.783285807,9.839438122,-2.135,4.347671931,-3.319544031,79.65301002 +73.86,50.42511147,-2.585450123,48.9314,1.797190589,9.838327776,-2.1803125,4.450922765,-3.343591184,79.64548497 +73.87,50.42511163,-2.585448739,48.9534,1.814571539,9.836329155,-2.22625,4.55428819,-3.36472267,79.63795985 +73.88,50.4251118,-2.585447355,48.9759,1.814571528,9.83521881,-2.2715625,4.657746778,-3.382920096,79.6304348 +73.89,50.42511196,-2.585445971,48.9989,1.797190577,9.835218812,-2.3146875,4.761276814,-3.398167534,79.62290968 +73.9,50.42511212,-2.585444587,49.0222,1.786762019,9.836107091,-2.356875,4.864856697,-3.410451692,79.61538463 +73.91,50.42511228,-2.585443203,49.046,1.797190599,9.83721744,-2.3996875,4.96846477,-3.419761912,79.60785951 +73.92,50.42511244,-2.585441818,49.0702,1.81457155,9.837217444,-2.44125,5.072079489,-3.426090059,79.60033446 +73.93,50.42511261,-2.585440434,49.0949,1.814571553,9.836107102,-2.48,5.175679139,-3.429430632,79.59280935 +73.94,50.42511277,-2.58543905,49.1198,1.800666811,9.835218831,-2.518125,5.279242062,-3.429780652,79.58528429 +73.95,50.42511293,-2.585437666,49.1452,1.80066684,9.834774698,-2.5565625,5.382746716,-3.427139832,79.57775918 +73.96,50.42511309,-2.585436282,49.171,1.814571612,9.834108496,-2.5928125,5.486171442,-3.421510522,79.57023412 +73.97,50.42511326,-2.585434898,49.1971,1.814571598,9.833664364,-2.6265625,5.589494583,-3.412897591,79.56270901 +73.98,50.42511342,-2.585433515,49.2235,1.800666825,9.83388644,-2.66,5.692694653,-3.401308603,79.55518395 +73.99,50.42511358,-2.58543213,49.2503,1.800666837,9.833886449,-2.693125,5.79575005,-3.386753584,79.54765884 +74,50.42511374,-2.585430747,49.2774,1.818047812,9.833664388,-2.7246875,5.89863929,-3.369245255,79.54013378 +74.01,50.42511391,-2.585429363,49.3048,1.831952585,9.833886465,-2.7546875,6.001340829,-3.348798912,79.53260867 +74.02,50.42511407,-2.585427979,49.3325,1.831952582,9.833664404,-2.7834375,6.103833296,-3.325432375,79.52508361 +74.03,50.42511424,-2.585426595,49.3605,1.821524007,9.832776136,-2.8115625,6.206095204,-3.299166042,79.5175585 +74.04,50.4251144,-2.585425212,49.3887,1.814571635,9.832554077,-2.8396875,6.30810524,-3.270022715,79.51003345 +74.05,50.42511456,-2.585423828,49.4173,1.818047852,9.832776156,-2.86625,6.40984209,-3.23802795,79.50250833 +74.06,50.42511473,-2.585422444,49.4461,1.818047882,9.832554098,-2.8896875,6.511284497,-3.203209534,79.49498328 +74.07,50.42511489,-2.585421061,49.4751,1.814571699,9.832554108,-2.9115625,6.612411318,-3.165597834,79.48745822 +74.08,50.42511505,-2.585419677,49.5043,1.821524068,9.832554119,-2.9334375,6.713201413,-3.125225738,79.47993311 +74.09,50.42511522,-2.585418293,49.5338,1.831952635,9.831443785,-2.9546875,6.813633695,-3.082128426,79.47240805 +74.1,50.42511538,-2.58541691,49.5634,1.83542884,9.830333452,-2.9746875,6.913687252,-3.036343426,79.46488294 +74.11,50.42511555,-2.585415527,49.5933,1.835428859,9.830555532,-2.993125,7.013341171,-2.987910673,79.45735788 +74.12,50.42511571,-2.585414143,49.6233,1.835428868,9.831221751,-3.0096875,7.112574596,-2.936872395,79.44983277 +74.13,50.42511588,-2.58541276,49.6535,1.835428866,9.831221763,-3.025,7.211366844,-2.883273167,79.44230771 +74.14,50.42511604,-2.585411376,49.6838,1.835428866,9.830555568,-3.0396875,7.309697288,-2.827159686,79.4347826 +74.15,50.42511621,-2.585409993,49.7143,1.835428875,9.830111443,-3.053125,7.407545416,-2.768580825,79.42725755 +74.16,50.42511637,-2.58540861,49.7449,1.835428892,9.830333525,-3.0646875,7.504890716,-2.707587749,79.41973243 +74.17,50.42511654,-2.585407226,49.7756,1.835428914,9.830111469,-3.0746875,7.601712906,-2.644233628,79.41220738 +74.18,50.4251167,-2.585405843,49.8064,1.835428932,9.829001137,-3.083125,7.69799176,-2.578573696,79.40468226 +74.19,50.42511687,-2.58540446,49.8373,1.835428941,9.828334943,-3.09,7.793707167,-2.510665191,79.39715721 +74.2,50.42511703,-2.585403077,49.8682,1.835428943,9.829001164,-3.0965625,7.888839131,-2.440567357,79.38963209 +74.21,50.4251172,-2.585401694,49.8992,1.83890514,9.830111523,-3.103125,7.983367828,-2.368341329,79.38210704 +74.22,50.42511736,-2.58540031,49.9303,1.849333726,9.830111536,-3.1078125,8.077273491,-2.294050074,79.37458193 +74.23,50.42511753,-2.585398927,49.9614,1.856286116,9.828779134,-3.1096875,8.170536467,-2.217758337,79.36705687 +74.24,50.4251177,-2.585397544,49.9925,1.84933373,9.827224664,-3.1096875,8.263137333,-2.139532696,79.35953176 +74.25,50.42511786,-2.585396161,50.0236,1.838905156,9.826780539,-3.108125,8.35505678,-2.05944139,79.3520067 +74.26,50.42511803,-2.585394779,50.0547,1.838905165,9.827668829,-3.105,8.4462755,-1.977554147,79.34448159 +74.27,50.42511819,-2.585393395,50.0857,1.849333758,9.827890912,-3.1015625,8.536774584,-1.89394253,79.33695653 +74.28,50.42511836,-2.585392012,50.1167,1.856286161,9.82655851,-3.0984375,8.626535012,-1.808679306,79.32943142 +74.29,50.42511853,-2.58539063,50.1477,1.852809978,9.825892316,-3.094375,8.715538047,-1.7218389,79.32190636 +74.3,50.42511869,-2.585389247,50.1786,1.852809976,9.826780606,-3.088125,8.803765182,-1.633497059,79.31438125 +74.31,50.42511886,-2.585387864,50.2095,1.856286168,9.827446826,-3.0796875,8.891197969,-1.54373073,79.30685619 +74.32,50.42511903,-2.585386481,50.2402,1.852809988,9.826780632,-3.0696875,8.977818072,-1.452618294,79.29933108 +74.33,50.42511919,-2.585385098,50.2709,1.856286206,9.825448229,-3.0584375,9.063607501,-1.360239105,79.29180603 +74.34,50.42511936,-2.585383716,50.3014,1.870191004,9.824559965,-3.04625,9.148548322,-1.266673779,79.28428091 +74.35,50.42511953,-2.585382333,50.3318,1.870191013,9.824559977,-3.033125,9.232622717,-1.172003906,79.27675586 +74.36,50.4251197,-2.585380951,50.3621,1.856286233,9.825226196,-3.018125,9.315813209,-1.076312047,79.26923074 +74.37,50.42511986,-2.585379568,50.3922,1.856286224,9.825448277,-3.00125,9.398102382,-0.979681626,79.26170569 +74.38,50.42512003,-2.585378185,50.4221,1.870190998,9.824337943,-2.9834375,9.479473103,-0.882196868,79.25418057 +74.39,50.4251202,-2.585376803,50.4519,1.870191015,9.823227608,-2.9646875,9.559908299,-0.783942857,79.24665552 +74.4,50.42512037,-2.585375421,50.4814,1.856286268,9.823449688,-2.9446875,9.639391239,-0.68500525,79.23913046 +74.41,50.42512053,-2.585374038,50.5108,1.856286277,9.824115906,-2.9234375,9.717905307,-0.585470277,79.23160535 +74.42,50.4251207,-2.585372656,50.5399,1.873667234,9.824337985,-2.9009375,9.795434117,-0.485424741,79.22408029 +74.43,50.42512087,-2.585371273,50.5688,1.884095809,9.824337995,-2.876875,9.871961397,-0.384955961,79.21655518 +74.44,50.42512104,-2.585369891,50.5975,1.873667241,9.824115935,-2.85125,9.947471275,-0.284151486,79.20903013 +74.45,50.42512121,-2.585368508,50.6258,1.856286299,9.823227667,-2.825,10.02194794,-0.183099206,79.20150501 +74.46,50.42512137,-2.585367126,50.654,1.856286319,9.82211733,-2.798125,10.09537586,-0.081887243,79.19397996 +74.47,50.42512154,-2.585365744,50.6818,1.873667287,9.822117338,-2.7696875,10.16773963,0.019396111,79.18645484 +74.48,50.42512171,-2.585364362,50.7094,1.887572052,9.823005622,-2.74,10.23902417,0.120662505,79.17892979 +74.49,50.42512188,-2.585362979,50.7366,1.891048243,9.823005629,-2.709375,10.30921465,0.221823762,79.17140467 +74.5,50.42512205,-2.585361597,50.7636,1.891048249,9.821895289,-2.6765625,10.37829635,0.32279153,79.16387962 +74.51,50.42512222,-2.585360215,50.7902,1.891048259,9.821007019,-2.6415625,10.44625487,0.423477805,79.15635451 +74.52,50.42512239,-2.585358833,50.8164,1.891048276,9.820784955,-2.606875,10.51307602,0.523794865,79.14882945 +74.53,50.42512256,-2.585357451,50.8423,1.891048294,9.820784959,-2.573125,10.5787458,0.623655106,79.14130434 +74.54,50.42512273,-2.585356069,50.8679,1.891048302,9.820562894,-2.5378125,10.6432506,0.722971553,79.13377928 +74.55,50.4251229,-2.585354687,50.8931,1.891048298,9.819674622,-2.4996875,10.70657681,0.821657517,79.12625417 +74.56,50.42512307,-2.585353305,50.9179,1.891048297,9.818564279,-2.4596875,10.76871128,0.919626998,79.11872911 +74.57,50.42512324,-2.585351924,50.9423,1.891048304,9.818564281,-2.4184375,10.82964104,1.016794566,79.111204 +74.58,50.42512341,-2.585350542,50.9663,1.89104832,9.819674628,-2.3765625,10.88935339,1.113075483,79.10367894 +74.59,50.42512358,-2.58534916,50.9898,1.891048338,9.820562906,-2.335,10.94783576,1.208385752,79.09615383 +74.6,50.42512375,-2.585347778,51.013,1.891048345,9.820562906,-2.293125,11.00507602,1.302642294,79.08862877 +74.61,50.42512392,-2.585346396,51.0357,1.891048341,9.81967463,-2.2496875,11.06106225,1.395762947,79.08110366 +74.62,50.42512409,-2.585345014,51.058,1.891048339,9.818342214,-2.2046875,11.11578264,1.487666409,79.07357861 +74.63,50.42512426,-2.585343633,51.0798,1.891048343,9.817453935,-2.158125,11.16922585,1.578272636,79.06605349 +74.64,50.42512443,-2.585342251,51.1012,1.891048354,9.817453933,-2.1103125,11.22138071,1.66750262,79.05852844 +74.65,50.4251246,-2.58534087,51.122,1.891048378,9.818120138,-2.063125,11.27223633,1.755278493,79.05100332 +74.66,50.42512477,-2.585339488,51.1424,1.891048406,9.818564272,-2.0165625,11.32178199,1.84152371,79.04347827 +74.67,50.42512494,-2.585338106,51.1624,1.891048412,9.818120129,-1.9675,11.37000751,1.926163156,79.03595315 +74.68,50.42512511,-2.585336725,51.1818,1.894524586,9.817231847,-1.915,11.41690273,2.009122918,79.0284281 +74.69,50.42512528,-2.585335343,51.2007,1.908429336,9.816343564,-1.861875,11.4624578,2.09033069,79.02090299 +74.7,50.42512545,-2.585333962,51.219,1.925810299,9.815899419,-1.81,11.50666333,2.169715654,79.01337793 +74.71,50.42512563,-2.585332581,51.2369,1.925810324,9.816343549,-1.7584375,11.54950997,2.247208597,79.00585282 +74.72,50.4251258,-2.585331199,51.2542,1.90842939,9.817009747,-1.7059375,11.59098891,2.322741967,78.99832776 +74.73,50.42512597,-2.585329818,51.271,1.894524624,9.817009737,-1.651875,11.63109137,2.396249874,78.99080265 +74.74,50.42512614,-2.585328436,51.2873,1.894524609,9.816121451,-1.59625,11.66980899,2.467668204,78.98327759 +74.75,50.42512631,-2.585327055,51.3029,1.908429365,9.815011094,-1.54,11.7071337,2.536934676,78.97575254 +74.76,50.42512648,-2.585325674,51.3181,1.925810327,9.814789012,-1.4834375,11.74305775,2.603988901,78.96822742 +74.77,50.42512666,-2.585324293,51.3326,1.925810344,9.815011068,-1.4265625,11.77757353,2.668772436,78.96070237 +74.78,50.42512683,-2.585322911,51.3466,1.911905597,9.814788985,-1.37,11.81067399,2.731228732,78.95317725 +74.79,50.425127,-2.585321531,51.36,1.911905601,9.81478897,-1.3128125,11.84235208,2.791303357,78.9456522 +74.8,50.42512717,-2.585320149,51.3729,1.925810357,9.815011023,-1.2534375,11.87260122,2.848943942,78.93812709 +74.81,50.42512735,-2.585318768,51.3851,1.92581035,9.814566868,-1.193125,11.90141515,2.904100183,78.93060203 +74.82,50.42512752,-2.585317387,51.3967,1.911905592,9.813900642,-1.1334375,11.92878775,2.956724007,78.92307692 +74.83,50.42512769,-2.585316006,51.4078,1.911905605,9.813456486,-1.073125,11.9547134,3.006769579,78.91555186 +74.84,50.42512786,-2.585314625,51.4182,1.925810369,9.81256819,-1.0115625,11.97918666,3.054193124,78.90802675 +74.85,50.42512804,-2.585313244,51.428,1.929286555,9.811457824,-0.9503125,12.00220238,3.098953446,78.90050169 +74.86,50.42512821,-2.585311864,51.4372,1.925810377,9.811457802,-0.89,12.02375579,3.141011356,78.89297658 +74.87,50.42512838,-2.585310483,51.4458,1.929286589,9.812568125,-0.8296875,12.04384237,3.180330298,78.88545152 +74.88,50.42512856,-2.585309102,51.4538,1.929286594,9.813456378,-0.768125,12.06245794,3.216875953,78.87792641 +74.89,50.42512873,-2.585307721,51.4612,1.925810393,9.813456353,-0.7046875,12.07959861,3.250616463,78.87040135 +74.9,50.4251289,-2.58530634,51.4679,1.929286579,9.812568051,-0.64,12.09526075,3.281522322,78.86287624 +74.91,50.42512908,-2.585304959,51.474,1.929286578,9.811235609,-0.5753125,12.10944117,3.309566716,78.85535119 +74.92,50.42512925,-2.585303579,51.4794,1.92581039,9.810347306,-0.5115625,12.12213688,3.334725063,78.84782607 +74.93,50.42512942,-2.585302198,51.4842,1.932762785,9.810347278,-0.4484375,12.13334526,3.356975478,78.84030102 +74.94,50.4251296,-2.585300818,51.4884,1.943191375,9.811013455,-0.385,12.14306388,3.376298594,78.8327759 +74.95,50.42512977,-2.585299437,51.4919,1.946667568,9.811235494,-0.3215625,12.15129081,3.39267751,78.82525085 +74.96,50.42512995,-2.585298056,51.4948,1.946667558,9.810125117,-0.2584375,12.15802421,3.406097957,78.81772573 +74.97,50.42513012,-2.585296676,51.4971,1.94666755,9.809014739,-0.1946875,12.16326282,3.416548249,78.81020068 +74.98,50.4251303,-2.585295296,51.4987,1.946667548,9.809014705,-0.13,12.16700544,3.424019275,78.80267557 +74.99,50.42513047,-2.585293915,51.4997,1.946667549,9.80901467,-0.065,12.16925132,3.428504503,78.79515051 +75,50.42513065,-2.585292535,51.5,1.946667551,9.808792565,-1.44E-12,12.17,3.42999998,78.7876254 +75.01,50.42513082,-2.585291155,51.4997,1.94666756,9.809014597,0.065,12.16925132,3.428504503,78.78010034 +75.02,50.425131,-2.585289774,51.4987,1.946667571,9.808792491,0.13,12.16700544,3.424019275,78.77257523 +75.03,50.42513117,-2.585288394,51.4971,1.94666757,9.807904177,0.1946875,12.16326282,3.416548249,78.76505017 +75.04,50.42513135,-2.585287014,51.4948,1.946667559,9.807904137,0.2584375,12.15802421,3.406097957,78.75752506 +75.05,50.42513152,-2.585285634,51.4919,1.946667549,9.808792372,0.3215625,12.15129081,3.39267751,78.75 +75.06,50.4251317,-2.585284253,51.4884,1.946667546,9.80879233,0.385,12.14306388,3.376298594,78.74247489 +75.07,50.42513187,-2.585282873,51.4842,1.946667547,9.807681943,0.4484375,12.13334526,3.356975478,78.73494983 +75.08,50.42513205,-2.585281493,51.4794,1.950143746,9.806793623,0.5115625,12.12213688,3.334725063,78.72742472 +75.09,50.42513222,-2.585280113,51.474,1.960572333,9.806571509,0.5753125,12.10944117,3.309566716,78.71989967 +75.1,50.4251324,-2.585278733,51.4679,1.967524714,9.806571463,0.64,12.09526075,3.281522322,78.71237461 +75.11,50.42513258,-2.585277353,51.4612,1.960572307,9.806349347,0.7046875,12.07959861,3.250616463,78.7048495 +75.12,50.42513275,-2.585275973,51.4538,1.950143708,9.805461023,0.768125,12.06245794,3.216875953,78.69732444 +75.13,50.42513293,-2.585274593,51.4458,1.950143703,9.804350629,0.8296875,12.04384237,3.180330298,78.68979933 +75.14,50.4251331,-2.585273214,51.4372,1.960572289,9.80435058,0.89,12.02375579,3.141011356,78.68227427 +75.15,50.42513328,-2.585271834,51.428,1.96752468,9.805460874,0.9503125,12.00220238,3.098953446,78.67474916 +75.16,50.42513346,-2.585270454,51.4182,1.964048489,9.806127029,1.0115625,11.97918666,3.054193124,78.6672241 +75.17,50.42513363,-2.585269074,51.4078,1.964048495,9.80546077,1.073125,11.9547134,3.006769579,78.65969899 +75.18,50.42513381,-2.585267694,51.3967,1.967524695,9.804350372,1.1334375,11.92878775,2.956724007,78.65217393 +75.19,50.42513399,-2.585266315,51.3851,1.964048499,9.804128249,1.193125,11.90141515,2.904100183,78.64464882 +75.2,50.42513416,-2.585264935,51.3729,1.967524676,9.804350262,1.2534375,11.87260122,2.848943942,78.63712377 +75.21,50.42513434,-2.585263555,51.36,1.981429433,9.803906067,1.3128125,11.84235208,2.791303357,78.62959865 +75.22,50.42513452,-2.585262176,51.3466,1.981429427,9.803239803,1.37,11.81067399,2.731228732,78.6220736 +75.23,50.4251347,-2.585260796,51.3326,1.967524653,9.803017676,1.4265625,11.77757353,2.668772436,78.61454848 +75.24,50.42513487,-2.585259417,51.3181,1.967524651,9.803017617,1.4834375,11.74305775,2.603988901,78.60702343 +75.25,50.42513505,-2.585258037,51.3029,1.984905614,9.803017557,1.54,11.7071337,2.536934676,78.59949831 +75.26,50.42513523,-2.585256658,51.2873,1.995334191,9.803017496,1.59625,11.66980899,2.467668204,78.59197326 +75.27,50.42513541,-2.585255278,51.271,1.984905605,9.803017434,1.651875,11.63109137,2.396249874,78.58444815 +75.28,50.42513559,-2.585253899,51.2542,1.967524629,9.802795303,1.7059375,11.59098891,2.322741967,78.57692309 +75.29,50.42513576,-2.585252519,51.2369,1.967524615,9.801906963,1.7584375,11.54950997,2.247208597,78.56939798 +75.3,50.42513594,-2.58525114,51.219,1.984905567,9.800574485,1.81,11.50666333,2.169715654,78.56187292 +75.31,50.42513612,-2.585249761,51.2007,1.998810334,9.799908212,1.861875,11.4624578,2.09033069,78.55434781 +75.32,50.4251363,-2.585248382,51.1818,1.998810335,9.800574353,1.915,11.41690273,2.009122918,78.54682275 +75.33,50.42513648,-2.585247003,51.1624,1.984905565,9.801462563,1.9675,11.37000751,1.926163156,78.53929764 +75.34,50.42513666,-2.585245623,51.1424,1.967524606,9.80057422,2.0165625,11.32178199,1.84152371,78.53177258 +75.35,50.42513683,-2.585244244,51.122,1.967524611,9.798575531,2.063125,11.27223633,1.755278493,78.52424747 +75.36,50.42513701,-2.585242866,51.1012,1.984905566,9.798575462,2.1103125,11.22138071,1.66750262,78.51672241 +75.37,50.42513719,-2.585241487,51.0798,1.998810317,9.800574013,2.158125,11.16922585,1.578272636,78.5091973 +75.38,50.42513737,-2.585240107,51.058,2.002286491,9.80124015,2.2046875,11.11578264,1.487666409,78.50167225 +75.39,50.42513755,-2.585238728,51.0357,2.002286473,9.799463527,2.2496875,11.06106225,1.395762947,78.49414713 +75.4,50.42513773,-2.585237349,51.013,2.002286455,9.797464833,2.293125,11.00507602,1.302642294,78.48662208 +75.41,50.42513791,-2.585235971,50.9898,2.002286448,9.797242691,2.335,10.94783576,1.208385752,78.47909696 +75.42,50.42513809,-2.585234592,50.9663,2.002286452,9.798352963,2.3765625,10.88935339,1.113075483,78.47157191 +75.43,50.42513827,-2.585233213,50.9423,2.002286455,9.799019096,2.4184375,10.82964104,1.016794566,78.46404679 +75.44,50.42513845,-2.585231834,50.9179,2.002286459,9.798352814,2.4596875,10.76871128,0.919626998,78.45652174 +75.45,50.42513863,-2.585230455,50.8931,2.002286462,9.797242394,2.4996875,10.70657681,0.821657517,78.44899668 +75.46,50.42513881,-2.585229077,50.8679,2.002286454,9.797020249,2.5378125,10.6432506,0.722971553,78.44147157 +75.47,50.42513899,-2.585227698,50.8423,2.002286435,9.797242243,2.573125,10.5787458,0.623655106,78.43394651 +75.48,50.42513917,-2.585226319,50.8164,2.002286418,9.796798028,2.606875,10.51307602,0.523794865,78.4264214 +75.49,50.42513935,-2.585224941,50.7902,2.002286406,9.796131744,2.6415625,10.44625487,0.423477805,78.41889634 +75.5,50.42513953,-2.585223562,50.7636,2.002286388,9.795909596,2.6765625,10.37829635,0.32279153,78.41137123 +75.51,50.42513971,-2.585222184,50.7366,2.002286369,9.795687448,2.709375,10.30921465,0.221823762,78.40384618 +75.52,50.42513989,-2.585220805,50.7094,2.002286363,9.795021162,2.74,10.23902417,0.120662505,78.39632106 +75.53,50.42514007,-2.585219427,50.6818,2.005762566,9.794576945,2.7696875,10.16773963,0.019396111,78.38879601 +75.54,50.42514025,-2.585218049,50.654,2.019667345,9.794798934,2.798125,10.09537586,-0.081887243,78.38127089 +75.55,50.42514043,-2.58521667,50.6258,2.037048298,9.794798853,2.825,10.02194794,-0.183099206,78.37374584 +75.56,50.42514062,-2.585215292,50.5975,2.037048278,9.794576703,2.85125,9.947471275,-0.284151486,78.36622073 +75.57,50.4251408,-2.585213914,50.5688,2.019667301,9.79479869,2.876875,9.871961397,-0.384955961,78.35869567 +75.58,50.42514098,-2.585212535,50.5399,2.005762519,9.794576541,2.9009375,9.795434117,-0.485424741,78.35117056 +75.59,50.42514116,-2.585211157,50.5108,2.005762501,9.793466114,2.9234375,9.717905307,-0.585470277,78.3436455 +75.6,50.42514134,-2.585209779,50.4814,2.019667249,9.792577755,2.9446875,9.639391239,-0.68500525,78.33612039 +75.61,50.42514152,-2.585208401,50.4519,2.037048199,9.792355603,2.9646875,9.559908299,-0.783942857,78.32859533 +75.62,50.42514171,-2.585207023,50.4221,2.037048203,9.79235552,2.9834375,9.479473103,-0.882196868,78.32107022 +75.63,50.42514189,-2.585205645,50.3922,2.019667252,9.792355436,3.00125,9.398102382,-0.979681626,78.31354516 +75.64,50.42514207,-2.585204267,50.3621,2.00923868,9.792355352,3.018125,9.315813209,-1.076312047,78.30602005 +75.65,50.42514225,-2.585202889,50.3318,2.019667246,9.792355269,3.033125,9.232622717,-1.172003906,78.29849499 +75.66,50.42514243,-2.585201511,50.3014,2.037048182,9.792355185,3.04625,9.148548322,-1.266673779,78.29096988 +75.67,50.42514262,-2.585200133,50.2709,2.040524346,9.7923551,3.0584375,9.063607501,-1.360239105,78.28344483 +75.68,50.4251428,-2.585198755,50.2402,2.037048132,9.792355015,3.0696875,8.977818072,-1.452618294,78.27591971 +75.69,50.42514298,-2.585197377,50.2095,2.040524314,9.792132861,3.0796875,8.891197969,-1.54373073,78.26839466 +75.7,50.42514317,-2.585195999,50.1786,2.037048123,9.7912445,3.088125,8.803765182,-1.633497059,78.26086954 +75.71,50.42514335,-2.585194621,50.1477,2.023143355,9.79013407,3.094375,8.715538047,-1.7218389,78.25334449 +75.72,50.42514353,-2.585193244,50.1167,2.023143348,9.789911917,3.0984375,8.626535012,-1.808679306,78.24581937 +75.73,50.42514371,-2.585191866,50.0857,2.037048107,9.790133901,3.1015625,8.536774584,-1.89394253,78.23829432 +75.74,50.4251439,-2.585190488,50.0547,2.040524295,9.789911746,3.105,8.4462755,-1.977554147,78.23076921 +75.75,50.42514408,-2.585189111,50.0236,2.037048096,9.78991166,3.108125,8.35505678,-2.05944139,78.22324415 +75.76,50.42514426,-2.585187733,49.9925,2.044000458,9.789911575,3.1096875,8.263137333,-2.139532696,78.21571904 +75.77,50.42514445,-2.585186355,49.9614,2.054429012,9.788801145,3.1096875,8.170536467,-2.217758337,78.20819398 +75.78,50.42514463,-2.585184978,49.9303,2.054429004,9.787690714,3.1078125,8.077273491,-2.294050074,78.20066892 +75.79,50.42514482,-2.585183601,49.8992,2.044000427,9.787912697,3.103125,7.983367828,-2.368341329,78.19314381 +75.8,50.425145,-2.585182223,49.8682,2.037048036,9.788578819,3.0965625,7.888839131,-2.440567357,78.18561876 +75.81,50.42514518,-2.585180846,49.8373,2.044000407,9.788578733,3.09,7.793707167,-2.510665191,78.17809364 +75.82,50.42514537,-2.585179468,49.8064,2.054428963,9.787912442,3.083125,7.69799176,-2.578573696,78.17056859 +75.83,50.42514555,-2.585178091,49.7756,2.057905133,9.787468219,3.0746875,7.601712906,-2.644233628,78.16304347 +75.84,50.42514574,-2.585176714,49.7449,2.057905123,9.787690203,3.0646875,7.504890716,-2.707587749,78.15551842 +75.85,50.42514592,-2.585175336,49.7143,2.057905125,9.787468049,3.053125,7.407545416,-2.768580825,78.14799331 +75.86,50.42514611,-2.585173959,49.6838,2.057905126,9.786357619,3.0396875,7.309697288,-2.827159686,78.14046825 +75.87,50.42514629,-2.585172582,49.6535,2.057905125,9.785469258,3.025,7.211366844,-2.883273167,78.13294314 +75.88,50.42514648,-2.585171205,49.6233,2.057905117,9.785247105,3.0096875,7.112574596,-2.936872395,78.12541808 +75.89,50.42514666,-2.585169828,49.5933,2.057905097,9.785247021,2.993125,7.013341171,-2.987910673,78.11789297 +75.9,50.42514685,-2.585168451,49.5634,2.057905076,9.785246937,2.9746875,6.913687252,-3.036343426,78.11036791 +75.91,50.42514703,-2.585167074,49.5338,2.057905069,9.785246853,2.9546875,6.813633695,-3.082128426,78.1028428 +75.92,50.42514722,-2.585165697,49.5043,2.057905066,9.78524677,2.9334375,6.713201413,-3.125225738,78.09531774 +75.93,50.4251474,-2.58516432,49.4751,2.057905057,9.785024618,2.9115625,6.612411318,-3.165597834,78.08779263 +75.94,50.42514759,-2.585162943,49.4461,2.06138123,9.78413626,2.8896875,6.511284497,-3.203209534,78.08026757 +75.95,50.42514777,-2.585161566,49.4173,2.071809783,9.783025834,2.86625,6.40984209,-3.23802795,78.07274246 +75.96,50.42514796,-2.58516019,49.3887,2.078762157,9.783025752,2.8396875,6.30810524,-3.270022715,78.0652174 +75.97,50.42514815,-2.585158813,49.3605,2.071809776,9.784136014,2.8115625,6.206095204,-3.299166042,78.05769229 +75.98,50.42514833,-2.585157436,49.3325,2.061381202,9.784802139,2.7834375,6.103833296,-3.325432375,78.05016724 +75.99,50.42514852,-2.585156059,49.3048,2.061381193,9.784135852,2.7546875,6.001340829,-3.348798912,78.04264212 +76,50.4251487,-2.585154682,49.2774,2.071809752,9.783025427,2.7246875,5.89863929,-3.369245255,78.03511707 +76.01,50.42514889,-2.585153306,49.2503,2.078762123,9.782803279,2.693125,5.79575005,-3.386753584,78.02759195 +76.02,50.42514908,-2.585151929,49.2235,2.075285934,9.7828032,2.66,5.692694653,-3.401308603,78.0200669 +76.03,50.42514926,-2.585150552,49.1971,2.075285937,9.781692775,2.6265625,5.589494583,-3.412897591,78.01254179 +76.04,50.42514945,-2.585149176,49.171,2.078762117,9.780582352,2.5928125,5.486171442,-3.421510522,78.00501673 +76.05,50.42514964,-2.5851478,49.1452,2.075285909,9.780582274,2.5565625,5.382746716,-3.427139832,77.99749162 +76.06,50.42514982,-2.585146423,49.1198,2.078762081,9.780582197,2.518125,5.279242062,-3.429780652,77.98996656 +76.07,50.42515001,-2.585145047,49.0949,2.092666826,9.780360051,2.48,5.175679139,-3.429430632,77.98244145 +76.08,50.4251502,-2.585143671,49.0702,2.092666818,9.780582044,2.44125,5.072079489,-3.426090059,77.97491639 +76.09,50.42515039,-2.585142294,49.046,2.078762057,9.7803599,2.3996875,4.96846477,-3.419761912,77.96739128 +76.1,50.42515057,-2.585140918,49.0222,2.078762056,9.779471549,2.356875,4.864856697,-3.410451692,77.95986622 +76.11,50.42515076,-2.585139542,48.9989,2.092666806,9.779471474,2.3146875,4.761276814,-3.398167534,77.95234111 +76.12,50.42515095,-2.585138166,48.9759,2.092666788,9.780359676,2.2715625,4.657746778,-3.382920096,77.94481605 +76.13,50.42515114,-2.585136789,48.9534,2.078762016,9.780359603,2.22625,4.55428819,-3.36472267,77.937291 +76.14,50.42515132,-2.585135413,48.9314,2.078762022,9.779249187,2.1803125,4.450922765,-3.343591184,77.92976588 +76.15,50.42515151,-2.585134037,48.9098,2.096142986,9.77836084,2.135,4.347671931,-3.319544031,77.92224083 +76.16,50.4251517,-2.585132661,48.8887,2.110047747,9.778138699,2.089375,4.244557347,-3.292602237,77.91471572 +76.17,50.42515189,-2.585131285,48.868,2.11004773,9.778138628,2.0415625,4.141600556,-3.262789181,77.90719066 +76.18,50.42515208,-2.585129909,48.8478,2.096142948,9.778138559,1.99125,4.038822985,-3.23013093,77.89966555 +76.19,50.42515227,-2.585128533,48.8282,2.078761989,9.777916421,1.9403125,3.936246179,-3.194655962,77.89214049 +76.2,50.42515245,-2.585127157,48.809,2.078761989,9.777028078,1.89,3.833891509,-3.156395215,77.88461538 +76.21,50.42515264,-2.585125781,48.7904,2.096142938,9.775917666,1.839375,3.731780403,-3.115382094,77.87709032 +76.22,50.42515283,-2.585124406,48.7722,2.110047687,9.77569553,1.786875,3.629934119,-3.071652236,77.86956521 +76.23,50.42515302,-2.58512303,48.7546,2.113523861,9.775917533,1.7328125,3.528373912,-3.025243858,77.86204015 +76.24,50.42515321,-2.585121654,48.7376,2.113523856,9.775695399,1.67875,3.427121097,-2.976197468,77.85451504 +76.25,50.4251534,-2.585120279,48.721,2.113523859,9.775917403,1.6246875,3.326196758,-2.92455575,77.84698998 +76.26,50.42515359,-2.585118903,48.7051,2.113523854,9.776805615,1.5696875,3.225621924,-2.870363798,77.83946487 +76.27,50.42515378,-2.585117527,48.6896,2.11352384,9.776805553,1.5134375,3.125417679,-2.813668822,77.83193982 +76.28,50.42515397,-2.585116151,48.6748,2.113523835,9.775695146,1.45625,3.025604936,-2.754520326,77.8244147 +76.29,50.42515416,-2.585114776,48.6605,2.113523842,9.77480681,1.39875,2.926204494,-2.692969819,77.81688965 +76.3,50.42515435,-2.5851134,48.6468,2.113523844,9.774584681,1.34125,2.827237093,-2.629070987,77.80936453 +76.31,50.42515454,-2.585112025,48.6337,2.113523833,9.774362553,1.2834375,2.728723531,-2.562879637,77.80183948 +76.32,50.42515473,-2.585110649,48.6211,2.11352382,9.773474219,1.2246875,2.630684265,-2.49445335,77.79431436 +76.33,50.42515492,-2.585109274,48.6092,2.113523825,9.772363817,1.1646875,2.533139747,-2.423851886,77.78678931 +76.34,50.42515511,-2.585107899,48.5978,2.113523843,9.772363761,1.10375,2.43611049,-2.351136781,77.7792642 +76.35,50.4251553,-2.585106524,48.5871,2.113523847,9.773251981,1.043125,2.339616605,-2.276371461,77.77173914 +76.36,50.42515549,-2.585105148,48.577,2.113523826,9.773251926,0.9834375,2.243678318,-2.199621072,77.76421403 +76.37,50.42515568,-2.585103773,48.5674,2.113523803,9.772363597,0.9228125,2.148315681,-2.120952591,77.75668897 +76.38,50.42515587,-2.585102398,48.5585,2.113523797,9.772363544,0.86,2.053548519,-2.040434661,77.74916386 +76.39,50.42515606,-2.585101023,48.5502,2.113523804,9.773251768,0.796875,1.959396771,-1.958137409,77.7416388 +76.4,50.42515625,-2.585099647,48.5426,2.113523801,9.773251717,0.735,1.865879974,-1.874132629,77.73411369 +76.41,50.42515644,-2.585098272,48.5355,2.116999981,9.771919254,0.673125,1.773017668,-1.788493544,77.72658863 +76.42,50.42515663,-2.585096897,48.5291,2.130904742,9.770142654,0.6096875,1.680829332,-1.701294926,77.71906352 +76.43,50.42515682,-2.585095522,48.5233,2.148285705,9.769032261,0.5453125,1.589334102,-1.61261269,77.71153846 +76.44,50.42515702,-2.585094148,48.5182,2.14828571,9.769698421,0.4815625,1.498551174,-1.522524301,77.70401335 +76.45,50.42515721,-2.585092773,48.5137,2.130904748,9.771030787,0.4184375,1.408499512,-1.431108198,77.6964883 +76.46,50.4251574,-2.585091397,48.5098,2.116999973,9.770808673,0.355,1.319197852,-1.338444192,77.68896318 +76.47,50.42515759,-2.585090023,48.5066,2.116999972,9.769698284,0.2915625,1.230664872,-1.244613014,77.68143813 +76.48,50.42515778,-2.585088648,48.504,2.130904743,9.769032034,0.228125,1.142919078,-1.149696481,77.67391307 +76.49,50.42515797,-2.585087273,48.502,2.148285696,9.768587854,0.163125,1.055978806,-1.053777445,77.66638796 +76.5,50.42515817,-2.585085899,48.5007,2.148285687,9.768587813,0.096875,0.969862161,-0.956939499,77.6588629 +76.51,50.42515836,-2.585084524,48.5001,2.134380924,9.768809841,0.031875,0.884587191,-0.859267097,77.65133779 +76.52,50.42515855,-2.585083149,48.5001,2.134380933,9.768365664,-0.0315625,0.800171657,-0.760845324,77.64381273 +76.53,50.42515874,-2.585081775,48.5007,2.148285699,9.767699418,-0.0953125,0.716633207,-0.66176018,77.63628762 +76.54,50.42515894,-2.5850804,48.502,2.148285699,9.76769938,-0.16,0.633989259,-0.562097896,77.62876256 +76.55,50.42515913,-2.585079026,48.5039,2.134380948,9.76836555,-0.2246875,0.552257174,-0.461945503,77.62123745 +76.56,50.42515932,-2.585077651,48.5065,2.134380957,9.768587583,-0.2884375,0.471453853,-0.361390264,77.6137124 +76.57,50.42515951,-2.585076276,48.5097,2.148285711,9.767477204,-0.351875,0.391596313,-0.260519899,77.60618728 +76.58,50.42515971,-2.585074902,48.5135,2.151761885,9.766366827,-0.4165625,0.31270117,-0.159422355,77.59866223 +76.59,50.4251599,-2.585073528,48.518,2.148285694,9.766366794,-0.4815625,0.234784869,-0.058185812,77.59113711 +76.6,50.42516009,-2.585072153,48.5232,2.151761895,9.766366762,-0.5446875,0.157863738,0.043101495,77.58361206 +76.61,50.42516029,-2.585070779,48.5289,2.151761897,9.765922593,-0.606875,0.081953878,0.144351216,77.57608694 +76.62,50.42516048,-2.585069405,48.5353,2.1482857,9.765256357,-0.6703125,0.007071044,0.245475058,77.56856189 +76.63,50.42516067,-2.58506803,48.5423,2.155238084,9.764145983,-0.734375,-0.066769064,0.346384844,77.56103678 +76.64,50.42516087,-2.585066657,48.55,2.165666668,9.763923885,-0.796875,-0.139551033,0.446992623,77.55351172 +76.65,50.42516106,-2.585065283,48.5583,2.165666671,9.765256272,-0.858125,-0.211259738,0.547210562,77.54598661 +76.66,50.42516126,-2.585063908,48.5671,2.155238092,9.765922452,-0.92,-0.281880052,0.646951341,77.53846155 +76.67,50.42516145,-2.585062534,48.5767,2.148285714,9.765034151,-0.9815625,-0.351397365,0.746127929,77.53093644 +76.68,50.42516164,-2.58506116,48.5868,2.155238108,9.764145851,-1.0415625,-0.419797124,0.844653923,77.52341138 +76.69,50.42516184,-2.585059786,48.5975,2.165666684,9.763923759,-1.101875,-0.487064947,0.94244338,77.51588627 +76.7,50.42516203,-2.585058412,48.6088,2.16914287,9.763701667,-1.163125,-0.55318697,1.039410987,77.50836121 +76.71,50.42516223,-2.585057038,48.6208,2.169142874,9.76281337,-1.223125,-0.618149211,1.135472231,77.5008361 +76.72,50.42516242,-2.585055664,48.6333,2.169142888,9.761703005,-1.2815625,-0.681938207,1.23054329,77.49331104 +76.73,50.42516262,-2.585054291,48.6464,2.169142892,9.761480916,-1.34,-0.744540549,1.324541314,77.48578593 +76.74,50.42516281,-2.585052917,48.6601,2.169142888,9.761702965,-1.398125,-0.80594329,1.417384311,77.47826088 +76.75,50.42516301,-2.585051543,48.6744,2.169142891,9.761480878,-1.4546875,-0.866133481,1.508991325,77.47073576 +76.76,50.4251632,-2.58505017,48.6892,2.169142898,9.761480861,-1.5103125,-0.92509863,1.59928254,77.46321071 +76.77,50.4251634,-2.585048796,48.7046,2.169142901,9.761702913,-1.5665625,-0.982826362,1.688179062,77.45568559 +76.78,50.42516359,-2.585047422,48.7205,2.169142909,9.76125876,-1.623125,-1.039304703,1.775603541,77.44816054 +76.79,50.42516379,-2.585046049,48.7371,2.169142923,9.760592539,-1.678125,-1.094521792,1.861479659,77.44063542 +76.8,50.42516398,-2.585044675,48.7541,2.169142929,9.760370456,-1.73125,-1.148466112,1.945732472,77.43311037 +76.81,50.42516418,-2.585043302,48.7717,2.172619118,9.760370442,-1.78375,-1.201126434,2.028288643,77.42558526 +76.82,50.42516437,-2.585041928,48.7898,2.183047695,9.760370429,-1.83625,-1.252491699,2.109076093,77.4180602 +76.83,50.42516457,-2.585040555,48.8084,2.190000085,9.760148349,-1.8884375,-1.302551251,2.188024406,77.41053514 +76.84,50.42516477,-2.585039181,48.8276,2.186523901,9.759260062,-1.9396875,-1.351294546,2.265064712,77.40301003 +76.85,50.42516496,-2.585037808,48.8472,2.186523919,9.757927638,-1.9896875,-1.398711445,2.340129861,77.39548498 +76.86,50.42516516,-2.585036435,48.8674,2.190000137,9.757261422,-2.0384375,-1.444792091,2.413154421,77.38795986 +76.87,50.42516536,-2.585035062,48.888,2.183047762,9.75792762,-2.0865625,-1.48952686,2.484074621,77.38043481 +76.88,50.42516555,-2.585033689,48.9091,2.172619176,9.759037957,-2.1346875,-1.532906297,2.552828697,77.37290969 +76.89,50.42516575,-2.585032315,48.9307,2.172619172,9.759037949,-2.1815625,-1.574921464,2.61935666,77.36538464 +76.9,50.42516594,-2.585030942,48.9528,2.186523944,9.757927598,-2.22625,-1.615563537,2.683600469,77.35785952 +76.91,50.42516614,-2.585029569,48.9752,2.203904905,9.757039316,-2.27,-1.654824038,2.745504205,77.35033447 +76.92,50.42516634,-2.585028196,48.9982,2.203904915,9.756817242,-2.3134375,-1.692694772,2.805013779,77.34280936 +76.93,50.42516654,-2.585026823,49.0215,2.190000168,9.756817237,-2.35625,-1.729167775,2.862077338,77.3352843 +76.94,50.42516673,-2.58502545,49.0453,2.186523985,9.756595164,-2.3984375,-1.764235543,2.916645151,77.32775919 +76.95,50.42516693,-2.585024077,49.0695,2.190000176,9.755706885,-2.439375,-1.797890625,2.968669547,77.32023413 +76.96,50.42516713,-2.585022704,49.0941,2.186523991,9.754596538,-2.4784375,-1.83012609,3.018105262,77.31270902 +76.97,50.42516732,-2.585021332,49.1191,2.190000193,9.754596536,-2.5165625,-1.860935177,3.064909153,77.30518396 +76.98,50.42516752,-2.585019959,49.1444,2.207381155,9.755706878,-2.5546875,-1.890311468,3.109040368,77.29765885 +76.99,50.42516772,-2.585018586,49.1702,2.217809738,9.756373083,-2.5915625,-1.918248775,3.150460518,77.29013379 +77,50.42516792,-2.585017213,49.1963,2.207381175,9.755706875,-2.6259375,-1.944741255,3.189133336,77.28260868 +77.01,50.42516812,-2.58501584,49.2227,2.190000226,9.754596531,-2.6584375,-1.969783464,3.225025246,77.27508362 +77.02,50.42516831,-2.585014468,49.2495,2.190000236,9.754374463,-2.69,-1.993370131,3.25810485,77.26755851 +77.03,50.42516851,-2.585013095,49.2765,2.207381204,9.754596532,-2.7215625,-2.015496272,3.288343327,77.26003346 +77.04,50.42516871,-2.585011722,49.3039,2.221285976,9.754152394,-2.7534375,-2.036157359,3.315714381,77.25250834 +77.05,50.42516891,-2.58501035,49.3316,2.224762179,9.75326412,-2.784375,-2.055349039,3.340194003,77.24498329 +77.06,50.42516911,-2.585008977,49.3596,2.221286007,9.752153778,-2.813125,-2.073067243,3.361760993,77.23745817 +77.07,50.42516931,-2.585007605,49.3879,2.207381251,9.750821368,-2.8396875,-2.089308362,3.380396446,77.22993312 +77.08,50.42516951,-2.585006233,49.4164,2.190000296,9.750155164,-2.8646875,-2.104069015,3.396084145,77.222408 +77.09,50.4251697,-2.585004861,49.4452,2.190000304,9.751043443,-2.8884375,-2.117345994,3.408810397,77.21488295 +77.1,50.4251699,-2.585003489,49.4742,2.207381273,9.752819997,-2.91125,-2.129136663,3.418564144,77.20735784 +77.11,50.4251701,-2.585002116,49.5034,2.221286046,9.753042069,-2.9334375,-2.139438502,3.425336849,77.19983278 +77.12,50.4251703,-2.585000743,49.5329,2.224762248,9.751043453,-2.9546875,-2.148249332,3.429122553,77.19230767 +77.13,50.4251705,-2.584999372,49.5625,2.22476226,9.749933114,-2.9746875,-2.155567378,3.429918105,77.18478261 +77.14,50.4251707,-2.584998,49.5924,2.224762269,9.751043462,-2.993125,-2.161391036,3.427722645,77.1772575 +77.15,50.4251709,-2.584996627,49.6224,2.224762279,9.751709674,-3.0096875,-2.165719159,3.422538179,77.16973244 +77.16,50.4251711,-2.584995255,49.6526,2.224762292,9.750599334,-3.025,-2.168550774,3.414369233,77.16220739 +77.17,50.4251713,-2.584993883,49.6829,2.2247623,9.749044858,-3.0396875,-2.169885364,3.403222855,77.15468227 +77.18,50.4251715,-2.584992511,49.7134,2.224762311,9.748378656,-3.053125,-2.169722587,3.389108842,77.14715722 +77.19,50.4251717,-2.58499114,49.744,2.224762324,9.748822799,-3.064375,-2.168062556,3.372039512,77.1396321 +77.2,50.4251719,-2.584989767,49.7747,2.224762333,9.749489012,-3.0734375,-2.164905502,3.352029649,77.13210705 +77.21,50.4251721,-2.584988396,49.8055,2.224762344,9.749489019,-3.0815625,-2.160252225,3.329096841,77.12458194 +77.22,50.4251723,-2.584987023,49.8363,2.224762357,9.748822818,-3.0896875,-2.154103528,3.303260914,77.11705688 +77.23,50.4251725,-2.584985652,49.8673,2.224762365,9.748156617,-3.0965625,-2.146460844,3.274544556,77.10953177 +77.24,50.4251727,-2.58498428,49.8983,2.224762376,9.747712485,-3.10125,-2.13732572,3.242972748,77.10200671 +77.25,50.4251729,-2.584982908,49.9293,2.224762389,9.747268354,-3.105,-2.126700046,3.208573049,77.0944816 +77.26,50.4251731,-2.584981537,49.9604,2.22823859,9.747268361,-3.108125,-2.114586056,3.171375369,77.08695654 +77.27,50.4251733,-2.584980165,49.9915,2.242143367,9.747268367,-3.1096875,-2.100986273,3.131412193,77.07943143 +77.28,50.4251735,-2.584978793,50.0226,2.259524339,9.746158028,-3.1096875,-2.08590356,3.088718414,77.07190637 +77.29,50.42517371,-2.584977422,50.0537,2.259524347,9.74504769,-3.108125,-2.069341012,3.043331219,77.06438126 +77.3,50.42517391,-2.584976051,50.0848,2.2421434,9.745269764,-3.1046875,-2.051302123,2.995290198,77.0568562 +77.31,50.42517411,-2.584974679,50.1158,2.228238646,9.745935977,-3.1,-2.031790676,2.944637233,77.04933109 +77.32,50.42517431,-2.584973308,50.1468,2.224762463,9.745935983,-3.0946875,-2.010810737,2.891416559,77.04180604 +77.33,50.42517451,-2.584971936,50.1777,2.228238666,9.745269783,-3.088125,-1.988366663,2.835674469,77.03428092 +77.34,50.42517471,-2.584970565,50.2086,2.242143446,9.744825651,-3.0796875,-1.96446315,2.777459608,77.02675587 +77.35,50.42517491,-2.584969194,50.2393,2.259524414,9.745047725,-3.0696875,-1.939105184,2.716822797,77.01923075 +77.36,50.42517512,-2.584967822,50.27,2.259524425,9.744825661,-3.0584375,-1.91229815,2.653816863,77.0117057 +77.37,50.42517532,-2.584966451,50.3005,2.24561967,9.743715322,-3.04625,-1.884047492,2.588496752,77.00418058 +77.38,50.42517552,-2.58496508,50.3309,2.245619677,9.742827051,-3.033125,-1.854359226,2.520919474,76.99665553 +77.39,50.42517572,-2.584963709,50.3612,2.259524448,9.742604986,-3.018125,-1.823239539,2.451143872,76.98913042 +77.4,50.42517593,-2.584962338,50.3913,2.259524459,9.742604991,-3.00125,-1.790694848,2.37923085,76.98160536 +77.41,50.42517613,-2.584960967,50.4212,2.245619709,9.742604995,-2.9834375,-1.75673203,2.305243091,76.97408025 +77.42,50.42517633,-2.584959596,50.451,2.245619724,9.742605,-2.9646875,-1.721358189,2.229245167,76.96655519 +77.43,50.42517653,-2.584958225,50.4805,2.2595245,9.742382934,-2.9446875,-1.684580601,2.151303255,76.95903008 +77.44,50.42517674,-2.584956854,50.5099,2.263000702,9.741494661,-2.9234375,-1.646407116,2.071485421,76.95150502 +77.45,50.42517694,-2.584955483,50.539,2.259524523,9.740384319,-2.90125,-1.606845526,1.989861166,76.94397991 +77.46,50.42517714,-2.584954113,50.5679,2.263000723,9.740384322,-2.878125,-1.565904254,1.906501765,76.93645485 +77.47,50.42517735,-2.584952742,50.5966,2.263000733,9.7412726,-2.853125,-1.523591722,1.821479871,76.92892974 +77.48,50.42517755,-2.584951371,50.625,2.259524554,9.741272602,-2.82625,-1.479916868,1.734869622,76.92140468 +77.49,50.42517775,-2.58495,50.6531,2.263000751,9.740384327,-2.7984375,-1.434888745,1.646746479,76.91387957 +77.5,50.42517796,-2.58494863,50.681,2.263000755,9.740162258,-2.77,-1.388516807,1.557187389,76.90635452 +77.51,50.42517816,-2.584947259,50.7085,2.259524572,9.740384328,-2.74125,-1.340810679,1.466270446,76.89882946 +77.52,50.42517836,-2.584945888,50.7358,2.266476973,9.73994019,-2.71125,-1.291780332,1.374074833,76.89130435 +77.53,50.42517857,-2.584944518,50.7628,2.276905563,9.739273982,-2.678125,-1.24143602,1.280681051,76.88377929 +77.54,50.42517877,-2.584943147,50.7894,2.28038176,9.739051912,-2.643125,-1.189788344,1.186170459,76.87625418 +77.55,50.42517898,-2.584941777,50.8156,2.280381763,9.738829842,-2.6084375,-1.13684796,1.090625564,76.86872912 +77.56,50.42517918,-2.584940406,50.8416,2.27690558,9.738163633,-2.573125,-1.082625927,0.994129559,76.86120401 +77.57,50.42517939,-2.584939036,50.8671,2.26647702,9.737497423,-2.53625,-1.027133704,0.896766727,76.85367895 +77.58,50.42517959,-2.584937666,50.8923,2.259524649,9.737053282,-2.4984375,-0.97038275,0.798621864,76.84615384 +77.59,50.42517979,-2.584936295,50.9171,2.26647704,9.73660914,-2.4596875,-0.912384926,0.699780571,76.83862878 +77.6,50.42518,-2.584934926,50.9415,2.276905625,9.736609135,-2.42,-0.853152434,0.600329078,76.83110367 +77.61,50.4251802,-2.584933555,50.9655,2.280381828,9.736831198,-2.3796875,-0.792697537,0.50035413,76.82357862 +77.62,50.42518041,-2.584932185,50.9891,2.280381832,9.736387055,-2.338125,-0.731032955,0.399942818,76.8160535 +77.63,50.42518061,-2.584930815,51.0123,2.280381834,9.735720841,-2.295,-0.66817152,0.299182747,76.80852845 +77.64,50.42518082,-2.584929445,51.035,2.283858035,9.735498765,-2.25125,-0.604126298,0.198161808,76.80100333 +77.65,50.42518102,-2.584928075,51.0573,2.294286624,9.735498757,-2.2065625,-0.538910752,0.096968065,76.79347828 +77.66,50.42518123,-2.584926705,51.0792,2.301239012,9.735498748,-2.1596875,-0.472538519,-0.004310247,76.78595316 +77.67,50.42518144,-2.584925335,51.1005,2.29428662,9.735276669,-2.111875,-0.405023407,-0.105584834,76.77842811 +77.68,50.42518164,-2.584923965,51.1214,2.283858044,9.734388383,-2.065,-0.336379511,-0.20676729,76.770903 +77.69,50.42518185,-2.584922595,51.1418,2.283858062,9.733278028,-2.0178125,-0.266621154,-0.307769494,76.76337794 +77.7,50.42518205,-2.584921226,51.1618,2.294286662,9.733278017,-1.968125,-0.195762948,-0.408503266,76.75585283 +77.71,50.42518226,-2.584919856,51.1812,2.30123906,9.734388348,-1.9165625,-0.123819675,-0.508880831,76.74832777 +77.72,50.42518247,-2.584918486,51.2001,2.294286678,9.735054541,-1.865,-0.050806345,-0.60881464,76.74080266 +77.73,50.42518267,-2.584917116,51.2185,2.283858101,9.73438832,-1.813125,0.023261743,-0.708217603,76.7332776 +77.74,50.42518288,-2.584915746,51.2364,2.283858108,9.733055892,-1.76,0.098369176,-0.807002918,76.72575249 +77.75,50.42518308,-2.584914377,51.2537,2.294286698,9.732167601,-1.7065625,0.174500255,-0.905084584,76.71822743 +77.76,50.42518329,-2.584913007,51.2705,2.301239093,9.731945516,-1.653125,0.25163911,-1.002376943,76.71070232 +77.77,50.4251835,-2.584911638,51.2868,2.297762902,9.731723429,-1.598125,0.329769583,-1.098795255,76.70317726 +77.78,50.4251837,-2.584910268,51.3025,2.301239093,9.731057203,-1.5415625,0.408875345,-1.194255352,76.69565215 +77.79,50.42518391,-2.584908899,51.3176,2.315143868,9.730613046,-1.485,0.488939894,-1.288674098,76.6881271 +77.8,50.42518412,-2.58490753,51.3322,2.31514388,9.731057164,-1.4284375,0.569946558,-1.381969103,76.68060198 +77.81,50.42518433,-2.58490616,51.3462,2.30123912,9.731723349,-1.37125,0.651878377,-1.474058947,76.67307693 +77.82,50.42518453,-2.584904791,51.3596,2.301239121,9.731723328,-1.3134375,0.734718277,-1.564863419,76.66555181 +77.83,50.42518474,-2.584903421,51.3725,2.315143889,9.730835029,-1.255,0.818448839,-1.654303334,76.65802676 +77.84,50.42518495,-2.584902052,51.3847,2.315143891,9.729502593,-1.19625,0.903052761,-1.742300656,76.65050164 +77.85,50.42518516,-2.584900683,51.3964,2.301239126,9.728614292,-1.1365625,0.988512224,-1.828778665,76.64297659 +77.86,50.42518536,-2.584899314,51.4075,2.301239132,9.728392197,-1.075,1.074809408,-1.913661962,76.63545153 +77.87,50.42518557,-2.584897945,51.4179,2.318620105,9.72839217,-1.0134375,1.16192638,-1.996876461,76.62792642 +77.88,50.42518578,-2.584896576,51.4277,2.32904869,9.728392142,-0.9534375,1.249844863,-2.078349742,76.62040136 +77.89,50.42518599,-2.584895207,51.437,2.318620112,9.728392114,-0.8928125,1.338546522,-2.158010585,76.61287625 +77.9,50.4251862,-2.584893838,51.4456,2.301239146,9.728392085,-0.83,1.428012793,-2.235789663,76.6053512 +77.91,50.4251864,-2.584892469,51.4536,2.301239147,9.728392054,-0.766875,1.518225055,-2.31161908,76.59782608 +77.92,50.42518661,-2.5848911,51.4609,2.318620112,9.728169954,-0.705,1.609164458,-2.385432774,76.59030103 +77.93,50.42518682,-2.584889731,51.4677,2.332524886,9.727281646,-0.643125,1.70081198,-2.457166288,76.58277591 +77.94,50.42518703,-2.584888362,51.4738,2.336001085,9.7259492,-0.5796875,1.793148483,-2.526757112,76.57525086 +77.95,50.42518724,-2.584886994,51.4793,2.332524893,9.72506089,-0.515,1.886154659,-2.594144626,76.56772574 +77.96,50.42518745,-2.584885625,51.4841,2.318620116,9.725060854,-0.4503125,1.9798112,-2.659269931,76.56020069 +77.97,50.42518766,-2.584884257,51.4883,2.301239151,9.725727024,-0.3865625,2.074098452,-2.722076362,76.55267558 +77.98,50.42518786,-2.584882888,51.4918,2.30123915,9.726171125,-0.3234375,2.168996707,-2.782509085,76.54515052 +77.99,50.42518807,-2.584881519,51.4948,2.318620111,9.725726949,-0.26,2.264486197,-2.840515447,76.53762541 +78,50.42518828,-2.584880151,51.497,2.332524889,9.724838635,-0.19625,2.360546983,-2.896044797,76.53010035 +78.01,50.42518849,-2.584878782,51.4987,2.336001095,9.723950319,-0.131875,2.457158954,-2.949048779,76.52257524 +78.02,50.4251887,-2.584877414,51.4997,2.336001102,9.723728208,-0.06625,2.554301943,-2.999481097,76.51505018 +78.03,50.42518891,-2.584876046,51.5,2.336001098,9.72483851,-0.000625,2.651955724,-3.047297863,76.50752507 +78.04,50.42518912,-2.584874677,51.4997,2.336001091,9.725726742,0.0634375,2.750099899,-3.092457365,76.50000001 +78.05,50.42518933,-2.584873308,51.4987,2.336001089,9.724616353,0.126875,2.8487139,-3.134920127,76.4924749 +78.06,50.42518954,-2.58487194,51.4972,2.336001088,9.722617689,0.1915625,2.947777157,-3.17464925,76.48494984 +78.07,50.42518975,-2.584870572,51.4949,2.336001088,9.721507298,0.2565625,3.047268986,-3.211610012,76.47742473 +78.08,50.42518996,-2.584869204,51.492,2.336001087,9.721285182,0.3196875,3.147168647,-3.245770214,76.46989968 +78.09,50.42519017,-2.584867836,51.4885,2.336001088,9.721507202,0.3821875,3.247455226,-3.277100062,76.46237456 +78.1,50.42519038,-2.584866468,51.4844,2.339477285,9.722173359,0.4465625,3.34810781,-3.305572226,76.45484951 +78.11,50.42519059,-2.5848651,51.4796,2.353382058,9.722395378,0.5115625,3.449105373,-3.331161839,76.44732439 +78.12,50.4251908,-2.584863731,51.4741,2.370763014,9.721284982,0.575,3.550426828,-3.35384667,76.43979934 +78.13,50.42519102,-2.584862364,51.4681,2.370763005,9.720174585,0.638125,3.652050977,-3.373606896,76.43227422 +78.14,50.42519123,-2.584860996,51.4614,2.353382038,9.7203966,0.701875,3.753956678,-3.39042527,76.42474917 +78.15,50.42519144,-2.584859628,51.454,2.339477266,9.721062753,0.7646875,3.856122558,-3.404287181,76.41722406 +78.16,50.42519165,-2.58485826,51.4461,2.336001068,9.721062697,0.8265625,3.958527362,-3.415180484,76.409699 +78.17,50.42519186,-2.584856892,51.4375,2.336001056,9.720174365,0.8884375,4.061149604,-3.423095667,76.40217389 +78.18,50.42519207,-2.584855524,51.4283,2.339477234,9.719063964,0.9496875,4.163967969,-3.428025912,76.39464883 +78.19,50.42519228,-2.584854157,51.4185,2.353382001,9.718841837,1.01,4.266960914,-3.429966806,76.38712372 +78.2,50.42519249,-2.584852789,51.4081,2.37076297,9.719063847,1.0703125,4.370106896,-3.428916746,76.37959866 +78.21,50.42519271,-2.584851421,51.3971,2.370762975,9.71861965,1.1315625,4.473384487,-3.424876649,76.37207361 +78.22,50.42519292,-2.584850054,51.3855,2.353382013,9.717953382,1.193125,4.576772028,-3.417850009,76.36454849 +78.23,50.42519313,-2.584848686,51.3732,2.342953438,9.717731251,1.2528125,4.680247977,-3.4078429,76.35702344 +78.24,50.42519334,-2.584847319,51.3604,2.353382015,9.717509119,1.31,4.783790675,-3.394864146,76.34949832 +78.25,50.42519355,-2.584845951,51.347,2.370762968,9.716842849,1.366875,4.887378522,-3.378924975,76.34197327 +78.26,50.42519377,-2.584844584,51.3331,2.370762956,9.716398647,1.425,4.990989918,-3.36003937,76.33444816 +78.27,50.42519398,-2.584843217,51.3185,2.356858179,9.71662065,1.483125,5.094603204,-3.338223773,76.3269231 +78.28,50.42519419,-2.584841849,51.3034,2.356858173,9.716620584,1.5396875,5.198196667,-3.313497149,76.31939799 +78.29,50.4251944,-2.584840482,51.2877,2.370762937,9.716398448,1.595,5.301748819,-3.285881156,76.31187293 +78.3,50.42519462,-2.584839115,51.2715,2.374239124,9.716620448,1.6496875,5.405237888,-3.255399801,76.30434782 +78.31,50.42519483,-2.584837747,51.2547,2.370762925,9.71639831,1.7034375,5.508642389,-3.22207967,76.29682276 +78.32,50.42519504,-2.58483638,51.2374,2.374239111,9.715287896,1.7565625,5.611940606,-3.185949868,76.28929765 +78.33,50.42519526,-2.584835013,51.2196,2.374239102,9.71439955,1.81,5.715111053,-3.147041851,76.28177259 +78.34,50.42519547,-2.584833646,51.2012,2.370762894,9.71417741,1.8628125,5.818132188,-3.105389538,76.27424748 +78.35,50.42519568,-2.584832279,51.1823,2.374239069,9.714177337,1.913125,5.92098241,-3.061029312,76.26672242 +78.36,50.4251959,-2.584830912,51.1629,2.374239062,9.713955196,1.961875,6.023640346,-3.013999848,76.25919731 +78.37,50.42519611,-2.584829545,51.1431,2.370762873,9.713066847,2.0115625,6.126084455,-2.964342111,76.25167225 +78.38,50.42519632,-2.584828178,51.1227,2.377715259,9.711956428,2.0615625,6.228293422,-2.912099419,76.24414714 +78.39,50.42519654,-2.584826812,51.1018,2.38814383,9.711956352,2.1096875,6.330245933,-2.85731732,76.23662209 +78.4,50.42519675,-2.584825445,51.0805,2.388143822,9.712844551,2.1565625,6.43192056,-2.800043656,76.22909697 +78.41,50.42519697,-2.584824078,51.0587,2.377715238,9.712844475,2.203125,6.53329616,-2.740328219,76.22157192 +78.42,50.42519718,-2.584822711,51.0364,2.370762845,9.711734053,2.248125,6.634351591,-2.678223261,76.2140468 +78.43,50.42519739,-2.584821345,51.0137,2.377715221,9.7108457,2.2915625,6.735065654,-2.613782812,76.20652175 +78.44,50.42519761,-2.584819978,50.9906,2.388143789,9.710623552,2.335,6.835417436,-2.54706308,76.19899664 +78.45,50.42519782,-2.584818612,50.967,2.391619972,9.710623472,2.378125,6.935385851,-2.478122334,76.19147158 +78.46,50.42519804,-2.584817245,50.943,2.391619963,9.710623391,2.419375,7.03495016,-2.407020564,76.18394647 +78.47,50.42519825,-2.584815879,50.9186,2.391619954,9.710623311,2.4584375,7.134089448,-2.333819877,76.17642141 +78.48,50.42519847,-2.584814512,50.8938,2.391619945,9.71062323,2.4965625,7.232783033,-2.258584044,76.1688963 +78.49,50.42519868,-2.584813146,50.8687,2.391619934,9.710401079,2.5346875,7.331010344,-2.181378726,76.16137124 +78.5,50.4251989,-2.584811779,50.8431,2.391619915,9.709512721,2.5715625,7.42875087,-2.102271188,76.15384613 +78.51,50.42519911,-2.584810413,50.8172,2.391619895,9.708402293,2.60625,7.525984215,-2.021330472,76.14632107 +78.52,50.42519933,-2.584809047,50.791,2.391619885,9.708402209,2.6403125,7.622689979,-1.938627051,76.13879596 +78.53,50.42519954,-2.584807681,50.7644,2.391619886,9.7092904,2.6746875,7.718848054,-1.854233175,76.1312709 +78.54,50.42519976,-2.584806314,50.7375,2.395096077,9.709290315,2.708125,7.814438327,-1.768222355,76.12374579 +78.55,50.42519997,-2.584804948,50.7102,2.405524645,9.708179886,2.7396875,7.90944086,-1.680669648,76.11622073 +78.56,50.42520019,-2.584803582,50.6827,2.412477019,9.707291525,2.7696875,8.003835771,-1.591651373,76.10869568 +78.57,50.42520041,-2.584802216,50.6548,2.405524624,9.70706937,2.798125,8.097603409,-1.501245107,76.10117057 +78.58,50.42520062,-2.58480085,50.6267,2.395096038,9.707069283,2.8246875,8.190724119,-1.409529805,76.09364551 +78.59,50.42520084,-2.584799484,50.5983,2.395096027,9.706847127,2.85,8.28317848,-1.316585279,76.0861204 +78.6,50.42520105,-2.584798118,50.5697,2.405524592,9.705958764,2.875,8.374947182,-1.222492717,76.07859534 +78.61,50.42520127,-2.584796752,50.5408,2.412476966,9.704848333,2.8996875,8.466011088,-1.127334168,76.07107023 +78.62,50.42520149,-2.584795387,50.5117,2.409000763,9.704626176,2.923125,8.556351177,-1.031192537,76.06354517 +78.63,50.4252017,-2.584794021,50.4823,2.409000749,9.704848156,2.9446875,8.645948541,-0.93415165,76.05602006 +78.64,50.42520192,-2.584792655,50.4528,2.412476922,9.704625998,2.9646875,8.734784501,-0.836296188,76.048495 +78.65,50.42520214,-2.58479129,50.423,2.409000707,9.704847977,2.9834375,8.822840494,-0.737711465,76.04096989 +78.66,50.42520235,-2.584789924,50.3931,2.412476886,9.705736162,3.00125,8.910098185,-0.638483483,76.03344483 +78.67,50.42520257,-2.584788558,50.363,2.426381646,9.705514003,3.018125,8.996539239,-0.538698701,76.02591972 +78.68,50.42520279,-2.584787192,50.3327,2.426381639,9.703737362,3.0328125,9.082145722,-0.438444207,76.01839467 +78.69,50.42520301,-2.584785827,50.3023,2.412476867,9.70240486,3.045,9.166899645,-0.337807322,76.01086955 +78.7,50.42520322,-2.584784462,50.2718,2.412476862,9.702404769,3.0565625,9.250783416,-0.236875879,76.0033445 +78.71,50.42520344,-2.584783096,50.2412,2.42638162,9.702404678,3.068125,9.333779447,-0.135737884,75.99581938 +78.72,50.42520366,-2.584781731,50.2104,2.426381609,9.702182517,3.078125,9.415870376,-0.034481517,75.98829433 +78.73,50.42520388,-2.584780366,50.1796,2.41247683,9.702626564,3.08625,9.497039187,0.066804874,75.98076922 +78.74,50.42520409,-2.584779,50.1487,2.412476816,9.703070611,3.0934375,9.577268805,0.168033051,75.97324416 +78.75,50.42520431,-2.584777635,50.1177,2.429857754,9.702404313,3.0996875,9.656542501,0.269114724,75.96571905 +78.76,50.42520453,-2.584776269,50.0867,2.440286307,9.701071809,3.1046875,9.734843773,0.369961656,75.95819399 +78.77,50.42520475,-2.584774905,50.0556,2.42985772,9.700183442,3.108125,9.812156234,0.470486012,75.95066888 +78.78,50.42520497,-2.584773539,50.0245,2.412476761,9.70018335,3.1096875,9.888463727,0.570600131,75.94314382 +78.79,50.42520518,-2.584772175,49.9934,2.412476756,9.700627396,3.1096875,9.963750324,0.670216636,75.93561871 +78.8,50.4252054,-2.584770809,49.9623,2.429857698,9.700183167,3.108125,10.03800027,0.769248724,75.92809365 +78.81,50.42520562,-2.584769444,49.9312,2.443762448,9.698628594,3.105,10.11119815,0.867609993,75.92056854 +78.82,50.42520584,-2.58476808,49.9002,2.447238632,9.697962296,3.1015625,10.18332861,0.965214728,75.91304348 +78.83,50.42520606,-2.584766715,49.8692,2.447238627,9.698850479,3.098125,10.25437658,1.061977732,75.90551837 +78.84,50.42520628,-2.58476535,49.8382,2.447238618,9.699516594,3.0928125,10.32432722,1.15781472,75.89799331 +78.85,50.4252065,-2.584763985,49.8073,2.443762414,9.698850296,3.0846875,10.39316598,1.252642043,75.8904682 +78.86,50.42520672,-2.58476262,49.7765,2.429857634,9.697739861,3.0746875,10.46087847,1.346377079,75.88294315 +78.87,50.42520694,-2.584761256,49.7458,2.412476656,9.697517701,3.0634375,10.5274505,1.43893801,75.87541803 +78.88,50.42520715,-2.584759891,49.7152,2.412476633,9.697739679,3.0515625,10.59286818,1.53024422,75.86789298 +78.89,50.42520737,-2.584758526,49.6848,2.429857579,9.697295451,3.0396875,10.65711784,1.620215955,75.86036792 +78.9,50.42520759,-2.584757162,49.6544,2.443762343,9.696629154,3.0265625,10.72018611,1.70877489,75.85284281 +78.91,50.42520781,-2.584755797,49.6242,2.447238525,9.696406994,3.0109375,10.78205982,1.795843791,75.84531775 +78.92,50.42520803,-2.584754433,49.5942,2.447238511,9.696184836,2.9934375,10.84272597,1.881346626,75.83779264 +78.93,50.42520825,-2.584753068,49.5643,2.447238504,9.69551854,2.9746875,10.902172,1.965208912,75.83026758 +78.94,50.42520847,-2.584751704,49.5347,2.4472385,9.695074312,2.955,10.96038537,2.04735748,75.82274247 +78.95,50.42520869,-2.58475034,49.5052,2.450714678,9.695296291,2.935,11.01735405,2.12772077,75.81521741 +78.96,50.42520891,-2.584748975,49.476,2.464619416,9.695074133,2.914375,11.07306606,2.20622865,75.8076923 +78.97,50.42520913,-2.584747611,49.4469,2.482000347,9.6939637,2.8915625,11.12750977,2.282812653,75.80016725 +78.98,50.42520936,-2.584746247,49.4181,2.48200034,9.693297405,2.86625,11.18067383,2.357406028,75.79264213 +78.99,50.42520958,-2.584744883,49.3896,2.46461939,9.693963522,2.84,11.23254714,2.429943688,75.78511708 +79,50.4252098,-2.584743519,49.3613,2.450714625,9.694851709,2.813125,11.28311892,2.500362379,75.77759196 +79.01,50.42521002,-2.584742154,49.3333,2.447238425,9.694185415,2.7846875,11.33237851,2.568600735,75.77006691 +79.02,50.42521024,-2.58474079,49.3056,2.447238415,9.692630848,2.755,11.38031565,2.634599285,75.76254179 +79.03,50.42521046,-2.584739427,49.2782,2.447238404,9.691964556,2.7246875,11.42692032,2.698300332,75.75501674 +79.04,50.42521068,-2.584738062,49.2511,2.450714583,9.691742401,2.6934375,11.47218284,2.75964847,75.74749163 +79.05,50.4252109,-2.584736699,49.2243,2.464619331,9.691520247,2.66125,11.5160937,2.818590185,75.73996657 +79.06,50.42521112,-2.584735335,49.1979,2.48200027,9.69174223,2.628125,11.55864378,2.875074026,75.73244146 +79.07,50.42521135,-2.584733971,49.1717,2.482000256,9.691520076,2.593125,11.5998242,2.929050719,75.7249164 +79.08,50.42521157,-2.584732607,49.146,2.464619286,9.690631717,2.55625,11.63962632,2.98047328,75.71739129 +79.09,50.42521179,-2.584731244,49.1206,2.454190702,9.690409564,2.5184375,11.67804182,3.02929679,75.70986623 +79.1,50.42521201,-2.58472988,49.0956,2.464619271,9.69063155,2.4796875,11.71506269,3.075478735,75.70234112 +79.11,50.42521223,-2.584728516,49.071,2.482000222,9.69018733,2.44,11.75068124,3.118978837,75.69481606 +79.12,50.42521246,-2.584727153,49.0468,2.482000219,9.689521042,2.4,11.78488997,3.159759108,75.68729095 +79.13,50.42521268,-2.584725789,49.023,2.468095452,9.689298892,2.3596875,11.81768172,3.197784025,75.67976589 +79.14,50.4252129,-2.584724426,48.9996,2.468095443,9.689076743,2.318125,11.84904973,3.233020471,75.67224078 +79.15,50.42521312,-2.584723062,48.9766,2.48200019,9.688188388,2.2746875,11.8789874,3.265437621,75.66471573 +79.16,50.42521335,-2.584721699,48.9541,2.482000168,9.687077965,2.2296875,11.9074885,3.295007285,75.65719061 +79.17,50.42521357,-2.584720336,48.932,2.468095388,9.687077886,2.1834375,11.93454706,3.321703623,75.64966556 +79.18,50.42521379,-2.584718973,48.9104,2.468095387,9.687966082,2.1365625,11.96015742,3.345503431,75.64214044 +79.19,50.42521401,-2.584717609,48.8893,2.482000156,9.687966005,2.0896875,11.98431424,3.366385851,75.63461539 +79.2,50.42521424,-2.584716246,48.8686,2.485476348,9.686855586,2.0415625,12.00701247,3.38433278,75.62709027 +79.21,50.42521446,-2.584714883,48.8484,2.482000149,9.685967235,1.9915625,12.02824732,3.399328518,75.61956522 +79.22,50.42521468,-2.58471352,48.8288,2.485476326,9.685745091,1.9415625,12.04801448,3.411360002,75.61204011 +79.23,50.42521491,-2.584712157,48.8096,2.485476314,9.685967085,1.8915625,12.06630977,3.420416688,75.60451505 +79.24,50.42521513,-2.584710794,48.7909,2.482000116,9.686633216,1.8396875,12.08312929,3.426490728,75.59698999 +79.25,50.42521535,-2.584709431,48.7728,2.488952482,9.686855212,1.786875,12.0984696,3.429576851,75.58946488 +79.26,50.42521558,-2.584708067,48.7552,2.499381035,9.685744797,1.735,12.1123275,3.429672306,75.58193983 +79.27,50.4252158,-2.584706705,48.7381,2.499381033,9.684634382,1.6828125,12.12470013,3.426777035,75.57441471 +79.28,50.42521603,-2.584705342,48.7215,2.488952471,9.684634312,1.628125,12.13558478,3.420893561,75.56688966 +79.29,50.42521625,-2.584703979,48.7055,2.482000092,9.684412173,1.5715625,12.14497928,3.412027039,75.55936454 +79.3,50.42521647,-2.584702616,48.6901,2.488952464,9.683523829,1.515,12.15288168,3.400185147,75.55183949 +79.31,50.4252167,-2.584701254,48.6752,2.499381026,9.683301692,1.458125,12.15929027,3.385378314,75.54431437 +79.32,50.42521692,-2.584699891,48.6609,2.502857216,9.683523694,1.4,12.16420373,3.367619315,75.53678932 +79.33,50.42521715,-2.584698528,48.6472,2.502857215,9.68307949,1.341875,12.16762102,3.346923678,75.52926421 +79.34,50.42521737,-2.584697166,48.6341,2.502857201,9.682413219,1.2846875,12.16954146,3.323309567,75.52173915 +79.35,50.4252176,-2.584695803,48.6215,2.502857179,9.682191085,1.2265625,12.16996459,3.296797377,75.51421404 +79.36,50.42521782,-2.584694441,48.6095,2.50285717,9.681968952,1.1665625,12.16889041,3.267410372,75.50668898 +79.37,50.42521805,-2.584693078,48.5982,2.502857179,9.681302683,1.1065625,12.16631909,3.235174162,75.49916387 +79.38,50.42521827,-2.584691716,48.5874,2.502857184,9.680858483,1.0465625,12.16225121,3.200116822,75.49163881 +79.39,50.4252185,-2.584690354,48.5772,2.50285718,9.681080491,0.9846875,12.15668756,3.162268949,75.4841137 +79.4,50.42521872,-2.584688991,48.5677,2.50285718,9.680858362,0.921875,12.14962929,3.121663488,75.47658864 +79.41,50.42521895,-2.584687629,48.5588,2.506333372,9.67974796,0.8603125,12.14107795,3.078335904,75.46906353 +79.42,50.42521917,-2.584686267,48.5505,2.516761933,9.678859626,0.7996875,12.13103532,3.032323955,75.46153847 +79.43,50.4252194,-2.584684905,48.5428,2.523714294,9.6786375,0.738125,12.1195034,2.983667806,75.45401336 +79.44,50.42521963,-2.584683543,48.5357,2.516761905,9.678637444,0.675,12.10648471,2.932409856,75.44648831 +79.45,50.42521985,-2.584682181,48.5293,2.506333343,9.678637388,0.6115625,12.09198189,2.878594738,75.43896319 +79.46,50.42522008,-2.584680819,48.5235,2.50633335,9.678637333,0.5484375,12.07599802,2.822269491,75.43143814 +79.47,50.4252203,-2.584679457,48.5183,2.516761921,9.678637279,0.4846875,12.05853639,2.763483162,75.42391302 +79.48,50.42522053,-2.584678095,48.5138,2.523714303,9.678415157,0.42,12.03960071,2.702287087,75.41638797 +79.49,50.42522076,-2.584676733,48.5099,2.520238108,9.677526831,0.3553125,12.01919487,2.638734551,75.40886285 +79.5,50.42522098,-2.584675371,48.5067,2.520238096,9.676416437,0.2915625,11.99732318,2.572880959,75.4013378 +79.51,50.42522121,-2.58467401,48.5041,2.523714279,9.676194318,0.2284375,11.97399017,2.504783837,75.39381269 +79.52,50.42522144,-2.584672648,48.5021,2.520238095,9.676416338,0.1646875,11.94920075,2.434502484,75.38628763 +79.53,50.42522166,-2.584671286,48.5008,2.520238105,9.676194221,0.1,11.92296008,2.362098152,75.37876252 +79.54,50.42522189,-2.584669925,48.5001,2.523714298,9.676194174,0.0353125,11.89527361,2.287634093,75.37123746 +79.55,50.42522212,-2.584668563,48.5001,2.520238105,9.676194128,-0.0284375,11.86614719,2.211175167,75.36371235 +79.56,50.42522234,-2.584667201,48.5007,2.523714296,9.67508374,-0.091875,11.83558688,2.132788066,75.35618729 +79.57,50.42522257,-2.58466584,48.5019,2.537619051,9.673973352,-0.156875,11.80359899,2.052541144,75.34866218 +79.58,50.4252228,-2.584664479,48.5038,2.537619039,9.673973309,-0.223125,11.77019028,1.970504417,75.34113712 +79.59,50.42522303,-2.584663117,48.5064,2.523714279,9.673973266,-0.288125,11.73536768,1.886749332,75.33361207 +79.6,50.42522325,-2.584661756,48.5096,2.523714291,9.673751156,-0.3515625,11.69913853,1.801348998,75.32608695 +79.61,50.42522348,-2.584660395,48.5134,2.541095254,9.673973184,-0.415,11.66151033,1.714377844,75.3185619 +79.62,50.42522371,-2.584659033,48.5179,2.555000024,9.673751076,-0.4784375,11.62249093,1.625911728,75.31103679 +79.63,50.42522394,-2.584657672,48.523,2.555000026,9.672640694,-0.5415625,11.58208852,1.536027771,75.30351173 +79.64,50.42522417,-2.584656311,48.5287,2.54109526,9.671752382,-0.605,11.54031154,1.44480441,75.29598662 +79.65,50.4252244,-2.58465495,48.5351,2.523714302,9.671530276,-0.6684375,11.49716873,1.352321172,75.28846156 +79.66,50.42522462,-2.584653589,48.5421,2.523714294,9.671752309,-0.7315625,11.45266899,1.258658616,75.28093645 +79.67,50.42522485,-2.584652228,48.5497,2.541095249,9.67241848,-0.795,11.40682177,1.163898558,75.27341139 +79.68,50.42522508,-2.584650867,48.558,2.555000029,9.672640515,-0.858125,11.35963651,1.068123563,75.26588628 +79.69,50.42522531,-2.584649505,48.5669,2.558476233,9.671530139,-0.9196875,11.31112315,0.971417111,75.25836122 +79.7,50.42522554,-2.584648145,48.5764,2.558476237,9.670419763,-0.98,11.2612918,0.873863598,75.25083611 +79.71,50.42522577,-2.584646784,48.5865,2.55500005,9.670419731,-1.04,11.21015286,0.775548051,75.24331105 +79.72,50.425226,-2.584645423,48.5972,2.541095282,9.670197632,-1.1,11.15771696,0.676556185,75.23578594 +79.73,50.42522623,-2.584644062,48.6085,2.523714319,9.66908726,-1.16,11.10399518,0.576974401,75.22826089 +79.74,50.42522645,-2.584642702,48.6204,2.523714326,9.668198958,-1.22,11.04899862,0.476889446,75.22073577 +79.75,50.42522668,-2.584641341,48.6329,2.541095296,9.667976862,-1.2796875,10.99273881,0.376388695,75.21321072 +79.76,50.42522691,-2.584639981,48.646,2.555000072,9.667976835,-1.338125,10.93522748,0.275559697,75.2056856 +79.77,50.42522714,-2.58463862,48.6597,2.558476273,9.66797681,-1.395,10.87647662,0.1744904,75.19816055 +79.78,50.42522737,-2.58463726,48.6739,2.558476279,9.667976784,-1.451875,10.81649859,0.073268926,75.19063543 +79.79,50.4252276,-2.584635899,48.6887,2.55847628,9.667976759,-1.5096875,10.75530584,-0.028016433,75.18311038 +79.8,50.42522783,-2.584634539,48.7041,2.55847628,9.667976736,-1.5665625,10.69291114,-0.129277327,75.17558527 +79.81,50.42522806,-2.584633178,48.7201,2.558476275,9.667976713,-1.6215625,10.62932761,-0.23042552,75.16806021 +79.82,50.42522829,-2.584631818,48.7365,2.55847628,9.667754622,-1.6765625,10.56456842,-0.331372776,75.1605351 +79.83,50.42522852,-2.584630457,48.7536,2.5584763,9.666866327,-1.7315625,10.49864716,-0.432031033,75.15301004 +79.84,50.42522875,-2.584629097,48.7712,2.561952507,9.665533895,-1.784375,10.43157758,-0.53231257,75.14548493 +79.85,50.42522898,-2.584627737,48.7893,2.575857277,9.664645601,-1.835,10.36337366,-0.632129954,75.13795987 +79.86,50.42522921,-2.584626377,48.8079,2.593238233,9.664423514,-1.8853125,10.29404966,-0.731396095,75.13043476 +79.87,50.42522945,-2.584625017,48.827,2.593238227,9.664423496,-1.9365625,10.22362009,-0.83002442,75.1229097 +79.88,50.42522968,-2.584623657,48.8466,2.575857271,9.66420141,-1.988125,10.15209966,-0.927928984,75.11538459 +79.89,50.42522991,-2.584622297,48.8668,2.561952526,9.663535187,-2.038125,10.07950327,-1.025024418,75.10785953 +79.9,50.42523014,-2.584620937,48.8874,2.558476361,9.663091034,-2.08625,10.00584605,-1.121225922,75.10033442 +79.91,50.42523037,-2.584619578,48.9085,2.558476374,9.663313088,-2.1334375,9.931143468,-1.216449789,75.09280937 +79.92,50.4252306,-2.584618217,48.9301,2.56195257,9.663313074,-2.1796875,9.855411052,-1.310612824,75.08528425 +79.93,50.42523083,-2.584616858,48.9521,2.575857337,9.662868923,-2.2246875,9.778664616,-1.403633038,75.0777592 +79.94,50.42523106,-2.584615498,48.9746,2.59323829,9.662424772,-2.2684375,9.700920259,-1.495429242,75.07023414 +79.95,50.4252313,-2.584614138,48.9975,2.593238297,9.661758554,-2.3115625,9.622194197,-1.585921394,75.06270903 +79.96,50.42523153,-2.584612779,49.0208,2.575857364,9.661092336,-2.355,9.542502815,-1.675030598,75.05518397 +79.97,50.42523176,-2.584611419,49.0446,2.565428807,9.661092326,-2.3978125,9.461862787,-1.76267916,75.04765886 +79.98,50.42523199,-2.58461006,49.0688,2.575857382,9.661758521,-2.438125,9.380290957,-1.848790649,75.0401338 +79.99,50.42523222,-2.5846087,49.0934,2.593238339,9.661980579,-2.4765625,9.297804401,-1.933289949,75.03260869 +80,50.42523246,-2.58460734,49.1183,2.593238347,9.660648157,-2.515,9.214420249,-2.016103435,75.02508363 +80.01,50.42523269,-2.584605981,49.1437,2.579333595,9.6588716,-2.553125,9.130155976,-2.0971588,75.01755852 +80.02,50.42523292,-2.584604622,49.1694,2.579333614,9.658649524,-2.589375,9.04502923,-2.176385399,75.01003347 +80.03,50.42523315,-2.584603263,49.1955,2.593238401,9.659537791,-2.6234375,8.959057658,-2.253714189,75.00250835 +80.04,50.42523339,-2.584601903,49.2219,2.593238414,9.659537783,-2.6565625,8.872259307,-2.329077734,74.9949833 +80.05,50.42523362,-2.584600544,49.2486,2.579333655,9.658427433,-2.69,8.784652341,-2.402410259,74.98745818 +80.06,50.42523385,-2.584599185,49.2757,2.57933366,9.657539153,-2.723125,8.696254923,-2.47364782,74.97993313 +80.07,50.42523408,-2.584597826,49.3031,2.593238423,9.657317078,-2.754375,8.607085616,-2.542728368,74.97240801 +80.08,50.42523432,-2.584596467,49.3308,2.596714617,9.657317073,-2.783125,8.517163041,-2.609591568,74.96488296 +80.09,50.42523455,-2.584595108,49.3588,2.593238448,9.657317067,-2.81,8.426505935,-2.67417921,74.95735785 +80.1,50.42523478,-2.584593749,49.387,2.596714669,9.657317062,-2.8365625,8.335133204,-2.736434913,74.94983279 +80.11,50.42523502,-2.58459239,49.4155,2.596714682,9.657317058,-2.863125,8.243064043,-2.796304419,74.94230768 +80.12,50.42523525,-2.584591031,49.4443,2.593238492,9.657317054,-2.888125,8.150317588,-2.853735474,74.93478262 +80.13,50.42523548,-2.584589672,49.4733,2.600190878,9.657317051,-2.91125,8.056913206,-2.908678058,74.92725751 +80.14,50.42523572,-2.584588313,49.5025,2.610619462,9.657094978,-2.9334375,7.962870435,-2.961084216,74.91973245 +80.15,50.42523595,-2.584586954,49.532,2.614095668,9.6562067,-2.9546875,7.868208926,-3.010908282,74.91220734 +80.16,50.42523619,-2.584585595,49.5616,2.614095689,9.654874286,-2.9746875,7.77294839,-3.058106769,74.90468228 +80.17,50.42523642,-2.584584237,49.5915,2.610619518,9.653763941,-2.993125,7.677108823,-3.102638539,74.89715717 +80.18,50.42523666,-2.584582878,49.6215,2.600190947,9.652875665,-3.0096875,7.580710107,-3.144464802,74.88963211 +80.19,50.42523689,-2.58458152,49.6517,2.593238557,9.652431526,-3.0246875,7.483772466,-3.183549003,74.882107 +80.2,50.42523712,-2.584580162,49.682,2.600190953,9.652875662,-3.038125,7.386316126,-3.219857109,74.87458195 +80.21,50.42523736,-2.584578803,49.7125,2.61061956,9.653541865,-3.05,7.288361428,-3.253357493,74.86705683 +80.22,50.42523759,-2.584577445,49.743,2.61409577,9.653541863,-3.0615625,7.189928883,-3.284020877,74.85953178 +80.23,50.42523783,-2.584576086,49.7737,2.614095767,9.652875656,-3.073125,7.091038946,-3.311820502,74.85200666 +80.24,50.42523806,-2.584574728,49.8045,2.614095769,9.652431518,-3.083125,6.991712301,-3.336732192,74.84448161 +80.25,50.4252383,-2.58457337,49.8354,2.614095791,9.652653586,-3.09125,6.891969745,-3.358734229,74.83695649 +80.26,50.42523853,-2.584572011,49.8663,2.614095817,9.652431517,-3.098125,6.791832078,-3.377807421,74.82943144 +80.27,50.42523877,-2.584570653,49.8974,2.617572028,9.651321172,-3.103125,6.691320212,-3.393935037,74.82190638 +80.28,50.425239,-2.584569295,49.9284,2.628000618,9.650432897,-3.10625,6.590455174,-3.407103154,74.81438127 +80.29,50.42523924,-2.584567937,49.9595,2.634953003,9.650210827,-3.1084375,6.489257936,-3.417300199,74.80685621 +80.3,50.42523948,-2.584566579,49.9906,2.628000613,9.650210826,-3.109375,6.387749697,-3.42451729,74.7993311 +80.31,50.42523971,-2.584565221,50.0217,2.617572051,9.650210825,-3.1084375,6.285951655,-3.428748182,74.79180605 +80.32,50.42523995,-2.584563863,50.0528,2.617572083,9.649988756,-3.1065625,6.183885011,-3.429989151,74.78428093 +80.33,50.42524018,-2.584562505,50.0838,2.62800068,9.649100481,-3.1046875,6.081571192,-3.428239109,74.77675588 +80.34,50.42524042,-2.584561147,50.1149,2.634953068,9.647990137,-3.10125,5.979031457,-3.423499602,74.76923076 +80.35,50.42524066,-2.58455979,50.1459,2.628000688,9.647768067,-3.0946875,5.87628729,-3.415774756,74.76170571 +80.36,50.42524089,-2.584558432,50.1768,2.617572124,9.647990134,-3.0865625,5.77336012,-3.405071332,74.75418059 +80.37,50.42524113,-2.584557074,50.2076,2.617572137,9.647545995,-3.0784375,5.670271434,-3.391398553,74.74665554 +80.38,50.42524136,-2.584555717,50.2384,2.628000727,9.646879789,-3.0696875,5.567042774,-3.37476851,74.73913043 +80.39,50.4252416,-2.584554359,50.269,2.634953132,9.646657719,-3.059375,5.463695683,-3.355195585,74.73160537 +80.4,50.42524184,-2.584553002,50.2996,2.631476962,9.646435649,-3.046875,5.360251763,-3.33269685,74.72408026 +80.41,50.42524207,-2.584551644,50.33,2.634953158,9.64576944,-3.0328125,5.256732613,-3.307291958,74.7165552 +80.42,50.42524231,-2.584550287,50.3602,2.648857918,9.6453253,-3.0184375,5.153159835,-3.279003084,74.70903009 +80.43,50.42524255,-2.58454893,50.3904,2.64885793,9.645547365,-3.0028125,5.049555085,-3.247854864,74.70150503 +80.44,50.42524279,-2.584547572,50.4203,2.634953195,9.645547362,-2.9846875,4.945939965,-3.213874456,74.69397992 +80.45,50.42524302,-2.584546215,50.4501,2.634953214,9.64532529,-2.965,4.84233619,-3.177091539,74.68645486 +80.46,50.42524326,-2.584544858,50.4796,2.648857977,9.645547356,-2.945,4.738765302,-3.137538086,74.67892975 +80.47,50.4252435,-2.5845435,50.509,2.648857971,9.645325283,-2.9246875,4.63524896,-3.095248701,74.67140469 +80.48,50.42524374,-2.584542143,50.5381,2.634953222,9.644214937,-2.9028125,4.531808821,-3.050260227,74.66387958 +80.49,50.42524397,-2.584540786,50.5671,2.634953256,9.643326658,-2.8784375,4.428466429,-3.002611853,74.65635453 +80.5,50.42524421,-2.584539429,50.5957,2.652334235,9.643104584,-2.8528125,4.325243384,-2.952345177,74.64882941 +80.51,50.42524445,-2.584538072,50.6241,2.666238997,9.643104578,-2.826875,4.222161287,-2.899503973,74.64130436 +80.52,50.42524469,-2.584536715,50.6523,2.666238991,9.643104572,-2.7996875,4.119241623,-2.844134363,74.63377924 +80.53,50.42524493,-2.584535358,50.6801,2.652334242,9.642882497,-2.77125,4.016505878,-2.786284648,74.62625419 +80.54,50.42524517,-2.584534001,50.7077,2.634953315,9.641994216,-2.741875,3.913975539,-2.726005248,74.61872907 +80.55,50.4252454,-2.584532644,50.735,2.634953335,9.640661798,-2.7109375,3.811671977,-2.663348761,74.61120402 +80.56,50.42524564,-2.584531288,50.7619,2.652334298,9.639773516,-2.6784375,3.70961662,-2.598369732,74.60367891 +80.57,50.42524588,-2.584529931,50.7886,2.666239069,9.639773508,-2.645,3.607830725,-2.531124941,74.59615385 +80.58,50.42524612,-2.584528575,50.8148,2.66971527,9.640439705,-2.61125,3.506335548,-2.461672945,74.58862874 +80.59,50.42524636,-2.584527218,50.8408,2.669715281,9.640883832,-2.5765625,3.405152348,-2.390074306,74.58110368 +80.6,50.4252466,-2.584525861,50.8664,2.669715292,9.640439685,-2.539375,3.304302207,-2.316391532,74.57357857 +80.61,50.42524684,-2.584524505,50.8916,2.669715302,9.639551399,-2.5,3.203806155,-2.240688796,74.56605351 +80.62,50.42524708,-2.584523148,50.9164,2.669715313,9.638441046,-2.46,3.103685218,-2.163032159,74.55852846 +80.63,50.42524732,-2.584521792,50.9408,2.666239131,9.637330691,-2.42,3.003960309,-2.083489345,74.55100334 +80.64,50.42524756,-2.584520436,50.9648,2.652334372,9.637330679,-2.38,2.904652285,-2.002129682,74.54347829 +80.65,50.4252478,-2.58451908,50.9884,2.634953423,9.638441009,-2.3396875,2.805781829,-1.919024159,74.53595317 +80.66,50.42524803,-2.584517723,51.0116,2.634953442,9.639107201,-2.2978125,2.707369566,-1.834245198,74.52842812 +80.67,50.42524827,-2.584516367,51.0344,2.652334422,9.638218914,-2.253125,2.609436125,-1.747866711,74.52090301 +80.68,50.42524851,-2.58451501,51.0567,2.669715383,9.63644235,-2.2065625,2.512001902,-1.659964099,74.51337795 +80.69,50.42524875,-2.584513655,51.0785,2.687096332,9.635776128,-2.16,2.415087294,-1.570613967,74.50585284 +80.7,50.42524899,-2.584512299,51.0999,2.704477294,9.636220248,-2.1134375,2.31871247,-1.479894236,74.49832778 +80.71,50.42524924,-2.584510942,51.1208,2.704477314,9.635776093,-2.06625,2.222897654,-1.387884032,74.49080267 +80.72,50.42524948,-2.584509587,51.1412,2.687096376,9.634887801,-2.018125,2.127662787,-1.294663513,74.48327761 +80.73,50.42524972,-2.584508231,51.1612,2.67319162,9.635109851,-1.968125,2.033027749,-1.200314094,74.4757525 +80.74,50.42524996,-2.584506875,51.1806,2.669715425,9.635553969,-1.9165625,1.939012307,-1.104917939,74.46822744 +80.75,50.4252502,-2.584505519,51.1995,2.669715424,9.634887743,-1.8653125,1.845636172,-1.008558298,74.46070233 +80.76,50.42525044,-2.584504163,51.2179,2.669715443,9.633777379,-1.8146875,1.752918709,-0.911319224,74.45317727 +80.77,50.42525068,-2.584502808,51.2358,2.669715466,9.633555288,-1.763125,1.6608794,-0.813285401,74.44565216 +80.78,50.42525092,-2.584501452,51.2532,2.669715467,9.633777334,-1.7096875,1.569537436,-0.71454237,74.4381271 +80.79,50.42525116,-2.584500096,51.27,2.673191644,9.633333174,-1.655,1.4789119,-0.615176305,74.43060199 +80.8,50.4252514,-2.584498741,51.2863,2.687096412,9.632666944,-1.6,1.38902164,-0.515273779,74.42307694 +80.81,50.42525164,-2.584497385,51.302,2.704477392,9.632444851,-1.5446875,1.299885507,-0.414921883,74.41555182 +80.82,50.42525189,-2.58449603,51.3172,2.704477414,9.632222756,-1.488125,1.211522123,-0.314208221,74.40802677 +80.83,50.42525213,-2.584494674,51.3318,2.687096462,9.631556523,-1.43,1.123949878,-0.213220571,74.40050165 +80.84,50.42525237,-2.584493319,51.3458,2.67666788,9.631112358,-1.371875,1.037187108,-0.112046939,74.3929766 +80.85,50.42525261,-2.584491964,51.3592,2.687096452,9.631334397,-1.3146875,0.951251919,-0.010775617,74.38545149 +80.86,50.42525285,-2.584490608,51.3721,2.704477424,9.631112299,-1.2565625,0.8661623,0.090505044,74.37792643 +80.87,50.4252531,-2.584489253,51.3844,2.704477443,9.630001926,-1.1965625,0.7819359,0.191706865,74.37040132 +80.88,50.42525334,-2.584487898,51.396,2.690572682,9.62911362,-1.136875,0.698590423,0.292741441,74.36287626 +80.89,50.42525358,-2.584486543,51.4071,2.690572676,9.628891519,-1.078125,0.616143286,0.393520821,74.35535115 +80.9,50.42525382,-2.584485188,51.4176,2.704477439,9.628891485,-1.0178125,0.534611621,0.493956999,74.34782609 +80.91,50.42525407,-2.584483833,51.4275,2.704477444,9.628891451,-0.955,0.454012502,0.593962428,74.34030098 +80.92,50.42525431,-2.584482478,51.4367,2.690572678,9.628891416,-0.891875,0.374362717,0.693449903,74.33277592 +80.93,50.42525455,-2.584481123,51.4453,2.690572682,9.62889138,-0.8303125,0.295678995,0.792332735,74.32525081 +80.94,50.42525479,-2.584479768,51.4533,2.704477466,9.628669275,-0.7696875,0.217977668,0.890524638,74.31772575 +80.95,50.42525504,-2.584478413,51.4607,2.707953673,9.627780963,-0.708125,0.141275063,0.987939953,74.31020064 +80.96,50.42525528,-2.584477058,51.4675,2.704477479,9.62667058,-0.645,0.065587109,1.08449377,74.30267559 +80.97,50.42525552,-2.584475704,51.4736,2.707953659,9.626448471,-0.5815625,-0.00907038,1.180101919,74.29515053 +80.98,50.42525577,-2.584474349,51.4791,2.70795365,9.626670499,-0.518125,-0.082681763,1.274680979,74.28762542 +80.99,50.42525601,-2.584472994,51.484,2.704477469,9.626226321,-0.4534375,-0.155231742,1.368148501,74.28010036 +81,50.42525625,-2.58447164,51.4882,2.711429878,9.625560072,-0.3884375,-0.226705076,1.460422953,74.27257525 +81.01,50.4252565,-2.584470285,51.4917,2.721858463,9.625337958,-0.325,-0.297086867,1.551423949,74.26505019 +81.02,50.42525674,-2.584468931,51.4947,2.721858447,9.625115845,-0.2615625,-0.36636245,1.641072019,74.25752508 +81.03,50.42525699,-2.584467576,51.497,2.711429851,9.624227525,-0.1965625,-0.434517326,1.729289128,74.25000002 +81.04,50.42525723,-2.584466222,51.4986,2.704477467,9.623117136,-0.131875,-0.501537288,1.815998211,74.24247491 +81.05,50.42525747,-2.584464868,51.4996,2.71142987,9.623117088,-0.0684375,-0.567408298,1.901123754,74.23494985 +81.06,50.42525772,-2.584463514,51.5,2.721858459,9.624005313,-0.0046875,-0.632116662,1.984591444,74.22742474 +81.07,50.42525796,-2.584462159,51.4997,2.725334642,9.624005263,0.06,-0.6956488,2.066328571,74.21989968 +81.08,50.42525821,-2.584460805,51.4988,2.725334631,9.62289487,0.125,-0.757991478,2.146263804,74.21237457 +81.09,50.42525845,-2.584459451,51.4972,2.725334633,9.622006543,0.19,-0.81913169,2.22432747,74.20484952 +81.1,50.4252587,-2.584458097,51.495,2.725334636,9.621784421,0.2546875,-0.879056601,2.300451502,74.1973244 +81.11,50.42525894,-2.584456743,51.4921,2.725334631,9.621784368,0.3184375,-0.937753835,2.374569552,74.18979935 +81.12,50.42525919,-2.584455389,51.4886,2.725334627,9.621784313,0.3815625,-0.99521096,2.446616875,74.18227423 +81.13,50.42525943,-2.584454035,51.4845,2.725334636,9.621784257,0.445,-1.051416114,2.516530732,74.17474918 +81.14,50.42525968,-2.584452681,51.4797,2.725334643,9.621562132,0.5084375,-1.106357495,2.584250161,74.16722407 +81.15,50.42525992,-2.584451327,51.4743,2.72533463,9.6206738,0.5715625,-1.160023645,2.649716032,74.15969901 +81.16,50.42526017,-2.584449973,51.4683,2.72533461,9.61934133,0.6353125,-1.212403332,2.712871336,74.1521739 +81.17,50.42526041,-2.58444862,51.4616,2.725334605,9.618452996,0.6996875,-1.26348567,2.773661012,74.14464884 +81.18,50.42526066,-2.584447266,51.4543,2.728810803,9.618230867,0.763125,-1.313259946,2.832031947,74.13712373 +81.19,50.4252609,-2.584445913,51.4463,2.73923938,9.618230805,0.825,-1.361715732,2.887933377,74.12959867 +81.2,50.42526115,-2.584444559,51.4378,2.746191761,9.618230743,0.8865625,-1.408843,2.941316427,74.12207356 +81.21,50.4252614,-2.584443206,51.4286,2.742715576,9.618008611,0.9484375,-1.454631897,2.992134632,74.1145485 +81.22,50.42526164,-2.584441852,51.4188,2.742715583,9.617342341,1.0096875,-1.499072738,3.040343645,74.10702339 +81.23,50.42526189,-2.584440499,51.4084,2.746191766,9.616898138,1.07,-1.542156414,3.085901468,74.09949833 +81.24,50.42526214,-2.584439146,51.3974,2.739239362,9.617120139,1.13,-1.583873815,3.128768279,74.09197322 +81.25,50.42526238,-2.584437792,51.3858,2.728810766,9.617120072,1.1896875,-1.624216231,3.16890678,74.08444816 +81.26,50.42526263,-2.584436439,51.3736,2.728810763,9.616675867,1.2484375,-1.663175299,3.206281963,74.07692305 +81.27,50.42526287,-2.584435086,51.3608,2.742715547,9.616231662,1.3065625,-1.700742824,3.240861226,74.069398 +81.28,50.42526312,-2.584433732,51.3475,2.760096522,9.615565386,1.365,-1.736911014,3.272614375,74.06187288 +81.29,50.42526337,-2.58443238,51.3335,2.760096509,9.614899109,1.4234375,-1.771672306,3.301513794,74.05434783 +81.3,50.42526362,-2.584431026,51.319,2.746191711,9.614899037,1.48125,-1.805019366,3.327534214,74.04682271 +81.31,50.42526386,-2.584429674,51.3039,2.742715503,9.615343101,1.538125,-1.836945319,3.350653003,74.03929766 +81.32,50.42526411,-2.58442832,51.2882,2.746191696,9.614898891,1.593125,-1.867443404,3.370849937,74.0317726 +81.33,50.42526436,-2.584426967,51.272,2.742715497,9.613344337,1.646875,-1.896507376,3.388107484,74.02424749 +81.34,50.4252646,-2.584425615,51.2553,2.746191673,9.612678057,1.7015625,-1.924131104,3.402410516,74.01672243 +81.35,50.42526485,-2.584424262,51.238,2.76357263,9.613344185,1.7565625,-1.950308801,3.4137466,74.00919732 +81.36,50.4252651,-2.584422909,51.2201,2.774001217,9.613344108,1.8096875,-1.975034966,3.422105882,74.00167226 +81.37,50.42526535,-2.584421556,51.2018,2.763572643,9.612233689,1.86125,-1.998304558,3.427480971,73.99414715 +81.38,50.4252656,-2.584420204,51.1829,2.746191665,9.611345336,1.911875,-2.020112592,3.429867283,73.9866221 +81.39,50.42526584,-2.584418851,51.1635,2.746191645,9.611123188,1.9615625,-2.0404546,3.429262698,73.97909698 +81.4,50.42526609,-2.584417499,51.1437,2.763572598,9.611123108,2.0115625,-2.059326282,3.425667789,73.97157193 +81.41,50.42526634,-2.584416146,51.1233,2.777477357,9.611123028,2.0615625,-2.076723687,3.419085593,73.96404681 +81.42,50.42526659,-2.584414794,51.1024,2.777477339,9.610900878,2.109375,-2.092643262,3.409521896,73.95652176 +81.43,50.42526684,-2.584413441,51.0811,2.763572563,9.610012522,2.155,-2.107081627,3.396985064,73.94899664 +81.44,50.42526709,-2.584412089,51.0593,2.746191612,9.608902097,2.2,-2.120035744,3.381485982,73.94147159 +81.45,50.42526733,-2.584410737,51.0371,2.74619162,9.608902013,2.245,-2.131502922,3.363038231,73.93394648 +81.46,50.42526758,-2.584409385,51.0144,2.763572565,9.609790202,2.29,-2.14148081,3.341657852,73.92642142 +81.47,50.42526783,-2.584408032,50.9913,2.777477302,9.609790116,2.334375,-2.149967232,3.317363525,73.91889631 +81.48,50.42526808,-2.58440668,50.9677,2.780953475,9.608679688,2.3765625,-2.156960525,3.290176391,73.91137125 +81.49,50.42526833,-2.584405328,50.9437,2.780953472,9.607791328,2.4165625,-2.162459201,3.260120114,73.90384614 +81.5,50.42526858,-2.584403976,50.9194,2.780953461,9.607569172,2.4565625,-2.166462056,3.227221049,73.89632108 +81.51,50.42526883,-2.584402624,50.8946,2.780953442,9.607569084,2.4965625,-2.168968288,3.19150773,73.88879597 +81.52,50.42526908,-2.584401272,50.8694,2.780953431,9.607346928,2.534375,-2.169977381,3.153011441,73.88127091 +81.53,50.42526933,-2.58439992,50.8439,2.780953429,9.606458565,2.57,-2.169489107,3.111765642,73.8737458 +81.54,50.42526958,-2.584398568,50.818,2.780953417,9.605348134,2.605,-2.167503579,3.067806314,73.86622074 +81.55,50.42526983,-2.584397217,50.7918,2.780953399,9.605125975,2.64,-2.164021199,3.021171847,73.85869563 +81.56,50.42527008,-2.584395865,50.7652,2.780953397,9.605347953,2.6746875,-2.159042711,2.971902862,73.85117058 +81.57,50.42527033,-2.584394513,50.7383,2.780953405,9.604903725,2.7078125,-2.152569147,2.920042333,73.84364546 +81.58,50.42527058,-2.584393162,50.711,2.780953393,9.604237428,2.738125,-2.144601883,2.865635464,73.83612041 +81.59,50.42527083,-2.58439181,50.6835,2.780953361,9.604237336,2.7665625,-2.135142522,2.808729754,73.82859529 +81.6,50.42527108,-2.584390459,50.6557,2.780953341,9.60490345,2.7953125,-2.124193069,2.749374764,73.82107024 +81.61,50.42527133,-2.584389107,50.6276,2.780953335,9.605125426,2.824375,-2.111755874,2.687622289,73.81354512 +81.62,50.42527158,-2.584387755,50.5992,2.780953323,9.603792921,2.8515625,-2.097833458,2.623526131,73.80602007 +81.63,50.42527183,-2.584386404,50.5705,2.780953302,9.601794212,2.87625,-2.082428743,2.557142267,73.79849496 +81.64,50.42527208,-2.584385053,50.5417,2.784429481,9.600905844,2.8996875,-2.065544937,2.488528508,73.7909699 +81.65,50.42527233,-2.584383702,50.5125,2.798334245,9.601571955,2.921875,-2.04718565,2.417744787,73.78344484 +81.66,50.42527258,-2.584382351,50.4832,2.815715192,9.602682201,2.9428125,-2.027354607,2.344852695,73.77591973 +81.67,50.42527284,-2.584380999,50.4537,2.815715173,9.602682106,2.9634375,-2.00605599,2.269915831,73.76839468 +81.68,50.42527309,-2.584379648,50.4239,2.798334209,9.601571669,2.9828125,-1.98329421,2.192999628,73.76086956 +81.69,50.42527334,-2.584378297,50.394,2.784429448,9.6006833,2.9996875,-1.959074081,2.114171063,73.75334451 +81.7,50.42527359,-2.584376946,50.3639,2.780953243,9.600461135,3.0153125,-1.933400644,2.033498892,73.74581939 +81.71,50.42527384,-2.584375595,50.3337,2.784429402,9.600461039,3.03125,-1.906279286,1.951053474,73.73829434 +81.72,50.42527409,-2.584374244,50.3033,2.798334148,9.600238875,3.04625,-1.877715621,1.866906772,73.73076922 +81.73,50.42527434,-2.584372893,50.2727,2.8157151,9.599350504,3.058125,-1.847715608,1.781132068,73.72324417 +81.74,50.4252746,-2.584371542,50.2421,2.815715087,9.598240065,3.068125,-1.81628555,1.69380419,73.71571906 +81.75,50.42527485,-2.584370192,50.2114,2.801810297,9.598017899,3.0784375,-1.783432035,1.604999284,73.708194 +81.76,50.4252751,-2.584368841,50.1805,2.801810284,9.598017802,3.0878125,-1.749161825,1.514794757,73.70066889 +81.77,50.42527535,-2.58436749,50.1496,2.815715046,9.596907362,3.0946875,-1.713482196,1.423269333,73.69314383 +81.78,50.42527561,-2.58436614,50.1186,2.815715033,9.595796923,3.1,-1.676400482,1.330502825,73.68561872 +81.79,50.42527586,-2.58436479,50.0876,2.801810244,9.596018894,3.1046875,-1.637924533,1.236576077,73.67809366 +81.8,50.42527611,-2.584363439,50.0565,2.80181023,9.596685002,3.108125,-1.59806237,1.141571023,73.67056855 +81.81,50.42527636,-2.584362089,50.0254,2.815714992,9.596684904,3.109375,-1.556822243,1.045570512,73.66304349 +81.82,50.42527662,-2.584360738,49.9943,2.81919117,9.5960186,3.1084375,-1.514212804,0.948658254,73.65551838 +81.83,50.42527687,-2.584359388,49.9632,2.815714956,9.595574366,3.1065625,-1.470242934,0.850918701,73.64799332 +81.84,50.42527712,-2.584358038,49.9322,2.819191136,9.595796337,3.105,-1.424921858,0.752437168,73.64046821 +81.85,50.42527738,-2.584356687,49.9011,2.81919114,9.595574171,3.1028125,-1.378259029,0.653299541,73.63294316 +81.86,50.42527763,-2.584355337,49.8701,2.815714946,9.594463731,3.0978125,-1.330264188,0.553592165,73.62541804 +81.87,50.42527788,-2.584353987,49.8391,2.819191115,9.59357536,3.0903125,-1.280947361,0.453402072,73.61789299 +81.88,50.42527814,-2.584352637,49.8083,2.819191091,9.593353194,3.0828125,-1.230318805,0.352816581,73.61036787 +81.89,50.42527839,-2.584351287,49.7775,2.815714886,9.593353097,3.075,-1.178389119,0.251923469,73.60284282 +81.9,50.42527864,-2.584349937,49.7467,2.822667253,9.593130931,3.0646875,-1.12516919,0.150810628,73.5953177 +81.91,50.4252789,-2.584348587,49.7162,2.833095806,9.59224256,3.053125,-1.070670074,0.04956635,73.58779265 +81.92,50.42527915,-2.584347237,49.6857,2.836571981,9.591132121,3.0415625,-1.014903175,-0.051721244,73.58026754 +81.93,50.42527941,-2.584345888,49.6553,2.83657197,9.590909956,3.0278125,-0.957880181,-0.152963688,73.57274248 +81.94,50.42527966,-2.584344538,49.6251,2.833095763,9.591131927,3.01125,-0.899612894,-0.254072748,73.56521737 +81.95,50.42527992,-2.584343188,49.5951,2.822667178,9.590909763,2.9934375,-0.840113634,-0.354960246,73.55769231 +81.96,50.42528017,-2.584341839,49.5652,2.815714791,9.591131735,2.975,-0.779394661,-0.455538174,73.5501672 +81.97,50.42528042,-2.584340489,49.5356,2.82266716,9.592019913,2.95625,-0.717468752,-0.555718927,73.54264214 +81.98,50.42528068,-2.584339139,49.5061,2.833095713,9.591797749,2.9365625,-0.654348856,-0.655415074,73.53511703 +81.99,50.42528093,-2.584337789,49.4768,2.836571892,9.589799039,2.914375,-0.590048095,-0.754539694,73.52759197 +82,50.42528119,-2.58433644,49.4478,2.836571888,9.587800328,2.89,-0.524579932,-0.85300633,73.52006692 +82.01,50.42528144,-2.584335091,49.419,2.836571875,9.587578165,2.865,-0.457958061,-0.950729095,73.5125418 +82.02,50.4252817,-2.584333742,49.3905,2.840048045,9.588466344,2.84,-0.390196348,-1.047622847,73.50501675 +82.03,50.42528195,-2.584332392,49.3622,2.850476604,9.58846625,2.8146875,-0.321308945,-1.143603075,73.49749164 +82.04,50.42528221,-2.584331043,49.3342,2.857428977,9.587355815,2.7878125,-0.251310232,-1.238586071,73.48996658 +82.05,50.42528247,-2.584329694,49.3064,2.85047658,9.586467448,2.758125,-0.180214879,-1.332488983,73.48244147 +82.06,50.42528272,-2.584328345,49.279,2.840047996,9.586467356,2.7265625,-0.108037724,-1.425229937,73.47491641 +82.07,50.42528298,-2.584326996,49.2519,2.836571801,9.587133468,2.695,-0.034793779,-1.516728031,73.4673913 +82.08,50.42528323,-2.584325647,49.2251,2.83657179,9.587355444,2.6628125,0.039501601,-1.606903567,73.45986624 +82.09,50.42528349,-2.584324297,49.1986,2.84004796,9.586245012,2.628125,0.114832889,-1.695677877,73.45234113 +82.1,50.42528374,-2.584322949,49.1725,2.850476523,9.58513458,2.5915625,0.191184442,-1.782973497,73.44481607 +82.11,50.425284,-2.5843216,49.1468,2.857428903,9.58513449,2.5553125,0.268540219,-1.868714339,73.43729096 +82.12,50.42528426,-2.584320251,49.1214,2.8539527,9.584912331,2.5196875,0.346884062,-1.952825632,73.4297659 +82.13,50.42528451,-2.584318902,49.0964,2.85395268,9.584023968,2.4828125,0.426199698,-2.035234037,73.42224079 +82.14,50.42528477,-2.584317554,49.0717,2.857428858,9.583801811,2.443125,0.506470512,-2.115867706,73.41471574 +82.15,50.42528503,-2.584316205,49.0475,2.853952659,9.584023791,2.4015625,0.587679716,-2.194656278,73.40719062 +82.16,50.42528528,-2.584314856,49.0237,2.857428837,9.583579567,2.36,0.669810409,-2.271531057,73.39966557 +82.17,50.42528554,-2.584313508,49.0003,2.871333593,9.582913276,2.318125,0.752845401,-2.346425063,73.39214045 +82.18,50.4252858,-2.584312159,48.9773,2.871333592,9.582691122,2.2746875,0.836767331,-2.41927298,73.3846154 +82.19,50.42528606,-2.584310811,48.9548,2.857428818,9.582468967,2.23,0.921558725,-2.490011209,73.37709028 +82.2,50.42528631,-2.584309462,48.9327,2.853952608,9.581802677,2.185,1.007201821,-2.558578156,73.36956523 +82.21,50.42528657,-2.584308114,48.9111,2.857428787,9.581358456,2.139375,1.093678799,-2.624913949,73.36204012 +82.22,50.42528683,-2.584306766,48.8899,2.853952589,9.581358373,2.0915625,1.180971555,-2.688960776,73.35451506 +82.23,50.42528708,-2.584305417,48.8692,2.857428769,9.580470017,2.0415625,1.26906181,-2.750662773,73.34698995 +82.24,50.42528734,-2.584304069,48.8491,2.874809717,9.579137525,1.991875,1.357931288,-2.809966197,73.33946489 +82.25,50.4252876,-2.584302722,48.8294,2.885238291,9.579359511,1.9434375,1.447561368,-2.866819252,73.33193978 +82.26,50.42528786,-2.584301373,48.8102,2.874809709,9.580247703,1.894375,1.537933314,-2.921172434,73.32441472 +82.27,50.42528812,-2.584300025,48.7915,2.857428737,9.580025555,1.843125,1.629028217,-2.972978247,73.31688961 +82.28,50.42528837,-2.584298677,48.7733,2.857428726,9.579137203,1.79,1.720827171,-3.022191655,73.30936455 +82.29,50.42528863,-2.584297329,48.7557,2.874809676,9.578026784,1.7365625,1.813310925,-3.068769628,73.30183944 +82.3,50.42528889,-2.584295981,48.7386,2.88871443,9.576694297,1.683125,1.906460169,-3.112671603,73.29431438 +82.31,50.42528915,-2.584294634,48.722,2.892190616,9.576028014,1.628125,2.000255422,-3.153859247,73.28678927 +82.32,50.42528941,-2.584293286,48.706,2.888714427,9.576694142,1.5715625,2.094677205,-3.192296693,73.27926422 +82.33,50.42528967,-2.584291939,48.6906,2.874809656,9.577582339,1.5153125,2.189705693,-3.227950425,73.2717391 +82.34,50.42528993,-2.58429059,48.6757,2.857428686,9.57691606,1.4596875,2.285321062,-3.260789329,73.26421405 +82.35,50.42529018,-2.584289243,48.6614,2.857428677,9.57536151,1.403125,2.381503373,-3.290784758,73.25668899 +82.36,50.42529044,-2.584287896,48.6476,2.874809628,9.574917301,1.345,2.478232514,-3.317910585,73.24916388 +82.37,50.4252907,-2.584286548,48.6345,2.888714384,9.575361365,1.2865625,2.575488318,-3.342143205,73.24163882 +82.38,50.42529096,-2.584285201,48.6219,2.892190571,9.575583362,1.2284375,2.673250388,-3.36346136,73.23411371 +82.39,50.42529122,-2.584283853,48.6099,2.892190575,9.575583292,1.1696875,2.77149844,-3.381846545,73.22658865 +82.4,50.42529148,-2.584282506,48.5985,2.89219057,9.575361154,1.1096875,2.870211849,-3.397282715,73.21906354 +82.41,50.42529174,-2.584281158,48.5877,2.892190556,9.574472813,1.0484375,2.969370045,-3.40975635,73.21153848 +82.42,50.425292,-2.584279811,48.5775,2.89219055,9.573140336,0.9865625,3.068952345,-3.419256678,73.20401337 +82.43,50.42529226,-2.584278464,48.568,2.892190548,9.572251996,0.925,3.168937892,-3.425775391,73.19648832 +82.44,50.42529252,-2.584277117,48.559,2.892190542,9.572029862,0.8634375,3.269305831,-3.429306701,73.1889632 +82.45,50.42529278,-2.58427577,48.5507,2.89219054,9.572029796,0.80125,3.370035192,-3.429847688,73.18143815 +82.46,50.42529304,-2.584274423,48.543,2.892190546,9.572029733,0.7384375,3.471104947,-3.427397721,73.17391303 +82.47,50.4252933,-2.584273076,48.5359,2.892190543,9.571807601,0.675,3.572494011,-3.421959033,73.16638798 +82.48,50.42529356,-2.584271729,48.5295,2.892190531,9.570919267,0.611875,3.674181185,-3.413536382,73.15886286 +82.49,50.42529382,-2.584270382,48.5237,2.892190526,9.569808865,0.55,3.77614527,-3.402137043,73.15133781 +82.5,50.42529408,-2.584269036,48.5185,2.892190526,9.569586736,0.488125,3.878364894,-3.387770985,73.1438127 +82.51,50.42529434,-2.584267689,48.5139,2.895666713,9.569808745,0.4246875,3.980818744,-3.370450758,73.13628764 +82.52,50.4252946,-2.584266342,48.51,2.909571475,9.569586618,0.36,4.083485504,-3.350191486,73.12876253 +82.53,50.42529486,-2.584264996,48.5067,2.92695243,9.56958656,0.295,4.186343632,-3.327010759,73.12123747 +82.54,50.42529513,-2.584263649,48.5041,2.926952427,9.569808571,0.23,4.289371642,-3.300928804,73.11371236 +82.55,50.42529539,-2.584262302,48.5021,2.909571474,9.569364379,0.165,4.392548106,-3.271968423,73.1061873 +82.56,50.42529565,-2.584260956,48.5008,2.895666719,9.568476051,0.1,4.495851422,-3.240154827,73.09866219 +82.57,50.42529591,-2.584259609,48.5001,2.892190528,9.567365657,0.0353125,4.599260048,-3.205515746,73.09113713 +82.58,50.42529617,-2.584258263,48.5001,2.895666708,9.566255264,-0.0284375,4.702752326,-3.168081434,73.08361202 +82.59,50.42529643,-2.584256917,48.5007,2.90957146,9.566255212,-0.0915625,4.806306656,-3.127884492,73.07608696 +82.6,50.42529669,-2.584255571,48.5019,2.926952407,9.567143434,-0.1553125,4.909901493,-3.084960041,73.06856185 +82.61,50.42529696,-2.584254224,48.5038,2.926952406,9.567143383,-0.22,5.013515123,-3.039345381,73.0610368 +82.62,50.42529722,-2.584252878,48.5063,2.909571463,9.566032993,-0.2846875,5.117125946,-2.99108039,73.05351168 +82.63,50.42529748,-2.584251532,48.5095,2.899142903,9.565144673,-0.3484375,5.220712304,-2.940207181,73.04598663 +82.64,50.42529774,-2.584250186,48.5133,2.909571478,9.564922558,-0.4115625,5.324252538,-2.886770043,73.03846151 +82.65,50.425298,-2.58424884,48.5177,2.926952435,9.564922511,-0.4753125,5.427725049,-2.830815558,73.03093646 +82.66,50.42529827,-2.584247494,48.5228,2.926952439,9.564700397,-0.54,5.531108293,-2.772392598,73.02341134 +82.67,50.42529853,-2.584246148,48.5285,2.913047676,9.56381208,-0.6046875,5.634380555,-2.711552044,73.01588629 +82.68,50.42529879,-2.584244802,48.5349,2.913047681,9.562701696,-0.668125,5.737520407,-2.648347007,73.00836118 +82.69,50.42529905,-2.584243457,48.5419,2.926952457,9.562701654,-0.73,5.84050619,-2.582832549,73.00083612 +82.7,50.42529932,-2.584242111,48.5495,2.930428652,9.563589885,-0.791875,5.943316476,-2.515065851,72.99331106 +82.71,50.42529958,-2.584240765,48.5577,2.926952456,9.563367776,-0.8546875,6.045929722,-2.445105928,72.98578595 +82.72,50.42529984,-2.584239419,48.5666,2.930428649,9.56159119,-0.9165625,6.148324557,-2.373013857,72.9782609 +82.73,50.42530011,-2.584238074,48.5761,2.930428656,9.560258742,-0.9765625,6.250479551,-2.298852549,72.97073578 +82.74,50.42530037,-2.584236729,48.5861,2.926952465,9.560480773,-1.036875,6.352373449,-2.222686519,72.96321073 +82.75,50.42530063,-2.584235383,48.5968,2.930428652,9.561146941,-1.0984375,6.453984936,-2.144582288,72.95568561 +82.76,50.4253009,-2.584234038,48.6081,2.930428649,9.561146904,-1.1596875,6.555292697,-2.064607979,72.94816056 +82.77,50.42530116,-2.584232692,48.62,2.926952461,9.560258596,-1.2196875,6.656275707,-1.982833323,72.94063544 +82.78,50.42530142,-2.584231347,48.6325,2.93390486,9.558926152,-1.2784375,6.756912821,-1.899329537,72.93311039 +82.79,50.42530169,-2.584230002,48.6456,2.94433345,9.558259914,-1.3365625,6.857183014,-1.814169559,72.92558528 +82.8,50.42530195,-2.584228657,48.6592,2.947809647,9.558704018,-1.3946875,6.957065371,-1.727427588,72.91806022 +82.81,50.42530222,-2.584227312,48.6735,2.947809654,9.559148123,-1.451875,7.056539038,-1.639179253,72.91053511 +82.82,50.42530248,-2.584225966,48.6883,2.944333472,9.558703955,-1.5078125,7.155583158,-1.549501561,72.90301005 +82.83,50.42530275,-2.584224622,48.7036,2.933904904,9.557815651,-1.56375,7.254177162,-1.458472662,72.89548494 +82.84,50.42530301,-2.584223276,48.7196,2.926952532,9.556927349,-1.6196875,7.352300424,-1.366171969,72.88795988 +82.85,50.42530327,-2.584221932,48.736,2.933904931,9.556483184,-1.6746875,7.449932433,-1.272679924,72.88043477 +82.86,50.42530354,-2.584220587,48.7531,2.944333512,9.556705225,-1.7284375,7.54705279,-1.178078118,72.87290971 +82.87,50.4253038,-2.584219242,48.7706,2.9478097,9.556483129,-1.78125,7.643641213,-1.082448998,72.8653846 +82.88,50.42530407,-2.584217897,48.7887,2.947809697,9.55559483,-1.8334375,7.739677533,-0.98587593,72.85785954 +82.89,50.42530433,-2.584216553,48.8073,2.947809697,9.555372737,-1.885,7.835141756,-0.888443197,72.85033443 +82.9,50.4253046,-2.584215208,48.8264,2.951285895,9.555594781,-1.9365625,7.930013884,-0.79023571,72.84280938 +82.91,50.42530486,-2.584213863,48.846,2.961714489,9.55515062,-1.9878125,8.024274093,-0.691339183,72.83528426 +82.92,50.42530513,-2.584212519,48.8662,2.968666891,9.554262324,-2.0365625,8.11790273,-0.591839734,72.82775921 +82.93,50.4253054,-2.584211174,48.8868,2.961714519,9.553374028,-2.083125,8.210880259,-0.491824221,72.82023409 +82.94,50.42530566,-2.58420983,48.9078,2.951285955,9.55292987,-2.1303125,8.303187197,-0.39137985,72.81270904 +82.95,50.42530593,-2.584208486,48.9294,2.947809777,9.553151916,-2.178125,8.394804295,-0.29059411,72.80518392 +82.96,50.42530619,-2.584207141,48.9514,2.947809785,9.552929828,-2.224375,8.485712471,-0.189555065,72.79765887 +82.97,50.42530646,-2.584205797,48.9739,2.951285984,9.551819467,-2.2684375,8.575892705,-0.088350665,72.79013376 +82.98,50.42530672,-2.584204453,48.9968,2.961714562,9.550931174,-2.31125,8.665326146,0.012930741,72.7826087 +82.99,50.42530699,-2.584203109,49.0201,2.968666942,9.550709088,-2.3534375,8.753994115,0.114200916,72.77508359 +83,50.42530726,-2.584201765,49.0439,2.965190762,9.550709071,-2.395,8.841878105,0.215371455,72.76755853 +83.01,50.42530752,-2.584200421,49.068,2.965190787,9.550709053,-2.43625,8.928959783,0.316354235,72.76003342 +83.02,50.42530779,-2.584199077,49.0926,2.968666996,9.550709035,-2.4765625,9.015220986,0.417061136,72.75250836 +83.03,50.42530806,-2.584197733,49.1176,2.965190819,9.550709019,-2.5146875,9.100643607,0.517404323,72.74498331 +83.04,50.42530832,-2.584196389,49.1429,2.965190833,9.550486935,-2.5515625,9.185209886,0.617296363,72.73745819 +83.05,50.42530859,-2.584195045,49.1686,2.968667034,9.549598648,-2.588125,9.268902118,0.71665011,72.72993314 +83.06,50.42530886,-2.584193701,49.1947,2.965190855,9.548266223,-2.623125,9.351702884,0.815378931,72.72240802 +83.07,50.42530912,-2.584192358,49.2211,2.968667059,9.547377936,-2.6565625,9.433594825,0.913396712,72.71488297 +83.08,50.42530939,-2.584191014,49.2478,2.982571826,9.547155854,-2.69,9.514560866,1.010617967,72.70735786 +83.09,50.42530966,-2.584189671,49.2749,2.982571827,9.547155841,-2.7228125,9.594584105,1.106958013,72.6998328 +83.1,50.42530993,-2.584188327,49.3023,2.968667077,9.547155828,-2.753125,9.673647812,1.202332739,72.69230769 +83.11,50.42531019,-2.584186984,49.33,2.968667099,9.547155816,-2.7815625,9.751735485,1.29665901,72.68478263 +83.12,50.42531046,-2.58418564,49.3579,2.982571886,9.547155804,-2.8096875,9.828830853,1.389854549,72.67725752 +83.13,50.42531073,-2.584184297,49.3862,2.982571904,9.546933724,-2.8365625,9.904917757,1.481838167,72.66973246 +83.14,50.425311,-2.584182953,49.4147,2.96866715,9.54604544,-2.8615625,9.979980328,1.572529594,72.66220735 +83.15,50.42531126,-2.58418161,49.4434,2.968667161,9.54471302,-2.8865625,10.05400287,1.661849704,72.65468229 +83.16,50.42531153,-2.584180267,49.4724,2.986048125,9.543824736,-2.91125,10.12697001,1.749720688,72.64715718 +83.17,50.4253118,-2.584178924,49.5017,2.999952892,9.543602658,-2.933125,10.19886642,1.836065886,72.63963212 +83.18,50.42531207,-2.584177581,49.5311,2.999952906,9.543602648,-2.953125,10.26967707,1.920810011,72.63210701 +83.19,50.42531234,-2.584176238,49.5607,2.986048167,9.543602638,-2.973125,10.3393873,2.003879208,72.62458196 +83.2,50.42531261,-2.584174895,49.5906,2.96866723,9.543602628,-2.9915625,10.40798238,2.085200942,72.61705684 +83.21,50.42531287,-2.584173552,49.6206,2.968667247,9.543602619,-3.0078125,10.47544816,2.164704336,72.60953179 +83.22,50.42531314,-2.584172209,49.6507,2.986048221,9.543380543,-3.0234375,10.54177037,2.242320064,72.60200667 +83.23,50.42531341,-2.584170866,49.6811,2.999952997,9.542492262,-3.038125,10.60693533,2.317980516,72.59448162 +83.24,50.42531368,-2.584169523,49.7115,3.003429194,9.541381912,-3.05125,10.67092933,2.39161963,72.5869565 +83.25,50.42531395,-2.584168181,49.7421,3.0034292,9.541159834,-3.0634375,10.73373902,2.463173178,72.57943145 +83.26,50.42531422,-2.584166838,49.7728,3.003429212,9.541381893,-3.074375,10.79535129,2.532578879,72.57190634 +83.27,50.42531449,-2.584165495,49.8036,3.003429238,9.540937749,-3.083125,10.85575325,2.599776056,72.56438128 +83.28,50.42531476,-2.584164153,49.8345,3.003429264,9.540049469,-3.09,10.91493234,2.664706212,72.55685617 +83.29,50.42531503,-2.58416281,49.8654,3.003429278,9.539161188,-3.09625,10.97287619,2.727312737,72.54933111 +83.3,50.4253153,-2.584161468,49.8964,3.003429291,9.538717044,-3.1015625,11.02957266,2.787540972,72.541806 +83.31,50.42531557,-2.584160126,49.9275,3.003429299,9.538939104,-3.1046875,11.08500994,2.845338434,72.53428094 +83.32,50.42531584,-2.584158783,49.9585,3.0034293,9.538939096,-3.1065625,11.13917645,2.900654759,72.52675583 +83.33,50.42531611,-2.584157441,49.9896,3.003429315,9.538494952,-3.1084375,11.19206085,2.953441647,72.51923077 +83.34,50.42531638,-2.584156099,50.0207,3.003429343,9.537828739,-3.109375,11.24365209,3.003653032,72.51170566 +83.35,50.42531665,-2.584154756,50.0518,3.003429365,9.536718391,-3.108125,11.29393945,3.051245256,72.5041806 +83.36,50.42531692,-2.584153415,50.0829,3.003429382,9.536496314,-3.1046875,11.34291245,3.096176721,72.49665549 +83.37,50.42531719,-2.584152073,50.1139,3.003429396,9.537828715,-3.1,11.39056077,3.138408294,72.48913044 +83.38,50.42531746,-2.58415073,50.1449,3.0034294,9.538272844,-3.0946875,11.43687449,3.177903134,72.48160538 +83.39,50.42531773,-2.584149388,50.1758,3.003429404,9.53649629,-3.088125,11.481844,3.214626749,72.47408027 +83.4,50.425318,-2.584148046,50.2067,3.003429421,9.534497668,-3.0796875,11.52545978,3.248547169,72.46655521 +83.41,50.42531827,-2.584146705,50.2374,3.003429444,9.534053524,-3.07,11.5677129,3.279634827,72.4590301 +83.42,50.42531854,-2.584145363,50.2681,3.006905659,9.534275584,-3.0596875,11.60859435,3.307862624,72.45150504 +83.43,50.42531881,-2.584144021,50.2986,3.020810444,9.534053508,-3.0478125,11.64809573,3.333205866,72.44397993 +83.44,50.42531908,-2.58414268,50.3291,3.038191405,9.534053498,-3.0334375,11.68620871,3.355642549,72.43645487 +83.45,50.42531936,-2.584141338,50.3593,3.038191401,9.534053487,-3.018125,11.72292539,3.375153022,72.42892976 +83.46,50.42531963,-2.584139996,50.3894,3.020810456,9.532943136,-3.003125,11.7582381,3.391720326,72.4214047 +83.47,50.4253199,-2.584138655,50.4194,3.00690572,9.531832786,-2.98625,11.79213938,3.405329965,72.41387959 +83.48,50.42532017,-2.584137314,50.4492,3.006905748,9.532054845,-2.9665625,11.82462225,3.415970192,72.40635453 +83.49,50.42532044,-2.584135972,50.4787,3.020810528,9.532498971,-2.9465625,11.85567982,3.423631554,72.39882942 +83.5,50.42532071,-2.584134631,50.5081,3.038191493,9.531832755,-2.9265625,11.88530575,3.42830752,72.39130437 +83.51,50.42532099,-2.584133289,50.5373,3.038191498,9.530722403,-2.904375,11.91349373,3.429993907,72.38377925 +83.52,50.42532126,-2.584131949,50.5662,3.02081055,9.530500323,-2.8796875,11.94023791,3.428689282,72.3762542 +83.53,50.42532153,-2.584130607,50.5949,3.010381998,9.530722379,-2.8534375,11.96553274,3.424394849,72.36872908 +83.54,50.4253218,-2.584129266,50.6233,3.020810599,9.530278231,-2.8265625,11.98937288,3.417114217,72.36120403 +83.55,50.42532207,-2.584127925,50.6514,3.038191571,9.529389946,-2.8,12.01175336,3.40685386,72.35367892 +83.56,50.42532235,-2.584126584,50.6793,3.041667767,9.52850166,-2.7728125,12.03266958,3.393622661,72.34615386 +83.57,50.42532262,-2.584125243,50.7069,3.03819158,9.528057509,-2.743125,12.05211709,3.377432191,72.33862875 +83.58,50.42532289,-2.584123903,50.7342,3.041667781,9.528279563,-2.7115625,12.0700918,3.358296547,72.33110369 +83.59,50.42532317,-2.584122561,50.7611,3.038191606,9.528057481,-2.6796875,12.08659012,3.3362324,72.32357858 +83.6,50.42532344,-2.584121221,50.7878,3.024286857,9.526947126,-2.6465625,12.10160844,3.311259004,72.31605352 +83.61,50.42532371,-2.58411988,50.8141,3.024286869,9.526280906,-2.61125,12.11514365,3.283398186,72.30852841 +83.62,50.42532398,-2.58411854,50.84,3.041667836,9.526725025,-2.575,12.12719301,3.252674126,72.30100335 +83.63,50.42532426,-2.584117199,50.8656,3.055572615,9.527169145,-2.5384375,12.13775394,3.219113754,72.29347824 +83.64,50.42532453,-2.584115858,50.8908,3.055572638,9.526724991,-2.50125,12.1468242,3.182746232,72.28595318 +83.65,50.42532481,-2.584114518,50.9156,3.045144085,9.5258367,-2.463125,12.15440197,3.143603302,72.27842807 +83.66,50.42532508,-2.584113177,50.9401,3.03819171,9.524948409,-2.423125,12.16048564,3.101719113,72.27090301 +83.67,50.42532535,-2.584111837,50.9641,3.041667905,9.524504254,-2.3815625,12.16507388,3.057130163,72.2633779 +83.68,50.42532563,-2.584110497,50.9877,3.041667907,9.524726302,-2.34,12.16816585,3.009875411,72.25585285 +83.69,50.4253259,-2.584109156,51.0109,3.038191724,9.524504213,-2.2978125,12.16976079,2.95999594,72.24832773 +83.7,50.42532617,-2.584107816,51.0337,3.045144131,9.523393852,-2.253125,12.16985848,2.907535294,72.24080268 +83.71,50.42532645,-2.584106476,51.056,3.055572727,9.522505558,-2.206875,12.1684588,2.85253931,72.23327756 +83.72,50.42532672,-2.584105136,51.0778,3.059048919,9.522283467,-2.1615625,12.1655621,2.795055829,72.22575251 +83.73,50.425327,-2.584103796,51.0992,3.059048912,9.522061375,-2.1165625,12.16116895,2.735134986,72.21822745 +83.74,50.42532727,-2.584102456,51.1202,3.059048922,9.521395147,-2.069375,12.15528026,2.672829092,72.21070234 +83.75,50.42532755,-2.584101116,51.1406,3.05904895,9.520950986,-2.02,12.1478973,2.608192463,72.20317728 +83.76,50.42532782,-2.584099777,51.1606,3.059048971,9.521173028,-1.97,12.13902155,2.54128142,72.19565217 +83.77,50.4253281,-2.584098436,51.18,3.059048971,9.520950934,-1.9196875,12.12865497,2.472154406,72.18812711 +83.78,50.42532837,-2.584097097,51.199,3.059048969,9.519840567,-1.8684375,12.11679967,2.400871581,72.180602 +83.79,50.42532865,-2.584095757,51.2174,3.059048981,9.519174334,-1.81625,12.10345806,2.327495168,72.17307695 +83.8,50.42532892,-2.584094418,51.2353,3.059048996,9.519618442,-1.7634375,12.088633,2.252089166,72.16555183 +83.81,50.4253292,-2.584093078,51.2527,3.059049004,9.520062549,-1.7096875,12.0723276,2.174719295,72.15802678 +83.82,50.42532947,-2.584091738,51.2695,3.059049006,9.519618382,-1.655,12.05454522,2.09545299,72.15050166 +83.83,50.42532975,-2.584090399,51.2858,3.062525202,9.518730079,-1.6,12.03528955,2.014359466,72.14297661 +83.84,50.42533002,-2.584089059,51.3015,3.072953792,9.517619707,-1.545,12.01456469,1.931509425,72.13545149 +83.85,50.4253303,-2.58408772,51.3167,3.079906188,9.516287265,-1.4896875,11.99237495,1.846975003,72.12792644 +83.86,50.42533058,-2.584086381,51.3313,3.076429996,9.515621026,-1.433125,11.96872491,1.760830053,72.12040133 +83.87,50.42533085,-2.584085042,51.3454,3.076429994,9.516287197,-1.375,11.94361956,1.673149577,72.11287627 +83.88,50.42533113,-2.584083703,51.3588,3.0799062,9.517397502,-1.3165625,11.91706406,1.584010121,72.10535116 +83.89,50.42533141,-2.584082363,51.3717,3.072953837,9.517397466,-1.2584375,11.88906407,1.493489379,72.0978261 +83.9,50.42533168,-2.584081024,51.384,3.06252527,9.516065019,-1.1996875,11.85962538,1.401666303,72.09030099 +83.91,50.42533196,-2.584079685,51.3957,3.062525269,9.514288436,-1.14,11.82875419,1.308620994,72.08277593 +83.92,50.42533223,-2.584078346,51.4068,3.076430036,9.512955989,-1.0796875,11.79645684,1.214434467,72.07525082 +83.93,50.42533251,-2.584077008,51.4173,3.093811001,9.512955948,-1.0184375,11.76274017,1.119189,72.06772576 +83.94,50.42533279,-2.584075669,51.4272,3.093811017,9.514066248,-0.9565625,11.72761121,1.022967556,72.06020065 +83.95,50.42533307,-2.58407433,51.4364,3.079906261,9.514732411,-0.895,11.69107724,0.925854075,72.05267559 +83.96,50.42533334,-2.584072991,51.4451,3.076430062,9.514066164,-0.8334375,11.65314589,0.827933181,72.04515048 +83.97,50.42533362,-2.584071652,51.4531,3.07990624,9.512733712,-0.77125,11.61382517,0.729290361,72.03762543 +83.98,50.4253339,-2.584070314,51.4605,3.076430052,9.511623326,-0.7084375,11.57312322,0.630011615,72.03010031 +83.99,50.42533417,-2.584068975,51.4673,3.079906263,9.510735008,-0.645,11.53104853,0.530183459,72.02257526 +84,50.42533445,-2.584067637,51.4734,3.093811041,9.510290826,-0.581875,11.48760996,0.429892984,72.01505014 +84.01,50.42533473,-2.584066299,51.4789,3.093811033,9.510734915,-0.52,11.44281652,0.329227622,72.00752509 +84.02,50.42533501,-2.58406496,51.4838,3.079906265,9.511401071,-0.4578125,11.39667761,0.228275209,71.99999998 +84.03,50.42533528,-2.584063622,51.4881,3.079906278,9.511401021,-0.393125,11.34920278,0.127123693,71.99247492 +84.04,50.42533556,-2.584062283,51.4917,3.097287238,9.510512699,-0.326875,11.30040202,0.025861367,71.98494981 +84.05,50.42533584,-2.584060945,51.4946,3.111191995,9.509180239,-0.261875,11.25028551,-0.075423534,71.97742475 +84.06,50.42533612,-2.584059607,51.4969,3.111191996,9.508291914,-0.1984375,11.1988637,-0.176642716,71.96989964 +84.07,50.4253364,-2.584058269,51.4986,3.097287242,9.508069791,-0.1346875,11.14614734,-0.277707773,71.96237458 +84.08,50.42533668,-2.584056931,51.4996,3.079906284,9.508069737,-0.07,11.09214744,-0.378530755,71.95484953 +84.09,50.42533695,-2.584055593,51.5,3.079906271,9.508069682,-0.0053125,11.03687524,-0.479023599,71.94732441 +84.1,50.42533723,-2.584054255,51.4997,3.097287228,9.508069626,0.0584375,10.98034235,-0.579098699,71.93979936 +84.11,50.42533751,-2.584052917,51.4988,3.111192006,9.507847501,0.121875,10.92256053,-0.678668852,71.93227424 +84.12,50.42533779,-2.584051579,51.4973,3.114668205,9.506959171,0.1865625,10.86354187,-0.777647197,71.92474919 +84.13,50.42533807,-2.584050241,51.4951,3.1146682,9.505848771,0.251875,10.80329868,-0.875947446,71.91722407 +84.14,50.42533835,-2.584048904,51.4922,3.114668194,9.505626642,0.31625,10.74184357,-0.973483827,71.90969902 +84.15,50.42533863,-2.584047566,51.4888,3.114668195,9.505626581,0.38,10.67918932,-1.070171315,71.90217391 +84.16,50.42533891,-2.584046228,51.4846,3.114668193,9.504516178,0.4434375,10.61534904,-1.165925568,71.89464885 +84.17,50.42533919,-2.584044891,51.4799,3.114668188,9.503405774,0.5065625,10.55033609,-1.260663166,71.88712374 +84.18,50.42533947,-2.584043554,51.4745,3.11466819,9.503627778,0.5703125,10.48416399,-1.354301429,71.87959868 +84.19,50.42533975,-2.584042216,51.4685,3.114668192,9.504293918,0.6346875,10.41684661,-1.446758712,71.87207357 +84.2,50.42534003,-2.584040879,51.4618,3.114668182,9.504293851,0.698125,10.34839803,-1.537954456,71.86454851 +84.21,50.42534031,-2.584039541,51.4545,3.11466817,9.503405512,0.76,10.27883248,-1.62780902,71.8570234 +84.22,50.42534059,-2.584038204,51.4466,3.114668173,9.502073035,0.821875,10.20816449,-1.716244139,71.84949834 +84.23,50.42534087,-2.584036867,51.4381,3.114668182,9.501184695,0.885,10.13640886,-1.803182635,71.84197323 +84.24,50.42534115,-2.58403553,51.4289,3.114668176,9.500962557,0.9478125,10.06358054,-1.888548763,71.83444817 +84.25,50.42534143,-2.584034193,51.4191,3.114668162,9.500962487,1.008125,9.98969477,-1.972268038,71.82692306 +84.26,50.42534171,-2.584032856,51.4087,3.114668159,9.500962415,1.066875,9.914766959,-2.054267466,71.81939801 +84.27,50.42534199,-2.584031519,51.3978,3.114668159,9.500740274,1.126875,9.838812751,-2.134475484,71.81187289 +84.28,50.42534227,-2.584030182,51.3862,3.114668147,9.499851928,1.188125,9.761848018,-2.212822306,71.80434784 +84.29,50.42534255,-2.584028845,51.374,3.114668132,9.498741514,1.248125,9.68388886,-2.289239463,71.79682272 +84.3,50.42534283,-2.584027509,51.3612,3.11466813,9.498519371,1.3065625,9.604951548,-2.363660378,71.78929767 +84.31,50.42534311,-2.584026172,51.3479,3.11466813,9.498741362,1.365,9.525052526,-2.436020135,71.78177255 +84.32,50.42534339,-2.584024835,51.3339,3.11814431,9.498297149,1.423125,9.444208467,-2.506255651,71.7742475 +84.33,50.42534367,-2.584023499,51.3194,3.132049068,9.497630868,1.4796875,9.362436332,-2.574305676,71.76672239 +84.34,50.42534395,-2.584022162,51.3043,3.14943003,9.497408721,1.535,9.279753136,-2.640110853,71.75919733 +84.35,50.42534424,-2.584020826,51.2887,3.149430022,9.497186573,1.59,9.196176184,-2.703613828,71.75167222 +84.36,50.42534452,-2.584019489,51.2725,3.132049046,9.496520288,1.645,9.11172295,-2.764759254,71.74414716 +84.37,50.4253448,-2.584018153,51.2558,3.118144274,9.496076071,1.6996875,9.026410966,-2.82349373,71.73662205 +84.38,50.42534508,-2.584016817,51.2385,3.118144279,9.496298057,1.7534375,8.940258167,-2.879766035,71.72909699 +84.39,50.42534536,-2.58401548,51.2207,3.132049038,9.496075907,1.8065625,8.853282487,-2.933527181,71.72157188 +84.4,50.42534564,-2.584014144,51.2024,3.149429982,9.494965483,1.8596875,8.765502087,-2.984730299,71.71404682 +84.41,50.42534593,-2.584012808,51.1835,3.149429973,9.494077126,1.9115625,8.676935302,-3.033330642,71.70652177 +84.42,50.42534621,-2.584011472,51.1641,3.135525192,9.493854973,1.96125,8.587600696,-3.079285868,71.69899665 +84.43,50.42534649,-2.584010136,51.1443,3.135525174,9.493854887,2.01,8.497516777,-3.122555869,71.6914716 +84.44,50.42534677,-2.5840088,51.1239,3.149429931,9.4938548,2.0584375,8.406702508,-3.163103004,71.68394649 +84.45,50.42534706,-2.584007464,51.1031,3.149429923,9.493632644,2.10625,8.315176797,-3.200891862,71.67642143 +84.46,50.42534734,-2.584006128,51.0818,3.135525144,9.492744283,2.1534375,8.222958725,-3.2358895,71.66889632 +84.47,50.42534762,-2.584004792,51.06,3.135525142,9.491633854,2.1996875,8.130067541,-3.268065434,71.66137126 +84.48,50.4253479,-2.584003457,51.0378,3.149429913,9.491411697,2.245,8.036522727,-3.297391477,71.65384615 +84.49,50.42534819,-2.584002121,51.0151,3.15290609,9.491633675,2.2896875,7.942343821,-3.323842245,71.64632109 +84.5,50.42534847,-2.584000785,50.992,3.149429871,9.491189449,2.333125,7.84755036,-3.347394478,71.63879598 +84.51,50.42534875,-2.58399945,50.9684,3.15290605,9.490523152,2.375,7.752162284,-3.368027777,71.63127092 +84.52,50.42534904,-2.583998114,50.9445,3.152906047,9.490300991,2.41625,7.656199416,-3.385724094,71.62374581 +84.53,50.42534932,-2.583996779,50.9201,3.149429845,9.49007883,2.4565625,7.559681868,-3.400468017,71.61622075 +84.54,50.4253496,-2.583995443,50.8953,3.156382213,9.489190465,2.4946875,7.46262975,-3.412246711,71.60869564 +84.55,50.42534989,-2.583994108,50.8702,3.166810773,9.487857963,2.5315625,7.365063346,-3.421049864,71.60117059 +84.56,50.42535017,-2.583992773,50.8447,3.166810758,9.486969596,2.5684375,7.267002994,-3.426869797,71.59364547 +84.57,50.42535046,-2.583991438,50.8188,3.156382178,9.486747432,2.6046875,7.168469265,-3.429701412,71.58612042 +84.58,50.42535074,-2.583990103,50.7926,3.149429794,9.486747336,2.6396875,7.069482612,-3.429542302,71.5785953 +84.59,50.42535102,-2.583988768,50.766,3.156382161,9.486747241,2.6734375,6.970063835,-3.426392581,71.57107025 +84.6,50.42535131,-2.583987433,50.7391,3.166810709,9.486747144,2.70625,6.870233617,-3.420255,71.56354513 +84.61,50.42535159,-2.583986098,50.7119,3.170286883,9.486747047,2.738125,6.770012814,-3.411134944,71.55602008 +84.62,50.42535188,-2.583984763,50.6843,3.170286872,9.486746949,2.768125,6.669422338,-3.399040263,71.54849497 +84.63,50.42535216,-2.583983428,50.6565,3.170286858,9.486746851,2.79625,6.568483274,-3.383981615,71.54096991 +84.64,50.42535245,-2.583982093,50.6284,3.170286851,9.486524684,2.8234375,6.467216651,-3.365972061,71.5334448 +84.65,50.42535273,-2.583980758,50.6,3.170286843,9.485636313,2.8496875,6.36564361,-3.34502736,71.52591974 +84.66,50.42535302,-2.583979423,50.5714,3.170286823,9.484303805,2.8746875,6.26378535,-3.321165673,71.51839463 +84.67,50.4253533,-2.583978089,50.5425,3.170286802,9.483193365,2.898125,6.161663186,-3.294407971,71.51086957 +84.68,50.42535359,-2.583976754,50.5134,3.17028679,9.482304993,2.92,6.059298432,-3.264777459,71.50334446 +84.69,50.42535387,-2.58397542,50.4841,3.17028678,9.481860756,2.9415625,5.956712401,-3.232299976,71.4958194 +84.7,50.42535416,-2.583974086,50.4546,3.17028677,9.482304792,2.963125,5.853926638,-3.197003943,71.48829429 +84.71,50.42535444,-2.583972751,50.4248,3.170286753,9.482970895,2.9828125,5.750962512,-3.158920011,71.48076923 +84.72,50.42535473,-2.583971417,50.3949,3.173762921,9.482970794,2.9996875,5.647841568,-3.11808147,71.47324412 +84.73,50.42535501,-2.583970082,50.3648,3.18419148,9.48208242,3.015,5.544585349,-3.074523958,71.46571907 +84.74,50.4253553,-2.583968748,50.3346,3.191143851,9.48074991,3.03,5.44121534,-3.028285347,71.45819395 +84.75,50.42535559,-2.583967414,50.3042,3.184191452,9.479861535,3.0446875,5.337753257,-2.979406089,71.4506689 +84.76,50.42535587,-2.58396608,50.2737,3.173762868,9.479639365,3.0578125,5.234220586,-2.927928753,71.44314384 +84.77,50.42535616,-2.583964746,50.243,3.17376286,9.479639263,3.0684375,5.130639041,-2.873898145,71.43561873 +84.78,50.42535644,-2.583963412,50.2123,3.184191413,9.47963916,3.0778125,5.027030224,-2.817361535,71.42809367 +84.79,50.42535673,-2.583962078,50.1815,3.191143775,9.479416989,3.086875,4.923415734,-2.758368081,71.42056856 +84.8,50.42535702,-2.583960744,50.1505,3.187667568,9.478528614,3.094375,4.81981723,-2.696969294,71.4130435 +84.81,50.4253573,-2.58395941,50.1196,3.187667551,9.477418171,3.0996875,4.716256369,-2.633218744,71.40551839 +84.82,50.42535759,-2.583958077,50.0885,3.191143729,9.477195999,3.1034375,4.612754751,-2.567172008,71.39799333 +84.83,50.42535788,-2.583956743,50.0575,3.187667531,9.477417964,3.10625,4.509333979,-2.498886611,71.39046822 +84.84,50.42535816,-2.583955409,50.0264,3.187667518,9.476973725,3.1084375,4.406015708,-2.428422142,71.38294317 +84.85,50.42535845,-2.583954076,49.9953,3.19114369,9.476307417,3.109375,4.302821483,-2.355840077,71.37541805 +84.86,50.42535874,-2.583952742,49.9642,3.187667478,9.476085246,3.1084375,4.199772903,-2.281203673,71.367893 +84.87,50.42535902,-2.583951409,49.9331,3.19114365,9.475863075,3.10625,4.096891398,-2.204578074,71.36036788 +84.88,50.42535931,-2.583950075,49.9021,3.208524593,9.475196768,3.103125,3.994198454,-2.126029972,71.35284283 +84.89,50.4253596,-2.583948742,49.871,3.218953157,9.474752529,3.098125,3.891715613,-2.045628007,71.34531771 +84.9,50.42535989,-2.583947409,49.8401,3.208524571,9.474974493,3.09125,3.78946419,-1.963442196,71.33779266 +84.91,50.42536018,-2.583946075,49.8092,3.191143602,9.474752321,3.0834375,3.687465613,-1.879544216,71.33026755 +84.92,50.42536046,-2.583944742,49.7784,3.191143584,9.473641878,3.0746875,3.585741082,-1.794007289,71.32274249 +84.93,50.42536075,-2.583943409,49.7477,3.208524516,9.472753504,3.0646875,3.484311968,-1.706905901,71.31521738 +84.94,50.42536104,-2.583942076,49.7171,3.218953067,9.472531333,3.053125,3.383199355,-1.618316141,71.30769232 +84.95,50.42536133,-2.583940743,49.6866,3.208524477,9.472309162,3.04,3.282424387,-1.528315128,71.30016721 +84.96,50.42536162,-2.58393941,49.6563,3.191143511,9.471420788,3.02625,3.18200809,-1.436981416,71.29264215 +84.97,50.4253619,-2.583938077,49.6261,3.1911435,9.470310346,3.0115625,3.081971493,-1.344394645,71.28511704 +84.98,50.42536219,-2.583936745,49.596,3.208524443,9.470088176,2.9946875,2.98233545,-1.250635545,71.27759198 +84.99,50.42536248,-2.583935412,49.5662,3.222429201,9.470310142,2.9765625,2.88312076,-1.15578582,71.27006687 +85,50.42536277,-2.583934079,49.5365,3.225905384,9.469865905,2.958125,2.784348165,-1.059928319,71.26254181 +85.01,50.42536306,-2.583932747,49.507,3.225905363,9.4691996,2.9378125,2.686038233,-0.963146465,71.2550167 +85.02,50.42536335,-2.583931414,49.4777,3.225905341,9.46897743,2.915,2.588211591,-0.86552477,71.24749165 +85.03,50.42536364,-2.583930082,49.4487,3.222429135,9.46897733,2.8915625,2.490888636,-0.767148318,71.23996653 +85.04,50.42536393,-2.583928749,49.4199,3.208524353,9.46897723,2.868125,2.394089651,-0.668102937,71.23244148 +85.05,50.42536422,-2.583927417,49.3913,3.191143384,9.468755062,2.8428125,2.297834861,-0.568474916,71.22491636 +85.06,50.4253645,-2.583926084,49.363,3.191143379,9.46786669,2.815,2.202144378,-0.468351172,71.21739131 +85.07,50.42536479,-2.583924752,49.335,3.208524322,9.466534184,2.7865625,2.107038197,-0.367819023,71.20986619 +85.08,50.42536508,-2.58392342,49.3073,3.222429063,9.465645814,2.758125,2.0125362,-0.266966132,71.20234114 +85.09,50.42536537,-2.583922088,49.2798,3.225905234,9.465423648,2.728125,1.918658096,-0.165880449,71.19481603 +85.1,50.42536566,-2.583920756,49.2527,3.225905224,9.46542355,2.69625,1.825423482,-0.064650151,71.18729097 +85.11,50.42536595,-2.583919424,49.2259,3.225905215,9.465423452,2.6634375,1.732851837,0.036636583,71.17976591 +85.12,50.42536624,-2.583918092,49.1994,3.225905202,9.465423354,2.6296875,1.64096247,0.137891289,71.1722408 +85.13,50.42536653,-2.58391676,49.1733,3.225905196,9.46520119,2.5946875,1.549774632,0.239025845,71.16471575 +85.14,50.42536682,-2.583915428,49.1475,3.229381381,9.464312823,2.558125,1.459307347,0.339951903,71.15719063 +85.15,50.42536711,-2.583914096,49.1221,3.243286124,9.46298032,2.52,1.369579406,0.440581569,71.14966558 +85.16,50.4253674,-2.583912765,49.0971,3.260667055,9.462091953,2.4815625,1.280609717,0.54082701,71.14214046 +85.17,50.4253677,-2.583911433,49.0725,3.26066704,9.46186979,2.443125,1.19241673,0.640600849,71.13461541 +85.18,50.42536799,-2.583910102,49.0482,3.243286079,9.461869696,2.403125,1.105018951,0.739816054,71.12709029 +85.19,50.42536828,-2.58390877,49.0244,3.229381306,9.462091671,2.36125,1.018434543,0.838386109,71.11956524 +85.2,50.42536857,-2.583907439,49.001,3.225905099,9.462757782,2.3184375,0.932681612,0.936225127,71.11204013 +85.21,50.42536886,-2.583906107,48.978,3.225905081,9.462979757,2.275,0.847778147,1.033247737,71.10451507 +85.22,50.42536915,-2.583904775,48.9555,3.225905069,9.461647259,2.23125,0.763741797,1.129369314,71.09698996 +85.23,50.42536944,-2.583903444,48.9334,3.229381258,9.459648558,2.1865625,0.680590151,1.224506091,71.0894649 +85.24,50.42536973,-2.583902113,48.9117,3.243286023,9.458760196,2.1396875,0.598340513,1.318575104,71.08193979 +85.25,50.42537002,-2.583900782,48.8906,3.260666968,9.45942631,2.091875,0.517010128,1.411494248,71.07441473 +85.26,50.42537032,-2.583899451,48.8699,3.260666947,9.460536561,2.045,0.436616013,1.503182564,71.06688962 +85.27,50.42537061,-2.583898119,48.8497,3.243285975,9.460314405,1.9978125,0.357174842,1.593560067,71.05936456 +85.28,50.4253709,-2.583896788,48.8299,3.232857396,9.458315706,1.9478125,0.278703287,1.682548033,71.05183945 +85.29,50.42537119,-2.583895457,48.8107,3.243285964,9.456317009,1.895,0.201217678,1.770068711,71.04431439 +85.3,50.42537148,-2.583894127,48.792,3.260666906,9.455872787,1.841875,0.124734287,1.856045899,71.03678928 +85.31,50.42537178,-2.583892796,48.7739,3.26066689,9.45609477,1.79,0.049268985,1.940404595,71.02926423 +85.32,50.42537207,-2.583891465,48.7562,3.246762117,9.455872619,1.738125,-0.025162416,2.023071175,71.02173911 +85.33,50.42537236,-2.583890135,48.7391,3.246762115,9.455872535,1.6846875,-0.098544329,2.103973675,71.01421406 +85.34,50.42537265,-2.583888804,48.7225,3.260666877,9.456094519,1.63,-0.170861515,2.183041449,71.00668894 +85.35,50.42537295,-2.583887473,48.7065,3.260666872,9.455650301,1.5746875,-0.24209879,2.260205572,70.99916389 +85.36,50.42537324,-2.583886143,48.691,3.246762097,9.454761948,1.5184375,-0.312241372,2.335398777,70.99163877 +85.37,50.42537353,-2.583884812,48.6761,3.246762085,9.453873597,1.4615625,-0.381274536,2.40855546,70.98411372 +85.38,50.42537382,-2.583883482,48.6618,3.260666842,9.453429382,1.405,-0.4491839,2.479611853,70.97658861 +85.39,50.42537412,-2.583882152,48.648,3.264143029,9.453651371,1.348125,-0.515955255,2.548506017,70.96906355 +85.4,50.42537441,-2.583880821,48.6348,3.260666827,9.453429226,1.2896875,-0.581574679,2.615177792,70.96153844 +85.41,50.4253747,-2.583879491,48.6222,3.264143005,9.45231881,1.23,-0.646028478,2.679569138,70.95401338 +85.42,50.425375,-2.583878161,48.6102,3.264142997,9.451430462,1.17,-0.709303187,2.741623848,70.94648827 +85.43,50.42537529,-2.583876831,48.5988,3.2606668,9.451208319,1.1096875,-0.77138557,2.801287834,70.93896321 +85.44,50.42537558,-2.583875501,48.588,3.267619179,9.451208244,1.0484375,-0.832262622,2.858509014,70.9314381 +85.45,50.42537588,-2.583874171,48.5778,3.278047753,9.451208171,0.986875,-0.891921738,2.913237599,70.92391304 +85.46,50.42537617,-2.583872841,48.5683,3.278047753,9.45098603,0.9265625,-0.95035037,2.965425747,70.91638799 +85.47,50.42537647,-2.583871511,48.5593,3.267619174,9.450097686,0.8665625,-1.007536371,3.015028021,70.90886287 +85.48,50.42537676,-2.583870181,48.5509,3.260666787,9.448987276,0.804375,-1.063467766,3.062001106,70.90133782 +85.49,50.42537705,-2.583868852,48.5432,3.267619168,9.448765139,0.7403125,-1.118132924,3.106304094,70.89381271 +85.5,50.42537735,-2.583867522,48.5361,3.278047733,9.448987138,0.676875,-1.171520329,3.147898366,70.88628765 +85.51,50.42537764,-2.583866192,48.5297,3.281523916,9.448542933,0.615,-1.223618923,3.186747597,70.87876254 +85.52,50.42537794,-2.583864863,48.5238,3.281523918,9.447876662,0.553125,-1.274417762,3.222817983,70.87123748 +85.53,50.42537823,-2.583863533,48.5186,3.28152392,9.447654529,0.4896875,-1.323906304,3.256077954,70.86371237 +85.54,50.42537853,-2.583862204,48.514,3.281523913,9.447432396,0.425,-1.372074179,3.286498633,70.85618731 +85.55,50.42537882,-2.583860874,48.5101,3.281523905,9.446544059,0.36,-1.418911301,3.314053433,70.8486622 +85.56,50.42537912,-2.583859545,48.5068,3.281523901,9.445433656,0.2953125,-1.464407932,3.338718292,70.84113714 +85.57,50.42537941,-2.583858216,48.5042,3.2815239,9.445211526,0.2315625,-1.508554559,3.360471781,70.83361203 +85.58,50.42537971,-2.583856887,48.5022,3.281523901,9.445433533,0.168125,-1.551341958,3.379294877,70.82608697 +85.59,50.42538,-2.583855557,48.5008,3.281523907,9.444989336,0.1034375,-1.592761135,3.395171136,70.81856186 +85.6,50.4253803,-2.583854229,48.5001,3.281523914,9.444323073,0.0384375,-1.632803551,3.408086808,70.81103681 +85.61,50.42538059,-2.583852899,48.5001,3.281523916,9.444100946,-0.025,-1.671460784,3.418030548,70.80351169 +85.62,50.42538089,-2.583851571,48.5006,3.285000105,9.44387882,-0.0884375,-1.708724813,3.424993704,70.79598664 +85.63,50.42538118,-2.583850241,48.5018,3.295428672,9.44321256,-0.15375,-1.744587731,3.428970261,70.78846152 +85.64,50.42538148,-2.583848913,48.5037,3.302381048,9.4425463,-0.2196875,-1.779042204,3.429956665,70.78093647 +85.65,50.42538178,-2.583847584,48.5062,3.295428666,9.44210211,-0.2846875,-1.812080899,3.427952115,70.77341135 +85.66,50.42538207,-2.583846255,48.5094,3.285000095,9.44165792,-0.3484375,-1.843696997,3.422958329,70.7658863 +85.67,50.42538237,-2.583844927,48.5132,3.285000097,9.441657867,-0.4115625,-1.873883908,3.414979663,70.75836119 +85.68,50.42538266,-2.583843598,48.5176,3.295428672,9.441879882,-0.475,-1.902635274,3.404023105,70.75083613 +85.69,50.42538296,-2.583842269,48.5227,3.302381059,9.441435695,-0.5384375,-1.929945078,3.390098168,70.74331102 +85.7,50.42538326,-2.583840941,48.5284,3.298904878,9.440547373,-0.6015625,-1.955807706,3.373217055,70.73578596 +85.71,50.42538355,-2.583839612,48.5347,3.302381077,9.439659052,-0.665,-1.980217656,3.353394434,70.72826085 +85.72,50.42538385,-2.583838284,48.5417,3.31628584,9.439214868,-0.728125,-2.003169887,3.330647552,70.72073579 +85.73,50.42538415,-2.583836956,48.5493,3.316285837,9.439436888,-0.79,-2.024659643,3.304996346,70.71321068 +85.74,50.42538445,-2.583835627,48.5575,3.302381076,9.438992705,-0.8515625,-2.044682341,3.276463105,70.70568562 +85.75,50.42538474,-2.583834299,48.5663,3.29890489,9.436994048,-0.9134375,-2.063233855,3.245072753,70.69816051 +85.76,50.42538504,-2.583832971,48.5758,3.302381086,9.435217461,-0.975,-2.080310346,3.210852676,70.69063545 +85.77,50.42538534,-2.583831644,48.5858,3.2989049,9.435661553,-1.0365625,-2.095908148,3.17383267,70.68311034 +85.78,50.42538563,-2.583830316,48.5965,3.302381097,9.436993916,-1.098125,-2.110024052,3.134045048,70.67558529 +85.79,50.42538593,-2.583828987,48.6078,3.319762058,9.436771806,-1.158125,-2.122655193,3.091524475,70.66806017 +85.8,50.42538623,-2.58382766,48.6197,3.330190639,9.435661425,-1.2165625,-2.133798764,3.046308021,70.66053512 +85.81,50.42538653,-2.583826332,48.6321,3.31976208,9.434995181,-1.275,-2.143452587,2.998435163,70.65301006 +85.82,50.42538683,-2.583825004,48.6452,3.302381136,9.434328937,-1.3334375,-2.1516146,2.947947612,70.64548495 +85.83,50.42538712,-2.583823677,48.6588,3.302381139,9.433662694,-1.3915625,-2.158283084,2.894889428,70.63795989 +85.84,50.42538742,-2.583822349,48.673,3.319762095,9.433440588,-1.45,-2.163456663,2.83930685,70.63043478 +85.85,50.42538772,-2.583821022,48.6878,3.330190674,9.433440551,-1.5078125,-2.167134193,2.781248349,70.62290972 +85.86,50.42538802,-2.583819694,48.7032,3.319762109,9.433440515,-1.563125,-2.169314985,2.720764575,70.61538461 +85.87,50.42538832,-2.583818367,48.7191,3.302381162,9.433218411,-1.616875,-2.169998581,2.65790824,70.60785955 +85.88,50.42538861,-2.583817039,48.7355,3.30238117,9.432330105,-1.6715625,-2.169184809,2.592734176,70.60033444 +85.89,50.42538891,-2.583815712,48.7525,3.319762137,9.430997664,-1.7265625,-2.166873841,2.525299221,70.59280938 +85.9,50.42538921,-2.583814385,48.7701,3.333666917,9.430331427,-1.7796875,-2.163066135,2.45566216,70.58528427 +85.91,50.42538951,-2.583813058,48.7881,3.337143123,9.430997598,-1.8315625,-2.157762552,2.383883669,70.57775922 +85.92,50.42538981,-2.583811731,48.8067,3.337143128,9.432107905,-1.8834375,-2.150964121,2.310026487,70.5702341 +85.93,50.42539011,-2.583810403,48.8258,3.337143132,9.431885806,-1.9346875,-2.142672333,2.234154842,70.56270905 +85.94,50.42539041,-2.583809076,48.8454,3.33714314,9.429887165,-1.985,-2.132888907,2.156335027,70.55518393 +85.95,50.42539071,-2.583807749,48.8655,3.33714315,9.427888525,-2.0346875,-2.121615847,2.076634879,70.54765888 +85.96,50.42539101,-2.583806423,48.8861,3.337143161,9.427666427,-2.083125,-2.108855504,1.99512384,70.54013377 +85.97,50.42539131,-2.583805096,48.9072,3.337143173,9.428776738,-2.13,-2.09461057,1.911873015,70.53260871 +85.98,50.42539161,-2.583803769,48.9287,3.337143184,9.429442913,-2.1765625,-2.078884082,1.826955055,70.5250836 +85.99,50.42539191,-2.583802442,48.9507,3.337143196,9.428554615,-2.223125,-2.061679191,1.740443929,70.51755854 +86,50.42539221,-2.583801115,48.9732,3.337143208,9.426555979,-2.2678125,-2.042999564,1.652415094,70.51003343 +86.01,50.42539251,-2.583799789,48.9961,3.33714322,9.425223546,-2.31,-2.022849154,1.562945328,70.50250837 +86.02,50.42539281,-2.583798463,49.0194,3.337143232,9.425445589,-2.351875,-2.001232086,1.472112724,70.49498326 +86.03,50.42539311,-2.583797136,49.0431,3.337143245,9.426111767,-2.3946875,-1.978152888,1.379996352,70.4874582 +86.04,50.42539341,-2.58379581,49.0673,3.337143258,9.426111743,-2.43625,-1.953616371,1.286676596,70.47993309 +86.05,50.42539371,-2.583794483,49.0919,3.337143271,9.425223449,-2.4746875,-1.927627693,1.192234874,70.47240803 +86.06,50.42539401,-2.583793157,49.1168,3.337143284,9.42389102,-2.511875,-1.900192297,1.096753462,70.46488292 +86.07,50.42539431,-2.583791831,49.1421,3.337143297,9.423002726,-2.55,-1.871315854,1.00031567,70.45735786 +86.08,50.42539461,-2.583790505,49.1678,3.337143311,9.422780637,-2.5878125,-1.841004439,0.903005607,70.44983275 +86.09,50.42539491,-2.583789179,49.1939,3.337143325,9.422780616,-2.623125,-1.809264353,0.804908127,70.4423077 +86.1,50.42539521,-2.583787853,49.2203,3.337143339,9.422780595,-2.65625,-1.776102243,0.706108775,70.43478258 +86.11,50.42539551,-2.583786527,49.247,3.340619544,9.422780575,-2.6884375,-1.741525043,0.606693607,70.42725753 +86.12,50.42539581,-2.583785201,49.2741,3.354524324,9.422780555,-2.72,-1.70553997,0.506749428,70.41973241 +86.13,50.42539611,-2.583783875,49.3014,3.371905296,9.422558467,-2.75125,-1.668154531,0.406363383,70.41220736 +86.14,50.42539642,-2.583782549,49.3291,3.37190531,9.421670177,-2.7815625,-1.629376518,0.305622964,70.4046823 +86.15,50.42539672,-2.583781223,49.3571,3.354524368,9.420337751,-2.8096875,-1.58921401,0.204616063,70.39715719 +86.16,50.42539702,-2.583779898,49.3853,3.340619618,9.419449462,-2.8365625,-1.547675487,0.103430685,70.38963213 +86.17,50.42539732,-2.583778572,49.4138,3.340619633,9.419227377,-2.863125,-1.504769542,0.002155123,70.38210702 +86.18,50.42539762,-2.583777247,49.4426,3.354524414,9.419005292,-2.8878125,-1.460505172,-0.099122272,70.37458196 +86.19,50.42539792,-2.583775921,49.4716,3.371905387,9.418117003,-2.9096875,-1.414891601,-0.200313264,70.36705685 +86.2,50.42539823,-2.583774596,49.5008,3.371905402,9.417006647,-2.9303125,-1.36793834,-0.30132962,70.3595318 +86.21,50.42539853,-2.583773271,49.5302,3.358000652,9.41700663,-2.9515625,-1.319655244,-0.402083159,70.35200668 +86.22,50.42539883,-2.583771946,49.5598,3.358000668,9.417894886,-2.9728125,-1.27005234,-0.502486106,70.34448163 +86.23,50.42539913,-2.58377062,49.5897,3.37190545,9.41789487,-2.99125,-1.219140055,-0.602450855,70.33695651 +86.24,50.42539944,-2.583769295,49.6197,3.371905466,9.416784515,-3.0065625,-1.166928932,-0.701890259,70.32943146 +86.25,50.42539974,-2.58376797,49.6498,3.358000716,9.415896229,-3.021875,-1.113429972,-0.800717571,70.32190635 +86.26,50.42540004,-2.583766645,49.6801,3.35800073,9.415674145,-3.038125,-1.05865429,-0.898846735,70.31438129 +86.27,50.42540034,-2.58376532,49.7106,3.371905506,9.415452062,-3.0528125,-1.002613345,-0.996192035,70.30685618 +86.28,50.42540065,-2.583763995,49.7412,3.375381709,9.414563775,-3.064375,-0.945318826,-1.092668617,70.29933112 +86.29,50.42540095,-2.58376267,49.7719,3.371905538,9.413453422,-3.0734375,-0.88678265,-1.188192427,70.29180601 +86.3,50.42540125,-2.583761346,49.8027,3.375381753,9.413231339,-3.0815625,-0.827017136,-1.2826801,70.28428095 +86.31,50.42540156,-2.583760021,49.8335,3.375381772,9.413453393,-3.0896875,-0.766034775,-1.376049245,70.27675584 +86.32,50.42540186,-2.583758696,49.8645,3.371905597,9.413009242,-3.0965625,-0.70384817,-1.468218445,70.26923078 +86.33,50.42540216,-2.583757372,49.8955,3.378857997,9.412343024,-3.10125,-0.640470443,-1.55910737,70.26170567 +86.34,50.42540247,-2.583756047,49.9265,3.389286589,9.412120942,-3.105,-0.575914716,-1.648636667,70.25418061 +86.35,50.42540277,-2.583754723,49.9576,3.389286605,9.41189886,-3.108125,-0.510194623,-1.736728412,70.2466555 +86.36,50.42540308,-2.583753398,49.9887,3.378858047,9.411232642,-3.1096875,-0.443323745,-1.823305658,70.23913044 +86.37,50.42540338,-2.583752074,50.0198,3.37190568,9.410788492,-3.1096875,-0.375316061,-1.908292946,70.23160533 +86.38,50.42540368,-2.58375075,50.0509,3.37885808,9.411010545,-3.108125,-0.306185838,-1.991616193,70.22408028 +86.39,50.42540399,-2.583749425,50.082,3.389286668,9.410788464,-3.1046875,-0.235947515,-2.07320269,70.21655516 +86.4,50.42540429,-2.583748101,50.113,3.392762863,9.409456042,-3.1,-0.164615702,-2.152981391,70.20903011 +86.41,50.4254046,-2.583746777,50.144,3.392762871,9.407901552,-3.0946875,-0.092205353,-2.230882623,70.20150499 +86.42,50.4254049,-2.583745453,50.1749,3.392762896,9.407235334,-3.088125,-0.018731537,-2.306838435,70.19397994 +86.43,50.42540521,-2.58374413,50.2058,3.392762926,9.407457387,-3.0796875,0.05579039,-2.380782706,70.18645483 +86.44,50.42540551,-2.583742805,50.2365,3.392762947,9.407457372,-3.0696875,0.131344845,-2.452650923,70.17892977 +86.45,50.42540582,-2.583741482,50.2672,3.392762964,9.407013221,-3.0584375,0.207916013,-2.522380345,70.17140466 +86.46,50.42540612,-2.583740158,50.2977,3.39276298,9.40656907,-3.04625,0.285487967,-2.589910239,70.1638796 +86.47,50.42540643,-2.583738834,50.3281,3.392762996,9.405902851,-3.0334375,0.364044491,-2.655181706,70.15635449 +86.48,50.42540673,-2.583737511,50.3584,3.39276301,9.405236631,-3.0196875,0.4435692,-2.718137792,70.14882943 +86.49,50.42540704,-2.583736187,50.3885,3.39276302,9.405014547,-3.004375,0.524045419,-2.77872361,70.14130438 +86.5,50.42540734,-2.583734864,50.4185,3.392763032,9.405014531,-2.9865625,0.60545642,-2.836886389,70.13377926 +86.51,50.42540765,-2.58373354,50.4483,3.392763052,9.405014515,-2.9665625,0.687785184,-2.892575309,70.12625421 +86.52,50.42540795,-2.583732217,50.4778,3.392763075,9.40479243,-2.9465625,0.771014465,-2.945741896,70.11872909 +86.53,50.42540826,-2.583730893,50.5072,3.396239285,9.403904142,-2.9265625,0.855126904,-2.996339742,70.11120404 +86.54,50.42540856,-2.58372957,50.5364,3.406667877,9.402571717,-2.904375,0.940104968,-3.044324728,70.10367892 +86.55,50.42540887,-2.583728247,50.5653,3.413620277,9.401683428,-2.88,1.025930837,-3.089654971,70.09615387 +86.56,50.42540918,-2.583726924,50.594,3.4101441,9.401461342,-2.855,1.112586693,-3.132291053,70.08862876 +86.57,50.42540948,-2.583725601,50.6224,3.410144113,9.401461323,-2.8296875,1.200054372,-3.17219573,70.0811037 +86.58,50.42540979,-2.583724278,50.6506,3.413620314,9.401461304,-2.8028125,1.288315656,-3.209334166,70.07357859 +86.59,50.4254101,-2.583722955,50.6785,3.410144132,9.401461284,-2.773125,1.377352037,-3.243674048,70.06605353 +86.6,50.4254104,-2.583721632,50.7061,3.410144152,9.401461264,-2.741875,1.467144951,-3.275185409,70.05852842 +86.61,50.42541071,-2.583720309,50.7333,3.413620365,9.401239176,-2.7115625,1.557675663,-3.30384069,70.05100336 +86.62,50.42541102,-2.583718986,50.7603,3.410144186,9.400350883,-2.68125,1.648925323,-3.329615024,70.04347825 +86.63,50.42541132,-2.583717663,50.787,3.410144187,9.399018455,-2.6478125,1.740874736,-3.352485895,70.03595319 +86.64,50.42541163,-2.583716341,50.8133,3.413620384,9.398130162,-2.6115625,1.833504822,-3.372433364,70.02842808 +86.65,50.42541194,-2.583715018,50.8392,3.410144215,9.397908071,-2.5753125,1.92679616,-3.389439954,70.02090302 +86.66,50.42541224,-2.583713696,50.8648,3.413620435,9.397685981,-2.5396875,2.020729324,-3.403490942,70.01337791 +86.67,50.42541255,-2.583712373,50.89,3.427525222,9.397019754,-2.503125,2.115284606,-3.414574066,70.00585286 +86.68,50.42541286,-2.583711051,50.9149,3.427525235,9.396575594,-2.4646875,2.210442411,-3.422679585,69.99832774 +86.69,50.42541317,-2.583709729,50.9393,3.413620477,9.396797637,-2.4246875,2.306182742,-3.42780051,69.99080269 +86.7,50.42541347,-2.583708406,50.9634,3.413620484,9.396575544,-2.3834375,2.402485603,-3.429932314,69.98327757 +86.71,50.42541378,-2.583707084,50.987,3.431001454,9.395465179,-2.34125,2.499330997,-3.429073164,69.97575252 +86.72,50.42541409,-2.583705762,51.0102,3.441430048,9.39457688,-2.2984375,2.596698586,-3.425223804,69.9682274 +86.73,50.4254144,-2.58370444,51.033,3.43100149,9.394354785,-2.2546875,2.694568028,-3.418387616,69.96070235 +86.74,50.42541471,-2.583703118,51.0553,3.413620542,9.394354757,-2.2096875,2.792918983,-3.408570557,69.95317724 +86.75,50.42541501,-2.583701796,51.0772,3.413620554,9.39413266,-2.1634375,2.891730884,-3.395781165,69.94565218 +86.76,50.42541532,-2.583700474,51.0986,3.431001526,9.39324436,-2.1165625,2.990983045,-3.380030555,69.93812707 +86.77,50.42541563,-2.583699152,51.1195,3.444906298,9.391911923,-2.0696875,3.090654725,-3.361332593,69.93060201 +86.78,50.42541594,-2.583697831,51.14,3.44838249,9.39102362,-2.0215625,3.190725185,-3.339703436,69.9230769 +86.79,50.42541625,-2.583696509,51.16,3.444906309,9.391023588,-1.97125,3.291173452,-3.315161992,69.91555184 +86.8,50.42541656,-2.583695188,51.1794,3.431001561,9.39168976,-1.9203125,3.391978616,-3.287729747,69.90802673 +86.81,50.42541687,-2.583693866,51.1984,3.413620616,9.392133863,-1.87,3.493119647,-3.257430478,69.90050167 +86.82,50.42541717,-2.583692544,51.2168,3.413620622,9.391689693,-1.819375,3.594575289,-3.224290771,69.89297656 +86.83,50.42541748,-2.583691223,51.2348,3.431001589,9.390801387,-1.7665625,3.696324457,-3.188339388,69.8854515 +86.84,50.42541779,-2.583689901,51.2522,3.444906373,9.389691013,-1.7115625,3.798345895,-3.149607671,69.87792645 +86.85,50.4254181,-2.58368858,51.269,3.448382581,9.388580638,-1.656875,3.900618289,-3.108129537,69.87040134 +86.86,50.42541841,-2.583687259,51.2853,3.44838259,9.388358533,-1.603125,4.003120266,-3.063941027,69.86287628 +86.87,50.42541872,-2.583685938,51.3011,3.448382592,9.388358495,-1.548125,4.1058304,-3.017080699,69.85535117 +86.88,50.42541903,-2.583684616,51.3163,3.448382594,9.387248117,-1.49125,4.208727317,-2.967589464,69.84782611 +86.89,50.42541934,-2.583683296,51.3309,3.448382598,9.386137738,-1.4334375,4.311789475,-2.915510408,69.840301 +86.9,50.42541965,-2.583681975,51.345,3.448382601,9.386359765,-1.375,4.414995332,-2.860889024,69.83277594 +86.91,50.42541996,-2.583680654,51.3584,3.448382611,9.387025927,-1.316875,4.518323343,-2.803772867,69.82525083 +86.92,50.42542027,-2.583679333,51.3713,3.448382629,9.387025885,-1.26,4.621751965,-2.744211841,69.81772577 +86.93,50.42542058,-2.583678012,51.3836,3.448382645,9.386137571,-1.2028125,4.725259598,-2.682257743,69.81020066 +86.94,50.42542089,-2.583676691,51.3954,3.448382651,9.385027188,-1.143125,4.828824584,-2.617964716,69.8026756 +86.95,50.4254212,-2.583675371,51.4065,3.448382651,9.384805075,-1.0815625,4.932425323,-2.551388797,69.79515049 +86.96,50.42542151,-2.58367405,51.417,3.448382652,9.384805029,-1.02,5.036040214,-2.482588025,69.78762544 +86.97,50.42542182,-2.583672729,51.4269,3.448382662,9.383694644,-0.9584375,5.139647542,-2.411622389,69.78010032 +86.98,50.42542213,-2.583671409,51.4362,3.451858867,9.382584258,-0.8965625,5.243225706,-2.338553769,69.77257527 +86.99,50.42542244,-2.583670089,51.4448,3.46576364,9.382584208,-0.835,5.346753049,-2.263445877,69.76505015 +87,50.42542275,-2.583668768,51.4529,3.483144594,9.382362091,-0.7734375,5.450208028,-2.186364261,69.7575251 +87.01,50.42542307,-2.583667448,51.4603,3.483144589,9.381473769,-0.71125,5.553568984,-2.107376127,69.74999998 +87.02,50.42542338,-2.583666128,51.4671,3.465763637,9.381473718,-0.6484375,5.656814317,-2.026550289,69.74247493 +87.03,50.42542369,-2.583664808,51.4733,3.451858877,9.382139869,-0.5846875,5.759922484,-1.943957277,69.73494982 +87.04,50.425424,-2.583663487,51.4788,3.448382687,9.381251544,-0.5203125,5.862871941,-1.859669112,69.72742476 +87.05,50.42542431,-2.583662167,51.4837,3.451858887,9.379030813,-0.4565625,5.965641204,-1.773759304,69.71989965 +87.06,50.42542462,-2.583660848,51.4879,3.465763667,9.378142486,-0.3934375,6.068208785,-1.68630274,69.71237459 +87.07,50.42542493,-2.583659528,51.4916,3.483144632,9.378808633,-0.3296875,6.170553314,-1.59737568,69.70484948 +87.08,50.42542525,-2.583658208,51.4945,3.483144627,9.378808576,-0.265,6.272653362,-1.507055701,69.69732442 +87.09,50.42542556,-2.583656888,51.4969,3.465763661,9.377920247,-0.2003125,6.374487672,-1.41542153,69.68979931 +87.1,50.42542587,-2.583655569,51.4985,3.455335084,9.377920188,-0.1365625,6.47603493,-1.322553093,69.68227425 +87.11,50.42542618,-2.583654249,51.4996,3.465763656,9.378808399,-0.0734375,6.577273879,-1.228531349,69.67474914 +87.12,50.42542649,-2.583652929,51.5,3.483144613,9.378586269,-0.009375,6.678183493,-1.133438346,69.66722408 +87.13,50.42542681,-2.583651609,51.4998,3.486620812,9.376809665,0.05625,6.778742628,-1.03735699,69.65969897 +87.14,50.42542712,-2.58365029,51.4989,3.483144626,9.375477196,0.121875,6.878930314,-0.940370992,69.65217392 +87.15,50.42542743,-2.583648971,51.4973,3.486620818,9.375477132,0.18625,6.978725582,-0.842564976,69.6446488 +87.16,50.42542775,-2.583647651,51.4952,3.483144629,9.375255,0.25,7.078107633,-0.744024257,69.63712375 +87.17,50.42542806,-2.583646332,51.4923,3.469239864,9.374144595,0.31375,7.177055668,-0.64483472,69.62959863 +87.18,50.42542837,-2.583645013,51.4889,3.469239862,9.373256257,0.3778125,7.275549061,-0.545082883,69.62207358 +87.19,50.42542868,-2.583643694,51.4848,3.483144622,9.373034122,0.4421875,7.373567243,-0.444855777,69.61454852 +87.2,50.425429,-2.583642375,51.48,3.486620801,9.373034054,0.50625,7.471089759,-0.344240664,69.60702341 +87.21,50.42542931,-2.583641056,51.4747,3.483144603,9.373033984,0.57,7.568096212,-0.243325435,69.59949835 +87.22,50.42542962,-2.583639737,51.4686,3.49009699,9.373033913,0.6334375,7.664566319,-0.142197983,69.59197324 +87.23,50.42542994,-2.583638418,51.462,3.500525568,9.372811773,0.69625,7.760480027,-0.040946543,69.58444818 +87.24,50.42543025,-2.583637099,51.4547,3.500525569,9.37192343,0.7584375,7.855817167,0.060340592,69.57692307 +87.25,50.42543057,-2.58363578,51.4468,3.490096987,9.37059095,0.82,7.950557973,0.16157513,69.56939802 +87.26,50.42543088,-2.583634462,51.4383,3.483144593,9.369702605,0.8815625,8.044682563,0.262668777,69.5618729 +87.27,50.42543119,-2.583633143,51.4292,3.490096969,9.369480462,0.9434375,8.138171284,0.363533356,69.55434785 +87.28,50.42543151,-2.583631825,51.4194,3.500525537,9.369258318,1.005,8.231004656,0.464080917,69.54682273 +87.29,50.42543182,-2.583630506,51.4091,3.500525534,9.368592038,1.06625,8.323163313,0.564223798,69.53929768 +87.3,50.42543214,-2.583629188,51.3981,3.490096959,9.368147824,1.126875,8.414627947,0.663874681,69.53177256 +87.31,50.42543245,-2.58362787,51.3865,3.48314457,9.368369813,1.18625,8.505379419,0.762946647,69.52424751 +87.32,50.42543276,-2.583626551,51.3744,3.490096947,9.368147666,1.245,8.595398939,0.861353294,69.5167224 +87.33,50.42543308,-2.583625233,51.3616,3.500525517,9.367037247,1.3034375,8.684667539,0.959008851,69.50919734 +87.34,50.42543339,-2.583623915,51.3483,3.504001696,9.366370961,1.3615625,8.773166658,1.055828176,69.50167223 +87.35,50.42543371,-2.583622597,51.3344,3.504001682,9.366815014,1.42,8.860877787,1.151726757,69.49414717 +87.36,50.42543402,-2.583621279,51.3199,3.504001681,9.367036999,1.478125,8.94778265,1.246621001,69.48662206 +87.37,50.42543434,-2.58361996,51.3048,3.504001679,9.365926577,1.5346875,9.033863085,1.340428173,69.479097 +87.38,50.42543465,-2.583618643,51.2892,3.504001671,9.364816153,1.59,9.119101042,1.43306651,69.47157189 +87.39,50.42543497,-2.583617325,51.273,3.507477857,9.364816067,1.645,9.203478817,1.524455169,69.46404683 +87.4,50.42543528,-2.583616007,51.2563,3.517906425,9.364593913,1.6996875,9.286978707,1.614514509,69.45652172 +87.41,50.4254356,-2.583614689,51.239,3.524858799,9.363483487,1.753125,9.36958335,1.703165919,69.44899666 +87.42,50.42543592,-2.583613372,51.2212,3.517906404,9.362595128,1.805,9.451275501,1.790332166,69.44147155 +87.43,50.42543623,-2.583612054,51.2029,3.50747781,9.36237297,1.8565625,9.53203797,1.875937217,69.4339465 +87.44,50.42543655,-2.583610737,51.1841,3.507477794,9.362150813,1.9084375,9.611854027,1.959906417,69.42642138 +87.45,50.42543686,-2.583609419,51.1647,3.517906367,9.36148452,1.9596875,9.690707,2.042166597,69.41889633 +87.46,50.42543718,-2.583608102,51.1449,3.524858748,9.361040293,2.0096875,9.76858033,2.122645911,69.41137121 +87.47,50.4254375,-2.583606785,51.1245,3.521382544,9.361262268,2.058125,9.845457801,2.201274284,69.40384616 +87.48,50.42543781,-2.583605467,51.1037,3.521382535,9.361040108,2.105,9.921323372,2.277983077,69.39632104 +87.49,50.42543813,-2.58360415,51.0824,3.524858712,9.359929676,2.1515625,9.996161171,2.352705483,69.38879599 +87.5,50.42543845,-2.583602833,51.0607,3.521382492,9.359041311,2.198125,10.06995561,2.425376241,69.38127088 +87.51,50.42543876,-2.583601516,51.0384,3.521382475,9.358819148,2.2434375,10.14269123,2.495932097,69.37374582 +87.52,50.42543908,-2.583600199,51.0158,3.524858669,9.358596985,2.2878125,10.2143529,2.564311401,69.36622076 +87.53,50.4254394,-2.583598882,50.9927,3.521382473,9.357708619,2.331875,10.2849256,2.630454623,69.35869565 +87.54,50.42543971,-2.583597565,50.9691,3.521382458,9.356598183,2.374375,10.35439461,2.694304066,69.3511706 +87.55,50.42544003,-2.583596249,50.9452,3.524858632,9.356376018,2.4146875,10.42274544,2.755803981,69.34364548 +87.56,50.42544035,-2.583594932,50.9208,3.521382423,9.356597988,2.4534375,10.48996376,2.814900853,69.33612043 +87.57,50.42544066,-2.583593615,50.8961,3.524858603,9.356375822,2.4915625,10.55603559,2.871543059,69.32859531 +87.58,50.42544098,-2.583592299,50.871,3.538763368,9.356375723,2.53,10.62094712,2.925681269,69.32107026 +87.59,50.4254413,-2.583590982,50.8455,3.538763356,9.356375623,2.568125,10.68468478,2.977268211,69.31354514 +87.6,50.42544162,-2.583589665,50.8196,3.524858571,9.355265184,2.6046875,10.74723527,3.02625891,69.30602009 +87.61,50.42544193,-2.583588349,50.7934,3.524858556,9.354154744,2.6396875,10.80858553,3.07261068,69.29849498 +87.62,50.42544225,-2.583587033,50.7668,3.542239494,9.354154642,2.673125,10.86872272,3.116283128,69.29096992 +87.63,50.42544257,-2.583585716,50.7399,3.552668043,9.353932473,2.7046875,10.92763436,3.157238093,69.28344481 +87.64,50.42544289,-2.5835844,50.7127,3.542239456,9.352822033,2.735,10.985308,3.195439883,69.27591975 +87.65,50.42544321,-2.583583084,50.6852,3.524858495,9.351933659,2.765,11.04173174,3.230855206,69.26839464 +87.66,50.42544352,-2.583581768,50.6574,3.524858484,9.351711488,2.7946875,11.09689377,3.263453239,69.26086958 +87.67,50.42544384,-2.583580452,50.6293,3.542239427,9.351711385,2.823125,11.15078251,3.293205447,69.25334447 +87.68,50.42544416,-2.583579136,50.6009,3.55614418,9.351711281,2.8496875,11.20338668,3.320085934,69.24581941 +87.69,50.42544448,-2.58357782,50.5723,3.559620348,9.351489108,2.8746875,11.25469546,3.344071208,69.2382943 +87.7,50.4254448,-2.583576504,50.5434,3.559620319,9.350600732,2.898125,11.30469794,3.36514047,69.23076924 +87.71,50.42544512,-2.583575188,50.5143,3.556144115,9.349268221,2.92,11.35338383,3.383275272,69.22324413 +87.72,50.42544544,-2.583573873,50.485,3.542239346,9.348379846,2.9415625,11.40074286,3.3984598,69.21571908 +87.73,50.42544576,-2.583572557,50.4555,3.524858372,9.348157672,2.963125,11.44676517,3.410680818,69.20819396 +87.74,50.42544607,-2.583571242,50.4257,3.524858347,9.348157566,2.9828125,11.49144116,3.419927669,69.20066891 +87.75,50.42544639,-2.583569926,50.3958,3.542239288,9.34815746,2.9996875,11.53476147,3.426192275,69.19314379 +87.76,50.42544671,-2.583568611,50.3657,3.556144042,9.347935286,3.015,11.57671716,3.429469192,69.18561874 +87.77,50.42544703,-2.583567295,50.3355,3.559620215,9.347046908,3.0296875,11.6172993,3.429755614,69.17809362 +87.78,50.42544735,-2.58356598,50.3051,3.559620198,9.345936463,3.0434375,11.65649953,3.427051196,69.17056857 +87.79,50.42544767,-2.583564665,50.2746,3.559620184,9.345936355,3.05625,11.69430964,3.421358344,69.16304346 +87.8,50.42544799,-2.58356335,50.244,3.559620165,9.34660245,3.068125,11.73072174,3.412681987,69.1555184 +87.81,50.42544831,-2.583562034,50.2132,3.55962015,9.345714072,3.078125,11.7657282,3.401029745,69.14799329 +87.82,50.42544863,-2.583560719,50.1824,3.559620142,9.343493288,3.08625,11.79932175,3.386411758,69.14046823 +87.83,50.42544895,-2.583559405,50.1515,3.559620122,9.342604909,3.0934375,11.83149533,3.368840746,69.13294312 +87.84,50.42544927,-2.58355809,50.1205,3.55962009,9.343493071,3.0996875,11.86224225,3.348332123,69.12541806 +87.85,50.42544959,-2.583556775,50.0895,3.559620068,9.344159166,3.1046875,11.89155609,3.32490365,69.11789295 +87.86,50.42544991,-2.58355546,50.0584,3.563096256,9.343492855,3.108125,11.91943066,3.298575838,69.11036789 +87.87,50.42545023,-2.583554145,50.0273,3.577001013,9.342160341,3.1096875,11.94586023,3.269371549,69.10284284 +87.88,50.42545055,-2.583552831,49.9962,3.594381946,9.341271962,3.1096875,11.9708393,3.237316394,69.09531772 +87.89,50.42545088,-2.583551516,49.9651,3.594381922,9.341049785,3.108125,11.99436254,3.202438218,69.08779267 +87.9,50.4254512,-2.583550202,49.934,3.57700095,9.340827609,3.105,12.01642508,3.164767504,69.08026756 +87.91,50.42545152,-2.583548887,49.903,3.56309617,9.340161298,3.1015625,12.03702234,3.124337023,69.0727425 +87.92,50.42545184,-2.583547573,49.872,3.559619959,9.339717055,3.098125,12.05615002,3.081182129,69.06521739 +87.93,50.42545216,-2.583546259,49.841,3.559619942,9.339939014,3.0928125,12.07380411,3.035340349,69.05769233 +87.94,50.42545248,-2.583544944,49.8101,3.563096119,9.339716838,3.0846875,12.08998095,2.986851732,69.05016722 +87.95,50.4254528,-2.58354363,49.7793,3.577000864,9.338606392,3.075,12.10467714,2.935758508,69.04264216 +87.96,50.42545312,-2.583542316,49.7486,3.594381801,9.337718013,3.0646875,12.1178896,2.88210525,69.03511705 +87.97,50.42545345,-2.583541002,49.718,3.594381791,9.337495837,3.053125,12.12961553,2.82593877,69.02759199 +87.98,50.42545377,-2.583539688,49.6875,3.577000825,9.337273662,3.04,12.13985257,2.767308056,69.02006688 +87.99,50.42545409,-2.583538374,49.6572,3.566572226,9.336385285,3.02625,12.14859854,2.706264216,69.01254182 +88,50.42545441,-2.58353706,49.627,3.577000771,9.335052773,3.0115625,12.15585167,2.64286042,69.00501671 +88.01,50.42545473,-2.583535747,49.5969,3.594381717,9.334164395,2.9946875,12.1616103,2.577152016,68.99749166 +88.02,50.42545506,-2.583534433,49.5671,3.594381716,9.333942221,2.9765625,12.16587339,2.509196357,68.98996654 +88.03,50.42545538,-2.58353312,49.5374,3.580476933,9.333942114,2.958125,12.16863991,2.439052571,68.98244149 +88.04,50.4254557,-2.583531806,49.5079,3.580476901,9.333942007,2.9378125,12.16990942,2.366781967,68.97491637 +88.05,50.42545602,-2.583530493,49.4786,3.594381646,9.333941901,2.915,12.16968155,2.292447454,68.96739132 +88.06,50.42545635,-2.583529179,49.4496,3.594381644,9.333941795,2.8915625,12.16795638,2.216113891,68.9598662 +88.07,50.42545667,-2.583527866,49.4208,3.580476868,9.333719622,2.868125,12.16473429,2.137847799,68.95234115 +88.08,50.42545699,-2.583526552,49.3922,3.580476843,9.332831247,2.843125,12.16001593,2.057717531,68.94481604 +88.09,50.42545731,-2.583525239,49.3639,3.594381587,9.331720805,2.81625,12.15380231,1.975792875,68.93729098 +88.1,50.42545764,-2.583523926,49.3359,3.597857767,9.331498633,2.7884375,12.14609471,1.892145334,68.92976587 +88.11,50.42545796,-2.583522613,49.3081,3.594381565,9.33149853,2.7596875,12.13689473,1.806847789,68.92224081 +88.12,50.42545828,-2.583521299,49.2807,3.601333928,9.330388088,2.7296875,12.12620431,1.719974668,68.9147157 +88.13,50.42545861,-2.583519987,49.2535,3.61176248,9.329277647,2.698125,12.11402563,1.631601657,68.90719064 +88.14,50.42545893,-2.583518674,49.2267,3.611762465,9.329277544,2.6646875,12.10036134,1.541805935,68.89966553 +88.15,50.42545926,-2.583517361,49.2002,3.601333883,9.329055375,2.63,12.08521417,1.450665654,68.89214047 +88.16,50.42545958,-2.583516048,49.1741,3.594381488,9.328167003,2.5946875,12.06858739,1.358260453,68.88461536 +88.17,50.4254599,-2.583514736,49.1483,3.601333847,9.327944834,2.5584375,12.05048439,1.264670776,68.8770903 +88.18,50.42546023,-2.583513423,49.1229,3.611762405,9.328166801,2.52125,12.030909,1.169978271,68.86956519 +88.19,50.42546055,-2.58351211,49.0979,3.611762404,9.327722566,2.4834375,12.00986529,1.074265556,68.86204014 +88.2,50.42546088,-2.583510798,49.0732,3.601333823,9.327056264,2.4446875,11.98735767,0.977616056,68.85451502 +88.21,50.4254612,-2.583509485,49.049,3.594381418,9.326834097,2.4046875,11.96339085,0.880114109,68.84698997 +88.22,50.42546152,-2.583508173,49.0251,3.601333781,9.326611931,2.3634375,11.9379698,0.781844628,68.83946491 +88.23,50.42546185,-2.58350686,49.0017,3.611762346,9.325723563,2.32125,11.9110998,0.682893385,68.8319398 +88.24,50.42546217,-2.583505548,48.9787,3.615238529,9.324391062,2.278125,11.88278657,0.583346666,68.82441474 +88.25,50.4254625,-2.583504236,48.9561,3.615238512,9.323502696,2.233125,11.85303591,0.483291218,68.81688963 +88.26,50.42546282,-2.583502924,48.934,3.615238493,9.323280532,2.1865625,11.82185412,0.38281436,68.80936457 +88.27,50.42546315,-2.583501612,48.9124,3.615238481,9.323280436,2.14,11.78924766,0.282003696,68.80183946 +88.28,50.42546347,-2.5835003,48.8912,3.615238476,9.323280341,2.0934375,11.75522331,0.180947119,68.7943144 +88.29,50.4254638,-2.583498988,48.8705,3.615238467,9.323058179,2.04625,11.71978827,0.079732749,68.78678929 +88.3,50.42546412,-2.583497676,48.8503,3.615238444,9.322169816,1.998125,11.68294989,-0.021551177,68.77926424 +88.31,50.42546445,-2.583496364,48.8305,3.618714616,9.321059387,1.948125,11.64471585,-0.122816311,68.77173912 +88.32,50.42546477,-2.583495053,48.8113,3.629143189,9.320837228,1.8965625,11.6050941,-0.223974301,68.76421407 +88.33,50.4254651,-2.583493741,48.7926,3.636095579,9.320837136,1.845,11.56409301,-0.324937028,68.75668895 +88.34,50.42546543,-2.583492429,48.7744,3.629143187,9.319726708,1.793125,11.52172112,-0.42561637,68.7491639 +88.35,50.42546575,-2.583491118,48.7567,3.618714586,9.318616281,1.7396875,11.47798719,-0.525924606,68.74163878 +88.36,50.42546608,-2.583489807,48.7396,3.618714565,9.318616192,1.685,11.43290046,-0.625774191,68.73411373 +88.37,50.4254664,-2.583488495,48.723,3.62914314,9.318616104,1.63,11.38647025,-0.72507809,68.72658862 +88.38,50.42546673,-2.583487184,48.707,3.636095531,9.318393949,1.575,11.33870637,-0.82374973,68.71906356 +88.39,50.42546706,-2.583485873,48.6915,3.632619332,9.31861593,1.52,11.28961872,-0.921703053,68.71153845 +88.4,50.42546738,-2.583484561,48.6766,3.632619308,9.318171709,1.4646875,11.23921752,-1.018852631,68.70401339 +88.41,50.42546771,-2.58348325,48.6622,3.636095486,9.316173018,1.408125,11.18751335,-1.115113723,68.69648828 +88.42,50.42546804,-2.583481939,48.6484,3.632619299,9.314174327,1.3496875,11.13451704,-1.210402448,68.68896322 +88.43,50.42546836,-2.583480629,48.6352,3.632619291,9.313952175,1.29,11.0802396,-1.304635728,68.68143811 +88.44,50.42546869,-2.583479318,48.6226,3.636095462,9.31506243,1.23,11.02469232,-1.397731286,68.67391305 +88.45,50.42546902,-2.583478007,48.6106,3.632619258,9.315728551,1.1703125,10.96788693,-1.489607991,68.66638794 +88.46,50.42546934,-2.583476696,48.5992,3.636095443,9.315062268,1.1115625,10.90983519,-1.5801858,68.65886288 +88.47,50.42546967,-2.583475385,48.5884,3.650000207,9.313951851,1.0528125,10.8505493,-1.669385588,68.65133777 +88.48,50.42547,-2.583474075,48.5781,3.650000217,9.313729704,0.9915625,10.79004152,-1.75712972,68.64381272 +88.49,50.42547033,-2.583472764,48.5685,3.636095455,9.313729626,0.9284375,10.72832463,-1.843341534,68.6362876 +88.5,50.42547065,-2.583471453,48.5596,3.636095439,9.312619212,0.866875,10.66541146,-1.927945971,68.62876255 +88.51,50.42547098,-2.583470143,48.5512,3.650000185,9.311508799,0.8065625,10.60131507,-2.010869236,68.62123743 +88.52,50.42547131,-2.583468833,48.5434,3.650000183,9.311508723,0.744375,10.53604899,-2.092038964,68.61371238 +88.53,50.42547164,-2.583467522,48.5363,3.636095428,9.311286581,0.68,10.46962674,-2.171384394,68.60618726 +88.54,50.42547196,-2.583466212,48.5298,3.636095425,9.31017617,0.6153125,10.40206224,-2.248836313,68.59866221 +88.55,50.42547229,-2.583464902,48.524,3.653476363,9.309287827,0.551875,10.33336958,-2.324327284,68.5911371 +88.56,50.42547262,-2.583463592,48.5188,3.667381118,9.309065687,0.49,10.2635631,-2.39779136,68.58361204 +88.57,50.42547295,-2.583462282,48.5142,3.670857307,9.309065616,0.4278125,10.19265745,-2.46916454,68.57608698 +88.58,50.42547328,-2.583460972,48.5102,3.66738112,9.309065546,0.3634375,10.12066731,-2.538384603,68.56856187 +88.59,50.42547361,-2.583459662,48.5069,3.65347637,9.309065477,0.298125,10.04760785,-2.6053911,68.56103681 +88.6,50.42547394,-2.583458352,48.5043,3.63609542,9.308843342,0.23375,9.973494216,-2.670125705,68.5535117 +88.61,50.42547426,-2.583457042,48.5022,3.636095408,9.307955005,0.17,9.89834192,-2.732531867,68.54598665 +88.62,50.42547459,-2.583455732,48.5009,3.653476347,9.306622534,0.10625,9.822166723,-2.79255527,68.53846153 +88.63,50.42547492,-2.583454423,48.5001,3.667381106,9.305734199,0.041875,9.744984438,-2.850143487,68.53093648 +88.64,50.42547525,-2.583453113,48.5,3.670857309,9.305512066,-0.0234375,9.666811222,-2.905246385,68.52341136 +88.65,50.42547558,-2.583451804,48.5006,3.67085732,9.305289936,-0.088125,9.587663406,-2.957815836,68.51588631 +88.66,50.42547591,-2.583450494,48.5018,3.670857319,9.304401603,-0.151875,9.507557546,-3.007806002,68.5083612 +88.67,50.42547624,-2.583449185,48.5036,3.670857311,9.303069137,-0.2165625,9.426510259,-3.05517334,68.50083614 +88.68,50.42547657,-2.583447876,48.5061,3.670857304,9.302402874,-0.2815625,9.34453862,-3.099876538,68.49331103 +88.69,50.4254769,-2.583446567,48.5093,3.670857304,9.303069016,-0.345,9.261659702,-3.141876579,68.48578597 +88.7,50.42547723,-2.583445258,48.513,3.67085732,9.303957227,-0.4084375,9.177890751,-3.181136851,68.47826086 +88.71,50.42547756,-2.583443948,48.5174,3.67085734,9.303290966,-0.4734375,9.093249301,-3.217623147,68.4707358 +88.72,50.42547789,-2.583442639,48.5225,3.670857343,9.301736437,-0.5378125,9.007753054,-3.251303611,68.46321069 +88.73,50.42547822,-2.583441331,48.5282,3.670857329,9.301070178,-0.6,8.921419773,-3.282148909,68.45568563 +88.74,50.42547855,-2.583440021,48.5345,3.67085732,9.300848055,-0.661875,8.834267622,-3.31013211,68.44816052 +88.75,50.42547888,-2.583438713,48.5414,3.670857324,9.300403866,-0.725,8.746314704,-3.335228808,68.44063546 +88.76,50.42547921,-2.583437404,48.549,3.670857331,9.299959678,-0.7884375,8.657579412,-3.357417171,68.43311035 +88.77,50.42547954,-2.583436095,48.5572,3.670857342,9.299293423,-0.85125,8.568080311,-3.376677778,68.42558529 +88.78,50.42547987,-2.583434787,48.566,3.670857361,9.298627169,-0.9134375,8.47783602,-3.392993897,68.41806018 +88.79,50.4254802,-2.583433478,48.5755,3.670857366,9.29840505,-0.9746875,8.386865449,-3.406351319,68.41053513 +88.8,50.42548053,-2.58343217,48.5855,3.670857359,9.298182933,-1.035,8.295187618,-3.416738299,68.40301001 +88.81,50.42548086,-2.583430861,48.5962,3.67433355,9.297294615,-1.095,8.20282155,-3.424145841,68.39548496 +88.82,50.42548119,-2.583429553,48.6074,3.688238319,9.295962162,-1.155,8.109786669,-3.428567471,68.38795984 +88.83,50.42548152,-2.583428245,48.6193,3.705619281,9.295073845,-1.215,8.016102339,-3.42999935,68.38043479 +88.84,50.42548186,-2.583426937,48.6317,3.705619302,9.29485173,-1.2746875,7.921788101,-3.42844016,68.37290968 +88.85,50.42548219,-2.583425629,48.6448,3.688238372,9.295073752,-1.3334375,7.826863719,-3.423891391,68.36538462 +88.86,50.42548252,-2.583424321,48.6584,3.674333615,9.295961976,-1.39125,7.731348962,-3.416356938,68.35785951 +88.87,50.42548285,-2.583423013,48.6726,3.674333606,9.296850201,-1.4484375,7.635263825,-3.405843335,68.35033445 +88.88,50.42548318,-2.583421704,48.6874,3.688238366,9.295961888,-1.5046875,7.538628362,-3.392359804,68.34280934 +88.89,50.42548351,-2.583420396,48.7027,3.705619331,9.293741172,-1.56,7.441462684,-3.375918093,68.33528428 +88.9,50.42548385,-2.583419089,48.7186,3.705619342,9.292630793,-1.615,7.343787188,-3.356532524,68.32775923 +88.91,50.42548418,-2.583417781,48.735,3.688238403,9.292630752,-1.67,7.245622157,-3.334220001,68.32023411 +88.92,50.42548451,-2.583416473,48.752,3.677809853,9.292186577,-1.725,7.146988218,-3.308999946,68.31270906 +88.93,50.42548484,-2.583415166,48.7695,3.688238437,9.291520336,-1.779375,7.047905881,-3.280894475,68.30518394 +88.94,50.42548517,-2.583413858,48.7876,3.70561939,9.29129823,-1.8315625,6.948395889,-3.249927997,68.29765889 +88.95,50.42548551,-2.583412551,48.8062,3.705619394,9.291076125,-1.8815625,6.848478983,-3.216127498,68.29013377 +88.96,50.42548584,-2.583411243,48.8252,3.691714639,9.290409885,-1.931875,6.748176017,-3.179522485,68.28260872 +88.97,50.42548617,-2.583409936,48.8448,3.691714648,9.289743646,-1.983125,6.64750802,-3.140144929,68.27508361 +88.98,50.4254865,-2.583408629,48.8649,3.705619429,9.289077408,-2.033125,6.546495904,-3.098029093,68.26755855 +88.99,50.42548684,-2.583407321,48.8855,3.709095641,9.287744969,-2.0815625,6.44516087,-3.053211704,68.26003344 +89,50.42548717,-2.583406015,48.9065,3.705619471,9.286634597,-2.1296875,6.343524001,-3.005731895,68.25250838 +89.01,50.4254875,-2.583404708,48.9281,3.709095678,9.286856631,-2.1765625,6.241606612,-2.955631033,68.24498327 +89.02,50.42548784,-2.583403401,48.9501,3.70909568,9.2875228,-2.22125,6.139429846,-2.902952835,68.23745821 +89.03,50.42548817,-2.583402094,48.9725,3.705619491,9.287522767,-2.265,6.037015187,-2.847743252,68.2299331 +89.04,50.4254885,-2.583400787,48.9954,3.709095695,9.286634466,-2.3084375,5.93438395,-2.790050356,68.22240804 +89.05,50.42548884,-2.58339948,49.0187,3.709095709,9.285524098,-2.35125,5.831557563,-2.729924451,68.21488293 +89.06,50.42548917,-2.583398174,49.0424,3.705619532,9.285302,-2.393125,5.728557513,-2.667418079,68.20735787 +89.07,50.4254895,-2.583396867,49.0666,3.71257194,9.285524037,-2.4334375,5.625405343,-2.60258567,68.19983276 +89.08,50.42548984,-2.58339556,49.0911,3.723000539,9.285079873,-2.4728125,5.522122539,-2.535483717,68.19230771 +89.09,50.42549017,-2.583394254,49.116,3.726476743,9.284191574,-2.511875,5.4187307,-2.466170836,68.18478259 +89.1,50.42549051,-2.583392947,49.1414,3.726476749,9.283081209,-2.5496875,5.315251429,-2.394707414,68.17725754 +89.11,50.42549084,-2.583391641,49.167,3.723000564,9.281970844,-2.58625,5.211706267,-2.321155733,68.16973242 +89.12,50.42549118,-2.583390335,49.1931,3.712572001,9.281748749,-2.6215625,5.10811693,-2.245579965,68.16220737 +89.13,50.42549151,-2.583389029,49.2195,3.705619636,9.28197079,-2.6546875,5.004505018,-2.168046055,68.15468225 +89.14,50.42549184,-2.583387722,49.2462,3.712572035,9.281748696,-2.686875,4.90089219,-2.088621557,68.1471572 +89.15,50.42549218,-2.583386417,49.2732,3.723000623,9.281526602,-2.7196875,4.797300045,-2.007375798,68.13963209 +89.16,50.42549251,-2.58338511,49.3006,3.726476835,9.280860374,-2.75125,4.693750185,-1.924379538,68.13210703 +89.17,50.42549285,-2.583383804,49.3283,3.72647686,9.279305878,-2.7796875,4.590264325,-1.8397052,68.12458192 +89.18,50.42549318,-2.583382499,49.3562,3.726476886,9.278639651,-2.806875,4.486864064,-1.753426579,68.11705686 +89.19,50.42549352,-2.583381193,49.3844,3.729953096,9.279305829,-2.835,4.383570889,-1.665618964,68.10953175 +89.2,50.42549385,-2.583379887,49.4129,3.740381676,9.279305805,-2.8628125,4.280406514,-1.5763589,68.10200669 +89.21,50.42549419,-2.583378581,49.4417,3.747334065,9.278195444,-2.8878125,4.17739237,-1.485724253,68.09448158 +89.22,50.42549453,-2.583377276,49.4707,3.740381699,9.27730715,-2.9096875,4.074550055,-1.393794035,68.08695652 +89.23,50.42549486,-2.58337597,49.4999,3.729953142,9.277085059,-2.9303125,3.971900999,-1.300648401,68.07943141 +89.24,50.4254952,-2.583374665,49.5293,3.726476966,9.276862969,-2.9515625,3.869466631,-1.206368539,68.07190635 +89.25,50.42549553,-2.583373359,49.5589,3.726476986,9.275974678,-2.9728125,3.767268378,-1.111036727,68.0643813 +89.26,50.42549587,-2.583372054,49.5888,3.729953195,9.274642252,-2.99125,3.665327555,-1.014736101,68.05685619 +89.27,50.4254962,-2.583370749,49.6188,3.740381788,9.273976027,-3.0065625,3.563665419,-0.917550599,68.04933113 +89.28,50.42549654,-2.583369444,49.6489,3.7473342,9.274642208,-3.0215625,3.462303284,-0.819564961,68.04180602 +89.29,50.42549688,-2.583368139,49.6792,3.743858037,9.275530456,-3.0365625,3.361262291,-0.720864673,68.03428096 +89.3,50.42549721,-2.583366833,49.7097,3.743858053,9.274642165,-3.0496875,3.260563526,-0.621535793,68.02675585 +89.31,50.42549755,-2.583365528,49.7402,3.747334254,9.272421469,-3.0615625,3.160228016,-0.521664894,68.01923079 +89.32,50.42549789,-2.583364224,49.7709,3.743858072,9.271533178,-3.073125,3.060276675,-0.421339068,68.01170568 +89.33,50.42549822,-2.583362919,49.8017,3.743858086,9.272199359,-3.0828125,2.960730472,-0.320645861,68.00418062 +89.34,50.42549856,-2.583361614,49.8326,3.747334298,9.272199338,-3.09,2.861610149,-0.21967305,67.99665551 +89.35,50.4254989,-2.583360309,49.8635,3.743858125,9.271088982,-3.0965625,2.762936388,-0.1185087,67.98913045 +89.36,50.42549923,-2.583359005,49.8945,3.743858141,9.270200692,-3.1028125,2.664729761,-0.017240988,67.98160534 +89.37,50.42549957,-2.5833577,49.9256,3.747334353,9.269978603,-3.10625,2.567010892,0.084041736,67.97408029 +89.38,50.42549991,-2.583356396,49.9567,3.74385818,9.269756515,-3.1065625,2.469800065,0.185251235,67.96655517 +89.39,50.42550024,-2.583355091,49.9877,3.747334388,9.269090293,-3.106875,2.373117677,0.286299161,67.95903012 +89.4,50.42550058,-2.583353787,50.0188,3.761239178,9.268646137,-3.1084375,2.276983896,0.387097391,67.951505 +89.41,50.42550092,-2.583352483,50.0499,3.761239206,9.268868184,-3.1090625,2.181418718,0.487558092,67.94397995 +89.42,50.42550126,-2.583351178,50.081,3.747334466,9.268646096,-3.1065625,2.086442255,0.587593658,67.93645483 +89.43,50.42550159,-2.583349874,50.1121,3.747334486,9.267535738,-3.10125,1.992074158,0.687116828,67.92892978 +89.44,50.42550193,-2.58334857,50.143,3.764715453,9.266647448,-3.095,1.898334309,0.786040799,67.92140467 +89.45,50.42550227,-2.583347266,50.174,3.778620228,9.266203292,-3.088125,1.805242132,0.884279341,67.91387961 +89.46,50.42550261,-2.583345962,50.2048,3.778620247,9.265315001,-3.0796875,1.712817164,0.981746795,67.9063545 +89.47,50.42550295,-2.583344658,50.2356,3.764715495,9.264204643,-3.07,1.621078714,1.078358137,67.89882944 +89.48,50.42550329,-2.583343355,50.2662,3.747334545,9.263982554,-3.0596875,1.530045862,1.17402914,67.89130433 +89.49,50.42550362,-2.583342051,50.2968,3.747334563,9.2642046,-3.048125,1.439737687,1.268676324,67.88377927 +89.5,50.42550396,-2.583340747,50.3272,3.76471555,9.263760443,-3.0346875,1.350173039,1.362217242,67.87625416 +89.51,50.4255043,-2.583339444,50.3575,3.778620339,9.263094219,-3.02,1.261370597,1.454570304,67.8687291 +89.52,50.42550464,-2.58333814,50.3876,3.782096546,9.262872129,-3.004375,1.173348924,1.545654951,67.86120399 +89.53,50.42550498,-2.583336837,50.4176,3.782096567,9.262650039,-2.9865625,1.086126413,1.635391773,67.85367893 +89.54,50.42550532,-2.583335533,50.4474,3.778620392,9.261983814,-2.9665625,0.999721226,1.723702503,67.84615382 +89.55,50.42550566,-2.58333423,50.4769,3.764715639,9.261317589,-2.9465625,0.914151469,1.810510078,67.83862877 +89.56,50.425506,-2.583332927,50.5063,3.747334699,9.260651364,-2.9265625,0.829435018,1.895738925,67.83110365 +89.57,50.42550633,-2.583331623,50.5355,3.747334716,9.259541003,-2.9046875,0.745589463,1.979314674,67.8235786 +89.58,50.42550667,-2.583330321,50.5644,3.764715694,9.259318912,-2.88125,0.662632451,2.061164388,67.81605348 +89.59,50.42550701,-2.583329018,50.5931,3.778620491,9.260429224,-2.8565625,0.580581228,2.141216734,67.80852843 +89.6,50.42550735,-2.583327714,50.6216,3.782096711,9.260207132,-2.8296875,0.499452925,2.219401924,67.80100337 +89.61,50.42550769,-2.583326411,50.6497,3.782096726,9.258208501,-2.8015625,0.419264559,2.295651778,67.79347826 +89.62,50.42550803,-2.583325109,50.6776,3.782096734,9.257098137,-2.7734375,0.340032747,2.369899774,67.7859532 +89.63,50.42550837,-2.583323806,50.7052,3.782096739,9.257098111,-2.7446875,0.261774161,2.442081169,67.77842809 +89.64,50.42550871,-2.583322503,50.7325,3.782096745,9.256653951,-2.7146875,0.184505072,2.512133052,67.77090303 +89.65,50.42550905,-2.583321201,50.7595,3.782096761,9.255987722,-2.6828125,0.10824164,2.579994345,67.76337792 +89.66,50.42550939,-2.583319898,50.7862,3.782096786,9.255765627,-2.648125,0.032999791,2.645605805,67.75585287 +89.67,50.42550973,-2.583318596,50.8125,3.785572996,9.25554353,-2.611875,-0.041204775,2.70891025,67.74832775 +89.68,50.42551007,-2.583317293,50.8384,3.799477779,9.254877299,-2.5765625,-0.114356532,2.769852505,67.7408027 +89.69,50.42551041,-2.583315991,50.864,3.816858758,9.254433135,-2.5415625,-0.186440237,2.828379399,67.73327758 +89.7,50.42551076,-2.583314689,50.8893,3.816858773,9.254655173,-2.5046875,-0.257440824,2.884439938,67.72575253 +89.71,50.4255111,-2.583313386,50.9141,3.799477825,9.254433075,-2.46625,-0.327343451,2.937985136,67.71822741 +89.72,50.42551144,-2.583312084,50.9386,3.785573072,9.253100639,-2.4265625,-0.396133566,2.98896841,67.71070236 +89.73,50.42551178,-2.583310782,50.9627,3.782096892,9.251324069,-2.3846875,-0.46379673,3.037345242,67.70317725 +89.74,50.42551212,-2.58330948,50.9863,3.782096898,9.249991634,-2.3415625,-0.530318849,3.08307352,67.69565219 +89.75,50.42551246,-2.583308179,51.0095,3.782096912,9.249991601,-2.2984375,-0.595686,3.12611325,67.68812708 +89.76,50.4255128,-2.583306877,51.0323,3.785573127,9.250879837,-2.255,-0.659884603,3.166426961,67.68060202 +89.77,50.42551314,-2.583305575,51.0546,3.799477912,9.250879803,-2.21125,-0.722901251,3.203979532,67.67307691 +89.78,50.42551348,-2.583304273,51.0765,3.816858885,9.249769431,-2.1665625,-0.784722652,3.238738189,67.66555185 +89.79,50.42551383,-2.583302972,51.098,3.8168589,9.248881127,-2.1196875,-0.845336087,3.270672564,67.65802674 +89.8,50.42551417,-2.58330167,51.1189,3.799477951,9.248659023,-2.0715625,-0.90472872,3.299754928,67.65050168 +89.81,50.42551451,-2.583300369,51.1394,3.789049384,9.248658986,-2.023125,-0.962888233,3.32595984,67.64297657 +89.82,50.42551485,-2.583299067,51.1594,3.799477976,9.248658948,-1.973125,-1.019802538,3.34926444,67.63545151 +89.83,50.42551519,-2.583297766,51.1789,3.816858948,9.248436842,-1.9215625,-1.0754596,3.369648445,67.6279264 +89.84,50.42551554,-2.583296464,51.1978,3.81685895,9.247548534,-1.87,-1.129847963,3.387094036,67.62040135 +89.85,50.42551588,-2.583295163,51.2163,3.802954191,9.24621609,-1.8184375,-1.182956109,3.401586087,67.61287623 +89.86,50.42551622,-2.583293862,51.2342,3.802954211,9.24532778,-1.76625,-1.234773094,3.413111877,67.60535118 +89.87,50.42551656,-2.583292561,51.2516,3.816858994,9.245105672,-1.7134375,-1.285287975,3.421661382,67.59782606 +89.88,50.42551691,-2.58329126,51.2685,3.820335195,9.245105629,-1.6596875,-1.334490267,3.427227151,67.59030101 +89.89,50.42551725,-2.583289959,51.2848,3.816859015,9.244883518,-1.605,-1.382369715,3.429804315,67.58277589 +89.9,50.42551759,-2.583288658,51.3006,3.820335215,9.243995205,-1.5496875,-1.428916233,3.429390697,67.57525084 +89.91,50.42551794,-2.583287357,51.3158,3.816859022,9.242884824,-1.493125,-1.474120197,3.425986526,67.56772573 +89.92,50.42551828,-2.583286057,51.3305,3.802954261,9.242662711,-1.4353125,-1.517972094,3.419594895,67.56020067 +89.93,50.42551862,-2.583284756,51.3445,3.802954279,9.242662665,-1.378125,-1.560462816,3.410221305,67.55267556 +89.94,50.42551896,-2.583283455,51.358,3.81685906,9.241552281,-1.3215625,-1.601583424,3.397873893,67.5451505 +89.95,50.42551931,-2.583282155,51.371,3.820335258,9.240441897,-1.2628125,-1.641325439,3.382563544,67.53762545 +89.96,50.42551965,-2.583280855,51.3833,3.816859075,9.240441848,-1.201875,-1.679680494,3.364303551,67.53010033 +89.97,50.42551999,-2.583279554,51.395,3.823811468,9.240441798,-1.141875,-1.716640512,3.343109842,67.52257528 +89.98,50.42552034,-2.583278254,51.4061,3.83424005,9.24021968,-1.083125,-1.752197929,3.319000867,67.51505016 +89.99,50.42552068,-2.583276954,51.4167,3.834240059,9.240441696,-1.023125,-1.786345182,3.29199771,67.50752511 +90,50.42552103,-2.583275653,51.4266,3.823811485,9.240219576,-0.96125,-1.819075224,3.262123862,67.49999999 +90.01,50.42552137,-2.583274353,51.4359,3.816859097,9.238887118,-0.89875,-1.85038118,3.229405394,67.49247494 +90.02,50.42552171,-2.583273053,51.4446,3.823811487,9.237110526,-0.8365625,-1.880256517,3.193870838,67.48494983 +90.03,50.42552206,-2.583271753,51.4526,3.834240079,9.235778067,-0.775,-1.90869499,3.155551134,67.47742477 +90.04,50.4255224,-2.583270454,51.4601,3.837716279,9.235778011,-0.713125,-1.935690699,3.1144798,67.46989966 +90.05,50.42552275,-2.583269154,51.4669,3.837716281,9.236666222,-0.6496875,-1.96123797,3.070692589,67.4623746 +90.06,50.42552309,-2.583267854,51.4731,3.837716287,9.236666164,-0.5853125,-1.985331476,3.02422766,67.45484949 +90.07,50.42552344,-2.583266554,51.4786,3.837716288,9.235555768,-0.521875,-2.007966174,2.975125578,67.44732443 +90.08,50.42552378,-2.583265255,51.4835,3.837716283,9.23466744,-0.4596875,-2.029137365,2.923429143,67.43979932 +90.09,50.42552413,-2.583263955,51.4878,3.837716286,9.234223245,-0.3965625,-2.048840582,2.869183447,67.43227426 +90.1,50.42552447,-2.583262656,51.4915,3.837716297,9.233334914,-0.3315625,-2.067071755,2.812435759,67.42474915 +90.11,50.42552482,-2.583261356,51.4944,3.837716301,9.232224514,-0.266875,-2.083827046,2.753235583,67.41722409 +90.12,50.42552516,-2.583260058,51.4968,3.8377163,9.232002383,-0.2034375,-2.099103018,2.691634541,67.40969898 +90.13,50.42552551,-2.583258758,51.4985,3.837716304,9.232224386,-0.1396875,-2.112896347,2.627686378,67.40217393 +90.14,50.42552585,-2.583257459,51.4996,3.837716303,9.231780186,-0.075,-2.125204339,2.561446784,67.39464881 +90.15,50.4255262,-2.58325616,51.5,3.841192487,9.231113918,-0.01,-2.136024246,2.492973629,67.38712376 +90.16,50.42552654,-2.583254861,51.4998,3.851621065,9.230891783,0.055,-2.145353947,2.422326501,67.37959864 +90.17,50.42552689,-2.583253562,51.4989,3.858573459,9.230891714,0.12,-2.15319138,2.349567106,67.37207359 +90.18,50.42552724,-2.583252263,51.4974,3.855097266,9.230669577,0.1846875,-2.159534996,2.274758872,67.36454847 +90.19,50.42552758,-2.583250964,51.4952,3.855097256,9.229781238,0.2484375,-2.164383423,2.197967,67.35702342 +90.2,50.42552793,-2.583249665,51.4924,3.858573447,9.228448763,0.3115625,-2.167735627,2.11925847,67.34949831 +90.21,50.42552828,-2.583248367,51.489,3.851621069,9.227560422,0.3753125,-2.169590979,2.038701922,67.34197325 +90.22,50.42552862,-2.583247068,51.4849,3.84119249,9.227338281,0.44,-2.169949077,1.9563676,67.33444814 +90.23,50.42552897,-2.58324577,51.4802,3.841192486,9.227116139,0.5046875,-2.168809751,1.872327239,67.32692308 +90.24,50.42552931,-2.583244471,51.4748,3.855097255,9.226449863,0.568125,-2.166173343,1.786654235,67.31939797 +90.25,50.42552966,-2.583243173,51.4688,3.872478213,9.226005653,0.63,-2.162040426,1.699423244,67.31187291 +90.26,50.42553001,-2.583241875,51.4622,3.872478198,9.226227643,0.691875,-2.156411746,1.610710298,67.3043478 +90.27,50.42553036,-2.583240576,51.455,3.858573415,9.226005498,0.755,-2.149288563,1.520592803,67.29682274 +90.28,50.4255307,-2.583239278,51.4471,3.855097215,9.224895083,0.8184375,-2.140672309,1.429149369,67.28929769 +90.29,50.42553105,-2.58323798,51.4386,3.858573403,9.223784668,0.88125,-2.130564875,1.336459638,67.28177257 +90.3,50.4255314,-2.583236682,51.4295,3.855097207,9.222896318,0.9434375,-2.118968267,1.24260451,67.27424752 +90.31,50.42553174,-2.583235384,51.4197,3.858573403,9.222452101,1.0046875,-2.105885005,1.147665804,67.26672241 +90.32,50.42553209,-2.583234087,51.4094,3.872478179,9.222674086,1.0646875,-2.091317725,1.051726313,67.25919735 +90.33,50.42553244,-2.583232788,51.3984,3.872478175,9.222451936,1.12375,-2.075269521,0.954869746,67.25167224 +90.34,50.42553279,-2.583231491,51.3869,3.858573395,9.221341515,1.183125,-2.057743716,0.857180499,67.24414718 +90.35,50.42553313,-2.583230193,51.3748,3.85857339,9.220453161,1.2434375,-2.038744034,0.758743772,67.23662207 +90.36,50.42553348,-2.583228896,51.362,3.875954343,9.220231008,1.303125,-2.018274372,0.659645393,67.22909701 +90.37,50.42553383,-2.583227598,51.3487,3.886382904,9.220230922,1.36125,-1.996339084,0.559971821,67.2215719 +90.38,50.42553418,-2.583226301,51.3348,3.875954319,9.220008767,1.4184375,-1.972942639,0.459809918,67.21404684 +90.39,50.42553453,-2.583225003,51.3203,3.858573356,9.219342476,1.475,-1.948090021,0.359247059,67.20652173 +90.4,50.42553487,-2.583223706,51.3053,3.858573347,9.218898253,1.5315625,-1.921786331,0.258370963,67.19899667 +90.41,50.42553522,-2.583222409,51.2897,3.875954292,9.218898164,1.588125,-1.894037183,0.157269524,67.19147156 +90.42,50.42553557,-2.583221111,51.2735,3.889859052,9.218009804,1.643125,-1.864848249,0.056030975,67.18394651 +90.43,50.42553592,-2.583219814,51.2568,3.893335244,9.216455241,1.6965625,-1.834225718,-0.045256447,67.17642139 +90.44,50.42553627,-2.583218518,51.2396,3.893335231,9.215788947,1.75,-1.802175948,-0.146504449,67.16889634 +90.45,50.42553662,-2.58321722,51.2218,3.893335203,9.215566786,1.8034375,-1.768705587,-0.247624624,67.16137122 +90.46,50.42553697,-2.583215924,51.2035,3.889858989,9.215344624,1.85625,-1.733821682,-0.348528909,67.15384617 +90.47,50.42553732,-2.583214627,51.1847,3.875954216,9.215566597,1.908125,-1.697531567,-0.44912924,67.14632105 +90.48,50.42553767,-2.58321333,51.1653,3.858573255,9.215344434,1.958125,-1.65984269,-0.549337954,67.138796 +90.49,50.42553801,-2.583212033,51.1455,3.85857325,9.214234002,2.0065625,-1.620763015,-0.649067618,67.13127089 +90.5,50.42553836,-2.583210737,51.1252,3.875954205,9.21312357,2.0553125,-1.580300678,-0.748231314,67.12374583 +90.51,50.42553871,-2.58320944,51.1044,3.88985896,9.212235203,2.1046875,-1.538464102,-0.846742526,67.11622072 +90.52,50.42553906,-2.583208144,51.0831,3.893335131,9.21179097,2.1528125,-1.49526211,-0.944515368,67.10869566 +90.53,50.42553941,-2.583206848,51.0613,3.893335118,9.212012938,2.198125,-1.450703583,-1.041464582,67.10117055 +90.54,50.42553976,-2.583205551,51.0391,3.893335113,9.211790771,2.2415625,-1.404797976,-1.137505601,67.09364549 +90.55,50.42554011,-2.583204255,51.0165,3.8933351,9.210680334,2.2853125,-1.357554798,-1.232554716,67.08612038 +90.56,50.42554046,-2.583202959,50.9934,3.893335077,9.209791964,2.3296875,-1.308983905,-1.326529019,67.07859532 +90.57,50.42554081,-2.583201663,50.9699,3.893335063,9.209569796,2.3728125,-1.259095496,-1.419346577,67.07107021 +90.58,50.42554116,-2.583200367,50.9459,3.893335057,9.209569694,2.4134375,-1.207899941,-1.510926432,67.06354515 +90.59,50.42554151,-2.583199071,50.9216,3.896811233,9.20956959,2.453125,-1.155407897,-1.601188714,67.05602004 +90.6,50.42554186,-2.583197775,50.8969,3.91071597,9.209347419,2.493125,-1.101630422,-1.690054754,67.04849499 +90.61,50.42554221,-2.583196479,50.8717,3.928096905,9.208459046,2.53125,-1.046578689,-1.77744709,67.04096987 +90.62,50.42554257,-2.583195183,50.8462,3.928096899,9.207126538,2.5665625,-0.990264214,-1.863289403,67.03344482 +90.63,50.42554292,-2.583193888,50.8204,3.910715933,9.206238164,2.601875,-0.932698743,-1.947506922,67.02591976 +90.64,50.42554327,-2.583192592,50.7942,3.896811148,9.206015991,2.638125,-0.873894309,-2.030026195,67.01839465 +90.65,50.42554362,-2.583191297,50.7676,3.893334941,9.205793817,2.6728125,-0.813863171,-2.110775257,67.01086959 +90.66,50.42554397,-2.583190001,50.7407,3.893334934,9.204905442,2.7046875,-0.752617936,-2.189683692,67.00334448 +90.67,50.42554432,-2.583188706,50.7135,3.89681111,9.203795,2.735,-0.690171266,-2.266682688,66.99581942 +90.68,50.42554467,-2.583187411,50.686,3.910715853,9.203794893,2.7646875,-0.626536339,-2.341705094,66.98829431 +90.69,50.42554502,-2.583186116,50.6582,3.928096795,9.204683053,2.793125,-0.561726333,-2.414685479,66.98076925 +90.7,50.42554538,-2.58318482,50.6301,3.928096779,9.204682944,2.82,-0.495754884,-2.485560243,66.97324414 +90.71,50.42554573,-2.583183525,50.6018,3.910715789,9.203350432,2.8465625,-0.428635685,-2.554267566,66.96571909 +90.72,50.42554608,-2.58318223,50.5732,3.896810994,9.201573785,2.873125,-0.360382776,-2.620747515,66.95819397 +90.73,50.42554643,-2.583180935,50.5443,3.896810988,9.200241273,2.898125,-0.291010421,-2.684942165,66.95066892 +90.74,50.42554678,-2.583179641,50.5152,3.910715757,9.200241163,2.92125,-0.220533117,-2.74679548,66.9431438 +90.75,50.42554713,-2.583178346,50.4859,3.928096702,9.201129321,2.943125,-0.148965532,-2.806253545,66.93561875 +90.76,50.42554749,-2.583177051,50.4563,3.928096675,9.20112921,2.963125,-0.076322734,-2.863264507,66.92809363 +90.77,50.42554784,-2.583175756,50.4266,3.914191889,9.200018763,2.98125,-0.002619735,-2.917778691,66.92056858 +90.78,50.42554819,-2.583174462,50.3967,3.914191879,9.199130384,2.9984375,0.072127938,-2.969748484,66.91304347 +90.79,50.42554854,-2.583173167,50.3666,3.928096627,9.198908206,3.0146875,0.147904815,-3.01912868,66.90551841 +90.8,50.4255489,-2.583171873,50.3364,3.931572783,9.198686027,3.0296875,0.22469491,-3.065876077,66.8979933 +90.81,50.42554925,-2.583170578,50.306,3.928096562,9.197797646,3.043125,0.302482296,-3.109950053,66.89046824 +90.82,50.4255496,-2.583169284,50.2755,3.931572744,9.196465131,3.055,0.381250701,-3.151312048,66.88294313 +90.83,50.42554996,-2.58316799,50.2449,3.931572736,9.195576749,3.0665625,0.460983679,-3.189926081,66.87541807 +90.84,50.42555031,-2.583166696,50.2142,3.928096526,9.19535457,3.078125,0.541664559,-3.22575846,66.86789296 +90.85,50.42555066,-2.583165402,50.1833,3.931572701,9.195354457,3.0878125,0.623276496,-3.258777903,66.8603679 +90.86,50.42555102,-2.583164108,50.1524,3.931572691,9.195132278,3.094375,0.705802472,-3.288955647,66.85284279 +90.87,50.42555137,-2.583162814,50.1214,3.92809648,9.194243897,3.0984375,0.789225241,-3.316265394,66.84531773 +90.88,50.42555172,-2.58316152,50.0904,3.93157264,9.193133448,3.1015625,0.873527329,-3.340683309,66.83779262 +90.89,50.42555208,-2.583160227,50.0594,3.931572606,9.193133334,3.105,0.95869126,-3.362188076,66.83026757 +90.9,50.42555243,-2.583158933,50.0283,3.92809639,9.194021489,3.108125,1.044699101,-3.380760961,66.82274245 +90.91,50.42555278,-2.583157639,49.9972,3.935048766,9.194021377,3.1096875,1.131532975,-3.396385807,66.8152174 +90.92,50.42555314,-2.583156345,49.9661,3.945477334,9.192910928,3.1096875,1.219174719,-3.409048919,66.80769228 +90.93,50.42555349,-2.583155052,49.935,3.945477315,9.19180048,3.1078125,1.307606056,-3.418739297,66.80016723 +90.94,50.42555385,-2.583153758,49.9039,3.935048723,9.190690031,3.103125,1.396808538,-3.425448518,66.79264211 +90.95,50.4255542,-2.583152465,49.8729,3.928096329,9.189357515,3.0965625,1.486763427,-3.429170624,66.78511706 +90.96,50.42555455,-2.583151172,49.842,3.935048691,9.188469133,3.0903125,1.577452046,-3.42990252,66.77759195 +90.97,50.42555491,-2.583149879,49.8111,3.94547723,9.18846902,3.0846875,1.66885543,-3.427643462,66.77006689 +90.98,50.42555526,-2.583148586,49.7803,3.948953392,9.189135109,3.0778125,1.7609545,-3.422395398,66.76254183 +90.99,50.42555562,-2.583147293,49.7495,3.948953382,9.189357063,3.0678125,1.853729946,-3.414163026,66.75501672 +91,50.42555597,-2.583145999,49.7189,3.948953375,9.188246616,3.0546875,1.94716246,-3.40295345,66.74749166 +91.01,50.42555633,-2.583144707,49.6884,3.948953356,9.187136169,3.0403125,2.041232562,-3.388776412,66.73996655 +91.02,50.42555668,-2.583143414,49.6581,3.94895334,9.187136056,3.02625,2.135920541,-3.371644286,66.7324415 +91.03,50.42555704,-2.583142121,49.6279,3.94895333,9.186913876,3.0115625,2.231206631,-3.351572085,66.72491638 +91.04,50.42555739,-2.583140828,49.5978,3.948953309,9.185803429,2.9946875,2.32707095,-3.328577283,66.71739133 +91.05,50.42555775,-2.583139536,49.568,3.952429463,9.184692982,2.9765625,2.423493501,-3.302679877,66.70986621 +91.06,50.4255581,-2.583138243,49.5383,3.962858002,9.183804602,2.9584375,2.520454118,-3.273902499,66.70234116 +91.07,50.42555846,-2.583136951,49.5088,3.969810374,9.183360357,2.939375,2.617932573,-3.242270187,66.69481605 +91.08,50.42555882,-2.583135659,49.4795,3.962857995,9.183582314,2.9178125,2.715908471,-3.207810614,66.68729099 +91.09,50.42555917,-2.583134366,49.4504,3.952429411,9.183360136,2.8934375,2.814361356,-3.170553747,66.67976588 +91.1,50.42555953,-2.583133074,49.4216,3.952429384,9.18224969,2.868125,2.913270659,-3.13053213,66.67224082 +91.11,50.42555988,-2.583131782,49.3931,3.962857933,9.181361313,2.843125,3.012615811,-3.087780654,66.66471571 +91.12,50.42556024,-2.58313049,49.3647,3.969810296,9.181139136,2.8165625,3.112375956,-3.042336564,66.65719065 +91.13,50.4255606,-2.583129198,49.3367,3.966334087,9.181139026,2.7878125,3.212530354,-2.994239565,66.64966554 +91.14,50.42556095,-2.583127906,49.309,3.966334073,9.18091685,2.75875,3.313058034,-2.943531482,66.64214048 +91.15,50.42556131,-2.583126614,49.2815,3.969810256,9.180028475,2.7296875,3.413937968,-2.890256606,66.63461537 +91.16,50.42556167,-2.583125322,49.2544,3.966334057,9.178918032,2.699375,3.515149186,-2.834461403,66.62709031 +91.17,50.42556202,-2.583124031,49.2275,3.966334032,9.178695857,2.6665625,3.616670432,-2.776194517,66.6195652 +91.18,50.42556238,-2.583122739,49.201,3.969810185,9.178917817,2.63125,3.718480621,-2.715506713,66.61204014 +91.19,50.42556274,-2.583121447,49.1749,3.966333971,9.178473576,2.5953125,3.820558438,-2.652450989,66.60451503 +91.2,50.42556309,-2.583120156,49.1491,3.966333972,9.177585202,2.5596875,3.922882512,-2.587082234,66.59698998 +91.21,50.42556345,-2.583118864,49.1237,3.969810168,9.176696829,2.523125,4.025431587,-2.519457515,66.58946486 +91.22,50.42556381,-2.583117573,49.0986,3.966333964,9.176030523,2.485,4.128184176,-2.449635847,66.58193981 +91.23,50.42556416,-2.583116282,49.074,3.969810127,9.175586285,2.44625,4.231118794,-2.37767802,66.57441469 +91.24,50.42556452,-2.58311499,49.0497,3.983714862,9.175142047,2.4065625,4.334214012,-2.303646831,66.56688964 +91.25,50.42556488,-2.5831137,49.0258,3.983714843,9.175141944,2.3646875,4.437448287,-2.227606794,66.55936453 +91.26,50.42556524,-2.583112408,49.0024,3.969810074,9.175363908,2.3215625,4.540800019,-2.149624316,66.55183947 +91.27,50.42556559,-2.583111117,48.9794,3.969810071,9.174697605,2.2784375,4.644247663,-2.069767292,66.54431436 +91.28,50.42556595,-2.583109826,48.9568,3.987191014,9.173143034,2.2346875,4.74776962,-1.988105394,66.5367893 +91.29,50.42556631,-2.583108535,48.9347,4.001095765,9.171810531,2.1896875,4.851344232,-1.90470984,66.52926419 +91.3,50.42556667,-2.583107245,48.913,4.001095752,9.171588363,2.143125,4.954949841,-1.819653338,66.52173913 +91.31,50.42556703,-2.583105954,48.8918,3.987190963,9.171810331,2.095,5.058564904,-1.733010145,66.51421402 +91.32,50.42556739,-2.583104663,48.8711,3.969809985,9.171366098,2.0465625,5.162167763,-1.644855661,66.50668896 +91.33,50.42556774,-2.583103373,48.8509,3.969809983,9.170477732,1.998125,5.265736702,-1.555266891,66.49916391 +91.34,50.4255681,-2.583102082,48.8311,3.987190943,9.169589367,1.9484375,5.36925018,-1.464321873,66.49163879 +91.35,50.42556846,-2.583100792,48.8119,4.00109569,9.169145137,1.8978125,5.472686537,-1.372099962,66.48411374 +91.36,50.42556882,-2.583099502,48.7932,4.004571847,9.169367107,1.846875,5.576024174,-1.278681542,66.47658862 +91.37,50.42556918,-2.583098211,48.7749,4.004571829,9.169144944,1.7946875,5.679241546,-1.18414809,66.46906357 +91.38,50.42556954,-2.583096921,48.7573,4.004571836,9.168034514,1.7415625,5.782316997,-1.088582053,66.46153846 +91.39,50.4255699,-2.583095631,48.7401,4.001095654,9.166924086,1.6884375,5.885229156,-0.992066739,66.4540134 +91.4,50.42557026,-2.583094341,48.7235,3.98719088,9.166035725,1.634375,5.987956363,-0.894686374,66.44648829 +91.41,50.42557062,-2.583093051,48.7074,3.969809894,9.165591499,1.5784375,6.090477306,-0.796525812,66.43896323 +91.42,50.42557097,-2.583091762,48.6919,3.969809867,9.165813474,1.5215625,6.192770497,-0.697670654,66.43143812 +91.43,50.42557133,-2.583090471,48.677,3.98719082,9.165591317,1.465,6.294814624,-0.598207128,66.42391306 +91.44,50.42557169,-2.583089182,48.6626,4.001095598,9.164480892,1.408125,6.396588315,-0.498221925,66.41638795 +91.45,50.42557205,-2.583087892,48.6488,4.004571788,9.163592535,1.3496875,6.498070314,-0.397802305,66.40886289 +91.46,50.42557241,-2.583086603,48.6356,4.004571762,9.16337038,1.2903125,6.599239534,-0.29703576,66.40133778 +91.47,50.42557277,-2.583085313,48.623,4.004571736,9.163370293,1.2315625,6.70007472,-0.196010237,66.39381272 +91.48,50.42557313,-2.583084024,48.611,4.004571736,9.163148139,1.1734375,6.800554902,-0.094813743,66.38628761 +91.49,50.42557349,-2.583082734,48.5995,4.004571751,9.162259786,1.1146875,6.900658994,0.00646537,66.37876256 +91.5,50.42557385,-2.583081445,48.5887,4.008047942,9.161149366,1.0546875,7.000366255,0.107738927,66.37123744 +91.51,50.42557421,-2.583080156,48.5784,4.021952683,9.161149281,0.9934375,7.099655716,0.20891846,66.36371239 +91.52,50.42557457,-2.583078867,48.5688,4.039333615,9.161815398,0.93125,7.198506692,0.309915851,66.35618727 +91.53,50.42557494,-2.583077577,48.5598,4.039333616,9.160927048,0.86875,7.296898499,0.410642977,66.34866222 +91.54,50.4255753,-2.583076288,48.5514,4.021952678,9.158706297,0.8065625,7.394810684,0.511012005,66.34113711 +91.55,50.42557566,-2.583075,48.5437,4.008047915,9.157817948,0.7446875,7.492222734,0.610935443,66.33361205 +91.56,50.42557602,-2.583073711,48.5365,4.004571702,9.158484069,0.681875,7.589114309,0.710326145,66.32608694 +91.57,50.42557638,-2.583072422,48.53,4.004571681,9.15848399,0.618125,7.685465184,0.809097423,66.31856188 +91.58,50.42557674,-2.583071133,48.5242,4.004571684,9.157373578,0.5553125,7.78125519,0.90716316,66.31103677 +91.59,50.4255771,-2.583069845,48.5189,4.004571703,9.156485233,0.493125,7.876464389,1.004437815,66.30351171 +91.6,50.42557746,-2.583068556,48.5143,4.008047898,9.15626309,0.4296875,7.971072899,1.100836589,66.2959866 +91.61,50.42557782,-2.583067268,48.5103,4.021952642,9.156263015,0.365,8.065060953,1.196275429,66.28846154 +91.62,50.42557818,-2.583065979,48.507,4.039333578,9.156262941,0.3,8.158408898,1.290671085,66.28093643 +91.63,50.42557855,-2.583064691,48.5043,4.039333583,9.1560408,0.2353125,8.251097198,1.383941281,66.27341137 +91.64,50.42557891,-2.583063402,48.5023,4.021952649,9.155152459,0.1715625,8.343106599,1.476004655,66.26588626 +91.65,50.42557927,-2.583062114,48.5009,4.011524082,9.153819986,0.108125,8.434417852,1.566780879,66.2583612 +91.66,50.42557963,-2.583060826,48.5001,4.021952637,9.152931648,0.043125,8.525011818,1.656190886,66.25083615 +91.67,50.42557999,-2.583059538,48.5,4.039333575,9.152487444,-0.023125,8.614869649,1.744156695,66.24331104 +91.68,50.42558036,-2.58305825,48.5006,4.039333582,9.151599108,-0.088125,8.70397255,1.830601531,66.23578598 +91.69,50.42558072,-2.583056962,48.5018,4.025428839,9.150488705,-0.1515625,8.792301958,1.915450106,66.22826087 +91.7,50.42558108,-2.583055675,48.5036,4.02542884,9.150488638,-0.215,8.879839367,1.998628337,66.22073581 +91.71,50.42558144,-2.583054387,48.5061,4.039333586,9.151376839,-0.2784375,8.966566556,2.080063745,66.2132107 +91.72,50.42558181,-2.583053099,48.5092,4.042809773,9.151154706,-0.3415625,9.052465305,2.159685341,66.20568564 +91.73,50.42558217,-2.583051811,48.5129,4.039333602,9.149378106,-0.4053125,9.137517796,2.237423624,66.19816053 +91.74,50.42558253,-2.583050524,48.5173,4.042809814,9.148045641,-0.47,9.221706266,2.313210814,66.19063547 +91.75,50.4255829,-2.583049237,48.5223,4.042809811,9.148045578,-0.5346875,9.305013012,2.386980906,66.18311036 +91.76,50.42558326,-2.583047949,48.528,4.039333602,9.14782345,-0.5984375,9.38742073,2.4586695,66.1755853 +91.77,50.42558362,-2.583046662,48.5343,4.04280979,9.146713055,-0.6615625,9.46891223,2.528214086,66.16806019 +91.78,50.42558399,-2.583045375,48.5412,4.04280981,9.145824727,-0.725,9.549470383,2.595553988,66.16053514 +91.79,50.42558435,-2.583044088,48.5488,4.039333635,9.145602601,-0.788125,9.629078514,2.660630591,66.15301002 +91.8,50.42558471,-2.583042801,48.557,4.042809823,9.145602542,-0.8496875,9.707719893,2.72338706,66.14548497 +91.81,50.42558508,-2.583041514,48.5658,4.042809818,9.145602485,-0.91,9.785378077,2.783768733,66.13795985 +91.82,50.42558544,-2.583040227,48.5752,4.039333635,9.145380362,-0.9703125,9.862036965,2.841722841,66.1304348 +91.83,50.4255858,-2.58303894,48.5852,4.046286031,9.144492039,-1.0315625,9.937680458,2.897198964,66.12290968 +91.84,50.42558617,-2.583037653,48.5958,4.056714613,9.143159582,-1.093125,10.01229274,2.950148744,66.11538463 +91.85,50.42558653,-2.583036367,48.6071,4.056714621,9.14227126,-1.1534375,10.08585829,3.000525886,66.10785952 +91.86,50.4255869,-2.58303508,48.6189,4.046286053,9.14204914,-1.213125,10.15836174,3.048286502,66.10033446 +91.87,50.42558726,-2.583033794,48.6313,4.03933367,9.142049089,-1.2734375,10.22978792,3.093389052,66.09280935 +91.88,50.42558762,-2.583032507,48.6444,4.046286052,9.142049037,-1.3328125,10.30012193,3.135794059,66.08528429 +91.89,50.42558799,-2.583031221,48.658,4.056714643,9.141826919,-1.3896875,10.3693491,3.175464626,66.07775918 +91.9,50.42558835,-2.583029934,48.6722,4.060190863,9.140938602,-1.4453125,10.43745493,3.212366087,66.07023412 +91.91,50.42558872,-2.583028648,48.6869,4.060190873,9.139606152,-1.5015625,10.50442521,3.246466415,66.06270901 +91.92,50.42558908,-2.583027362,48.7022,4.060190863,9.138717836,-1.5584375,10.57024597,3.277735701,66.05518395 +91.93,50.42558945,-2.583026076,48.7181,4.060190867,9.138495722,-1.6146875,10.63490346,3.306146788,66.04765884 +91.94,50.42558981,-2.58302479,48.7345,4.060190893,9.138495675,-1.6696875,10.69838415,3.331674865,66.04013378 +91.95,50.42559018,-2.583023504,48.7515,4.060190915,9.138495629,-1.7234375,10.76067486,3.354297645,66.03260867 +91.96,50.42559054,-2.583022218,48.769,4.060190918,9.138273516,-1.7765625,10.82176247,3.373995418,66.02508362 +91.97,50.42559091,-2.583020932,48.787,4.060190918,9.137385204,-1.8296875,10.88163427,3.390751054,66.0175585 +91.98,50.42559127,-2.583019646,48.8056,4.06019093,9.13605276,-1.8815625,10.94027782,3.404549883,66.01003345 +91.99,50.42559164,-2.583018361,48.8247,4.063667134,9.135164449,-1.9315625,10.9976808,3.415379931,66.00250833 +92,50.425592,-2.583017075,48.8442,4.074095721,9.13494234,-1.9815625,11.05383123,3.423231687,65.99498328 +92.01,50.42559237,-2.58301579,48.8643,4.081048127,9.134720232,-2.0315625,11.10871738,3.428098333,65.98745822 +92.02,50.42559274,-2.583014504,48.8849,4.074095767,9.13405399,-2.0796875,11.16232784,3.42997563,65.97993311 +92.03,50.4255931,-2.583013219,48.9059,4.063667196,9.133609815,-2.1265625,11.21465138,3.428861914,65.97240805 +92.04,50.42559347,-2.583011934,48.9274,4.063667194,9.133609776,-2.1734375,11.26567705,3.424758219,65.96488294 +92.05,50.42559383,-2.583010648,48.9494,4.074095789,9.132499403,-2.2196875,11.3153942,3.417668095,65.95735788 +92.06,50.4255942,-2.583009363,48.9718,4.081048206,9.130500763,-2.2646875,11.36379246,3.407597674,65.94983277 +92.07,50.42559457,-2.583008079,48.9947,4.07757203,9.130278658,-2.308125,11.41086175,3.39455578,65.94230772 +92.08,50.42559493,-2.583006794,49.018,4.077572025,9.131388955,-2.35,11.4565922,3.378553813,65.9347826 +92.09,50.4255953,-2.583005508,49.0417,4.081048225,9.131166851,-2.3915625,11.50097426,3.359605641,65.92725755 +92.1,50.42559567,-2.583004224,49.0658,4.077572065,9.130056481,-2.433125,11.54399869,3.337727878,65.91973243 +92.11,50.42559603,-2.583002939,49.0904,4.081048283,9.129168178,-2.473125,11.5856565,3.312939603,65.91220738 +92.12,50.4255964,-2.583001654,49.1153,4.094953056,9.127835742,-2.51125,11.62593893,3.285262361,65.90468226 +92.13,50.42559677,-2.58300037,49.1406,4.09495306,9.12694744,-2.5484375,11.66483767,3.254720273,65.89715721 +92.14,50.42559714,-2.582999086,49.1663,4.081048304,9.127835674,-2.5846875,11.70234452,3.221340096,65.8896321 +92.15,50.4255975,-2.582997801,49.1923,4.081048317,9.128723908,-2.6196875,11.73845169,3.185150821,65.88210704 +92.16,50.42559787,-2.582996516,49.2187,4.094953104,9.127613541,-2.6534375,11.77315161,3.146184076,65.87458193 +92.17,50.42559824,-2.582995232,49.2454,4.094953139,9.125614907,-2.68625,11.80643702,3.10447378,65.86705687 +92.18,50.42559861,-2.582993948,49.2724,4.081048402,9.12450454,-2.7184375,11.83830104,3.060056373,65.85953176 +92.19,50.42559897,-2.582992664,49.2998,4.081048411,9.124282441,-2.7496875,11.86873696,3.012970529,65.8520067 +92.2,50.42559934,-2.58299138,49.3274,4.094953182,9.12428241,-2.7796875,11.89773842,2.96325733,65.84448159 +92.21,50.42559971,-2.582990096,49.3554,4.094953193,9.12428238,-2.808125,11.92529935,2.910960092,65.83695653 +92.22,50.42560008,-2.582988812,49.3836,4.081048443,9.124060283,-2.8346875,11.95141402,2.856124536,65.82943142 +92.23,50.42560044,-2.582987528,49.4121,4.081048473,9.123171986,-2.86,11.97607705,2.798798332,65.82190636 +92.24,50.42560081,-2.582986244,49.4408,4.098429469,9.121839555,-2.8846875,11.99928316,2.739031558,65.81438125 +92.25,50.42560118,-2.582984961,49.4698,4.112334254,9.120951258,-2.908125,12.02102754,2.676876294,65.8068562 +92.26,50.42560155,-2.582983677,49.499,4.115810445,9.120729162,-2.93,12.04130572,2.612386743,65.79933108 +92.27,50.42560192,-2.582982394,49.5284,4.112334262,9.120729133,-2.95125,12.06011334,2.545619169,65.79180603 +92.28,50.42560229,-2.58298111,49.558,4.098429517,9.120507037,-2.9715625,12.07744663,2.476631785,65.78428091 +92.29,50.42560266,-2.582979827,49.5879,4.081048584,9.119618742,-2.9896875,12.09330187,2.40548475,65.77675586 +92.3,50.42560302,-2.582978543,49.6178,4.081048617,9.11850838,-3.0065625,12.10767572,2.332240118,65.76923074 +92.31,50.42560339,-2.582977261,49.648,4.098429604,9.118286286,-3.023125,12.12056526,2.256961657,65.76170569 +92.32,50.42560376,-2.582975977,49.6783,4.11233438,9.118508324,-3.0378125,12.13196775,2.179715143,65.75418058 +92.33,50.42560413,-2.582974694,49.7088,4.115810576,9.117842095,-3.05,12.14188078,2.100567899,65.74665552 +92.34,50.4256045,-2.582973411,49.7393,4.1158106,9.116287601,-3.0615625,12.15030234,2.019588909,65.73913041 +92.35,50.42560487,-2.582972128,49.77,4.115810634,9.114955173,-3.073125,12.15723072,1.936848819,65.73160535 +92.36,50.42560524,-2.582970846,49.8008,4.115810651,9.114955146,-3.0828125,12.16266431,1.852419763,65.7240803 +92.37,50.42560561,-2.582969563,49.8317,4.115810661,9.115843386,-3.0896875,12.16660213,1.766375311,65.71655518 +92.38,50.42560598,-2.58296828,49.8626,4.115810674,9.115621292,-3.095,12.16904328,1.678790633,65.70903013 +92.39,50.42560635,-2.582966997,49.8936,4.11581069,9.113844731,-3.1,12.16998728,1.589741991,65.70150501 +92.4,50.42560672,-2.582965715,49.9246,4.115810713,9.112734371,-3.1046875,12.16943386,1.499307077,65.69397996 +92.41,50.42560709,-2.582964433,49.9557,4.115810744,9.113622611,-3.108125,12.16738325,1.407564732,65.68645484 +92.42,50.42560746,-2.58296315,49.9868,4.115810773,9.114510851,-3.1096875,12.16383584,1.314594995,65.67892979 +92.43,50.42560783,-2.582961867,50.0179,4.115810793,9.11340049,-3.1096875,12.15879232,1.220478885,65.67140468 +92.44,50.4256082,-2.582960585,50.049,4.115810805,9.111401862,-3.108125,12.15225378,1.125298506,65.66387962 +92.45,50.42560857,-2.582959303,50.0801,4.115810814,9.110291501,-3.1046875,12.1442216,1.029136879,65.65635451 +92.46,50.42560894,-2.582958021,50.1111,4.115810837,9.110069408,-3.1,12.13469744,0.932077829,65.64882945 +92.47,50.42560931,-2.582956739,50.1421,4.119287067,9.109847314,-3.095,12.12368324,0.834205923,65.64130434 +92.48,50.42560968,-2.582955457,50.173,4.133191866,9.10895902,-3.089375,12.11118142,0.735606648,65.63377928 +92.49,50.42561005,-2.582954175,50.2039,4.150572838,9.107848658,-3.0815625,12.09719448,0.636365888,65.62625417 +92.5,50.42561043,-2.582952894,50.2347,4.150572844,9.107626563,-3.07125,12.08172543,0.53657022,65.61872911 +92.51,50.4256108,-2.582951612,50.2653,4.133191898,9.107626536,-3.06,12.06477739,0.436306616,65.611204 +92.52,50.42561117,-2.58295033,50.2959,4.119287145,9.106516175,-3.048125,12.04635399,0.335662626,65.60367894 +92.53,50.42561154,-2.582949049,50.3263,4.115810975,9.105405813,-3.0346875,12.02645906,0.234725854,65.59615383 +92.54,50.42561191,-2.582947768,50.3566,4.119287198,9.105405785,-3.02,12.00509673,0.133584422,65.58862878 +92.55,50.42561228,-2.582946486,50.3867,4.133191995,9.105405757,-3.0046875,11.98227147,0.032326508,65.58110366 +92.56,50.42561265,-2.582945205,50.4167,4.150572976,9.105183661,-2.9878125,11.95798803,-0.068959596,65.57357861 +92.57,50.42561303,-2.582943924,50.4465,4.150572986,9.105405699,-2.968125,11.93225157,-0.170185539,65.56605349 +92.58,50.4256134,-2.582942642,50.4761,4.133192034,9.105183602,-2.946875,11.90506735,-0.271263144,65.55852844 +92.59,50.42561377,-2.582941361,50.5054,4.122763475,9.104073239,-2.9265625,11.87644106,-0.372104174,65.55100332 +92.6,50.42561414,-2.58294008,50.5346,4.133192075,9.103184942,-2.90625,11.84637877,-0.472620681,65.54347827 +92.61,50.42561451,-2.582938799,50.5636,4.150573062,9.102740778,-2.8828125,11.81488672,-0.572725117,65.53595316 +92.62,50.42561489,-2.582937518,50.5923,4.150573091,9.10185248,-2.8565625,11.78197144,-0.672330105,65.5284281 +92.63,50.42561526,-2.582936237,50.6207,4.136668343,9.100520049,-2.83,11.74763981,-0.771348786,65.52090299 +92.64,50.42561563,-2.582934957,50.6489,4.136668349,9.099631751,-2.803125,11.71189905,-0.869694872,65.51337793 +92.65,50.425616,-2.582933676,50.6768,4.150573128,9.099409652,-2.7746875,11.6747566,-0.967282533,65.50585282 +92.66,50.42561638,-2.582932396,50.7044,4.154049338,9.099187553,-2.745,11.6362202,-1.064026743,65.49832776 +92.67,50.42561675,-2.582931115,50.7317,4.150573164,9.09852132,-2.7146875,11.59629788,-1.159843106,65.49080265 +92.68,50.42561712,-2.582929835,50.7587,4.154049383,9.098077153,-2.683125,11.55499805,-1.254648083,65.48327759 +92.69,50.4256175,-2.582928555,50.7854,4.154049414,9.098299186,-2.6496875,11.51232925,-1.34835894,65.47575248 +92.7,50.42561787,-2.582927274,50.8117,4.150573234,9.098077086,-2.6146875,11.46830048,-1.44089403,65.46822742 +92.71,50.42561824,-2.582925994,50.8377,4.154049426,9.096966717,-2.5784375,11.42292091,-1.532172681,65.46070237 +92.72,50.42561862,-2.582924714,50.8633,4.154049434,9.096078415,-2.5415625,11.37619992,-1.622115195,65.45317726 +92.73,50.42561899,-2.582923434,50.8885,4.150573263,9.095634245,-2.5046875,11.32814738,-1.710643248,65.4456522 +92.74,50.42561936,-2.582922154,50.9134,4.154049479,9.094745942,-2.4665625,11.27877332,-1.797679548,65.43812709 +92.75,50.42561974,-2.582920874,50.9379,4.154049501,9.093635572,-2.42625,11.22808798,-1.883148292,65.43060203 +92.76,50.42562011,-2.582919595,50.9619,4.150573336,9.093635534,-2.385,11.17610197,-1.966974825,65.42307692 +92.77,50.42562048,-2.582918315,50.9856,4.157525739,9.094523763,-2.3434375,11.12282618,-2.049086209,65.41555186 +92.78,50.42562086,-2.582917035,51.0088,4.167954318,9.094523725,-2.30125,11.06827172,-2.129410709,65.40802675 +92.79,50.42562123,-2.582915755,51.0316,4.171430517,9.093191285,-2.258125,11.01244999,-2.207878368,65.40050169 +92.8,50.42562161,-2.582914476,51.054,4.171430532,9.091414711,-2.213125,10.95537262,-2.284420716,65.39297658 +92.81,50.42562198,-2.582913196,51.0759,4.167954354,9.090082269,-2.1665625,10.89705153,-2.358971005,65.38545152 +92.82,50.42562236,-2.582911918,51.0973,4.1575258,9.089860161,-2.12,10.83749893,-2.431464204,65.37792641 +92.83,50.42562273,-2.582910638,51.1183,4.150573442,9.090082186,-2.073125,10.77672724,-2.501837172,65.37040136 +92.84,50.4256231,-2.582909359,51.1388,4.157525836,9.08963801,-2.0246875,10.7147492,-2.570028489,65.36287624 +92.85,50.42562348,-2.58290808,51.1588,4.167954409,9.088971766,-1.9746875,10.65157762,-2.635978739,65.35535119 +92.86,50.42562385,-2.582906801,51.1783,4.171430606,9.088749656,-1.9234375,10.58722587,-2.699630339,65.34782607 +92.87,50.42562423,-2.582905522,51.1973,4.171430623,9.088527544,-1.8715625,10.52170722,-2.760927828,65.34030102 +92.88,50.4256246,-2.582904243,51.2157,4.171430642,9.087639231,-1.82,10.45503551,-2.819817747,65.3327759 +92.89,50.42562498,-2.582902964,51.2337,4.174906853,9.086306784,-1.768125,10.38722452,-2.876248705,65.32525085 +92.9,50.42562535,-2.582901686,51.2511,4.185335454,9.08541847,-1.7146875,10.31828853,-2.930171596,65.31772574 +92.91,50.42562573,-2.582900407,51.268,4.192287853,9.085418422,-1.6603125,10.24824186,-2.981539325,65.31020068 +92.92,50.42562611,-2.582899129,51.2843,4.185335465,9.086084573,-1.60625,10.17709912,-3.030307086,65.30267557 +92.93,50.42562648,-2.58289785,51.3001,4.174906889,9.086306591,-1.5515625,10.10487527,-3.076432366,65.29515051 +92.94,50.42562686,-2.582896571,51.3154,4.174906899,9.08497414,-1.4946875,10.03158532,-3.119874943,65.2876254 +92.95,50.42562723,-2.582895293,51.33,4.185335483,9.083197555,-1.436875,9.95724456,-3.160596944,65.28010034 +92.96,50.42562761,-2.582894015,51.3441,4.192287873,9.082753369,-1.38,9.881868582,-3.198562904,65.27257523 +92.97,50.42562799,-2.582892737,51.3576,4.185335506,9.082753316,-1.323125,9.805473082,-3.233739647,65.26505017 +92.98,50.42562836,-2.582891458,51.3706,4.174906954,9.081642929,-1.2646875,9.72807399,-3.266096522,65.25752506 +92.99,50.42562874,-2.582890181,51.3829,4.174906967,9.080532541,-1.205,9.649687519,-3.295605281,65.25 +93,50.42562911,-2.582888903,51.3947,4.185335538,9.080754552,-1.145,9.57033,-3.322240255,65.24247489 +93.01,50.42562949,-2.582887625,51.4058,4.192287915,9.08119863,-1.0846875,9.490018047,-3.345978183,65.23494984 +93.02,50.42562987,-2.582886347,51.4164,4.188811727,9.080532373,-1.0234375,9.408768392,-3.366798324,65.22742472 +93.03,50.42563024,-2.582885069,51.4263,4.192287934,9.079199914,-0.9615625,9.326598051,-3.384682628,65.21989967 +93.04,50.42563062,-2.582883792,51.4356,4.206192717,9.078311588,-0.9003125,9.243524155,-3.399615398,65.21237455 +93.05,50.425631,-2.582882514,51.4443,4.206192728,9.078089461,-0.8396875,9.159564066,-3.411583684,65.2048495 +93.06,50.42563138,-2.582881237,51.4524,4.192287967,9.077867334,-0.778125,9.074735258,-3.420577002,65.19732444 +93.07,50.42563175,-2.582879959,51.4599,4.188811779,9.076979006,-0.715,8.989055493,-3.426587558,65.18979933 +93.08,50.42563213,-2.582878682,51.4667,4.192287972,9.075646542,-0.6515625,8.902542705,-3.429610025,65.18227427 +93.09,50.42563251,-2.582877405,51.4729,4.18881178,9.074980278,-0.5884375,8.815214884,-3.429641824,65.17474916 +93.1,50.42563288,-2.582876128,51.4785,4.19228797,9.075646414,-0.525,8.727090366,-3.426682956,65.1672241 +93.11,50.42563326,-2.582874851,51.4834,4.20966893,9.076534617,-0.4615625,8.638187427,-3.420735998,65.15969899 +93.12,50.42563364,-2.582873573,51.4877,4.220097514,9.075646284,-0.398125,8.548524746,-3.411806049,65.15217394 +93.13,50.42563402,-2.582872296,51.4914,4.209668954,9.07342555,-0.3334375,8.458120944,-3.39990096,65.14464882 +93.14,50.4256344,-2.58287102,51.4944,4.192288008,9.072315148,-0.268125,8.366994986,-3.385031101,65.13712377 +93.15,50.42563477,-2.582869743,51.4967,4.192288005,9.072315079,-0.20375,8.275165894,-3.367209478,65.12959865 +93.16,50.42563515,-2.582868466,51.4985,4.209668953,9.072092942,-0.14,8.182652805,-3.346451618,65.1220736 +93.17,50.42563553,-2.58286719,51.4995,4.223573716,9.071870804,-0.07625,8.089475085,-3.32277557,65.11454848 +93.18,50.42563591,-2.582865913,51.5,4.223573721,9.071204532,-0.011875,7.995652158,-3.296201959,65.10702343 +93.19,50.42563629,-2.582864636,51.4998,4.209668954,9.069649993,0.0534375,7.901203618,-3.266754106,65.09949832 +93.2,50.42563667,-2.582863361,51.4989,4.192287986,9.068983719,0.118125,7.806149175,-3.234457564,65.09197326 +93.21,50.42563704,-2.582862084,51.4974,4.192287981,9.069871912,0.1815625,7.710508768,-3.199340465,65.08444815 +93.22,50.42563742,-2.582860808,51.4953,4.209668952,9.070538037,0.2453125,7.614302221,-3.161433577,65.07692309 +93.23,50.4256378,-2.582859531,51.4925,4.223573739,9.069649693,0.31,7.51754976,-3.120769845,65.06939798 +93.24,50.42563818,-2.582858255,51.4891,4.227049934,9.067428948,0.3746875,7.420271553,-3.077384736,65.06187292 +93.25,50.42563856,-2.582856979,51.485,4.227049916,9.065430269,0.4384375,7.322487883,-3.031316122,65.05434781 +93.26,50.42563894,-2.582855704,51.4803,4.227049898,9.064986057,0.5015625,7.224219204,-2.98260411,65.04682275 +93.27,50.42563932,-2.582854428,51.475,4.22704989,9.065208044,0.565,7.125486028,-2.93129127,65.03929764 +93.28,50.4256397,-2.582853152,51.469,4.227049887,9.064985896,0.6284375,7.026308925,-2.877422294,65.03177258 +93.29,50.42564008,-2.582851877,51.4624,4.227049885,9.064985814,0.69125,6.926708692,-2.821044164,65.02424747 +93.3,50.42564046,-2.582850601,51.4552,4.227049889,9.064985731,0.7534375,6.826706128,-2.762206039,65.01672242 +93.31,50.42564084,-2.582849325,51.4473,4.227049898,9.063875314,0.8153125,6.726322032,-2.700959257,65.0091973 +93.32,50.42564122,-2.58284805,51.4389,4.227049899,9.062764896,0.878125,6.62557743,-2.63735716,65.00167225 +93.33,50.4256416,-2.582846775,51.4298,4.227049886,9.062764811,0.9415625,6.524493294,-2.571455268,64.99414713 +93.34,50.42564198,-2.582845499,51.42,4.227049867,9.062542657,1.0028125,6.423090879,-2.503310991,64.98662208 +93.35,50.42564236,-2.582844224,51.4097,4.227049852,9.061432236,1.061875,6.321391215,-2.432983802,64.97909696 +93.36,50.42564274,-2.582842949,51.3988,4.227049845,9.060543882,1.121875,6.219415613,-2.360535065,64.97157191 +93.37,50.42564312,-2.582841674,51.3873,4.227049844,9.060321726,1.183125,6.117185332,-2.286027863,64.9640468 +93.38,50.4256435,-2.582840399,51.3751,4.227049841,9.060321637,1.243125,6.014721743,-2.209527226,64.95652174 +93.39,50.42564388,-2.582839124,51.3624,4.227049828,9.060099479,1.30125,5.912046216,-2.131099846,64.94899668 +93.4,50.42564426,-2.582837849,51.3491,4.227049815,9.059211121,1.35875,5.809180296,-2.050814078,64.94147157 +93.41,50.42564464,-2.582836574,51.3352,4.227049815,9.057878629,1.41625,5.706145353,-1.968739993,64.93394651 +93.42,50.42564502,-2.5828353,51.3208,4.227049823,9.056990269,1.4734375,5.60296293,-1.884949156,64.9264214 +93.43,50.4256454,-2.582834025,51.3057,4.230526011,9.056768109,1.53,5.499654572,-1.799514617,64.91889635 +93.44,50.42564578,-2.582832751,51.2902,4.244430756,9.056768014,1.58625,5.396241878,-1.712510861,64.91137123 +93.45,50.42564616,-2.582831476,51.274,4.261811693,9.056767919,1.641875,5.292746449,-1.624013805,64.90384618 +93.46,50.42564655,-2.582830202,51.2573,4.261811678,9.056323688,1.69625,5.189189885,-1.534100513,64.89632106 +93.47,50.42564693,-2.582828927,51.2401,4.244430703,9.054769123,1.75,5.085593787,-1.442849535,64.88879601 +93.48,50.42564731,-2.582827653,51.2223,4.230525921,9.053214559,1.803125,4.98197987,-1.350340343,64.8812709 +93.49,50.42564769,-2.58282638,51.204,4.230525912,9.053436527,1.8546875,4.878369677,-1.256653607,64.87374584 +93.5,50.42564807,-2.582825105,51.1852,4.244430679,9.054102628,1.905,4.774784867,-1.16187109,64.86622073 +93.51,50.42564845,-2.582823831,51.1659,4.26181164,9.052992195,1.955,4.671247096,-1.066075354,64.85869567 +93.52,50.42564884,-2.582822557,51.1461,4.261811629,9.05121556,2.005,4.567778023,-0.969350051,64.85117056 +93.53,50.42564922,-2.582821284,51.1258,4.244430649,9.050771325,2.0546875,4.464399133,-0.871779407,64.8436455 +93.54,50.4256496,-2.58282001,51.105,4.234002053,9.050993289,2.103125,4.361132142,-0.773448562,64.83612039 +93.55,50.42564998,-2.582818736,51.0837,4.24443061,9.050549053,2.1496875,4.257998593,-0.674443288,64.82859533 +93.56,50.42565036,-2.582817463,51.062,4.261811552,9.049660683,2.195,4.155019972,-0.574849874,64.82107022 +93.57,50.42565075,-2.582816189,51.0398,4.265287728,9.048772313,2.24,4.052217822,-0.474755178,64.81354516 +93.58,50.42565113,-2.582814916,51.0172,4.26181152,9.048328074,2.2846875,3.949613629,-0.374246521,64.80602005 +93.59,50.42565151,-2.582813643,50.9941,4.265287698,9.048550035,2.3284375,3.847228763,-0.273411449,64.798495 +93.6,50.4256519,-2.582812369,50.9706,4.261811492,9.048327862,2.37125,3.745084655,-0.172338027,64.79096988 +93.61,50.42565228,-2.582811096,50.9467,4.247906715,9.047217422,2.413125,3.643202618,-0.071114261,64.78344483 +93.62,50.42565266,-2.582809823,50.9223,4.24790671,9.046329048,2.453125,3.541603966,0.030171442,64.77591971 +93.63,50.42565304,-2.58280855,50.8976,4.261811466,9.046106873,2.49125,3.44030984,0.131430903,64.76839466 +93.64,50.42565343,-2.582807277,50.8725,4.265287638,9.045884698,2.5284375,3.339341441,0.232575716,64.76086954 +93.65,50.42565381,-2.582806004,50.847,4.261811424,9.044996323,2.565,3.238719797,0.333517759,64.75334449 +93.66,50.42565419,-2.582804731,50.8212,4.268763785,9.043885881,2.60125,3.138466048,0.434168911,64.74581938 +93.67,50.42565458,-2.582803459,50.795,4.279192338,9.043663704,2.6365625,3.038601051,0.534441509,64.73829432 +93.68,50.42565496,-2.582802186,50.7684,4.279192319,9.043663593,2.6696875,2.939145605,0.634248065,64.73076921 +93.69,50.42565535,-2.582800913,50.7416,4.268763724,9.042553148,2.7015625,2.840120622,0.733501543,64.72324415 +93.7,50.42565573,-2.582799641,50.7144,4.261811321,9.041442703,2.7334375,2.741546671,0.832115372,64.71571904 +93.71,50.42565611,-2.582798369,50.6869,4.26876369,9.041442591,2.7646875,2.643444321,0.930003607,64.70819398 +93.72,50.4256565,-2.582797096,50.6591,4.279192257,9.041220412,2.7946875,2.5458342,1.02708082,64.70066887 +93.73,50.42565688,-2.582795824,50.631,4.282668442,9.040109966,2.8228125,2.448736532,1.123262443,64.69314381 +93.74,50.42565727,-2.582794552,50.6026,4.282668423,9.039221586,2.848125,2.352171658,1.218464595,64.68561876 +93.75,50.42565765,-2.58279328,50.574,4.279192201,9.038999406,2.8715625,2.256159802,1.312604196,64.67809364 +93.76,50.42565804,-2.582792008,50.5452,4.268763597,9.038999292,2.8953125,2.160720904,1.405599143,64.67056859 +93.77,50.42565842,-2.582790736,50.5161,4.261811191,9.038999178,2.9196875,2.065875018,1.497368475,64.66304348 +93.78,50.4256588,-2.582789464,50.4868,4.268763556,9.038776997,2.9428125,1.971641853,1.587831979,64.65551842 +93.79,50.42565919,-2.582788192,50.4572,4.279192113,9.03766655,2.9628125,1.878041118,1.676910931,64.64799331 +93.8,50.42565957,-2.58278692,50.4275,4.282668285,9.035667835,2.98,1.785092352,1.764527579,64.64046825 +93.81,50.42565996,-2.582785649,50.3976,4.286144458,9.034335319,2.996875,1.692814978,1.85060555,64.63294314 +93.82,50.42566034,-2.582784378,50.3676,4.296573014,9.034335203,3.0146875,1.601228305,1.935069785,64.62541808 +93.83,50.42566073,-2.582783106,50.3373,4.303525381,9.034335087,3.03125,1.510351355,2.017846544,64.61789297 +93.84,50.42566112,-2.582781835,50.3069,4.296572985,9.034112904,3.044375,1.420203206,2.098863751,64.61036791 +93.85,50.4256615,-2.582780564,50.2764,4.2861444,9.034334854,3.055,1.330802711,2.178050701,64.6028428 +93.86,50.42566189,-2.582779292,50.2458,4.282668189,9.034112671,3.065,1.242168432,2.25533841,64.59531774 +93.87,50.42566227,-2.582778021,50.2151,4.282668165,9.033002222,3.075,1.154318876,2.330659384,64.58779263 +93.88,50.42566266,-2.58277675,50.1843,4.28614433,9.032113839,3.0846875,1.067272492,2.403947963,64.58026757 +93.89,50.42566304,-2.582775479,50.1534,4.296572872,9.031669588,3.093125,0.981047443,2.475140318,64.57274246 +93.9,50.42566343,-2.582774208,50.1224,4.303525224,9.030781205,3.0996875,0.895661663,2.544174284,64.56521741 +93.91,50.42566382,-2.582772937,50.0914,4.300049014,9.029448688,3.1046875,0.811133027,2.6109897,64.55769229 +93.92,50.4256642,-2.582771667,50.0603,4.300049002,9.028560304,3.108125,0.727479184,2.675528296,64.55016724 +93.93,50.42566459,-2.582770396,50.0292,4.303525182,9.02833812,3.1096875,0.644717608,2.737733808,64.54264212 +93.94,50.42566498,-2.582769126,49.9981,4.300048972,9.028338003,3.1096875,0.562865545,2.79755192,64.53511707 +93.95,50.42566536,-2.582767855,49.967,4.300048942,9.028337886,3.108125,0.481940126,2.854930549,64.52759196 +93.96,50.42566575,-2.582766585,49.9359,4.303525111,9.028115701,3.105,0.401958255,2.909819677,64.5200669 +93.97,50.42566614,-2.582765314,49.9049,4.300048912,9.027227318,3.1015625,0.32293666,2.962171346,64.51254179 +93.98,50.42566652,-2.582764044,49.8739,4.300048898,9.025894801,3.098125,0.244891787,3.011940007,64.50501673 +93.99,50.42566691,-2.582762774,49.8429,4.30352506,9.025006418,3.0928125,0.167839965,3.059082173,64.49749162 +94,50.4256673,-2.582761504,49.812,4.300048839,9.024784234,3.0846875,0.091797235,3.103556818,64.48996656 +94.01,50.42566768,-2.582760234,49.7812,4.303525008,9.024784118,3.075,0.016779585,3.14532504,64.48244145 +94.02,50.42566807,-2.582758964,49.7505,4.317429755,9.024561934,3.065,-0.05719746,3.184350571,64.47491639 +94.03,50.42566846,-2.582757694,49.7199,4.317429735,9.023673551,3.0546875,-0.130118314,3.220599261,64.46739128 +94.04,50.42566885,-2.582756424,49.6894,4.303524947,9.022341035,3.043125,-0.201967795,3.254039542,64.45986622 +94.05,50.42566923,-2.582755155,49.659,4.303524927,9.021452652,3.029375,-0.272730947,3.284642249,64.45234111 +94.06,50.42566962,-2.582753885,49.6288,4.320905865,9.021230469,3.013125,-0.342392989,3.312380683,64.44481605 +94.07,50.42567001,-2.582752616,49.5987,4.33133442,9.021230353,2.995,-0.410939254,3.337230722,64.43729094 +94.08,50.4256704,-2.582751346,49.5689,4.320905825,9.021230237,2.9765625,-0.478355588,3.359170594,64.42976589 +94.09,50.42567079,-2.582750077,49.5392,4.303524849,9.021008055,2.9584375,-0.54462784,3.378181276,64.42224083 +94.1,50.42567117,-2.582748807,49.5097,4.303524838,9.020119674,2.939375,-0.609742087,3.394246096,64.41471572 +94.11,50.42567156,-2.582747538,49.4804,4.320905788,9.01878716,2.918125,-0.673684864,3.407351073,64.40719066 +94.12,50.42567195,-2.582746269,49.4513,4.334810535,9.017898779,2.8946875,-0.736442765,3.417484806,64.39966555 +94.13,50.42567234,-2.582745,49.4225,4.334810505,9.017676597,2.8696875,-0.798002726,3.42463847,64.39214049 +94.14,50.42567273,-2.582743731,49.3939,4.320905711,9.017454417,2.8434375,-0.858351797,3.428805764,64.38461538 +94.15,50.42567312,-2.582742462,49.3656,4.303524732,9.016566038,2.8165625,-0.917477432,3.429983078,64.37709032 +94.16,50.4256735,-2.582741193,49.3376,4.303524713,9.015233526,2.7896875,-0.975367254,3.42816938,64.36956521 +94.17,50.42567389,-2.582739925,49.3098,4.320905652,9.014345147,2.7615625,-1.032009231,3.423366332,64.36204015 +94.18,50.42567428,-2.582738656,49.2823,4.3348104,9.014122967,2.73125,-1.087391504,3.415578002,64.35451504 +94.19,50.42567467,-2.582737388,49.2552,4.338286571,9.014122855,2.6996875,-1.141502497,3.404811266,64.34698999 +94.2,50.42567506,-2.582736119,49.2283,4.338286547,9.014122743,2.6665625,-1.194330925,3.391075462,64.33946487 +94.21,50.42567545,-2.582734851,49.2018,4.338286525,9.013900566,2.6315625,-1.245865728,3.374382623,64.33193982 +94.22,50.42567584,-2.582733582,49.1757,4.338286512,9.013012189,2.5965625,-1.296096136,3.354747245,64.3244147 +94.23,50.42567623,-2.582732314,49.1499,4.338286501,9.01167968,2.5615625,-1.34501172,3.332186516,64.31688965 +94.24,50.42567662,-2.582731046,49.1244,4.338286486,9.010791304,2.5246875,-1.392602225,3.306720032,64.30936453 +94.25,50.42567701,-2.582729778,49.0994,4.338286469,9.010569128,2.4865625,-1.438857738,3.278370023,64.30183948 +94.26,50.4256774,-2.58272851,49.0747,4.338286455,9.010569019,2.448125,-1.483768519,3.247161241,64.29431437 +94.27,50.42567779,-2.582727242,49.0504,4.338286448,9.010568911,2.4078125,-1.527325287,3.213120902,64.28678931 +94.28,50.42567818,-2.582725974,49.0265,4.338286443,9.010346736,2.365,-1.56951893,3.176278684,64.2792642 +94.29,50.42567857,-2.582724706,49.0031,4.338286427,9.009236298,2.321875,-1.610340569,3.136666674,64.27173914 +94.3,50.42567896,-2.582723438,48.9801,4.338286401,9.007237594,2.2796875,-1.649781723,3.094319478,64.26421403 +94.31,50.42567935,-2.582722171,48.9575,4.338286377,9.006127155,2.23625,-1.687834199,3.049273995,64.25668897 +94.32,50.42567974,-2.582720904,48.9353,4.338286358,9.006793248,2.19,-1.724489976,3.001569471,64.24916386 +94.33,50.42568013,-2.582719636,48.9137,4.338286336,9.00701521,2.143125,-1.759741434,2.951247505,64.2416388 +94.34,50.42568052,-2.582718368,48.8925,4.338286318,9.005682708,2.096875,-1.793581238,2.898352041,64.23411369 +94.35,50.42568091,-2.582717102,48.8717,4.3417625,9.00479434,2.049375,-1.826002226,2.842929203,64.22658863 +94.36,50.4256813,-2.582715834,48.8515,4.355667258,9.004794237,2,-1.856997753,2.785027235,64.21906352 +94.37,50.42568169,-2.582714567,48.8317,4.373048204,9.004350002,1.95,-1.88656123,2.724696727,64.21153847 +94.38,50.42568209,-2.5827133,48.8125,4.373048191,9.003461635,1.8996875,-1.914686582,2.661990163,64.20401335 +94.39,50.42568248,-2.582712033,48.7937,4.355667222,9.002351202,1.8484375,-1.941367851,2.596962375,64.1964883 +94.4,50.42568287,-2.582710766,48.7755,4.341762445,9.00124077,1.79625,-1.966599538,2.529669972,64.18896318 +94.41,50.42568326,-2.5827095,48.7578,4.338286239,9.00124067,1.7434375,-1.990376312,2.460171681,64.18143813 +94.42,50.42568365,-2.582708233,48.7406,4.341762413,9.002128838,1.6896875,-2.012693247,2.388528064,64.17391301 +94.43,50.42568404,-2.582706966,48.724,4.355667162,9.001906674,1.6346875,-2.033545645,2.314801631,64.16638796 +94.44,50.42568443,-2.582705699,48.7079,4.373048114,9.000130046,1.5784375,-2.052929209,2.239056668,64.1588629 +94.45,50.42568483,-2.582704433,48.6924,4.373048119,8.998797551,1.521875,-2.070839869,2.161359179,64.15133779 +94.46,50.42568522,-2.582703167,48.6775,4.355667167,8.998797455,1.4665625,-2.087273846,2.081776946,64.14381273 +94.47,50.42568561,-2.5827019,48.6631,4.345238583,8.998575294,1.41125,-2.102227758,2.00037941,64.13628762 +94.48,50.425686,-2.582700634,48.6492,4.355667135,8.997686935,1.353125,-2.115698454,1.917237505,64.12876257 +94.49,50.42568639,-2.582699368,48.636,4.373048066,8.997464776,1.293125,-2.127683127,1.832423708,64.12123745 +94.5,50.42568679,-2.582698102,48.6234,4.376524243,8.997464684,1.23375,-2.138179312,1.746012047,64.1137124 +94.51,50.42568718,-2.582696835,48.6113,4.373048048,8.996354261,1.175,-2.147184719,1.658077808,64.10618728 +94.52,50.42568757,-2.58269557,48.5999,4.376524238,8.995021772,1.11625,-2.154697571,1.568697767,64.09866223 +94.53,50.42568797,-2.582694304,48.589,4.373048042,8.994355482,1.0565625,-2.160716206,1.477949732,64.09113711 +94.54,50.42568836,-2.582693038,48.5787,4.359143271,8.993911261,0.9946875,-2.165239479,1.385912943,64.08361206 +94.55,50.42568875,-2.582691773,48.5691,4.359143262,8.993911173,0.931875,-2.1682663,1.292667557,64.07608695 +94.56,50.42568914,-2.582690507,48.5601,4.373048014,8.993911086,0.8703125,-2.169796212,1.198294991,64.06856189 +94.57,50.42568954,-2.582689241,48.5517,4.376524196,8.992578601,0.8096875,-2.169828756,1.102877464,64.06103678 +94.58,50.42568993,-2.582687976,48.5439,4.373048004,8.990801984,0.748125,-2.16836399,1.006498228,64.05351172 +94.59,50.42569032,-2.582686711,48.5367,4.380000388,8.990579833,0.6846875,-2.165402199,0.909241336,64.04598661 +94.6,50.42569072,-2.582685446,48.5302,4.390428957,8.991468015,0.6203125,-2.160943957,0.811191584,64.03846155 +94.61,50.42569111,-2.58268418,48.5243,4.390428947,8.991467933,0.5565625,-2.154990295,0.712434401,64.03093644 +94.62,50.42569151,-2.582682915,48.5191,4.380000366,8.990357519,0.4934375,-2.147542417,0.613056017,64.02341138 +94.63,50.4256919,-2.58268165,48.5144,4.373047985,8.989247106,0.43,-2.138601812,0.513143007,64.01588627 +94.64,50.42569229,-2.582680385,48.5105,4.37652418,8.988136694,0.3665625,-2.128170485,0.412782516,64.00836121 +94.65,50.42569269,-2.58267912,48.5071,4.376524181,8.987026283,0.3034375,-2.116250441,0.312062093,64.0008361 +94.66,50.42569308,-2.582677856,48.5044,4.373047988,8.986804138,0.239375,-2.102844318,0.211069573,63.99331105 +94.67,50.42569347,-2.582676591,48.5023,4.380000367,8.987026127,0.17375,-2.087954863,0.109892961,63.98578593 +94.68,50.42569387,-2.582675326,48.5009,4.390428935,8.986581918,0.1084375,-2.071585115,0.008620494,63.97826088 +94.69,50.42569426,-2.582674062,48.5002,4.39390513,8.985693576,0.045,-2.053738626,-0.092659422,63.97073576 +94.7,50.42569466,-2.582672797,48.5,4.393905146,8.984805236,-0.0184375,-2.034419005,-0.193858551,63.96321071 +94.71,50.42569505,-2.582671533,48.5005,4.393905153,8.984361029,-0.08375,-2.013630377,-0.294888657,63.95568559 +94.72,50.42569545,-2.582670269,48.5017,4.393905143,8.984583022,-0.1496875,-1.991376983,-0.39566162,63.94816054 +94.73,50.42569584,-2.582669004,48.5035,4.39390513,8.984360883,-0.2146875,-1.967663578,-0.496089548,63.94063543 +94.74,50.42569624,-2.58266774,48.506,4.393905125,8.983250481,-0.2784375,-1.942495089,-0.596084893,63.93311037 +94.75,50.42569663,-2.582666476,48.5091,4.393905132,8.982362145,-0.3415625,-1.915876673,-0.69556045,63.92558526 +94.76,50.42569703,-2.582665212,48.5128,4.393905141,8.982140009,-0.405,-1.887814002,-0.794429417,63.9180602 +94.77,50.42569742,-2.582663948,48.5172,4.393905145,8.981917874,-0.4684375,-1.858312921,-0.892605678,63.91053515 +94.78,50.42569782,-2.582662684,48.5222,4.397381333,8.980807475,-0.5315625,-1.82737956,-0.990003518,63.90301003 +94.79,50.42569821,-2.58266142,48.5278,4.407809906,8.978808811,-0.595,-1.795020393,-1.08653814,63.89548498 +94.8,50.42569861,-2.582660157,48.5341,4.414762295,8.977698413,-0.6584375,-1.761242125,-1.182125205,63.88795986 +94.81,50.42569901,-2.582658894,48.541,4.407809918,8.978586613,-0.7215625,-1.726051916,-1.276681519,63.88043481 +94.82,50.4256994,-2.58265763,48.5485,4.397381348,8.979474814,-0.785,-1.689457045,-1.370124461,63.87290969 +94.83,50.4256998,-2.582656366,48.5567,4.397381358,8.978364419,-0.848125,-1.65146513,-1.462372728,63.86538464 +94.84,50.42570019,-2.582655103,48.5655,4.407809945,8.97636576,-0.9096875,-1.612084194,-1.553345706,63.85785953 +94.85,50.42570059,-2.58265384,48.5749,4.414762334,8.975255366,-0.97,-1.571322372,-1.642964155,63.85033447 +94.86,50.42570099,-2.582652577,48.5849,4.407809952,8.975033238,-1.03,-1.529188202,-1.73114998,63.84280936 +94.87,50.42570138,-2.582651314,48.5955,4.397381382,8.975033178,-1.0903125,-1.485690506,-1.817826119,63.8352843 +94.88,50.42570178,-2.582650051,48.6067,4.397381394,8.97503312,-1.1515625,-1.440838396,-1.902917169,63.82775919 +94.89,50.42570217,-2.582648788,48.6185,4.411286174,8.975033062,-1.213125,-1.394641153,-1.98634882,63.82023413 +94.9,50.42570257,-2.582647525,48.631,4.428667139,8.974810938,-1.2728125,-1.347108517,-2.068048304,63.81270902 +94.91,50.42570297,-2.582646262,48.644,4.428667142,8.973922615,-1.3296875,-1.298250343,-2.147944461,63.80518396 +94.92,50.42570337,-2.582644999,48.6576,4.414762382,8.972590161,-1.3853125,-1.24807683,-2.225967562,63.79765885 +94.93,50.42570376,-2.582643737,48.6717,4.411286203,8.971479775,-1.441875,-1.19659852,-2.302049654,63.79013379 +94.94,50.42570416,-2.582642474,48.6864,4.414762405,8.970369389,-1.5,-1.143826128,-2.376124216,63.78260868 +94.95,50.42570456,-2.582641212,48.7017,4.411286222,8.969259004,-1.558125,-1.089770654,-2.448126848,63.77508363 +94.96,50.42570495,-2.58263995,48.7176,4.414762429,8.969258951,-1.6146875,-1.034443443,-2.517994639,63.76755851 +94.97,50.42570535,-2.582638688,48.734,4.428667213,8.970147163,-1.6696875,-0.977856011,-2.585666684,63.76003346 +94.98,50.42570575,-2.582637425,48.751,4.428667225,8.970147112,-1.723125,-0.920020161,-2.651084026,63.75250834 +94.99,50.42570615,-2.582636163,48.7685,4.414762465,8.96903673,-1.775,-0.860947983,-2.71418954,63.74498329 +95,50.42570654,-2.582634901,48.7865,4.414762474,8.967926349,-1.8265625,-0.800651853,-2.77492828,63.73745817 +95.01,50.42570694,-2.582633639,48.805,4.432143446,8.966815969,-1.8784375,-0.739144318,-2.833247248,63.72993312 +95.02,50.42570734,-2.582632377,48.8241,4.442572033,8.965705589,-1.9296875,-0.676438213,-2.889095564,63.72240801 +95.03,50.42570774,-2.582631116,48.8436,4.432143471,8.965483474,-1.98,-0.612546715,-2.942424528,63.71488295 +95.04,50.42570814,-2.582629854,48.8637,4.414762531,8.965705493,-2.03,-0.54748306,-2.993187672,63.70735784 +95.05,50.42570853,-2.582628592,48.8842,4.414762548,8.965261314,-2.079375,-0.481260885,-3.041340706,63.69983278 +95.06,50.42570893,-2.582627331,48.9053,4.432143524,8.964373004,-2.1265625,-0.413893997,-3.086841634,63.69230767 +95.07,50.42570933,-2.582626069,48.9268,4.446048313,8.963262627,-2.1715625,-0.345396549,-3.129650806,63.68478261 +95.08,50.42570973,-2.582624808,48.9487,4.449524525,8.961930185,-2.216875,-0.27578275,-3.169730923,63.6772575 +95.09,50.42571013,-2.582623547,48.9711,4.446048349,8.961263942,-2.263125,-0.205067153,-3.207046919,63.66973244 +95.1,50.42571053,-2.582622286,48.994,4.432143595,8.961930097,-2.3078125,-0.133264597,-3.241566366,63.66220733 +95.11,50.42571093,-2.582621025,49.0173,4.414762646,8.963040386,-2.3496875,-0.060389981,-3.273259068,63.65468227 +95.12,50.42571132,-2.582619763,49.041,4.414762658,8.962818278,-2.39,0.013541399,-3.302097466,63.64715722 +95.13,50.42571172,-2.582618502,49.0651,4.43214363,8.96081964,-2.43,0.088514187,-3.328056407,63.63963211 +95.14,50.42571212,-2.582617241,49.0896,4.446048411,8.958821003,-2.47,0.164512627,-3.351113203,63.63210705 +95.15,50.42571252,-2.582615981,49.1145,4.449524623,8.958376829,-2.5096875,0.241520962,-3.371247799,63.62458194 +95.16,50.42571292,-2.58261472,49.1398,4.44952464,8.958598855,-2.548125,0.319522978,-3.388442607,63.61705688 +95.17,50.42571332,-2.582613459,49.1655,4.449524656,8.958154683,-2.5846875,0.39850246,-3.40268267,63.60953177 +95.18,50.42571372,-2.582612199,49.1915,4.449524677,8.957266379,-2.6196875,0.478442906,-3.4139555,63.60200671 +95.19,50.42571412,-2.582610938,49.2179,4.449524696,8.956378076,-2.653125,0.559327645,-3.422251299,63.5944816 +95.2,50.42571452,-2.582609678,49.2446,4.449524713,8.955933906,-2.685,0.641139773,-3.427562904,63.58695654 +95.21,50.42571492,-2.582608418,49.2716,4.449524734,8.956155934,-2.7165625,0.723862159,-3.429885561,63.57943143 +95.22,50.42571532,-2.582607157,49.2989,4.449524753,8.95593383,-2.748125,0.807477557,-3.429217377,63.57190637 +95.23,50.42571572,-2.582605897,49.3266,4.449524771,8.954601395,-2.778125,0.891968549,-3.425558813,63.56438126 +95.24,50.42571612,-2.582604637,49.3545,4.449524793,8.952824829,-2.80625,0.977317431,-3.418913132,63.55685621 +95.25,50.42571652,-2.582603377,49.3827,4.449524813,8.951492396,-2.8334375,1.063506383,-3.409286066,63.54933109 +95.26,50.42571692,-2.582602118,49.4112,4.449524831,8.95149236,-2.8596875,1.150517473,-3.396686094,63.54180604 +95.27,50.42571732,-2.582600858,49.4399,4.453001045,8.95238059,-2.8846875,1.238332422,-3.381124159,63.53428092 +95.28,50.42571772,-2.582599598,49.4689,4.466905832,8.952380555,-2.908125,1.326932954,-3.362613841,63.52675587 +95.29,50.42571812,-2.582598338,49.4981,4.484286809,8.951270189,-2.9296875,1.416300562,-3.341171239,63.51923075 +95.3,50.42571853,-2.582597079,49.5275,4.484286832,8.950159823,-2.95,1.506416624,-3.31681509,63.5117057 +95.31,50.42571893,-2.582595819,49.5571,4.466905895,8.949049457,-2.97,1.597262234,-3.28956665,63.50418059 +95.32,50.42571933,-2.58259456,49.5869,4.453001147,8.947939091,-2.9896875,1.688818426,-3.259449639,63.49665553 +95.33,50.42571973,-2.582593301,49.6169,4.449524979,8.947939057,-3.0078125,1.781066178,-3.226490356,63.48913042 +95.34,50.42572013,-2.582592042,49.6471,4.449525,8.948827289,-3.023125,1.873986124,-3.190717564,63.48160536 +95.35,50.42572053,-2.582590782,49.6774,4.453001211,8.948827256,-3.0365625,1.967558955,-3.152162375,63.47408025 +95.36,50.42572093,-2.582589523,49.7078,4.466906002,8.947716892,-3.05,2.06176502,-3.11085842,63.46655519 +95.37,50.42572133,-2.582588264,49.7384,4.484286983,8.946606528,-3.0628125,2.156584722,-3.066841797,63.45903008 +95.38,50.42572174,-2.582587005,49.7691,4.484287003,8.945496163,-3.073125,2.251998238,-3.020150836,63.45150502 +95.39,50.42572214,-2.582585746,49.7999,4.466906067,8.944163733,-3.08125,2.347985628,-2.970826275,63.44397991 +95.4,50.42572254,-2.582584488,49.8307,4.456477514,8.943275435,-3.0884375,2.444526839,-2.918911085,63.43645485 +95.41,50.42572294,-2.582583229,49.8617,4.466906109,8.943053337,-3.095,2.541601761,-2.864450529,63.42892974 +95.42,50.42572334,-2.582581971,49.8926,4.484287093,8.943053305,-3.10125,2.639190052,-2.807492165,63.42140469 +95.43,50.42572375,-2.582580712,49.9237,4.484287115,8.943053273,-3.1065625,2.737271374,-2.748085666,63.41387957 +95.44,50.42572415,-2.582579454,49.9548,4.470382367,8.942831174,-3.109375,2.835825272,-2.686282714,63.40635452 +95.45,50.42572455,-2.582578195,49.9859,4.470382392,8.941942876,-3.1096875,2.934831118,-2.622137339,63.3988294 +95.46,50.42572495,-2.582576937,50.017,4.484287182,8.940610446,-3.1084375,3.03426823,-2.555705403,63.39130435 +95.47,50.42572536,-2.582575679,50.0481,4.487763394,8.939722148,-3.1065625,3.134115866,-2.487044891,63.38377929 +95.48,50.42572576,-2.582574421,50.0791,4.484287226,8.93950005,-3.1046875,3.234353171,-2.41621562,63.37625418 +95.49,50.42572616,-2.582573163,50.1102,4.487763438,8.939277951,-3.1015625,3.334959174,-2.343279353,63.36872912 +95.5,50.42572657,-2.582571905,50.1412,4.487763451,8.938389653,-3.0959375,3.435912962,-2.268299689,63.36120401 +95.51,50.42572697,-2.582570647,50.1721,4.484287281,8.937279289,-3.0884375,3.537193336,-2.191342061,63.35367895 +95.52,50.42572737,-2.58256939,50.203,4.487763504,8.93705719,-3.0796875,3.638779269,-2.112473561,63.34615384 +95.53,50.42572778,-2.582568132,50.2337,4.487763528,8.937057157,-3.07,3.740649389,-2.031762944,63.33862879 +95.54,50.42572818,-2.582566874,50.2644,4.484287356,8.935946793,-3.06,3.842782554,-1.949280628,63.33110367 +95.55,50.42572858,-2.582565617,50.2949,4.487763572,8.934836428,-3.049375,3.945157392,-1.86509846,63.32357862 +95.56,50.42572899,-2.58256436,50.3254,4.487763592,8.934836395,-3.0365625,4.047752533,-1.779289894,63.3160535 +95.57,50.42572939,-2.582563102,50.3557,4.484287412,8.934614295,-3.02125,4.15054649,-1.691929816,63.30852845 +95.58,50.42572979,-2.582561845,50.3858,4.491239818,8.93350393,-3.005,4.253517892,-1.603094314,63.30100333 +95.59,50.4257302,-2.582560588,50.4158,4.501668425,8.93261563,-2.988125,4.356645195,-1.51286091,63.29347828 +95.6,50.4257306,-2.582559331,50.4456,4.501668449,8.93239353,-2.969375,4.4599068,-1.42130827,63.28595317 +95.61,50.42573101,-2.582558074,50.4752,4.491239891,8.932393496,-2.9484375,4.563281221,-1.328516208,63.27842811 +95.62,50.42573141,-2.582556817,50.5046,4.48428753,8.932171394,-2.9265625,4.666746856,-1.234565626,63.270903 +95.63,50.42573181,-2.58255556,50.5337,4.491239935,8.931283094,-2.9046875,4.770282106,-1.13953857,63.26337794 +95.64,50.42573222,-2.582554303,50.5627,4.50166853,8.929950661,-2.8815625,4.873865255,-1.043517719,63.25585283 +95.65,50.42573262,-2.582553047,50.5914,4.505144743,8.92906236,-2.85625,4.977474817,-0.946587011,63.24832777 +95.66,50.42573303,-2.58255179,50.6198,4.505144753,8.928840257,-2.8303125,5.081089078,-0.848830786,63.24080266 +95.67,50.42573343,-2.582550534,50.648,4.505144755,8.928618154,-2.8046875,5.184686379,-0.750334413,63.2332776 +95.68,50.42573384,-2.582549277,50.6759,4.505144782,8.927951918,-2.7778125,5.28824512,-0.651183723,63.22575249 +95.69,50.42573424,-2.582548021,50.7036,4.505144824,8.927507748,-2.748125,5.391743643,-0.551465174,63.21822743 +95.7,50.42573465,-2.582546765,50.7309,4.505144846,8.927729776,-2.71625,5.495160405,-0.451265742,63.21070232 +95.71,50.42573505,-2.582545508,50.7579,4.505144861,8.927507672,-2.6834375,5.598473691,-0.350672802,63.20317727 +95.72,50.42573546,-2.582544252,50.7846,4.505144886,8.926397301,-2.6496875,5.701662072,-0.249774075,63.19565215 +95.73,50.42573586,-2.582542996,50.8109,4.505144899,8.925286931,-2.615,5.804703834,-0.148657567,63.1881271 +95.74,50.42573627,-2.58254174,50.8369,4.508621092,8.92417656,-2.5796875,5.907577604,-0.047411398,63.18060198 +95.75,50.42573667,-2.582540484,50.8625,4.51904969,8.923066188,-2.543125,6.010261839,0.053876081,63.17307693 +95.76,50.42573708,-2.582539229,50.8878,4.526002109,8.922844081,-2.505,6.112735054,0.155116635,63.16555181 +95.77,50.42573749,-2.582537973,50.9126,4.519049744,8.922844039,-2.4665625,6.214975935,0.256221856,63.15802676 +95.78,50.42573789,-2.582536717,50.9371,4.508621175,8.921733665,-2.428125,6.316963053,0.357103738,63.15050165 +95.79,50.4257383,-2.582535462,50.9612,4.508621193,8.920623291,-2.3878125,6.418675151,0.45767416,63.14297659 +95.8,50.4257387,-2.582534207,50.9849,4.519049796,8.920623248,-2.345,6.520090973,0.55784546,63.13545148 +95.81,50.42573911,-2.582532951,51.0081,4.526002198,8.920401138,-2.3015625,6.621189375,0.657530376,63.12792642 +95.82,50.42573952,-2.582531696,51.0309,4.522526013,8.919290763,-2.2584375,6.72194916,0.756641876,63.12040137 +95.83,50.42573992,-2.582530441,51.0533,4.522526029,8.918402453,-2.2146875,6.822349357,0.855093558,63.11287625 +95.84,50.42574033,-2.582529186,51.0752,4.526002247,8.91818034,-2.1696875,6.922368995,0.952799592,63.1053512 +95.85,50.42574074,-2.582527931,51.0967,4.522526072,8.918180293,-2.123125,7.021987161,1.049674838,63.09782608 +95.86,50.42574114,-2.582526676,51.1177,4.526002277,8.91795818,-2.0746875,7.121183058,1.145634669,63.09030103 +95.87,50.42574155,-2.582525421,51.1382,4.539907065,8.917069868,-2.025,7.219935944,1.240595548,63.08277591 +95.88,50.42574196,-2.582524166,51.1582,4.539907077,8.915737421,-1.975,7.318225249,1.334474568,63.07525086 +95.89,50.42574237,-2.582522912,51.1777,4.526002312,8.914849107,-1.925,7.416030463,1.427189911,63.06772575 +95.9,50.42574277,-2.582521657,51.1967,4.522526133,8.914626991,-1.8746875,7.513331072,1.518660732,63.06020069 +95.91,50.42574318,-2.582520403,51.2152,4.526002348,8.914404875,-1.823125,7.610106795,1.608807276,63.05267558 +95.92,50.42574359,-2.582519148,51.2332,4.522526169,8.913738624,-1.77,7.706337463,1.697550876,63.04515052 +95.93,50.42574399,-2.582517894,51.2506,4.526002365,8.913294439,-1.7165625,7.802002966,1.784814239,63.03762541 +95.94,50.4257444,-2.58251664,51.2675,4.543383341,8.913294387,-1.663125,7.897083249,1.870521162,63.03010035 +95.95,50.42574481,-2.582515385,51.2839,4.55381194,8.912406069,-1.608125,7.991558546,1.954596989,63.02257524 +95.96,50.42574522,-2.582514131,51.2997,4.543383373,8.91085155,-1.5515625,8.085409091,2.036968381,63.01505018 +95.97,50.42574563,-2.582512878,51.3149,4.526002412,8.910185296,-1.495,8.178615286,2.117563489,63.00752507 +95.98,50.42574603,-2.582511623,51.3296,4.526002423,8.909741107,-1.4384375,8.271157653,2.196312069,63.00000001 +95.99,50.42574644,-2.58251037,51.3437,4.543383406,8.908630719,-1.3815625,8.36301694,2.273145423,62.9924749 +96,50.42574685,-2.582509116,51.3572,4.557288186,8.907964463,-1.3246875,8.454173837,2.347996572,62.98494985 +96.01,50.42574726,-2.582507863,51.3702,4.557288187,8.908408537,-1.2665625,8.544609381,2.420800199,62.97742473 +96.02,50.42574767,-2.582506609,51.3826,4.543383425,8.908630544,-1.20625,8.634304721,2.491492935,62.96989968 +96.03,50.42574808,-2.582505355,51.3943,4.526002479,8.907298086,-1.1453125,8.723241063,2.560012957,62.96237456 +96.04,50.42574848,-2.582504102,51.4055,4.526002485,8.905521495,-1.085,8.811399845,2.626300679,62.95484951 +96.05,50.42574889,-2.582502849,51.416,4.543383437,8.905299367,-1.025,8.898762673,2.690298174,62.94732439 +96.06,50.4257493,-2.582501596,51.426,4.557288198,8.906187569,-0.965,8.985311271,2.751949693,62.93979934 +96.07,50.42574971,-2.582500342,51.4353,4.560764404,8.906187506,-0.904375,9.071027591,2.811201494,62.93227423 +96.08,50.42575012,-2.582499089,51.4441,4.560764433,8.90507711,-0.841875,9.155893756,2.868001894,62.92474917 +96.09,50.42575053,-2.582497836,51.4522,4.560764448,8.903966713,-0.778125,9.239892004,2.922301333,62.91722406 +96.1,50.42575094,-2.582496583,51.4596,4.560764447,8.902856316,-0.7153125,9.323004803,2.974052486,62.909699 +96.11,50.42575135,-2.58249533,51.4665,4.560764452,8.901523851,-0.6534375,9.405214793,3.023210259,62.90217389 +96.12,50.42575176,-2.582494078,51.4727,4.560764466,8.900635518,-0.59125,9.486504842,3.069731682,62.89464883 +96.13,50.42575217,-2.582492825,51.4783,4.56076447,8.900413383,-0.528125,9.566857933,3.113576303,62.88712372 +96.14,50.42575258,-2.582491573,51.4833,4.560764465,8.900413313,-0.4634375,9.646257278,3.154705792,62.87959866 +96.15,50.42575299,-2.58249032,51.4876,4.560764468,8.900413242,-0.3984375,9.724686262,3.193084396,62.87207361 +96.16,50.4257534,-2.582489068,51.4912,4.56076448,8.900191104,-0.335,9.802128613,3.228678539,62.86454849 +96.17,50.42575381,-2.582487815,51.4943,4.560764483,8.899302766,-0.2715625,9.878568116,3.261457226,62.85702344 +96.18,50.42575422,-2.582486563,51.4967,4.560764474,8.897970296,-0.2065625,9.953988785,3.291391864,62.84949833 +96.19,50.42575463,-2.582485311,51.4984,4.560764468,8.897081957,-0.141875,10.02837486,3.318456385,62.84197327 +96.2,50.42575504,-2.582484059,51.4995,4.560764476,8.896859815,-0.0784375,10.10171083,3.342627182,62.83444816 +96.21,50.42575545,-2.582482807,51.5,4.560764488,8.896637673,-0.0146875,10.17398132,3.363883114,62.8269231 +96.22,50.42575586,-2.582481555,51.4998,4.560764488,8.895749331,0.05,10.24517138,3.382205732,62.81939799 +96.23,50.42575627,-2.582480303,51.499,4.560764479,8.894416856,0.115,10.315266,3.397578992,62.81187293 +96.24,50.42575668,-2.582479052,51.4975,4.560764478,8.893528513,0.18,10.38425058,3.409989487,62.80434782 +96.25,50.42575709,-2.5824778,51.4954,4.564240679,8.893528433,0.2446875,10.45211079,3.419426445,62.79682276 +96.26,50.4257575,-2.582476549,51.4926,4.578145448,8.894194551,0.3084375,10.51883235,3.425881617,62.78929765 +96.27,50.42575791,-2.582475297,51.4892,4.595526399,8.894416534,0.3715625,10.58440136,3.429349387,62.78177259 +96.28,50.42575833,-2.582474045,51.4852,4.59552639,8.893084054,0.4353125,10.64880416,3.429826661,62.77424748 +96.29,50.42575874,-2.582472794,51.4805,4.578145427,8.891085375,0.5,10.7120273,3.427313095,62.76672242 +96.3,50.42575915,-2.582471543,51.4752,4.564240655,8.889974961,0.5646875,10.77405755,3.421810924,62.75919731 +96.31,50.42575956,-2.582470292,51.4692,4.560764447,8.88975281,0.628125,10.83488194,3.413324789,62.75167226 +96.32,50.42575997,-2.582469041,51.4626,4.564240624,8.889752723,0.69,10.89448778,3.401862252,62.74414714 +96.33,50.42576038,-2.58246779,51.4554,4.578145395,8.88953057,0.751875,10.95286266,3.387433227,62.73662209 +96.34,50.42576079,-2.582466539,51.4476,4.595526369,8.888642217,0.815,11.00999435,3.37005026,62.72909697 +96.35,50.42576121,-2.582465288,51.4391,4.595526377,8.887309731,0.878125,11.06587097,3.349728593,62.72157192 +96.36,50.42576162,-2.582464038,51.43,4.581621599,8.886421377,0.9396875,11.12048072,3.32648593,62.71404681 +96.37,50.42576203,-2.582462787,51.4203,4.581621582,8.88619922,1,11.17381238,3.300342496,62.70652175 +96.38,50.42576244,-2.582461537,51.41,4.595526339,8.886199128,1.06,11.22585465,3.271321152,62.69899664 +96.39,50.42576286,-2.582460286,51.3991,4.595526338,8.886199035,1.12,11.27659677,3.239447109,62.69147158 +96.4,50.42576327,-2.582459036,51.3876,4.58162157,8.885976876,1.18,11.32602807,3.204748269,62.68394647 +96.41,50.42576368,-2.582457785,51.3755,4.581621562,8.885088518,1.2396875,11.37413831,3.167254828,62.67642141 +96.42,50.42576409,-2.582456535,51.3628,4.595526313,8.883756026,1.2984375,11.42091733,3.126999501,62.6688963 +96.43,50.42576451,-2.582455285,51.3495,4.599002488,8.8826456,1.3565625,11.46635546,3.084017353,62.66137124 +96.44,50.42576492,-2.582454035,51.3357,4.595526285,8.881757238,1.415,11.51044319,3.038345913,62.65384613 +96.45,50.42576533,-2.582452785,51.3212,4.599002477,8.881313009,1.473125,11.55317129,2.990025002,62.64632107 +96.46,50.42576575,-2.582451536,51.3062,4.599002477,8.881534977,1.5296875,11.59453082,2.939096732,62.63879596 +96.47,50.42576616,-2.582450285,51.2906,4.595526271,8.881312812,1.585,11.63451319,2.885605564,62.6312709 +96.48,50.42576657,-2.582449036,51.2745,4.599002437,8.879980316,1.6396875,11.67311003,2.829598022,62.62374579 +96.49,50.42576699,-2.582447786,51.2578,4.599002421,8.878425752,1.6934375,11.71031327,2.771123096,62.61622074 +96.5,50.4257674,-2.582446537,51.2406,4.595526227,8.877759452,1.7465625,11.74611511,2.71023172,62.60869568 +96.51,50.42576781,-2.582445288,51.2229,4.599002408,8.877981417,1.8,11.78050816,2.64697695,62.60117057 +96.52,50.42576823,-2.582444038,51.2046,4.599002382,8.877759248,1.853125,11.81348515,2.581413962,62.59364551 +96.53,50.42576864,-2.582442789,51.1858,4.595526171,8.876648815,1.9046875,11.84503925,2.513599938,62.5861204 +96.54,50.42576905,-2.58244154,51.1665,4.60247855,8.875760446,1.955,11.87516383,2.443594064,62.57859534 +96.55,50.42576947,-2.582440291,51.1467,4.612907124,8.875538275,2.0046875,11.90385268,2.371457303,62.57107023 +96.56,50.42576988,-2.582439042,51.1264,4.616383314,8.875538169,2.053125,11.93109969,2.297252622,62.56354517 +96.57,50.4257703,-2.582437793,51.1056,4.616383299,8.875315997,2.1,11.95689924,2.221044651,62.55602006 +96.58,50.42577071,-2.582436544,51.0844,4.61290708,8.874427625,2.1465625,11.98124593,2.142899969,62.548495 +96.59,50.42577113,-2.582435295,51.0627,4.602478479,8.873317187,2.1934375,12.00413468,2.062886585,62.54096989 +96.6,50.42577154,-2.582434047,51.0405,4.595526078,8.873095012,2.2396875,12.02556072,1.9810744,62.53344484 +96.61,50.42577195,-2.582432798,51.0179,4.602478456,8.873094904,2.2846875,12.04551954,1.897534632,62.52591972 +96.62,50.42577237,-2.582431549,50.9948,4.612907028,8.871984464,2.328125,12.06400705,1.812340162,62.51839467 +96.63,50.42577278,-2.582430301,50.9713,4.616383202,8.870874024,2.3696875,12.08101926,1.725565361,62.51086955 +96.64,50.4257732,-2.582429053,50.9474,4.616383165,8.870873913,2.41,12.09655271,1.637285857,62.5033445 +96.65,50.42577361,-2.582427804,50.9231,4.616383128,8.870651736,2.45,12.11060416,1.547578543,62.49581939 +96.66,50.42577403,-2.582426556,50.8984,4.619859302,8.869541293,2.4896875,12.12317061,1.456521798,62.48829433 +96.67,50.42577444,-2.582425308,50.8733,4.630287882,8.86843085,2.528125,12.1342495,1.364194863,62.48076922 +96.68,50.42577486,-2.58242406,50.8478,4.637240269,8.867320407,2.565,12.14383852,1.270678411,62.47324416 +96.69,50.42577528,-2.582422812,50.822,4.630287868,8.866209963,2.60125,12.15193562,1.176053858,62.46571905 +96.7,50.42577569,-2.582421565,50.7958,4.61985926,8.865987783,2.6365625,12.15853913,1.080403768,62.45819399 +96.71,50.42577611,-2.582420317,50.7692,4.61638304,8.866209735,2.6696875,12.16364768,0.983811563,62.45066888 +96.72,50.42577652,-2.582419069,50.7424,4.616383021,8.865765489,2.7015625,12.16726017,0.886361469,62.44314382 +96.73,50.42577694,-2.582417822,50.7152,4.619859203,8.864877109,2.7334375,12.16937588,0.788138398,62.43561871 +96.74,50.42577735,-2.582416574,50.6877,4.630287772,8.863988728,2.764375,12.16999433,0.68922812,62.42809365 +96.75,50.42577777,-2.582415327,50.6599,4.637240137,8.863544479,2.793125,12.16911547,0.589716811,62.42056854 +96.76,50.42577819,-2.58241408,50.6318,4.633763913,8.863766429,2.82,12.16673941,0.489691271,62.41304348 +96.77,50.4257786,-2.582412832,50.6035,4.633763884,8.863544247,2.84625,12.16286668,0.389238706,62.40551837 +96.78,50.42577902,-2.582411585,50.5749,4.637240051,8.862433799,2.8715625,12.15749801,0.288446721,62.39799332 +96.79,50.42577944,-2.582410338,50.546,4.633763832,8.861545417,2.895,12.15063466,0.18740315,62.3904682 +96.8,50.42577985,-2.582409091,50.517,4.633763809,8.861101167,2.918125,12.14227795,0.086196229,62.38294315 +96.81,50.42578027,-2.582407844,50.4877,4.637239991,8.860212785,2.9415625,12.13242973,-0.015085864,62.37541803 +96.82,50.42578069,-2.582406597,50.4581,4.633763789,8.85888027,2.9625,12.12109192,-0.116354837,62.36789298 +96.83,50.4257811,-2.582405351,50.4284,4.637239957,8.85776982,2.98,12.10826701,-0.217522338,62.36036787 +96.84,50.42578152,-2.582404104,50.3985,4.651144698,8.856881436,2.9965625,12.09395762,-0.318500134,62.35284281 +96.85,50.42578194,-2.582402858,50.3685,4.651144675,8.856437185,3.013125,12.07816673,-0.419200216,62.34531775 +96.86,50.42578236,-2.582401612,50.3382,4.637239886,8.856881197,3.0284375,12.06089766,-0.519534695,62.33779264 +96.87,50.42578277,-2.582400365,50.3079,4.637239873,8.857547275,3.0428125,12.04215404,-0.619416193,62.33026758 +96.88,50.42578319,-2.582399119,50.2774,4.651144631,8.857325089,3.0565625,12.02193974,-0.718757506,62.32274247 +96.89,50.42578361,-2.582397872,50.2467,4.651144609,8.855770507,3.0678125,12.00025896,-0.817472118,62.31521742 +96.9,50.42578403,-2.582396626,50.216,4.637239808,8.853993859,3.0765625,11.97711634,-0.915473799,62.3076923 +96.91,50.42578444,-2.582395381,50.1852,4.637239774,8.85332754,3.085,11.95251657,-1.012677234,62.30016725 +96.92,50.42578486,-2.582394134,50.1543,4.654620702,8.853105354,3.093125,11.92646492,-1.10899757,62.29264213 +96.93,50.42578528,-2.582392889,50.1233,4.665049247,8.852883166,3.099375,11.89896673,-1.204350868,62.28511708 +96.94,50.4257857,-2.582391643,50.0923,4.654620657,8.853105111,3.103125,11.87002778,-1.298653934,62.27759196 +96.95,50.42578612,-2.582390397,50.0612,4.637239697,8.852660858,3.105,11.83965408,-1.39182455,62.27006691 +96.96,50.42578653,-2.582389151,50.0302,4.637239683,8.850662143,3.1065625,11.80785206,-1.483781525,62.2625418 +96.97,50.42578695,-2.582387906,49.9991,4.654620612,8.848663428,3.1084375,11.77462824,-1.574444534,62.25501674 +96.98,50.42578737,-2.582386661,49.968,4.668525349,8.848441241,3.109375,11.73998968,-1.663734677,62.24749163 +96.99,50.42578779,-2.582385416,49.9369,4.672001516,8.849329385,3.108125,11.70394358,-1.751573978,62.23996657 +97,50.42578821,-2.58238417,49.9058,4.672001494,8.849329264,3.1046875,11.66649741,-1.837885887,62.23244146 +97.01,50.42578863,-2.582382925,49.8748,4.668525282,8.848218813,3.0996875,11.62765901,-1.922595176,62.2249164 +97.02,50.42578905,-2.58238168,49.8438,4.654620501,8.847108361,3.093125,11.58743657,-2.005627876,62.21739129 +97.03,50.42578947,-2.582380435,49.8129,4.637239528,8.846219977,3.0846875,11.54583834,-2.086911679,62.20986623 +97.04,50.42578988,-2.58237919,49.7821,4.637239497,8.845775725,3.075,11.50287316,-2.166375654,62.20234112 +97.05,50.4257903,-2.582377946,49.7514,4.654620412,8.845775604,3.065,11.45854994,-2.243950473,62.19481606 +97.06,50.42579072,-2.5823767,49.7208,4.668525148,8.84488722,3.0546875,11.41287793,-2.319568583,62.18729095 +97.07,50.42579114,-2.582375456,49.6903,4.672001327,8.843332638,3.043125,11.36586663,-2.393163981,62.1797659 +97.08,50.42579156,-2.582374212,49.6599,4.672001314,8.842888386,3.029375,11.31752595,-2.464672494,62.17224078 +97.09,50.42579198,-2.582372967,49.6297,4.672001295,8.843332397,3.013125,11.26786592,-2.534031785,62.16471573 +97.1,50.4257924,-2.582371723,49.5996,4.672001273,8.843332278,2.995,11.21689691,-2.60118135,62.15719061 +97.11,50.42579282,-2.582370478,49.5698,4.672001254,8.842443895,2.9765625,11.16462958,-2.66606269,62.14966556 +97.12,50.42579324,-2.582369234,49.5401,4.672001241,8.841111381,2.9584375,11.11107487,-2.728619139,62.14214044 +97.13,50.42579366,-2.58236799,49.5106,4.672001231,8.840222998,2.939375,11.05624396,-2.788796208,62.13461539 +97.14,50.42579408,-2.582366746,49.4813,4.672001207,8.840000812,2.918125,11.00014824,-2.846541416,62.12709028 +97.15,50.4257945,-2.582365502,49.4522,4.672001167,8.839778628,2.8946875,10.94279946,-2.901804398,62.11956522 +97.16,50.42579492,-2.582364258,49.4234,4.675477317,8.838890246,2.87,10.88420966,-2.954536913,62.11204011 +97.17,50.42579534,-2.582363014,49.3948,4.689382061,8.837557733,2.845,10.82439097,-3.004693065,62.10451505 +97.18,50.42579576,-2.582361771,49.3665,4.70676301,8.836669351,2.819375,10.76335596,-3.052229082,62.09698994 +97.19,50.42579619,-2.582360527,49.3384,4.706762999,8.836447168,2.7915625,10.70111727,-3.097103537,62.08946488 +97.2,50.42579661,-2.582359284,49.3106,4.689382023,8.836224985,2.7615625,10.63768803,-3.139277242,62.08193983 +97.21,50.42579703,-2.58235804,49.2832,4.675477239,8.835558671,2.7315625,10.57308149,-3.178713411,62.07441471 +97.22,50.42579745,-2.582356797,49.256,4.672001036,8.834892357,2.70125,10.50731097,-3.215377782,62.06688966 +97.23,50.42579787,-2.582355554,49.2291,4.672001028,8.83444811,2.668125,10.44039042,-3.249238213,62.05936454 +97.24,50.42579829,-2.58235431,49.2026,4.675477198,8.833781798,2.633125,10.37233363,-3.28026531,62.05183949 +97.25,50.42579871,-2.582353068,49.1765,4.689381926,8.83289342,2.5984375,10.30315494,-3.308431973,62.04431438 +97.26,50.42579913,-2.582351824,49.1506,4.706762845,8.832005042,2.563125,10.23286877,-3.333713563,62.03678932 +97.27,50.42579956,-2.582350582,49.1252,4.706762824,8.831560796,2.52625,10.16148975,-3.356088196,62.02926421 +97.28,50.42579998,-2.582349339,49.1001,4.68938186,8.831782749,2.488125,10.08903282,-3.375536217,62.02173915 +97.29,50.4258004,-2.582348096,49.0754,4.675477084,8.83156057,2.448125,10.01551311,-3.392040724,62.01421404 +97.3,50.42580082,-2.582346853,49.0511,4.675477069,8.830450129,2.4065625,9.940946031,-3.405587337,62.00668898 +97.31,50.42580124,-2.582345611,49.0273,4.689381818,8.829339689,2.365,9.865347,-3.416164195,61.99916387 +97.32,50.42580166,-2.582344368,49.0038,4.706762761,8.828451315,2.3234375,9.788732,-3.423762132,61.99163881 +97.33,50.42580209,-2.582343126,48.9808,4.706762753,8.828007072,2.28125,9.711116903,-3.428374499,61.9841137 +97.34,50.42580251,-2.582341884,48.9582,4.69285798,8.828006962,2.238125,9.632517922,-3.429997287,61.97658864 +97.35,50.42580293,-2.582340641,48.936,4.692857955,8.82711859,2.193125,9.552951502,-3.428629064,61.96906353 +97.36,50.42580335,-2.582339399,48.9143,4.706762683,8.82556402,2.14625,9.472434259,-3.424270975,61.96153848 +97.37,50.42580378,-2.582338158,48.8931,4.71023885,8.824897714,2.0984375,9.390983037,-3.416926917,61.95401336 +97.38,50.4258042,-2.582336915,48.8723,4.706762652,8.824675541,2.05,9.308614797,-3.406603249,61.94648831 +97.39,50.42580462,-2.582335674,48.8521,4.710238838,8.824453369,2.00125,9.225346726,-3.393308966,61.93896319 +97.4,50.42580505,-2.582334432,48.8323,4.706762635,8.824675329,1.951875,9.1411963,-3.377055643,61.93143814 +97.41,50.42580547,-2.58233319,48.813,4.692857855,8.824231091,1.90125,9.056180994,-3.357857547,61.92391302 +97.42,50.42580589,-2.582331948,48.7943,4.692857842,8.82245446,1.85,8.970318627,-3.335731292,61.91638797 +97.43,50.42580631,-2.582330707,48.776,4.706762592,8.821121962,1.798125,8.883627076,-3.310696245,61.90886286 +97.44,50.42580674,-2.582329466,48.7583,4.710238762,8.821121859,1.7446875,8.796124561,-3.282774178,61.9013378 +97.45,50.42580716,-2.582328224,48.7411,4.706762547,8.820899691,1.69,8.707829186,-3.251989556,61.89381269 +97.46,50.42580758,-2.582326983,48.7245,4.713714918,8.81978926,1.635,8.618759516,-3.218369081,61.88628763 +97.47,50.42580801,-2.582325742,48.7084,4.724143493,8.818900896,1.58,8.528934115,-3.1819422,61.87876252 +97.48,50.42580843,-2.582324501,48.6929,4.7241435,8.81867873,1.5246875,8.438371776,-3.142740542,61.87123746 +97.49,50.42580886,-2.58232326,48.6779,4.713714928,8.818456564,1.4684375,8.347091291,-3.100798427,61.86371235 +97.5,50.42580928,-2.582322019,48.6635,4.706762536,8.817568202,1.4115625,8.255111856,-3.056152353,61.85618729 +97.51,50.4258097,-2.582320778,48.6497,4.713714897,8.816457775,1.3546875,8.162452663,-3.00884128,61.84866218 +97.52,50.42581013,-2.582319538,48.6364,4.724143453,8.816235612,1.2965625,8.069133021,-2.958906461,61.84113712 +97.53,50.42581055,-2.582318297,48.6237,4.72761963,8.816457583,1.2365625,7.975172412,-2.906391441,61.83361207 +97.54,50.42581098,-2.582317056,48.6117,4.727619613,8.816013356,1.1765625,7.880590487,-2.851341943,61.82608696 +97.55,50.4258114,-2.582315816,48.6002,4.727619594,8.815124998,1.116875,7.785406957,-2.793806094,61.8185619 +97.56,50.42581183,-2.582314575,48.5893,4.727619586,8.81423664,1.05625,7.689641759,-2.733833971,61.81103679 +97.57,50.42581225,-2.582313335,48.5791,4.72761959,8.813570349,0.9953125,7.593314834,-2.671477943,61.80351173 +97.58,50.42581268,-2.582312095,48.5694,4.727619592,8.812904059,0.935,7.49644635,-2.606792326,61.79598662 +97.59,50.4258131,-2.582310854,48.5604,4.727619588,8.811571573,0.874375,7.399056531,-2.539833498,61.78846156 +97.6,50.42581353,-2.582309615,48.5519,4.727619582,8.810461153,0.811875,7.30116566,-2.47065996,61.78093645 +97.61,50.42581395,-2.582308375,48.5441,4.727619574,8.810461063,0.748125,7.20279425,-2.399331928,61.77341139 +97.62,50.42581438,-2.582307135,48.537,4.72761956,8.810238909,0.6853125,7.103962812,-2.325911684,61.76588628 +97.63,50.4258148,-2.582305895,48.5304,4.727619545,8.809350559,0.623125,7.004691972,-2.250463169,61.75836122 +97.64,50.42581523,-2.582304656,48.5245,4.727619543,8.809128407,0.5596875,6.90500253,-2.173052274,61.75083611 +97.65,50.42581565,-2.582303416,48.5192,4.727619559,8.80912832,0.4953125,6.804915225,-2.093746378,61.74331106 +97.66,50.42581608,-2.582302176,48.5146,4.731095767,8.80779584,0.4315625,6.704450972,-2.012614752,61.73578594 +97.67,50.4258165,-2.582300937,48.5106,4.741524341,8.806019228,0.3684375,6.60363074,-1.929728099,61.72826089 +97.68,50.42581693,-2.582299698,48.5072,4.74847671,8.805797078,0.3046875,6.502475672,-1.845158669,61.72073577 +97.69,50.42581736,-2.582298459,48.5045,4.741524317,8.806685259,0.24,6.401006794,-1.758980202,61.71321072 +97.7,50.42581778,-2.582297219,48.5024,4.731095738,8.806685177,0.1753125,6.299245307,-1.671267926,61.7056856 +97.71,50.42581821,-2.58229598,48.501,4.731095728,8.805352702,0.1115625,6.197212525,-1.582098276,61.69816055 +97.72,50.42581863,-2.582294741,48.5002,4.74152429,8.803576096,0.048125,6.094929703,-1.491549,61.69063544 +97.73,50.42581906,-2.582293502,48.5,4.748476673,8.802243622,-0.016875,5.992418272,-1.399699052,61.68311038 +97.74,50.42581949,-2.582292264,48.5005,4.745000494,8.802243543,-0.083125,5.889699544,-1.30662859,61.67558527 +97.75,50.42581991,-2.582291025,48.5017,4.745000504,8.803131729,-0.148125,5.786795006,-1.212418687,61.66806021 +97.76,50.42582034,-2.582289786,48.5035,4.748476699,8.802909586,-0.2115625,5.683726144,-1.117151562,61.6605351 +97.77,50.42582077,-2.582288547,48.5059,4.74500051,8.801132984,-0.275,5.580514558,-1.020910294,61.65301004 +97.78,50.42582119,-2.582287309,48.509,4.748476701,8.799800515,-0.3384375,5.477181677,-0.923778707,61.64548493 +97.79,50.42582162,-2.582286071,48.5127,4.762381461,8.799800441,-0.4015625,5.373749159,-0.825841656,61.63795987 +97.8,50.42582205,-2.582284832,48.517,4.762381453,8.799578301,-0.4653125,5.270238604,-0.727184397,61.63043476 +97.81,50.42582248,-2.582283594,48.522,4.748476692,8.7984679,-0.53,5.166671612,-0.627893046,61.6229097 +97.82,50.4258229,-2.582282356,48.5276,4.745000517,8.797579566,-0.5946875,5.063069785,-0.528054119,61.61538459 +97.83,50.42582333,-2.582281118,48.5339,4.748476722,8.797135364,-0.658125,4.959454836,-0.427754763,61.60785954 +97.84,50.42582376,-2.58227988,48.5408,4.745000538,8.796247032,-0.72,4.855848311,-0.327082411,61.60033442 +97.85,50.42582418,-2.582278642,48.5483,4.748476735,8.795136634,-0.781875,4.752271923,-0.226124784,61.59280937 +97.86,50.42582461,-2.582277405,48.5564,4.765857696,8.7949145,-0.845,4.648747215,-0.124970002,61.58528425 +97.87,50.42582504,-2.582276167,48.5652,4.776286268,8.794914433,-0.908125,4.545295904,-0.023706243,61.5777592 +97.88,50.42582547,-2.582274929,48.5746,4.76585769,8.793804038,-0.9696875,4.441939532,0.077578142,61.57023414 +97.89,50.4258259,-2.582273692,48.5846,4.748476742,8.792693643,-1.03,4.338699756,0.178794918,61.56270903 +97.9,50.42582632,-2.582272455,48.5952,4.748476761,8.792693578,-1.09,4.235598006,0.279855792,61.55518397 +97.91,50.42582675,-2.582271217,48.6064,4.765857735,8.792471449,-1.15,4.13265594,0.380672643,61.54765886 +97.92,50.42582718,-2.58226998,48.6182,4.779762511,8.791361057,-1.2096875,4.029894985,0.481157523,61.5401338 +97.93,50.42582761,-2.582268743,48.6306,4.78323871,8.790472732,-1.2684375,3.927336686,0.581222769,61.53260869 +97.94,50.42582804,-2.582267506,48.6436,4.77976252,8.790250604,-1.3265625,3.825002298,0.680781233,61.52508364 +97.95,50.42582847,-2.582266269,48.6571,4.765857754,8.790028478,-1.385,3.722913366,0.779746056,61.51755852 +97.96,50.4258289,-2.582265032,48.6713,4.748476809,8.789140155,-1.443125,3.621091145,0.878030949,61.51003347 +97.97,50.42582932,-2.582263795,48.686,4.748476831,8.788029767,-1.4996875,3.519556836,0.975550142,61.50250835 +97.98,50.42582975,-2.582262559,48.7013,4.765857808,8.787807644,-1.555,3.418331752,1.072218665,61.4949833 +97.99,50.42583018,-2.582261322,48.7171,4.779762588,8.787807586,-1.61,3.317436921,1.167952177,61.48745818 +98,50.42583061,-2.582260085,48.7335,4.78323879,8.7866972,-1.665,3.216893485,1.2626672,61.47993313 +98.01,50.42583104,-2.582258849,48.7504,4.783238794,8.785586815,-1.7196875,3.116722472,1.356281227,61.47240802 +98.02,50.42583147,-2.582257613,48.7679,4.783238796,8.78558676,-1.7734375,3.016944736,1.448712498,61.46488296 +98.03,50.4258319,-2.582256376,48.7859,4.78323881,8.785364639,-1.82625,2.917581135,1.539880453,61.45735785 +98.04,50.42583233,-2.58225514,48.8044,4.783238836,8.784254256,-1.8784375,2.818652409,1.629705683,61.44983279 +98.05,50.42583276,-2.582253904,48.8235,4.783238859,8.783143874,-1.9296875,2.720179241,1.718109747,61.44230768 +98.06,50.42583319,-2.582252668,48.843,4.783238876,8.782033492,-1.9796875,2.622182201,1.805015585,61.43478262 +98.07,50.42583362,-2.582251432,48.8631,4.783238892,8.780923112,-2.0284375,2.524681687,1.890347392,61.42725751 +98.08,50.42583405,-2.582250197,48.8836,4.783238905,8.780700995,-2.07625,2.427698152,1.974030858,61.41973245 +98.09,50.42583448,-2.582248961,48.9046,4.783238912,8.78092301,-2.1234375,2.331251823,2.055992871,61.41220734 +98.1,50.42583491,-2.582247725,48.9261,4.783238918,8.780478829,-2.17,2.235362752,2.1361621,61.40468228 +98.11,50.42583534,-2.58224649,48.948,4.783238935,8.779590517,-2.21625,2.140051108,2.214468528,61.39715717 +98.12,50.42583577,-2.582245254,48.9704,4.783238963,8.778702206,-2.2615625,2.045336716,2.290843917,61.38963212 +98.13,50.4258362,-2.582244019,48.9933,4.783238989,8.778258026,-2.3046875,1.951239341,2.365221631,61.382107 +98.14,50.42583663,-2.582242784,49.0165,4.783239009,8.778480044,-2.346875,1.857778695,2.437536812,61.37458195 +98.15,50.42583706,-2.582241548,49.0402,4.783239025,8.778257931,-2.39,1.764974257,2.507726491,61.36705683 +98.16,50.42583749,-2.582240313,49.0643,4.786715226,8.777147555,-2.4325,1.672845394,2.575729362,61.35953178 +98.17,50.42583792,-2.582239078,49.0889,4.80062,8.776037181,-2.4715625,1.581411414,2.641486181,61.35200666 +98.18,50.42583835,-2.582237843,49.1138,4.818000977,8.774926807,-2.508125,1.490691282,2.704939538,61.34448161 +98.19,50.42583879,-2.582236608,49.139,4.818001008,8.773594367,-2.5453125,1.400704078,2.766034199,61.3369565 +98.2,50.42583922,-2.582235374,49.1647,4.800620078,8.77270606,-2.583125,1.311468537,2.824716823,61.32943144 +98.21,50.42583965,-2.582234139,49.1907,4.786715334,8.77248395,-2.619375,1.22300328,2.880936244,61.32190633 +98.22,50.42584008,-2.582232905,49.2171,4.78323916,8.772483907,-2.653125,1.135326815,2.934643417,61.31438127 +98.23,50.42584051,-2.58223167,49.2438,4.786715364,8.772483864,-2.6846875,1.048457475,2.985791589,61.30685622 +98.24,50.42584094,-2.582230436,49.2708,4.80062014,8.772261756,-2.7153125,0.962413309,3.034336068,61.2993311 +98.25,50.42584137,-2.582229201,49.2981,4.818001119,8.771373451,-2.7465625,0.877212365,3.080234571,61.29180605 +98.26,50.42584181,-2.582227967,49.3257,4.818001151,8.770041014,-2.7778125,0.792872404,3.123447105,61.28428093 +98.27,50.42584224,-2.582226733,49.3537,4.804096415,8.76915271,-2.8065625,0.709411017,3.163935913,61.27675588 +98.28,50.42584267,-2.582225499,49.3819,4.804096436,8.768930604,-2.8328125,0.626845679,3.201665699,61.26923076 +98.29,50.4258431,-2.582224265,49.4103,4.818001216,8.768708497,-2.8584375,0.545193635,3.236603577,61.26170571 +98.3,50.42584354,-2.582223031,49.4391,4.818001227,8.767820193,-2.883125,0.464471961,3.268719122,61.2541806 +98.31,50.42584397,-2.582221797,49.468,4.804096482,8.766487758,-2.90625,0.384697385,3.297984316,61.24665554 +98.32,50.4258444,-2.582220564,49.4972,4.804096516,8.765599456,-2.9284375,0.305886754,3.324373607,61.23913043 +98.33,50.42584483,-2.58221933,49.5266,4.818001312,8.76537735,-2.9496875,0.228056339,3.347863959,61.23160537 +98.34,50.42584527,-2.582218097,49.5562,4.818001328,8.765377311,-2.97,0.151222527,3.36843492,61.22408026 +98.35,50.4258457,-2.582216863,49.586,4.80409657,8.765377273,-2.9896875,0.075401303,3.386068613,61.2165552 +98.36,50.42584613,-2.58221563,49.616,4.804096585,8.765155169,-3.0078125,0.000608538,3.400749568,61.20903009 +98.37,50.42584656,-2.582214396,49.6462,4.818001375,8.764266868,-3.023125,-0.073140182,3.412465008,61.20150503 +98.38,50.425847,-2.582213163,49.6765,4.821477599,8.762934435,-3.03625,-0.145829447,3.421204734,61.19397992 +98.39,50.42584743,-2.58221193,49.7069,4.818001444,8.761824068,-3.0484375,-0.217444015,3.426961127,61.18645486 +98.4,50.42584786,-2.582210697,49.7375,4.821477668,8.760713701,-3.06,-0.287969046,3.4297292,61.17892975 +98.41,50.4258483,-2.582209464,49.7681,4.821477692,8.759381269,-3.07125,-0.357389759,3.429506434,61.1714047 +98.42,50.42584873,-2.582208232,49.7989,4.818001515,8.758492969,-3.0815625,-0.425691599,3.426293115,61.16387958 +98.43,50.42584916,-2.582206999,49.8298,4.824953911,8.758270865,-3.0896875,-0.492860415,3.420091993,61.15635453 +98.44,50.4258496,-2.582205767,49.8607,4.835382511,8.758270827,-3.09625,-0.558882056,3.410908568,61.14882941 +98.45,50.42585003,-2.582204534,49.8917,4.835382546,8.75827079,-3.1015625,-0.623742826,3.39875069,61.14130436 +98.46,50.42585047,-2.582203302,49.9228,4.824954002,8.758048687,-3.1046875,-0.687429148,3.383629131,61.13377924 +98.47,50.4258509,-2.582202069,49.9538,4.818001644,8.757160387,-3.1065625,-0.749927728,3.365556953,61.12625419 +98.48,50.42585133,-2.582200837,49.9849,4.82495405,8.755827955,-3.1084375,-0.811225503,3.344549971,61.11872908 +98.49,50.42585177,-2.582199605,50.016,4.835382641,8.754939654,-3.109375,-0.871309696,3.320626463,61.11120402 +98.5,50.4258522,-2.582198373,50.0471,4.838858846,8.754717551,-3.108125,-0.930167702,3.293807339,61.10367891 +98.51,50.42585264,-2.582197141,50.0782,4.83885887,8.754717514,-3.105,-0.987787318,3.264115979,61.09615385 +98.52,50.42585307,-2.582195909,50.1092,4.838858903,8.754495411,-3.10125,-1.044156395,3.231578221,61.08862874 +98.53,50.42585351,-2.582194677,50.1402,4.838858925,8.75360711,-3.0965625,-1.099263304,3.196222543,61.08110368 +98.54,50.42585394,-2.582193445,50.1712,4.838858931,8.752274678,-3.0896875,-1.153096413,3.158079654,61.07357857 +98.55,50.42585438,-2.582192214,50.202,4.838858944,8.751386377,-3.08125,-1.20564455,3.1171829,61.06605351 +98.56,50.42585481,-2.582190982,50.2328,4.838858978,8.751164274,-3.071875,-1.256896713,3.073567921,61.0585284 +98.57,50.42585525,-2.582189751,50.2635,4.838859022,8.75094217,-3.0609375,-1.306842189,3.027272759,61.05100334 +98.58,50.42585568,-2.582188519,50.294,4.838859057,8.750275935,-3.0484375,-1.355470549,2.978337751,61.04347829 +98.59,50.42585612,-2.582187288,50.3245,4.838859082,8.749609699,-3.035,-1.402771653,2.926805584,61.03595318 +98.6,50.42585655,-2.582186057,50.3547,4.838859103,8.749165529,-3.02125,-1.448735645,2.872721175,61.02842812 +98.61,50.42585699,-2.582184825,50.3849,4.838859118,8.748499293,-3.0065625,-1.4933529,2.816131738,61.02090301 +98.62,50.42585742,-2.582183595,50.4149,4.83885913,8.747610991,-2.989375,-1.536614078,2.757086604,61.01337795 +98.63,50.42585786,-2.582182363,50.4447,4.842335345,8.746722689,-2.97,-1.578510185,2.695637224,61.00585284 +98.64,50.42585829,-2.582181133,50.4743,4.852763956,8.746056452,-2.9496875,-1.619032453,2.631837228,60.99832778 +98.65,50.42585873,-2.582179902,50.5037,4.859716372,8.745390216,-2.928125,-1.65817246,2.565742192,60.99080267 +98.66,50.42585917,-2.582178671,50.5329,4.85276401,8.744057781,-2.905,-1.695921899,2.497409813,60.98327761 +98.67,50.4258596,-2.582177441,50.5618,4.842335444,8.742947412,-2.8815625,-1.732273035,2.426899678,60.9757525 +98.68,50.42586004,-2.582176211,50.5905,4.842335447,8.742947371,-2.858125,-1.767218246,2.354273267,60.96822744 +98.69,50.42586047,-2.58217498,50.619,4.852764035,8.74294733,-2.8328125,-1.8007502,2.279593833,60.96070233 +98.7,50.42586091,-2.58217375,50.6472,4.859716452,8.742725222,-2.805,-1.832861906,2.20292658,60.95317727 +98.71,50.42586135,-2.58217252,50.6751,4.856240299,8.74272518,-2.7765625,-1.863546604,2.124338371,60.94565216 +98.72,50.42586178,-2.582171289,50.7027,4.859716516,8.741614808,-2.7478125,-1.89279799,2.043897675,60.93812711 +98.73,50.42586222,-2.582170059,50.7301,4.873621298,8.739394109,-2.7165625,-1.920609877,1.961674679,60.93060199 +98.74,50.42586266,-2.58216883,50.7571,4.873621319,8.738505803,-2.683125,-1.946976478,1.877741117,60.92307694 +98.75,50.4258631,-2.5821676,50.7837,4.85971658,8.739171956,-2.65,-1.97189235,1.7921701,60.91555182 +98.76,50.42586353,-2.58216637,50.8101,4.856240417,8.739171912,-2.6165625,-1.995352164,1.705036283,60.90802677 +98.77,50.42586397,-2.58216514,50.8361,4.859716628,8.738061539,-2.58125,-2.017351108,1.61641564,60.90050166 +98.78,50.42586441,-2.582163911,50.8617,4.856240437,8.736951165,-2.545,-2.037884597,1.526385464,60.8929766 +98.79,50.42586484,-2.582162681,50.887,4.859716628,8.736062856,-2.508125,-2.056948278,1.43502425,60.88545149 +98.8,50.42586528,-2.582161452,50.9119,4.873621417,8.735618677,-2.4696875,-2.074538197,1.342411695,60.87792643 +98.81,50.42586572,-2.582160223,50.9364,4.873621458,8.735840696,-2.4296875,-2.090650744,1.248628531,60.87040132 +98.82,50.42586616,-2.582158993,50.9605,4.859716724,8.735618583,-2.3884375,-2.105282482,1.153756518,60.86287626 +98.83,50.42586659,-2.582157764,50.9842,4.859716745,8.734508207,-2.34625,-2.118430317,1.057878448,60.85535115 +98.84,50.42586703,-2.582156535,51.0074,4.877097717,8.73339783,-2.3034375,-2.130091612,0.961077859,60.84782609 +98.85,50.42586747,-2.582155306,51.0303,4.891002495,8.732287453,-2.2596875,-2.140263847,0.863439204,60.84030098 +98.86,50.42586791,-2.582154077,51.0526,4.891002512,8.731177075,-2.2146875,-2.14894496,0.765047626,60.83277592 +98.87,50.42586835,-2.582152849,51.0746,4.877097767,8.730954958,-2.1684375,-2.156133117,0.665988952,60.82525081 +98.88,50.42586879,-2.58215162,51.096,4.859716819,8.731176973,-2.1215625,-2.16182677,0.566349472,60.81772576 +98.89,50.42586922,-2.582150391,51.117,4.859716818,8.730732789,-2.075,-2.166024775,0.466216159,60.81020064 +98.9,50.42586966,-2.582149163,51.1375,4.877097786,8.729844474,-2.0278125,-2.168726271,0.365676275,60.80267559 +98.91,50.4258701,-2.582147934,51.1576,4.891002583,8.728734092,-1.978125,-2.169930628,0.264817483,60.79515047 +98.92,50.42587054,-2.582146706,51.1771,4.894478811,8.727401644,-1.9265625,-2.169637675,0.163727847,60.78762542 +98.93,50.42587098,-2.582145478,51.1961,4.894478835,8.726513328,-1.8753125,-2.167847411,0.062495372,60.78010036 +98.94,50.42587142,-2.58214425,51.2146,4.89100265,8.726291206,-1.8246875,-2.164560295,-0.038791535,60.77257525 +98.95,50.42587186,-2.582143022,51.2326,4.877097883,8.72629115,-1.773125,-2.159776899,-0.140044693,60.76505019 +98.96,50.4258723,-2.582141794,51.2501,4.85971693,8.726069027,-1.7196875,-2.153498256,-0.241175698,60.75752508 +98.97,50.42587273,-2.582140566,51.267,4.859716946,8.725180707,-1.665,-2.14572574,-0.342096369,60.75000002 +98.98,50.42587317,-2.582139338,51.2834,4.87709792,8.724070322,-1.61,-2.136460897,-0.442718759,60.74247491 +98.99,50.42587361,-2.582138111,51.2992,4.891002704,8.723848197,-1.5546875,-2.125705735,-0.542955032,60.73494985 +99,50.42587405,-2.582136883,51.3145,4.894478911,8.723848137,-1.498125,-2.113462429,-0.642717928,60.72742474 +99.01,50.42587449,-2.582135655,51.3292,4.89447892,8.722515682,-1.44,-2.099733558,-0.741920299,60.71989969 +99.02,50.42587493,-2.582134428,51.3433,4.894478934,8.720739096,-1.381875,-2.084521987,-0.840475743,60.71237457 +99.03,50.42587537,-2.582133201,51.3568,4.894478956,8.720294902,-1.325,-2.067830981,-0.93829826,60.70484952 +99.04,50.42587581,-2.582131974,51.3698,4.894478973,8.720516905,-1.268125,-2.049663865,-1.035302536,60.6973244 +99.05,50.42587625,-2.582130746,51.3822,4.894478974,8.72007271,-1.209375,-2.030024533,-1.131404059,60.68979935 +99.06,50.42587669,-2.58212952,51.394,4.894478963,8.719184383,-1.1484375,-2.008917112,-1.226519006,60.68227424 +99.07,50.42587713,-2.582128292,51.4052,4.894478961,8.718296055,-1.086875,-1.986345955,-1.320564356,60.67474918 +99.08,50.42587757,-2.582127066,51.4157,4.894478981,8.717629792,-1.0265625,-1.962315761,-1.413458175,60.66722407 +99.09,50.42587801,-2.582125839,51.4257,4.894479006,8.717185593,-0.9665625,-1.93683163,-1.505119448,60.65969901 +99.1,50.42587845,-2.582124612,51.4351,4.897955209,8.716519328,-0.9046875,-1.909898775,-1.595468188,60.6521739 +99.11,50.42587889,-2.582123386,51.4438,4.911859979,8.715853062,-0.841875,-1.881522868,-1.684425673,60.64464884 +99.12,50.42587933,-2.582122159,51.4519,4.929240947,8.715630926,-0.78,-1.851709926,-1.77191438,60.63712373 +99.13,50.42587978,-2.582120933,51.4594,4.929240956,8.71540879,-0.718125,-1.820466022,-1.857857878,60.62959867 +99.14,50.42588022,-2.582119706,51.4663,4.911859993,8.714520455,-0.655,-1.787797744,-1.942181337,60.62207356 +99.15,50.42588066,-2.58211848,51.4725,4.89795522,8.713187989,-0.591875,-1.75371197,-2.024811133,60.6145485 +99.16,50.4258811,-2.582117254,51.4781,4.894479031,8.712299654,-0.5296875,-1.718215744,-2.105675302,60.60702339 +99.17,50.42588154,-2.582116028,51.4831,4.894479045,8.712077515,-0.4665625,-1.681316518,-2.184703314,60.59949833 +99.18,50.42588198,-2.582114802,51.4875,4.897955254,8.711855375,-0.4015625,-1.643021967,-2.261826183,60.59197322 +99.19,50.42588242,-2.582113576,51.4911,4.911860034,8.710967036,-0.336875,-1.603340113,-2.336976702,60.58444817 +99.2,50.42588286,-2.58211235,51.4942,4.929240985,8.709634565,-0.2734375,-1.562279207,-2.410089383,60.57692305 +99.21,50.42588331,-2.582111125,51.4966,4.929240965,8.708746225,-0.2096875,-1.519847901,-2.481100454,60.569398 +99.22,50.42588375,-2.582109899,51.4984,4.911860003,8.708524081,-0.145,-1.47605496,-2.549947922,60.56187288 +99.23,50.42588419,-2.582108674,51.4995,4.901431447,8.708301936,-0.08,-1.43090961,-2.616571799,60.55434783 +99.24,50.42588463,-2.582107448,51.5,4.911860044,8.707413593,-0.015,-1.384421247,-2.680913985,60.54682272 +99.25,50.42588507,-2.582106223,51.4998,4.929241011,8.706303184,0.05,-1.336599554,-2.742918389,60.53929766 +99.26,50.42588552,-2.582104998,51.499,4.929241,8.706081036,0.1146875,-1.287454558,-2.802530923,60.5317726 +99.27,50.42588596,-2.582103773,51.4975,4.915336208,8.706080953,0.1784375,-1.236996514,-2.859699621,60.52424749 +99.28,50.4258864,-2.582102547,51.4954,4.915336195,8.704970541,0.2415625,-1.185235965,-2.914374577,60.51672243 +99.29,50.42588684,-2.582101323,51.4927,4.929240974,8.703860128,0.3053125,-1.132183683,-2.966508178,60.50919732 +99.3,50.42588729,-2.582100098,51.4893,4.929240983,8.704082107,0.37,-1.077850783,-3.016054933,60.50167227 +99.31,50.42588773,-2.582098873,51.4853,4.915336209,8.704526152,0.4346875,-1.022248609,-3.062971639,60.49414715 +99.32,50.42588817,-2.582097648,51.4806,4.915336205,8.703859869,0.4984375,-0.965388793,-3.107217446,60.4866221 +99.33,50.42588861,-2.582096423,51.4753,4.929240975,8.702527387,0.5615625,-0.907283138,-3.148753677,60.47909698 +99.34,50.42588906,-2.582095199,51.4694,4.93271716,8.701416969,0.625,-0.847943847,-3.187544123,60.47157193 +99.35,50.4258895,-2.582093974,51.4628,4.929240955,8.700306551,0.688125,-0.787383239,-3.223554979,60.46404681 +99.36,50.42588994,-2.58209275,51.4556,4.932717143,8.698974067,0.75,-0.725614034,-3.256754904,60.45652176 +99.37,50.42589039,-2.582091526,51.4478,4.932717146,8.698085714,0.811875,-0.662649124,-3.287114849,60.44899665 +99.38,50.42589083,-2.582090302,51.4394,4.929240958,8.697863555,0.8746875,-0.598501686,-3.314608343,60.44147159 +99.39,50.42589127,-2.582089078,51.4303,4.932717142,8.697863462,0.9365625,-0.533185013,-3.339211495,60.43394648 +99.4,50.42589172,-2.582087854,51.4206,4.932717118,8.697641302,0.9965625,-0.466712799,-3.360902817,60.42642142 +99.41,50.42589216,-2.58208663,51.4104,4.929240906,8.696752945,1.056875,-0.399098966,-3.379663403,60.41889631 +99.42,50.4258926,-2.582085406,51.3995,4.936193295,8.695642521,1.1184375,-0.330357553,-3.395476809,60.41137125 +99.43,50.42589305,-2.582084183,51.388,4.946621885,8.695420358,1.1796875,-0.260502996,-3.408329341,60.40384614 +99.44,50.42589349,-2.582082959,51.3759,4.950098075,8.69542026,1.2396875,-0.189549851,-3.418209769,60.39632108 +99.45,50.42589394,-2.582081735,51.3632,4.95009805,8.694087768,1.298125,-0.117512956,-3.425109442,60.38879597 +99.46,50.42589438,-2.582080512,51.3499,4.946621825,8.692311144,1.355,-0.044407323,-3.4290224,60.38127091 +99.47,50.42589483,-2.582079289,51.3361,4.936193237,8.692088979,1.411875,0.029751808,-3.429945148,60.3737458 +99.48,50.42589527,-2.582078066,51.3217,4.929240862,8.69297714,1.47,0.104948909,-3.427877,60.36622075 +99.49,50.42589571,-2.582076842,51.3067,4.936193252,8.692977039,1.528125,0.181168223,-3.422819616,60.35869563 +99.5,50.42589616,-2.582075619,51.2911,4.946621812,8.691644543,1.584375,0.258393939,-3.414777523,60.35117058 +99.51,50.4258966,-2.582074396,51.275,4.950097973,8.689867915,1.6384375,0.33660984,-3.403757711,60.34364546 +99.52,50.42589705,-2.582073173,51.2583,4.950097949,8.688313352,1.6915625,0.415799655,-3.389769749,60.33612041 +99.53,50.42589749,-2.582071951,51.2412,4.950097945,8.687424986,1.745,0.495946824,-3.37282584,60.32859529 +99.54,50.42589794,-2.582070728,51.2234,4.950097943,8.687424881,1.7984375,0.577034619,-3.352940824,60.32107024 +99.55,50.42589838,-2.582069506,51.2052,4.950097927,8.688090971,1.85125,0.659046079,-3.330131947,60.31354513 +99.56,50.42589883,-2.582068283,51.1864,4.953574099,8.688312929,1.9034375,0.741964073,-3.304419205,60.30602007 +99.57,50.42589927,-2.58206706,51.1671,4.964002662,8.686980428,1.954375,0.825771297,-3.275824887,60.29849496 +99.58,50.42589972,-2.582065838,51.1473,4.970955039,8.68498173,2.0034375,0.910450276,-3.244374031,60.2909699 +99.59,50.42590017,-2.582064616,51.127,4.964002643,8.683871294,2.0515625,0.995983307,-3.21009408,60.28344479 +99.6,50.42590061,-2.582063394,51.1063,4.953574045,8.683649118,2.0996875,1.082352512,-3.17301483,60.27591973 +99.61,50.42590106,-2.582062172,51.085,4.950097829,8.683649008,2.146875,1.169539901,-3.133168652,60.26839468 +99.62,50.4259015,-2.58206095,51.0633,4.950097811,8.683426832,2.1928125,1.257527196,-3.090590325,60.26086956 +99.63,50.42590195,-2.582059728,51.0412,4.953573986,8.682538459,2.2384375,1.346296063,-3.045316976,60.25334451 +99.64,50.42590239,-2.582058506,51.0185,4.964002549,8.681428019,2.283125,1.435827995,-2.997388025,60.24581939 +99.65,50.42590284,-2.582057285,50.9955,4.970954926,8.68120584,2.32625,1.526104256,-2.946845355,60.23829434 +99.66,50.42590329,-2.582056063,50.972,4.967478726,8.681205726,2.3684375,1.61710594,-2.89373297,60.23076923 +99.67,50.42590373,-2.582054841,50.9481,4.967478706,8.680095285,2.4096875,1.708814137,-2.838097164,60.22324417 +99.68,50.42590418,-2.58205362,50.9238,4.970954862,8.678984843,2.4496875,1.801209655,-2.779986524,60.21571906 +99.69,50.42590463,-2.582052399,50.8991,4.96747864,8.678984728,2.4884375,1.894273184,-2.719451699,60.208194 +99.7,50.42590507,-2.582051177,50.874,4.967478632,8.678762547,2.52625,1.987985302,-2.656545517,60.20066889 +99.71,50.42590552,-2.582049956,50.8486,4.97095482,8.677652103,2.5634375,2.08232647,-2.591322752,60.19314383 +99.72,50.42590597,-2.582048735,50.8227,4.967478601,8.676541659,2.5996875,2.177276921,-2.523840298,60.18561872 +99.73,50.42590641,-2.582047514,50.7966,4.970954754,8.675431215,2.6346875,2.272816889,-2.454156999,60.17809366 +99.74,50.42590686,-2.582046293,50.77,4.984859503,8.674098704,2.6684375,2.368926433,-2.382333703,60.17056855 +99.75,50.42590731,-2.582045073,50.7432,4.984859503,8.673210324,2.7009375,2.465585387,-2.308432919,60.16304349 +99.76,50.42590776,-2.582043852,50.716,4.970954719,8.67298814,2.731875,2.56277364,-2.232519163,60.15551838 +99.77,50.4259082,-2.582042632,50.6885,4.970954682,8.672988022,2.76125,2.660470851,-2.15465861,60.14799333 +99.78,50.42590865,-2.582041411,50.6608,4.98485942,8.672765837,2.79,2.758656623,-2.074919214,60.14046821 +99.79,50.4259091,-2.582040191,50.6327,4.984859409,8.671877454,2.8184375,2.857310559,-1.993370418,60.13294316 +99.8,50.42590955,-2.58203897,50.6044,4.970954633,8.670767007,2.84625,2.95641186,-1.910083382,60.12541804 +99.81,50.42590999,-2.582037751,50.5758,4.970954605,8.670322756,2.8728125,3.055940015,-1.8251307,60.11789299 +99.82,50.42591044,-2.58203653,50.5469,4.988335524,8.669656439,2.8965625,3.155874167,-1.738586514,60.11036787 +99.83,50.42591089,-2.58203531,50.5178,4.998764079,8.66810186,2.918125,3.256193405,-1.650526224,60.10284282 +99.84,50.42591134,-2.582034091,50.4886,4.988335502,8.667435542,2.94,3.356876815,-1.561026664,60.09531771 +99.85,50.42591179,-2.582032871,50.459,4.970954531,8.668323682,2.96125,3.457903369,-1.470165871,60.08779265 +99.86,50.42591223,-2.582031651,50.4293,4.970954495,8.668989756,2.979375,3.559251982,-1.378023028,60.08026754 +99.87,50.42591268,-2.582030431,50.3994,4.988335411,8.668101372,2.9953125,3.660901513,-1.284678577,60.07274248 +99.88,50.42591313,-2.582029211,50.3694,5.002240157,8.665880596,3.0115625,3.762830648,-1.190213879,60.06521737 +99.89,50.42591358,-2.582027992,50.3392,5.005716344,8.663881885,3.028125,3.865018129,-1.094711269,60.05769231 +99.9,50.42591403,-2.582026773,50.3088,5.00571632,8.663659695,3.043125,3.9674427,-0.998254053,60.0501672 +99.91,50.42591448,-2.582025554,50.2783,5.005716279,8.664547833,3.05625,4.070082875,-0.900926343,60.04264214 +99.92,50.42591493,-2.582024334,50.2477,5.002240063,8.664547709,3.068125,4.172917226,-0.80281305,60.03511703 +99.93,50.42591538,-2.582023115,50.2169,4.988335289,8.663437259,3.0778125,4.275924323,-0.70399966,60.02759197 +99.94,50.42591583,-2.582021896,50.1861,4.970954304,8.662326809,3.085,4.379082681,-0.604572346,60.02006686 +99.95,50.42591627,-2.582020677,50.1552,4.970954262,8.661216359,3.0915625,4.482370642,-0.504617853,60.01254181 +99.96,50.42591672,-2.582019458,50.1243,4.988335199,8.660105908,3.098125,4.58576672,-0.404223329,60.00501675 +99.97,50.42591717,-2.58201824,50.0932,5.002239966,8.659883719,3.103125,4.689249315,-0.303476321,59.99749164 +99.98,50.42591762,-2.582017021,50.0622,5.005716148,8.659883594,3.10625,4.792796826,-0.202464721,59.98996658 +99.99,50.42591807,-2.582015802,50.0311,5.00571611,8.658773143,3.1084375,4.896387596,-0.101276536,59.98244147 +100,50.42591852,-2.582014584,50,5.005716064,8.657662692,3.109375,5.000000023,0,59.97491641 +100.01,50.42591897,-2.582013366,49.9689,5.00571604,8.657662568,3.1084375,5.103612393,0.101276536,59.9673913 +100.02,50.42591942,-2.582012147,49.9378,5.005716034,8.657440379,3.10625,5.207203162,0.202464721,59.95986624 +100.03,50.42591987,-2.582010929,49.9068,5.00571601,8.656107862,3.103125,5.310750673,0.303476321,59.95234113 +100.04,50.42592032,-2.582009711,49.8757,5.005715968,8.654331215,3.098125,5.414233268,0.404223329,59.94481607 +100.05,50.42592077,-2.582008493,49.8448,5.005715944,8.652998699,3.0915625,5.517629346,0.504617853,59.93729096 +100.06,50.42592122,-2.582007276,49.8139,5.00919213,8.652998575,3.085,5.620917308,0.604572346,59.92976591 +100.07,50.42592167,-2.582006058,49.7831,5.023096874,8.653886713,3.0778125,5.724075666,0.70399966,59.92224079 +100.08,50.42592212,-2.58200484,49.7523,5.040477792,8.653886589,3.068125,5.827082763,0.80281305,59.91471574 +100.09,50.42592258,-2.582003622,49.7217,5.040477769,8.652776139,3.05625,5.929917113,0.900926343,59.90719062 +100.1,50.42592303,-2.582002405,49.6912,5.023096803,8.651665688,3.043125,6.032557289,0.998254053,59.89966557 +100.11,50.42592348,-2.582001187,49.6608,5.009192012,8.650777303,3.028125,6.13498186,1.094711269,59.89214045 +100.12,50.42592393,-2.58199997,49.6306,5.005715779,8.650333049,3.0115625,6.237169341,1.190213879,59.8846154 +100.13,50.42592438,-2.581998753,49.6006,5.005715756,8.650554992,2.9953125,6.339098532,1.284678577,59.87709029 +100.14,50.42592483,-2.581997535,49.5707,5.00571575,8.650332805,2.979375,6.440748006,1.378023028,59.86956523 +100.15,50.42592528,-2.581996318,49.541,5.009191919,8.64900029,2.96125,6.54209662,1.470165871,59.86204012 +100.16,50.42592573,-2.581995101,49.5114,5.023096646,8.647223646,2.94,6.643123174,1.561026664,59.85451506 +100.17,50.42592618,-2.581993884,49.4822,5.040477582,8.645669067,2.918125,6.743806584,1.650526224,59.84698995 +100.18,50.42592664,-2.581992668,49.4531,5.040477577,8.644780684,2.8965625,6.844125878,1.738586514,59.83946489 +100.19,50.42592709,-2.581991451,49.4242,5.023096596,8.644558497,2.8728125,6.944059974,1.8251307,59.83193978 +100.2,50.42592754,-2.581990235,49.3956,5.012667981,8.644336311,2.84625,7.043588129,1.910083382,59.82441472 +100.21,50.42592799,-2.581989018,49.3673,5.023096532,8.643669994,2.8184375,7.142689487,1.993370418,59.81688961 +100.22,50.42592844,-2.581987802,49.3392,5.04047748,8.643225743,2.79,7.241343366,2.074919214,59.80936455 +100.23,50.4259289,-2.581986586,49.3115,5.040477456,8.643447688,2.76125,7.339529138,2.15465861,59.80183944 +100.24,50.42592935,-2.581985369,49.284,5.026572662,8.643225504,2.731875,7.437226406,2.232519163,59.79431439 +100.25,50.4259298,-2.581984153,49.2568,5.026572649,8.642115059,2.7009375,7.534414658,2.308432919,59.78678927 +100.26,50.42593025,-2.581982937,49.23,5.040477404,8.641226679,2.6684375,7.631073612,2.382333703,59.77926422 +100.27,50.42593071,-2.581981721,49.2034,5.040477375,8.640782429,2.6346875,7.7271831,2.454156999,59.7717391 +100.28,50.42593116,-2.581980505,49.1773,5.026572579,8.639894051,2.5996875,7.822723068,2.523840298,59.76421405 +100.29,50.42593161,-2.581979289,49.1514,5.026572568,8.638561542,2.5634375,7.917673519,2.591322752,59.75668893 +100.3,50.42593206,-2.581978074,49.126,5.040477323,8.637673165,2.52625,8.012014687,2.656545517,59.74916388 +100.31,50.42593252,-2.581976858,49.1009,5.043953487,8.637450983,2.4884375,8.105726804,2.719451699,59.74163882 +100.32,50.42593297,-2.581975643,49.0762,5.040477265,8.637228802,2.4496875,8.198790333,2.779986524,59.73411371 +100.33,50.42593342,-2.581974427,49.0519,5.04395344,8.636340425,2.4096875,8.291185851,2.838097164,59.72658865 +100.34,50.42593388,-2.581973212,49.028,5.043953428,8.635007918,2.3684375,8.382894049,2.89373297,59.71906354 +100.35,50.42593433,-2.581971997,49.0045,5.040477221,8.634119543,2.32625,8.47389579,2.946845355,59.71153849 +100.36,50.42593478,-2.581970782,48.9815,5.043953394,8.633897365,2.283125,8.564171994,2.997388025,59.70401337 +100.37,50.42593524,-2.581969567,48.9588,5.043953375,8.633897252,2.2384375,8.653703926,3.045316976,59.69648832 +100.38,50.42593569,-2.581968352,48.9367,5.040477159,8.633675074,2.1928125,8.742472793,3.090590325,59.6889632 +100.39,50.42593614,-2.581967137,48.915,5.047429521,8.632786701,2.146875,8.830460088,3.133168652,59.68143815 +100.4,50.4259366,-2.581965922,48.8937,5.057858083,8.631454199,2.0996875,8.917647477,3.17301483,59.67391303 +100.41,50.42593705,-2.581964708,48.873,5.057858074,8.630565828,2.0515625,9.004016682,3.21009408,59.66638798 +100.42,50.42593751,-2.581963493,48.8527,5.047429486,8.630343652,2.0034375,9.089549712,3.244374031,59.65886287 +100.43,50.42593796,-2.581962279,48.8329,5.040477088,8.630121477,1.954375,9.174228692,3.275824887,59.65133781 +100.44,50.42593841,-2.581961064,48.8136,5.047429456,8.629233108,1.9034375,9.258035916,3.304419205,59.6438127 +100.45,50.42593887,-2.58195985,48.7948,5.057858016,8.627900609,1.85125,9.340953967,3.330131947,59.63628764 +100.46,50.42593932,-2.581958636,48.7766,5.061334191,8.627012241,1.7984375,9.422965427,3.352940824,59.62876253 +100.47,50.42593978,-2.581957422,48.7588,5.061334171,8.626790069,1.745,9.504053164,3.37282584,59.62123747 +100.48,50.42594023,-2.581956208,48.7417,5.061334155,8.626789962,1.6915625,9.584200334,3.389769749,59.61371236 +100.49,50.42594069,-2.581954994,48.725,5.061334153,8.626567792,1.6384375,9.663390149,3.403757711,59.6061873 +100.5,50.42594114,-2.58195378,48.7089,5.06133415,8.625679427,1.584375,9.74160605,3.414777523,59.59866219 +100.51,50.4259416,-2.581952566,48.6933,5.061334129,8.624346933,1.528125,9.818831765,3.422819616,59.59113713 +100.52,50.42594205,-2.581951353,48.6783,5.061334109,8.623236503,1.47,9.895051137,3.427877,59.58361202 +100.53,50.42594251,-2.581950139,48.6639,5.061334104,8.62234814,1.411875,9.970248181,3.429945148,59.57608697 +100.54,50.42594296,-2.581948926,48.6501,5.061334096,8.621903909,1.355,10.04440731,3.4290224,59.56856185 +100.55,50.42594342,-2.581947713,48.6368,5.061334075,8.622125873,1.298125,10.11751294,3.425109442,59.5610368 +100.56,50.42594387,-2.581946499,48.6241,5.061334063,8.621903708,1.2396875,10.18954984,3.418209769,59.55351168 +100.57,50.42594433,-2.581945286,48.612,5.064810249,8.620793284,1.1796875,10.26050304,3.408329341,59.54598663 +100.58,50.42594478,-2.581944073,48.6005,5.07523881,8.619904925,1.1184375,10.3303576,3.395476809,59.53846151 +100.59,50.42594524,-2.58194286,48.5896,5.082191187,8.619460696,1.056875,10.39909895,3.379663403,59.53093646 +100.6,50.4259457,-2.581941647,48.5794,5.075238808,8.618572338,0.9965625,10.46671279,3.360902817,59.52341135 +100.61,50.42594615,-2.581940434,48.5697,5.064810224,8.617239851,0.9365625,10.533185,3.339211495,59.51588629 +100.62,50.42594661,-2.581939222,48.5606,5.064810208,8.616351496,0.8746875,10.59850167,3.314608343,59.50836118 +100.63,50.42594706,-2.581938009,48.5522,5.075238778,8.616129337,0.811875,10.66264917,3.287114849,59.50083612 +100.64,50.42594752,-2.581936797,48.5444,5.082191162,8.615907178,0.75,10.72561408,3.256754904,59.49331107 +100.65,50.42594798,-2.581935584,48.5372,5.078714967,8.615018825,0.688125,10.78738323,3.223554979,59.48578595 +100.66,50.42594843,-2.581934372,48.5306,5.078714962,8.613686343,0.625,10.84794384,3.187544123,59.4782609 +100.67,50.42594889,-2.58193316,48.5247,5.082191149,8.612797992,0.5615625,10.90728313,3.148753677,59.47073578 +100.68,50.42594935,-2.581931948,48.5194,5.078714954,8.612575837,0.4984375,10.96538878,3.107217446,59.46321073 +100.69,50.4259498,-2.581930736,48.5147,5.078714949,8.612575747,0.4346875,11.0222486,3.062971639,59.45568561 +100.7,50.42595026,-2.581929524,48.5107,5.082191131,8.612353593,0.37,11.07785083,3.016054933,59.44816056 +100.71,50.42595072,-2.581928312,48.5073,5.078714933,8.611465245,0.3053125,11.13218367,2.966508178,59.44063545 +100.72,50.42595117,-2.5819271,48.5046,5.082191124,8.610132767,0.2415625,11.18523595,2.914374577,59.43311039 +100.73,50.42595163,-2.581925889,48.5025,5.096095888,8.609244421,0.1784375,11.23699656,2.859699621,59.42558528 +100.74,50.42595209,-2.581924677,48.501,5.096095887,8.609022271,0.1146875,11.2874546,2.802530923,59.41806022 +100.75,50.42595255,-2.581923466,48.5002,5.082191131,8.608800122,0.05,11.33659954,2.742918389,59.41053511 +100.76,50.425953,-2.581922254,48.5,5.082191133,8.607911778,-0.015,11.38442124,2.680913985,59.40301005 +100.77,50.42595346,-2.581921043,48.5005,5.09957208,8.606579305,-0.08,11.4309096,2.616571799,59.39548494 +100.78,50.42595392,-2.581919832,48.5016,5.110000653,8.605690963,-0.145,11.47605495,2.549947922,59.38795988 +100.79,50.42595438,-2.581918621,48.5034,5.099572085,8.605468816,-0.2096875,11.51984789,2.481100454,59.38043477 +100.8,50.42595484,-2.58191741,48.5058,5.082191126,8.605246672,-0.2734375,11.5622792,2.410089383,59.37290971 +100.81,50.42595529,-2.581916199,48.5089,5.082191131,8.604358333,-0.336875,11.6033401,2.336976702,59.3653846 +100.82,50.42595575,-2.581914988,48.5125,5.099572102,8.603247929,-0.4015625,11.64302196,2.261826183,59.35785955 +100.83,50.42595621,-2.581913778,48.5169,5.113476869,8.603025786,-0.4665625,11.68131651,2.184703314,59.35033443 +100.84,50.42595667,-2.581912567,48.5219,5.113476865,8.603247775,-0.5296875,11.71821573,2.105675302,59.34280938 +100.85,50.42595713,-2.581911356,48.5275,5.099572107,8.602803569,-0.591875,11.75371196,2.024811133,59.33528426 +100.86,50.42595759,-2.581910146,48.5337,5.082191162,8.601915234,-0.655,11.78779773,1.942181337,59.32775921 +100.87,50.42595804,-2.581908935,48.5406,5.082191168,8.600804835,-0.718125,11.82046601,1.857857878,59.32023409 +100.88,50.4259585,-2.581907725,48.5481,5.099572124,8.599472371,-0.78,11.85170991,1.77191438,59.31270904 +100.89,50.42595896,-2.581906515,48.5562,5.113476892,8.598361974,-0.841875,11.88152291,1.684425673,59.30518393 +100.9,50.42595942,-2.581905305,48.5649,5.116953093,8.597473641,-0.9046875,11.90989876,1.595468188,59.29765887 +100.91,50.42595988,-2.581904095,48.5743,5.116953101,8.597029439,-0.9665625,11.93683162,1.505119448,59.29013376 +100.92,50.42596034,-2.581902886,48.5843,5.116953105,8.597251435,-1.0265625,11.96231575,1.413458175,59.2826087 +100.93,50.4259608,-2.581901675,48.5948,5.116953109,8.597029301,-1.086875,11.98634594,1.320564356,59.27508359 +100.94,50.42596126,-2.581900466,48.606,5.116953117,8.595918908,-1.1484375,12.0089171,1.226519006,59.26755853 +100.95,50.42596172,-2.581899256,48.6178,5.116953135,8.59503058,-1.209375,12.03002458,1.131404059,59.26003342 +100.96,50.42596218,-2.581898047,48.6302,5.116953159,8.594586383,-1.268125,12.04966385,1.035302536,59.25250836 +100.97,50.42596264,-2.581896837,48.6432,5.116953167,8.593698056,-1.325,12.06783097,0.93829826,59.24498325 +100.98,50.4259631,-2.581895628,48.6567,5.113476978,8.5923656,-1.381875,12.08452203,0.840475743,59.23745819 +100.99,50.42596356,-2.581894419,48.6708,5.103048416,8.591477275,-1.44,12.09973355,0.741920299,59.22993314 +101,50.42596402,-2.58189321,48.6855,5.099572237,8.591255148,-1.498125,12.11346242,0.642717928,59.22240803 +101.01,50.42596447,-2.581892001,48.7008,5.116953204,8.591255085,-1.5546875,12.12570572,0.542955032,59.21488297 +101.02,50.42596494,-2.581890792,48.7166,5.134334179,8.591032958,-1.61,12.13646089,0.442718759,59.20735786 +101.03,50.4259654,-2.581889583,48.733,5.130858008,8.589922571,-1.665,12.14572573,0.342096369,59.1998328 +101.04,50.42596586,-2.581888374,48.7499,5.120429447,8.587923925,-1.7196875,12.15349824,0.241175698,59.19230769 +101.05,50.42596632,-2.581887166,48.7674,5.116953264,8.586591475,-1.773125,12.15977689,0.140044693,59.18478263 +101.06,50.42596678,-2.581885958,48.7854,5.116953272,8.586813481,-1.8246875,12.16456028,0.038791535,59.17725752 +101.07,50.42596724,-2.581884749,48.8039,5.116953283,8.587479617,-1.8753125,12.16784746,-0.062495372,59.16973246 +101.08,50.4259677,-2.581883541,48.8229,5.116953296,8.587479559,-1.9265625,12.16963766,-0.163727847,59.16220735 +101.09,50.42596816,-2.581882332,48.8424,5.116953321,8.586591241,-1.978125,12.16993067,-0.264817483,59.15468229 +101.1,50.42596862,-2.581881124,48.8625,5.116953351,8.585258795,-2.0278125,12.16872626,-0.365676275,59.14715718 +101.11,50.42596908,-2.581879916,48.883,5.120429557,8.584370479,-2.075,12.16602476,-0.466216159,59.13963213 +101.12,50.42596954,-2.581878708,48.904,5.134334332,8.583926294,-2.1215625,12.16182676,-0.566349472,59.13210701 +101.13,50.42597,-2.5818775,48.9254,5.151715307,8.583037979,-2.1684375,12.15613311,-0.665988952,59.12458196 +101.14,50.42597047,-2.581876292,48.9474,5.151715325,8.581705534,-2.2146875,12.14894495,-0.765047626,59.11705684 +101.15,50.42597093,-2.581875085,48.9697,5.134334384,8.58081722,-2.2596875,12.14026389,-0.863439204,59.10953179 +101.16,50.42597139,-2.581873877,48.9926,5.120429641,8.580595102,-2.3034375,12.1300916,-0.961077859,59.10200667 +101.17,50.42597185,-2.58187267,49.0158,5.120429664,8.580372985,-2.34625,12.11843031,-1.057878448,59.09448162 +101.18,50.42597231,-2.581871462,49.0395,5.134334443,8.579484673,-2.3884375,12.10528247,-1.153756518,59.08695651 +101.19,50.42597277,-2.581870255,49.0636,5.151715412,8.578152231,-2.4296875,12.09065073,-1.248628531,59.07943145 +101.2,50.42597324,-2.581869048,49.0881,5.151715437,8.577263921,-2.4696875,12.07453824,-1.342411695,59.07190634 +101.21,50.4259737,-2.581867841,49.113,5.134334506,8.577041806,-2.508125,12.05694827,-1.43502425,59.06438128 +101.22,50.42597416,-2.581866634,49.1383,5.123905945,8.577041756,-2.545,12.03788459,-1.526385464,59.05685617 +101.23,50.42597462,-2.581865427,49.1639,5.134334535,8.576819642,-2.58125,12.0173511,-1.61641564,59.04933111 +101.24,50.42597508,-2.58186422,49.1899,5.151715516,8.575931332,-2.6165625,11.99535215,-1.705036283,59.041806 +101.25,50.42597555,-2.581863013,49.2163,5.151715542,8.574820959,-2.65,11.97189234,-1.7921701,59.03428094 +101.26,50.42597601,-2.581861807,49.2429,5.137810802,8.574598846,-2.683125,11.94697652,-1.877741117,59.02675583 +101.27,50.42597647,-2.5818606,49.2699,5.137810824,8.5745988,-2.7165625,11.92060987,-1.961674679,59.01923077 +101.28,50.42597693,-2.581859393,49.2973,5.151715611,8.573266362,-2.7478125,11.89279798,-2.043897675,59.01170566 +101.29,50.4259774,-2.581858187,49.3249,5.15519183,8.571267729,-2.7765625,11.86354659,-2.124338371,59.00418061 +101.3,50.42597786,-2.581856981,49.3528,5.151715666,8.570157358,-2.805,11.83286189,-2.20292658,58.99665549 +101.31,50.42597832,-2.581855775,49.381,5.155191874,8.569935247,-2.8328125,11.80075019,-2.279593833,58.98913044 +101.32,50.42597879,-2.581854569,49.4095,5.155191889,8.569713136,-2.858125,11.76721823,-2.354273267,58.98160532 +101.33,50.42597925,-2.581853363,49.4382,5.151715725,8.569046896,-2.8815625,11.73227308,-2.426899678,58.97408027 +101.34,50.42597971,-2.581852157,49.4671,5.155191947,8.568602721,-2.905,11.69592195,-2.497409813,58.96655521 +101.35,50.42598018,-2.581850952,49.4963,5.155191965,8.568824742,-2.928125,11.65817245,-2.565742192,58.9590301 +101.36,50.42598064,-2.581849745,49.5257,5.15171579,8.568602633,-2.9496875,11.61903244,-2.631837228,58.95150504 +101.37,50.4259811,-2.58184854,49.5553,5.158668201,8.567270199,-2.97,11.57851017,-2.695637224,58.94397993 +101.38,50.42598157,-2.581847334,49.5851,5.169096805,8.565493634,-2.989375,11.53661407,-2.757086604,58.93645487 +101.39,50.42598203,-2.581846129,49.6151,5.169096837,8.563939135,-3.0065625,11.49335289,-2.816131738,58.92892976 +101.4,50.4259825,-2.581844924,49.6453,5.15866829,8.563050831,-3.02125,11.44873563,-2.872721175,58.9214047 +101.41,50.42598296,-2.581843719,49.6755,5.151715925,8.562828723,-3.035,11.4027717,-2.926805584,58.91387959 +101.42,50.42598342,-2.581842514,49.706,5.15866832,8.56282868,-3.0484375,11.35547054,-2.978337751,58.90635454 +101.43,50.42598389,-2.581841309,49.7365,5.169096913,8.562828637,-3.0609375,11.30684218,-3.027272759,58.89882942 +101.44,50.42598435,-2.581840104,49.7672,5.172573132,8.56260653,-3.071875,11.2568967,-3.073567921,58.89130437 +101.45,50.42598482,-2.581838899,49.798,5.172573173,8.561718227,-3.08125,11.20564454,-3.1171829,58.88377925 +101.46,50.42598528,-2.581837694,49.8288,5.172573214,8.560607859,-3.0896875,11.1530964,-3.158079654,58.8762542 +101.47,50.42598575,-2.58183649,49.8598,5.172573235,8.560385751,-3.0965625,11.09926329,-3.196222543,58.86872909 +101.48,50.42598621,-2.581835285,49.8908,5.172573245,8.560385709,-3.10125,11.04415644,-3.231578221,58.86120403 +101.49,50.42598668,-2.58183408,49.9218,5.172573268,8.559053277,-3.105,10.98778731,-3.264115979,58.85367892 +101.5,50.42598714,-2.581832876,49.9529,5.172573303,8.557054649,-3.108125,10.93016769,-3.293807339,58.84615386 +101.51,50.42598761,-2.581831672,49.984,5.172573331,8.555944282,-3.109375,10.87130968,-3.320626463,58.83862875 +101.52,50.42598807,-2.581830468,50.0151,5.172573352,8.555722174,-3.1084375,10.81122549,-3.344549971,58.83110369 +101.53,50.42598854,-2.581829264,50.0462,5.172573373,8.555722132,-3.1065625,10.74992772,-3.365556953,58.82357858 +101.54,50.425989,-2.58182806,50.0772,5.172573397,8.55572209,-3.1046875,10.68742914,-3.383629131,58.81605352 +101.55,50.42598947,-2.581826856,50.1083,5.176049621,8.555499983,-3.1015625,10.62374281,-3.39875069,58.80852841 +101.56,50.42598993,-2.581825652,50.1393,5.18647823,8.554611681,-3.09625,10.55888204,-3.410908568,58.80100335 +101.57,50.4259904,-2.581824448,50.1702,5.193430633,8.553279248,-3.0896875,10.4928604,-3.420091993,58.79347824 +101.58,50.42599087,-2.581823245,50.2011,5.18647827,8.552168879,-3.0815625,10.42569159,-3.426293115,58.78595318 +101.59,50.42599133,-2.581822041,50.2319,5.176049725,8.551058511,-3.07125,10.35738975,-3.429506434,58.77842807 +101.6,50.4259918,-2.581820838,50.2625,5.176049751,8.549948143,-3.06,10.28796903,-3.4297292,58.77090302 +101.61,50.42599226,-2.581819635,50.2931,5.186478346,8.549948101,-3.0484375,10.21744406,-3.426961127,58.7633779 +101.62,50.42599273,-2.581818432,50.3235,5.19343076,8.550614252,-3.03625,10.14582944,-3.421204734,58.75585285 +101.63,50.4259932,-2.581817228,50.3538,5.1899546,8.549725948,-3.023125,10.07314017,-3.412465008,58.74832773 +101.64,50.42599366,-2.581816025,50.384,5.189954618,8.547505254,-3.0078125,9.99939145,-3.400749568,58.74080268 +101.65,50.42599413,-2.581814823,50.414,5.193430829,8.546394885,-2.9896875,9.924598685,-3.386068613,58.73327757 +101.66,50.4259946,-2.58181362,50.4438,5.189954661,8.546394841,-2.97,9.848777462,-3.36843492,58.72575251 +101.67,50.42599506,-2.581812417,50.4734,5.189954683,8.546172732,-2.9496875,9.771943649,-3.347863959,58.7182274 +101.68,50.42599553,-2.581811215,50.5028,5.1934309,8.546172687,-2.9284375,9.694113292,-3.324373607,58.71070234 +101.69,50.425996,-2.581810012,50.532,5.189954734,8.546172642,-2.90625,9.615302603,-3.297984316,58.70317728 +101.7,50.42599646,-2.581808809,50.5609,5.19343095,8.544840207,-2.883125,9.535528085,-3.268719122,58.69565217 +101.71,50.42599693,-2.581807607,50.5897,5.207335751,8.542841576,-2.8584375,9.454806353,-3.236603577,58.68812712 +101.72,50.4259974,-2.581806405,50.6181,5.207335781,8.541731205,-2.8328125,9.37315431,-3.201665699,58.680602 +101.73,50.42599787,-2.581805203,50.6463,5.193431028,8.541509093,-2.8065625,9.290588971,-3.163935913,58.67307695 +101.74,50.42599833,-2.581804001,50.6743,5.193431044,8.541509046,-2.7778125,9.207127642,-3.123447105,58.66555183 +101.75,50.4259988,-2.581802799,50.7019,5.207335837,8.541508999,-2.7465625,9.122787681,-3.080234571,58.65802678 +101.76,50.42599927,-2.581801597,50.7292,5.207335858,8.541286886,-2.7153125,9.03758668,-3.034336068,58.65050166 +101.77,50.42599974,-2.581800395,50.7562,5.19343111,8.540398579,-2.6846875,8.951542571,-2.985791589,58.64297661 +101.78,50.4260002,-2.581799193,50.7829,5.193431135,8.539066141,-2.653125,8.864673174,-2.934643417,58.6354515 +101.79,50.42600067,-2.581797992,50.8093,5.210812119,8.537955767,-2.619375,8.776996708,-2.880936244,58.62792644 +101.8,50.42600114,-2.58179679,50.8353,5.221240725,8.536845392,-2.583125,8.688531452,-2.824716823,58.62040133 +101.81,50.42600161,-2.581795589,50.861,5.210812175,8.535512951,-2.5453125,8.599295911,-2.766034199,58.61287627 +101.82,50.42600208,-2.581794388,50.8862,5.193431227,8.534624641,-2.508125,8.509308707,-2.704939538,58.60535116 +101.83,50.42600254,-2.581793187,50.9111,5.193431241,8.534402525,-2.4715625,8.418588632,-2.641486181,58.5978261 +101.84,50.42600301,-2.581791986,50.9357,5.210812225,8.534402474,-2.4325,8.327154595,-2.575729362,58.59030099 +101.85,50.42600348,-2.581790785,50.9598,5.224717013,8.534402421,-2.39,8.235025731,-2.507726491,58.58277593 +101.86,50.42600395,-2.581789584,50.9835,5.228193226,8.534180304,-2.346875,8.142221294,-2.437536812,58.57525082 +101.87,50.42600442,-2.581788383,51.0067,5.228193247,8.533291991,-2.3046875,8.048760647,-2.365221631,58.56772576 +101.88,50.42600489,-2.581787182,51.0296,5.228193264,8.531959547,-2.2615625,7.954663273,-2.290843917,58.56020065 +101.89,50.42600536,-2.581785982,51.052,5.22471709,8.530849167,-2.21625,7.85994888,-2.214468528,58.5526756 +101.9,50.42600583,-2.581784781,51.0739,5.210812342,8.529960852,-2.17,7.764637237,-2.1361621,58.54515048 +101.91,50.4260063,-2.581783581,51.0954,5.193431401,8.529516667,-2.1234375,7.668748223,-2.055992871,58.53762543 +101.92,50.42600676,-2.581782381,51.1164,5.193431423,8.529738676,-2.07625,7.572301836,-1.974030858,58.53010031 +101.93,50.42600723,-2.58178118,51.1369,5.210812402,8.529516554,-2.0284375,7.475318302,-1.890347392,58.52257526 +101.94,50.4260077,-2.58177998,51.157,5.224717181,8.528184107,-1.9796875,7.377817845,-1.805015585,58.51505015 +101.95,50.42600817,-2.58177878,51.1765,5.228193388,8.526407529,-1.9296875,7.279820748,-1.718109747,58.50752509 +101.96,50.42600864,-2.58177758,51.1956,5.228193406,8.52507508,-1.8784375,7.18134758,-1.629705683,58.49999998 +101.97,50.42600911,-2.581776381,51.2141,5.22819342,8.52507502,-1.82625,7.082418854,-1.539880453,58.49247492 +101.98,50.42600958,-2.581775181,51.2321,5.228193435,8.525963219,-1.7734375,6.983055252,-1.448712498,58.48494981 +101.99,50.42601005,-2.581773981,51.2496,5.228193452,8.525741093,-1.7196875,6.883277517,-1.356281227,58.47742475 +102,50.42601052,-2.581772781,51.2665,5.228193464,8.523742447,-1.665,6.783106504,-1.2626672,58.46989964 +102.01,50.42601099,-2.581771582,51.2829,5.228193478,8.521743799,-1.61,6.682563067,-1.167952177,58.46237458 +102.02,50.42601146,-2.581770383,51.2987,5.228193493,8.521521671,-1.555,6.581668294,-1.072218665,58.45484953 +102.03,50.42601193,-2.581769184,51.314,5.228193504,8.522409867,-1.4996875,6.480443153,-0.975550142,58.44732441 +102.04,50.4260124,-2.581767984,51.3287,5.231669709,8.522409802,-1.443125,6.378908901,-0.878030949,58.43979936 +102.05,50.42601287,-2.581766785,51.3429,5.245574495,8.521077347,-1.385,6.277086623,-0.779746056,58.43227424 +102.06,50.42601334,-2.581765586,51.3564,5.262955469,8.51930076,-1.3265625,6.17499769,-0.680781233,58.42474919 +102.07,50.42601382,-2.581764387,51.3694,5.26295548,8.517968303,-1.2684375,6.07266336,-0.581222769,58.41722408 +102.08,50.42601429,-2.581763189,51.3818,5.245574528,8.517746169,-1.2096875,5.970105003,-0.481157523,58.40969902 +102.09,50.42601476,-2.58176199,51.3936,5.231669763,8.517968165,-1.15,5.867344049,-0.380672643,58.40217391 +102.1,50.42601523,-2.581760791,51.4048,5.228193573,8.517523967,-1.09,5.764401982,-0.279855792,58.39464885 +102.11,50.4260157,-2.581759593,51.4154,5.228193582,8.516635637,-1.03,5.66130029,-0.178794918,58.38712374 +102.12,50.42601617,-2.581758394,51.4254,5.23166979,8.515525241,-0.9696875,5.558060457,-0.077578142,58.37959868 +102.13,50.42601664,-2.581757196,51.4348,5.245574574,8.514192779,-0.908125,5.454704085,0.023706243,58.37207357 +102.14,50.42601711,-2.581755998,51.4436,5.262955544,8.513304446,-0.845,5.351252773,0.124970002,58.36454851 +102.15,50.42601759,-2.5817548,51.4517,5.262955551,8.513082307,-0.781875,5.247728123,0.226124784,58.3570234 +102.16,50.42601806,-2.581753602,51.4592,5.245574596,8.513082233,-0.72,5.144151678,0.327082411,58.34949834 +102.17,50.42601853,-2.581752404,51.4661,5.23166983,8.512860092,-0.658125,5.040545152,0.427754763,58.34197323 +102.18,50.426019,-2.581751206,51.4724,5.231669842,8.511971756,-0.5946875,4.936930204,0.528054119,58.33444818 +102.19,50.42601947,-2.581750008,51.478,5.245574623,8.510639289,-0.53,4.833328377,0.627893046,58.32692306 +102.2,50.42601994,-2.581748811,51.483,5.262955579,8.509528887,-0.4653125,4.729761385,0.727184397,58.31939801 +102.21,50.42602042,-2.581747613,51.4873,5.262955575,8.508418484,-0.4015625,4.62625083,0.825841656,58.31187289 +102.22,50.42602089,-2.581746416,51.491,5.249050817,8.507086014,-0.3384375,4.522818311,0.923778707,58.30434784 +102.23,50.42602136,-2.581745219,51.4941,5.249050827,8.506419738,-0.275,4.41948543,1.020910294,58.29682272 +102.24,50.42602183,-2.581744022,51.4965,5.262955592,8.507085852,-0.2115625,4.316273844,1.117151562,58.28929767 +102.25,50.42602231,-2.581742825,51.4983,5.262955588,8.507974029,-0.148125,4.213204982,1.212418687,58.28177256 +102.26,50.42602278,-2.581741627,51.4995,5.249050824,8.507085687,-0.083125,4.110300444,1.30662859,58.2742475 +102.27,50.42602325,-2.58174043,51.5,5.249050833,8.504864954,-0.016875,4.007581717,1.399699052,58.26672239 +102.28,50.42602372,-2.581739234,51.4998,5.262955599,8.503754544,0.048125,3.905070285,1.491549,58.25919733 +102.29,50.4260242,-2.581738037,51.499,5.266431776,8.503754458,0.1115625,3.802787464,1.582098276,58.25167222 +102.3,50.42602467,-2.58173684,51.4976,5.262955578,8.503310241,0.1753125,3.700754681,1.671267926,58.24414716 +102.31,50.42602514,-2.581735644,51.4955,5.266431776,8.502421894,0.24,3.598993194,1.758980202,58.23662205 +102.32,50.42602562,-2.581734447,51.4928,5.266431783,8.501533546,0.3046875,3.497524374,1.845158669,58.22909699 +102.33,50.42602609,-2.581733251,51.4894,5.262955592,8.500867263,0.3684375,3.396369249,1.929728099,58.22157188 +102.34,50.42602656,-2.581732055,51.4854,5.26643178,8.500200978,0.4315625,3.295549074,2.012614752,58.21404682 +102.35,50.42602704,-2.581730858,51.4808,5.266431777,8.498868497,0.4953125,3.195084821,2.093746378,58.20652171 +102.36,50.42602751,-2.581729663,51.4755,5.262955582,8.49775808,0.5596875,3.094997459,2.173052274,58.19899666 +102.37,50.42602798,-2.581728467,51.4696,5.269907962,8.497757988,0.623125,2.995308017,2.250463169,58.1914716 +102.38,50.42602846,-2.581727271,51.463,5.280336535,8.49753583,0.6853125,2.896037177,2.325911684,58.18394649 +102.39,50.42602893,-2.581726075,51.4559,5.283812725,8.496425411,0.748125,2.797205739,2.399331928,58.17642143 +102.4,50.42602941,-2.58172488,51.4481,5.283812717,8.495537056,0.811875,2.698834329,2.47065996,58.16889632 +102.41,50.42602988,-2.581723684,51.4396,5.280336517,8.495314894,0.874375,2.600943458,2.539833498,58.16137126 +102.42,50.42603036,-2.581722489,51.4306,5.269907934,8.495092732,0.935,2.503553639,2.606792326,58.15384615 +102.43,50.42603083,-2.581721293,51.4209,5.262955536,8.49442644,0.9953125,2.406685154,2.671477943,58.14632109 +102.44,50.4260313,-2.581720098,51.4107,5.269907907,8.493760147,1.05625,2.310358229,2.733833971,58.13879598 +102.45,50.42603178,-2.581718903,51.3998,5.280336477,8.493093854,1.116875,2.214593032,2.793806094,58.13127092 +102.46,50.42603225,-2.581717707,51.3883,5.283812668,8.491761364,1.1765625,2.119409559,2.851341943,58.12374581 +102.47,50.42603273,-2.581716513,51.3763,5.283812663,8.490650939,1.2365625,2.024827577,2.906391441,58.11622076 +102.48,50.4260332,-2.581715318,51.3636,5.283812648,8.490650837,1.2965625,1.930866967,2.958906461,58.10869564 +102.49,50.42603368,-2.581714123,51.3503,5.283812631,8.49042867,1.3546875,1.837547326,3.00884128,58.10117059 +102.5,50.42603415,-2.581712928,51.3365,5.283812618,8.489318242,1.4115625,1.744888133,3.056152353,58.09364547 +102.51,50.42603463,-2.581711734,51.3221,5.283812608,8.488429878,1.4684375,1.652908697,3.100798427,58.08612042 +102.52,50.4260351,-2.581710539,51.3071,5.283812603,8.488207709,1.5246875,1.56162827,3.142740542,58.0785953 +102.53,50.42603558,-2.581709345,51.2916,5.287288788,8.487985538,1.58,1.471065873,3.1819422,58.07107025 +102.54,50.42603605,-2.58170815,51.2755,5.297717349,8.487097172,1.635,1.381240472,3.218369081,58.06354514 +102.55,50.42603653,-2.581706956,51.2589,5.304669715,8.485764676,1.69,1.292170802,3.251989556,58.05602008 +102.56,50.42603701,-2.581705762,51.2417,5.297717315,8.484654243,1.7446875,1.203875485,3.282774178,58.04849497 +102.57,50.42603748,-2.581704568,51.224,5.287288729,8.48354381,1.798125,1.116372912,3.310696245,58.04096991 +102.58,50.42603796,-2.581703374,51.2057,5.287288719,8.482433377,1.85,1.029681361,3.335731292,58.0334448 +102.59,50.42603843,-2.581702181,51.187,5.29771728,8.482211203,1.90125,0.943818995,3.357857547,58.02591974 +102.6,50.42603891,-2.581700987,51.1677,5.30466965,8.482433157,1.951875,0.858803689,3.377055643,58.01839463 +102.61,50.42603939,-2.581699793,51.1479,5.301193441,8.481988915,2.00125,0.774653263,3.393308966,58.01086957 +102.62,50.42603986,-2.5816986,51.1277,5.301193416,8.481100544,2.05,0.691385192,3.406603249,58.00334446 +102.63,50.42604034,-2.581697406,51.1069,5.304669587,8.480212172,2.0984375,0.609016951,3.416926917,57.9958194 +102.64,50.42604082,-2.581696213,51.0857,5.301193384,8.479545864,2.14625,0.527565729,3.424270975,57.98829429 +102.65,50.42604129,-2.58169502,51.064,5.301193369,8.478879556,2.193125,0.447048486,3.428629064,57.98076924 +102.66,50.42604177,-2.581693826,51.0418,5.304669539,8.477547053,2.238125,0.367482066,3.429997287,57.97324412 +102.67,50.42604225,-2.581692634,51.0192,5.301193328,8.476436613,2.28125,0.288883143,3.428374499,57.96571907 +102.68,50.42604272,-2.581691441,50.9962,5.301193316,8.476436498,2.3234375,0.211267988,3.423762132,57.95819395 +102.69,50.4260432,-2.581690248,50.9727,5.304669494,8.476214316,2.365,0.134652989,3.416164195,57.9506689 +102.7,50.42604368,-2.581689055,50.9489,5.301193275,8.475103876,2.4065625,0.059054015,3.405587337,57.94314378 +102.71,50.42604415,-2.581687863,50.9246,5.304669435,8.473993435,2.448125,-0.015513119,3.392040724,57.93561873 +102.72,50.42604463,-2.58168667,50.8999,5.318574181,8.473105057,2.488125,-0.089032829,3.375536217,57.92809367 +102.73,50.42604511,-2.581685478,50.8748,5.318574171,8.472660809,2.52625,-0.161489759,3.356088196,57.92056856 +102.74,50.42604559,-2.581684286,50.8494,5.304669391,8.472882754,2.563125,-0.232868784,3.333713563,57.9130435 +102.75,50.42604606,-2.581683093,50.8235,5.30466937,8.472660571,2.5984375,-0.303154949,3.308431973,57.90551839 +102.76,50.42604654,-2.581681901,50.7974,5.318574119,8.471550127,2.633125,-0.372333644,3.28026531,57.89799334 +102.77,50.42604702,-2.581680709,50.7709,5.3185741,8.470661747,2.668125,-0.440390373,3.249238213,57.89046822 +102.78,50.4260475,-2.581679517,50.744,5.304669303,8.470217497,2.70125,-0.507310984,3.215377782,57.88294317 +102.79,50.42604797,-2.581678325,50.7168,5.304669272,8.469329117,2.7315625,-0.573081439,3.178713411,57.87541805 +102.8,50.42604845,-2.581677133,50.6894,5.322050206,8.467996606,2.7615625,-0.637688046,3.139277242,57.867893 +102.81,50.42604893,-2.581675942,50.6616,5.335954955,8.467108225,2.7915625,-0.701117281,3.097103537,57.86036788 +102.82,50.42604941,-2.58167475,50.6335,5.335954941,8.466886038,2.819375,-0.76335591,3.052229082,57.85284283 +102.83,50.42604989,-2.581673559,50.6052,5.322050152,8.46666385,2.845,-0.824390984,3.004693065,57.84531772 +102.84,50.42605037,-2.581672367,50.5766,5.304669169,8.465775468,2.87,-0.884209669,2.954536913,57.83779266 +102.85,50.42605084,-2.581671176,50.5478,5.304669147,8.464442956,2.8946875,-0.942799474,2.901804398,57.83026755 +102.86,50.42605132,-2.581669985,50.5187,5.322050079,8.463554573,2.918125,-1.000148252,2.846541416,57.82274249 +102.87,50.4260518,-2.581668794,50.4894,5.335954812,8.463110319,2.939375,-1.056243971,2.788796208,57.81521738 +102.88,50.42605228,-2.581667603,50.4599,5.339430975,8.462221936,2.9584375,-1.111074886,2.728619139,57.80769232 +102.89,50.42605276,-2.581666412,50.4302,5.339430962,8.461111487,2.9765625,-1.164629595,2.66606269,57.80016721 +102.9,50.42605324,-2.581665222,50.4004,5.339430948,8.460889298,2.995,-1.216896925,2.60118135,57.79264215 +102.91,50.42605372,-2.581664031,50.3703,5.339430919,8.461111237,3.013125,-1.267865933,2.534031785,57.78511704 +102.92,50.4260542,-2.58166284,50.3401,5.339430881,8.460666981,3.029375,-1.317525961,2.464672494,57.77759198 +102.93,50.42605468,-2.58166165,50.3097,5.339430852,8.459778596,3.043125,-1.365866639,2.393163981,57.77006687 +102.94,50.42605516,-2.581660459,50.2792,5.339430838,8.458668147,3.0546875,-1.412877941,2.319568583,57.76254182 +102.95,50.42605564,-2.581659269,50.2486,5.339430824,8.457335633,3.065,-1.458549954,2.243950473,57.7550167 +102.96,50.42605612,-2.581658079,50.2179,5.339430794,8.456447248,3.075,-1.502873167,2.166375654,57.74749165 +102.97,50.4260566,-2.581656889,50.1871,5.339430755,8.456225057,3.0846875,-1.545838355,2.086911679,57.73996653 +102.98,50.42605708,-2.581655699,50.1562,5.339430725,8.456224931,3.093125,-1.587436523,2.005627876,57.73244148 +102.99,50.42605756,-2.581654509,50.1252,5.339430711,8.45600274,3.0996875,-1.62765902,1.922595176,57.72491636 +103,50.42605804,-2.581653319,50.0942,5.339430696,8.454892289,3.1046875,-1.666497423,1.837885887,57.71739131 +103.01,50.42605852,-2.581652129,50.0631,5.339430671,8.45289358,3.108125,-1.703943595,1.751573978,57.7098662 +103.02,50.426059,-2.58165094,50.032,5.339430645,8.451561065,3.109375,-1.739989688,1.663734677,57.70234114 +103.03,50.42605948,-2.581649751,50.0009,5.33943062,8.451560939,3.1084375,-1.774628252,1.574444534,57.69481603 +103.04,50.42605996,-2.581648561,49.9698,5.339430583,8.451338748,3.1065625,-1.807852069,1.483781525,57.68729097 +103.05,50.42606044,-2.581647372,49.9388,5.339430546,8.450450362,3.105,-1.839654092,1.39182455,57.67976586 +103.06,50.42606092,-2.581646183,49.9077,5.339430525,8.450450236,3.103125,-1.87002773,1.298653934,57.6722408 +103.07,50.4260614,-2.581644994,49.8767,5.339430513,8.451116304,3.099375,-1.898966683,1.204350868,57.66471575 +103.08,50.42606188,-2.581643804,49.8457,5.339430492,8.450227919,3.093125,-1.926464875,1.10899757,57.65719063 +103.09,50.42606236,-2.581642615,49.8148,5.339430458,8.44778508,3.085,-1.952516579,1.012677234,57.64966558 +103.1,50.42606284,-2.581641427,49.784,5.34290662,8.446008437,3.0765625,-1.97711635,0.915473799,57.64214046 +103.11,50.42606332,-2.581640238,49.7533,5.356811369,8.445564181,3.0678125,-2.000258975,0.817472118,57.63461541 +103.12,50.4260638,-2.58163905,49.7226,5.374192306,8.445564055,3.0565625,-2.021939755,0.718757506,57.6270903 +103.13,50.42606429,-2.581637861,49.6921,5.374192275,8.445563928,3.0428125,-2.04215405,0.619416193,57.61956524 +103.14,50.42606477,-2.581636673,49.6618,5.356811283,8.445341738,3.0284375,-2.060897676,0.519534695,57.61204013 +103.15,50.42606525,-2.581635484,49.6315,5.342906492,8.444453354,3.013125,-2.078166739,0.419200216,57.60451507 +103.16,50.42606573,-2.581634296,49.6015,5.342906474,8.443120841,2.9965625,-2.093957628,0.318500134,57.59698996 +103.17,50.42606621,-2.581633108,49.5716,5.356811213,8.442010393,2.98,-2.108267019,0.217522338,57.5894649 +103.18,50.42606669,-2.58163192,49.5419,5.374192139,8.440899945,2.9625,-2.121091935,0.116354837,57.58193979 +103.19,50.42606718,-2.581630732,49.5123,5.374192119,8.439789496,2.9415625,-2.132429738,0.015085864,57.57441473 +103.2,50.42606766,-2.581629545,49.483,5.356811149,8.439567307,2.918125,-2.142277966,-0.086196229,57.56688962 +103.21,50.42606814,-2.581628357,49.454,5.346382553,8.439789248,2.895,-2.15063467,-0.18740315,57.55936456 +103.22,50.42606862,-2.581627169,49.4251,5.356811094,8.439344995,2.8715625,-2.157498017,-0.288446721,57.55183945 +103.23,50.4260691,-2.581625982,49.3965,5.374192019,8.438456612,2.84625,-2.162866631,-0.389238706,57.5443144 +103.24,50.42606959,-2.581624794,49.3682,5.377668187,8.437346166,2.82,-2.166739368,-0.489691271,57.53678928 +103.25,50.42607007,-2.581623607,49.3401,5.374191972,8.436013656,2.793125,-2.169115481,-0.589716811,57.52926423 +103.26,50.42607055,-2.58162242,49.3123,5.377668141,8.435125275,2.764375,-2.169994341,-0.68922812,57.52173911 +103.27,50.42607104,-2.581621233,49.2848,5.374191937,8.434903088,2.7334375,-2.169375833,-0.788138398,57.51421406 +103.28,50.42607152,-2.581620046,49.2576,5.360287159,8.434902966,2.7015625,-2.167260129,-0.886361469,57.50668894 +103.29,50.426072,-2.581618859,49.2308,5.360287132,8.43468078,2.6696875,-2.16364763,-0.983811563,57.49916389 +103.3,50.42607248,-2.581617672,49.2042,5.374191864,8.433570336,2.6365625,-2.158539139,-1.080403768,57.49163878 +103.31,50.42607297,-2.581616485,49.178,5.37766803,8.431571634,2.60125,-2.151935628,-1.176053858,57.48411372 +103.32,50.42607345,-2.581615299,49.1522,5.374191828,8.430461192,2.565,-2.143838531,-1.270678411,57.47658861 +103.33,50.42607393,-2.581614113,49.1267,5.37766801,8.431349331,2.528125,-2.13424951,-1.364194863,57.46906355 +103.34,50.42607442,-2.581612926,49.1016,5.377667984,8.43223747,2.4896875,-2.123170626,-1.456521798,57.46153844 +103.35,50.4260749,-2.581611739,49.0769,5.374191759,8.431127029,2.45,-2.110604172,-1.547578543,57.45401338 +103.36,50.42607538,-2.581610553,49.0526,5.381144118,8.429128329,2.41,-2.096552725,-1.637285857,57.44648827 +103.37,50.42607587,-2.581609367,49.0287,5.391572682,8.427795824,2.3696875,-2.081019267,-1.725565361,57.43896321 +103.38,50.42607635,-2.581608181,49.0052,5.391572667,8.426685384,2.328125,-2.064007004,-1.812340162,57.4314381 +103.39,50.42607684,-2.581606995,48.9821,5.381144067,8.425574944,2.2846875,-2.045519546,-1.897534632,57.42391304 +103.4,50.42607732,-2.58160581,48.9595,5.37419166,8.425352765,2.2396875,-2.025560734,-1.9810744,57.41638799 +103.41,50.4260778,-2.581604624,48.9373,5.381144025,8.425574715,2.1934375,-2.00413469,-2.062886585,57.40886288 +103.42,50.42607829,-2.581603438,48.9156,5.391572586,8.425130471,2.1465625,-1.981245943,-2.142899969,57.40133782 +103.43,50.42607877,-2.581602253,48.8944,5.395048767,8.424242099,2.1,-1.956899248,-2.221044651,57.39381271 +103.44,50.42607926,-2.581601067,48.8736,5.395048746,8.423131662,2.053125,-1.931099703,-2.297252622,57.38628765 +103.45,50.42607974,-2.581599882,48.8533,5.39504872,8.421799161,2.0046875,-1.903852638,-2.371457303,57.37876254 +103.46,50.42608023,-2.581598697,48.8335,5.395048708,8.420910791,1.955,-1.875163839,-2.443594064,57.37123748 +103.47,50.42608071,-2.581597512,48.8142,5.395048706,8.420688615,1.9046875,-1.845039265,-2.513599938,57.36371237 +103.48,50.4260812,-2.581596327,48.7954,5.395048695,8.420688505,1.853125,-1.813485161,-2.581413962,57.35618731 +103.49,50.42608168,-2.581595142,48.7771,5.395048668,8.42046633,1.8,-1.780508117,-2.64697695,57.3486622 +103.5,50.42608217,-2.581593957,48.7594,5.395048643,8.419577962,1.7465625,-1.746115122,-2.71023172,57.34113714 +103.51,50.42608265,-2.581592772,48.7422,5.395048629,8.418245466,1.6934375,-1.710313224,-2.771123096,57.33361203 +103.52,50.42608314,-2.581591588,48.7255,5.395048615,8.4173571,1.6396875,-1.673109986,-2.829598022,57.32608698 +103.53,50.42608362,-2.581590403,48.7094,5.395048602,8.417134928,1.585,-1.6345132,-2.885605564,57.31856186 +103.54,50.42608411,-2.581589219,48.6938,5.395048598,8.416912757,1.5296875,-1.59453083,-2.939096732,57.31103681 +103.55,50.42608459,-2.581588034,48.6788,5.39504859,8.416024393,1.473125,-1.553171298,-2.990025002,57.30351169 +103.56,50.42608508,-2.58158685,48.6643,5.398524763,8.414691901,1.415,-1.5104432,-3.038345913,57.29598664 +103.57,50.42608556,-2.581585666,48.6505,5.408953322,8.413581474,1.3565625,-1.466355473,-3.084017353,57.28846152 +103.58,50.42608605,-2.581584482,48.6372,5.415905694,8.412471048,1.2984375,-1.420917341,-3.126999501,57.28093647 +103.59,50.42608654,-2.581583298,48.6245,5.412429497,8.411360622,1.2396875,-1.374138316,-3.167254828,57.27341136 +103.6,50.42608702,-2.581582115,48.6124,5.412429493,8.411360519,1.18,-1.326028082,-3.204748269,57.2658863 +103.61,50.42608751,-2.581580931,48.6009,5.415905671,8.412248676,1.12,-1.276596778,-3.239447109,57.25836119 +103.62,50.426088,-2.581579747,48.59,5.408953271,8.412026511,1.06,-1.225854662,-3.271321152,57.25083613 +103.63,50.42608848,-2.581578563,48.5797,5.398524688,8.410249895,1,-1.17381239,-3.300342496,57.24331102 +103.64,50.42608897,-2.58157738,48.57,5.39852468,8.408695345,0.9396875,-1.120480733,-3.32648593,57.23578596 +103.65,50.42608945,-2.581576197,48.5609,5.412429439,8.407806989,0.878125,-1.065870923,-3.349728593,57.22826085 +103.66,50.42608994,-2.581575013,48.5524,5.429810398,8.40669657,0.815,-1.00999436,-3.37005026,57.22073579 +103.67,50.42609043,-2.581573831,48.5446,5.429810396,8.406252344,0.751875,-0.952862675,-3.387433227,57.21321068 +103.68,50.42609092,-2.581572648,48.5374,5.415905618,8.406696377,0.69,-0.894487787,-3.401862252,57.20568562 +103.69,50.4260914,-2.581571464,48.5308,5.412429417,8.406030088,0.628125,-0.834881956,-3.413324789,57.19816051 +103.7,50.42609189,-2.581570282,48.5248,5.415905602,8.404253478,0.5646875,-0.774057559,-3.421810924,57.19063546 +103.71,50.42609238,-2.581569099,48.5195,5.412429404,8.403143062,0.5,-0.712027314,-3.427313095,57.18311034 +103.72,50.42609286,-2.581567917,48.5148,5.415905596,8.402698841,0.4353125,-0.648804172,-3.429826661,57.17558529 +103.73,50.42609335,-2.581566734,48.5108,5.429810365,8.402032556,0.3715625,-0.584401367,-3.429349387,57.16806017 +103.74,50.42609384,-2.581565552,48.5074,5.429810365,8.401588336,0.3084375,-0.518832363,-3.425881617,57.16053512 +103.75,50.42609433,-2.58156437,48.5046,5.415905596,8.401810311,0.2446875,-0.452110797,-3.419426445,57.15301006 +103.76,50.42609481,-2.581563187,48.5025,5.415905588,8.401588158,0.18,-0.384250593,-3.409989487,57.14548495 +103.77,50.4260953,-2.581562005,48.501,5.433286539,8.400477747,0.115,-0.315266016,-3.397578992,57.13795989 +103.78,50.42609579,-2.581560823,48.5002,5.443715115,8.399589401,0.05,-0.245171333,-3.382205732,57.13043478 +103.79,50.42609628,-2.581559641,48.5,5.433286544,8.399145185,-0.0146875,-0.173981327,-3.363883114,57.12290972 +103.8,50.42609677,-2.581558459,48.5005,5.415905592,8.398034777,-0.0784375,-0.10171078,-3.342627182,57.11538461 +103.81,50.42609725,-2.581557277,48.5016,5.4159056,8.396036113,-0.141875,-0.028374818,-3.318456385,57.10785955 +103.82,50.42609774,-2.581556096,48.5033,5.433286552,8.394703642,-0.2065625,0.046011261,-3.291391864,57.10033444 +103.83,50.42609823,-2.581554915,48.5057,5.447191305,8.394925623,-0.2715625,0.121431873,-3.261457226,57.09280939 +103.84,50.42609872,-2.581553733,48.5088,5.447191306,8.395591733,-0.335,0.197871376,-3.228678539,57.08528427 +103.85,50.42609921,-2.581552552,48.5124,5.433286553,8.395369587,-0.3984375,0.275313726,-3.193084396,57.07775922 +103.86,50.4260997,-2.58155137,48.5167,5.415905604,8.39359299,-0.4634375,0.353742768,-3.154705792,57.0702341 +103.87,50.42610018,-2.581550189,48.5217,5.415905613,8.391150202,-0.528125,0.433142113,-3.113576303,57.06270905 +103.88,50.42610067,-2.581549009,48.5273,5.433286582,8.390261866,-0.59125,0.513495147,-3.069731682,57.05518394 +103.89,50.42610116,-2.581547828,48.5335,5.447191349,8.391150045,-0.6534375,0.594785195,-3.023210259,57.04765888 +103.9,50.42610165,-2.581546647,48.5404,5.450667538,8.391816161,-0.7153125,0.676995185,-2.974052486,57.04013377 +103.91,50.42610214,-2.581545466,48.5478,5.450667545,8.391149891,-0.778125,0.760107984,-2.922301333,57.03260871 +103.92,50.42610263,-2.581544285,48.5559,5.450667552,8.389817428,-0.841875,0.844106233,-2.868001894,57.0250836 +103.93,50.42610312,-2.581543105,48.5647,5.45066756,8.388707031,-0.904375,0.928972398,-2.811201494,57.01755854 +103.94,50.42610361,-2.581541924,48.574,5.450667578,8.387596635,-0.965,1.014688717,-2.751949693,57.01003343 +103.95,50.4261041,-2.581540744,48.584,5.450667589,8.386264174,-1.025,1.101237315,-2.690298174,57.00250837 +103.96,50.42610459,-2.581539564,48.5945,5.450667585,8.385375844,-1.085,1.188600144,-2.626300679,56.99498326 +103.97,50.42610508,-2.581538384,48.6057,5.450667588,8.385153707,-1.1453125,1.276758925,-2.560012957,56.9874582 +103.98,50.42610557,-2.581537204,48.6174,5.450667605,8.385153636,-1.20625,1.365695268,-2.491492935,56.97993309 +103.99,50.42610606,-2.581536024,48.6298,5.450667619,8.384931501,-1.2665625,1.455390607,-2.420800199,56.97240803 +104,50.42610655,-2.581534844,48.6428,5.450667628,8.384043174,-1.3246875,1.545826151,-2.347996572,56.96488292 +104.01,50.42610704,-2.581533664,48.6563,5.450667642,8.382710719,-1.3815625,1.636983049,-2.273145423,56.95735787 +104.02,50.42610753,-2.581532485,48.6704,5.450667653,8.381822393,-1.4384375,1.728842335,-2.196312069,56.94983275 +104.03,50.42610802,-2.581531305,48.6851,5.450667657,8.381600261,-1.495,1.821384702,-2.117563489,56.9423077 +104.04,50.42610851,-2.581530126,48.7003,5.450667672,8.38137813,-1.5515625,1.914590898,-2.036968381,56.93478258 +104.05,50.426109,-2.581528946,48.7161,5.450667702,8.380267742,-1.608125,2.008441442,-1.954596989,56.92725753 +104.06,50.42610949,-2.581527767,48.7325,5.450667723,8.378269098,-1.663125,2.10291674,-1.870521162,56.91973242 +104.07,50.42610998,-2.581526588,48.7494,5.450667731,8.376936646,-1.7165625,2.197997023,-1.784814239,56.91220736 +104.08,50.42611047,-2.58152541,48.7668,5.450667742,8.376936582,-1.77,2.293662526,-1.697550876,56.90468225 +104.09,50.42611096,-2.58152423,48.7848,5.450667758,8.376714455,-1.823125,2.389893194,-1.608807276,56.89715719 +104.1,50.42611145,-2.581523052,48.8033,5.45414397,8.375604071,-1.8746875,2.486668917,-1.518660732,56.88963213 +104.11,50.42611194,-2.581521873,48.8223,5.46804876,8.374715751,-1.925,2.583969526,-1.427189911,56.88210702 +104.12,50.42611243,-2.581520695,48.8418,5.485429728,8.374493626,-1.975,2.681774739,-1.334474568,56.87458197 +104.13,50.42611293,-2.581519516,48.8618,5.48542973,8.374493565,-2.025,2.780064045,-1.240595548,56.86705685 +104.14,50.42611342,-2.581518338,48.8823,5.468048788,8.374271441,-2.0746875,2.878816931,-1.145634669,56.8595318 +104.15,50.42611391,-2.581517159,48.9033,5.454144049,8.373383124,-2.123125,2.978012827,-1.049674838,56.85200668 +104.16,50.4261144,-2.581515981,48.9248,5.454144068,8.372050679,-2.1696875,3.077630994,-0.952799592,56.84448163 +104.17,50.42611489,-2.581514803,48.9467,5.468048845,8.371162364,-2.2146875,3.177650632,-0.855093558,56.83695652 +104.18,50.42611538,-2.581513625,48.9691,5.485429823,8.370940242,-2.2584375,3.278050828,-0.756641876,56.82943146 +104.19,50.42611588,-2.581512447,48.9919,5.485429852,8.37071812,-2.3015625,3.37881067,-0.657530376,56.82190635 +104.2,50.42611637,-2.581511269,49.0151,5.468048918,8.369607742,-2.345,3.479909016,-0.55784546,56.81438129 +104.21,50.42611686,-2.581510091,49.0388,5.457620368,8.367609107,-2.3878125,3.581324838,-0.45767416,56.80685618 +104.22,50.42611735,-2.581508914,49.0629,5.468048971,8.366276665,-2.428125,3.683036936,-0.357103738,56.79933112 +104.23,50.42611784,-2.581507737,49.0874,5.485429945,8.36627661,-2.4665625,3.785024053,-0.256221856,56.79180601 +104.24,50.42611834,-2.581506559,49.1122,5.485429951,8.366276556,-2.505,3.887264934,-0.155116635,56.78428095 +104.25,50.42611883,-2.581505382,49.1375,5.471525204,8.365832373,-2.543125,3.989738149,-0.053876081,56.77675584 +104.26,50.42611932,-2.581504205,49.1631,5.471525235,8.365166127,-2.5796875,4.092422385,0.047411398,56.76923078 +104.27,50.42611981,-2.581503027,49.1891,5.485430025,8.363833688,-2.615,4.195296155,0.148657567,56.76170567 +104.28,50.42612031,-2.581501851,49.2154,5.488906231,8.362501249,-2.6496875,4.298337973,0.249774075,56.75418061 +104.29,50.4261208,-2.581500674,49.2421,5.485430063,8.361835004,-2.6834375,4.401526297,0.350672802,56.7466555 +104.3,50.42612129,-2.581499497,49.2691,5.488906287,8.361168759,-2.71625,4.50483964,0.451265742,56.73913045 +104.31,50.42612179,-2.581498321,49.2964,5.488906313,8.360502514,-2.748125,4.608256345,0.551465174,56.73160533 +104.32,50.42612228,-2.581497144,49.3241,5.485430144,8.3602804,-2.7778125,4.711754868,0.651183723,56.72408028 +104.33,50.42612277,-2.581495968,49.352,5.488906364,8.360058286,-2.8046875,4.815313609,0.750334413,56.71655516 +104.34,50.42612327,-2.581494791,49.3802,5.488906394,8.359392042,-2.8303125,4.918910968,0.848830786,56.70903011 +104.35,50.42612376,-2.581493615,49.4086,5.48543022,8.358725799,-2.85625,5.022525171,0.946587011,56.701505 +104.36,50.42612425,-2.581492439,49.4373,5.488906426,8.358059556,-2.8815625,5.126134733,1.043517719,56.69397994 +104.37,50.42612475,-2.581491262,49.4663,5.488906451,8.35672712,-2.9046875,5.22971794,1.13953857,56.68645483 +104.38,50.42612524,-2.581490087,49.4954,5.485430294,8.355394686,-2.9265625,5.333253132,1.234565626,56.67892977 +104.39,50.42612573,-2.581488911,49.5248,5.492382704,8.354728445,-2.9484375,5.436718768,1.328516208,56.67140466 +104.4,50.42612623,-2.581487735,49.5544,5.502811297,8.354284268,-2.969375,5.540093188,1.42130827,56.6638796 +104.41,50.42612672,-2.58148656,49.5842,5.506287515,8.354284219,-2.988125,5.643354851,1.51286091,56.65635449 +104.42,50.42612722,-2.581485384,49.6142,5.506287552,8.354284171,-3.005,5.746482097,1.603094314,56.64882943 +104.43,50.42612771,-2.581484208,49.6443,5.506287585,8.352951738,-3.02125,5.849453499,1.691929816,56.64130432 +104.44,50.42612821,-2.581483033,49.6746,5.506287608,8.350953111,-3.0365625,5.952247456,1.779289894,56.63377926 +104.45,50.4261287,-2.581481858,49.7051,5.502811438,8.350064806,-3.049375,6.054842597,1.86509846,56.62625421 +104.46,50.4261292,-2.581480683,49.7356,5.492382891,8.350508887,-3.06,6.157217435,1.949280628,56.61872909 +104.47,50.42612969,-2.581479508,49.7663,5.485430531,8.350730905,-3.07,6.2593506,2.031762944,56.61120404 +104.48,50.42613018,-2.581478332,49.797,5.492382931,8.349620537,-3.0796875,6.361220777,2.112473561,56.60367893 +104.49,50.42613068,-2.581477158,49.8279,5.502811528,8.348288104,-3.0884375,6.462806652,2.191342061,56.59615387 +104.5,50.42613117,-2.581475983,49.8588,5.506287754,8.3473998,-3.0959375,6.564087027,2.268299689,56.58862876 +104.51,50.42613167,-2.581474808,49.8898,5.506287792,8.346067367,-3.1015625,6.665040815,2.343279353,56.5811037 +104.52,50.42613216,-2.581473634,49.9209,5.50628782,8.344956998,-3.1046875,6.765646818,2.41621562,56.57357859 +104.53,50.42613266,-2.58147246,49.9519,5.50976403,8.344956952,-3.1065625,6.865884123,2.487044891,56.56605353 +104.54,50.42613315,-2.581471285,49.983,5.520192634,8.344734842,-3.1084375,6.965731759,2.555705403,56.55852842 +104.55,50.42613365,-2.581470111,50.0141,5.527145055,8.343624473,-3.1096875,7.065168928,2.622137339,56.55100336 +104.56,50.42613415,-2.581468937,50.0452,5.520192698,8.342736168,-3.109375,7.164174717,2.686282714,56.54347825 +104.57,50.42613464,-2.581467763,50.0763,5.509764142,8.342514057,-3.1065625,7.262728614,2.748085666,56.53595319 +104.58,50.42613514,-2.581466589,50.1074,5.509764176,8.342291947,-3.10125,7.360809936,2.807492165,56.52842808 +104.59,50.42613563,-2.581465415,50.1383,5.520192793,8.341403643,-3.095,7.458398285,2.864450529,56.52090303 +104.6,50.42613613,-2.581464241,50.1693,5.527145201,8.34007121,-3.0884375,7.555473149,2.918911085,56.51337791 +104.61,50.42613663,-2.581463068,50.2001,5.520192825,8.339182905,-3.08125,7.652014418,2.970826275,56.50585286 +104.62,50.42613712,-2.581461894,50.2309,5.509764267,8.338960794,-3.073125,7.748001808,3.020150836,56.49832774 +104.63,50.42613762,-2.581460721,50.2616,5.5097643,8.338738682,-3.0628125,7.843415266,3.066841797,56.49080269 +104.64,50.42613811,-2.581459547,50.2922,5.520192916,8.337850378,-3.05,7.938234969,3.11085842,56.48327757 +104.65,50.42613861,-2.581458374,50.3226,5.527145327,8.336517945,-3.0365625,8.032441033,3.152162375,56.47575252 +104.66,50.42613911,-2.581457201,50.3529,5.52366915,8.335407575,-3.023125,8.126013865,3.190717564,56.46822741 +104.67,50.4261396,-2.581456028,50.3831,5.52366917,8.334297205,-3.0078125,8.218933811,3.226490356,56.46070235 +104.68,50.4261401,-2.581454855,50.4131,5.527145396,8.333186835,-2.9896875,8.311181563,3.259449639,56.45317724 +104.69,50.4261406,-2.581453683,50.4429,5.523669241,8.332964723,-2.97,8.402737812,3.28956665,56.44565218 +104.7,50.42614109,-2.58145251,50.4725,5.527145459,8.333186738,-2.95,8.493583422,3.31681509,56.43812707 +104.71,50.42614159,-2.581451337,50.5019,5.541050247,8.332742561,-2.9296875,8.583699427,3.341171239,56.43060201 +104.72,50.42614209,-2.581450165,50.5311,5.541050272,8.331854254,-2.908125,8.673067035,3.362613841,56.4230769 +104.73,50.42614259,-2.581448992,50.5601,5.527145537,8.330743883,-2.8846875,8.761667566,3.381124159,56.41555184 +104.74,50.42614308,-2.58144782,50.5888,5.527145562,8.329411447,-2.8596875,8.849482573,3.396686094,56.40802673 +104.75,50.42614358,-2.581446648,50.6173,5.541050346,8.32852314,-2.8334375,8.936493606,3.409286066,56.40050167 +104.76,50.42614408,-2.581445476,50.6455,5.541050367,8.328301025,-2.80625,9.022682558,3.418913132,56.39297656 +104.77,50.42614458,-2.581444304,50.6734,5.527145635,8.328300974,-2.778125,9.10803144,3.425558813,56.38545151 +104.78,50.42614507,-2.581443132,50.7011,5.527145675,8.328078859,-2.748125,9.192522432,3.429217377,56.37792645 +104.79,50.42614557,-2.58144196,50.7284,5.544526658,8.327190549,-2.7165625,9.27613783,3.429885561,56.37040134 +104.8,50.42614607,-2.581440788,50.7554,5.554955242,8.325858111,-2.685,9.358860216,3.427562904,56.36287628 +104.81,50.42614657,-2.581439617,50.7821,5.544526678,8.324747737,-2.653125,9.440672344,3.422251299,56.35535117 +104.82,50.42614707,-2.581438445,50.8085,5.527145745,8.323859427,-2.6196875,9.521557082,3.4139555,56.34782611 +104.83,50.42614756,-2.581437274,50.8345,5.527145779,8.323415244,-2.5846875,9.601497529,3.40268267,56.340301 +104.84,50.42614806,-2.581436103,50.8602,5.544526766,8.323637254,-2.548125,9.680477011,3.388442607,56.33277594 +104.85,50.42614856,-2.581434931,50.8855,5.558431548,8.323193072,-2.5096875,9.758479084,3.371247799,56.32525083 +104.86,50.42614906,-2.58143376,50.9104,5.558431563,8.321194438,-2.47,9.835487362,3.351113203,56.31772577 +104.87,50.42614956,-2.581432589,50.9349,5.544526821,8.319195803,-2.43,9.911485801,3.328056407,56.31020066 +104.88,50.42615006,-2.581431419,50.959,5.52714589,8.318973683,-2.39,9.986458589,3.302097466,56.30267561 +104.89,50.42615055,-2.581430248,50.9827,5.527145911,8.319861884,-2.3496875,10.06038997,3.273259068,56.29515049 +104.9,50.42615105,-2.581429077,51.006,5.544526884,8.319639763,-2.3078125,10.13326459,3.241566366,56.28762544 +104.91,50.42615155,-2.581427906,51.0289,5.558431669,8.317641127,-2.263125,10.2050672,3.207046919,56.28010032 +104.92,50.42615205,-2.581426736,51.0513,5.561907888,8.315642489,-2.216875,10.27578274,3.169730923,56.27257527 +104.93,50.42615255,-2.581425566,51.0732,5.561907919,8.315420366,-2.1715625,10.34539654,3.129650806,56.26505015 +104.94,50.42615305,-2.581424396,51.0947,5.561907938,8.316308563,-2.1265625,10.41389404,3.086841634,56.2575251 +104.95,50.42615355,-2.581423225,51.1158,5.561907946,8.316086439,-2.079375,10.48126087,3.041340706,56.24999999 +104.96,50.42615405,-2.581422055,51.1363,5.561907956,8.3140878,-2.03,10.54748305,2.993187672,56.24247493 +104.97,50.42615455,-2.581420885,51.1564,5.561907974,8.311867095,-1.98,10.6125467,2.942424528,56.23494982 +104.98,50.42615505,-2.581419716,51.1759,5.561908,8.310756711,-1.9296875,10.6764382,2.889095564,56.22742476 +104.99,50.42615555,-2.581418546,51.195,5.561908028,8.310756648,-1.8784375,10.73914431,2.833247248,56.21989965 +105,50.42615605,-2.581417377,51.2135,5.561908045,8.311422778,-1.8265625,10.80065184,2.77492828,56.21237459 +105.01,50.42615655,-2.581416207,51.2315,5.56190805,8.311644778,-1.775,10.86094797,2.71418954,56.20484948 +105.02,50.42615705,-2.581415037,51.249,5.561908057,8.310312328,-1.723125,10.92002015,2.651084026,56.19732442 +105.03,50.42615755,-2.581413868,51.266,5.561908074,8.308313684,-1.6696875,10.977856,2.585666684,56.18979931 +105.04,50.42615805,-2.581412699,51.2824,5.561908105,8.307203296,-1.6146875,11.03444343,2.517994639,56.18227425 +105.05,50.42615855,-2.58141153,51.2983,5.561908135,8.306981164,-1.558125,11.08977064,2.448126848,56.17474914 +105.06,50.42615905,-2.581410361,51.3136,5.561908144,8.306981097,-1.5,11.14382612,2.376124216,56.16722409 +105.07,50.42615955,-2.581409192,51.3283,5.561908137,8.306758964,-1.441875,11.19659851,2.302049654,56.15969897 +105.08,50.42616005,-2.581408023,51.3424,5.561908135,8.305870638,-1.3853125,11.24807682,2.225967562,56.15217392 +105.09,50.42616055,-2.581406854,51.356,5.561908151,8.304538183,-1.3296875,11.29825033,2.147944461,56.1446488 +105.1,50.42616105,-2.581405686,51.369,5.565384378,8.303427791,-1.2728125,11.34710851,2.068048304,56.13712375 +105.11,50.42616155,-2.581404517,51.3815,5.579289173,8.302539462,-1.213125,11.39464114,1.98634882,56.12959863 +105.12,50.42616205,-2.581403349,51.3933,5.596670135,8.302095261,-1.1515625,11.44083838,1.902917169,56.12207358 +105.13,50.42616256,-2.581402181,51.4045,5.59667013,8.302317252,-1.0903125,11.48569055,1.817826119,56.11454852 +105.14,50.42616306,-2.581401012,51.4151,5.57928917,8.301873049,-1.03,11.52918819,1.73114998,56.10702341 +105.15,50.42616356,-2.581399844,51.4251,5.56538441,8.300096461,-0.97,11.57132236,1.642964155,56.09949835 +105.16,50.42616406,-2.581398676,51.4345,5.561908234,8.298763999,-0.9096875,11.61208418,1.553345706,56.09197324 +105.17,50.42616456,-2.581397509,51.4433,5.565384447,8.298541859,-0.848125,11.65146512,1.462372728,56.08444819 +105.18,50.42616506,-2.58139634,51.4515,5.579289226,8.297653525,-0.785,11.68945703,1.370124461,56.07692307 +105.19,50.42616556,-2.581395173,51.459,5.596670188,8.296098997,-0.7215625,11.7260519,1.276681519,56.06939802 +105.2,50.42616607,-2.581394006,51.4659,5.596670185,8.29565479,-0.6584375,11.76124217,1.182125205,56.0618729 +105.21,50.42616657,-2.581392838,51.4722,5.579289226,8.296098839,-0.595,11.79502038,1.08653814,56.05434785 +105.22,50.42616707,-2.581391671,51.4778,5.568860661,8.295876694,-0.5315625,11.82737955,0.990003518,56.04682273 +105.23,50.42616757,-2.581390503,51.4828,5.579289256,8.294322164,-0.4684375,11.85831291,0.892605678,56.03929768 +105.24,50.42616807,-2.581389336,51.4872,5.596670226,8.292767632,-0.405,11.88781405,0.794429417,56.03177257 +105.25,50.42616858,-2.58138817,51.4909,5.596670218,8.292767549,-0.3415625,11.91587672,0.69556045,56.02424751 +105.26,50.42616908,-2.581387002,51.494,5.582765441,8.292767465,-0.2784375,11.94249508,0.596084893,56.0167224 +105.27,50.42616958,-2.581385835,51.4965,5.582765441,8.291212931,-0.2146875,11.96766357,0.496089548,56.00919734 +105.28,50.42617008,-2.581384669,51.4983,5.596670218,8.289658396,-0.1496875,11.99137703,0.39566162,56.00167223 +105.29,50.42617059,-2.581383502,51.4995,5.600146421,8.289214181,-0.08375,12.01363037,0.294888657,55.99414717 +105.3,50.42617109,-2.581382336,51.5,5.59667024,8.288992029,-0.0184375,12.03441899,0.193858551,55.98662206 +105.31,50.42617159,-2.581381169,51.4998,5.600146433,8.288103684,0.045,12.05373861,0.092659422,55.979097 +105.32,50.4261721,-2.581380003,51.4991,5.600146422,8.28677121,0.1084375,12.0715851,-0.008620494,55.97157189 +105.33,50.4261726,-2.581378837,51.4977,5.596670219,8.285882864,0.17375,12.08795485,-0.109892961,55.96404683 +105.34,50.4261731,-2.581377671,51.4956,5.600146409,8.285660709,0.239375,12.10284431,-0.211069573,55.95652172 +105.35,50.42617361,-2.581376505,51.4929,5.600146409,8.285660617,0.3034375,12.11625049,-0.312062093,55.94899667 +105.36,50.42617411,-2.581375339,51.4895,5.596670223,8.285660525,0.3665625,12.12817047,-0.412782516,55.94147155 +105.37,50.42617461,-2.581374173,51.4856,5.600146424,8.285438368,0.43,12.13860186,-0.513143007,55.9339465 +105.38,50.42617512,-2.581373007,51.4809,5.60014642,8.284327953,0.4934375,12.14754241,-0.613056017,55.92642138 +105.39,50.42617562,-2.581371841,51.4757,5.59667021,8.28232928,0.5565625,12.15499028,-0.712434401,55.91889633 +105.4,50.42617612,-2.581370676,51.4698,5.603622576,8.280996799,0.6203125,12.160944,-0.811191584,55.91137121 +105.41,50.42617663,-2.581369511,51.4633,5.614051143,8.280996703,0.6846875,12.16540219,-0.909241336,55.90384616 +105.42,50.42617713,-2.581368345,51.4561,5.614051144,8.280774542,0.748125,12.16836398,-1.006498228,55.89632105 +105.43,50.42617764,-2.58136718,51.4483,5.603622576,8.279664123,0.8096875,12.16982874,-1.102877464,55.88879599 +105.44,50.42617814,-2.581366015,51.4399,5.596670203,8.278775767,0.8703125,12.1697962,-1.198294991,55.88127088 +105.45,50.42617864,-2.58136485,51.4309,5.603622584,8.278331539,0.931875,12.16826635,-1.292667557,55.87374582 +105.46,50.42617915,-2.581363685,51.4213,5.614051133,8.277443182,0.9946875,12.16523947,-1.385912943,55.86622071 +105.47,50.42617965,-2.58136252,51.411,5.617527297,8.276110696,1.0565625,12.16071619,-1.477949732,55.85869565 +105.48,50.42618016,-2.581361356,51.4001,5.617527288,8.275222336,1.11625,12.15469756,-1.568697767,55.8511706 +105.49,50.42618066,-2.581360191,51.3887,5.617527285,8.27500017,1.175,12.14718471,-1.658077808,55.84364548 +105.5,50.42618117,-2.581359027,51.3766,5.617527277,8.274778002,1.23375,12.1381793,-1.746012047,55.83612043 +105.51,50.42618167,-2.581357862,51.364,5.617527269,8.273889641,1.293125,12.12768312,-1.832423708,55.82859531 +105.52,50.42618218,-2.581356698,51.3508,5.617527266,8.27255715,1.353125,12.11569844,-1.917237505,55.82107026 +105.53,50.42618268,-2.581355534,51.3369,5.617527266,8.271668788,1.41125,12.10222775,-2.00037941,55.81354515 +105.54,50.42618319,-2.58135437,51.3225,5.617527254,8.271224553,1.4665625,12.08727389,-2.081776946,55.80602009 +105.55,50.42618369,-2.581353206,51.3076,5.61752723,8.27033619,1.521875,12.07083986,-2.161359179,55.79849498 +105.56,50.4261842,-2.581352042,51.2921,5.617527208,8.269225761,1.5784375,12.05292925,-2.239056668,55.79096992 +105.57,50.4261847,-2.581350879,51.276,5.617527192,8.269003587,1.6346875,12.03354569,-2.314801631,55.78344481 +105.58,50.42618521,-2.581349715,51.2594,5.621003371,8.269225541,1.6896875,12.01269324,-2.388528064,55.77591975 +105.59,50.42618571,-2.581348551,51.2422,5.631431935,8.268781303,1.7434375,11.9903763,-2.460171681,55.76839464 +105.6,50.42618622,-2.581347388,51.2245,5.638384308,8.267892936,1.79625,11.96659953,-2.529669972,55.76086958 +105.61,50.42618673,-2.581346224,51.2063,5.631431915,8.266782503,1.8484375,11.94136784,-2.596962375,55.75334447 +105.62,50.42618723,-2.581345061,51.1875,5.621003331,8.265450005,1.8996875,11.91468657,-2.661990163,55.74581941 +105.63,50.42618774,-2.581343898,51.1683,5.621003315,8.264561635,1.95,11.88656122,-2.724696727,55.7382943 +105.64,50.42618824,-2.581342735,51.1485,5.631431866,8.264117394,2,11.85699774,-2.785027235,55.73076925 +105.65,50.42618875,-2.581341572,51.1283,5.638384225,8.263229024,2.049375,11.82600222,-2.842929203,55.72324413 +105.66,50.42618926,-2.581340409,51.1075,5.634908012,8.261896524,2.096875,11.79358123,-2.898352041,55.71571908 +105.67,50.42618976,-2.581339247,51.0863,5.634907994,8.261008152,2.143125,11.75974142,-2.951247505,55.70819396 +105.68,50.42619027,-2.581338084,51.0647,5.638384168,8.260785971,2.19,11.72448996,-3.001569471,55.70066891 +105.69,50.42619078,-2.581336922,51.0425,5.634907956,8.26056379,2.23625,11.68783419,-3.049273995,55.69314379 +105.7,50.42619128,-2.581335759,51.0199,5.634907939,8.259675416,2.2796875,11.64978177,-3.094319478,55.68561874 +105.71,50.42619179,-2.581334597,50.9969,5.638384121,8.258342914,2.321875,11.61034056,-3.136666674,55.67809363 +105.72,50.4261923,-2.581333435,50.9735,5.634907917,8.257454539,2.365,11.56951892,-3.176278684,55.67056857 +105.73,50.4261928,-2.581332273,50.9496,5.638384082,8.257232355,2.4078125,11.52732528,-3.213120902,55.66304346 +105.74,50.42619331,-2.581331111,50.9253,5.652288817,8.257010172,2.448125,11.48376851,-3.247161241,55.6555184 +105.75,50.42619382,-2.581329949,50.9006,5.652288791,8.256121795,2.4865625,11.43885773,-3.278370023,55.64799329 +105.76,50.42619433,-2.581328787,50.8756,5.638384003,8.255011354,2.5246875,11.39260221,-3.306720032,55.64046823 +105.77,50.42619483,-2.581327626,50.8501,5.638383983,8.254789169,2.5615625,11.34501171,-3.332186516,55.63294312 +105.78,50.42619534,-2.581326464,50.8243,5.652288731,8.254789048,2.5965625,11.29609612,-3.354747245,55.62541806 +105.79,50.42619585,-2.581325302,50.7982,5.652288709,8.253456541,2.6315625,11.24586572,-3.374382623,55.61789295 +105.8,50.42619636,-2.581324141,50.7717,5.638383915,8.251457842,2.6665625,11.19433091,-3.391075462,55.61036789 +105.81,50.42619686,-2.58132298,50.7448,5.638383894,8.250347398,2.6996875,11.14150249,-3.404811266,55.60284278 +105.82,50.42619737,-2.581321819,50.7177,5.655764842,8.250125211,2.73125,11.08739149,-3.415578002,55.59531773 +105.83,50.42619788,-2.581320658,50.6902,5.666193407,8.250125087,2.7615625,11.03200922,-3.423366332,55.58779267 +105.84,50.42619839,-2.581319497,50.6624,5.655764806,8.249902899,2.7896875,10.97536724,-3.42816938,55.58026756 +105.85,50.4261989,-2.581318336,50.6344,5.638383807,8.249014518,2.8165625,10.91747742,-3.429983078,55.5727425 +105.86,50.4261994,-2.581317175,50.6061,5.638383774,8.247682009,2.8434375,10.85835179,-3.428805764,55.56521739 +105.87,50.42619991,-2.581316015,50.5775,5.655764709,8.246793628,2.8696875,10.79800271,-3.42463847,55.55769233 +105.88,50.42620042,-2.581314854,50.5487,5.669669455,8.246571438,2.8946875,10.73644281,-3.417484806,55.55016722 +105.89,50.42620093,-2.581313694,50.5196,5.67314562,8.246349247,2.918125,10.67368491,-3.407351073,55.54264216 +105.9,50.42620144,-2.581312533,50.4903,5.673145587,8.245460865,2.939375,10.60974213,-3.394246096,55.53511705 +105.91,50.42620195,-2.581311373,50.4608,5.669669365,8.24390629,2.9584375,10.54462783,-3.378181276,55.52759199 +105.92,50.42620246,-2.581310213,50.4311,5.655764573,8.242129651,2.9765625,10.47835558,-3.359170594,55.52006688 +105.93,50.42620297,-2.581309053,50.4013,5.638383594,8.24079714,2.995,10.4109393,-3.337230722,55.51254183 +105.94,50.42620347,-2.581307894,50.3712,5.638383579,8.24057495,3.013125,10.34239298,-3.312380683,55.50501671 +105.95,50.42620398,-2.581306734,50.341,5.655764526,8.240796886,3.029375,10.27273094,-3.284642249,55.49749166 +105.96,50.42620449,-2.581305574,50.3106,5.669669269,8.240352631,3.043125,10.20196784,-3.254039542,55.48996654 +105.97,50.426205,-2.581304415,50.2801,5.673145424,8.239686311,3.0546875,10.1301183,-3.220599261,55.48244149 +105.98,50.42620551,-2.581303255,50.2495,5.673145388,8.239464119,3.065,10.05719745,-3.184350571,55.47491637 +105.99,50.42620602,-2.581302096,50.2188,5.673145359,8.239241926,3.075,9.983220461,-3.14532504,55.46739132 +106,50.42620653,-2.581300936,50.188,5.673145332,8.238353542,3.0846875,9.908202753,-3.103556818,55.45986621 +106.01,50.42620704,-2.581299777,50.1571,5.673145305,8.23702103,3.0928125,9.832160024,-3.059082173,55.45234115 +106.02,50.42620755,-2.581298618,50.1261,5.673145278,8.235910581,3.098125,9.755108201,-3.011940007,55.44481604 +106.03,50.42620806,-2.581297459,50.0951,5.673145251,8.234800133,3.1015625,9.677063328,-2.962171346,55.43729098 +106.04,50.42620857,-2.5812963,50.0641,5.673145222,8.23346762,3.105,9.598041734,-2.909819677,55.42976587 +106.05,50.42620908,-2.581295142,50.033,5.673145188,8.232579236,3.108125,9.518059862,-2.854930549,55.42224081 +106.06,50.42620959,-2.581293983,50.0019,5.673145156,8.232357044,3.1096875,9.437134444,-2.79755192,55.4147157 +106.07,50.4262101,-2.581292825,49.9708,5.673145134,8.232134851,3.1096875,9.355282438,-2.737733808,55.40719064 +106.08,50.42621061,-2.581291666,49.9397,5.673145113,8.231246466,3.108125,9.272520805,-2.675528296,55.39966553 +106.09,50.42621112,-2.581290508,49.9086,5.673145088,8.229913954,3.1046875,9.188866961,-2.6109897,55.39214047 +106.1,50.42621163,-2.58128935,49.8776,5.673145063,8.22902557,3.0996875,9.104338326,-2.544174284,55.38461536 +106.11,50.42621214,-2.581288192,49.8466,5.676621235,8.228803377,3.093125,9.018952545,-2.475140318,55.37709031 +106.12,50.42621265,-2.581287034,49.8157,5.690525981,8.228803249,3.0846875,8.932727497,-2.403947963,55.36956519 +106.13,50.42621316,-2.581285876,49.7849,5.707906912,8.228581056,3.075,8.845681113,-2.330659384,55.36204014 +106.14,50.42621368,-2.581284718,49.7542,5.707906886,8.227692672,3.065,8.757831614,-2.25533841,55.35451502 +106.15,50.42621419,-2.58128356,49.7236,5.6905259,8.22636016,3.055,8.669197335,-2.178050701,55.34698997 +106.16,50.4262147,-2.581282403,49.6931,5.676621101,8.225249712,3.044375,8.579796782,-2.098863751,55.33946485 +106.17,50.42621521,-2.581281245,49.6627,5.673144873,8.224139265,3.03125,8.489648634,-2.017846544,55.3319398 +106.18,50.42621572,-2.581280088,49.6324,5.67662103,8.223028818,3.0146875,8.398771741,-1.935069785,55.32441474 +106.19,50.42621623,-2.581278931,49.6024,5.690525767,8.222806627,2.996875,8.30718501,-1.85060555,55.31688963 +106.2,50.42621674,-2.581277774,49.5725,5.707906706,8.2228065,2.98,8.214907636,-1.764527579,55.30936457 +106.21,50.42621726,-2.581276616,49.5428,5.707906687,8.221696053,2.9628125,8.121958928,-1.676910931,55.30183946 +106.22,50.42621777,-2.58127546,49.5132,5.690525703,8.220585606,2.9428125,8.028358193,-1.587831979,55.2943144 +106.23,50.42621828,-2.581274303,49.4839,5.680097101,8.22058548,2.9196875,7.934125028,-1.497368475,55.28678929 +106.24,50.42621879,-2.581273146,49.4548,5.690525652,8.22036329,2.8953125,7.839279084,-1.405599143,55.27926424 +106.25,50.4262193,-2.581271989,49.426,5.707906586,8.219252845,2.8715625,7.743840186,-1.312604196,55.27173912 +106.26,50.42621982,-2.581270833,49.3974,5.707906559,8.2181424,2.848125,7.647828331,-1.218464595,55.26421407 +106.27,50.42622033,-2.581269676,49.369,5.69400176,8.217031955,2.8228125,7.551263456,-1.123262443,55.25668895 +106.28,50.42622084,-2.58126852,49.3409,5.694001731,8.215699446,2.7946875,7.454165846,-1.02708082,55.2491639 +106.29,50.42622135,-2.581267364,49.3131,5.707906478,8.214811066,2.7646875,7.356555667,-0.930003607,55.24163879 +106.3,50.42622187,-2.581266208,49.2856,5.707906461,8.214588878,2.7334375,7.258453318,-0.832115372,55.23411373 +106.31,50.42622238,-2.581265052,49.2584,5.694001672,8.214588755,2.7015625,7.159879367,-0.733501543,55.22658862 +106.32,50.42622289,-2.581263896,49.2316,5.694001648,8.214366568,2.6696875,7.060854384,-0.634248065,55.21906356 +106.33,50.4262234,-2.58126274,49.205,5.707906392,8.21347819,2.6365625,6.961398995,-0.534441509,55.21153845 +106.34,50.42622392,-2.581261584,49.1788,5.711382561,8.212145683,2.60125,6.861533941,-0.434168911,55.20401339 +106.35,50.42622443,-2.581260429,49.153,5.707906345,8.211035241,2.565,6.761280192,-0.333517759,55.19648828 +106.36,50.42622494,-2.581259273,49.1275,5.711382507,8.2099248,2.5284375,6.660658605,-0.232575716,55.18896322 +106.37,50.42622546,-2.581258118,49.1024,5.711382481,8.208592296,2.49125,6.559690206,-0.131430903,55.18143811 +106.38,50.42622597,-2.581256963,49.0777,5.707906272,8.207703921,2.453125,6.45839608,-0.030171442,55.17391305 +106.39,50.42622648,-2.581255808,49.0533,5.711382451,8.207481737,2.413125,6.356797371,0.071114261,55.16638794 +106.4,50.426227,-2.581254653,49.0294,5.711382439,8.207481617,2.37125,6.254915333,0.172338027,55.15886289 +106.41,50.42622751,-2.581253498,49.0059,5.707906232,8.207481497,2.3284375,6.152771225,0.273411449,55.15133777 +106.42,50.42622802,-2.581252343,48.9828,5.714858588,8.207259316,2.2846875,6.05038636,0.374246521,55.14381272 +106.43,50.42622854,-2.581251188,48.9602,5.72528713,8.206370942,2.24,5.947782167,0.474755178,55.1362876 +106.44,50.42622905,-2.581250033,48.938,5.725287109,8.205038441,2.195,5.844980016,0.574849874,55.12876255 +106.45,50.42622957,-2.581248879,48.9163,5.714858532,8.203928005,2.1496875,5.742001395,0.674443288,55.12123743 +106.46,50.42623008,-2.581247724,48.895,5.707906144,8.20281757,2.103125,5.638867846,0.773448562,55.11371238 +106.47,50.42623059,-2.58124657,48.8742,5.714858495,8.201485071,2.0546875,5.535600855,0.871779407,55.10618727 +106.48,50.42623111,-2.581245416,48.8539,5.725287035,8.200596701,2.005,5.432222023,0.969350051,55.09866221 +106.49,50.42623162,-2.581244262,48.8341,5.728763209,8.200374523,1.955,5.328752893,1.066075354,55.0911371 +106.5,50.42623214,-2.581243108,48.8148,5.728763199,8.200152345,1.905,5.225215122,1.16187109,55.08361204 +106.51,50.42623265,-2.581241954,48.796,5.728763185,8.199263977,1.8546875,5.121630368,1.256653607,55.07608698 +106.52,50.42623317,-2.5812408,48.7777,5.728763169,8.197931481,1.803125,5.018020176,1.350340343,55.06856187 +106.53,50.42623368,-2.581239647,48.7599,5.728763151,8.197043114,1.75,4.914406202,1.442849535,55.06103682 +106.54,50.4262342,-2.581238493,48.7427,5.72876313,8.196820938,1.69625,4.810810104,1.534100513,55.0535117 +106.55,50.42623471,-2.58123734,48.726,5.728763111,8.196598764,1.641875,4.70725354,1.624013805,55.04598665 +106.56,50.42623523,-2.581236186,48.7098,5.728763101,8.1957104,1.58625,4.603758111,1.712510861,55.03846153 +106.57,50.42623574,-2.581235033,48.6943,5.728763095,8.194377908,1.53,4.500345417,1.799514617,55.03093648 +106.58,50.42623626,-2.58123388,48.6792,5.728763084,8.193489544,1.4734375,4.397037058,1.884949156,55.02341137 +106.59,50.42623677,-2.581232727,48.6648,5.728763071,8.193267374,1.41625,4.293854693,1.968739993,55.01588631 +106.6,50.42623729,-2.581231574,48.6509,5.728763059,8.193045203,1.35875,4.190819693,2.050814078,55.0083612 +106.61,50.4262378,-2.581230421,48.6376,5.728763048,8.192156842,1.30125,4.087953773,2.131099846,55.00083614 +106.62,50.42623832,-2.581229268,48.6249,5.732239226,8.190824353,1.243125,3.985278246,2.209527226,54.99331103 +106.63,50.42623883,-2.581228116,48.6127,5.742667784,8.18971393,1.183125,3.882814714,2.286027863,54.98578597 +106.64,50.42623935,-2.581226963,48.6012,5.749620153,8.188603507,1.121875,3.780584433,2.360535065,54.97826086 +106.65,50.42623987,-2.581225811,48.5903,5.742667765,8.187493085,1.061875,3.678608831,2.432983802,54.9707358 +106.66,50.42624038,-2.581224659,48.58,5.732239188,8.187270919,1.0028125,3.576909166,2.503310991,54.96321069 +106.67,50.4262409,-2.581223507,48.5702,5.732239177,8.187270817,0.9415625,3.475506695,2.571455268,54.95568563 +106.68,50.42624141,-2.581222354,48.5611,5.742667731,8.186160397,0.878125,3.374422616,2.63735716,54.94816052 +106.69,50.42624193,-2.581221203,48.5527,5.749620098,8.185049979,0.8153125,3.273678014,2.700959257,54.94063546 +106.7,50.42624245,-2.581220051,48.5448,5.746143907,8.18504988,0.7534375,3.173293918,2.762206039,54.93311035 +106.71,50.42624296,-2.581218899,48.5376,5.746143907,8.184827717,0.69125,3.073291297,2.821044164,54.9255853 +106.72,50.42624348,-2.581217747,48.531,5.749620093,8.183717301,0.6284375,2.973691064,2.877422294,54.91806018 +106.73,50.426244,-2.581216596,48.525,5.746143901,8.182606885,0.565,2.87451396,2.93129127,54.91053513 +106.74,50.42624451,-2.581215444,48.5197,5.749620093,8.18149647,0.5015625,2.775780784,2.98260411,54.90301001 +106.75,50.42624503,-2.581214293,48.515,5.763524851,8.180163992,0.4384375,2.677512105,3.031316122,54.89548496 +106.76,50.42624555,-2.581213142,48.5109,5.763524843,8.179275643,0.3746875,2.579728435,3.077384736,54.88795985 +106.77,50.42624607,-2.581211991,48.5075,5.749620079,8.179053486,0.31,2.482450228,3.120769845,54.88043479 +106.78,50.42624658,-2.58121084,48.5047,5.746143892,8.179053394,0.2453125,2.385697767,3.161433577,54.87290968 +106.79,50.4262471,-2.581209689,48.5026,5.749620085,8.178831238,0.1815625,2.289491278,3.199340465,54.86538462 +106.8,50.42624762,-2.581208538,48.5011,5.746143892,8.177942891,0.118125,2.193850814,3.234457564,54.85785951 +106.81,50.42624813,-2.581207387,48.5002,5.749620081,8.176610418,0.0534375,2.098796371,3.266754106,54.85033445 +106.82,50.42624865,-2.581206237,48.5,5.767001032,8.17550001,-0.011875,2.004347831,3.296201959,54.84280934 +106.83,50.42624917,-2.581205086,48.5005,5.777429603,8.174611666,-0.07625,1.910524903,3.32277557,54.83528428 +106.84,50.42624969,-2.581203936,48.5015,5.767001035,8.174167451,-0.14,1.817347183,3.346451618,54.82775917 +106.85,50.42625021,-2.581202786,48.5033,5.749620086,8.174389428,-0.20375,1.724834095,3.367209478,54.82023411 +106.86,50.42625072,-2.581201635,48.5056,5.749620091,8.174167278,-0.268125,1.633005003,3.385031101,54.81270906 +106.87,50.42625124,-2.581200485,48.5086,5.767001051,8.173056875,-0.3334375,1.541879045,3.39990096,54.80518394 +106.88,50.42625176,-2.581199335,48.5123,5.777429628,8.171946471,-0.398125,1.451475243,3.411806049,54.79765889 +106.89,50.42625228,-2.581198185,48.5166,5.767001051,8.170614004,-0.4615625,1.361812562,3.420735998,54.79013378 +106.9,50.4262528,-2.581197035,48.5215,5.749620094,8.168615347,-0.525,1.27290968,3.426682956,54.78260872 +106.91,50.42625331,-2.581195886,48.5271,5.749620104,8.167282883,-0.5884375,1.184785104,3.429641824,54.77508361 +106.92,50.42625383,-2.581194737,48.5333,5.767001074,8.167282803,-0.6515625,1.097457284,3.429610025,54.76755855 +106.93,50.42625435,-2.581193587,48.5401,5.780905847,8.167282722,-0.715,1.010944495,3.426587558,54.76003344 +106.94,50.42625487,-2.581192438,48.5476,5.784382039,8.167060579,-0.778125,0.925264731,3.420577002,54.75250838 +106.95,50.42625539,-2.581191289,48.5557,5.784382042,8.167060499,-0.8396875,0.84043598,3.411583684,54.74498327 +106.96,50.42625591,-2.581190139,48.5644,5.784382055,8.165950102,-0.9003125,0.756475833,3.399615398,54.73745821 +106.97,50.42625643,-2.58118899,48.5737,5.784382071,8.163729387,-0.9615625,0.673401938,3.384682628,54.7299331 +106.98,50.42625695,-2.581187842,48.5836,5.780905891,8.162841054,-1.0234375,0.591231596,3.366798324,54.72240804 +106.99,50.42625747,-2.581186693,48.5942,5.767001135,8.16350717,-1.0846875,0.509981941,3.345978183,54.71488293 +107,50.42625799,-2.581185544,48.6053,5.749620184,8.163285032,-1.145,0.429669989,3.322240255,54.70735788 +107.01,50.4262585,-2.581184395,48.6171,5.749620179,8.161286386,-1.205,0.350312469,3.295605281,54.69983276 +107.02,50.42625902,-2.581183247,48.6294,5.767001133,8.159065675,-1.2646875,0.271925999,3.266096522,54.69230771 +107.03,50.42625954,-2.581182099,48.6424,5.780905916,8.158177347,-1.323125,0.194526964,3.233739647,54.68478259 +107.04,50.42626006,-2.581180951,48.6559,5.784382138,8.158621402,-1.38,0.118131407,3.198562904,54.67725754 +107.05,50.42626058,-2.581179803,48.67,5.78438216,8.159065458,-1.436875,0.042755428,3.160596944,54.66973242 +107.06,50.4262611,-2.581178654,48.6846,5.78438217,8.15862126,-1.4946875,-0.03158533,3.119874943,54.66220737 +107.07,50.42626162,-2.581177507,48.6999,5.784382179,8.157732935,-1.5515625,-0.104875283,3.076432366,54.65468226 +107.08,50.42626214,-2.581176358,48.7157,5.784382199,8.156622547,-1.60625,-0.177099135,3.030307086,54.6471572 +107.09,50.42626266,-2.581175211,48.732,5.787858412,8.155068033,-1.6603125,-0.248241814,2.981539325,54.63963209 +107.1,50.42626318,-2.581174063,48.7489,5.801763197,8.153513519,-1.7146875,-0.318288483,2.930171596,54.63210703 +107.11,50.4262637,-2.581172916,48.7663,5.819144171,8.15284726,-1.768125,-0.38722453,2.876248705,54.62458192 +107.12,50.42626423,-2.581171769,48.7843,5.819144186,8.153069257,-1.82,-0.455035461,2.819817747,54.61705686 +107.13,50.42626475,-2.581170621,48.8027,5.801763238,8.152847127,-1.8715625,-0.521707236,2.760927828,54.60953175 +107.14,50.42626527,-2.581169474,48.8217,5.787858485,8.151736744,-1.9234375,-0.587225819,2.699630339,54.60200669 +107.15,50.42626579,-2.581168327,48.8412,5.784382316,8.150848424,-1.9746875,-0.651577631,2.635978739,54.59448158 +107.16,50.42626631,-2.58116718,48.8612,5.784382339,8.150404233,-2.0246875,-0.71474915,2.570028489,54.58695652 +107.17,50.42626683,-2.581166033,48.8817,5.78438235,8.149515915,-2.073125,-0.776727256,2.501837172,54.57943141 +107.18,50.42626735,-2.581164886,48.9027,5.784382352,8.14818347,-2.12,-0.837498941,2.431464204,54.57190636 +107.19,50.42626787,-2.58116374,48.9241,5.787858559,8.147295153,-2.1665625,-0.897051544,2.358971005,54.56438124 +107.2,50.42626839,-2.581162593,48.946,5.801763362,8.147073028,-2.213125,-0.955372574,2.284420716,54.55685619 +107.21,50.42626891,-2.581161447,48.9684,5.819144357,8.146850904,-2.258125,-1.012449942,2.207878368,54.54933113 +107.22,50.42626944,-2.5811603,48.9912,5.81914438,8.145962589,-2.30125,-1.06827173,2.129410709,54.54180602 +107.23,50.42626996,-2.581159154,49.0144,5.801763436,8.144408082,-2.3434375,-1.122826193,2.049086209,54.53428096 +107.24,50.42627048,-2.581158008,49.0381,5.787858687,8.142631514,-2.385,-1.176101986,1.966974825,54.52675585 +107.25,50.426271,-2.581156862,49.0621,5.787858714,8.141299073,-2.42625,-1.228087937,1.883148292,54.51923079 +107.26,50.42627152,-2.581155717,49.0866,5.80176351,8.141299014,-2.4665625,-1.278773273,1.797679548,54.51170568 +107.27,50.42627204,-2.581154571,49.1115,5.819144493,8.142187211,-2.5046875,-1.328147395,1.710643248,54.50418062 +107.28,50.42627257,-2.581153425,49.1367,5.819144509,8.14196509,-2.5415625,-1.376199933,1.622115195,54.49665551 +107.29,50.42627309,-2.581152279,49.1623,5.80176357,8.140188524,-2.5784375,-1.42292086,1.532172681,54.48913046 +107.3,50.42627361,-2.581151134,49.1883,5.791335021,8.138856086,-2.6146875,-1.468300492,1.44089403,54.48160534 +107.31,50.42627413,-2.581149989,49.2146,5.801763618,8.13885603,-2.6496875,-1.512329262,1.34835894,54.47408029 +107.32,50.42627465,-2.581148843,49.2413,5.819144592,8.13863391,-2.683125,-1.554998059,1.254648083,54.46655517 +107.33,50.42627518,-2.581147698,49.2683,5.822620802,8.137523536,-2.7146875,-1.596297889,1.159843106,54.45903012 +107.34,50.4262757,-2.581146553,49.2956,5.819144642,8.136635227,-2.745,-1.636220155,1.064026743,54.451505 +107.35,50.42627622,-2.581145408,49.3232,5.822620873,8.136191046,-2.7746875,-1.674756552,0.967282533,54.44397995 +107.36,50.42627675,-2.581144263,49.3511,5.819144716,8.135302737,-2.803125,-1.711899057,0.869694872,54.43645484 +107.37,50.42627727,-2.581143118,49.3793,5.805239974,8.133970301,-2.83,-1.74763982,0.771348786,54.42892978 +107.38,50.42627779,-2.581141974,49.4077,5.805239994,8.132859929,-2.8565625,-1.781971394,0.672330105,54.42140467 +107.39,50.42627831,-2.581140829,49.4364,5.819144784,8.131749557,-2.8828125,-1.814886731,0.572725117,54.41387961 +107.4,50.42627884,-2.581139685,49.4654,5.822621003,8.130417123,-2.90625,-1.846378783,0.472620681,54.4063545 +107.41,50.42627936,-2.581138541,49.4946,5.81914483,8.12975088,-2.9265625,-1.876441076,0.372104174,54.39882944 +107.42,50.42627988,-2.581137397,49.5239,5.826097228,8.130194955,-2.946875,-1.905067308,0.271263144,54.39130433 +107.43,50.42628041,-2.581136253,49.5535,5.836525836,8.130416967,-2.968125,-1.93225152,0.170185539,54.38377927 +107.44,50.42628093,-2.581135108,49.5833,5.836525881,8.129084533,-2.9878125,-1.957988039,0.068959596,54.37625416 +107.45,50.42628146,-2.581133965,49.6133,5.826097344,8.127085907,-3.0046875,-1.98227148,-0.032326508,54.3687291 +107.46,50.42628198,-2.581132821,49.6434,5.81914499,8.126197601,-3.02,-2.005096686,-0.133584422,54.36120399 +107.47,50.4262825,-2.581131678,49.6737,5.822621208,8.126641677,-3.0346875,-2.026459017,-0.234725854,54.35367894 +107.48,50.42628303,-2.581130534,49.7041,5.82262123,8.126863691,-3.048125,-2.046354002,-0.335662626,54.34615382 +107.49,50.42628355,-2.58112939,49.7347,5.819145062,8.125531258,-3.06,-2.064777403,-0.436306616,54.33862877 +107.5,50.42628407,-2.581128247,49.7653,5.826097475,8.123532634,-3.07125,-2.08172538,-0.53657022,54.33110365 +107.51,50.4262846,-2.581127104,49.7961,5.836526071,8.122422265,-3.0815625,-2.097194495,-0.636365888,54.3235786 +107.52,50.42628512,-2.581125961,49.827,5.840002279,8.121978088,-3.089375,-2.111181427,-0.735606648,54.31605348 +107.53,50.42628565,-2.581124818,49.8579,5.840002312,8.121311847,-3.095,-2.123683251,-0.834205923,54.30852843 +107.54,50.42628617,-2.581123675,49.8889,5.840002359,8.120867669,-3.1,-2.134697448,-0.932077829,54.30100332 +107.55,50.4262867,-2.581122533,49.9199,5.840002397,8.120867619,-3.1046875,-2.144221611,-1.029136879,54.29347826 +107.56,50.42628722,-2.581121389,49.951,5.840002421,8.119979314,-3.108125,-2.152253791,-1.125298506,54.2859532 +107.57,50.42628775,-2.581120247,49.9821,5.840002446,8.118424818,-3.1096875,-2.158792329,-1.220478885,54.27842809 +107.58,50.42628827,-2.581119105,50.0132,5.840002479,8.117758576,-3.1096875,-2.163835847,-1.314594995,54.27090304 +107.59,50.4262888,-2.581117962,50.0443,5.840002513,8.117314398,-3.108125,-2.167383258,-1.407564732,54.26337792 +107.6,50.42628932,-2.58111682,50.0754,5.840002533,8.11620403,-3.1046875,-2.169433874,-1.499307077,54.25585287 +107.61,50.42628985,-2.581115678,50.1064,5.840002544,8.115315726,-3.1,-2.169987236,-1.589741991,54.24832775 +107.62,50.42629037,-2.581114536,50.1374,5.840002568,8.114871548,-3.095,-2.169043288,-1.678790633,54.2408027 +107.63,50.4262909,-2.581113394,50.1683,5.840002613,8.113983243,-3.0896875,-2.166602144,-1.766375311,54.23327758 +107.64,50.42629142,-2.581112252,50.1992,5.840002657,8.112872874,-3.0828125,-2.16266432,-1.852419763,54.22575253 +107.65,50.42629195,-2.581111111,50.23,5.843478881,8.11265076,-3.073125,-2.157230675,-1.936848819,54.21822742 +107.66,50.42629247,-2.581109969,50.2607,5.85390748,8.112650708,-3.0615625,-2.150302355,-2.019588909,54.21070236 +107.67,50.426293,-2.581108827,50.2912,5.860859887,8.111318275,-3.05,-2.141880792,-2.100567899,54.20317725 +107.68,50.42629353,-2.581107686,50.3217,5.853907524,8.109319652,-3.0378125,-2.131967705,-2.179715143,54.19565219 +107.69,50.42629405,-2.581106545,50.352,5.843478963,8.108209283,-3.023125,-2.120565215,-2.256961657,54.18812708 +107.7,50.42629458,-2.581105404,50.3822,5.84347899,8.107987168,-3.0065625,-2.107675727,-2.332240118,54.18060202 +107.71,50.4262951,-2.581104263,50.4121,5.853907611,8.107987116,-2.9896875,-2.09330182,-2.40548475,54.17307691 +107.72,50.42629563,-2.581103122,50.442,5.860860039,8.107765,-2.9715625,-2.077446646,-2.476631785,54.16555185 +107.73,50.42629616,-2.581101981,50.4716,5.857383876,8.106876693,-2.95125,-2.060113354,-2.545619169,54.15802674 +107.74,50.42629668,-2.58110084,50.501,5.857383897,8.105544259,-2.93,-2.041305728,-2.612386743,54.15050168 +107.75,50.42629721,-2.5810997,50.5302,5.860860111,8.104655951,-2.908125,-2.021027549,-2.676876294,54.14297657 +107.76,50.42629774,-2.581098559,50.5592,5.857383939,8.104433835,-2.8846875,-1.99928317,-2.739031558,54.13545152 +107.77,50.42629826,-2.581097419,50.5879,5.857383955,8.104211718,-2.86,-1.976077004,-2.798798332,54.1279264 +107.78,50.42629879,-2.581096278,50.6164,5.860860172,8.10332341,-2.8346875,-1.951414036,-2.856124536,54.12040135 +107.79,50.42629932,-2.581095138,50.6446,5.857384021,8.101990974,-2.808125,-1.925299365,-2.910960092,54.11287623 +107.8,50.42629984,-2.581093998,50.6726,5.860860255,8.1008806,-2.7796875,-1.897738433,-2.96325733,54.10535118 +107.81,50.42630037,-2.581092858,50.7002,5.874765054,8.099770227,-2.7496875,-1.868736971,-3.012970529,54.09782606 +107.82,50.4263009,-2.581091718,50.7276,5.874765071,8.098659854,-2.7184375,-1.838301052,-3.060056373,54.09030101 +107.83,50.42630143,-2.581090579,50.7546,5.860860312,8.098437735,-2.68625,-1.806437036,-3.10447378,54.0827759 +107.84,50.42630195,-2.581089439,50.7813,5.860860329,8.098437679,-2.6534375,-1.773151625,-3.146184076,54.07525084 +107.85,50.42630248,-2.581088299,50.8077,5.874765125,8.097105241,-2.6196875,-1.738451697,-3.185150821,54.06772573 +107.86,50.42630301,-2.58108716,50.8337,5.874765158,8.095106612,-2.5846875,-1.702344527,-3.221340096,54.06020067 +107.87,50.42630354,-2.581086021,50.8594,5.860860424,8.093996236,-2.5484375,-1.664837678,-3.254720273,54.05267556 +107.88,50.42630406,-2.581084882,50.8847,5.860860457,8.093774114,-2.51125,-1.625938943,-3.285262361,54.0451505 +107.89,50.42630459,-2.581083743,50.9096,5.878241442,8.093774056,-2.473125,-1.585656458,-3.312939603,54.03762545 +107.9,50.42630512,-2.581082604,50.9342,5.888670028,8.093773997,-2.433125,-1.543998702,-3.337727878,54.03010033 +107.91,50.42630565,-2.581081465,50.9583,5.878241457,8.093551874,-2.3915625,-1.50097427,-3.359605641,54.02257528 +107.92,50.42630618,-2.581080326,50.982,5.860860517,8.09266356,-2.35,-1.456592157,-3.378553813,54.01505016 +107.93,50.4263067,-2.581079187,51.0053,5.860860551,8.091331118,-2.308125,-1.41086176,-3.39455578,54.00752511 +107.94,50.42630723,-2.581078049,51.0282,5.878241543,8.090220738,-2.2646875,-1.363792475,-3.407597674,54 +107.95,50.42630776,-2.58107691,51.0506,5.892146338,8.089332422,-2.2196875,-1.315394157,-3.417668095,53.99247494 +107.96,50.42630829,-2.581075772,51.0726,5.895622543,8.088888233,-2.1734375,-1.265677005,-3.424758219,53.98494983 +107.97,50.42630882,-2.581074634,51.0941,5.892146357,8.08888817,-2.1265625,-1.214651332,-3.428861914,53.97742477 +107.98,50.42630935,-2.581073495,51.1151,5.87824161,8.087777789,-2.0796875,-1.162327852,-3.42997563,53.96989966 +107.99,50.42630988,-2.581072357,51.1357,5.860860682,8.085557089,-2.0315625,-1.108717394,-3.428098333,53.9623746 +108,50.4263104,-2.58107122,51.1558,5.86086071,8.08466877,-1.9815625,-1.053831246,-3.423231687,53.95484949 +108.01,50.42631093,-2.581070082,51.1753,5.878241689,8.085334896,-1.9315625,-0.997680809,-3.415379931,53.94732443 +108.02,50.42631146,-2.581068944,51.1944,5.892146473,8.085112766,-1.8815625,-0.940277829,-3.404549883,53.93979932 +108.03,50.42631199,-2.581067806,51.213,5.895622677,8.083336191,-1.8296875,-0.881634281,-3.390751054,53.93227426 +108.04,50.42631252,-2.581066669,51.231,5.895622683,8.082003742,-1.7765625,-0.821762483,-3.373995418,53.92474915 +108.05,50.42631305,-2.581065532,51.2485,5.895622697,8.082003674,-1.7234375,-0.760674812,-3.354297645,53.9172241 +108.06,50.42631358,-2.581064394,51.2655,5.895622729,8.081559479,-1.6696875,-0.698384158,-3.331674865,53.90969898 +108.07,50.42631411,-2.581063257,51.2819,5.89562276,8.079560837,-1.6146875,-0.634903471,-3.306146788,53.90217393 +108.08,50.42631464,-2.58106212,51.2978,5.895622775,8.077562194,-1.5584375,-0.570245986,-3.277735701,53.89464881 +108.09,50.42631517,-2.581060984,51.3131,5.895622775,8.077340059,-1.5015625,-0.504425225,-3.246466415,53.88712376 +108.1,50.4263157,-2.581059847,51.3278,5.895622773,8.078228243,-1.4453125,-0.437454938,-3.212366087,53.87959864 +108.11,50.42631623,-2.58105871,51.342,5.895622789,8.078006108,-1.3896875,-0.369349107,-3.175464626,53.87207359 +108.12,50.42631676,-2.581057573,51.3556,5.895622813,8.076229526,-1.3328125,-0.300121939,-3.135794059,53.86454848 +108.13,50.42631729,-2.581056437,51.3687,5.89562283,8.07489707,-1.2734375,-0.229787932,-3.093389052,53.85702342 +108.14,50.42631782,-2.581055301,51.3811,5.895622838,8.074896996,-1.213125,-0.158361753,-3.048286502,53.84949831 +108.15,50.42631835,-2.581054164,51.3929,5.895622838,8.074674858,-1.1534375,-0.085858299,-3.000525886,53.84197325 +108.16,50.42631888,-2.581053028,51.4042,5.895622847,8.073564464,-1.093125,-0.012292752,-2.950148744,53.83444814 +108.17,50.42631941,-2.581051892,51.4148,5.895622873,8.07245407,-1.0315625,0.062319588,-2.897198964,53.82692308 +108.18,50.42631994,-2.581050756,51.4248,5.895622898,8.071343674,-0.9703125,0.137963023,-2.841722841,53.81939797 +108.19,50.42632047,-2.58104962,51.4342,5.895622907,8.070233278,-0.91,0.214621911,-2.783768733,53.81187291 +108.2,50.426321,-2.581048485,51.443,5.899099094,8.070011136,-0.8496875,0.292280153,-2.72338706,53.8043478 +108.21,50.42632153,-2.581047349,51.4512,5.913003859,8.070011056,-0.788125,0.370921475,-2.660630591,53.79682274 +108.22,50.42632206,-2.581046213,51.4588,5.930384834,8.068678594,-0.725,0.450529606,-2.595553988,53.78929763 +108.23,50.4263226,-2.581045078,51.4657,5.930384852,8.06667994,-0.6615625,0.531087816,-2.528214086,53.78177258 +108.24,50.42632313,-2.581043943,51.472,5.913003897,8.06556954,-0.5984375,0.612579259,-2.4586695,53.77424752 +108.25,50.42632366,-2.581042808,51.4777,5.899099126,8.065347393,-0.5346875,0.694986977,-2.386980906,53.76672241 +108.26,50.42632419,-2.581041673,51.4827,5.895622927,8.065347309,-0.47,0.778293779,-2.313210814,53.75919735 +108.27,50.42632472,-2.581040538,51.4871,5.899099123,8.065347225,-0.4053125,0.862482193,-2.237423624,53.75167224 +108.28,50.42632525,-2.581039403,51.4908,5.913003913,8.065125076,-0.3415625,0.947534683,-2.159685341,53.74414718 +108.29,50.42632578,-2.581038268,51.4939,5.930384888,8.064236735,-0.2784375,1.033433433,-2.080063745,53.73662207 +108.3,50.42632632,-2.581037133,51.4964,5.930384882,8.062904267,-0.215,1.120160622,-1.998628337,53.72909701 +108.31,50.42632685,-2.581035999,51.4982,5.913003912,8.061793862,-0.1515625,1.20769803,-1.915450106,53.7215719 +108.32,50.42632738,-2.581034864,51.4994,5.902575341,8.060683455,-0.088125,1.296027439,-1.830601531,53.71404684 +108.33,50.42632791,-2.58103373,51.5,5.913003933,8.059350984,-0.023125,1.38513034,-1.744156695,53.70652173 +108.34,50.42632844,-2.581032596,51.4999,5.930384901,8.05846264,0.043125,1.47498817,-1.656190886,53.69899668 +108.35,50.42632898,-2.581031462,51.4991,5.930384897,8.058240485,0.108125,1.565582194,-1.566780879,53.69147156 +108.36,50.42632951,-2.581030328,51.4977,5.916480117,8.058240393,0.1715625,1.656893389,-1.476004655,53.68394651 +108.37,50.42633004,-2.581029194,51.4957,5.916480104,8.058018237,0.2353125,1.748902791,-1.383941281,53.67642139 +108.38,50.42633057,-2.58102806,51.493,5.930384873,8.056907826,0.3,1.841591148,-1.290671085,53.66889634 +108.39,50.42633111,-2.581026926,51.4897,5.933861074,8.054687096,0.365,1.934939036,-1.196275429,53.66137122 +108.4,50.42633164,-2.581025793,51.4857,5.930384878,8.052688428,0.4296875,2.02892709,-1.100836589,53.65384617 +108.41,50.42633217,-2.58102466,51.4811,5.933861056,8.052466268,0.493125,2.1235356,-1.004437815,53.64632106 +108.42,50.42633271,-2.581023527,51.4758,5.930384861,8.053354426,0.5553125,2.218744799,-0.90716316,53.638796 +108.43,50.42633324,-2.581022393,51.47,5.916480095,8.053354329,0.618125,2.314534862,-0.809097423,53.63127089 +108.44,50.42633377,-2.58102126,51.4635,5.916480094,8.05202185,0.681875,2.410885737,-0.710326145,53.62374583 +108.45,50.4263343,-2.581020127,51.4563,5.933861049,8.050245242,0.7446875,2.507777312,-0.610935443,53.61622072 +108.46,50.42633484,-2.581018994,51.4486,5.947765803,8.048912761,0.8065625,2.605189304,-0.511012005,53.60869566 +108.47,50.42633537,-2.581017862,51.4402,5.947765794,8.048690596,0.86875,2.703101489,-0.410642977,53.60117055 +108.48,50.42633591,-2.581016729,51.4312,5.93733722,8.048912558,0.93125,2.801493354,-0.309915851,53.59364549 +108.49,50.42633644,-2.581015596,51.4216,5.930384832,8.048468328,0.9934375,2.90034433,-0.20891846,53.58612038 +108.5,50.42633697,-2.581014464,51.4113,5.933861007,8.047579971,1.0546875,2.999633791,-0.107738927,53.57859532 +108.51,50.42633751,-2.581013331,51.4005,5.933860989,8.046469549,1.1146875,3.099340995,-0.00646537,53.57107021 +108.52,50.42633804,-2.581012199,51.389,5.930384786,8.045137064,1.1734375,3.199445144,0.094813743,53.56354516 +108.53,50.42633857,-2.581011067,51.377,5.937337168,8.044026641,1.2315625,3.299925268,0.196010237,53.55602004 +108.54,50.42633911,-2.581009935,51.3644,5.947765738,8.042916217,1.2903125,3.400760512,0.29703576,53.54849499 +108.55,50.42633964,-2.581008803,51.3512,5.951241911,8.041805793,1.3496875,3.501929675,0.397802305,53.54096987 +108.56,50.42634018,-2.581007672,51.3374,5.951241896,8.041583622,1.408125,3.603411673,0.498221925,53.53344482 +108.57,50.42634071,-2.58100654,51.323,5.947765706,8.041583514,1.465,3.705185421,0.598207128,53.5259197 +108.58,50.42634125,-2.581005408,51.3081,5.937337126,8.040473087,1.5215625,3.807229491,0.697670654,53.51839465 +108.59,50.42634178,-2.581004277,51.2926,5.93038472,8.03936266,1.5784375,3.909522683,0.796525812,53.51086959 +108.6,50.42634231,-2.581003146,51.2765,5.937337074,8.039362549,1.634375,4.012043626,0.894686374,53.50334448 +108.61,50.42634285,-2.581002014,51.2599,5.947765633,8.039140374,1.6884375,4.11477089,0.992066739,53.49581942 +108.62,50.42634338,-2.581000883,51.2427,5.951241822,8.037807882,1.7415625,4.217682991,1.088582053,53.48829431 +108.63,50.42634392,-2.580999752,51.2251,5.951241806,8.036031261,1.7946875,4.3207585,1.18414809,53.48076926 +108.64,50.42634445,-2.580998621,51.2068,5.951241779,8.034698767,1.846875,4.423975815,1.278681542,53.47324414 +108.65,50.42634499,-2.580997491,51.1881,5.951241764,8.03447659,1.8978125,4.527313452,1.372099962,53.46571909 +108.66,50.42634552,-2.58099636,51.1689,5.951241758,8.034698539,1.9484375,4.630749809,1.464321873,53.45819397 +108.67,50.42634606,-2.580995229,51.1491,5.954717937,8.034032233,1.998125,4.734263286,1.555266891,53.45066892 +108.68,50.42634659,-2.580994099,51.1289,5.965146493,8.032477673,2.0465625,4.837832226,1.644855661,53.4431438 +108.69,50.42634713,-2.580992968,51.1082,5.972098849,8.031145176,2.095,4.941435085,1.733010145,53.43561875 +108.7,50.42634767,-2.580991839,51.087,5.965146442,8.030922995,2.143125,5.045050147,1.819653338,53.42809364 +108.71,50.4263482,-2.580990708,51.0653,5.954717854,8.031144941,2.1896875,5.148655814,1.90470984,53.42056858 +108.72,50.42634874,-2.580989578,51.0432,5.954717832,8.030478632,2.2346875,5.252230426,1.988105394,53.41304347 +108.73,50.42634927,-2.580988448,51.0206,5.965146372,8.028924069,2.2784375,5.355752325,2.069767292,53.40551841 +108.74,50.42634981,-2.580987318,50.9976,5.972098737,8.027591569,2.3215625,5.45919997,2.149624316,53.3979933 +108.75,50.42635035,-2.580986189,50.9742,5.965146348,8.027369386,2.3646875,5.562551701,2.227606794,53.39046824 +108.76,50.42635088,-2.580985059,50.9503,5.95471775,8.027369265,2.4065625,5.665785976,2.303646831,53.38294313 +108.77,50.42635142,-2.580983929,50.926,5.954717717,8.026036764,2.44625,5.768881194,2.37767802,53.37541807 +108.78,50.42635195,-2.5809828,50.9014,5.965146277,8.024038072,2.485,5.871815813,2.449635847,53.36789296 +108.79,50.42635249,-2.580981671,50.8763,5.972098655,8.022927634,2.523125,5.974568402,2.519457515,53.3603679 +108.8,50.42635303,-2.580980542,50.8509,5.968622439,8.022705447,2.5596875,6.077117477,2.587082234,53.35284279 +108.81,50.42635356,-2.580979413,50.8251,5.9686224,8.022483261,2.5953125,6.179441608,2.652450989,53.34531774 +108.82,50.4263541,-2.580978284,50.799,5.972098565,8.021594884,2.63125,6.281519368,2.715506713,53.33779262 +108.83,50.42635464,-2.580977155,50.7725,5.968622359,8.02026238,2.6665625,6.383329556,2.776194517,53.33026757 +108.84,50.42635517,-2.580976027,50.7456,5.972098524,8.019374002,2.699375,6.48485086,2.834461403,53.32274245 +108.85,50.42635571,-2.580974898,50.7185,5.986003253,8.019151814,2.7296875,6.586062021,2.890256606,53.3152174 +108.86,50.42635625,-2.58097377,50.691,5.986003228,8.018929626,2.75875,6.686942012,2.943531482,53.30769228 +108.87,50.42635679,-2.580972641,50.6633,5.972098449,8.018041246,2.7878125,6.787469634,2.994239565,53.30016723 +108.88,50.42635732,-2.580971513,50.6353,5.972098425,8.01670874,2.8165625,6.887624032,3.042336564,53.29264212 +108.89,50.42635786,-2.580970385,50.6069,5.986003159,8.015820361,2.843125,6.987384178,3.087780654,53.28511706 +108.9,50.4263584,-2.580969257,50.5784,5.986003135,8.015598171,2.868125,7.08672933,3.13053213,53.27759195 +108.91,50.42635894,-2.580968129,50.5496,5.972098347,8.015375981,2.8934375,7.185638633,3.170553747,53.27006689 +108.92,50.42635947,-2.580967001,50.5205,5.972098318,8.014487601,2.9178125,7.284091575,3.207810614,53.26254178 +108.93,50.42636001,-2.580965873,50.4912,5.986003055,8.013155093,2.939375,7.382067473,3.242270187,53.25501672 +108.94,50.42636055,-2.580964746,50.4617,5.986003026,8.012044648,2.9584375,7.479545871,3.273902499,53.24749167 +108.95,50.42636109,-2.580963618,50.432,5.972098228,8.010934203,2.9765625,7.576506487,3.302679877,53.23996655 +108.96,50.42636162,-2.580962491,50.4022,5.972098201,8.009823759,2.9946875,7.672929039,3.328577283,53.2324415 +108.97,50.42636216,-2.580961364,50.3721,5.989479138,8.009823631,3.0115625,7.768793358,3.351572085,53.22491638 +108.98,50.4263627,-2.580960237,50.3419,6.003383887,8.010711756,3.02625,7.864079448,3.371644286,53.21739133 +108.99,50.42636324,-2.580959109,50.3116,6.003383861,8.010489564,3.0403125,7.958767427,3.388776412,53.20986622 +109,50.42636378,-2.580957982,50.2811,5.989479054,8.008268801,3.0546875,8.052837528,3.40295345,53.20234116 +109.01,50.42636432,-2.580956855,50.2505,5.972098061,8.00538185,3.0678125,8.146270043,3.414163026,53.19481605 +109.02,50.42636485,-2.580955729,50.2197,5.972098044,8.003827278,3.0778125,8.239045546,3.422395398,53.18729099 +109.03,50.42636539,-2.580954603,50.1889,5.989478978,8.004049211,3.0846875,8.331144558,3.427643462,53.17976588 +109.04,50.42636593,-2.580953476,50.158,6.003383708,8.004715271,3.0903125,8.422547942,3.42990252,53.17224082 +109.05,50.42636647,-2.58095235,50.1271,6.006859872,8.004715141,3.0965625,8.513236562,3.429170624,53.16471571 +109.06,50.42636701,-2.580951223,50.0961,6.006859846,8.003826758,3.103125,8.603191508,3.425448518,53.15719065 +109.07,50.42636755,-2.580950097,50.065,6.006859813,8.002494249,3.1078125,8.692393932,3.418739297,53.14966554 +109.08,50.42636809,-2.580948971,50.0339,6.006859788,8.001605866,3.1096875,8.78082527,3.409048919,53.14214048 +109.09,50.42636863,-2.580947845,50.0028,6.006859766,8.00116161,3.1096875,8.868467014,3.396385807,53.13461537 +109.1,50.42636917,-2.580946719,49.9717,6.006859729,8.000051163,3.108125,8.955300888,3.380760961,53.12709031 +109.11,50.42636971,-2.580945593,49.9406,6.006859691,7.998052464,3.105,9.041308728,3.362188076,53.1195652 +109.12,50.42637025,-2.580944468,49.9096,6.006859669,7.996719955,3.1015625,9.126472659,3.340683309,53.11204015 +109.13,50.42637079,-2.580943343,49.8786,6.006859645,7.996719825,3.0984375,9.210774747,3.316265394,53.10451503 +109.14,50.42637133,-2.580942217,49.8476,6.006859612,7.996497632,3.094375,9.294197517,3.288955647,53.09698998 +109.15,50.42637187,-2.580941092,49.8167,6.006859588,7.995387187,3.0878125,9.376723493,3.258777903,53.08946486 +109.16,50.42637241,-2.580939967,49.7858,6.006859568,7.994498804,3.078125,9.458335429,3.22575846,53.08193981 +109.17,50.42637295,-2.580938842,49.7551,6.006859537,7.994054549,3.0665625,9.539016309,3.189926081,53.0744147 +109.18,50.42637349,-2.580937717,49.7245,6.006859502,7.993166166,3.055,9.618749288,3.151312048,53.06688964 +109.19,50.42637403,-2.580936592,49.694,6.006859472,7.992055721,3.043125,9.697517692,3.109950053,53.05936453 +109.2,50.42637457,-2.580935468,49.6636,6.006859444,7.991833528,3.0296875,9.775305078,3.065876077,53.05183947 +109.21,50.42637511,-2.580934343,49.6334,6.006859416,7.9918334,3.0146875,9.852095231,3.01912868,53.04431436 +109.22,50.42637565,-2.580933218,49.6033,6.00685939,7.990500893,2.9984375,9.927872051,2.969748484,53.0367893 +109.23,50.42637619,-2.580932094,49.5734,6.006859369,7.988502196,2.98125,10.00261972,2.917778691,53.02926419 +109.24,50.42637673,-2.58093097,49.5437,6.006859344,7.987613814,2.963125,10.07632272,2.863264507,53.02173913 +109.25,50.42637727,-2.580929846,49.5141,6.006859308,7.988057812,2.943125,10.14896558,2.806253545,53.01421402 +109.26,50.42637781,-2.580928722,49.4848,6.006859277,7.988279748,2.92125,10.22053311,2.74679548,53.00668896 +109.27,50.42637835,-2.580927597,49.4557,6.006859254,7.987169305,2.898125,10.29101041,2.684942165,52.99916391 +109.28,50.42637889,-2.580926474,49.4268,6.010335415,7.9858368,2.873125,10.36038276,2.620747515,52.99163879 +109.29,50.42637943,-2.58092535,49.3982,6.024240148,7.98494842,2.8465625,10.42863567,2.554267566,52.98411374 +109.3,50.42637997,-2.580924226,49.3699,6.041621084,7.983615914,2.82,10.49575487,2.485560243,52.97658863 +109.31,50.42638052,-2.580923103,49.3418,6.041621065,7.982505472,2.793125,10.56172632,2.414685479,52.96906357 +109.32,50.42638106,-2.58092198,49.314,6.024240084,7.982505345,2.7646875,10.62653633,2.341705094,52.96153846 +109.33,50.4263816,-2.580920856,49.2865,6.010335297,7.982283157,2.735,10.69017125,2.266682688,52.9540134 +109.34,50.42638214,-2.580919733,49.2593,6.010335274,7.980950653,2.7046875,10.75261792,2.189683692,52.94648829 +109.35,50.42638268,-2.58091861,49.2324,6.024240008,7.979174024,2.6728125,10.81386322,2.110775257,52.93896323 +109.36,50.42638322,-2.580917487,49.2058,6.041620939,7.977841521,2.638125,10.8738943,2.030026195,52.93143812 +109.37,50.42638377,-2.580916365,49.1796,6.041620919,7.977619333,2.601875,10.93269873,1.947506922,52.92391306 +109.38,50.42638431,-2.580915242,49.1538,6.024239931,7.977841273,2.5665625,10.9902642,1.863289403,52.91638795 +109.39,50.42638485,-2.580914119,49.1283,6.013811323,7.977397024,2.53125,11.04657868,1.77744709,52.90886289 +109.4,50.42638539,-2.580912997,49.1031,6.024239878,7.976508649,2.493125,11.10163041,1.690054754,52.90133778 +109.41,50.42638593,-2.580911874,49.0784,6.041620821,7.975398211,2.453125,11.15540794,1.601188714,52.89381273 +109.42,50.42638648,-2.580910752,49.0541,6.041620801,7.974065711,2.4134375,11.20789993,1.510926432,52.88628761 +109.43,50.42638702,-2.58090963,49.0301,6.027716011,7.973177337,2.3728125,11.25909548,1.419346577,52.87876256 +109.44,50.42638756,-2.580908508,49.0066,6.027715989,7.972955154,2.3296875,11.30898389,1.326529019,52.87123744 +109.45,50.4263881,-2.580907386,48.9835,6.041620733,7.97273297,2.2853125,11.35755479,1.232554716,52.86371239 +109.46,50.42638865,-2.580906264,48.9609,6.045096897,7.971844598,2.2415625,11.40479796,1.137505601,52.85618728 +109.47,50.42638919,-2.580905142,48.9387,6.041620683,7.970512101,2.198125,11.45070363,1.041464582,52.84866222 +109.48,50.42638973,-2.580904021,48.9169,6.045096863,7.969623731,2.1528125,11.4952621,0.944515368,52.84113711 +109.49,50.42639028,-2.580902899,48.8956,6.045096848,7.969179487,2.1046875,11.53846409,0.846742526,52.83361205 +109.5,50.42639082,-2.580901778,48.8748,6.041620633,7.968291117,2.0553125,11.58030067,0.748231314,52.82608694 +109.51,50.42639136,-2.580900656,48.8545,6.045096808,7.966958621,2.0065625,11.620763,0.649067618,52.81856188 +109.52,50.42639191,-2.580899536,48.8347,6.045096792,7.965848189,1.958125,11.65984268,0.549337954,52.81103677 +109.53,50.42639245,-2.580898414,48.8153,6.041620578,7.964959822,1.908125,11.69753156,0.44912924,52.80351171 +109.54,50.42639299,-2.580897294,48.7965,6.045096757,7.964293518,1.85625,11.73382173,0.348528909,52.7959866 +109.55,50.42639354,-2.580896173,48.7782,6.045096747,7.963849278,1.8034375,11.76870558,0.247624624,52.78846154 +109.56,50.42639408,-2.580895052,48.7604,6.04162053,7.963182976,1.75,11.80217594,0.146504449,52.78093643 +109.57,50.42639462,-2.580893932,48.7432,6.048572887,7.96229461,1.6965625,11.83422571,0.045256447,52.77341137 +109.58,50.42639517,-2.580892811,48.7265,6.059001446,7.961406246,1.643125,11.86484824,-0.056030975,52.76588626 +109.59,50.42639571,-2.580891691,48.7103,6.059001434,7.960962009,1.588125,11.89403717,-0.157269524,52.75836121 +109.6,50.42639626,-2.580890571,48.6947,6.048572849,7.961183961,1.5315625,11.92178638,-0.258370963,52.75083609 +109.61,50.4263968,-2.58088945,48.6797,6.041620459,7.960739724,1.475,11.94809001,-0.359247059,52.74331104 +109.62,50.42639734,-2.58088833,48.6652,6.048572827,7.958741047,1.4184375,11.97294263,-0.459809918,52.73578598 +109.63,50.42639789,-2.58088721,48.6513,6.059001387,7.956742371,1.36125,11.99633907,-0.559971821,52.72826087 +109.64,50.42639843,-2.580886091,48.638,6.062477571,7.956298138,1.303125,12.01827436,-0.659645393,52.72073581 +109.65,50.42639898,-2.580884971,48.6252,6.062477555,7.956520094,1.2434375,12.03874402,-0.758743772,52.7132107 +109.66,50.42639952,-2.580883851,48.6131,6.062477535,7.956075861,1.183125,12.0577437,-0.857180499,52.70568564 +109.67,50.42640007,-2.580882732,48.6016,6.062477527,7.955187503,1.12375,12.07526951,-0.954869746,52.69816053 +109.68,50.42640061,-2.580881612,48.5906,6.062477523,7.954077083,1.0646875,12.09131771,-1.051726313,52.69063547 +109.69,50.42640116,-2.580880493,48.5803,6.062477514,7.9527446,1.0046875,12.10588499,-1.147665804,52.68311036 +109.7,50.4264017,-2.580879374,48.5705,6.062477499,7.951856244,0.9434375,12.11896826,-1.24260451,52.67558531 +109.71,50.42640225,-2.580878255,48.5614,6.062477489,7.951634078,0.88125,12.13056486,-1.336459638,52.66806019 +109.72,50.42640279,-2.580877136,48.5529,6.06247749,7.951411914,0.8184375,12.14067235,-1.429149369,52.66053514 +109.73,50.42640334,-2.580876017,48.545,6.062477487,7.950301498,0.755,12.14928855,-1.520592803,52.65301002 +109.74,50.42640388,-2.580874898,48.5378,6.062477477,7.94830283,0.691875,12.15641173,-1.610710298,52.64548497 +109.75,50.42640443,-2.58087378,48.5312,6.065953665,7.946970351,0.63,12.16204041,-1.699423244,52.63795985 +109.76,50.42640497,-2.580872662,48.5252,6.076382237,7.946970253,0.568125,12.16617339,-1.786654235,52.6304348 +109.77,50.42640552,-2.580871543,48.5198,6.083334609,7.946748092,0.5046875,12.16880974,-1.872327239,52.62290969 +109.78,50.42640607,-2.580870425,48.5151,6.076382217,7.94563768,0.44,12.16994907,-1.9563676,52.61538463 +109.79,50.42640661,-2.580869307,48.511,6.065953637,7.944749331,0.3753125,12.16959097,-2.038701922,52.60785952 +109.8,50.42640716,-2.580868189,48.5076,6.065953632,7.944305109,0.3115625,12.16773562,-2.11925847,52.60033446 +109.81,50.4264077,-2.580867071,48.5048,6.076382209,7.943416762,0.2484375,12.16438341,-2.197967,52.59280935 +109.82,50.42640825,-2.580865953,48.5026,6.083334597,7.942306353,0.1846875,12.15953499,-2.274758872,52.58528429 +109.83,50.4264088,-2.580864836,48.5011,6.076382213,7.942084197,0.12,12.15319137,-2.349567106,52.57775918 +109.84,50.42640934,-2.580863718,48.5002,6.065953632,7.942084104,0.055,12.14535394,-2.422326501,52.57023412 +109.85,50.42640989,-2.5808626,48.5,6.06595363,7.940751634,-0.01,12.13602423,-2.492973629,52.56270901 +109.86,50.42641043,-2.580861483,48.5004,6.079858406,7.938752977,-0.075,12.12520433,-2.561446784,52.55518395 +109.87,50.42641098,-2.580860366,48.5015,6.09723937,7.937642572,-0.1396875,12.11289639,-2.627686378,52.54765884 +109.88,50.42641153,-2.580859249,48.5032,6.097239365,7.937420419,-0.2034375,12.09910301,-2.691634541,52.54013379 +109.89,50.42641208,-2.580858132,48.5056,6.083334597,7.937420331,-0.266875,12.08382703,-2.753235583,52.53260867 +109.9,50.42641262,-2.580857015,48.5085,6.079858407,7.93719818,-0.3315625,12.06707174,-2.812435759,52.52508362 +109.91,50.42641317,-2.580855898,48.5122,6.0833346,7.936087777,-0.3965625,12.04884057,-2.869183447,52.5175585 +109.92,50.42641372,-2.580854781,48.5165,6.079858418,7.934089125,-0.4596875,12.02913735,-2.923429143,52.51003345 +109.93,50.42641426,-2.580853665,48.5214,6.083334621,7.932756662,-0.521875,12.00796616,-2.975125578,52.50250833 +109.94,50.42641481,-2.580852549,48.5269,6.097239396,7.932756578,-0.5853125,11.98533146,-3.02422766,52.49498328 +109.95,50.42641536,-2.580851432,48.5331,6.097239402,7.93253443,-0.6496875,11.96123796,-3.070692589,52.48745817 +109.96,50.42641591,-2.580850316,48.5399,6.083334641,7.931424032,-0.713125,11.93569069,-3.1144798,52.47993311 +109.97,50.42641645,-2.5808492,48.5474,6.08333464,7.930535698,-0.775,11.90869498,-3.155551134,52.47240805 +109.98,50.426417,-2.580848084,48.5554,6.097239406,7.93009149,-0.8365625,11.88025651,-3.193870838,52.46488294 +109.99,50.42641755,-2.580846968,48.5641,6.097239421,7.929203158,-0.89875,11.85038117,-3.229405394,52.45735789 +110,50.4264181,-2.580845852,48.5734,6.083334677,7.927870699,-0.96125,11.81907521,-3.262123862,52.44983277 +110.01,50.42641864,-2.580844737,48.5833,6.083334685,7.926982368,-1.023125,11.78634517,-3.29199771,52.44230772 +110.02,50.42641919,-2.580843621,48.5939,6.100715645,7.926760227,-1.083125,11.75219792,-3.319000867,52.4347826 +110.03,50.42641974,-2.580842506,48.605,6.114620425,7.926538087,-1.141875,11.71664056,-3.343109842,52.42725755 +110.04,50.42642029,-2.58084139,48.6167,6.114620441,7.925649758,-1.201875,11.67968048,-3.364303551,52.41973243 +110.05,50.42642084,-2.580840275,48.629,6.100715683,7.924317303,-1.2628125,11.64132543,-3.382563544,52.41220738 +110.06,50.42642139,-2.58083916,48.642,6.083334735,7.923206913,-1.3215625,11.60158347,-3.397873893,52.40468227 +110.07,50.42642193,-2.580838045,48.6555,6.083334757,7.922096524,-1.378125,11.5604628,-3.410221305,52.39715721 +110.08,50.42642248,-2.58083693,48.6695,6.100715732,7.920986135,-1.4353125,11.51797208,-3.419594895,52.3896321 +110.09,50.42642303,-2.580835816,48.6842,6.1146205,7.920763998,-1.493125,11.47412019,-3.425986526,52.38210704 +110.1,50.42642358,-2.580834701,48.6994,6.1180967,7.920763926,-1.5496875,11.42891622,-3.429390697,52.37458193 +110.11,50.42642413,-2.580833586,48.7152,6.118096725,7.919653539,-1.605,11.3823697,-3.429804315,52.36705687 +110.12,50.42642468,-2.580832472,48.7315,6.118096748,7.918543152,-1.6596875,11.33449026,-3.427227151,52.35953176 +110.13,50.42642523,-2.580831358,48.7484,6.114620568,7.918321019,-1.7134375,11.28528796,-3.421661382,52.3520067 +110.14,50.42642578,-2.580830243,48.7658,6.100715816,7.917210634,-1.76625,11.23477308,-3.413111877,52.34448159 +110.15,50.42642633,-2.580829129,48.7837,6.083334884,7.914989935,-1.8184375,11.18295615,-3.401586087,52.33695653 +110.16,50.42642687,-2.580828016,48.8022,6.083334907,7.914101615,-1.87,11.12984795,-3.387094036,52.32943142 +110.17,50.42642742,-2.580826902,48.8211,6.100715878,7.914767736,-1.9215625,11.07545965,-3.369648445,52.32190637 +110.18,50.42642797,-2.580825788,48.8406,6.11462066,7.914545606,-1.973125,11.01980253,-3.34926444,52.31438125 +110.19,50.42642852,-2.580824674,48.8606,6.118096869,7.912769035,-2.023125,10.96288828,-3.32595984,52.3068562 +110.2,50.42642907,-2.580823561,48.8811,6.118096887,7.911436591,-2.0715625,10.90472871,-3.299754928,52.29933108 +110.21,50.42642962,-2.580822448,48.902,6.118096912,7.911436525,-2.1196875,10.84533608,-3.270672564,52.29180603 +110.22,50.42643017,-2.580821334,48.9235,6.118096938,7.911214397,-2.1665625,10.7847227,-3.238738189,52.28428091 +110.23,50.42643072,-2.580820221,48.9454,6.118096953,7.910104018,-2.21125,10.72290124,-3.203979532,52.27675586 +110.24,50.42643127,-2.580819108,48.9677,6.118096966,7.909215703,-2.255,10.65988465,-3.166426961,52.26923075 +110.25,50.42643182,-2.580817995,48.9905,6.118096995,7.908771514,-2.2984375,10.59568605,-3.12611325,52.26170569 +110.26,50.42643237,-2.580816882,49.0137,6.118097031,7.907883199,-2.3415625,10.53031884,-3.08307352,52.25418058 +110.27,50.42643292,-2.580815769,49.0373,6.11809705,7.906550759,-2.3846875,10.46379672,-3.037345242,52.24665552 +110.28,50.42643347,-2.580814657,49.0614,6.12157325,7.905440382,-2.4265625,10.39613355,-2.98896841,52.23913041 +110.29,50.42643402,-2.580813544,49.0859,6.135478039,7.904330006,-2.46625,10.32734344,-2.937985136,52.23160535 +110.3,50.42643457,-2.580812432,49.1107,6.152859032,7.903219631,-2.5046875,10.25744081,-2.884439938,52.22408024 +110.31,50.42643513,-2.58081132,49.136,6.152859059,7.902997506,-2.5415625,10.18644028,-2.828379399,52.21655518 +110.32,50.42643568,-2.580810208,49.1616,6.135478123,7.902997445,-2.5765625,10.11435658,-2.769852505,52.20903013 +110.33,50.42643623,-2.580809095,49.1875,6.121573385,7.901887071,-2.611875,10.04120476,-2.70891025,52.20150501 +110.34,50.42643678,-2.580807984,49.2138,6.118097223,7.900554635,-2.648125,9.967000255,-2.645605805,52.19397996 +110.35,50.42643733,-2.580806872,49.2405,6.118097243,7.899888388,-2.6828125,9.891758349,-2.579994345,52.18645485 +110.36,50.42643788,-2.58080576,49.2675,6.11809726,7.899222141,-2.7146875,9.815494916,-2.512133052,52.17892979 +110.37,50.42643843,-2.580804649,49.2948,6.121573486,7.898333832,-2.7446875,9.738225828,-2.442081169,52.17140468 +110.38,50.42643898,-2.580803537,49.3224,6.135478294,7.89722346,-2.7734375,9.659967242,-2.369899774,52.16387962 +110.39,50.42643953,-2.580802426,49.3503,6.152859278,7.895891025,-2.8015625,9.580735486,-2.295651778,52.15635451 +110.4,50.42644009,-2.580801315,49.3784,6.15285929,7.895002716,-2.8296875,9.500547064,-2.219401924,52.14882945 +110.41,50.42644064,-2.580800204,49.4069,6.135478355,7.894780596,-2.8565625,9.419418761,-2.141216734,52.14130434 +110.42,50.42644119,-2.580799093,49.4356,6.125049816,7.89478054,-2.88125,9.337367538,-2.061164388,52.13377928 +110.43,50.42644174,-2.580797982,49.4645,6.135478421,7.894780484,-2.9046875,9.254410525,-1.979314674,52.12625417 +110.44,50.42644229,-2.580796871,49.4937,6.152859401,7.894558365,-2.9265625,9.17056497,-1.895738925,52.11872911 +110.45,50.42644285,-2.58079576,49.5231,6.152859432,7.893447995,-2.9465625,9.085848519,-1.810510078,52.111204 +110.46,50.4264434,-2.580794649,49.5526,6.135478516,7.891449374,-2.9665625,9.000278762,-1.723702503,52.10367895 +110.47,50.42644395,-2.580793539,49.5824,6.125049973,7.890116941,-2.9865625,8.913873576,-1.635391773,52.09615383 +110.48,50.4264445,-2.580792429,49.6124,6.135478566,7.889894824,-3.004375,8.826651064,-1.545654951,52.08862878 +110.49,50.42644505,-2.580791318,49.6425,6.15285955,7.888784455,-3.02,8.738629392,-1.454570304,52.08110366 +110.5,50.42644561,-2.580790208,49.6728,6.156335779,7.886563772,-3.0346875,8.64982695,-1.362217242,52.07357861 +110.51,50.42644616,-2.580789099,49.7032,6.152859616,7.885675465,-3.048125,8.560262302,-1.268676324,52.06605349 +110.52,50.42644671,-2.580787989,49.7338,6.156335832,7.886563663,-3.0596875,8.469954126,-1.17402914,52.05852844 +110.53,50.42644727,-2.580786879,49.7644,6.152859677,7.887229798,-3.07,8.378921274,-1.078358137,52.05100333 +110.54,50.42644782,-2.580785769,49.7952,6.138954951,7.886341493,-3.0796875,8.287182824,-0.981746795,52.04347827 +110.55,50.42644837,-2.580784659,49.826,6.138954977,7.88412081,-3.088125,8.194757857,-0.884279341,52.03595316 +110.56,50.42644892,-2.58078355,49.857,6.152859761,7.882122189,-3.095,8.101665737,-0.786040799,52.0284281 +110.57,50.42644948,-2.580782441,49.8879,6.156335982,7.88167801,-3.10125,8.007925831,-0.687116828,52.02090299 +110.58,50.42645003,-2.580781332,49.919,6.152859829,7.881677957,-3.1065625,7.913557791,-0.587593658,52.01337793 +110.59,50.42645058,-2.580780222,49.9501,6.156336056,7.88056759,-3.1090625,7.81858127,-0.487558092,52.00585282 +110.6,50.42645114,-2.580779114,49.9812,6.156336091,7.879235158,-3.1084375,7.723016093,-0.387097391,51.99832776 +110.61,50.42645169,-2.580778005,50.0123,6.152859936,7.878568916,-3.106875,7.626882312,-0.286299161,51.99080265 +110.62,50.42645224,-2.580776896,50.0433,6.159812345,7.878124737,-3.1065625,7.530199924,-0.185251235,51.98327759 +110.63,50.4264528,-2.580775788,50.0744,6.170240935,7.878124683,-3.10625,7.432989097,-0.084041736,51.97575248 +110.64,50.42645335,-2.580774679,50.1055,6.170240957,7.87812463,-3.1028125,7.335270228,0.017240988,51.96822743 +110.65,50.42645391,-2.58077357,50.1365,6.159812417,7.876792198,-3.0965625,7.237063658,0.1185087,51.96070237 +110.66,50.42645446,-2.580772462,50.1674,6.152860073,7.874793579,-3.09,7.138389897,0.21967305,51.95317726 +110.67,50.42645501,-2.580771354,50.1983,6.159812489,7.873683211,-3.0828125,7.039269517,0.320645861,51.9456522 +110.68,50.42645557,-2.580770246,50.2291,6.170241088,7.873461094,-3.073125,6.939723314,0.421339068,51.93812709 +110.69,50.42645612,-2.580769138,50.2598,6.173717311,7.873238977,-3.0615625,6.839772029,0.521664894,51.93060203 +110.7,50.42645668,-2.58076803,50.2903,6.173717352,7.872350671,-3.0496875,6.739436463,0.621535793,51.92307692 +110.71,50.42645723,-2.580766922,50.3208,6.173717389,7.871018239,-3.0365625,6.638737698,0.720864673,51.91555186 +110.72,50.42645779,-2.580765815,50.3511,6.173717414,7.86990787,-3.0215625,6.537696705,0.819564961,51.90802675 +110.73,50.42645834,-2.580764707,50.3812,6.170241247,7.868797502,-3.0065625,6.43633457,0.917550599,51.90050169 +110.74,50.4264589,-2.5807636,50.4112,6.159812701,7.86746507,-2.99125,6.334672491,1.014736101,51.89297658 +110.75,50.42645945,-2.580762493,50.4411,6.156336535,7.866576763,-2.9728125,6.232731668,1.111036727,51.88545153 +110.76,50.42646,-2.580761386,50.4707,6.173717519,7.866354644,-2.9515625,6.130533358,1.206368539,51.87792641 +110.77,50.42646056,-2.580760279,50.5001,6.191098511,7.866354588,-2.9303125,6.028099047,1.300648401,51.87040136 +110.78,50.42646112,-2.580759172,50.5293,6.187622356,7.86613247,-2.9096875,5.925449933,1.393794035,51.86287624 +110.79,50.42646167,-2.580758065,50.5583,6.177193807,7.865244163,-2.8878125,5.822607619,1.485724253,51.85535119 +110.8,50.42646223,-2.580756958,50.5871,6.173717632,7.863911729,-2.8628125,5.719593474,1.5763589,51.84782607 +110.81,50.42646278,-2.580755852,50.6156,6.173717653,7.86302342,-2.835,5.6164291,1.665618964,51.84030102 +110.82,50.42646334,-2.580754745,50.6438,6.173717688,7.862579236,-2.806875,5.513135982,1.753426579,51.83277591 +110.83,50.42646389,-2.580753639,50.6717,6.173717727,7.861690928,-2.7796875,5.409735664,1.8397052,51.82525085 +110.84,50.42646445,-2.580752532,50.6994,6.177193947,7.860580556,-2.75125,5.306249803,1.924379538,51.81772574 +110.85,50.426465,-2.580751427,50.7268,6.187622546,7.860136372,-2.7196875,5.202699943,2.007375798,51.81020068 +110.86,50.42646556,-2.58075032,50.7538,6.194574965,7.859470124,-2.686875,5.099107799,2.088621557,51.80267557 +110.87,50.42646612,-2.580749214,50.7805,6.187622619,7.857693562,-2.6546875,4.99549497,2.168046055,51.79515051 +110.88,50.42646667,-2.580748109,50.8069,6.177194062,7.856139063,-2.6215625,4.891883059,2.245579965,51.7876254 +110.89,50.42646723,-2.580747003,50.833,6.177194073,7.855694878,-2.58625,4.788293722,2.321155733,51.78010034 +110.9,50.42646778,-2.580745898,50.8586,6.187622675,7.855472755,-2.5496875,4.684748617,2.394707414,51.77257523 +110.91,50.42646834,-2.580744792,50.884,6.194575094,7.854584442,-2.511875,4.581269288,2.466170836,51.76505017 +110.92,50.4264689,-2.580743687,50.9089,6.191098926,7.853474066,-2.4728125,4.47787745,2.535483717,51.75752506 +110.93,50.42646945,-2.580742582,50.9334,6.191098942,7.853251942,-2.4334375,4.374594645,2.60258567,51.75000001 +110.94,50.42647001,-2.580741477,50.9576,6.194575159,7.853251879,-2.393125,4.271442475,2.667418079,51.74247489 +110.95,50.42647057,-2.580740371,50.9813,6.191098998,7.852141503,-2.35125,4.168442425,2.729924451,51.73494984 +110.96,50.42647112,-2.580739267,51.0046,6.191099022,7.850809062,-2.3084375,4.065616039,2.790050356,51.72742472 +110.97,50.42647168,-2.580738162,51.0275,6.194575226,7.849920746,-2.265,3.962984802,2.847743252,51.71989967 +110.98,50.42647224,-2.580737057,51.0499,6.191099049,7.848588305,-2.22125,3.860570143,2.902952835,51.71237455 +110.99,50.42647279,-2.580735953,51.0719,6.194575271,7.847477926,-2.1765625,3.758393434,2.955631033,51.7048495 +111,50.42647335,-2.580734849,51.0935,6.208480075,7.84747786,-2.1296875,3.656475987,3.005731895,51.69732444 +111.01,50.42647391,-2.580733744,51.1145,6.208480096,7.847255731,-2.0815625,3.554839119,3.053211704,51.68979933 +111.02,50.42647447,-2.58073264,51.1351,6.194575334,7.84614535,-2.033125,3.453504084,3.098029093,51.68227427 +111.03,50.42647502,-2.580731536,51.1552,6.194575347,7.845034968,-1.983125,3.352491969,3.140144929,51.67474916 +111.04,50.42647558,-2.580730432,51.1748,6.208480146,7.843924587,-1.931875,3.251823972,3.179522485,51.66722411 +111.05,50.42647614,-2.580729328,51.1938,6.208480176,7.842814204,-1.8815625,3.151521006,3.216127498,51.65969899 +111.06,50.4264767,-2.580728225,51.2124,6.194575422,7.842592072,-1.8315625,3.051604099,3.249927997,51.65217394 +111.07,50.42647725,-2.580727121,51.2305,6.194575432,7.842592002,-1.779375,2.952094107,3.280894475,51.64464882 +111.08,50.42647781,-2.580726017,51.248,6.211956415,7.841259554,-1.725,2.853011771,3.308999946,51.63712377 +111.09,50.42647837,-2.580724914,51.265,6.22238502,7.839260918,-1.67,2.754377831,3.334220001,51.62959865 +111.1,50.42647893,-2.580723811,51.2814,6.211956457,7.838150532,-1.615,2.6562128,3.356532524,51.6220736 +111.11,50.42647949,-2.580722708,51.2973,6.194575499,7.837928396,-1.56,2.558537305,3.375918093,51.61454849 +111.12,50.42648004,-2.580721605,51.3126,6.194575514,7.837928323,-1.5046875,2.461371627,3.392359804,51.60702343 +111.13,50.4264806,-2.580720502,51.3274,6.211956504,7.837706186,-1.4484375,2.364736164,3.405843335,51.59949832 +111.14,50.42648116,-2.580719399,51.3416,6.225861291,7.836817861,-1.39125,2.268651027,3.416356938,51.59197326 +111.15,50.42648172,-2.580718296,51.3552,6.229337487,7.835485408,-1.3334375,2.17313627,3.423891391,51.58444815 +111.16,50.42648228,-2.580717194,51.3683,6.225861301,7.83459708,-1.2746875,2.078211888,3.42844016,51.57692309 +111.17,50.42648284,-2.580716091,51.3807,6.211956547,7.834152878,-1.215,1.983897649,3.42999935,51.56939798 +111.18,50.4264834,-2.580714989,51.3926,6.194575605,7.83326455,-1.155,1.89021332,3.428567471,51.56187292 +111.19,50.42648395,-2.580713886,51.4038,6.194575616,7.832154158,-1.095,1.797178439,3.424145841,51.55434781 +111.2,50.42648451,-2.580712785,51.4145,6.211956582,7.831709954,-1.035,1.704812371,3.416738299,51.54682275 +111.21,50.42648507,-2.580711682,51.4245,6.225861359,7.831043685,-0.9746875,1.61313454,3.406351319,51.53929764 +111.22,50.42648563,-2.58071058,51.434,6.229337568,7.829267102,-0.9134375,1.522163968,3.392993897,51.53177259 +111.23,50.42648619,-2.580709479,51.4428,6.229337588,7.82771258,-0.85125,1.431919678,3.376677778,51.52424747 +111.24,50.42648675,-2.580708377,51.451,6.229337597,7.827268373,-0.7884375,1.342420576,3.357417171,51.51672242 +111.25,50.42648731,-2.580707276,51.4586,6.229337596,7.827046228,-0.725,1.253685285,3.335228808,51.5091973 +111.26,50.42648787,-2.580706174,51.4655,6.229337604,7.826157893,-0.661875,1.165732367,3.31013211,51.50167225 +111.27,50.42648843,-2.580705073,51.4718,6.229337619,7.824825432,-0.6,1.078580215,3.282148909,51.49414713 +111.28,50.42648899,-2.580703972,51.4775,6.229337625,7.823937095,-0.5378125,0.992246992,3.251303611,51.48662208 +111.29,50.42648955,-2.580702871,51.4826,6.22933762,7.823714945,-0.4734375,0.906750688,3.217623147,51.47909697 +111.3,50.42649011,-2.58070177,51.487,6.229337618,7.823492796,-0.4084375,0.822109237,3.181136851,51.47157191 +111.31,50.42649067,-2.580700669,51.4907,6.229337627,7.822604458,-0.345,0.738340344,3.141876579,51.4640468 +111.32,50.42649123,-2.580699568,51.4939,6.229337635,7.821271993,-0.2815625,0.655461369,3.099876538,51.45652174 +111.33,50.42649179,-2.580698468,51.4964,6.229337634,7.82016159,-0.2165625,0.573489729,3.05517334,51.44899663 +111.34,50.42649235,-2.580697367,51.4982,6.229337629,7.819273249,-0.151875,0.4924425,3.007806002,51.44147157 +111.35,50.42649291,-2.580696267,51.4994,6.229337631,7.818829033,-0.088125,0.412336583,2.957815836,51.43394652 +111.36,50.42649347,-2.580695167,51.5,6.229337641,7.818828942,-0.0234375,0.333188766,2.905246385,51.4264214 +111.37,50.42649403,-2.580694066,51.4999,6.229337653,7.817940598,0.041875,0.25501555,2.850143487,51.41889635 +111.38,50.42649459,-2.580692966,51.4991,6.229337653,7.816386066,0.10625,0.177833323,2.79255527,51.41137123 +111.39,50.42649515,-2.580691867,51.4978,6.232813834,7.815719784,0.17,0.101658068,2.732531867,51.40384618 +111.4,50.42649571,-2.580690766,51.4957,6.246718599,7.815275564,0.23375,0.026505772,2.670125705,51.39632107 +111.41,50.42649627,-2.580689667,51.4931,6.26409957,7.814165154,0.298125,-0.047607808,2.6053911,51.38879601 +111.42,50.42649684,-2.580688567,51.4898,6.264099578,7.813276807,0.3634375,-0.120667318,2.538384603,51.3812709 +111.43,50.4264974,-2.580687468,51.4858,6.246718609,7.812832584,0.4278125,-0.192657402,2.46916454,51.37374584 +111.44,50.42649796,-2.580686368,51.4812,6.232813823,7.811944235,0.49,-0.263563107,2.39779136,51.36622073 +111.45,50.42649852,-2.580685269,51.476,6.229337625,7.81061176,0.551875,-0.333369592,2.324327284,51.35869567 +111.46,50.42649908,-2.58068417,51.4702,6.23281382,7.809501347,0.6153125,-0.402062247,2.248836313,51.35117056 +111.47,50.42649964,-2.580683071,51.4637,6.246718581,7.808390934,0.68,-0.469626748,2.171384394,51.3436455 +111.48,50.4265002,-2.580681972,51.4566,6.264099525,7.807280519,0.744375,-0.536049,2.092038964,51.33612039 +111.49,50.42650077,-2.580680874,51.4488,6.264099516,7.807058354,0.8065625,-0.601315081,2.010869236,51.32859533 +111.5,50.42650133,-2.580679775,51.4404,6.246718555,7.807058251,0.866875,-0.665411411,1.927945971,51.32107022 +111.51,50.42650189,-2.580678676,51.4315,6.232813788,7.805947835,0.9284375,-0.72832464,1.843341534,51.31354516 +111.52,50.42650245,-2.580677578,51.4219,6.232813779,7.804615355,0.9915625,-0.790041534,1.75712972,51.30602005 +111.53,50.42650301,-2.58067648,51.4116,6.246718531,7.803949062,1.0528125,-0.850549258,1.669385588,51.298495 +111.54,50.42650357,-2.580675381,51.4008,6.26409948,7.803504831,1.1115625,-0.909835206,1.5801858,51.29096988 +111.55,50.42650414,-2.580674284,51.3894,6.264099477,7.803282662,1.1703125,-0.967886946,1.489607991,51.28344483 +111.56,50.4265047,-2.580673185,51.3774,6.250194704,7.802616367,1.23,-1.024692331,1.397731286,51.27591971 +111.57,50.42650526,-2.580672087,51.3648,6.25019469,7.800839758,1.29,-1.080239558,1.304635728,51.26839466 +111.58,50.42650582,-2.58067099,51.3516,6.264099432,7.799285211,1.3496875,-1.134517053,1.210402448,51.26086955 +111.59,50.42650639,-2.580669892,51.3378,6.264099408,7.798840977,1.408125,-1.187513358,1.115113723,51.25334449 +111.6,50.42650695,-2.580668795,51.3234,6.250194633,7.798618804,1.4646875,-1.239217527,1.018852631,51.24581938 +111.61,50.42650751,-2.580667697,51.3085,6.250194637,7.797730442,1.52,-1.289618676,0.921703053,51.23829432 +111.62,50.42650807,-2.5806666,51.293,6.264099397,7.796397955,1.575,-1.338706377,0.82374973,51.23076921 +111.63,50.42650864,-2.580665503,51.277,6.267575564,7.795509592,1.63,-1.386470259,0.72507809,51.22324415 +111.64,50.4265092,-2.580664406,51.2604,6.264099349,7.795287417,1.685,-1.432900467,0.625774191,51.21571904 +111.65,50.42650976,-2.580663309,51.2433,6.267575532,7.795065241,1.7396875,-1.477987203,0.525924606,51.20819398 +111.66,50.42651033,-2.580662212,51.2256,6.267575524,7.793954814,1.793125,-1.521721072,0.42561637,51.20066887 +111.67,50.42651089,-2.580661115,51.2074,6.264099307,7.791956135,1.845,-1.56409302,0.324937028,51.19314381 +111.68,50.42651145,-2.580660019,51.1887,6.267575467,7.790623644,1.8965625,-1.605094109,0.223974301,51.1856187 +111.69,50.42651202,-2.580658923,51.1695,6.267575447,7.790623529,1.948125,-1.644715859,0.122816311,51.17809365 +111.7,50.42651258,-2.580657826,51.1497,6.264099248,7.79040135,1.998125,-1.682949848,0.021551177,51.17056859 +111.71,50.42651314,-2.58065673,51.1295,6.271051628,7.789290919,2.04625,-1.719788284,-0.079732749,51.16304348 +111.72,50.42651371,-2.580655634,51.1088,6.281480187,7.78840255,2.0934375,-1.755223318,-0.180947119,51.15551842 +111.73,50.42651427,-2.580654538,51.0876,6.284956347,7.787958307,2.14,-1.789247614,-0.282003696,51.14799331 +111.74,50.42651484,-2.580653442,51.066,6.284956313,7.787069938,2.1865625,-1.821854127,-0.38281436,51.14046825 +111.75,50.4265154,-2.580652346,51.0439,6.281480101,7.785737443,2.233125,-1.853035922,-0.483291218,51.13294314 +111.76,50.42651597,-2.580651251,51.0213,6.271051516,7.784849072,2.278125,-1.882786584,-0.583346666,51.12541808 +111.77,50.42651653,-2.580650155,50.9983,6.264099115,7.784626889,2.32125,-1.911099809,-0.682893385,51.11789297 +111.78,50.42651709,-2.58064906,50.9749,6.271051469,7.784404705,2.3634375,-1.937969753,-0.781844628,51.11036791 +111.79,50.42651766,-2.580647964,50.951,6.281480016,7.783516332,2.4046875,-1.963390859,-0.880114109,51.1028428 +111.8,50.42651822,-2.580646869,50.9268,6.284956184,7.781961772,2.4446875,-1.987357684,-0.977616056,51.09531774 +111.81,50.42651879,-2.580645774,50.9021,6.284956162,7.78018515,2.4834375,-2.0098653,-1.074265556,51.08779263 +111.82,50.42651935,-2.580644679,50.8771,6.284956145,7.778852652,2.52125,-2.030909008,-1.169978271,51.08026758 +111.83,50.42651992,-2.580643585,50.8517,6.284956125,7.778852528,2.5584375,-2.050484398,-1.264670776,51.07274246 +111.84,50.42652048,-2.58064249,50.8259,6.284956096,7.779740654,2.5946875,-2.068587343,-1.358260453,51.06521741 +111.85,50.42652105,-2.580641395,50.7998,6.284956066,7.779518467,2.63,-2.085214177,-1.450665654,51.05769229 +111.86,50.42652161,-2.5806403,50.7733,6.284956047,7.777519779,2.6646875,-2.10036129,-1.541805935,51.05016724 +111.87,50.42652218,-2.580639206,50.7465,6.28495603,7.775521091,2.698125,-2.114025646,-1.631601657,51.04264213 +111.88,50.42652274,-2.580638112,50.7193,6.284955998,7.77507684,2.7296875,-2.126204265,-1.719974668,51.03511707 +111.89,50.42652331,-2.580637018,50.6919,6.284955956,7.775076714,2.7596875,-2.136894741,-1.806847789,51.02759196 +111.9,50.42652387,-2.580635923,50.6641,6.284955927,7.773966275,2.7884375,-2.146094724,-1.892145334,51.0200669 +111.91,50.42652444,-2.58063483,50.6361,6.288432106,7.772633773,2.81625,-2.153802325,-1.975792875,51.01254179 +111.92,50.426525,-2.580633736,50.6078,6.298860668,7.771967458,2.843125,-2.160015937,-2.057717531,51.00501673 +111.93,50.42652557,-2.580632642,50.5792,6.305813019,7.771301143,2.868125,-2.164734302,-2.137847799,50.99749162 +111.94,50.42652614,-2.580631549,50.5504,6.29886059,7.770412765,2.8915625,-2.167956387,-2.216113891,50.98996656 +111.95,50.4265267,-2.580630455,50.5214,6.28843198,7.769302324,2.915,-2.169681563,-2.292447454,50.98244145 +111.96,50.42652727,-2.580629362,50.4921,6.288431958,7.767969821,2.9378125,-2.169909429,-2.366781967,50.97491639 +111.97,50.42652783,-2.580628269,50.4626,6.298860519,7.767081443,2.958125,-2.168639926,-2.439052571,50.96739128 +111.98,50.4265284,-2.580627176,50.4329,6.305812886,7.766859252,2.9765625,-2.165873399,-2.509196357,50.95986622 +111.99,50.42652897,-2.580626083,50.4031,6.302336663,7.766859123,2.9946875,-2.161610307,-2.577152016,50.95234111 +112,50.42652953,-2.58062499,50.373,6.302336616,7.766636931,3.0115625,-2.155851623,-2.64286042,50.94481606 +112.01,50.4265301,-2.580623897,50.3428,6.305812768,7.765526488,3.02625,-2.14859855,-2.706264216,50.93729094 +112.02,50.42653067,-2.580622804,50.3125,6.302336555,7.763305734,3.04,-2.139852578,-2.767308056,50.92976589 +112.03,50.42653123,-2.580621712,50.282,6.302336536,7.761307042,3.053125,-2.129615541,-2.82593877,50.92224083 +112.04,50.4265318,-2.58062062,50.2514,6.305812697,7.761084849,3.0646875,-2.117889559,-2.88210525,50.91471572 +112.05,50.42653237,-2.580619528,50.2207,6.302336468,7.761750907,3.075,-2.104677152,-2.935758508,50.90719066 +112.06,50.42653293,-2.580618435,50.1899,6.302336436,7.761084589,3.0846875,-2.089980957,-2.986851732,50.89966555 +112.07,50.4265335,-2.580617343,50.159,6.305812599,7.759530022,3.0928125,-2.073804124,-3.035340349,50.89214049 +112.08,50.42653407,-2.580616252,50.128,6.302336379,7.758641642,3.098125,-2.056150034,-3.081182129,50.88461538 +112.09,50.42653463,-2.580615159,50.097,6.305812548,7.7575312,3.1015625,-2.037022353,-3.124337023,50.87709032 +112.1,50.4265352,-2.580614068,50.066,6.319717292,7.755976631,3.105,-2.016425093,-3.164767504,50.86956521 +112.11,50.42653577,-2.580612977,50.0349,6.319717257,7.755532375,3.108125,-1.994362494,-3.202438218,50.86204016 +112.12,50.42653634,-2.580611885,50.0038,6.305812449,7.75597637,3.1096875,-1.970839253,-3.237316394,50.85451504 +112.13,50.4265369,-2.580610794,49.9727,6.305812412,7.75597624,3.1096875,-1.945860242,-3.269371549,50.84698999 +112.14,50.42653747,-2.580609702,49.9416,6.323193348,7.75508786,3.108125,-1.919430673,-3.298575838,50.83946487 +112.15,50.42653804,-2.580608611,49.9105,6.333621911,7.753755354,3.1046875,-1.891556047,-3.32490365,50.83193982 +112.16,50.42653861,-2.58060752,49.8795,6.32319331,7.752644911,3.0996875,-1.862242265,-3.348332123,50.8244147 +112.17,50.42653918,-2.580606429,49.8485,6.305812307,7.751534468,3.0934375,-1.831495345,-3.368840746,50.81688965 +112.18,50.42653974,-2.580605338,49.8176,6.305812263,7.750201963,3.08625,-1.799321759,-3.386411758,50.80936454 +112.19,50.42654031,-2.580604248,49.7868,6.323193197,7.749313584,3.078125,-1.765728212,-3.401029745,50.80183948 +112.2,50.42654088,-2.580603157,49.756,6.33362176,7.748869329,3.068125,-1.730721752,-3.412681987,50.79431437 +112.21,50.42654145,-2.580602067,49.7254,6.32319316,7.747980949,3.05625,-1.694309653,-3.421358344,50.78678931 +112.22,50.42654202,-2.580600976,49.6949,6.305812158,7.746648445,3.0434375,-1.656499538,-3.427051196,50.7792642 +112.23,50.42654258,-2.580599887,49.6645,6.305812113,7.745538003,3.0296875,-1.617299313,-3.429755614,50.77173914 +112.24,50.42654315,-2.580598796,49.6343,6.32319304,7.744649625,3.015,-1.576717113,-3.429469192,50.76421403 +112.25,50.42654372,-2.580597707,49.6042,6.337097791,7.744205371,2.9996875,-1.534761477,-3.426192275,50.75668897 +112.26,50.42654429,-2.580596617,49.5743,6.340573966,7.744427303,2.9828125,-1.491441169,-3.419927669,50.74916386 +112.27,50.42654486,-2.580595527,49.5445,6.340573934,7.74398305,2.963125,-1.446765129,-3.410680818,50.7416388 +112.28,50.42654543,-2.580594437,49.515,6.340573897,7.742206422,2.9415625,-1.40074281,-3.3984598,50.73411369 +112.29,50.426546,-2.580593348,49.4857,6.337097667,7.740651856,2.92,-1.35338378,-3.383275272,50.72658864 +112.3,50.42654657,-2.580592259,49.4566,6.323192868,7.739985541,2.898125,-1.304697952,-3.36514047,50.71906352 +112.31,50.42654714,-2.580591169,49.4277,6.305811893,7.739541288,2.8746875,-1.254695409,-3.344071208,50.71153847 +112.32,50.4265477,-2.580590081,49.3991,6.305811883,7.739319099,2.8496875,-1.203386695,-3.320085934,50.70401335 +112.33,50.42654827,-2.580588991,49.3707,6.323192816,7.738652785,2.823125,-1.150782466,-3.293205447,50.6964883 +112.34,50.42654884,-2.580587902,49.3426,6.337097539,7.737098221,2.7946875,-1.096893722,-3.263453239,50.68896318 +112.35,50.42654941,-2.580586814,49.3148,6.340573691,7.736209845,2.765,-1.041731752,-3.230855206,50.68143813 +112.36,50.42654998,-2.580585725,49.2873,6.340573664,7.735987657,2.735,-0.985308015,-3.195439883,50.67391302 +112.37,50.42655055,-2.580584636,49.2601,6.34057364,7.734655157,2.7046875,-0.927634312,-3.157238093,50.66638796 +112.38,50.42655112,-2.580583548,49.2332,6.340573621,7.73265647,2.673125,-0.868722734,-3.116283128,50.6588629 +112.39,50.42655169,-2.58058246,49.2066,6.34057361,7.731546033,2.6396875,-0.808585542,-3.07261068,50.65133779 +112.4,50.42655226,-2.580581372,49.1804,6.340573591,7.731323847,2.6046875,-0.747235284,-3.02625891,50.64381274 +112.41,50.42655283,-2.580580284,49.1545,6.340573555,7.731323722,2.568125,-0.684684794,-2.977268211,50.63628762 +112.42,50.4265534,-2.580579196,49.129,6.340573517,7.731101535,2.53,-0.620947136,-2.925681269,50.62876257 +112.43,50.42655397,-2.580578108,49.1039,6.340573495,7.730213163,2.4915625,-0.556035601,-2.871543059,50.62123745 +112.44,50.42655454,-2.58057702,49.0792,6.340573484,7.728880666,2.4534375,-0.48996377,-2.814900853,50.6137124 +112.45,50.42655511,-2.580575933,49.0548,6.344049653,7.727992295,2.4146875,-0.42274545,-2.755803981,50.60618728 +112.46,50.42655568,-2.580574845,49.0309,6.357954384,7.727770111,2.374375,-0.354394622,-2.694304066,50.59866223 +112.47,50.42655625,-2.580573758,49.0073,6.375335314,7.727547927,2.331875,-0.284925609,-2.630454623,50.59113712 +112.48,50.42655683,-2.58057267,48.9842,6.37533529,7.726659556,2.2878125,-0.214352908,-2.564311401,50.58361206 +112.49,50.4265574,-2.580571583,48.9616,6.357954308,7.725327061,2.2434375,-0.142691243,-2.495932097,50.57608695 +112.5,50.42655797,-2.580570496,48.9393,6.34404953,7.724216629,2.198125,-0.069955626,-2.425376241,50.56856189 +112.51,50.42655854,-2.580569409,48.9176,6.340573328,7.723106199,2.1515625,0.003838817,-2.352705483,50.56103678 +112.52,50.42655911,-2.580568322,48.8963,6.340573305,7.721773707,2.105,0.078676616,-2.277983077,50.55351172 +112.53,50.42655968,-2.580567236,48.8755,6.340573279,7.720663277,2.058125,0.154542187,-2.201274284,50.54598661 +112.54,50.42656025,-2.580566149,48.8551,6.344049449,7.719774911,2.0096875,0.231419659,-2.122645911,50.53846155 +112.55,50.42656082,-2.580565063,48.8353,6.357954197,7.719108607,1.9596875,0.309292988,-2.042166597,50.53093644 +112.56,50.42656139,-2.580563977,48.8159,6.375335137,7.718664366,1.9084375,0.388145961,-1.959906417,50.52341138 +112.57,50.42656197,-2.58056289,48.7971,6.375335119,7.718220125,1.8565625,0.467962019,-1.875937217,50.51588627 +112.58,50.42656254,-2.580561805,48.7788,6.357954143,7.717997948,1.805,0.548724545,-1.790332166,50.50836122 +112.59,50.42656311,-2.580560718,48.761,6.347525548,7.717331646,1.753125,0.630416638,-1.703165919,50.5008361 +112.6,50.42656368,-2.580559632,48.7437,6.3579541,7.715555034,1.6996875,0.713021282,-1.614514509,50.49331105 +112.61,50.42656425,-2.580558547,48.727,6.375335038,7.713778422,1.645,0.796521171,-1.524455169,50.48578593 +112.62,50.42656483,-2.580557461,48.7108,6.375335029,7.712667998,1.59,0.880898947,-1.43306651,50.47826088 +112.63,50.4265654,-2.580556376,48.6952,6.361430263,7.712223762,1.5346875,0.966136961,-1.340428173,50.47073576 +112.64,50.42656597,-2.580555291,48.6801,6.361430259,7.712445714,1.478125,1.052217338,-1.246621001,50.46321071 +112.65,50.42656654,-2.580554205,48.6656,6.375335006,7.712223541,1.42,1.139122202,-1.151726757,50.4556856 +112.66,50.42656712,-2.58055312,48.6517,6.375334977,7.711113119,1.3615625,1.226833331,-1.055828176,50.44816054 +112.67,50.42656769,-2.580552035,48.6384,6.361430191,7.710002698,1.3034375,1.315332449,-0.959008851,50.44063543 +112.68,50.42656826,-2.58055095,48.6256,6.361430174,7.708892279,1.245,1.404601107,-0.861353294,50.43311037 +112.69,50.42656883,-2.580549865,48.6135,6.375334923,7.707559798,1.18625,1.494620569,-0.762946647,50.42558526 +112.7,50.42656941,-2.580548781,48.6019,6.375334921,7.706671441,1.126875,1.585372099,-0.663874681,50.4180602 +112.71,50.42656998,-2.580547696,48.5909,6.361430164,7.706449273,1.06625,1.676836732,-0.564223798,50.41053509 +112.72,50.42657055,-2.580546612,48.5806,6.361430156,7.706227106,1.005,1.768995332,-0.464080917,50.40301003 +112.73,50.42657112,-2.580545527,48.5708,6.375334901,7.705338752,0.9434375,1.861828704,-0.363533356,50.39548498 +112.74,50.4265717,-2.580544443,48.5617,6.378811077,7.704006275,0.8815625,1.955317483,-0.262668777,50.38795986 +112.75,50.42657227,-2.580543359,48.5532,6.375334878,7.702895859,0.82,2.049442073,-0.16157513,50.38043481 +112.76,50.42657284,-2.580542275,48.5453,6.378811069,7.701785445,0.7584375,2.144182822,-0.060340592,50.3729097 +112.77,50.42657342,-2.580541191,48.538,6.378811075,7.70045297,0.69625,2.239520019,0.040946543,50.36538464 +112.78,50.42657399,-2.580540108,48.5314,6.375334878,7.699564621,0.6334375,2.33543367,0.142197983,50.35785953 +112.79,50.42657456,-2.580539024,48.5253,6.382287242,7.699342459,0.57,2.431903777,0.243325435,50.35033447 +112.8,50.42657514,-2.580537941,48.52,6.392715806,7.699120297,0.50625,2.52891023,0.344240664,50.34280936 +112.81,50.42657571,-2.580536857,48.5152,6.3927158,7.698231948,0.4421875,2.626432746,0.444855777,50.3352843 +112.82,50.42657629,-2.580535774,48.5111,6.382287221,7.696899476,0.3778125,2.724450928,0.545082883,50.32775919 +112.83,50.42657686,-2.580534691,48.5077,6.375334846,7.69601113,0.31375,2.822944321,0.64483472,50.32023413 +112.84,50.42657743,-2.580533608,48.5048,6.382287238,7.695788972,0.25,2.921892413,0.744024257,50.31270902 +112.85,50.42657801,-2.580532525,48.5027,6.39271581,7.695566815,0.18625,3.021274407,0.842564976,50.30518396 +112.86,50.42657858,-2.580531442,48.5011,6.396191991,7.694456409,0.121875,3.121069732,0.940370992,50.29765885 +112.87,50.42657916,-2.580530359,48.5002,6.396191982,7.692457754,0.05625,3.221257361,1.03735699,50.2901338 +112.88,50.42657973,-2.580529277,48.5,6.392715787,7.691125287,-0.009375,3.321816496,1.133438346,50.28260868 +112.89,50.42658031,-2.580528195,48.5004,6.382287217,7.691125194,-0.0734375,3.422726109,1.228531349,50.27508363 +112.9,50.42658088,-2.580527112,48.5015,6.375334844,7.69090304,-0.1365625,3.523965116,1.322553093,50.26755851 +112.91,50.42658145,-2.58052603,48.5031,6.382287239,7.689792638,-0.2003125,3.625512317,1.41542153,50.26003346 +112.92,50.42658203,-2.580524948,48.5055,6.392715819,7.688682237,-0.265,3.727346627,1.507055701,50.25250834 +112.93,50.4265826,-2.580523866,48.5084,6.396192001,7.687571837,-0.3296875,3.829446675,1.59737568,50.24498329 +112.94,50.42658318,-2.580522784,48.5121,6.396191988,7.686239375,-0.3934375,3.931791203,1.68630274,50.23745818 +112.95,50.42658375,-2.580521703,48.5163,6.39619199,7.685128975,-0.4565625,4.034358842,1.773759304,50.22993312 +112.96,50.42658433,-2.580520621,48.5212,6.396192007,7.684240639,-0.5203125,4.137128104,1.859669112,50.22240801 +112.97,50.4265849,-2.58051954,48.5267,6.396192024,7.683796429,-0.5846875,4.240077562,1.943957277,50.21488295 +112.98,50.42658548,-2.580518459,48.5329,6.399668232,7.684018405,-0.6484375,4.343185729,2.026550289,50.20735784 +112.99,50.42658605,-2.580517377,48.5397,6.410096816,7.683796258,-0.71125,4.446431062,2.107376127,50.19983278 +113,50.42658663,-2.580516296,48.5471,6.417049194,7.682685863,-0.7734375,4.549791961,2.186364261,50.19230767 +113.01,50.42658721,-2.580515215,48.5552,6.410096802,7.681575468,-0.835,4.653246939,2.263445877,50.18478261 +113.02,50.42658778,-2.580514134,48.5638,6.399668234,7.680465075,-0.8965625,4.756774282,2.338553769,50.1772575 +113.03,50.42658836,-2.580513053,48.5731,6.399668253,7.679354681,-0.9584375,4.860352447,2.411622389,50.16973244 +113.04,50.42658893,-2.580511973,48.583,6.410096843,7.679132537,-1.02,4.963959774,2.482588025,50.16220733 +113.05,50.42658951,-2.580510892,48.5935,6.417049244,7.679132457,-1.0815625,5.067574665,2.551388797,50.15468228 +113.06,50.42659009,-2.580509811,48.6046,6.410096886,7.677800005,-1.143125,5.171175404,2.617964716,50.14715716 +113.07,50.42659066,-2.580508731,48.6164,6.399668323,7.675801366,-1.2028125,5.27474039,2.682257743,50.13963211 +113.08,50.42659124,-2.580507651,48.6287,6.399668323,7.674690977,-1.26,5.378248024,2.744211841,50.13210705 +113.09,50.42659181,-2.580506571,48.6416,6.410096905,7.674246775,-1.316875,5.481676646,2.803772867,50.12458194 +113.1,50.42659239,-2.580505491,48.655,6.417049298,7.673358449,-1.375,5.585004657,2.860889024,50.11705688 +113.11,50.42659297,-2.580504411,48.6691,6.413573115,7.672025999,-1.4334375,5.68821057,2.915510408,50.10953177 +113.12,50.42659354,-2.580503332,48.6837,6.413573139,7.670915613,-1.49125,5.791272672,2.967589464,50.10200671 +113.13,50.42659412,-2.580502252,48.6989,6.417049367,7.67002729,-1.548125,5.894169589,3.017080699,50.0944816 +113.14,50.4265947,-2.580501173,48.7147,6.413573191,7.669583092,-1.603125,5.996879722,3.063941027,50.08695654 +113.15,50.42659527,-2.580500094,48.731,6.413573189,7.66980508,-1.656875,6.0993817,3.108129537,50.07943143 +113.16,50.42659585,-2.580499014,48.7478,6.417049389,7.669582945,-1.7115625,6.201654093,3.149607671,50.07190638 +113.17,50.42659643,-2.580497935,48.7652,6.413573222,7.668250499,-1.7665625,6.303675531,3.188339388,50.06438126 +113.18,50.426597,-2.580496856,48.7832,6.417049435,7.666473931,-1.819375,6.4054247,3.224290771,50.05685621 +113.19,50.42659758,-2.580495777,48.8016,6.430954221,7.665141487,-1.87,6.506880399,3.257430478,50.04933109 +113.2,50.42659816,-2.580494699,48.8206,6.430954252,7.664919354,-1.9203125,6.608021373,3.287729747,50.04180604 +113.21,50.42659874,-2.58049362,48.84,6.417049514,7.664919284,-1.97125,6.708826536,3.315161992,50.03428092 +113.22,50.42659931,-2.580492541,48.86,6.417049526,7.663808903,-2.0215625,6.809274804,3.339703436,50.02675587 +113.23,50.42659989,-2.580491463,48.8805,6.434430495,7.662476462,-2.0696875,6.909345263,3.361332593,50.01923076 +113.24,50.42660047,-2.580490385,48.9014,6.444859093,7.661810207,-2.1165625,7.009017001,3.380030555,50.0117057 +113.25,50.42660105,-2.580489306,48.9228,6.434430539,7.661143953,-2.1634375,7.108269105,3.395781165,50.00418059 +113.26,50.42660163,-2.580488229,48.9447,6.4170496,7.660255638,-2.2096875,7.207081005,3.408570557,49.99665553 +113.27,50.4266022,-2.58048715,48.967,6.417049628,7.659145261,-2.2546875,7.305431961,3.418387616,49.98913042 +113.28,50.42660278,-2.580486073,48.9898,6.434430618,7.657812823,-2.2984375,7.40330146,3.425223804,49.98160536 +113.29,50.42660336,-2.580484995,49.013,6.44485922,7.656924508,-2.34125,7.500669049,3.429073164,49.97408025 +113.3,50.42660394,-2.580483918,49.0366,6.434430668,7.656480318,-2.3834375,7.597514386,3.429932314,49.96655519 +113.31,50.42660452,-2.58048284,49.0607,6.417049731,7.655592006,-2.4246875,7.693817304,3.42780051,49.95903008 +113.32,50.42660509,-2.580481763,49.0851,6.417049748,7.654481632,-2.4646875,7.789557635,3.422679585,49.95150502 +113.33,50.42660567,-2.580480686,49.11,6.434430722,7.654259506,-2.503125,7.884715382,3.414574066,49.94397991 +113.34,50.42660625,-2.580479609,49.1352,6.448335517,7.654259443,-2.5396875,7.979270722,3.403490942,49.93645486 +113.35,50.42660683,-2.580478531,49.1608,6.451811744,7.652927007,-2.5753125,8.073203829,3.389439954,49.92892974 +113.36,50.42660741,-2.580477455,49.1867,6.451811773,7.650928385,-2.6115625,8.166495224,3.372433364,49.92140469 +113.37,50.42660799,-2.580476378,49.213,6.448335608,7.650040075,-2.6478125,8.259125253,3.352485895,49.91387957 +113.38,50.42660857,-2.580475302,49.2397,6.434430878,7.650484138,-2.68125,8.351074723,3.329615024,49.90635452 +113.39,50.42660915,-2.580474225,49.2667,6.417049955,7.65070614,-2.7115625,8.442324325,3.30384069,49.8988294 +113.4,50.42660972,-2.580473148,49.2939,6.417049972,7.649373707,-2.741875,8.532855038,3.275185409,49.89130435 +113.41,50.4266103,-2.580472072,49.3215,6.434430943,7.647375088,-2.773125,8.622647952,3.243674048,49.88377924 +113.42,50.42661088,-2.580470996,49.3494,6.448335738,7.646264717,-2.8028125,8.71168439,3.209334166,49.87625418 +113.43,50.42661146,-2.58046992,49.3776,6.451811968,7.645820533,-2.8296875,8.799945616,3.17219573,49.86872912 +113.44,50.42661204,-2.580468844,49.406,6.451812,7.644710163,-2.855,8.887413296,3.132291053,49.86120401 +113.45,50.42661262,-2.580467768,49.4347,6.45181203,7.642711545,-2.88,8.974069152,3.089654971,49.85367896 +113.46,50.4266132,-2.580466693,49.4636,6.451812071,7.641379114,-2.904375,9.059895078,3.044324728,49.84615384 +113.47,50.42661378,-2.580465618,49.4928,6.45181211,7.641601117,-2.9265625,9.144873084,2.996339742,49.83862879 +113.48,50.42661436,-2.580464542,49.5222,6.451812129,7.642267245,-2.9465625,9.228985581,2.945741896,49.83110367 +113.49,50.42661494,-2.580463467,49.5517,6.451812142,7.642267187,-2.9665625,9.312214862,2.892575309,49.82357862 +113.5,50.42661552,-2.580462391,49.5815,6.451812171,7.641156819,-2.9865625,9.394543569,2.836886389,49.8160535 +113.51,50.4266161,-2.580461316,49.6115,6.45181221,7.638936141,-3.004375,9.475954569,2.77872361,49.80852845 +113.52,50.42661668,-2.580460241,49.6416,6.451812241,7.636937525,-3.0196875,9.556430789,2.718137792,49.80100334 +113.53,50.42661726,-2.580459167,49.6719,6.451812266,7.636493343,-3.0334375,9.635955497,2.655181706,49.79347828 +113.54,50.42661784,-2.580458092,49.7023,6.451812306,7.636715348,-3.04625,9.714512022,2.589910239,49.78595317 +113.55,50.42661842,-2.580457017,49.7328,6.451812358,7.636049105,-3.0584375,9.792083975,2.522380345,49.77842811 +113.56,50.426619,-2.580455943,49.7635,6.45181239,7.634494614,-3.0696875,9.868655201,2.452650923,49.770903 +113.57,50.42661958,-2.580454868,49.7942,6.455288594,7.633162185,-3.0796875,9.944209598,2.380782706,49.76337794 +113.58,50.42662016,-2.580453795,49.8251,6.469193387,7.632940066,-3.088125,10.01873153,2.306838435,49.75585283 +113.59,50.42662074,-2.58045272,49.856,6.486574387,7.633162071,-3.0946875,10.09220534,2.230882623,49.74832777 +113.6,50.42662133,-2.580451646,49.887,6.486574419,7.632495828,-3.1,10.16461569,2.152981391,49.74080266 +113.61,50.42662191,-2.580450572,49.918,6.46919348,7.630719275,-3.1046875,10.2359475,2.07320269,49.7332776 +113.62,50.42662249,-2.580449498,49.9491,6.455288745,7.628498598,-3.108125,10.30618583,1.991616193,49.72575249 +113.63,50.42662307,-2.580448425,49.9802,6.451812602,7.62716617,-3.1096875,10.37531605,1.908292946,49.71822744 +113.64,50.42662365,-2.580447352,50.0113,6.451812645,7.627166114,-3.1096875,10.44332373,1.823305658,49.71070232 +113.65,50.42662423,-2.580446278,50.0424,6.455288859,7.627166058,-3.108125,10.51019461,1.736728412,49.70317727 +113.66,50.42662481,-2.580445205,50.0735,6.469193644,7.626721878,-3.105,10.57591476,1.648636667,49.69565215 +113.67,50.42662539,-2.580444132,50.1045,6.486574637,7.626055635,-3.10125,10.64047043,1.55910737,49.6881271 +113.68,50.42662598,-2.580443058,50.1355,6.486574677,7.624723206,-3.0965625,10.70384816,1.468218445,49.68060198 +113.69,50.42662656,-2.580441986,50.1665,6.469193746,7.623390777,-3.0896875,10.76603476,1.376049245,49.67307693 +113.7,50.42662714,-2.580440913,50.1973,6.458765192,7.622502471,-3.0815625,10.82701718,1.2826801,49.66555182 +113.71,50.42662772,-2.58043984,50.2281,6.469193804,7.621170042,-3.0734375,10.8867827,1.188192427,49.65802676 +113.72,50.4266283,-2.580438768,50.2588,6.486574817,7.620059675,-3.064375,10.94531881,1.092668617,49.65050165 +113.73,50.42662889,-2.580437696,50.2894,6.486574859,7.620059618,-3.0528125,11.00261333,0.996192035,49.64297659 +113.74,50.42662947,-2.580436623,50.3199,6.469193916,7.619837499,-3.038125,11.05865428,0.898846735,49.63545148 +113.75,50.42663005,-2.580435551,50.3502,6.458765352,7.618727132,-3.021875,11.11342996,0.800717571,49.62792642 +113.76,50.42663063,-2.580434479,50.3803,6.46919396,7.617838827,-3.0065625,11.16692898,0.701890259,49.62040137 +113.77,50.42663121,-2.580433407,50.4103,6.486574963,7.617394645,-2.99125,11.21914004,0.602450855,49.61287625 +113.78,50.4266318,-2.580432335,50.4402,6.490051187,7.616506338,-2.9728125,11.27005233,0.502486106,49.6053512 +113.79,50.42663238,-2.580431263,50.4698,6.486575014,7.615173908,-2.9515625,11.31965523,0.402083159,49.59782608 +113.8,50.42663296,-2.580430192,50.4992,6.490051231,7.614063539,-2.9303125,11.36793833,0.30132962,49.59030103 +113.81,50.42663355,-2.58042912,50.5284,6.486575077,7.613175232,-2.9096875,11.41489159,0.200313264,49.58277592 +113.82,50.42663413,-2.580428049,50.5574,6.472670356,7.612508987,-2.8878125,11.46050516,0.099122272,49.57525086 +113.83,50.42663471,-2.580426978,50.5862,6.472670397,7.611842742,-2.863125,11.50476953,-0.002155123,49.56772575 +113.84,50.42663529,-2.580425906,50.6147,6.486575189,7.610510311,-2.8365625,11.54767548,-0.103430685,49.56020069 +113.85,50.42663588,-2.580424836,50.6429,6.4900514,7.60939994,-2.8096875,11.589214,-0.204616063,49.55267558 +113.86,50.42663646,-2.580423765,50.6709,6.486575236,7.60939988,-2.7815625,11.62937651,-0.305622964,49.54515052 +113.87,50.42663704,-2.580422694,50.6986,6.490051456,7.609177757,-2.75125,11.66815452,-0.406363383,49.53762541 +113.88,50.42663763,-2.580421623,50.7259,6.490051473,7.608067386,-2.72,11.70553996,-0.506749428,49.53010035 +113.89,50.42663821,-2.580420553,50.753,6.486575302,7.606957015,-2.6884375,11.74152503,-0.606693607,49.52257524 +113.9,50.42663879,-2.580419482,50.7797,6.493527722,7.605846643,-2.65625,11.77610223,-0.706108775,49.51505018 +113.91,50.42663938,-2.580418412,50.8061,6.50395634,7.604514209,-2.623125,11.80926434,-0.804908127,49.50752507 +113.92,50.42663996,-2.580417342,50.8322,6.503956369,7.603625898,-2.5878125,11.84100443,-0.903005607,49.50000002 +113.93,50.42664055,-2.580416272,50.8579,6.493527815,7.603403773,-2.55,11.87131584,-1.00031567,49.4924749 +113.94,50.42664113,-2.580415202,50.8832,6.48657546,7.603181648,-2.511875,11.90019229,-1.096753462,49.48494985 +113.95,50.42664171,-2.580414132,50.9081,6.493527878,7.602071274,-2.4746875,11.92762768,-1.192234874,49.47742473 +113.96,50.4266423,-2.580413062,50.9327,6.503956483,7.600072652,-2.43625,11.95361636,-1.286676596,49.46989968 +113.97,50.42664288,-2.580411993,50.9569,6.507432693,7.598740214,-2.3946875,11.97815288,-1.379996352,49.46237456 +113.98,50.42664347,-2.580410924,50.9806,6.507432704,7.598740149,-2.351875,12.00123207,-1.472112724,49.45484951 +113.99,50.42664405,-2.580409854,51.0039,6.50743272,7.598518021,-2.31,12.02284914,-1.562945328,49.4473244 +114,50.42664464,-2.580408785,51.0268,6.507432744,7.597407644,-2.2678125,12.04299961,-1.652415094,49.43979934 +114.01,50.42664522,-2.580407716,51.0493,6.503956583,7.596519329,-2.223125,12.06167918,-1.740443929,49.43227423 +114.02,50.42664581,-2.580406647,51.0713,6.493528038,7.596075137,-2.1765625,12.07888407,-1.826955055,49.42474917 +114.03,50.42664639,-2.580405578,51.0928,6.486575677,7.595186822,-2.13,12.09461062,-1.911873015,49.41722406 +114.04,50.42664697,-2.580404509,51.1139,6.493528083,7.593854382,-2.083125,12.10885549,-1.99512384,49.409699 +114.05,50.42664756,-2.580403441,51.1345,6.507432881,7.592744004,-2.0346875,12.12161584,-2.076634879,49.40217389 +114.06,50.42664814,-2.580402372,51.1546,6.521337682,7.591633624,-1.985,12.1328889,-2.156335027,49.39464883 +114.07,50.42664873,-2.580401304,51.1742,6.528290089,7.590301181,-1.9346875,12.14267232,-2.234154842,49.38712372 +114.08,50.42664932,-2.580400236,51.1933,6.521337714,7.589412862,-1.8834375,12.15096411,-2.310026487,49.37959866 +114.09,50.4266499,-2.580399168,51.2119,6.510909141,7.589190728,-1.8315625,12.15776254,-2.383883669,49.37207355 +114.1,50.42665049,-2.5803981,51.2299,6.50743296,7.589190656,-1.7796875,12.16306612,-2.45566216,49.3645485 +114.11,50.42665107,-2.580397032,51.2475,6.507432985,7.588968521,-1.7265625,12.16687383,-2.525299221,49.35702344 +114.12,50.42665166,-2.580395964,51.2645,6.507433014,7.5880802,-1.6715625,12.1691848,-2.592734176,49.34949833 +114.13,50.42665224,-2.580394896,51.2809,6.507433032,7.586747754,-1.616875,12.16999857,-2.65790824,49.34197327 +114.14,50.42665283,-2.580393829,51.2968,6.510909231,7.58563737,-1.563125,12.16931503,-2.720764575,49.33444816 +114.15,50.42665341,-2.580392761,51.3122,6.52133782,7.584526985,-1.5078125,12.16713418,-2.781248349,49.3269231 +114.16,50.426654,-2.580391694,51.327,6.528290231,7.583194537,-1.45,12.16345665,-2.83930685,49.31939799 +114.17,50.42665459,-2.580390627,51.3412,6.52133788,7.58208415,-1.3915625,12.15828307,-2.894889428,49.31187293 +114.18,50.42665517,-2.58038956,51.3548,6.510909326,7.580973763,-1.3334375,12.15161459,-2.947947612,49.30434782 +114.19,50.42665576,-2.580388493,51.3679,6.510909329,7.579863375,-1.275,12.14345263,-2.998435163,49.29682276 +114.2,50.42665634,-2.580387427,51.3803,6.521337902,7.579641234,-1.2165625,12.13379881,-3.046308021,49.28929765 +114.21,50.42665693,-2.58038636,51.3922,6.52829029,7.579863216,-1.158125,12.12265518,-3.091524475,49.28177259 +114.22,50.42665752,-2.580385293,51.4035,6.524814109,7.57919695,-1.098125,12.1100241,-3.134045048,49.27424748 +114.23,50.4266581,-2.580384227,51.4142,6.52481413,7.577642436,-1.0365625,12.09590814,-3.17383267,49.26672243 +114.24,50.42665869,-2.58038316,51.4242,6.528290345,7.576309982,-0.975,12.08031033,-3.210852676,49.25919731 +114.25,50.42665928,-2.580382095,51.4337,6.524814162,7.576087837,-0.9134375,12.06323384,-3.245072753,49.25167226 +114.26,50.42665986,-2.580381028,51.4425,6.528290354,7.576087754,-0.8515625,12.04468233,-3.276463105,49.24414714 +114.27,50.42666045,-2.580379962,51.4507,6.542195132,7.574755299,-0.79,12.02465963,-3.304996346,49.23662209 +114.28,50.42666104,-2.580378896,51.4583,6.542195156,7.572756657,-0.728125,12.00316993,-3.330647552,49.22909698 +114.29,50.42666163,-2.580377831,51.4653,6.528290412,7.5714242,-0.665,11.98021764,-3.353394434,49.22157192 +114.3,50.42666221,-2.580376765,51.4716,6.524814226,7.570535866,-0.6015625,11.95580769,-3.373217055,49.21404681 +114.31,50.4266628,-2.5803757,51.4773,6.528290404,7.570091655,-0.5384375,11.92994507,-3.390098168,49.20652175 +114.32,50.42666339,-2.580374635,51.4824,6.524814199,7.570313629,-0.475,11.90263526,-3.404023105,49.19899664 +114.33,50.42666397,-2.580373569,51.4868,6.528290393,7.570091479,-0.4115625,11.8738839,-3.414979663,49.19147158 +114.34,50.42666456,-2.580372504,51.4906,6.545671366,7.568759018,-0.3484375,11.84369699,-3.422958329,49.18394647 +114.35,50.42666515,-2.580371439,51.4938,6.556099959,7.566982432,-0.2846875,11.81208089,-3.427952115,49.17642141 +114.36,50.42666574,-2.580370374,51.4963,6.545671394,7.56564997,-0.2196875,11.77904219,-3.429956665,49.1688963 +114.37,50.42666633,-2.58036931,51.4982,6.528290429,7.565427817,-0.15375,11.74458778,-3.428970261,49.16137124 +114.38,50.42666691,-2.580368245,51.4994,6.52829042,7.565427725,-0.0884375,11.7087248,-3.424993704,49.15384613 +114.39,50.4266675,-2.58036718,51.4999,6.545671379,7.56409526,-0.025,11.67146083,-3.418030548,49.14632107 +114.4,50.42666809,-2.580366116,51.4999,6.556099962,7.562318671,0.0384375,11.6328036,-3.408086808,49.13879596 +114.41,50.42666868,-2.580365052,51.4992,6.5456714,7.561874452,0.1034375,11.59276118,-3.395171136,49.13127091 +114.42,50.42666927,-2.580363988,51.4978,6.528290454,7.561874357,0.168125,11.55134195,-3.379294877,49.12374579 +114.43,50.42666985,-2.580362923,51.4958,6.528290453,7.560541891,0.2315625,11.50855455,-3.360471781,49.11622074 +114.44,50.42667044,-2.58036186,51.4932,6.545671396,7.558543237,0.2953125,11.46440792,-3.338718292,49.10869562 +114.45,50.42667103,-2.580360796,51.4899,6.559576149,7.557654891,0.36,11.41891129,-3.314053433,49.10117057 +114.46,50.42667162,-2.580359733,51.486,6.563052334,7.558098915,0.425,11.37207417,-3.286498633,49.09364551 +114.47,50.42667221,-2.580358669,51.4814,6.56305233,7.558320878,0.4896875,11.32390629,-3.256077954,49.0861204 +114.48,50.4266728,-2.580357605,51.4762,6.559576134,7.556988407,0.553125,11.27441775,-3.222817983,49.07859534 +114.49,50.42667339,-2.580356542,51.4703,6.545671365,7.55498975,0.615,11.22361891,-3.186747597,49.07107023 +114.5,50.42667398,-2.580355479,51.4639,6.528290403,7.553879339,0.676875,11.17152032,-3.147898366,49.06354517 +114.51,50.42667456,-2.580354416,51.4568,6.528290396,7.553435114,0.7403125,11.11813291,-3.106304094,49.05602006 +114.52,50.42667515,-2.580353353,51.4491,6.545671345,7.552546764,0.804375,11.06346781,-3.062001106,49.04849501 +114.53,50.42667574,-2.58035229,51.4407,6.559576101,7.551214288,0.8665625,11.00753642,-3.015028021,49.04096989 +114.54,50.42667633,-2.580351228,51.4317,6.563052284,7.550325936,0.9265625,10.95035042,-2.965425747,49.03344484 +114.55,50.42667692,-2.580350165,51.4222,6.563052279,7.550103769,0.986875,10.89192173,-2.913237599,49.02591972 +114.56,50.42667751,-2.580349103,51.412,6.563052287,7.549881602,1.0484375,10.83226267,-2.858509014,49.01839467 +114.57,50.4266781,-2.58034804,51.4012,6.563052299,7.548993248,1.1096875,10.77138556,-2.801287834,49.01086955 +114.58,50.42667869,-2.580346978,51.3898,6.563052287,7.54766077,1.17,10.70930318,-2.741623848,49.0033445 +114.59,50.42667928,-2.580345916,51.3778,6.563052254,7.546550353,1.23,10.64602847,-2.679569138,48.99581939 +114.6,50.42667987,-2.580344854,51.3652,6.563052224,7.545439935,1.2896875,10.58157473,-2.615177792,48.98829433 +114.61,50.42668046,-2.580343792,51.352,6.563052206,7.544329516,1.348125,10.51595524,-2.548506017,48.98076922 +114.62,50.42668105,-2.580342731,51.3382,6.563052195,7.544107344,1.405,10.44918389,-2.479611853,48.97324416 +114.63,50.42668164,-2.580341669,51.3239,6.56305219,7.544107233,1.4615625,10.38127452,-2.40855546,48.96571905 +114.64,50.42668223,-2.580340607,51.309,6.563052186,7.542774751,1.5184375,10.31224136,-2.335398777,48.95819399 +114.65,50.42668282,-2.580339546,51.2935,6.563052171,7.540776082,1.5746875,10.24209884,-2.260205572,48.95066888 +114.66,50.42668341,-2.580338485,51.2775,6.563052144,7.53966566,1.63,10.1708615,-2.183041449,48.94314382 +114.67,50.426684,-2.580337424,51.2609,6.563052119,7.539443485,1.6846875,10.09854432,-2.103973675,48.93561871 +114.68,50.42668459,-2.580336363,51.2438,6.5630521,7.53922131,1.738125,10.0251624,-2.023071175,48.92809365 +114.69,50.42668518,-2.580335302,51.2261,6.566528275,7.538332948,1.79,9.950731004,-1.940404595,48.92056854 +114.7,50.42668577,-2.580334241,51.208,6.58043303,7.537000462,1.841875,9.875265701,-1.856045899,48.91304349 +114.71,50.42668636,-2.580333181,51.1893,6.597813982,7.535890037,1.895,9.79878231,-1.770068711,48.90551837 +114.72,50.42668696,-2.58033212,51.1701,6.59781398,7.534779611,1.9478125,9.721296701,-1.682548033,48.89799332 +114.73,50.42668755,-2.58033106,51.1503,6.580433017,7.533447122,1.9978125,9.642825146,-1.593560067,48.8904682 +114.74,50.42668814,-2.58033,51.1301,6.566528224,7.532558757,2.045,9.563384033,-1.503182564,48.88294315 +114.75,50.42668873,-2.58032894,51.1094,6.563051988,7.532336578,2.091875,9.482989861,-1.411494248,48.87541804 +114.76,50.42668932,-2.58032788,51.0883,6.563051949,7.532336459,2.1396875,9.401659476,-1.318575104,48.86789298 +114.77,50.42668991,-2.58032682,51.0666,6.566528116,7.532114278,2.1865625,9.319409837,-1.224506091,48.86036787 +114.78,50.4266905,-2.58032576,51.0445,6.580432867,7.531225911,2.23125,9.236258191,-1.129369314,48.85284281 +114.79,50.42669109,-2.5803247,51.022,6.59781381,7.52989342,2.275,9.152221841,-1.033247737,48.8453177 +114.8,50.42669169,-2.580323641,50.999,6.597813789,7.528782989,2.3184375,9.067318377,-0.936225127,48.83779264 +114.81,50.42669228,-2.580322581,50.9756,6.580432809,7.527672559,2.36125,8.981565445,-0.838386109,48.83026759 +114.82,50.42669287,-2.580321522,50.9518,6.570004217,7.526340067,2.403125,8.894981094,-0.739816054,48.82274247 +114.83,50.42669346,-2.580320463,50.9275,6.580432771,7.525451698,2.443125,8.807583258,-0.640600849,48.81521742 +114.84,50.42669405,-2.580319404,50.9029,6.597813701,7.525229514,2.4815625,8.719390271,-0.54082701,48.8076923 +114.85,50.42669465,-2.580318345,50.8779,6.597813667,7.525007328,2.52,8.630420583,-0.440581569,48.80016725 +114.86,50.42669524,-2.580317286,50.8525,6.583908867,7.524118957,2.558125,8.540692699,-0.339951903,48.79264213 +114.87,50.42669583,-2.580316227,50.8267,6.583908841,7.522786462,2.5946875,8.450225356,-0.239025845,48.78511708 +114.88,50.42669642,-2.580315169,50.8006,6.597813587,7.521676028,2.6296875,8.359037519,-0.137891289,48.77759197 +114.89,50.42669702,-2.58031411,50.7741,6.597813564,7.520565594,2.6634375,8.267148152,-0.036636583,48.77006691 +114.9,50.42669761,-2.580313052,50.7473,6.583908783,7.519233099,2.69625,8.174576507,0.064650151,48.7625418 +114.91,50.4266982,-2.580311994,50.7202,6.583908778,7.518344726,2.728125,8.081341892,0.165880449,48.75501674 +114.92,50.42669879,-2.580310936,50.6927,6.597813522,7.518122538,2.758125,7.987463789,0.266966132,48.74749163 +114.93,50.42669939,-2.580309878,50.665,6.601289665,7.51790035,2.7865625,7.892961792,0.367819023,48.73996657 +114.94,50.42669998,-2.58030882,50.637,6.597813426,7.517011977,2.815,7.797855611,0.468351172,48.73244146 +114.95,50.42670057,-2.580307762,50.6087,6.601289586,7.515679479,2.8428125,7.702165127,0.568474916,48.7249164 +114.96,50.42670117,-2.580306705,50.5801,6.597813364,7.514569043,2.868125,7.605910395,0.668102937,48.71739129 +114.97,50.42670176,-2.580305647,50.5513,6.583908563,7.513458606,2.8915625,7.50911141,0.767148318,48.70986623 +114.98,50.42670235,-2.58030459,50.5223,6.583908534,7.512126108,2.915,7.411788398,0.86552477,48.70234112 +114.99,50.42670294,-2.580303533,50.493,6.601289468,7.511237733,2.9378125,7.313961756,0.963146465,48.69481607 +115,50.42670354,-2.580302476,50.4635,6.615194212,7.511015542,2.958125,7.215651824,1.059928319,48.68729095 +115.01,50.42670413,-2.580301419,50.4338,6.615194191,7.510793352,2.9765625,7.116879228,1.15578582,48.6797659 +115.02,50.42670473,-2.580300362,50.404,6.604765593,7.509904976,2.9946875,7.017664539,1.250635545,48.67224078 +115.03,50.42670532,-2.580299305,50.3739,6.597813177,7.508572477,3.0115625,6.918028496,1.344394645,48.66471573 +115.04,50.42670591,-2.580298249,50.3437,6.601289328,7.507684101,3.02625,6.817991898,1.436981416,48.65719061 +115.05,50.42670651,-2.580297192,50.3134,6.601289289,7.507239849,3.04,6.717575602,1.528315128,48.64966556 +115.06,50.4267071,-2.580296136,50.2829,6.597813063,7.50612941,3.053125,6.616800633,1.618316141,48.64214045 +115.07,50.42670769,-2.580295079,50.2523,6.604765417,7.504130725,3.0646875,6.515688021,1.706905901,48.63461539 +115.08,50.42670829,-2.580294024,50.2216,6.615193964,7.502798225,3.0746875,6.414258907,1.794007289,48.62709028 +115.09,50.42670888,-2.580292968,50.1908,6.618670126,7.503020157,3.0834375,6.312534376,1.879544216,48.61956522 +115.1,50.42670948,-2.580291912,50.1599,6.618670094,7.503464149,3.09125,6.210535799,1.963442196,48.61204011 +115.11,50.42671007,-2.580290856,50.129,6.618670063,7.502797834,3.098125,6.108284375,2.045628007,48.60451505 +115.12,50.42671067,-2.5802898,50.0979,6.618670031,7.501465334,3.103125,6.005801535,2.126029972,48.59698994 +115.13,50.42671126,-2.580288745,50.0669,6.615193812,7.500354895,3.10625,5.903108647,2.204578074,48.58946488 +115.14,50.42671186,-2.580287689,50.0358,6.60476522,7.499244456,3.1084375,5.800227142,2.281203673,48.58193983 +115.15,50.42671245,-2.580286634,50.0047,6.597812826,7.497911956,3.109375,5.697178506,2.355840077,48.57441471 +115.16,50.42671304,-2.580285579,49.9736,6.604765179,7.497023579,3.1084375,5.593984281,2.428422142,48.56688966 +115.17,50.42671364,-2.580284524,49.9425,6.618669896,7.496801387,3.10625,5.49066601,2.498886611,48.55936455 +115.18,50.42671423,-2.580283469,49.9115,6.632574616,7.496579195,3.1034375,5.387245237,2.567172008,48.55183949 +115.19,50.42671483,-2.580282414,49.8804,6.639526965,7.495468756,3.0996875,5.283743677,2.633218744,48.54431438 +115.2,50.42671543,-2.580281359,49.8495,6.632574549,7.493248009,3.094375,5.180182759,2.696969294,48.53678932 +115.21,50.42671602,-2.580280305,49.8185,6.62214594,7.491249324,3.086875,5.076584312,2.758368081,48.52926421 +115.22,50.42671662,-2.580279251,49.7877,6.618669716,7.491027132,3.0778125,4.972969822,2.817361535,48.52173915 +115.23,50.42671721,-2.580278197,49.757,6.618669685,7.491693188,3.0684375,4.869360947,2.873898145,48.51421404 +115.24,50.42671781,-2.580277142,49.7263,6.618669654,7.490804812,3.0578125,4.765779403,2.927928753,48.50668898 +115.25,50.4267184,-2.580276088,49.6958,6.618669623,7.488584066,3.0446875,4.662246731,2.979406089,48.49916387 +115.26,50.426719,-2.580275035,49.6654,6.622145784,7.487473628,3.03,4.558784648,3.028285347,48.49163881 +115.27,50.42671959,-2.580273981,49.6352,6.632574331,7.487473499,3.015,4.455414639,3.074523958,48.4841137 +115.28,50.42672019,-2.580272927,49.6051,6.639526687,7.487029246,2.9996875,4.35215842,3.11808147,48.47658865 +115.29,50.42672079,-2.580271874,49.5752,6.632574281,7.486140871,2.9828125,4.249037476,3.158920011,48.46906353 +115.3,50.42672138,-2.58027082,49.5454,6.622145685,7.485030435,2.963125,4.146073351,3.197003943,48.46153848 +115.31,50.42672198,-2.580269767,49.5159,6.622145655,7.483919998,2.9415625,4.043287587,3.232299976,48.45401336 +115.32,50.42672257,-2.580268714,49.4866,6.632574191,7.483697807,2.92,3.940701614,3.264777459,48.44648831 +115.33,50.42672317,-2.580267661,49.4575,6.639526537,7.483697679,2.898125,3.838336802,3.294407971,48.43896319 +115.34,50.42672377,-2.580266607,49.4286,6.636050313,7.482587244,2.8746875,3.736214638,3.321165673,48.43143814 +115.35,50.42672436,-2.580265555,49.4,6.636050284,7.481254747,2.8496875,3.634356379,3.34502736,48.42391303 +115.36,50.42672496,-2.580264502,49.3716,6.639526447,7.480366374,2.8234375,3.532783338,3.365972061,48.41638797 +115.37,50.42672556,-2.580263449,49.3435,6.636050226,7.479033877,2.79625,3.431516714,3.383981615,48.40886286 +115.38,50.42672615,-2.580262397,49.3157,6.63952639,7.477923442,2.768125,3.330577651,3.399040263,48.4013378 +115.39,50.42672675,-2.580261345,49.2881,6.653431131,7.477923316,2.738125,3.229987175,3.411134944,48.39381269 +115.4,50.42672735,-2.580260292,49.2609,6.653431103,7.477479067,2.70625,3.129766371,3.420255,48.38628763 +115.41,50.42672795,-2.58025924,49.234,6.639526307,7.475480387,2.6734375,3.029936153,3.426392581,48.37876252 +115.42,50.42672854,-2.580258188,49.2074,6.63605009,7.473259647,2.6396875,2.930517376,3.429542302,48.37123746 +115.43,50.42672914,-2.580257137,49.1812,6.639526265,7.472149215,2.6046875,2.831530781,3.429701412,48.36371235 +115.44,50.42672974,-2.580256085,49.1553,6.636050057,7.471927029,2.5684375,2.732996994,3.426869797,48.35618729 +115.45,50.42673033,-2.580255034,49.1298,6.639526224,7.471704844,2.5315625,2.6349367,3.421049864,48.34866218 +115.46,50.42673093,-2.580253982,49.1047,6.653430955,7.471038535,2.4946875,2.537370238,3.412246711,48.34113713 +115.47,50.42673153,-2.580252931,49.0799,6.653430921,7.470594289,2.4565625,2.440318121,3.400468017,48.33361201 +115.48,50.42673213,-2.58025188,49.0555,6.639526126,7.470594166,2.41625,2.343800572,3.385724094,48.32608696 +115.49,50.42673272,-2.580250828,49.0316,6.639526102,7.469483737,2.375,2.247837705,3.368027777,48.3185619 +115.5,50.42673332,-2.580249777,49.008,6.656907038,7.467040939,2.333125,2.152449628,3.347394478,48.31103679 +115.51,50.42673392,-2.580248727,48.9849,6.667335593,7.465264326,2.2896875,2.057656225,3.323842245,48.30351173 +115.52,50.42673452,-2.580247676,48.9622,6.656907003,7.464820081,2.245,1.963477261,3.297391477,48.29598662 +115.53,50.42673512,-2.580246626,48.94,6.639526031,7.464819962,2.1996875,1.869932448,3.268065434,48.28846156 +115.54,50.42673571,-2.580245575,48.9182,6.639526009,7.464819843,2.1534375,1.777041264,3.2358895,48.28093645 +115.55,50.42673631,-2.580244525,48.8969,6.656906937,7.464597662,2.10625,1.684823248,3.200891862,48.27341139 +115.56,50.42673691,-2.580243474,48.8761,6.670811675,7.463709298,2.0584375,1.593297481,3.163103004,48.26588628 +115.57,50.42673751,-2.580242424,48.8557,6.674287844,7.462154749,2.01,1.502483212,3.122555869,48.25836123 +115.58,50.42673811,-2.580241374,48.8359,6.670811632,7.46037814,1.96125,1.412399349,3.079285868,48.25083611 +115.59,50.42673871,-2.580240324,48.8165,6.656906845,7.458823593,1.9115625,1.323064687,3.033330642,48.24331106 +115.6,50.42673931,-2.580239275,48.7976,6.639525866,7.457935231,1.8596875,1.234497902,2.984730299,48.23578594 +115.61,50.4267399,-2.580238225,48.7793,6.639525847,7.457713054,1.8065625,1.146717502,2.933527181,48.22826089 +115.62,50.4267405,-2.580237176,48.7615,6.656906789,7.457490878,1.7534375,1.059741821,2.879766035,48.22073577 +115.63,50.4267411,-2.580236126,48.7442,6.670811539,7.456602518,1.6996875,0.973589022,2.82349373,48.21321072 +115.64,50.4267417,-2.580235077,48.7275,6.674287714,7.455270036,1.645,0.888277039,2.764759254,48.20568561 +115.65,50.4267423,-2.580234028,48.7113,6.674287698,7.454381677,1.59,0.803823805,2.703613828,48.19816055 +115.66,50.4267429,-2.580232979,48.6957,6.674287683,7.453937441,1.535,0.720246852,2.640110853,48.19063544 +115.67,50.4267435,-2.58023193,48.6806,6.674287667,7.453049083,1.4796875,0.637563657,2.574305676,48.18311038 +115.68,50.4267441,-2.580230881,48.6661,6.674287653,7.451716603,1.423125,0.555791521,2.506255651,48.17558527 +115.69,50.4267447,-2.580229833,48.6521,6.674287639,7.450828247,1.365,0.47494752,2.436020135,48.16806021 +115.7,50.4267453,-2.580228784,48.6388,6.674287626,7.450606076,1.3065625,0.395048498,2.363660378,48.1605351 +115.71,50.4267459,-2.580227736,48.626,6.674287613,7.450383906,1.248125,0.316111129,2.289239463,48.15301004 +115.72,50.4267465,-2.580226687,48.6138,6.674287601,7.449495552,1.188125,0.23815197,2.212822306,48.14548493 +115.73,50.4267471,-2.580225639,48.6022,6.67428759,7.448163076,1.126875,0.161187237,2.134475484,48.13795987 +115.74,50.4267477,-2.580224591,48.5913,6.674287579,7.447052661,1.066875,0.08523303,2.054267466,48.13043476 +115.75,50.4267483,-2.580223543,48.5809,6.674287569,7.445720186,1.008125,0.010305276,1.972268038,48.12290971 +115.76,50.4267489,-2.580222495,48.5711,6.674287559,7.443721527,0.9478125,-0.063580554,1.888548763,48.11538459 +115.77,50.4267495,-2.580221448,48.5619,6.67428755,7.442389054,0.885,-0.136408818,1.803182635,48.10785954 +115.78,50.4267501,-2.580220401,48.5534,6.674287542,7.442388951,0.821875,-0.208164448,1.716244139,48.10033442 +115.79,50.4267507,-2.580219353,48.5455,6.674287534,7.442166786,0.76,-0.278832432,1.62780902,48.09280937 +115.8,50.4267513,-2.580218306,48.5382,6.674287527,7.441056377,0.698125,-0.348397988,1.537954456,48.08528425 +115.81,50.4267519,-2.580217259,48.5315,6.674287521,7.440168029,0.6346875,-0.41684662,1.446758712,48.0777592 +115.82,50.4267525,-2.580216212,48.5255,6.674287515,7.439945866,0.5703125,-0.484164005,1.354301429,48.07023409 +115.83,50.4267531,-2.580215165,48.5201,6.67428751,7.439723704,0.5065625,-0.550336104,1.260663166,48.06270903 +115.84,50.4267537,-2.580214118,48.5154,6.674287506,7.438835359,0.4434375,-0.615349052,1.165925568,48.05518397 +115.85,50.4267543,-2.580213071,48.5112,6.677763694,7.437502891,0.38,-0.679189327,1.070171315,48.04765886 +115.86,50.4267549,-2.580212025,48.5078,6.691668458,7.436392486,0.31625,-0.74184358,0.973483827,48.04013381 +115.87,50.4267555,-2.580210978,48.5049,6.709049415,7.435282082,0.251875,-0.803298689,0.875947446,48.03260869 +115.88,50.42675611,-2.580209932,48.5027,6.709049413,7.433949617,0.1865625,-0.863541878,0.777647197,48.02508364 +115.89,50.42675671,-2.580208886,48.5012,6.691668454,7.433061275,0.121875,-0.922560542,0.678668852,48.01755852 +115.9,50.42675731,-2.58020784,48.5003,6.677763686,7.432617057,0.0584375,-0.980342361,0.579098699,48.01003347 +115.91,50.42675791,-2.580206794,48.5,6.677763687,7.431728717,-0.0053125,-1.036875247,0.479023599,48.00250835 +115.92,50.42675851,-2.580205748,48.5004,6.691668455,7.430396254,-0.07,-1.092147455,0.378530755,47.9949833 +115.93,50.42675911,-2.580204703,48.5014,6.709049416,7.429507916,-0.1346875,-1.146147352,0.277707773,47.98745819 +115.94,50.42675972,-2.580203657,48.5031,6.709049418,7.429285763,-0.1984375,-1.198863709,0.176642716,47.97993313 +115.95,50.42676032,-2.580202612,48.5054,6.691668462,7.42906361,-0.261875,-1.250285525,0.075423534,47.97240802 +115.96,50.42676092,-2.580201566,48.5083,6.677763699,7.428175273,-0.326875,-1.300402029,-0.025861367,47.96488296 +115.97,50.42676152,-2.580200521,48.5119,6.677763703,7.426620754,-0.393125,-1.349202792,-0.127123693,47.95735785 +115.98,50.42676212,-2.580199476,48.5162,6.691668476,7.424844174,-0.4578125,-1.396677559,-0.228275209,47.94983279 +115.99,50.42676272,-2.580198431,48.5211,6.70904944,7.423511718,-0.52,-1.442816533,-0.329227622,47.94230768 +116,50.42676333,-2.580197387,48.5266,6.709049447,7.423289569,-0.581875,-1.487609972,-0.429892984,47.93478262 +116.01,50.42676393,-2.580196342,48.5327,6.695144687,7.423289481,-0.645,-1.531048538,-0.530183459,47.92725751 +116.02,50.42676453,-2.580195297,48.5395,6.695144695,7.422179088,-0.7084375,-1.573123236,-0.630011615,47.91973245 +116.03,50.42676513,-2.580194253,48.5469,6.70904947,7.421068696,-0.77125,-1.613825183,-0.729290361,47.91220734 +116.04,50.42676574,-2.580193209,48.5549,6.712525671,7.421068611,-0.8334375,-1.653145902,-0.827933181,47.90468229 +116.05,50.42676634,-2.580192164,48.5636,6.709049489,7.420846465,-0.895,-1.691077197,-0.925854075,47.89715717 +116.06,50.42676694,-2.58019112,48.5728,6.712525692,7.419514013,-0.9565625,-1.727611164,-1.022967556,47.88963212 +116.07,50.42676755,-2.580190076,48.5827,6.709049511,7.417737439,-1.0184375,-1.76274018,-1.119189,47.882107 +116.08,50.42676815,-2.580189032,48.5932,6.695144755,7.416182928,-1.0796875,-1.796456856,-1.214434467,47.87458195 +116.09,50.42676875,-2.580187989,48.6043,6.695144768,7.415294601,-1.14,-1.8287542,-1.308620994,47.86705683 +116.1,50.42676935,-2.580186945,48.616,6.709049548,7.414850399,-1.1996875,-1.859625395,-1.401666303,47.85953178 +116.11,50.42676996,-2.580185902,48.6283,6.712525753,7.413962073,-1.2584375,-1.889064081,-1.493489379,47.85200667 +116.12,50.42677056,-2.580184858,48.6412,6.709049576,7.412629626,-1.3165625,-1.91706407,-1.584010121,47.84448161 +116.13,50.42677116,-2.580183816,48.6546,6.716001975,7.41151924,-1.375,-1.943619518,-1.673149577,47.8369565 +116.14,50.42677177,-2.580182772,48.6687,6.726430566,7.410630917,-1.433125,-1.968724925,-1.760830053,47.82943144 +116.15,50.42677237,-2.58018173,48.6833,6.726430582,7.410186717,-1.4896875,-1.992374961,-1.846975003,47.82190633 +116.16,50.42677298,-2.580180687,48.6985,6.716002023,7.410408702,-1.545,-2.014564699,-1.931509425,47.81438127 +116.17,50.42677358,-2.580179644,48.7142,6.709049656,7.409964503,-1.6,-2.035289557,-2.014359466,47.80685616 +116.18,50.42677418,-2.580178601,48.7305,6.712525866,7.407965876,-1.655,-2.054545179,-2.09545299,47.7993311 +116.19,50.42677479,-2.580177559,48.7473,6.712525882,7.40596725,-1.7096875,-2.072327611,-2.174719295,47.79180605 +116.2,50.42677539,-2.580176517,48.7647,6.7090497,7.405523053,-1.7634375,-2.088633016,-2.252089166,47.78428093 +116.21,50.42677599,-2.580175475,48.7826,6.716002093,7.40574504,-1.81625,-2.10345807,-2.327495168,47.77675588 +116.22,50.4267766,-2.580174432,48.801,6.726430689,7.405300845,-1.8684375,-2.116799621,-2.400871581,47.76923077 +116.23,50.4267772,-2.580173391,48.82,6.729906912,7.404412528,-1.9196875,-2.128654978,-2.472154406,47.76170571 +116.24,50.42677781,-2.580172348,48.8394,6.729906943,7.40330215,-1.97,-2.13902156,-2.54128142,47.7541806 +116.25,50.42677841,-2.580171307,48.8594,6.729906967,7.401747649,-2.02,-2.147897307,-2.608192463,47.74665554 +116.26,50.42677902,-2.580170265,48.8798,6.729906989,7.400193149,-2.069375,-2.155280269,-2.672829092,47.73913043 +116.27,50.42677962,-2.580169224,48.9008,6.729907012,7.399526895,-2.1165625,-2.1611689,-2.735134986,47.73160537 +116.28,50.42678023,-2.580168183,48.9222,6.729907035,7.399748887,-2.1615625,-2.165562054,-2.795055829,47.72408026 +116.29,50.42678083,-2.580167141,48.944,6.729907059,7.399304696,-2.206875,-2.168458814,-2.85253931,47.7165552 +116.3,50.42678144,-2.5801661,48.9663,6.729907083,7.397306075,-2.253125,-2.169858493,-2.907535294,47.70903009 +116.31,50.42678204,-2.580165059,48.9891,6.729907108,7.395307455,-2.2978125,-2.169760803,-2.95999594,47.70150503 +116.32,50.42678265,-2.580164019,49.0123,6.729907133,7.394863265,-2.34,-2.168165861,-3.009875411,47.69397992 +116.33,50.42678325,-2.580162978,49.0359,6.729907158,7.39508526,-2.3815625,-2.165073894,-3.057130163,47.68645487 +116.34,50.42678386,-2.580161937,49.0599,6.729907185,7.394641071,-2.423125,-2.160485591,-3.101719113,47.67892975 +116.35,50.42678446,-2.580160897,49.0844,6.729907211,7.393752761,-2.463125,-2.154401982,-3.143603302,47.6714047 +116.36,50.42678507,-2.580159856,49.1092,6.729907238,7.392420327,-2.50125,-2.146824214,-3.182746232,47.66387958 +116.37,50.42678567,-2.580158816,49.1344,6.729907265,7.390199649,-2.5384375,-2.137753891,-3.219113754,47.65635453 +116.38,50.42678628,-2.580157776,49.16,6.729907293,7.388201033,-2.575,-2.127193019,-3.252674126,47.64882941 +116.39,50.42678688,-2.580156737,49.1859,6.729907321,7.387978907,-2.61125,-2.115143659,-3.283398186,47.64130436 +116.4,50.42678749,-2.580155697,49.2122,6.73338354,7.388867088,-2.6465625,-2.101608448,-3.311259004,47.63377925 +116.41,50.42678809,-2.580154657,49.2389,6.743812136,7.388644963,-2.6796875,-2.086590078,-3.3362324,47.62625419 +116.42,50.4267887,-2.580153617,49.2658,6.750764539,7.38686841,-2.7115625,-2.070091816,-3.358296547,47.61872908 +116.43,50.42678931,-2.580152578,49.2931,6.747288376,7.38553598,-2.743125,-2.052117041,-3.377432191,47.61120402 +116.44,50.42678991,-2.580151539,49.3207,6.747288417,7.385535917,-2.7728125,-2.032669536,-3.393622661,47.60367891 +116.45,50.42679052,-2.580150499,49.3486,6.750764648,7.385313794,-2.8,-2.011753367,-3.40685386,47.59615385 +116.46,50.42679113,-2.58014946,49.3767,6.743812296,7.383981365,-2.8265625,-1.989372834,-3.417114217,47.58862874 +116.47,50.42679173,-2.580148421,49.4051,6.73338375,7.382204813,-2.8534375,-1.96553269,-3.424394849,47.58110368 +116.48,50.42679234,-2.580147382,49.4338,6.733383781,7.380650323,-2.8796875,-1.940237921,-3.428689282,47.57357857 +116.49,50.42679294,-2.580146344,49.4627,6.74381239,7.379762017,-2.904375,-1.913493684,-3.429993907,47.56605351 +116.5,50.42679355,-2.580145305,49.4919,6.750764806,7.379539895,-2.9265625,-1.885305707,-3.42830752,47.5585284 +116.51,50.42679416,-2.580144267,49.5213,6.747288645,7.379317774,-2.9465625,-1.855679836,-3.423631554,47.55100335 +116.52,50.42679476,-2.580143228,49.5508,6.75076487,7.378429468,-2.9665625,-1.8246222,-3.415970192,47.54347829 +116.53,50.42679537,-2.58014219,49.5806,6.764669671,7.377097041,-2.98625,-1.792139389,-3.405329965,47.53595318 +116.54,50.42679598,-2.580141152,49.6106,6.764669704,7.375986674,-3.003125,-1.75823805,-3.391720326,47.52842812 +116.55,50.42679659,-2.580140114,49.6407,6.750764967,7.374876308,-3.018125,-1.7229254,-3.375153022,47.52090301 +116.56,50.42679719,-2.580139076,49.6709,6.747288807,7.373765943,-3.0334375,-1.686208718,-3.355642549,47.51337795 +116.57,50.4267978,-2.580138039,49.7014,6.75076503,7.373543823,-3.0478125,-1.648095737,-3.333205866,47.50585284 +116.58,50.42679841,-2.580137001,49.7319,6.747288862,7.373543764,-3.0596875,-1.608594365,-3.307862624,47.49832778 +116.59,50.42679901,-2.580135963,49.7626,6.750765077,7.372211338,-3.07,-1.567712852,-3.279634827,47.49080267 +116.6,50.42679962,-2.580134926,49.7933,6.76466988,7.370212728,-3.0796875,-1.525459793,-3.248547169,47.48327761 +116.61,50.42680023,-2.580133889,49.8242,6.764669924,7.369102362,-3.088125,-1.481843954,-3.214626749,47.4757525 +116.62,50.42680084,-2.580132852,49.8551,6.750765197,7.368658181,-3.0946875,-1.436874502,-3.177903134,47.46822744 +116.63,50.42680144,-2.580131815,49.8861,6.750765233,7.367769878,-3.1,-1.390560777,-3.138408294,47.46070233 +116.64,50.42680205,-2.580130778,49.9171,6.768146229,7.366659513,-3.1046875,-1.34291246,-3.096176721,47.45317728 +116.65,50.42680266,-2.580129742,49.9482,6.77857484,7.366437393,-3.108125,-1.293939466,-3.051245256,47.44565216 +116.66,50.42680327,-2.580128705,49.9793,6.768146296,7.366437335,-3.109375,-1.243652106,-3.003653032,47.43812711 +116.67,50.42680388,-2.580127668,50.0104,6.750765367,7.365104909,-3.1084375,-1.192060809,-2.953441647,47.43060199 +116.68,50.42680448,-2.580126632,50.0415,6.750765401,7.3631063,-3.1065625,-1.139176403,-2.900654759,47.42307694 +116.69,50.42680509,-2.580125596,50.0725,6.768146393,7.361995934,-3.1046875,-1.085009947,-2.845338434,47.41555183 +116.7,50.4268057,-2.58012456,50.1036,6.78205118,7.361773814,-3.1015625,-1.029572671,-2.787540972,47.40802677 +116.71,50.42680631,-2.580123524,50.1346,6.785527384,7.361551694,-3.09625,-0.972876205,-2.727312737,47.40050166 +116.72,50.42680692,-2.580122488,50.1655,6.782051225,7.360663391,-3.09,-0.914932353,-2.664706212,47.3929766 +116.73,50.42680753,-2.580121452,50.1964,6.768146509,7.359330965,-3.083125,-0.855753262,-2.599776056,47.38545149 +116.74,50.42680814,-2.580120417,50.2272,6.750765597,7.358220601,-3.074375,-0.795351249,-2.532578879,47.37792643 +116.75,50.42680874,-2.580119381,50.2579,6.750765635,7.357332296,-3.0634375,-0.733738977,-2.463173178,47.37040132 +116.76,50.42680935,-2.580118346,50.2885,6.768146632,7.356666053,-3.05125,-0.670929338,-2.39161963,47.36287626 +116.77,50.42680996,-2.580117311,50.3189,6.782051436,7.35599981,-3.038125,-0.606935338,-2.317980516,47.35535115 +116.78,50.42681057,-2.580116275,50.3493,6.785527662,7.354667383,-3.0234375,-0.541770385,-2.242320064,47.34782609 +116.79,50.42681118,-2.580115241,50.3794,6.785527692,7.353557018,-3.0078125,-0.475448113,-2.164704336,47.34030098 +116.8,50.42681179,-2.580114206,50.4094,6.785527716,7.353556959,-2.9915625,-0.40798239,-2.085200942,47.33277593 +116.81,50.4268124,-2.580113171,50.4393,6.785527737,7.353334837,-2.973125,-0.339387253,-2.003879208,47.32525081 +116.82,50.42681301,-2.580112136,50.4689,6.78552777,7.35222447,-2.953125,-0.269677082,-1.920810011,47.31772576 +116.83,50.42681362,-2.580111102,50.4983,6.785527813,7.350892042,-2.933125,-0.198866431,-1.836065886,47.31020064 +116.84,50.42681423,-2.580110067,50.5276,6.785527853,7.349115492,-2.91125,-0.126970026,-1.749720688,47.30267559 +116.85,50.42681484,-2.580109033,50.5566,6.785527887,7.347338942,-2.8865625,-0.054002876,-1.661849704,47.29515047 +116.86,50.42681545,-2.580108,50.5853,6.785527919,7.346672696,-2.8615625,0.020019661,-1.572529594,47.28762542 +116.87,50.42681606,-2.580106965,50.6138,6.78552795,7.346228512,-2.8365625,0.095082232,-1.481838167,47.28010036 +116.88,50.42681667,-2.580105932,50.6421,6.78552798,7.345118144,-2.8096875,0.171169136,-1.389854549,47.27257525 +116.89,50.42681728,-2.580104898,50.67,6.785528009,7.344451899,-2.7815625,0.248264503,-1.29665901,47.26505019 +116.9,50.42681789,-2.580103865,50.6977,6.78552803,7.344895958,-2.753125,0.326352176,-1.202332739,47.25752508 +116.91,50.4268185,-2.580102831,50.7251,6.785528049,7.345117957,-2.7228125,0.405415883,-1.106958013,47.25000002 +116.92,50.42681911,-2.580101797,50.7522,6.785528078,7.343785527,-2.69,0.485439122,-1.010617967,47.24247491 +116.93,50.42681972,-2.580100764,50.7789,6.785528119,7.341564851,-2.6565625,0.566405163,-0.913396712,47.23494986 +116.94,50.42682033,-2.580099731,50.8053,6.785528156,7.339566236,-2.623125,0.648297104,-0.815378931,47.22742474 +116.95,50.42682094,-2.580098698,50.8314,6.785528187,7.338233805,-2.588125,0.731097871,-0.71665011,47.21989969 +116.96,50.42682155,-2.580097666,50.8571,6.785528215,7.338011679,-2.5515625,0.814790102,-0.617296363,47.21237457 +116.97,50.42682216,-2.580096633,50.8824,6.785528243,7.338233675,-2.5146875,0.899356381,-0.517404323,47.20484952 +116.98,50.42682277,-2.5800956,50.9074,6.785528268,7.337789487,-2.4765625,0.984779003,-0.417061136,47.19732441 +116.99,50.42682338,-2.580094568,50.932,6.785528284,7.336901176,-2.43625,1.071040205,-0.316354235,47.18979935 +117,50.42682399,-2.580093535,50.9561,6.789004483,7.335790804,-2.395,1.158121883,-0.215371455,47.18227424 +117.01,50.4268246,-2.580092503,50.9799,6.802909271,7.33445837,-2.3534375,1.246005874,-0.114200916,47.17474918 +117.02,50.42682521,-2.580091471,51.0032,6.820290273,7.333347996,-2.31125,1.334673843,-0.012930741,47.16722407 +117.03,50.42682583,-2.580090439,51.0261,6.820290318,7.332237622,-2.2684375,1.424107284,0.088350665,47.15969901 +117.04,50.42682644,-2.580089407,51.0486,6.802909388,7.330905186,-2.224375,1.514287517,0.189555065,47.1521739 +117.05,50.42682705,-2.580088376,51.0706,6.789004642,7.330016873,-2.178125,1.605195694,0.29059411,47.14464884 +117.06,50.42682766,-2.580087344,51.0922,6.789004663,7.329794742,-2.1303125,1.696812791,0.39137985,47.13712373 +117.07,50.42682827,-2.580086313,51.1132,6.802909451,7.32957261,-2.083125,1.789119787,0.491824221,47.12959867 +117.08,50.42682888,-2.580085281,51.1338,6.820290429,7.328684294,-2.0365625,1.882097258,0.591839734,47.12207356 +117.09,50.4268295,-2.58008425,51.154,6.820290451,7.327351856,-1.9878125,1.975725896,0.691339183,47.1145485 +117.1,50.42683011,-2.580083219,51.1736,6.802909517,7.326241479,-1.9365625,2.069986162,0.79023571,47.10702339 +117.11,50.42683072,-2.580082188,51.1927,6.792480967,7.325131101,-1.885,2.164858233,0.888443197,47.09949834 +117.12,50.42683133,-2.580081157,51.2113,6.80290957,7.324020722,-1.8334375,2.260322455,0.98587593,47.09197322 +117.13,50.42683194,-2.580080127,51.2294,6.820290556,7.323798587,-1.78125,2.356358776,1.082448998,47.08444817 +117.14,50.42683256,-2.580079096,51.2469,6.820290576,7.323798512,-1.7284375,2.452947256,1.178078118,47.07692305 +117.15,50.42683317,-2.580078065,51.264,6.802909626,7.322466071,-1.6746875,2.550067613,1.272679924,47.069398 +117.16,50.42683378,-2.580077035,51.2804,6.792481055,7.320467445,-1.6196875,2.647699564,1.366171969,47.06187289 +117.17,50.42683439,-2.580076005,51.2964,6.802909642,7.319357063,-1.56375,2.745822827,1.458472662,47.05434783 +117.18,50.426835,-2.580074975,51.3117,6.820290626,7.319134925,-1.5078125,2.844416831,1.549501561,47.04682272 +117.19,50.42683562,-2.580073945,51.3265,6.823766845,7.318912787,-1.451875,2.943460951,1.639179253,47.03929766 +117.2,50.42683623,-2.580072915,51.3408,6.820290667,7.317802403,-1.3946875,3.042934618,1.727427588,47.03177255 +117.21,50.42683684,-2.580071885,51.3544,6.823766867,7.315803774,-1.3365625,3.142816975,1.814169559,47.02424749 +117.22,50.42683746,-2.580070856,51.3675,6.820290686,7.314471328,-1.2784375,3.243087167,1.899329537,47.01672244 +117.23,50.42683807,-2.580069827,51.38,6.806385929,7.314471247,-1.2196875,3.343724282,1.982833323,47.00919732 +117.24,50.42683868,-2.580068797,51.3919,6.80638594,7.314249106,-1.1596875,3.444707291,2.064607979,47.00167227 +117.25,50.42683929,-2.580067768,51.4032,6.820290729,7.312916658,-1.0984375,3.54601511,2.144582288,46.99414715 +117.26,50.42683991,-2.580066739,51.4139,6.823766946,7.311140087,-1.036875,3.64762654,2.222686519,46.9866221 +117.27,50.42684052,-2.58006571,51.4239,6.820290772,7.309807637,-0.9765625,3.749520437,2.298852549,46.97909698 +117.28,50.42684113,-2.580064682,51.4334,6.827243172,7.309585492,-0.9165625,3.851675432,2.373013857,46.97157193 +117.29,50.42684175,-2.580063653,51.4423,6.837671761,7.309807469,-0.8546875,3.954070266,2.445105928,46.96404682 +117.3,50.42684236,-2.580062624,51.4505,6.837671761,7.309363261,-0.791875,4.05668357,2.515065851,46.95652176 +117.31,50.42684298,-2.580061596,51.4581,6.827243179,7.30825287,-0.73,4.159493798,2.582832549,46.94899665 +117.32,50.42684359,-2.580060567,51.4651,6.8202908,7.306254234,-0.668125,4.262479582,2.648347007,46.94147159 +117.33,50.4268442,-2.580059539,51.4715,6.823767012,7.303811475,-0.6046875,4.365619433,2.711552044,46.93394648 +117.34,50.42684482,-2.580058512,51.4772,6.823767028,7.302923143,-0.54,4.468891695,2.772392598,46.92642142 +117.35,50.42684543,-2.580057484,51.4823,6.820290843,7.303589237,-0.4753125,4.572274939,2.830815558,46.91889631 +117.36,50.42684604,-2.580056456,51.4867,6.827243231,7.303589148,-0.4115625,4.67574745,2.886770043,46.91137125 +117.37,50.42684666,-2.580055428,51.4905,6.837671798,7.302478752,-0.3484375,4.779287742,2.940207181,46.90384614 +117.38,50.42684727,-2.580054401,51.4937,6.841147974,7.301368356,-0.2846875,4.882874042,2.99108039,46.89632108 +117.39,50.42684789,-2.580053373,51.4962,6.841147977,7.30048002,-0.22,4.986484865,3.039345381,46.88879597 +117.4,50.4268485,-2.580052346,51.4981,6.841148002,7.299813745,-0.1553125,5.090098496,3.084960041,46.88127092 +117.41,50.42684912,-2.580051319,51.4993,6.841148022,7.299147468,-0.0915625,5.193693333,3.127884492,46.8737458 +117.42,50.42684973,-2.580050291,51.4999,6.841148025,7.297815008,-0.0284375,5.297247662,3.168081434,46.86622075 +117.43,50.42685035,-2.580049265,51.4999,6.841148017,7.296482547,0.0353125,5.400739997,3.205515746,46.85869563 +117.44,50.42685096,-2.580048238,51.4992,6.841148006,7.295816269,0.1,5.504148566,3.240154827,46.85117058 +117.45,50.42685158,-2.580047211,51.4979,6.841148005,7.295149989,0.165,5.607451883,3.271968423,46.84364546 +117.46,50.42685219,-2.580046185,51.4959,6.841148015,7.294261649,0.23,5.710628346,3.300928804,46.83612041 +117.47,50.42685281,-2.580045158,51.4933,6.841148022,7.293151246,0.295,5.813656356,3.327010759,46.8285953 +117.48,50.42685342,-2.580044132,51.49,6.841148019,7.291818781,0.36,5.916514485,3.350191486,46.82107024 +117.49,50.42685404,-2.580043106,51.4861,6.841148007,7.290930437,0.4246875,6.019181245,3.370450758,46.81354513 +117.5,50.42685465,-2.58004208,51.4815,6.841147992,7.290708277,0.488125,6.121635094,3.387770985,46.80602007 +117.51,50.42685527,-2.580041054,51.4763,6.841147987,7.290486116,0.55,6.223854776,3.402137043,46.79849496 +117.52,50.42685588,-2.580040028,51.4705,6.841147992,7.28937571,0.611875,6.325818803,3.413536382,46.7909699 +117.53,50.4268565,-2.580039002,51.4641,6.841147995,7.287377059,0.675,6.427505978,3.421959033,46.78344479 +117.54,50.42685711,-2.580037977,51.457,6.841147986,7.28604459,0.7384375,6.528895042,3.427397721,46.77591973 +117.55,50.42685773,-2.580036952,51.4493,6.844624154,7.286044486,0.80125,6.629964797,3.429847688,46.76839462 +117.56,50.42685834,-2.580035926,51.441,6.855052704,7.285822321,0.8634375,6.730694215,3.429306701,46.76086956 +117.57,50.42685896,-2.580034901,51.432,6.862005082,7.284489851,0.925,6.831062154,3.425775391,46.75334451 +117.58,50.42685958,-2.580033876,51.4225,6.855052708,7.282713257,0.9865625,6.931047644,3.419256678,46.7458194 +117.59,50.42686019,-2.580032851,51.4123,6.844624135,7.281158724,1.0484375,7.030629943,3.40975635,46.73829434 +117.6,50.42686081,-2.580031827,51.4015,6.844624126,7.280270373,1.1096875,7.129788139,3.397282715,46.73076923 +117.61,50.42686142,-2.580030802,51.3901,6.855052686,7.280048204,1.1696875,7.228501548,3.381846545,46.72324417 +117.62,50.42686204,-2.580029778,51.3781,6.86200505,7.279826035,1.2284375,7.326749601,3.36346136,46.71571906 +117.63,50.42686266,-2.580028753,51.3655,6.858528844,7.279159744,1.2865625,7.424511728,3.342143205,46.708194 +117.64,50.42686327,-2.580027729,51.3524,6.858528841,7.278493452,1.345,7.521767475,3.317910585,46.70066889 +117.65,50.42686389,-2.580026705,51.3386,6.862005027,7.277827159,1.403125,7.618496616,3.290784758,46.69314383 +117.66,50.42686451,-2.58002568,51.3243,6.858528812,7.276494681,1.4596875,7.714678926,3.260789329,46.68561872 +117.67,50.42686512,-2.580024657,51.3094,6.858528786,7.275162204,1.5153125,7.810294295,3.227950425,46.67809366 +117.68,50.42686574,-2.580023633,51.294,6.862004964,7.274273848,1.5715625,7.905322783,3.192296693,46.67056855 +117.69,50.42686636,-2.580022609,51.278,6.858528763,7.272941369,1.628125,7.999744566,3.153859247,46.6630435 +117.7,50.42686697,-2.580021586,51.2614,6.862004937,7.271830951,1.683125,8.09353982,3.112671603,46.65551838 +117.71,50.42686759,-2.580020563,51.2443,6.875909675,7.271830837,1.7365625,8.186689064,3.068769628,46.64799333 +117.72,50.42686821,-2.580019539,51.2267,6.875909645,7.271608662,1.79,8.279172817,3.022191655,46.64046821 +117.73,50.42686883,-2.580018516,51.2085,6.862004864,7.270498241,1.843125,8.370971771,2.972978247,46.63294316 +117.74,50.42686944,-2.580017493,51.1898,6.862004865,7.269387821,1.894375,8.462066732,2.921172434,46.62541804 +117.75,50.42687006,-2.58001647,51.1706,6.875909629,7.268055339,1.9434375,8.552438678,2.866819252,46.61789299 +117.76,50.42687068,-2.580015447,51.1509,6.875909609,7.266056673,1.991875,8.6420687,2.809966197,46.61036788 +117.77,50.4268713,-2.580014425,51.1308,6.862004806,7.264724189,2.0415625,8.730938178,2.750662773,46.60284282 +117.78,50.42687191,-2.580013403,51.1101,6.862004773,7.264724071,2.0915625,8.819028491,2.688960776,46.59531771 +117.79,50.42687253,-2.58001238,51.0889,6.879385717,7.264501892,2.139375,8.90632119,2.624913949,46.58779265 +117.8,50.42687315,-2.580011358,51.0673,6.889814285,7.263391468,2.185,8.992798168,2.558578156,46.58026754 +117.81,50.42687377,-2.580010336,51.0452,6.879385687,7.262281044,2.23,9.078441264,2.490011209,46.57274248 +117.82,50.42687439,-2.580009314,51.0227,6.862004682,7.261170619,2.2746875,9.163232658,2.41927298,46.56521737 +117.83,50.426875,-2.580008292,50.9997,6.862004636,7.259838133,2.318125,9.247154588,2.346425063,46.55769231 +117.84,50.42687562,-2.580007271,50.9763,6.879385577,7.258949768,2.36,9.33018958,2.271531057,46.5501672 +117.85,50.42687624,-2.580006249,50.9525,6.893290347,7.258727586,2.4015625,9.412320272,2.194656278,46.54264214 +117.86,50.42687686,-2.580005228,50.9283,6.893290337,7.258505403,2.443125,9.493529476,2.115867706,46.53511703 +117.87,50.42687748,-2.580004206,50.9036,6.879385534,7.257617037,2.4828125,9.573800291,2.035234037,46.52759198 +117.88,50.4268781,-2.580003185,50.8786,6.862004531,7.256284548,2.5196875,9.653115927,1.952825632,46.52006686 +117.89,50.42687871,-2.580002164,50.8532,6.862004504,7.25517412,2.5553125,9.731459827,1.868714339,46.51254181 +117.9,50.42687933,-2.580001143,50.8275,6.879385454,7.254063692,2.5915625,9.808815603,1.782973497,46.50501675 +117.91,50.42687995,-2.580000122,50.8014,6.893290206,7.252731203,2.628125,9.8851671,1.695677877,46.49749164 +117.92,50.42688057,-2.579999102,50.7749,6.896766364,7.251842835,2.6628125,9.960498387,1.606903567,46.48996658 +117.93,50.42688119,-2.579998081,50.7481,6.896766325,7.251620649,2.695,10.03479377,1.516728031,46.48244147 +117.94,50.42688181,-2.579997061,50.721,6.896766296,7.251398462,2.7265625,10.10803771,1.425229937,46.47491641 +117.95,50.42688243,-2.57999604,50.6936,6.896766274,7.250510092,2.758125,10.18021487,1.332488983,46.4673913 +117.96,50.42688305,-2.57999502,50.6658,6.893290043,7.249177601,2.7878125,10.25131022,1.238586071,46.45986624 +117.97,50.42688367,-2.579994,50.6378,6.879385222,7.248289231,2.8146875,10.32130893,1.143603075,46.45234113 +117.98,50.42688429,-2.57999298,50.6095,6.862004227,7.247844983,2.84,10.39019634,1.047622847,46.44481608 +117.99,50.4268849,-2.57999196,50.581,6.862004219,7.246956613,2.865,10.45795805,0.950729095,46.43729096 +118,50.42688552,-2.57999094,50.5522,6.879385169,7.245624121,2.89,10.52457998,0.85300633,46.42976591 +118.01,50.42688614,-2.579989921,50.5232,6.893289906,7.24451369,2.914375,10.59004814,0.754539694,46.42224079 +118.02,50.42688676,-2.579988901,50.4939,6.896766057,7.243403258,2.9365625,10.65434884,0.655415074,46.41471574 +118.03,50.42688738,-2.579987882,50.4644,6.896766026,7.242070765,2.95625,10.7174688,0.555718927,46.40719062 +118.04,50.426888,-2.579986863,50.4348,6.896766005,7.241182393,2.975,10.77939465,0.455538174,46.39966557 +118.05,50.42688862,-2.579985844,50.4049,6.89676598,7.240738143,2.9934375,10.84011362,0.354960246,46.39214046 +118.06,50.42688924,-2.579984825,50.3749,6.89676594,7.23984977,3.01125,10.89961294,0.254072748,46.3846154 +118.07,50.42688986,-2.579983806,50.3447,6.896765888,7.238517276,3.0278125,10.95788017,0.152963688,46.37709029 +118.08,50.42689048,-2.579982788,50.3143,6.900242038,7.237628904,3.0415625,11.01490322,0.051721244,46.36956523 +118.09,50.4268911,-2.579981769,50.2838,6.914146785,7.237406715,3.053125,11.07067006,-0.04956635,46.36204012 +118.1,50.42689172,-2.579980751,50.2533,6.931527728,7.237184525,3.0646875,11.12516918,-0.150810628,46.35451506 +118.11,50.42689235,-2.579979732,50.2225,6.931527696,7.236296152,3.075,11.17838911,-0.251923469,46.34698995 +118.12,50.42689297,-2.579978714,50.1917,6.914146701,7.234741596,3.0828125,11.23031879,-0.352816581,46.33946489 +118.13,50.42689359,-2.579977696,50.1609,6.900241908,7.23296498,3.0903125,11.28094735,-0.453402072,46.33193978 +118.14,50.42689421,-2.579976678,50.1299,6.89676569,7.231410425,3.0978125,11.33026418,-0.553592165,46.32441472 +118.15,50.42689483,-2.579975661,50.0989,6.89676565,7.230522052,3.1028125,11.37825902,-0.653299541,46.31688961 +118.16,50.42689545,-2.579974643,50.0678,6.896765606,7.230299862,3.105,11.42492185,-0.752437168,46.30936456 +118.17,50.42689607,-2.579973626,50.0368,6.896765573,7.230077671,3.1065625,11.47024292,-0.850918701,46.30183944 +118.18,50.42689669,-2.579972608,50.0057,6.896765547,7.229189298,3.1084375,11.51421279,-0.948658254,46.29431439 +118.19,50.42689731,-2.579971591,49.9746,6.900241698,7.227856804,3.109375,11.55682223,-1.045570512,46.28678927 +118.2,50.42689793,-2.579970574,49.9435,6.914146416,7.226968431,3.108125,11.59806236,-1.141571023,46.27926422 +118.21,50.42689855,-2.579969557,49.9124,6.931527346,7.22652418,3.1046875,11.63792458,-1.236576077,46.2717391 +118.22,50.42689918,-2.57996854,49.8814,6.931527333,7.225635807,3.1,11.67640053,-1.330502825,46.26421405 +118.23,50.4268998,-2.579967523,49.8504,6.914146346,7.224303312,3.0946875,11.71348218,-1.423269333,46.25668894 +118.24,50.42690042,-2.579966507,49.8195,6.900241536,7.223414939,3.0878125,11.74916187,-1.514794757,46.24916388 +118.25,50.42690104,-2.57996549,49.7886,6.900241503,7.22319275,3.0784375,11.78343202,-1.604999284,46.24163882 +118.26,50.42690166,-2.579964474,49.7579,6.91414625,7.2227485,3.068125,11.8162856,-1.69380419,46.23411371 +118.27,50.42690228,-2.579963457,49.7273,6.93152718,7.220971884,3.058125,11.8477156,-1.781132068,46.22658866 +118.28,50.42690291,-2.579962441,49.6967,6.931527137,7.218529086,3.04625,11.87771561,-1.866906772,46.21906354 +118.29,50.42690353,-2.579961426,49.6663,6.917622326,7.217640714,3.03125,11.90627927,-1.951053474,46.21153849 +118.3,50.42690415,-2.57996041,49.6361,6.917622291,7.218306768,3.0153125,11.93340069,-2.033498892,46.20401337 +118.31,50.42690477,-2.579959394,49.606,6.931527029,7.218306639,2.9996875,11.95907413,-2.114171063,46.19648832 +118.32,50.4269054,-2.579958378,49.5761,6.931527,7.217196207,2.9828125,11.9832942,-2.192999628,46.1889632 +118.33,50.42690602,-2.579957363,49.5463,6.917622207,7.216085775,2.9634375,12.00605598,-2.269915831,46.18143815 +118.34,50.42690664,-2.579956347,49.5168,6.917622187,7.214975344,2.9428125,12.0273546,-2.344852695,46.17391304 +118.35,50.42690726,-2.579955332,49.4875,6.931526925,7.213642852,2.921875,12.04718564,-2.417744787,46.16638798 +118.36,50.42690789,-2.579954317,49.4583,6.931526886,7.212532421,2.8996875,12.06554498,-2.488528508,46.15886287 +118.37,50.42690851,-2.579953302,49.4295,6.917622085,7.21142199,2.87625,12.08242873,-2.557142267,46.15133781 +118.38,50.42690913,-2.579952287,49.4008,6.917622062,7.210089498,2.8515625,12.09783345,-2.623526131,46.1438127 +118.39,50.42690975,-2.579951273,49.3724,6.931526792,7.209201128,2.824375,12.11175586,-2.687622289,46.13628764 +118.4,50.42691038,-2.579950258,49.3443,6.935002935,7.208978942,2.7953125,12.12419311,-2.749374764,46.12876253 +118.41,50.426911,-2.579949244,49.3165,6.931526713,7.208756755,2.7665625,12.13514251,-2.808729754,46.12123747 +118.42,50.42691162,-2.579948229,49.289,6.935002896,7.207868387,2.738125,12.14460187,-2.865635464,46.11371236 +118.43,50.42691225,-2.579947215,49.2617,6.935002876,7.206535898,2.7078125,12.15256914,-2.920042333,46.1061873 +118.44,50.42691287,-2.579946201,49.2348,6.931526649,7.205425469,2.6746875,12.1590427,-2.971902862,46.09866219 +118.45,50.42691349,-2.579945187,49.2082,6.935002813,7.204315041,2.64,12.16402119,-3.021171847,46.09113714 +118.46,50.42691412,-2.579944173,49.182,6.935002794,7.202982553,2.605,12.16750357,-3.067806314,46.08361202 +118.47,50.42691474,-2.57994316,49.1561,6.931526574,7.201872125,2.57,12.1694891,-3.111765642,46.07608697 +118.48,50.42691536,-2.579942146,49.1306,6.93847892,7.200761699,2.534375,12.16997737,-3.153011441,46.06856185 +118.49,50.42691599,-2.579941133,49.1054,6.948907461,7.199429212,2.4965625,12.16896828,-3.19150773,46.0610368 +118.5,50.42691661,-2.57994012,49.0806,6.948907433,7.198540846,2.4565625,12.16646204,-3.227221049,46.05351168 +118.51,50.42691724,-2.579939107,49.0563,6.938478831,7.198318663,2.4165625,12.16245919,-3.260120114,46.04598663 +118.52,50.42691786,-2.579938094,49.0323,6.931526423,7.198318542,2.3765625,12.15696051,-3.290176391,46.03846152 +118.53,50.42691848,-2.579937081,49.0087,6.938478789,7.198318421,2.334375,12.14996728,-3.317363525,46.03093646 +118.54,50.42691911,-2.579936068,48.9856,6.948907346,7.19809624,2.29,12.1414808,-3.341657852,46.02341135 +118.55,50.42691973,-2.579935055,48.9629,6.94890732,7.196985816,2.245,12.13150291,-3.363038231,46.01588629 +118.56,50.42692036,-2.579934042,48.9407,6.938478722,7.194987151,2.2,12.12003573,-3.381485982,46.00836118 +118.57,50.42692098,-2.57993303,48.9189,6.931526321,7.193432607,2.155,12.10708162,-3.396985064,46.00083612 +118.58,50.4269216,-2.579932018,48.8976,6.938478674,7.192544246,2.109375,12.09264325,-3.409521896,45.99331101 +118.59,50.42692223,-2.579931005,48.8767,6.948907209,7.191211764,2.0615625,12.07672373,-3.419085593,45.98578595 +118.6,50.42692285,-2.579929994,48.8563,6.952383379,7.189879283,2.0115625,12.05932627,-3.425667789,45.9782609 +118.61,50.42692348,-2.579928982,48.8365,6.952383378,7.189212984,1.9615625,12.04045459,-3.429262698,45.97073578 +118.62,50.4269241,-2.57992797,48.8171,6.952383367,7.188546686,1.911875,12.02011258,-3.429867283,45.96321073 +118.63,50.42692473,-2.579926959,48.7982,6.95238334,7.187880388,1.86125,11.99830455,-3.427480971,45.95568562 +118.64,50.42692535,-2.579925947,48.7799,6.952383319,7.187658213,1.8096875,11.97503501,-3.422105882,45.94816056 +118.65,50.42692598,-2.579924936,48.762,6.952383302,7.187436037,1.7565625,11.95030879,-3.4137466,45.94063545 +118.66,50.4269266,-2.579923924,48.7447,6.95238328,7.18632562,1.7015625,11.92413109,-3.402410516,45.93311039 +118.67,50.42692723,-2.579922913,48.728,6.955859448,7.1841049,1.646875,11.89650736,-3.388107484,45.92558528 +118.68,50.42692785,-2.579921902,48.7118,6.966288004,7.182106242,1.593125,11.86744345,-3.370849937,45.91806022 +118.69,50.42692848,-2.579920892,48.6961,6.973240372,7.181662008,1.538125,11.83694531,-3.350653003,45.91053511 +118.7,50.42692911,-2.579919881,48.681,6.966287975,7.181883957,1.48125,11.80501935,-3.327534214,45.90301005 +118.71,50.42692973,-2.57991887,48.6665,6.95585939,7.181439725,1.4234375,11.77167229,-3.301513794,45.89548494 +118.72,50.42693036,-2.57991786,48.6525,6.952383188,7.180551373,1.365,11.736911,-3.272614375,45.88795988 +118.73,50.42693098,-2.579916849,48.6392,6.952383172,7.179440961,1.3065625,11.70074287,-3.240861226,45.88043477 +118.74,50.42693161,-2.579915839,48.6264,6.955859353,7.178108488,1.2484375,11.66317529,-3.206281963,45.87290972 +118.75,50.42693223,-2.579914829,48.6142,6.966287923,7.177220137,1.1896875,11.62421622,-3.16890678,45.8653846 +118.76,50.42693286,-2.579913819,48.6026,6.973240286,7.176775907,1.13,11.5838738,-3.128768279,45.85785955 +118.77,50.42693349,-2.579912809,48.5916,6.969764063,7.175665498,1.07,11.5421564,-3.085901468,45.85033443 +118.78,50.42693411,-2.579911799,48.5812,6.96976405,7.173666847,1.0096875,11.49907278,-3.040343645,45.84280938 +118.79,50.42693474,-2.57991079,48.5714,6.973240245,7.172334378,0.9484375,11.45463189,-2.992134632,45.83528426 +118.8,50.42693537,-2.579909781,48.5622,6.969764051,7.172334273,0.8865625,11.40884299,-2.941316427,45.82775921 +118.81,50.42693599,-2.579908771,48.5537,6.969764047,7.172112108,0.825,11.36171572,-2.887933377,45.8202341 +118.82,50.42693662,-2.579907762,48.5457,6.973240239,7.171001701,0.763125,11.31325994,-2.832031947,45.81270904 +118.83,50.42693725,-2.579906753,48.5384,6.96976404,7.169891295,0.6996875,11.26348566,-2.773661012,45.80518393 +118.84,50.42693787,-2.579905744,48.5317,6.969764023,7.16878089,0.6353125,11.21240332,-2.712871336,45.79765887 +118.85,50.4269385,-2.579904735,48.5257,6.973240198,7.167448426,0.5715625,11.16002363,-2.649716032,45.79013376 +118.86,50.42693913,-2.579903727,48.5203,6.969763992,7.166338022,0.5084375,11.10635748,-2.584250161,45.7826087 +118.87,50.42693975,-2.579902718,48.5155,6.969763985,7.16544968,0.445,11.0514161,-2.516530732,45.77508359 +118.88,50.42694038,-2.57990171,48.5114,6.973240184,7.164783399,0.3815625,10.99521095,-2.446616875,45.76755853 +118.89,50.42694101,-2.579900702,48.5079,6.969764,7.16411712,0.3184375,10.93775382,-2.374569552,45.76003342 +118.9,50.42694163,-2.579899693,48.505,6.97324019,7.162784659,0.2546875,10.87905665,-2.300451502,45.75250836 +118.91,50.42694226,-2.579898686,48.5028,6.987144958,7.161674259,0.19,10.81913168,-2.22432747,45.74498325 +118.92,50.42694289,-2.579897678,48.5012,6.987144964,7.161674162,0.125,10.75799147,-2.146263804,45.7374582 +118.93,50.42694352,-2.57989667,48.5003,6.973240187,7.161452006,0.06,10.69564879,-2.066328571,45.72993308 +118.94,50.42694414,-2.579895662,48.5,6.973240168,7.160341609,-0.0046875,10.63211665,-1.984591444,45.72240803 +118.95,50.42694477,-2.579894655,48.5004,6.990621126,7.159231212,-0.0684375,10.56740829,-1.901123754,45.71488297 +118.96,50.4269454,-2.579893647,48.5014,7.001049717,7.158120816,-0.131875,10.50153728,-1.815998211,45.70735786 +118.97,50.42694603,-2.57989264,48.503,6.99062115,7.156788359,-0.1965625,10.43451731,-1.729289128,45.6998328 +118.98,50.42694666,-2.579891633,48.5053,6.973240196,7.155900025,-0.2615625,10.36636244,-1.641072019,45.69230769 +118.99,50.42694728,-2.579890626,48.5083,6.973240202,7.155455813,-0.325,10.29708686,-1.551423949,45.68478263 +119,50.42694791,-2.579889619,48.5118,6.990621162,7.15434542,-0.3884375,10.22670506,-1.460422953,45.67725752 +119.01,50.42694854,-2.579888612,48.516,7.001049734,7.152346785,-0.4534375,10.15523173,-1.368148501,45.66973246 +119.02,50.42694917,-2.579887606,48.5209,6.990621156,7.151014332,-0.518125,10.08268181,-1.274680979,45.66220735 +119.03,50.4269498,-2.5798866,48.5264,6.973240201,7.151014244,-0.5815625,10.00907037,-1.180101919,45.6546823 +119.04,50.42695042,-2.579885593,48.5325,6.97324022,7.150792097,-0.645,9.934412937,-1.08449377,45.64715718 +119.05,50.42695105,-2.579884587,48.5393,6.990621198,7.149681708,-0.708125,9.858724983,-0.987939953,45.63963213 +119.06,50.42695168,-2.579883581,48.5467,7.004525975,7.148793379,-0.7696875,9.782022321,-0.890524638,45.63210701 +119.07,50.42695231,-2.579882575,48.5547,7.008002174,7.148349172,-0.8303125,9.704320993,-0.792332735,45.62458196 +119.08,50.42695294,-2.579881569,48.5633,7.008002178,7.147460845,-0.891875,9.625637272,-0.693449903,45.61705684 +119.09,50.42695357,-2.579880563,48.5725,7.004525983,7.146128398,-0.955,9.545987487,-0.593962428,45.60953179 +119.1,50.4269542,-2.579879558,48.5824,6.990621227,7.145018012,-1.0178125,9.465388368,-0.493956999,45.60200668 +119.11,50.42695483,-2.579878552,48.5929,6.973240293,7.143907627,-1.078125,9.383856703,-0.393520821,45.59448162 +119.12,50.42695545,-2.579877547,48.604,6.973240313,7.142575182,-1.136875,9.301409566,-0.292741441,45.58695651 +119.13,50.42695608,-2.579876542,48.6156,6.990621288,7.141686859,-1.1965625,9.218064088,-0.191706865,45.57943145 +119.14,50.42695671,-2.579875537,48.6279,7.004526072,7.141242657,-1.2565625,9.133837745,-0.090505044,45.57190634 +119.15,50.42695734,-2.579874532,48.6408,7.008002275,7.140354334,-1.3146875,9.04874807,0.010775617,45.56438128 +119.16,50.42695797,-2.579873527,48.6542,7.008002281,7.139021891,-1.371875,8.96281288,0.112046939,45.55685617 +119.17,50.4269586,-2.579872523,48.6682,7.008002289,7.13813357,-1.43,8.87605011,0.213220571,45.54933111 +119.18,50.42695923,-2.579871518,48.6828,7.008002303,7.137911432,-1.488125,8.788477866,0.314208221,45.541806 +119.19,50.42695986,-2.579870514,48.698,7.008002332,7.137689294,-1.5446875,8.700114481,0.414921883,45.53428094 +119.2,50.42696049,-2.579869509,48.7137,7.008002361,7.136800975,-1.6,8.610978349,0.515273779,45.52675583 +119.21,50.42696112,-2.579868505,48.73,7.00800238,7.135468536,-1.655,8.521088146,0.615176305,45.51923078 +119.22,50.42696175,-2.579867501,48.7468,7.008002397,7.134358158,-1.7096875,8.430462552,0.71454237,45.51170566 +119.23,50.42696238,-2.579866497,48.7642,7.00800241,7.13324778,-1.763125,8.339120589,0.813285401,45.50418061 +119.24,50.42696301,-2.579865493,48.7821,7.008002417,7.131915342,-1.8146875,8.247081279,0.911319224,45.49665549 +119.25,50.42696364,-2.57986449,48.8005,7.008002438,7.130804966,-1.8653125,8.154363874,1.008558298,45.48913044 +119.26,50.42696427,-2.579863486,48.8194,7.008002473,7.12969459,-1.9165625,8.060987681,1.104917939,45.48160532 +119.27,50.4269649,-2.579862483,48.8388,7.008002502,7.128362155,-1.968125,7.96697224,1.200314094,45.47408027 +119.28,50.42696553,-2.57986148,48.8588,7.008002527,7.127473841,-2.018125,7.872337259,1.294663513,45.46655516 +119.29,50.42696616,-2.579860477,48.8792,7.008002552,7.127251708,-2.06625,7.777102334,1.387884032,45.4590301 +119.3,50.42696679,-2.579859474,48.9001,7.008002571,7.127251637,-2.1134375,7.681287519,1.479894236,45.45150504 +119.31,50.42696742,-2.579858471,48.9215,7.011478779,7.127029506,-2.16,7.584912695,1.570613967,45.44397993 +119.32,50.42696805,-2.579857468,48.9433,7.025383563,7.125919134,-2.2065625,7.487998087,1.659964099,45.43645487 +119.33,50.42696868,-2.579856465,48.9656,7.042764547,7.12369846,-2.253125,7.390563864,1.747866711,45.42892976 +119.34,50.42696932,-2.579855463,48.9884,7.042764584,7.121699846,-2.2978125,7.292630422,1.834245198,45.42140471 +119.35,50.42696995,-2.579854461,49.0116,7.025383661,7.121255656,-2.3396875,7.194218217,1.919024159,45.41387959 +119.36,50.42697058,-2.579853459,49.0352,7.011478919,7.121255588,-2.38,7.095347704,2.002129682,45.40635454 +119.37,50.42697121,-2.579852456,49.0592,7.008002752,7.120145218,-2.42,6.996039679,2.083489345,45.39882942 +119.38,50.42697184,-2.579851455,49.0836,7.008002772,7.118812788,-2.46,6.896314771,2.163032159,45.39130437 +119.39,50.42697247,-2.579850453,49.1084,7.01147898,7.118146539,-2.5,6.796193834,2.240688796,45.38377926 +119.4,50.4269731,-2.579849451,49.1336,7.025383777,7.117480291,-2.539375,6.695697781,2.316391532,45.3762542 +119.41,50.42697373,-2.57984845,49.1592,7.042764781,7.116591984,-2.5765625,6.594847641,2.390074306,45.36872909 +119.42,50.42697437,-2.579847448,49.1852,7.042764816,7.115481616,-2.61125,6.49366444,2.461672945,45.36120403 +119.43,50.426975,-2.579846447,49.2114,7.025383887,7.114149189,-2.645,6.392169264,2.531124941,45.35367892 +119.44,50.42697563,-2.579845446,49.2381,7.01495534,7.113260882,-2.6784375,6.290383369,2.598369732,45.34615386 +119.45,50.42697626,-2.579844445,49.265,7.025383935,7.113038757,-2.7109375,6.188328012,2.663348761,45.33862875 +119.46,50.42697689,-2.579843444,49.2923,7.042764909,7.112816632,-2.741875,6.086024449,2.726005248,45.33110369 +119.47,50.42697753,-2.579842443,49.3199,7.04276494,7.111706266,-2.77125,5.98349411,2.786284648,45.32357858 +119.48,50.42697816,-2.579841442,49.3477,7.025384028,7.109707659,-2.7996875,5.880758366,2.844134363,45.31605352 +119.49,50.42697879,-2.579840442,49.3759,7.014955496,7.108375233,-2.826875,5.777838702,2.899503973,45.30852841 +119.5,50.42697942,-2.579839442,49.4043,7.025384105,7.10837517,-2.8528125,5.674756605,2.952345177,45.30100335 +119.51,50.42698005,-2.579838441,49.4329,7.042765097,7.108153047,-2.8784375,5.57153356,3.002611853,45.29347824 +119.52,50.42698069,-2.579837441,49.4619,7.042765123,7.107042683,-2.9028125,5.468191225,3.050260227,45.28595319 +119.53,50.42698132,-2.579836441,49.491,7.028860371,7.105932318,-2.9246875,5.364751029,3.095248701,45.27842807 +119.54,50.42698195,-2.579835441,49.5204,7.028860398,7.104821954,-2.945,5.261234687,3.137538086,45.27090302 +119.55,50.42698258,-2.579834441,49.5499,7.042765212,7.10348953,-2.965,5.157663799,3.177091539,45.2633779 +119.56,50.42698322,-2.579833442,49.5797,7.046241453,7.102379167,-2.9846875,5.054060023,3.213874456,45.25585285 +119.57,50.42698385,-2.579832442,49.6096,7.042765299,7.101268804,-3.0028125,4.950444903,3.247854864,45.24832774 +119.58,50.42698448,-2.579831443,49.6398,7.046241515,7.09993638,-3.0184375,4.846840154,3.279003084,45.24080268 +119.59,50.42698512,-2.579830444,49.67,7.046241538,7.099048077,-3.0328125,4.743267375,3.307291958,45.23327757 +119.6,50.42698575,-2.579829445,49.7004,7.042765382,7.098603896,-3.046875,4.639748226,3.33269685,45.22575251 +119.61,50.42698638,-2.579828446,49.731,7.046241618,7.097715594,-3.059375,4.536304305,3.355195585,45.2182274 +119.62,50.42698702,-2.579827447,49.7616,7.046241661,7.096605231,-3.0696875,4.432957215,3.37476851,45.21070234 +119.63,50.42698765,-2.579826449,49.7924,7.042765508,7.09638311,-3.0784375,4.329728555,3.391398553,45.20317729 +119.64,50.42698828,-2.57982545,49.8232,7.046241729,7.09638305,-3.0865625,4.226639868,3.405071332,45.19565217 +119.65,50.42698892,-2.579824451,49.8541,7.046241748,7.095050627,-3.0946875,4.123712699,3.415774756,45.18812712 +119.66,50.42698955,-2.579823453,49.8851,7.04276558,7.093052024,-3.10125,4.020968532,3.423499602,45.180602 +119.67,50.42699018,-2.579822455,49.9162,7.046241814,7.091941662,-3.1046875,3.918428796,3.428239109,45.17307695 +119.68,50.42699082,-2.579821457,49.9472,7.046241864,7.091497481,-3.1065625,3.816114978,3.429989151,45.16555183 +119.69,50.42699145,-2.579820459,49.9783,7.042765711,7.090609179,-3.1084375,3.713234562,3.428748182,45.15802678 +119.7,50.42699208,-2.579819461,50.0094,7.049718125,7.089276757,-3.109375,3.605739887,3.42451729,45.15050167 +119.71,50.42699272,-2.579818464,50.0405,7.06014673,7.088166395,-3.1084375,3.488769407,3.417300199,45.14297661 +119.72,50.42699335,-2.579817466,50.0716,7.063622953,7.087278094,-3.10625,3.357461518,3.407103154,45.1354515 +119.73,50.42699399,-2.579816469,50.1026,7.063622993,7.086611852,-3.103125,3.206954501,3.393935037,45.12792644 +119.74,50.42699462,-2.579815472,50.1337,7.063623035,7.085945611,-3.098125,3.032386636,3.377807421,45.12040133 +119.75,50.42699526,-2.579814474,50.1646,7.063623072,7.084613188,-3.09125,2.828896092,3.358734229,45.11287627 +119.76,50.42699589,-2.579813478,50.1955,7.060146916,7.083502826,-3.083125,2.591621034,3.336732192,45.10535116 +119.77,50.42699653,-2.579812481,50.2263,7.049718377,7.083502765,-3.073125,2.317326943,3.311820502,45.0978261 +119.78,50.42699716,-2.579811484,50.257,7.042766022,7.083058584,-3.0615625,2.009289878,3.284020877,45.09030099 +119.79,50.42699779,-2.579810487,50.2875,7.049718429,7.081059981,-3.05,1.672413269,3.253357493,45.08277593 +119.8,50.42699843,-2.579809491,50.318,7.060147042,7.079061377,-3.038125,1.311600546,3.219857109,45.07525082 +119.81,50.42699906,-2.579808495,50.3483,7.063623282,7.078617195,-3.0246875,0.931754853,3.183549003,45.06773831 +119.82,50.4269997,-2.579807499,50.3785,7.063623321,7.078617134,-3.0096875,0.537779447,3.144464802,45.06030098 +119.83,50.42700033,-2.579806502,50.4085,7.063623348,7.077506771,-2.993125,0.134577416,3.102638539,45.05301422 +119.84,50.42700097,-2.579805507,50.4384,7.063623373,7.076396408,-2.9746875,-0.272948385,3.058106769,45.0459532 +119.85,50.4270016,-2.579804511,50.468,7.063623403,7.076396346,-2.9546875,-0.679895096,3.010908282,45.03919316 +119.86,50.42700224,-2.579803515,50.4975,7.067099634,7.076174223,-2.9334375,-1.081360034,2.961084216,45.03280937 +119.87,50.42700287,-2.579802519,50.5267,7.077528253,7.075063859,-2.91125,-1.472440571,2.908678058,45.02687708 +119.88,50.42700351,-2.579801524,50.5557,7.084480674,7.073953495,-2.888125,-1.848234249,2.853735474,45.02147157 +119.89,50.42700415,-2.579800528,50.5845,7.077528322,7.07306519,-2.863125,-2.203838786,2.796304419,45.01666806 +119.9,50.42700478,-2.579799533,50.613,7.06709978,7.072621007,-2.8365625,-2.534351954,2.736434913,45.01254179 +119.91,50.42700542,-2.579798538,50.6412,7.063623615,7.072843004,-2.81,-2.834871812,2.67417921,45.00914295 +119.92,50.42700605,-2.579797542,50.6692,7.063623631,7.07262088,-2.783125,-3.100496364,2.609591568,45.0064214 +119.93,50.42700669,-2.579796547,50.6969,7.067099849,7.071510515,-2.754375,-3.327951499,2.542728368,45.00430186 +119.94,50.42700732,-2.579795552,50.7243,7.077528471,7.070622209,-2.723125,-3.520473683,2.47364782,45.00270904 +119.95,50.42700796,-2.579794557,50.7514,7.084480901,7.070400084,-2.69,-3.682927042,2.402410259,45.0015677 +119.96,50.4270086,-2.579793562,50.7781,7.077528543,7.070622079,-2.6565625,-3.820175988,2.329077734,45.00080269 +119.97,50.42700923,-2.579792567,50.8045,7.067099978,7.071288194,-2.6234375,-3.93708499,2.253714189,45.00033865 +119.98,50.42700987,-2.579791572,50.8306,7.063623808,7.071510189,-2.589375,-4.038518802,2.176385399,45.00010036 +119.99,50.4270105,-2.579790576,50.8563,7.063623848,7.070621882,-2.553125,-4.129342181,2.0971588,45.00001253 +120,50.42701114,-2.579789582,50.8817,7.063623893,7.070399755,-2.515,-4.214420283,2.016103435,44.99999998 +120.01,50.42701177,-2.579788587,50.9066,7.063623928,7.071732049,-2.4765625,-4.297804378,1.933289949,44.99999998 +120.02,50.42701241,-2.579787591,50.9312,7.067100142,7.072398163,-2.438125,-4.380290992,1.848790649,44.99999998 +120.03,50.42701304,-2.579786596,50.9554,7.077528734,7.071509853,-2.3978125,-4.461862821,1.76267916,44.99999998 +120.04,50.42701368,-2.579785601,50.9792,7.084481137,7.070621544,-2.355,-4.542502792,1.675030598,44.99999998 +120.05,50.42701432,-2.579784606,51.0025,7.077528783,7.070621476,-2.3115625,-4.622194174,1.585921394,44.99999998 +120.06,50.42701495,-2.579783611,51.0254,7.067100245,7.071287587,-2.2684375,-4.700920294,1.495429242,44.99999998 +120.07,50.42701559,-2.579782616,51.0479,7.06362408,7.071509577,-2.2246875,-4.778664651,1.403633038,44.99999998 +120.08,50.42701622,-2.57978162,51.0699,7.063624092,7.070621266,-2.1796875,-4.855411029,1.310612824,44.99999998 +120.09,50.42701686,-2.579780626,51.0915,7.067100297,7.070399135,-2.1334375,-4.931143445,1.216449789,44.99999998 +120.1,50.42701749,-2.579779631,51.1126,7.077528901,7.071731425,-2.08625,-5.005846026,1.121225922,44.99999998 +120.11,50.42701813,-2.579778635,51.1332,7.084481324,7.072397534,-2.038125,-5.079503246,1.025024418,44.99999998 +120.12,50.42701877,-2.57977764,51.1534,7.077528976,7.07150922,-1.988125,-5.152099634,0.927928984,44.99999998 +120.13,50.4270194,-2.579776645,51.173,7.067100425,7.070620906,-1.9365625,-5.223620122,0.83002442,44.99999998 +120.14,50.42702004,-2.57977565,51.1921,7.06362425,7.070398773,-1.8853125,-5.294049698,0.731396095,44.99999998 +120.15,50.42702067,-2.579774655,51.2107,7.063624262,7.070398699,-1.835,-5.363373638,0.632129954,44.99999998 +120.16,50.42702131,-2.57977366,51.2288,7.067100468,7.070398624,-1.784375,-5.43157756,0.53231257,44.99999998 +120.17,50.42702194,-2.579772665,51.2464,7.077529064,7.070620609,-1.7315625,-5.49864714,0.432031033,44.99999998 +120.18,50.42702258,-2.57977167,51.2635,7.084481475,7.071508774,-1.6765625,-5.564568398,0.331372776,44.99999998 +120.19,50.42702322,-2.579770675,51.2799,7.077529116,7.072396939,-1.6215625,-5.629327583,0.23042552,44.99999998 +120.2,50.42702385,-2.579769679,51.2959,7.06710056,7.071730681,-1.5665625,-5.692911173,0.129277327,44.99999998 +120.21,50.42702449,-2.579768684,51.3113,7.06362438,7.070398242,-1.5096875,-5.755305819,0.028016433,44.99999998 +120.22,50.42702512,-2.57976769,51.3261,7.063624382,7.070620224,-1.451875,-5.816498571,-0.073268926,44.99999998 +120.23,50.42702576,-2.579766694,51.3403,7.067100586,7.071508386,-1.395,-5.876476652,-0.1744904,44.99999998 +120.24,50.42702639,-2.579765699,51.354,7.077529193,7.071286246,-1.338125,-5.935227458,-0.275559697,44.99999998 +120.25,50.42702703,-2.579764704,51.3671,7.084481611,7.070619986,-1.2796875,-5.992738784,-0.376388695,44.99999998 +120.26,50.42702767,-2.579763709,51.3796,7.077529243,7.070397845,-1.22,-6.048998599,-0.476889446,44.99999998 +120.27,50.4270283,-2.579762714,51.3915,7.067100663,7.070397763,-1.16,-6.103995156,-0.576974401,44.99999998 +120.28,50.42702894,-2.579761719,51.4028,7.063624465,7.07039768,-1.1,-6.157716997,-0.676556185,44.99999998 +120.29,50.42702957,-2.579760724,51.4135,7.063624475,7.070619658,-1.04,-6.210152834,-0.775548051,44.99999998 +120.3,50.42703021,-2.579759729,51.4236,7.063624499,7.071507815,-0.98,-6.261291781,-0.873863598,44.99999998 +120.31,50.42703084,-2.579758734,51.4331,7.063624521,7.072618032,-0.9196875,-6.311123181,-0.971417111,44.99999998 +120.32,50.42703148,-2.579757738,51.442,7.067100732,7.072617948,-0.858125,-6.359636548,-1.068123563,44.99999998 +120.33,50.42703211,-2.579756743,51.4503,7.077529318,7.071507561,-0.795,-6.406821743,-1.163898558,44.99999998 +120.34,50.42703275,-2.579755748,51.4579,7.084481699,7.070619235,-0.7315625,-6.452669023,-1.258658616,44.99999998 +120.35,50.42703339,-2.579754753,51.4649,7.077529314,7.070397087,-0.6684375,-6.497168707,-1.352321172,44.99999998 +120.36,50.42703402,-2.579753758,51.4713,7.067100752,7.070396999,-0.605,-6.54031157,-1.44480441,44.99999998 +120.37,50.42703466,-2.579752763,51.477,7.063624581,7.07039691,-0.5415625,-6.582088558,-1.536027771,44.99999998 +120.38,50.42703529,-2.579751768,51.4821,7.063624592,7.070396822,-0.4784375,-6.622490906,-1.625911728,44.99999998 +120.39,50.42703593,-2.579750773,51.4866,7.067100778,7.070618793,-0.415,-6.661510306,-1.714377844,44.99999998 +120.4,50.42703656,-2.579749778,51.4904,7.077529346,7.071284883,-0.3515625,-6.699138507,-1.801348998,44.99999998 +120.41,50.4270372,-2.579748783,51.4936,7.084481737,7.071728912,-0.288125,-6.735367717,-1.886749332,44.99999998 +120.42,50.42703784,-2.579747787,51.4962,7.077529371,7.071506759,-0.223125,-6.770190259,-1.970504417,44.99999998 +120.43,50.42703847,-2.579746793,51.4981,7.067100807,7.071506667,-0.156875,-6.803598969,-2.052541144,44.99999998 +120.44,50.42703911,-2.579745797,51.4993,7.063624615,7.071728634,-0.091875,-6.835586859,-2.132788066,44.99999998 +120.45,50.42703974,-2.579744802,51.4999,7.063624615,7.07128442,-0.0284375,-6.866147225,-2.211175167,44.99999998 +120.46,50.42704038,-2.579743807,51.4999,7.067100802,7.070618145,0.0353125,-6.895273649,-2.287634093,44.99999998 +120.47,50.42704101,-2.579742812,51.4992,7.077529368,7.070395989,0.1,-6.922960058,-2.362098152,44.99999998 +120.48,50.42704165,-2.579741817,51.4979,7.084481747,7.070617952,0.1646875,-6.94920078,-2.434502484,44.99999998 +120.49,50.42704229,-2.579740822,51.4959,7.077529368,7.071284036,0.2284375,-6.9739902,-2.504783837,44.99999998 +120.5,50.42704292,-2.579739827,51.4933,7.067100791,7.071506,0.2915625,-6.997323162,-2.572880959,44.99999998 +120.51,50.42704356,-2.579738831,51.4901,7.063624591,7.07061766,0.3553125,-7.019194852,-2.638734551,44.99999998 +120.52,50.42704419,-2.579737837,51.4862,7.063624583,7.070395501,0.42,-7.039600686,-2.702287087,44.99999998 +120.53,50.42704483,-2.579736842,51.4817,7.067100776,7.071727762,0.4846875,-7.058536426,-2.763483162,44.99999998 +120.54,50.42704546,-2.579735846,51.4765,7.077529359,7.072393843,0.5484375,-7.075998002,-2.822269491,44.99999998 +120.55,50.4270461,-2.579734851,51.4707,7.084481743,7.071505501,0.6115625,-7.091981863,-2.878594738,44.99999998 +120.56,50.42704674,-2.579733856,51.4643,7.077529351,7.070617158,0.675,-7.106484685,-2.932409856,44.99999998 +120.57,50.42704737,-2.579732861,51.4572,7.067100768,7.070394995,0.738125,-7.119503432,-2.983667806,44.99999998 +120.58,50.42704801,-2.579731866,51.4495,7.063624562,7.070394892,0.7996875,-7.131035297,-3.032323955,44.99999998 +120.59,50.42704864,-2.579730871,51.4412,7.063624538,7.070394789,0.8603125,-7.141077986,-3.078335904,44.99999998 +120.6,50.42704928,-2.579729876,51.4323,7.067100716,7.070616745,0.921875,-7.149629324,-3.121663488,44.99999998 +120.61,50.42704991,-2.579728881,51.4228,7.077529298,7.07150488,0.9846875,-7.156687534,-3.162268949,44.99999998 +120.62,50.42705055,-2.579727886,51.4126,7.084481688,7.072393014,1.0465625,-7.162251183,-3.200116822,44.99999998 +120.63,50.42705119,-2.57972689,51.4018,7.077529287,7.071726727,1.1065625,-7.166319126,-3.235174162,44.99999998 +120.64,50.42705182,-2.579725895,51.3905,7.06710068,7.070394259,1.1665625,-7.168890446,-3.267410372,44.99999998 +120.65,50.42705246,-2.579724901,51.3785,7.063624467,7.070616212,1.2265625,-7.169964627,-3.296797377,44.99999998 +120.66,50.42705309,-2.579723905,51.3659,7.063624465,7.071504344,1.2846875,-7.169541441,-3.323309567,44.99999998 +120.67,50.42705373,-2.57972291,51.3528,7.063624466,7.071282174,1.341875,-7.167621001,-3.346923678,44.99999998 +120.68,50.42705436,-2.579721915,51.3391,7.063624459,7.070615884,1.4,-7.164203709,-3.367619315,44.99999998 +120.69,50.427055,-2.57972092,51.3248,7.06710063,7.070393714,1.458125,-7.159290252,-3.385378314,44.99999998 +120.7,50.42705563,-2.579719925,51.3099,7.07752918,7.070393603,1.515,-7.152881662,-3.400185147,44.99999998 +120.71,50.42705627,-2.57971893,51.2945,7.084481539,7.070393491,1.5715625,-7.144979313,-3.412027039,44.99999998 +120.72,50.42705691,-2.579717935,51.2785,7.077529142,7.070615438,1.628125,-7.135584811,-3.420893561,44.99999998 +120.73,50.42705754,-2.57971694,51.2619,7.06710056,7.071503566,1.6828125,-7.124700102,-3.426777035,44.99999998 +120.74,50.42705818,-2.579715945,51.2448,7.063624352,7.072613753,1.735,-7.112327537,-3.429672306,44.99999998 +120.75,50.42705881,-2.579714949,51.2272,7.063624327,7.072613639,1.786875,-7.098469636,-3.429576851,44.99999998 +120.76,50.42705945,-2.579713954,51.2091,7.067100492,7.071503223,1.8396875,-7.083129321,-3.426490728,44.99999998 +120.77,50.42706008,-2.579712959,51.1904,7.077529048,7.070614868,1.8915625,-7.066309744,-3.420416688,44.99999998 +120.78,50.42706072,-2.579711964,51.1712,7.084481419,7.070392692,1.9415625,-7.048014514,-3.411360002,44.99999998 +120.79,50.42706136,-2.579710969,51.1516,7.077529018,7.070392576,1.9915625,-7.028247356,-3.399328518,44.99999998 +120.8,50.42706199,-2.579709974,51.1314,7.067100418,7.070392458,2.0415625,-7.007012451,-3.38433278,44.99999998 +120.81,50.42706263,-2.579708979,51.1107,7.063624203,7.070614401,2.0896875,-6.984314212,-3.366385851,44.99999998 +120.82,50.42706326,-2.579707984,51.0896,7.063624178,7.071502523,2.1365625,-6.960157395,-3.345503431,44.99999998 +120.83,50.4270639,-2.579706989,51.068,7.067100341,7.072390645,2.1834375,-6.934547041,-3.321703623,44.99999998 +120.84,50.42706453,-2.579705993,51.0459,7.077528893,7.071724346,2.2296875,-6.907488536,-3.295007285,44.99999998 +120.85,50.42706517,-2.579704998,51.0234,7.08448126,7.070391866,2.2746875,-6.878987438,-3.265437621,44.99999998 +120.86,50.42706581,-2.579704004,51.0004,7.077528858,7.070613806,2.318125,-6.849049763,-3.233020471,44.99999998 +120.87,50.42706644,-2.579703008,50.977,7.067100259,7.071501925,2.3596875,-6.817681756,-3.197784025,44.99999998 +120.88,50.42706708,-2.579702013,50.9532,7.063624036,7.071279744,2.4,-6.784889949,-3.159759108,44.99999998 +120.89,50.42706771,-2.579701018,50.929,7.063623994,7.070613443,2.44,-6.750681218,-3.118978837,44.99999998 +120.9,50.42706835,-2.579700023,50.9044,7.067100154,7.070391262,2.4796875,-6.715062666,-3.075478735,44.99999998 +120.91,50.42706898,-2.579699028,50.8794,7.077528718,7.070613199,2.5184375,-6.6780418,-3.02929679,44.99999998 +120.92,50.42706962,-2.579698033,50.854,7.084481093,7.071279256,2.55625,-6.639626298,-2.98047328,44.99999998 +120.93,50.42707026,-2.579697038,50.8283,7.077528685,7.071723252,2.593125,-6.59982418,-2.929050719,44.99999998 +120.94,50.42707089,-2.579696042,50.8021,7.067100071,7.071501069,2.628125,-6.558643813,-2.875074026,44.99999998 +120.95,50.42707153,-2.579695048,50.7757,7.063623833,7.071500945,2.66125,-6.516093732,-2.818590185,44.99999998 +120.96,50.42707216,-2.579694052,50.7489,7.063623793,7.071722881,2.6934375,-6.47218282,-2.75964847,44.99999998 +120.97,50.4270728,-2.579693057,50.7218,7.063623771,7.071278637,2.7246875,-6.4269203,-2.698300332,44.99999998 +120.98,50.42707343,-2.579692062,50.6944,7.063623757,7.070612332,2.755,-6.380315627,-2.634599285,44.99999998 +120.99,50.42707407,-2.579691067,50.6667,7.067099922,7.070390146,2.7846875,-6.332378482,-2.568600735,44.99999998 +121,50.4270747,-2.579690072,50.6387,7.077528458,7.070612081,2.813125,-6.283118894,-2.500362379,44.99999998 +121.01,50.42707534,-2.579689077,50.6104,7.084480803,7.071278135,2.84,-6.232547176,-2.429943688,44.99999998 +121.02,50.42707598,-2.579688082,50.5819,7.077528392,7.071500069,2.86625,-6.180673869,-2.357406028,44.99999998 +121.03,50.42707661,-2.579687086,50.5531,7.067099797,7.070611702,2.8915625,-6.127509802,-2.282812653,44.99999998 +121.04,50.42707725,-2.579686092,50.524,7.063623577,7.070389515,2.914375,-6.073066035,-2.20622865,44.99999998 +121.05,50.42707788,-2.579685097,50.4948,7.063623541,7.071721748,2.935,-6.017354025,-2.12772077,44.99999998 +121.06,50.42707852,-2.579684101,50.4653,7.067099698,7.072387801,2.955,-5.960385405,-2.04735748,44.99999998 +121.07,50.42707915,-2.579683106,50.4357,7.077528236,7.071499433,2.9746875,-5.902171976,-1.965208912,44.99999998 +121.08,50.42707979,-2.579682111,50.4058,7.084480581,7.070611065,2.9934375,-5.842726,-1.881346626,44.99999998 +121.09,50.42708043,-2.579681116,50.3758,7.077528169,7.070388878,3.0109375,-5.782059797,-1.795843791,44.99999998 +121.1,50.42708106,-2.579680121,50.3456,7.067099573,7.07038875,3.0265625,-5.720186142,-1.70877489,44.99999998 +121.11,50.4270817,-2.579679126,50.3152,7.063623353,7.070388621,3.0396875,-5.65711787,-1.620215955,44.99999998 +121.12,50.42708233,-2.579678131,50.2848,7.06362332,7.070610553,3.0515625,-5.592868159,-1.53024422,44.99999998 +121.13,50.42708297,-2.579677136,50.2542,7.067099473,7.071498665,3.0634375,-5.527450473,-1.43893801,44.99999998 +121.14,50.4270836,-2.579676141,50.2235,7.077528003,7.072386776,3.0746875,-5.46087845,-1.346377079,44.99999998 +121.15,50.42708424,-2.579675145,50.1927,7.084480349,7.071720467,3.0846875,-5.393166011,-1.252642043,44.99999998 +121.16,50.42708488,-2.57967415,50.1618,7.077527941,7.070387978,3.0928125,-5.324327252,-1.15781472,44.99999998 +121.17,50.42708551,-2.579673156,50.1308,7.067099344,7.07060991,3.098125,-5.254376554,-1.061977732,44.99999998 +121.18,50.42708615,-2.57967216,50.0998,7.063623122,7.071498021,3.1015625,-5.183328584,-0.965214728,44.99999998 +121.19,50.42708678,-2.579671165,50.0688,7.063623075,7.071275832,3.105,-5.111198125,-0.867609993,44.99999998 +121.2,50.42708742,-2.57967017,50.0377,7.067099217,7.070609523,3.108125,-5.038000303,-0.769248724,44.99999998 +121.21,50.42708805,-2.579669175,50.0066,7.077527761,7.070387334,3.1096875,-4.963750301,-0.670216636,44.99999998 +121.22,50.42708869,-2.57966818,49.9755,7.084480131,7.070387204,3.1096875,-4.888463704,-0.570600131,44.99999998 +121.23,50.42708933,-2.579667185,49.9444,7.077527725,7.070387075,3.108125,-4.812156211,-0.470486012,44.99999998 +121.24,50.42708996,-2.57966619,49.9133,7.067099109,7.070609006,3.1046875,-4.73484375,-0.369961656,44.99999998 +121.25,50.4270906,-2.579665195,49.8823,7.063622867,7.071497117,3.0996875,-4.656542478,-0.269114724,44.99999998 +121.26,50.42709123,-2.5796642,49.8513,7.06362282,7.072607288,3.0934375,-4.577268782,-0.168033051,44.99999998 +121.27,50.42709187,-2.579663204,49.8204,7.063622787,7.072607159,3.08625,-4.497039164,-0.066804874,44.99999998 +121.28,50.4270925,-2.579662209,49.7896,7.063622766,7.07149673,3.078125,-4.41587041,0.034481517,44.99999998 +121.29,50.42709314,-2.579661214,49.7588,7.067098941,7.070608363,3.068125,-4.333779424,0.135737884,44.99999998 +121.3,50.42709377,-2.579660219,49.7282,7.07752749,7.070386175,3.0565625,-4.250783393,0.236875879,44.99999998 +121.31,50.42709441,-2.579659224,49.6977,7.084479829,7.070386045,3.045,-4.166899679,0.337807322,44.99999998 +121.32,50.42709505,-2.579658229,49.6673,7.077527393,7.070385917,3.0328125,-4.082145699,0.438444207,44.99999998 +121.33,50.42709568,-2.579657234,49.637,7.067098783,7.070385789,3.018125,-3.996539273,0.538698701,44.99999998 +121.34,50.42709632,-2.579656239,49.6069,7.063622575,7.070607722,3.00125,-3.910098162,0.638483483,44.99999998 +121.35,50.42709695,-2.579655244,49.577,7.063622556,7.071495833,2.9834375,-3.822840528,0.737711465,44.99999998 +121.36,50.42709759,-2.579654249,49.5472,7.067098712,7.072606005,2.9646875,-3.734784536,0.836296188,44.99999998 +121.37,50.42709822,-2.579653253,49.5177,7.077527242,7.072605877,2.9446875,-3.645948575,0.93415165,44.99999998 +121.38,50.42709886,-2.579652258,49.4883,7.084479584,7.07149545,2.923125,-3.556351154,1.031192537,44.99999998 +121.39,50.4270995,-2.579651263,49.4592,7.077527175,7.070607084,2.8996875,-3.466011123,1.127334168,44.99999998 +121.4,50.42710013,-2.579650268,49.4303,7.067098581,7.070384898,2.875,-3.374947216,1.222492717,44.99999998 +121.41,50.42710077,-2.579649273,49.4017,7.063622362,7.070384772,2.85,-3.283178457,1.316585279,44.99999998 +121.42,50.4271014,-2.579648278,49.3733,7.063622325,7.070384646,2.8246875,-3.190724096,1.409529805,44.99999998 +121.43,50.42710204,-2.579647283,49.3452,7.067098478,7.070606579,2.798125,-3.097603386,1.501245107,44.99999998 +121.44,50.42710267,-2.579646288,49.3173,7.077527021,7.071272633,2.7696875,-3.003835806,1.591651373,44.99999998 +121.45,50.42710331,-2.579645293,49.2898,7.08447938,7.071494568,2.7396875,-2.909440837,1.680669648,44.99999998 +121.46,50.42710395,-2.579644297,49.2625,7.077526973,7.070606205,2.708125,-2.814438361,1.768222355,44.99999998 +121.47,50.42710458,-2.579643303,49.2356,7.067098369,7.07038402,2.6746875,-2.718848088,1.854233175,44.99999998 +121.48,50.42710522,-2.579642308,49.209,7.06362215,7.071716255,2.6403125,-2.622690014,1.938627051,44.99999998 +121.49,50.42710585,-2.579641312,49.1828,7.063622126,7.072382311,2.60625,-2.525984192,2.021330472,44.99999998 +121.5,50.42710649,-2.579640317,49.1569,7.067098286,7.071493948,2.5715625,-2.428750905,2.102271188,44.99999998 +121.51,50.42710712,-2.579639322,49.1313,7.07752682,7.070605586,2.5346875,-2.331010378,2.181378726,44.99999998 +121.52,50.42710776,-2.579638327,49.1062,7.084479171,7.070383403,2.4965625,-2.232783067,2.258584044,44.99999998 +121.53,50.4271084,-2.579637332,49.0814,7.07752677,7.070383281,2.4584375,-2.134089425,2.333819877,44.99999998 +121.54,50.42710903,-2.579636337,49.057,7.067098181,7.07038316,2.419375,-2.034950137,2.407020564,44.99999998 +121.55,50.42710967,-2.579635342,49.033,7.06362196,7.070605099,2.378125,-1.935385886,2.478122334,44.99999998 +121.56,50.4271103,-2.579634347,49.0094,7.063621919,7.071493217,2.335,-1.835417413,2.54706308,44.99999998 +121.57,50.42711094,-2.579633352,48.9863,7.06709808,7.072381336,2.2915625,-1.735065688,2.613782812,44.99999998 +121.58,50.42711157,-2.579632356,48.9636,7.077526643,7.071715037,2.248125,-1.634351568,2.678223261,44.99999998 +121.59,50.42711221,-2.579631361,48.9413,7.084479019,7.070382559,2.203125,-1.533296194,2.740328219,44.99999998 +121.6,50.42711285,-2.579630367,48.9195,7.077526618,7.070604499,2.1565625,-1.431920537,2.800043656,44.99999998 +121.61,50.42711348,-2.579629371,48.8982,7.067098012,7.07149262,2.1096875,-1.330245911,2.85731732,44.99999998 +121.62,50.42711412,-2.579628376,48.8773,7.063621782,7.071270443,2.0615625,-1.228293457,2.912099419,44.99999998 +121.63,50.42711475,-2.579627381,48.8569,7.063621749,7.070604146,2.0115625,-1.12608449,2.964342111,44.99999998 +121.64,50.42711539,-2.579626386,48.8371,7.063621735,7.07060403,1.961875,-1.023640323,3.013999848,44.99999998 +121.65,50.42711602,-2.579625391,48.8177,7.063621729,7.071492153,1.913125,-0.920982387,3.061029312,44.99999998 +121.66,50.42711666,-2.579624396,48.7988,7.067097904,7.072380276,1.8628125,-0.818132165,3.105389538,44.99999998 +121.67,50.42711729,-2.5796234,48.7804,7.077526447,7.071713982,1.81,-0.715111031,3.147041851,44.99999998 +121.68,50.42711793,-2.579622405,48.7626,7.084478801,7.070381509,1.7565625,-0.611940583,3.185949868,44.99999998 +121.69,50.42711857,-2.579621411,48.7453,7.077526405,7.070603455,1.7034375,-0.508642366,3.22207967,44.99999998 +121.7,50.4271192,-2.579620415,48.7285,7.067097827,7.071491581,1.6496875,-0.405237865,3.255399801,44.99999998 +121.71,50.42711984,-2.57961942,48.7123,7.063621622,7.071269408,1.595,-0.301748796,3.285881156,44.99999998 +121.72,50.42712047,-2.579618425,48.6966,7.063621601,7.070603117,1.5396875,-0.198196701,3.313497149,44.99999998 +121.73,50.42712111,-2.57961743,48.6815,7.067097775,7.070380947,1.483125,-0.094603181,3.338223773,44.99999998 +121.74,50.42712174,-2.579616435,48.6669,7.077526333,7.070602896,1.425,0.009010105,3.36003937,44.99999998 +121.75,50.42712238,-2.57961544,48.653,7.084478696,7.071268964,1.366875,0.112621444,3.378924975,44.99999998 +121.76,50.42712302,-2.579614445,48.6396,7.077526293,7.071712974,1.31,0.216209348,3.394864146,44.99999998 +121.77,50.42712365,-2.579613449,48.6268,7.067097708,7.071490805,1.2528125,0.319752046,3.4078429,44.99999998 +121.78,50.42712429,-2.579612455,48.6145,7.063621512,7.071490697,1.193125,0.423227938,3.417850009,44.99999998 +121.79,50.42712492,-2.579611459,48.6029,7.063621507,7.071712649,1.1315625,0.526615536,3.424876649,44.99999998 +121.8,50.42712556,-2.579610464,48.5919,7.067097683,7.071268424,1.0703125,0.62989307,3.428916746,44.99999998 +121.81,50.42712619,-2.579609469,48.5815,7.077526233,7.070602139,1.01,0.733039109,3.429966806,44.99999998 +121.82,50.42712683,-2.579608474,48.5717,7.0844786,7.070379973,0.9496875,0.836032054,3.428025912,44.99999998 +121.83,50.42712747,-2.579607479,48.5625,7.077526218,7.070379868,0.8884375,0.938850362,3.423095667,44.99999998 +121.84,50.4271281,-2.579606484,48.5539,7.067097648,7.070379764,0.8265625,1.041472661,3.415180484,44.99999998 +121.85,50.42712874,-2.579605489,48.546,7.063621453,7.070379661,0.7646875,1.143877465,3.404287181,44.99999998 +121.86,50.42712937,-2.579604494,48.5386,7.063621432,7.070601618,0.701875,1.246043345,3.39042527,44.99999998 +121.87,50.42713001,-2.579603499,48.5319,7.063621408,7.071489754,0.638125,1.347948989,3.373606896,44.99999998 +121.88,50.42713064,-2.579602504,48.5259,7.063621402,7.072599951,0.575,1.449573195,3.35384667,44.99999998 +121.89,50.42713128,-2.579601508,48.5204,7.067097606,7.07259985,0.5115625,1.55089465,3.331161839,44.99999998 +121.9,50.42713191,-2.579600513,48.5156,7.077526191,7.071489451,0.4465625,1.651892213,3.305572226,44.99999998 +121.91,50.42713255,-2.579599518,48.5115,7.084478567,7.070601114,0.3821875,1.752544797,3.277100062,44.99999998 +121.92,50.42713319,-2.579598523,48.508,7.077526164,7.070378956,0.3196875,1.852831376,3.245770214,44.99999998 +121.93,50.42713382,-2.579597528,48.5051,7.067097575,7.070378859,0.2565625,1.952731037,3.211610012,44.99999998 +121.94,50.42713446,-2.579596533,48.5028,7.063621388,7.070378761,0.1915625,2.052222866,3.17464925,44.99999998 +121.95,50.42713509,-2.579595538,48.5013,7.063621402,7.070600724,0.126875,2.151286123,3.134920127,44.99999998 +121.96,50.42713573,-2.579594543,48.5003,7.067097598,7.071488867,0.0634375,2.249900124,3.092457365,44.99999998 +121.97,50.42713636,-2.579593548,48.5,7.077526168,7.072377011,-0.000625,2.348044242,3.047297863,44.99999998 +121.98,50.427137,-2.579592552,48.5003,7.084478542,7.071710737,-0.06625,2.445698022,2.999481097,44.99999998 +121.99,50.42713764,-2.579591557,48.5013,7.077526149,7.070378286,-0.131875,2.542841068,2.949048779,44.99999998 +122,50.42713827,-2.579590563,48.503,7.067097578,7.070600253,-0.19625,2.63945304,2.896044797,44.99999998 +122.01,50.42713891,-2.579589567,48.5052,7.063621407,7.071488399,-0.26,2.735513826,2.840515447,44.99999998 +122.02,50.42713954,-2.579588572,48.5082,7.063621424,7.071266248,-0.3234375,2.831003316,2.782509085,44.99999998 +122.03,50.42714018,-2.579587577,48.5117,7.067097616,7.070599978,-0.3865625,2.925901571,2.722076362,44.99999998 +122.04,50.42714081,-2.579586582,48.5159,7.077526182,7.070377829,-0.4503125,3.020188823,2.659269931,44.99999998 +122.05,50.42714145,-2.579585587,48.5207,7.084478561,7.07037774,-0.515,3.113845307,2.594144626,44.99999998 +122.06,50.42714209,-2.579584592,48.5262,7.077526191,7.070377651,-0.5796875,3.20685154,2.526757112,44.99999998 +122.07,50.42714272,-2.579583597,48.5323,7.067097638,7.070599622,-0.643125,3.299188043,2.457166288,44.99999998 +122.08,50.42714336,-2.579582602,48.5391,7.063621461,7.071487773,-0.705,3.390835565,2.385432774,44.99999998 +122.09,50.42714399,-2.579581607,48.5464,7.063621472,7.072597985,-0.766875,3.481774968,2.31161908,44.99999998 +122.1,50.42714463,-2.579580611,48.5544,7.067097674,7.072597899,-0.83,3.57198723,2.235789663,44.99999998 +122.11,50.42714526,-2.579579616,48.563,7.077526247,7.071487516,-0.8928125,3.661453501,2.158010585,44.99999998 +122.12,50.4271459,-2.579578621,48.5723,7.084478624,7.070599194,-0.9534375,3.75015516,2.078349742,44.99999998 +122.13,50.42714654,-2.579577626,48.5821,7.077526252,7.070377051,-1.0134375,3.838073643,1.996876461,44.99999998 +122.14,50.42714717,-2.579576631,48.5925,7.067097706,7.070376967,-1.075,3.925190558,1.913661962,44.99999998 +122.15,50.42714781,-2.579575636,48.6036,7.06362154,7.070376885,-1.1365625,4.011487799,1.828778665,44.99999998 +122.16,50.42714844,-2.579574641,48.6153,7.063621549,7.070376803,-1.19625,4.096947262,1.742300656,44.99999998 +122.17,50.42714908,-2.579573646,48.6275,7.06709774,7.070598781,-1.255,4.181551127,1.654303334,44.99999998 +122.18,50.42714971,-2.579572651,48.6404,7.077526318,7.071486939,-1.3134375,4.265281746,1.564863419,44.99999998 +122.19,50.42715035,-2.579571656,48.6538,7.084478718,7.072597157,-1.37125,4.348121589,1.474058947,44.99999998 +122.2,50.42715099,-2.57957066,48.6678,7.077526363,7.072597078,-1.4284375,4.430053407,1.381969103,44.99999998 +122.21,50.42715162,-2.579569665,48.6824,7.067097819,7.071486702,-1.485,4.511060071,1.288674098,44.99999998 +122.22,50.42715226,-2.57956867,48.6975,7.063621649,7.070598386,-1.5415625,4.591124678,1.194255352,44.99999998 +122.23,50.42715289,-2.579567675,48.7132,7.063621654,7.070376248,-1.598125,4.67023044,1.098795255,44.99999998 +122.24,50.42715353,-2.57956668,48.7295,7.063621655,7.070376172,-1.653125,4.748360913,1.002376943,44.99999998 +122.25,50.42715416,-2.579565685,48.7463,7.063621675,7.070376096,-1.7065625,4.82549971,0.905084584,44.99999998 +122.26,50.4271548,-2.57956469,48.7636,7.067097905,7.07059808,-1.76,4.90163079,0.807002918,44.99999998 +122.27,50.42715543,-2.579563695,48.7815,7.077526515,7.071264184,-1.813125,4.976738223,0.708217603,44.99999998 +122.28,50.42715607,-2.5795627,48.7999,7.084478916,7.071486169,-1.865,5.050806368,0.60881464,44.99999998 +122.29,50.42715671,-2.579561704,48.8188,7.077526538,7.070597857,-1.9165625,5.123819698,0.508880831,44.99999998 +122.3,50.42715734,-2.57956071,48.8382,7.067097973,7.070375725,-1.968125,5.195762971,0.408503266,44.99999998 +122.31,50.42715798,-2.579559715,48.8582,7.06362181,7.071708009,-2.0178125,5.26662112,0.307769494,44.99999998 +122.32,50.42715861,-2.579558719,48.8786,7.063621849,7.072374116,-2.065,5.336379476,0.20676729,44.99999998 +122.33,50.42715925,-2.579557724,48.8995,7.067098069,7.071485806,-2.111875,5.405023373,0.105584834,44.99999998 +122.34,50.42715988,-2.579556729,48.9208,7.077526664,7.070597497,-2.1596875,5.472538542,0.004310247,44.99999998 +122.35,50.42716052,-2.579555734,48.9427,7.084479065,7.070597426,-2.2065625,5.538910775,-0.096968065,44.99999998 +122.36,50.42716116,-2.579554739,48.965,7.077526701,7.071263535,-2.25125,5.604126321,-0.198161808,44.99999998 +122.37,50.42716179,-2.579553744,48.9877,7.067098155,7.071485525,-2.295,5.668171486,-0.299182747,44.99999998 +122.38,50.42716243,-2.579552748,49.0109,7.063621996,7.070597218,-2.338125,5.731032978,-0.399942818,44.99999998 +122.39,50.42716306,-2.579551754,49.0345,7.063622025,7.070375089,-2.3796875,5.79269756,-0.50035413,44.99999998 +122.4,50.4271637,-2.579550759,49.0585,7.067098245,7.071707378,-2.42,5.8531524,-0.600329078,44.99999998 +122.41,50.42716433,-2.579549763,49.0829,7.077526847,7.07237349,-2.4596875,5.912384949,-0.699780571,44.99999998 +122.42,50.42716497,-2.579548768,49.1077,7.084479253,7.071485185,-2.4984375,5.970382716,-0.798621864,44.99999998 +122.43,50.42716561,-2.579547773,49.1329,7.077526893,7.070596879,-2.53625,6.02713367,-0.896766727,44.99999998 +122.44,50.42716624,-2.579546778,49.1584,7.067098349,7.070374753,-2.573125,6.08262595,-0.994129559,44.99999998 +122.45,50.42716688,-2.579545783,49.1844,7.063622195,7.070374687,-2.6084375,6.136847926,-1.090625564,44.99999998 +122.46,50.42716751,-2.579544788,49.2106,7.063622232,7.070374622,-2.643125,6.189788309,-1.186170459,44.99999998 +122.47,50.42716815,-2.579543793,49.2372,7.06709845,7.070596616,-2.678125,6.241436043,-1.280681051,44.99999998 +122.48,50.42716878,-2.579542798,49.2642,7.077527043,7.071484789,-2.71125,6.291780355,-1.374074833,44.99999998 +122.49,50.42716942,-2.579541803,49.2915,7.084479452,7.072372963,-2.74125,6.340810645,-1.466270446,44.99999998 +122.5,50.42717006,-2.579540807,49.319,7.077527109,7.07170672,-2.77,6.388516773,-1.557187389,44.99999998 +122.51,50.42717069,-2.579539812,49.3469,7.067098579,7.070374299,-2.7984375,6.434888768,-1.646746479,44.99999998 +122.52,50.42717133,-2.579538818,49.375,7.063622425,7.070596295,-2.82625,6.479916891,-1.734869622,44.99999998 +122.53,50.42717196,-2.579537822,49.4034,7.063622451,7.071484471,-2.853125,6.523591745,-1.821479871,44.99999998 +122.54,50.4271726,-2.579536827,49.4321,7.067098661,7.071262348,-2.878125,6.565904219,-1.906501765,44.99999998 +122.55,50.42717323,-2.579535832,49.461,7.07752726,7.070596106,-2.90125,6.606845549,-1.989861166,44.99999998 +122.56,50.42717387,-2.579534837,49.4901,7.084479685,7.070373984,-2.9234375,6.646407081,-2.071485421,44.99999998 +122.57,50.42717451,-2.579533842,49.5195,7.077527348,7.070595982,-2.9446875,6.684580624,-2.151303255,44.99999998 +122.58,50.42717514,-2.579532847,49.549,7.067098807,7.071262098,-2.9646875,6.721358154,-2.229245167,44.99999998 +122.59,50.42717578,-2.579531852,49.5788,7.063622634,7.071706155,-2.9834375,6.756732053,-2.305243091,44.99999998 +122.6,50.42717641,-2.579530856,49.6087,7.063622657,7.071484034,-3.00125,6.790694871,-2.37923085,44.99999998 +122.61,50.42717705,-2.579529862,49.6388,7.063622698,7.071483973,-3.018125,6.823239504,-2.451143872,44.99999998 +122.62,50.42717768,-2.579528866,49.6691,7.063622748,7.071705971,-3.033125,6.854359248,-2.520919474,44.99999998 +122.63,50.42717832,-2.579527871,49.6995,7.06709898,7.071261791,-3.04625,6.884047515,-2.588496752,44.99999998 +122.64,50.42717895,-2.579526876,49.73,7.077527588,7.070595552,-3.0584375,6.912298116,-2.653816863,44.99999998 +122.65,50.42717959,-2.579525881,49.7607,7.084480006,7.070373432,-3.0696875,6.939105207,-2.716822797,44.99999998 +122.66,50.42718023,-2.579524886,49.7914,7.077527653,7.070595431,-3.0796875,6.964463173,-2.777459608,44.99999998 +122.67,50.42718086,-2.579523891,49.8223,7.067099103,7.071261548,-3.088125,6.988366628,-2.835674469,44.99999998 +122.68,50.4271815,-2.579522896,49.8532,7.063622941,7.071483547,-3.0946875,7.010810703,-2.891416559,44.99999998 +122.69,50.42718213,-2.5795219,49.8842,7.063622981,7.070595249,-3.1,7.031790641,-2.944637233,44.99999998 +122.7,50.42718277,-2.579520906,49.9152,7.067099217,7.070373129,-3.1046875,7.051302146,-2.995290198,44.99999998 +122.71,50.4271834,-2.579519911,49.9463,7.077527838,7.071705426,-3.108125,7.069340977,-3.043331219,44.99999998 +122.72,50.42718404,-2.579518915,49.9774,7.084480254,7.072371544,-3.1096875,7.085903526,-3.088718414,44.99999998 +122.73,50.42718468,-2.57951792,50.0085,7.077527888,7.071483246,-3.1096875,7.100986296,-3.131412193,44.99999998 +122.74,50.42718531,-2.579516925,50.0396,7.067099338,7.070594947,-3.108125,7.114586079,-3.171375369,44.99999998 +122.75,50.42718595,-2.57951593,50.0707,7.063623192,7.070372827,-3.105,7.126700069,-3.208573049,44.99999998 +122.76,50.42718658,-2.579514935,50.1017,7.063623243,7.070372768,-3.10125,7.137325743,-3.242972748,44.99999998 +122.77,50.42718722,-2.57951394,50.1327,7.067099475,7.070372708,-3.0965625,7.146460867,-3.274544556,44.99999998 +122.78,50.42718785,-2.579512945,50.1637,7.077528076,7.070594707,-3.0896875,7.154103551,-3.303260914,44.99999998 +122.79,50.42718849,-2.57951195,50.1945,7.084480479,7.071482883,-3.0815625,7.160252191,-3.329096841,44.99999998 +122.8,50.42718913,-2.579510955,50.2253,7.077528128,7.07237106,-3.0734375,7.164905525,-3.352029649,44.99999998 +122.81,50.42718976,-2.579509959,50.256,7.067099601,7.071704822,-3.064375,7.168062522,-3.372039512,44.99999998 +122.82,50.4271904,-2.579508964,50.2866,7.063623456,7.070372404,-3.053125,7.16972261,-3.389108842,44.99999998 +122.83,50.42719103,-2.57950797,50.3171,7.063623487,7.070594403,-3.0396875,7.169885387,-3.403222855,44.99999998 +122.84,50.42719167,-2.579506974,50.3474,7.063623505,7.071482579,-3.025,7.168550797,-3.414369233,44.99999998 +122.85,50.4271923,-2.579505979,50.3776,7.063623529,7.071260458,-3.0096875,7.165719125,-3.422538179,44.99999998 +122.86,50.42719294,-2.579504984,50.4076,7.067099762,7.070594219,-2.993125,7.161391059,-3.427722645,44.99999998 +122.87,50.42719357,-2.579503989,50.4375,7.077528391,7.070372098,-2.9746875,7.155567344,-3.429918105,44.99999998 +122.88,50.42719421,-2.579502994,50.4671,7.084480815,7.070594096,-2.9546875,7.148249355,-3.429122553,44.99999998 +122.89,50.42719485,-2.579501999,50.4966,7.077528456,7.071260212,-2.9334375,7.139438467,-3.425336849,44.99999998 +122.9,50.42719548,-2.579501004,50.5258,7.067099901,7.071704268,-2.91125,7.129136686,-3.418564144,44.99999998 +122.91,50.42719612,-2.579500008,50.5548,7.063623736,7.071482146,-2.8884375,7.117346017,-3.408810397,44.99999998 +122.92,50.42719675,-2.579499014,50.5836,7.063623773,7.071482084,-2.8646875,7.104068981,-3.396084145,44.99999998 +122.93,50.42719739,-2.579498018,50.6121,7.067100006,7.07170408,-2.8396875,7.089308385,-3.380396446,44.99999998 +122.94,50.42719802,-2.579497023,50.6404,7.07752862,7.071259897,-2.813125,7.073067266,-3.361760993,44.99999998 +122.95,50.42719866,-2.579496028,50.6684,7.084481036,7.070593655,-2.784375,7.055349004,-3.340194003,44.99999998 +122.96,50.4271993,-2.579495033,50.6961,7.077528672,7.070371532,-2.7534375,7.036157382,-3.315714381,44.99999998 +122.97,50.42719993,-2.579494038,50.7235,7.067100114,7.070593527,-2.7215625,7.015496294,-3.288343327,44.99999998 +122.98,50.42720057,-2.579493043,50.7505,7.063623959,7.07125964,-2.69,6.993370097,-3.25810485,44.99999998 +122.99,50.4272012,-2.579492048,50.7773,7.063624004,7.071481635,-2.6584375,6.969783487,-3.225025246,44.99999998 +123,50.42720184,-2.579491052,50.8037,7.067100232,7.070593332,-2.6259375,6.944741278,-3.189133336,44.99999998 +123.01,50.42720247,-2.579490058,50.8298,7.077528835,7.070371207,-2.5915625,6.918248741,-3.150460518,44.99999998 +123.02,50.42720311,-2.579489063,50.8556,7.084481242,7.071703497,-2.5546875,6.890311433,-3.109040368,44.99999998 +123.03,50.42720375,-2.579488067,50.8809,7.07752888,7.072369608,-2.5165625,6.8609352,-3.064909153,44.99999998 +123.04,50.42720438,-2.579487072,50.9059,7.067100333,7.071481304,-2.4784375,6.830126113,-3.018105262,44.99999998 +123.05,50.42720502,-2.579486077,50.9305,7.063624177,7.070592999,-2.439375,6.797890648,-2.968669547,44.99999998 +123.06,50.42720565,-2.579485082,50.9547,7.063624213,7.070592931,-2.3984375,6.764235508,-2.916645151,44.99999998 +123.07,50.42720629,-2.579484087,50.9785,7.067100438,7.071259041,-2.35625,6.729167798,-2.862077338,44.99999998 +123.08,50.42720692,-2.579483092,51.0018,7.077529038,7.071481032,-2.3134375,6.692694737,-2.805013779,44.99999998 +123.09,50.42720756,-2.579482096,51.0248,7.084481436,7.070592724,-2.27,6.654824061,-2.745504205,44.99999998 +123.1,50.4272082,-2.579481102,51.0472,7.077529064,7.070370594,-2.22625,6.61556356,-2.683600469,44.99999998 +123.11,50.42720883,-2.579480107,51.0693,7.067100515,7.071702881,-2.1815625,6.574921487,-2.61935666,44.99999998 +123.12,50.42720947,-2.579479111,51.0909,7.063624362,7.072368989,-2.1346875,6.53290632,-2.552828697,44.99999998 +123.13,50.4272101,-2.579478116,51.112,7.063624388,7.07148068,-2.0865625,6.489526825,-2.484074621,44.99999998 +123.14,50.42721074,-2.579477121,51.1326,7.067100592,7.07059237,-2.0384375,6.444792114,-2.413154421,44.99999998 +123.15,50.42721137,-2.579476126,51.1528,7.077529183,7.070370239,-1.9896875,6.398711468,-2.340129861,44.99999998 +123.16,50.42721201,-2.579475131,51.1724,7.084481592,7.070370166,-1.9396875,6.351294569,-2.265064712,44.99999998 +123.17,50.42721265,-2.579474136,51.1916,7.07752924,7.070370092,-1.8884375,6.302551216,-2.188024406,44.99999998 +123.18,50.42721328,-2.579473141,51.2102,7.067100697,7.070592077,-1.83625,6.252491722,-2.109076093,44.99999998 +123.19,50.42721392,-2.579472146,51.2283,7.063624531,7.07148024,-1.78375,6.201126399,-2.028288643,44.99999998 +123.2,50.42721455,-2.579471151,51.2459,7.063624544,7.072368403,-1.73125,6.148466135,-1.945732472,44.99999998 +123.21,50.42721519,-2.579470155,51.2629,7.063624549,7.071702149,-1.678125,6.094521815,-1.861479659,44.99999998 +123.22,50.42721582,-2.57946916,51.2795,7.063624557,7.070369717,-1.623125,6.039304726,-1.775603541,44.99999998 +123.23,50.42721646,-2.579468166,51.2954,7.067100775,7.070591699,-1.5665625,5.982826385,-1.688179062,44.99999998 +123.24,50.42721709,-2.57946717,51.3108,7.077529389,7.071479858,-1.5103125,5.925098596,-1.59928254,44.99999998 +123.25,50.42721773,-2.579466175,51.3256,7.084481798,7.07125772,-1.4546875,5.866133446,-1.508991325,44.99999998 +123.26,50.42721837,-2.57946518,51.3399,7.077529421,7.070591463,-1.398125,5.805943256,-1.417384311,44.99999998 +123.27,50.427219,-2.579464185,51.3536,7.067100847,7.070369325,-1.34,5.744540572,-1.324541314,44.99999998 +123.28,50.42721964,-2.57946319,51.3667,7.063624665,7.070591304,-1.2815625,5.681938172,-1.23054329,44.99999998 +123.29,50.42722027,-2.579462195,51.3792,7.063624684,7.071257401,-1.223125,5.618149177,-1.135472231,44.99999998 +123.3,50.42722091,-2.5794612,51.3912,7.067100898,7.071701438,-1.163125,5.553186935,-1.039410987,44.99999998 +123.31,50.42722154,-2.579460204,51.4025,7.077529494,7.071479297,-1.101875,5.48706497,-0.94244338,44.99999998 +123.32,50.42722218,-2.57945921,51.4132,7.084481894,7.071479214,-1.0415625,5.419797089,-0.844653923,44.99999998 +123.33,50.42722282,-2.579458214,51.4233,7.077529517,7.07170119,-0.9815625,5.351397388,-0.746127929,44.99999998 +123.34,50.42722345,-2.579457219,51.4329,7.067100941,7.071256987,-0.92,5.281880075,-0.646951341,44.99999998 +123.35,50.42722409,-2.579456224,51.4417,7.063624753,7.070590724,-0.858125,5.211259703,-0.547210562,44.99999998 +123.36,50.42722472,-2.579455229,51.45,7.063624767,7.07036858,-0.796875,5.139551056,-0.446992623,44.99999998 +123.37,50.42722536,-2.579454234,51.4577,7.067100979,7.070590553,-0.734375,5.066769087,-0.346384844,44.99999998 +123.38,50.42722599,-2.579453239,51.4647,7.077529575,7.071256644,-0.6703125,4.992928979,-0.245475058,44.99999998 +123.39,50.42722663,-2.579452244,51.4711,7.084481966,7.071478615,-0.606875,4.918046145,-0.144351216,44.99999998 +123.4,50.42722727,-2.579451248,51.4768,7.077529571,7.07059029,-0.5446875,4.842136228,-0.043101495,44.99999998 +123.41,50.4272279,-2.579450254,51.482,7.067100989,7.070368141,-0.4815625,4.765215097,0.058185812,44.99999998 +123.42,50.42722854,-2.579449259,51.4865,7.063624812,7.071700407,-0.4165625,4.687298852,0.159422355,44.99999998 +123.43,50.42722917,-2.579448263,51.4903,7.063624833,7.072366495,-0.351875,4.60840371,0.260519899,44.99999998 +123.44,50.42722981,-2.579447268,51.4935,7.063624844,7.071478168,-0.2884375,4.528546113,0.361390264,44.99999998 +123.45,50.42723044,-2.579446273,51.4961,7.063624841,7.070589838,-0.2246875,4.447742849,0.461945503,44.99999998 +123.46,50.42723108,-2.579445278,51.498,7.067101022,7.070367686,-0.16,4.366010706,0.562097896,44.99999998 +123.47,50.42723171,-2.579444283,51.4993,7.077529594,7.070367593,-0.0953125,4.283366815,0.66176018,44.99999998 +123.48,50.42723235,-2.579443288,51.4999,7.08448199,7.070367499,-0.0315625,4.199828308,0.760845324,44.99999998 +123.49,50.42723299,-2.579442293,51.4999,7.077529619,7.070589464,0.031875,4.115412775,0.859267097,44.99999998 +123.5,50.42723362,-2.579441298,51.4993,7.06710104,7.071477605,0.096875,4.030137805,0.956939499,44.99999998 +123.51,50.42723426,-2.579440303,51.498,7.063624832,7.072365746,0.163125,3.944021217,1.053777445,44.99999998 +123.52,50.42723489,-2.579439307,51.496,7.06362482,7.071699472,0.228125,3.857080887,1.149696481,44.99999998 +123.53,50.42723553,-2.579438312,51.4934,7.067101018,7.070367019,0.2915625,3.769335094,1.244613014,44.99999998 +123.54,50.42723616,-2.579437318,51.4902,7.077529612,7.07058898,0.355,3.680802171,1.338444192,44.99999998 +123.55,50.4272368,-2.579436322,51.4863,7.084482,7.071477118,0.4184375,3.591500511,1.431108198,44.99999998 +123.56,50.42723744,-2.579435327,51.4818,7.077529604,7.071254959,0.4815625,3.501448791,1.522524301,44.99999998 +123.57,50.42723807,-2.579434332,51.4767,7.067101016,7.070588681,0.5453125,3.410665863,1.61261269,44.99999998 +123.58,50.42723871,-2.579433337,51.4709,7.063624814,7.07036652,0.6096875,3.319170691,1.701294926,44.99999998 +123.59,50.42723934,-2.579432342,51.4645,7.063624801,7.070588478,0.673125,3.226982298,1.788493544,44.99999998 +123.6,50.42723998,-2.579431347,51.4574,7.067100984,7.071254553,0.735,3.134120049,1.874132629,44.99999998 +123.61,50.42724061,-2.579430352,51.4498,7.077529561,7.071698569,0.796875,3.040603252,1.958137409,44.99999998 +123.62,50.42724125,-2.579429356,51.4415,7.084481949,7.071476406,0.86,2.946451447,2.040434661,44.99999998 +123.63,50.42724189,-2.579428362,51.4326,7.077529559,7.071476301,0.9228125,2.851684342,2.120952591,44.99999998 +123.64,50.42724252,-2.579427366,51.423,7.067100964,7.071698254,0.9834375,2.756321705,2.199621072,44.99999998 +123.65,50.42724316,-2.579426371,51.4129,7.063624744,7.07125403,1.043125,2.660383417,2.276371461,44.99999998 +123.66,50.42724379,-2.579425376,51.4022,7.063624727,7.070587746,1.10375,2.563889533,2.351136781,44.99999998 +123.67,50.42724443,-2.579424381,51.3908,7.06710092,7.07036558,1.1646875,2.466860219,2.423851886,44.99999998 +123.68,50.42724506,-2.579423386,51.3789,7.077529503,7.070587532,1.2246875,2.369315758,2.49445335,44.99999998 +123.69,50.4272457,-2.579422391,51.3663,7.084481882,7.071253601,1.2834375,2.271276492,2.562879637,44.99999998 +123.7,50.42724634,-2.579421396,51.3532,7.077529468,7.07147555,1.34125,2.172762873,2.629070987,44.99999998 +123.71,50.42724697,-2.5794204,51.3395,7.067100855,7.070587203,1.39875,2.073795529,2.692969819,44.99999998 +123.72,50.42724761,-2.579419406,51.3252,7.063624646,7.070365034,1.45625,1.974395087,2.754520326,44.99999998 +123.73,50.42724824,-2.579418411,51.3104,7.063624648,7.071697278,1.5134375,1.874582344,2.813668822,44.99999998 +123.74,50.42724888,-2.579417415,51.2949,7.067100839,7.072363344,1.5696875,1.774378042,2.870363798,44.99999998 +123.75,50.42724951,-2.57941642,51.279,7.077529398,7.071474995,1.6246875,1.673803265,2.92455575,44.99999998 +123.76,50.42725015,-2.579415425,51.2624,7.084481752,7.070586645,1.67875,1.572878926,2.976197468,44.99999998 +123.77,50.42725079,-2.57941443,51.2454,7.077529336,7.070586531,1.7328125,1.471626054,3.025243858,44.99999998 +123.78,50.42725142,-2.579413435,51.2278,7.067100743,7.071252594,1.786875,1.370065904,3.071652236,44.99999998 +123.79,50.42725206,-2.57941244,51.2096,7.063624546,7.07147454,1.839375,1.26821962,3.115382094,44.99999998 +123.8,50.42725269,-2.579411444,51.191,7.06362453,7.070586188,1.89,1.166108456,3.156395215,44.99999998 +123.81,50.42725333,-2.57941045,51.1718,7.063624503,7.070364013,1.9403125,1.063753786,3.194655962,44.99999998 +123.82,50.42725396,-2.579409455,51.1522,7.063624473,7.071696251,1.99125,0.96117698,3.23013093,44.99999998 +123.83,50.4272546,-2.579408459,51.132,7.067100641,7.072362312,2.0415625,0.858399467,3.262789181,44.99999998 +123.84,50.42725523,-2.579407464,51.1113,7.077529203,7.071473958,2.089375,0.755442618,3.292602237,44.99999998 +123.85,50.42725587,-2.579406469,51.0902,7.084481574,7.070585603,2.135,0.652328034,3.319544031,44.99999998 +123.86,50.42725651,-2.579405474,51.0686,7.077529166,7.070363425,2.1803125,0.549077258,3.343591184,44.99999998 +123.87,50.42725714,-2.579404479,51.0466,7.067100562,7.070363306,2.22625,0.445711776,3.36472267,44.99999998 +123.88,50.42725778,-2.579403484,51.0241,7.063624343,7.070363187,2.2715625,0.342253245,3.382920096,44.99999998 +123.89,50.42725841,-2.579402489,51.0011,7.063624311,7.070585126,2.3146875,0.238723209,3.398167534,44.99999998 +123.9,50.42725905,-2.579401494,50.9778,7.067100475,7.071473242,2.356875,0.135143326,3.410451692,44.99999998 +123.91,50.42725968,-2.579400499,50.954,7.077529034,7.072361357,2.3996875,0.031535196,3.419761912,44.99999998 +123.92,50.42726032,-2.579399503,50.9298,7.084481402,7.071695059,2.44125,-0.072079466,3.426090059,44.99999998 +123.93,50.42726096,-2.579398508,50.9051,7.077528988,7.070362582,2.48,-0.175679116,3.429430632,44.99999998 +123.94,50.42726159,-2.579397514,50.8802,7.067100375,7.070584518,2.518125,-0.279242097,3.429780652,44.99999998 +123.95,50.42726223,-2.579396518,50.8548,7.063624149,7.071472632,2.5565625,-0.382746693,3.427139832,44.99999998 +123.96,50.42726286,-2.579395523,50.829,7.063624126,7.07125045,2.5928125,-0.48617142,3.421510522,44.99999998 +123.97,50.4272635,-2.579394528,50.8029,7.067100298,7.070584149,2.6265625,-0.589494618,3.412897591,44.99999998 +123.98,50.42726413,-2.579393533,50.7765,7.077528851,7.070361966,2.66,-0.69269463,3.401308603,44.99999998 +123.99,50.42726477,-2.579392538,50.7497,7.084481211,7.070583901,2.693125,-0.795750085,3.386753584,44.99999998 +124,50.42726541,-2.579391543,50.7226,7.0775288,7.071249954,2.7246875,-0.898639267,3.369245255,44.99999998 +124.01,50.42726604,-2.579390548,50.6952,7.067100186,7.071693947,2.7546875,-1.001340863,3.348798912,44.99999998 +124.02,50.42726668,-2.579389552,50.6675,7.063623949,7.071471762,2.7834375,-1.103833273,3.325432375,44.99999998 +124.03,50.42726731,-2.579388558,50.6395,7.063623919,7.071471637,2.8115625,-1.206095181,3.299166042,44.99999998 +124.04,50.42726795,-2.579387562,50.6113,7.067100095,7.071693571,2.8396875,-1.308105217,3.270022715,44.99999998 +124.05,50.42726858,-2.579386567,50.5827,7.077528646,7.071249326,2.86625,-1.409842067,3.23802795,44.99999998 +124.06,50.42726922,-2.579385572,50.5539,7.084480988,7.070583021,2.8896875,-1.511284531,3.203209534,44.99999998 +124.07,50.42726986,-2.579384577,50.5249,7.077528557,7.070360836,2.9115625,-1.612411353,3.165597834,44.99999998 +124.08,50.42727049,-2.579383582,50.4957,7.067099946,7.070582769,2.9334375,-1.71320139,3.125225738,44.99999998 +124.09,50.42727113,-2.579382587,50.4662,7.063623734,7.071248819,2.9546875,-1.813633729,3.082128426,44.99999998 +124.1,50.42727176,-2.579381592,50.4366,7.063623718,7.07147075,2.9746875,-1.913687286,3.036343426,44.99999998 +124.11,50.4272724,-2.579380596,50.4067,7.067099885,7.070582385,2.993125,-2.013341148,2.987910673,44.99999998 +124.12,50.42727303,-2.579379602,50.3767,7.077528425,7.070360198,3.0096875,-2.112574631,2.936872395,44.99999998 +124.13,50.42727367,-2.579378607,50.3465,7.084480763,7.071692425,3.025,-2.211366879,2.883273167,44.99999998 +124.14,50.42727431,-2.579377611,50.3162,7.077528333,7.072358474,3.0396875,-2.309697322,2.827159686,44.99999998 +124.15,50.42727494,-2.579376616,50.2857,7.067099727,7.07147011,3.053125,-2.407545393,2.768580825,44.99999998 +124.16,50.42727558,-2.579375621,50.2551,7.063623517,7.070581745,3.0646875,-2.504890693,2.707587749,44.99999998 +124.17,50.42727621,-2.579374626,50.2244,7.063623486,7.070359557,3.0746875,-2.601712883,2.644233628,44.99999998 +124.18,50.42727685,-2.579373631,50.1936,7.063623439,7.070359428,3.083125,-2.697991737,2.578573696,44.99999998 +124.19,50.42727748,-2.579372636,50.1627,7.063623395,7.0703593,3.09,-2.793707144,2.510665191,44.99999998 +124.2,50.42727812,-2.579371641,50.1318,7.067099561,7.070581231,3.0965625,-2.888839166,2.440567357,44.99999998 +124.21,50.42727875,-2.579370646,50.1008,7.077528121,7.071469337,3.103125,-2.983367805,2.368341329,44.99999998 +124.22,50.42727939,-2.579369651,50.0697,7.084480478,7.072357444,3.1078125,-3.077273468,2.294050074,44.99999998 +124.23,50.42728003,-2.579368655,50.0386,7.077528054,7.071691138,3.1096875,-3.170536501,2.217758337,44.99999998 +124.24,50.42728066,-2.57936766,50.0075,7.067099439,7.070358655,3.1096875,-3.263137367,2.139532696,44.99999998 +124.25,50.4272813,-2.579366666,49.9764,7.06362321,7.070580584,3.108125,-3.355056757,2.05944139,44.99999998 +124.26,50.42728193,-2.57936567,49.9453,7.06362317,7.071468691,3.105,-3.446275534,1.977554147,44.99999998 +124.27,50.42728257,-2.579364675,49.9143,7.067099325,7.071246504,3.1015625,-3.536774562,1.89394253,44.99999998 +124.28,50.4272832,-2.57936368,49.8833,7.077527874,7.070580198,3.0984375,-3.626534989,1.808679306,44.99999998 +124.29,50.42728384,-2.579362685,49.8523,7.084480235,7.07035801,3.094375,-3.715538081,1.7218389,44.99999998 +124.3,50.42728448,-2.57936169,49.8214,7.077527823,7.07057994,3.088125,-3.803765216,1.633497059,44.99999998 +124.31,50.42728511,-2.579360695,49.7905,7.067099206,7.071245987,3.0796875,-3.891197946,1.54373073,44.99999998 +124.32,50.42728575,-2.5793597,49.7598,7.063622965,7.071689977,3.0696875,-3.977818106,1.452618294,44.99999998 +124.33,50.42728638,-2.579358704,49.7291,7.063622925,7.07146779,3.0584375,-4.063607535,1.360239105,44.99999998 +124.34,50.42728702,-2.57935771,49.6986,7.067099096,7.071467662,3.04625,-4.148548299,1.266673779,44.99999998 +124.35,50.42728765,-2.579356714,49.6682,7.077527656,7.071689592,3.033125,-4.232622694,1.172003906,44.99999998 +124.36,50.42728829,-2.579355719,49.6379,7.084480014,7.071245346,3.018125,-4.315813186,1.076312047,44.99999998 +124.37,50.42728893,-2.579354724,49.6078,7.077527582,7.070579041,3.00125,-4.398102416,0.979681626,44.99999998 +124.38,50.42728956,-2.579353729,49.5779,7.067098954,7.070356854,2.9834375,-4.47947308,0.882196868,44.99999998 +124.39,50.4272902,-2.579352734,49.5481,7.063622729,7.070578786,2.9646875,-4.559908333,0.783942857,44.99999998 +124.4,50.42729083,-2.579351739,49.5186,7.063622715,7.071244836,2.9446875,-4.639391273,0.68500525,44.99999998 +124.41,50.42729147,-2.579350744,49.4892,7.063622696,7.071466767,2.9234375,-4.717905284,0.585470277,44.99999998 +124.42,50.4272921,-2.579349748,49.4601,7.06362266,7.070578404,2.9009375,-4.795434094,0.485424741,44.99999998 +124.43,50.42729274,-2.579348754,49.4312,7.067098806,7.070356219,2.876875,-4.871961431,0.384955961,44.99999998 +124.44,50.42729337,-2.579347759,49.4025,7.077527342,7.071688446,2.85125,-4.94747131,0.284151486,44.99999998 +124.45,50.42729401,-2.579346763,49.3742,7.084479703,7.072354497,2.825,-5.021947973,0.183099206,44.99999998 +124.46,50.42729465,-2.579345768,49.346,7.077527303,7.071466136,2.798125,-5.095375838,0.081887243,44.99999998 +124.47,50.42729528,-2.579344773,49.3182,7.0670987,7.070577775,2.7696875,-5.167739605,-0.019396111,44.99999998 +124.48,50.42729592,-2.579343778,49.2906,7.063622471,7.07057765,2.74,-5.239024207,-0.120662505,44.99999998 +124.49,50.42729655,-2.579342783,49.2634,7.063622432,7.071243701,2.709375,-5.309214688,-0.221823762,44.99999998 +124.5,50.42729719,-2.579341788,49.2364,7.067098591,7.071465636,2.6765625,-5.378296381,-0.32279153,44.99999998 +124.51,50.42729782,-2.579340792,49.2098,7.077527145,7.070577276,2.6415625,-5.446254905,-0.423477805,44.99999998 +124.52,50.42729846,-2.579339798,49.1836,7.084479508,7.070355093,2.606875,-5.513076051,-0.523794865,44.99999998 +124.53,50.4272991,-2.579338803,49.1577,7.077527097,7.071687323,2.573125,-5.578745838,-0.623655106,44.99999998 +124.54,50.42729973,-2.579337807,49.1321,7.067098494,7.072353377,2.5378125,-5.643250572,-0.722971553,44.99999998 +124.55,50.42730037,-2.579336812,49.1069,7.063622279,7.071465019,2.4996875,-5.70657679,-0.821657517,44.99999998 +124.56,50.427301,-2.579335817,49.0821,7.063622248,7.070576662,2.4596875,-5.768711312,-0.919626998,44.99999998 +124.57,50.42730164,-2.579334822,49.0577,7.067098399,7.070354481,2.4184375,-5.829641077,-1.016794566,44.99999998 +124.58,50.42730227,-2.579333827,49.0337,7.077526943,7.07035436,2.3765625,-5.889353363,-1.113075483,44.99999998 +124.59,50.42730291,-2.579332832,49.0102,7.084479314,7.070354239,2.335,-5.947835796,-1.208385752,44.99999998 +124.6,50.42730355,-2.579331837,48.987,7.07752692,7.070576178,2.293125,-6.005076055,-1.302642294,44.99999998 +124.61,50.42730418,-2.579330842,48.9643,7.067098323,7.071464293,2.2496875,-6.061062225,-1.395762947,44.99999998 +124.62,50.42730482,-2.579329847,48.942,7.063622093,7.072574468,2.2046875,-6.115782674,-1.487666409,44.99999998 +124.63,50.42730545,-2.579328851,48.9202,7.063622052,7.072574349,2.158125,-6.169225885,-1.578272636,44.99999998 +124.64,50.42730609,-2.579327856,48.8988,7.067098219,7.071463937,2.1103125,-6.221380687,-1.66750262,44.99999998 +124.65,50.42730672,-2.579326861,48.878,7.077526785,7.070575584,2.063125,-6.272236306,-1.755278493,44.99999998 +124.66,50.42730736,-2.579325866,48.8576,7.084479159,7.070353408,2.0165625,-6.321782029,-1.84152371,44.99999998 +124.67,50.427308,-2.579324871,48.8376,7.077526759,7.070353291,1.9675,-6.370007486,-1.926163156,44.99999998 +124.68,50.42730863,-2.579323876,48.8182,7.067098157,7.070353175,1.915,-6.416902706,-2.009122918,44.99999998 +124.69,50.42730927,-2.579322881,48.7993,7.063621932,7.070353059,1.861875,-6.462457835,-2.09033069,44.99999998 +124.7,50.4273099,-2.579321886,48.781,7.063621912,7.070575003,1.81,-6.506663306,-2.169715654,44.99999998 +124.71,50.42731054,-2.579320891,48.7631,7.067098099,7.071463124,1.7584375,-6.549510006,-2.247208597,44.99999998 +124.72,50.42731117,-2.579319896,48.7458,7.077526661,7.072573304,1.7059375,-6.590988885,-2.322741967,44.99999998 +124.73,50.42731181,-2.5793189,48.729,7.084479021,7.072573191,1.651875,-6.631091347,-2.396249874,44.99999998 +124.74,50.42731245,-2.579317905,48.7127,7.077526611,7.071462784,1.59625,-6.66980897,-2.467668204,44.99999998 +124.75,50.42731308,-2.57931691,48.6971,7.067098013,7.070574437,1.54,-6.707133675,-2.536934676,44.99999998 +124.76,50.42731372,-2.579315915,48.6819,7.063621809,7.070352267,1.4834375,-6.743057728,-2.603988901,44.99999998 +124.77,50.42731435,-2.57931492,48.6674,7.063621801,7.070352156,1.4265625,-6.777573565,-2.668772436,44.99999998 +124.78,50.42731499,-2.579313925,48.6534,7.063621788,7.070352046,1.37,-6.810673967,-2.731228732,44.99999998 +124.79,50.42731562,-2.57931293,48.64,7.063621774,7.070573996,1.3128125,-6.842352058,-2.791303357,44.99999998 +124.8,50.42731626,-2.579311935,48.6271,7.06709795,7.071462122,1.2534375,-6.872601251,-2.848943942,44.99999998 +124.81,50.42731689,-2.57931094,48.6149,7.077526507,7.072350249,1.193125,-6.901415126,-2.904100183,44.99999998 +124.82,50.42731753,-2.579309944,48.6033,7.084478875,7.071683964,1.1334375,-6.928787784,-2.956724007,44.99999998 +124.83,50.42731817,-2.579308949,48.5922,7.077526484,7.070351504,1.073125,-6.954713379,-3.006769579,44.99999998 +124.84,50.4273188,-2.579307955,48.5818,7.067097903,7.070573457,1.0115625,-6.979186641,-3.054193124,44.99999998 +124.85,50.42731944,-2.579306959,48.572,7.063621701,7.071461587,0.9503125,-7.002202356,-3.098953446,44.99999998 +124.86,50.42732007,-2.579305964,48.5628,7.063621685,7.071239424,0.89,-7.023755768,-3.141011356,44.99999998 +124.87,50.42732071,-2.579304969,48.5542,7.067097864,7.070573144,0.8296875,-7.04384235,-3.180330298,44.99999998 +124.88,50.42732134,-2.579303974,48.5462,7.077526437,7.070350981,0.768125,-7.062457921,-3.216875953,44.99999998 +124.89,50.42732198,-2.579302979,48.5388,7.08447882,7.070572936,0.7046875,-7.079598583,-3.250616463,44.99999998 +124.9,50.42732262,-2.579301984,48.5321,7.077526431,7.071239011,0.64,-7.095260786,-3.281522322,44.99999998 +124.91,50.42732325,-2.579300989,48.526,7.067097849,7.071683028,0.5753125,-7.109441205,-3.309566716,44.99999998 +124.92,50.42732389,-2.579299993,48.5206,7.06362165,7.071460868,0.5115625,-7.122136918,-3.334725063,44.99999998 +124.93,50.42732452,-2.579298999,48.5158,7.063621638,7.071460767,0.4484375,-7.133345233,-3.356975478,44.99999998 +124.94,50.42732516,-2.579298003,48.5116,7.067097822,7.071682727,0.385,-7.143063858,-3.376298594,44.99999998 +124.95,50.42732579,-2.579297008,48.5081,7.0775264,7.071238511,0.3215625,-7.151290787,-3.39267751,44.99999998 +124.96,50.42732643,-2.579296013,48.5052,7.08447879,7.070572237,0.2584375,-7.158024244,-3.406097957,44.99999998 +124.97,50.42732707,-2.579295018,48.5029,7.077526411,7.070350081,0.1946875,-7.163262797,-3.416548249,44.99999998 +124.98,50.4273277,-2.579294023,48.5013,7.067097829,7.070572043,0.13,-7.167005415,-3.424019275,44.99999998 +124.99,50.42732834,-2.579293028,48.5003,7.063621624,7.071238123,0.065,-7.169251295,-3.428504503,44.99999998 +125,50.42732897,-2.579292033,48.5,7.063621624,7.071460087,-1.44E-12,-7.169999979,-3.42999998,44.99999998 +125.01,50.42732961,-2.579291037,48.5003,7.063621638,7.070571758,-0.065,-7.169251295,-3.428504503,44.99999998 +125.02,50.42733024,-2.579290043,48.5013,7.063621645,7.070349606,-0.13,-7.167005415,-3.424019275,44.99999998 +125.03,50.42733088,-2.579289048,48.5029,7.067097833,7.071681866,-0.1946875,-7.163262797,-3.416548249,44.99999998 +125.04,50.42733151,-2.579288052,48.5052,7.077526401,7.07234795,-0.2584375,-7.158024244,-3.406097957,44.99999998 +125.05,50.42733215,-2.579287057,48.5081,7.084478779,7.071459623,-0.3215625,-7.151290787,-3.39267751,44.99999998 +125.06,50.42733279,-2.579286062,48.5116,7.077526401,7.070571298,-0.385,-7.143063858,-3.376298594,44.99999998 +125.07,50.42733342,-2.579285067,48.5158,7.067097848,7.070349149,-0.4484375,-7.133345233,-3.356975478,44.99999998 +125.08,50.42733406,-2.579284072,48.5206,7.067097867,7.070349059,-0.5115625,-7.122136918,-3.334725063,44.99999998 +125.09,50.42733469,-2.579283077,48.526,7.077526446,7.07034897,-0.5753125,-7.109441205,-3.309566716,44.99999998 +125.1,50.42733533,-2.579282082,48.5321,7.084478822,7.070570941,-0.64,-7.095260786,-3.281522322,44.99999998 +125.11,50.42733597,-2.579281087,48.5388,7.077526435,7.071459089,-0.7046875,-7.079598583,-3.250616463,44.99999998 +125.12,50.4273366,-2.579280092,48.5462,7.067097874,7.072569296,-0.768125,-7.062457921,-3.216875953,44.99999998 +125.13,50.42733724,-2.579279096,48.5542,7.063621707,7.07256921,-0.8296875,-7.04384235,-3.180330298,44.99999998 +125.14,50.42733787,-2.579278101,48.5628,7.063621722,7.071458832,-0.89,-7.023755768,-3.141011356,44.99999998 +125.15,50.42733851,-2.579277106,48.572,7.063621729,7.070570513,-0.9503125,-7.002202356,-3.098953446,44.99999998 +125.16,50.42733914,-2.579276111,48.5818,7.063621738,7.07034837,-1.0115625,-6.979186641,-3.054193124,44.99999998 +125.17,50.42733978,-2.579275116,48.5922,7.06709794,7.070348287,-1.073125,-6.954713379,-3.006769579,44.99999998 +125.18,50.42734041,-2.579274121,48.6033,7.077526523,7.070348204,-1.1334375,-6.928787784,-2.956724007,44.99999998 +125.19,50.42734105,-2.579273126,48.6149,7.084478917,7.070570181,-1.193125,-6.901415126,-2.904100183,44.99999998 +125.2,50.42734169,-2.579272131,48.6271,7.077526551,7.071458335,-1.2534375,-6.872601251,-2.848943942,44.99999998 +125.21,50.42734232,-2.579271136,48.64,7.067097999,7.072568547,-1.3128125,-6.842352058,-2.791303357,44.99999998 +125.22,50.42734296,-2.57927014,48.6534,7.063621829,7.072568468,-1.37,-6.810673967,-2.731228732,44.99999998 +125.23,50.42734359,-2.579269145,48.6674,7.063621841,7.071458096,-1.4265625,-6.777573565,-2.668772436,44.99999998 +125.24,50.42734423,-2.57926815,48.6819,7.067098034,7.070569782,-1.4834375,-6.743057728,-2.603988901,44.99999998 +125.25,50.42734486,-2.579267155,48.6971,7.077526622,7.070347645,-1.54,-6.707133675,-2.536934676,44.99999998 +125.26,50.4273455,-2.57926616,48.7127,7.084479036,7.070347568,-1.59625,-6.66980897,-2.467668204,44.99999998 +125.27,50.42734614,-2.579265165,48.729,7.077526685,7.070347491,-1.651875,-6.631091347,-2.396249874,44.99999998 +125.28,50.42734677,-2.57926417,48.7458,7.067098132,7.070347415,-1.7059375,-6.590988885,-2.322741967,44.99999998 +125.29,50.42734741,-2.579263175,48.7631,7.063621947,7.070569398,-1.7584375,-6.549510006,-2.247208597,44.99999998 +125.3,50.42734804,-2.57926218,48.781,7.06362195,7.071457558,-1.81,-6.506663306,-2.169715654,44.99999998 +125.31,50.42734868,-2.579261185,48.7993,7.067098163,7.072567777,-1.861875,-6.462457835,-2.09033069,44.99999998 +125.32,50.42734931,-2.579260189,48.8182,7.07752678,7.072567704,-1.915,-6.416902706,-2.009122918,44.99999998 +125.33,50.42734995,-2.579259194,48.8376,7.0844792,7.071457337,-1.9675,-6.370007486,-1.926163156,44.99999998 +125.34,50.42735059,-2.579258199,48.8576,7.077526834,7.07056903,-2.0165625,-6.321782029,-1.84152371,44.99999998 +125.35,50.42735122,-2.579257204,48.878,7.067098264,7.070346899,-2.063125,-6.272236306,-1.755278493,44.99999998 +125.36,50.42735186,-2.579256209,48.8988,7.063622085,7.070346827,-2.1103125,-6.221380687,-1.66750262,44.99999998 +125.37,50.42735249,-2.579255214,48.9202,7.063622116,7.070346756,-2.158125,-6.169225885,-1.578272636,44.99999998 +125.38,50.42735313,-2.579254219,48.942,7.063622157,7.070568745,-2.2046875,-6.115782674,-1.487666409,44.99999998 +125.39,50.42735376,-2.579253224,48.9643,7.063622186,7.071456909,-2.2496875,-6.061062225,-1.395762947,44.99999998 +125.4,50.4273544,-2.579252229,48.987,7.067098398,7.072345074,-2.293125,-6.005076055,-1.302642294,44.99999998 +125.41,50.42735503,-2.579251233,49.0102,7.077526993,7.071678829,-2.335,-5.947835796,-1.208385752,44.99999998 +125.42,50.42735567,-2.579250238,49.0337,7.0844794,7.070346409,-2.3765625,-5.889353363,-1.113075483,44.99999998 +125.43,50.42735631,-2.579249244,49.0577,7.077527047,7.070568399,-2.4184375,-5.829641077,-1.016794566,44.99999998 +125.44,50.42735694,-2.579248248,49.0821,7.067098504,7.071456566,-2.4596875,-5.768711312,-0.919626998,44.99999998 +125.45,50.42735758,-2.579247253,49.1069,7.063622342,7.07123444,-2.4996875,-5.70657679,-0.821657517,44.99999998 +125.46,50.42735821,-2.579246258,49.1321,7.063622373,7.070568198,-2.5378125,-5.643250572,-0.722971553,44.99999998 +125.47,50.42735885,-2.579245263,49.1577,7.067098599,7.070346073,-2.573125,-5.578745838,-0.623655106,44.99999998 +125.48,50.42735948,-2.579244268,49.1836,7.077527202,7.070568065,-2.606875,-5.513076051,-0.523794865,44.99999998 +125.49,50.42736012,-2.579243273,49.2098,7.084479601,7.071234175,-2.6415625,-5.446254905,-0.423477805,44.99999998 +125.5,50.42736076,-2.579242278,49.2364,7.07752724,7.071678228,-2.6765625,-5.378296381,-0.32279153,44.99999998 +125.51,50.42736139,-2.579241282,49.2634,7.067098704,7.071456104,-2.709375,-5.309214688,-0.221823762,44.99999998 +125.52,50.42736203,-2.579240288,49.2906,7.063622556,7.071456039,-2.74,-5.239024207,-0.120662505,44.99999998 +125.53,50.42736266,-2.579239292,49.3182,7.063622585,7.071678034,-2.7696875,-5.167739605,-0.019396111,44.99999998 +125.54,50.4273633,-2.579238297,49.346,7.067098794,7.071233853,-2.798125,-5.095375838,0.081887243,44.99999998 +125.55,50.42736393,-2.579237302,49.3742,7.077527397,7.070567614,-2.825,-5.021947973,0.183099206,44.99999998 +125.56,50.42736457,-2.579236307,49.4025,7.084479825,7.070345491,-2.85125,-4.94747131,0.284151486,44.99999998 +125.57,50.42736521,-2.579235312,49.4312,7.077527488,7.070567487,-2.876875,-4.871961431,0.384955961,44.99999998 +125.58,50.42736584,-2.579234317,49.4601,7.06709895,7.0712336,-2.9009375,-4.795434094,0.485424741,44.99999998 +125.59,50.42736648,-2.579233322,49.4892,7.063622784,7.071455596,-2.9234375,-4.717905284,0.585470277,44.99999998 +125.6,50.42736711,-2.579232326,49.5186,7.063622801,7.0705673,-2.9446875,-4.639391273,0.68500525,44.99999998 +125.61,50.42736775,-2.579231332,49.5481,7.067099014,7.07034518,-2.9646875,-4.559908333,0.783942857,44.99999998 +125.62,50.42736838,-2.579230337,49.5779,7.077527626,7.07167747,-2.9834375,-4.47947308,0.882196868,44.99999998 +125.63,50.42736902,-2.579229341,49.6078,7.084480059,7.072343583,-3.00125,-4.398102416,0.979681626,44.99999998 +125.64,50.42736966,-2.579228346,49.6379,7.077527721,7.071455287,-3.018125,-4.315813186,1.076312047,44.99999998 +125.65,50.42737029,-2.579227351,49.6682,7.067099175,7.070566991,-3.033125,-4.232622694,1.172003906,44.99999998 +125.66,50.42737093,-2.579226356,49.6986,7.063623003,7.070344872,-3.04625,-4.148548299,1.266673779,44.99999998 +125.67,50.42737156,-2.579225361,49.7291,7.063623038,7.070344812,-3.0584375,-4.063607535,1.360239105,44.99999998 +125.68,50.4273722,-2.579224366,49.7598,7.067099279,7.070344751,-3.0696875,-3.977818106,1.452618294,44.99999998 +125.69,50.42737283,-2.579223371,49.7905,7.077527897,7.070566748,-3.0796875,-3.891197946,1.54373073,44.99999998 +125.7,50.42737347,-2.579222376,49.8214,7.084480313,7.071454922,-3.088125,-3.803765216,1.633497059,44.99999998 +125.71,50.42737411,-2.579221381,49.8523,7.07752796,7.072343096,-3.094375,-3.715538081,1.7218389,44.99999998 +125.72,50.42737474,-2.579220385,49.8833,7.067099414,7.07167686,-3.0984375,-3.626534989,1.808679306,44.99999998 +125.73,50.42737538,-2.57921939,49.9143,7.06362325,7.070344449,-3.1015625,-3.536774562,1.89394253,44.99999998 +125.74,50.42737601,-2.579218396,49.9453,7.063623281,7.070566447,-3.105,-3.446275534,1.977554147,44.99999998 +125.75,50.42737665,-2.5792174,49.9764,7.06362332,7.071454621,-3.108125,-3.355056757,2.05944139,44.99999998 +125.76,50.42737728,-2.579216405,50.0075,7.063623364,7.071232501,-3.1096875,-3.263137367,2.139532696,44.99999998 +125.77,50.42737792,-2.57921541,50.0386,7.067099599,7.070566266,-3.1096875,-3.170536501,2.217758337,44.99999998 +125.78,50.42737855,-2.579214415,50.0697,7.077528209,7.070344147,-3.1078125,-3.077273468,2.294050074,44.99999998 +125.79,50.42737919,-2.57921342,50.1008,7.084480615,7.070566145,-3.103125,-2.983367805,2.368341329,44.99999998 +125.8,50.42737983,-2.579212425,50.1318,7.077528257,7.071454319,-3.0965625,-2.888839166,2.440567357,44.99999998 +125.81,50.42738046,-2.57921143,50.1627,7.067099722,7.072564551,-3.09,-2.793707144,2.510665191,44.99999998 +125.82,50.4273811,-2.579210434,50.1936,7.063623573,7.072564491,-3.083125,-2.697991737,2.578573696,44.99999998 +125.83,50.42738173,-2.579209439,50.2244,7.06362361,7.071454138,-3.0746875,-2.601712883,2.644233628,44.99999998 +125.84,50.42738237,-2.579208444,50.2551,7.067099836,7.070565843,-3.0646875,-2.504890693,2.707587749,44.99999998 +125.85,50.427383,-2.579207449,50.2857,7.077528443,7.070343723,-3.053125,-2.407545393,2.768580825,44.99999998 +125.86,50.42738364,-2.579206454,50.3162,7.08448086,7.070343663,-3.0396875,-2.309697322,2.827159686,44.99999998 +125.87,50.42738428,-2.579205459,50.3465,7.077528512,7.070343601,-3.025,-2.211366879,2.883273167,44.99999998 +125.88,50.42738491,-2.579204464,50.3767,7.067099976,7.070565598,-3.0096875,-2.112574631,2.936872395,44.99999998 +125.89,50.42738555,-2.579203469,50.4067,7.063623823,7.071453771,-2.993125,-2.013341148,2.987910673,44.99999998 +125.9,50.42738618,-2.579202474,50.4366,7.063623853,7.072564002,-2.9746875,-1.913687286,3.036343426,44.99999998 +125.91,50.42738682,-2.579201478,50.4662,7.067100064,7.07256394,-2.9546875,-1.813633729,3.082128426,44.99999998 +125.92,50.42738745,-2.579200483,50.4957,7.077528671,7.071453586,-2.9334375,-1.71320139,3.125225738,44.99999998 +125.93,50.42738809,-2.579199488,50.5249,7.084481101,7.070565289,-2.9115625,-1.612411353,3.165597834,44.99999998 +125.94,50.42738873,-2.579198493,50.5539,7.077528763,7.070343168,-2.8896875,-1.511284531,3.203209534,44.99999998 +125.95,50.42738936,-2.579197498,50.5827,7.067100221,7.070343105,-2.86625,-1.409842067,3.23802795,44.99999998 +125.96,50.42739,-2.579196503,50.6113,7.063624049,7.070343042,-2.8396875,-1.308105217,3.270022715,44.99999998 +125.97,50.42739063,-2.579195508,50.6395,7.06362407,7.070565037,-2.8115625,-1.206095181,3.299166042,44.99999998 +125.98,50.42739127,-2.579194513,50.6675,7.063624104,7.071453208,-2.7834375,-1.103833273,3.325432375,44.99999998 +125.99,50.4273919,-2.579193518,50.6952,7.063624142,7.072341378,-2.7546875,-1.001340863,3.348798912,44.99999998 +126,50.42739254,-2.579192522,50.7226,7.067100369,7.071675138,-2.7246875,-0.898639267,3.369245255,44.99999998 +126.01,50.42739317,-2.579191527,50.7497,7.077528977,7.070342723,-2.693125,-0.795750085,3.386753584,44.99999998 +126.02,50.42739381,-2.579190533,50.7765,7.084481386,7.070564716,-2.66,-0.69269463,3.401308603,44.99999998 +126.03,50.42739445,-2.579189537,50.8029,7.07752902,7.071452884,-2.6265625,-0.589494618,3.412897591,44.99999998 +126.04,50.42739508,-2.579188542,50.829,7.067100476,7.071230759,-2.5928125,-0.48617142,3.421510522,44.99999998 +126.05,50.42739572,-2.579187547,50.8548,7.063624328,7.070564518,-2.5565625,-0.382746693,3.427139832,44.99999998 +126.06,50.42739635,-2.579186552,50.8802,7.063624361,7.070342393,-2.518125,-0.279242097,3.429780652,44.99999998 +126.07,50.42739699,-2.579185557,50.9051,7.067100576,7.070564384,-2.48,-0.175679116,3.429430632,44.99999998 +126.08,50.42739762,-2.579184562,50.9298,7.077529176,7.071230493,-2.44125,-0.072079466,3.426090059,44.99999998 +126.09,50.42739826,-2.579183567,50.954,7.084481586,7.071674542,-2.3996875,0.031535196,3.419761912,44.99999998 +126.1,50.4273989,-2.579182571,50.9778,7.077529231,7.071452415,-2.356875,0.135143326,3.410451692,44.99999998 +126.11,50.42739953,-2.579181577,51.0011,7.067100684,7.071452346,-2.3146875,0.238723209,3.398167534,44.99999998 +126.12,50.42740017,-2.579180581,51.0241,7.063624519,7.071674335,-2.2715625,0.342253245,3.382920096,44.99999998 +126.13,50.4274008,-2.579179586,51.0466,7.063624546,7.071230149,-2.22625,0.445711776,3.36472267,44.99999998 +126.14,50.42740144,-2.579178591,51.0686,7.06710077,7.070563903,-2.1803125,0.549077258,3.343591184,44.99999998 +126.15,50.42740207,-2.579177596,51.0902,7.077529371,7.070341773,-2.135,0.652328034,3.319544031,44.99999998 +126.16,50.42740271,-2.579176601,51.1113,7.084481767,7.07056376,-2.089375,0.755442618,3.292602237,44.99999998 +126.17,50.42740335,-2.579175606,51.132,7.077529396,7.071229864,-2.0415625,0.858399467,3.262789181,44.99999998 +126.18,50.42740398,-2.579174611,51.1522,7.06710085,7.07145185,-1.99125,0.96117698,3.23013093,44.99999998 +126.19,50.42740462,-2.579173615,51.1718,7.063624694,7.070563543,-1.9403125,1.063753786,3.194655962,44.99999998 +126.2,50.42740525,-2.579172621,51.191,7.063624721,7.070341412,-1.89,1.166108456,3.156395215,44.99999998 +126.21,50.42740589,-2.579171626,51.2096,7.067100923,7.071673689,-1.839375,1.26821962,3.115382094,44.99999998 +126.22,50.42740652,-2.57917063,51.2278,7.077529507,7.07233979,-1.786875,1.370065904,3.071652236,44.99999998 +126.23,50.42740716,-2.579169635,51.2454,7.084481914,7.07145148,-1.7328125,1.471626054,3.025243858,44.99999998 +126.24,50.4274078,-2.57916864,51.2624,7.077529564,7.07056317,-1.67875,1.572878926,2.976197468,44.99999998 +126.25,50.42740843,-2.579167645,51.279,7.067101016,7.070341035,-1.6246875,1.673803265,2.92455575,44.99999998 +126.26,50.42740907,-2.57916665,51.2949,7.063624836,7.070340958,-1.5696875,1.774378042,2.870363798,44.99999998 +126.27,50.4274097,-2.579165655,51.3104,7.063624838,7.070340881,-1.5134375,1.874582344,2.813668822,44.99999998 +126.28,50.42741034,-2.57916466,51.3252,7.067101038,7.070562861,-1.45625,1.974395087,2.754520326,44.99999998 +126.29,50.42741097,-2.579163665,51.3395,7.077529643,7.071451017,-1.39875,2.073795529,2.692969819,44.99999998 +126.3,50.42741161,-2.57916267,51.3532,7.084482062,7.072561229,-1.34125,2.172762873,2.629070987,44.99999998 +126.31,50.42741225,-2.579161674,51.3663,7.077529694,7.072561148,-1.2834375,2.271276492,2.562879637,44.99999998 +126.32,50.42741288,-2.579160679,51.3789,7.067101121,7.071450775,-1.2246875,2.369315758,2.49445335,44.99999998 +126.33,50.42741352,-2.579159684,51.3908,7.063624932,7.070562461,-1.1646875,2.466860219,2.423851886,44.99999998 +126.34,50.42741415,-2.579158689,51.4022,7.063624941,7.07034032,-1.10375,2.563889533,2.351136781,44.99999998 +126.35,50.42741479,-2.579157694,51.4129,7.063624958,7.070340237,-1.043125,2.660383417,2.276371461,44.99999998 +126.36,50.42741542,-2.579156699,51.423,7.063624977,7.070340153,-0.9834375,2.756321705,2.199621072,44.99999998 +126.37,50.42741606,-2.579155704,51.4326,7.067101184,7.07034007,-0.9228125,2.851684342,2.120952591,44.99999998 +126.38,50.42741669,-2.579154709,51.4415,7.077529776,7.070562044,-0.86,2.946451447,2.040434661,44.99999998 +126.39,50.42741733,-2.579153714,51.4498,7.084482172,7.071450191,-0.796875,3.040603252,1.958137409,44.99999998 +126.4,50.42741797,-2.579152719,51.4574,7.077529787,7.072560397,-0.735,3.134120049,1.874132629,44.99999998 +126.41,50.4274186,-2.579151723,51.4645,7.067101209,7.072560311,-0.673125,3.226982298,1.788493544,44.99999998 +126.42,50.42741924,-2.579150728,51.4709,7.063625028,7.071449931,-0.6096875,3.319170691,1.701294926,44.99999998 +126.43,50.42741987,-2.579149733,51.4767,7.063625044,7.070561609,-0.5453125,3.410665863,1.61261269,44.99999998 +126.44,50.42742051,-2.579148738,51.4818,7.067101251,7.070339462,-0.4815625,3.501448791,1.522524301,44.99999998 +126.45,50.42742114,-2.579147743,51.4863,7.077529834,7.070339372,-0.4184375,3.591500511,1.431108198,44.99999998 +126.46,50.42742178,-2.579146748,51.4902,7.084482211,7.070339282,-0.355,3.680802171,1.338444192,44.99999998 +126.47,50.42742242,-2.579145753,51.4934,7.077529821,7.070561249,-0.2915625,3.769335094,1.244613014,44.99999998 +126.48,50.42742305,-2.579144758,51.496,7.067101254,7.07144939,-0.228125,3.857080887,1.149696481,44.99999998 +126.49,50.42742369,-2.579143763,51.498,7.063625079,7.072337532,-0.163125,3.944021217,1.053777445,44.99999998 +126.5,50.42742432,-2.579142767,51.4993,7.063625088,7.071671263,-0.096875,4.030137805,0.956939499,44.99999998 +126.51,50.42742496,-2.579141772,51.4999,7.067101276,7.070338819,-0.031875,4.115412775,0.859267097,44.99999998 +126.52,50.42742559,-2.579140778,51.4999,7.077529843,7.070560783,0.0315625,4.199828308,0.760845324,44.99999998 +126.53,50.42742623,-2.579139782,51.4993,7.08448222,7.071448921,0.0953125,4.283366815,0.66176018,44.99999998 +126.54,50.42742687,-2.579138787,51.498,7.077529838,7.071226767,0.16,4.366010706,0.562097896,44.99999998 +126.55,50.4274275,-2.579137792,51.4961,7.067101271,7.070560494,0.2246875,4.447742849,0.461945503,44.99999998 +126.56,50.42742814,-2.579136797,51.4935,7.063625077,7.070560397,0.2884375,4.528546113,0.361390264,44.99999998 +126.57,50.42742877,-2.579135802,51.4903,7.063625061,7.071448532,0.351875,4.60840371,0.260519899,44.99999998 +126.58,50.42742941,-2.579134807,51.4865,7.063625047,7.072336667,0.4165625,4.687298852,0.159422355,44.99999998 +126.59,50.42743004,-2.579133811,51.482,7.063625049,7.071670392,0.4815625,4.765215097,0.058185812,44.99999998 +126.6,50.42743068,-2.579132816,51.4768,7.067101253,7.070337942,0.5446875,4.842136228,-0.043101495,44.99999998 +126.61,50.42743131,-2.579131822,51.4711,7.077529834,7.070559899,0.606875,4.918046145,-0.144351216,44.99999998 +126.62,50.42743195,-2.579130826,51.4647,7.08448221,7.07144803,0.6703125,4.992928979,-0.245475058,44.99999998 +126.63,50.42743259,-2.579129831,51.4577,7.077529814,7.071225869,0.734375,5.066769087,-0.346384844,44.99999998 +126.64,50.42743322,-2.579128836,51.45,7.067101222,7.070559592,0.796875,5.139551056,-0.446992623,44.99999998 +126.65,50.42743386,-2.579127841,51.4417,7.067101207,7.07033743,0.858125,5.211259703,-0.547210562,44.99999998 +126.66,50.42743449,-2.579126846,51.4329,7.077529775,7.070559384,0.92,5.281880075,-0.646951341,44.99999998 +126.67,50.42743513,-2.579125851,51.4233,7.084482157,7.071447511,0.9815625,5.351397388,-0.746127929,44.99999998 +126.68,50.42743577,-2.579124856,51.4132,7.077529768,7.072557697,1.0415625,5.419797089,-0.844653923,44.99999998 +126.69,50.4274364,-2.57912386,51.4025,7.067101182,7.072557591,1.101875,5.48706497,-0.94244338,44.99999998 +126.7,50.42743704,-2.579122865,51.3912,7.063624972,7.071447192,1.163125,5.553186935,-1.039410987,44.99999998 +126.71,50.42743767,-2.57912187,51.3792,7.063624945,7.07055885,1.223125,5.618149177,-1.135472231,44.99999998 +126.72,50.42743831,-2.579120875,51.3667,7.063624925,7.070336684,1.2815625,5.681938172,-1.23054329,44.99999998 +126.73,50.42743894,-2.57911988,51.3536,7.063624922,7.070336575,1.34,5.744540572,-1.324541314,44.99999998 +126.74,50.42743958,-2.579118885,51.3399,7.067101117,7.070336465,1.398125,5.805943256,-1.417384311,44.99999998 +126.75,50.42744021,-2.57911789,51.3256,7.077529687,7.070558413,1.4546875,5.866133446,-1.508991325,44.99999998 +126.76,50.42744085,-2.579116895,51.3108,7.084482046,7.071446535,1.5103125,5.925098596,-1.59928254,44.99999998 +126.77,50.42744149,-2.5791159,51.2954,7.077529625,7.072334657,1.5665625,5.982826385,-1.688179062,44.99999998 +126.78,50.42744212,-2.579114904,51.2795,7.067101024,7.071668369,1.623125,6.039304726,-1.775603541,44.99999998 +126.79,50.42744276,-2.579113909,51.2629,7.063624824,7.070335906,1.678125,6.094521815,-1.861479659,44.99999998 +126.8,50.42744339,-2.579112915,51.2459,7.063624817,7.070557852,1.73125,6.148466135,-1.945732472,44.99999998 +126.81,50.42744403,-2.579111919,51.2283,7.067100999,7.071445971,1.78375,6.201126399,-2.028288643,44.99999998 +126.82,50.42744466,-2.579110924,51.2102,7.077529556,7.071223797,1.83625,6.252491722,-2.109076093,44.99999998 +126.83,50.4274453,-2.579109929,51.1916,7.084481908,7.070557507,1.8884375,6.302551216,-2.188024406,44.99999998 +126.84,50.42744594,-2.579108934,51.1724,7.077529493,7.070335333,1.9396875,6.351294569,-2.265064712,44.99999998 +126.85,50.42744657,-2.579107939,51.1528,7.067100903,7.070557275,1.9896875,6.398711468,-2.340129861,44.99999998 +126.86,50.42744721,-2.579106944,51.1326,7.063624703,7.071223333,2.0384375,6.444792114,-2.413154421,44.99999998 +126.87,50.42744784,-2.579105949,51.112,7.063624685,7.071667332,2.0865625,6.489526825,-2.484074621,44.99999998 +126.88,50.42744848,-2.579104953,51.0909,7.067100843,7.071445156,2.1346875,6.53290632,-2.552828697,44.99999998 +126.89,50.42744911,-2.579103959,51.0693,7.077529383,7.071445038,2.1815625,6.574921487,-2.61935666,44.99999998 +126.9,50.42744975,-2.579102963,51.0472,7.084481746,7.071666976,2.22625,6.61556356,-2.683600469,44.99999998 +126.91,50.42745039,-2.579101968,51.0248,7.077529353,7.07122274,2.27,6.654824061,-2.745504205,44.99999998 +126.92,50.42745102,-2.579100973,51.0018,7.067100761,7.070556445,2.3134375,6.692694737,-2.805013779,44.99999998 +126.93,50.42745166,-2.579099978,50.9785,7.063624537,7.070334267,2.35625,6.729167798,-2.862077338,44.99999998 +126.94,50.42745229,-2.579098983,50.9547,7.063624496,7.070556204,2.3984375,6.764235508,-2.916645151,44.99999998 +126.95,50.42745293,-2.579097988,50.9305,7.063624459,7.071222258,2.439375,6.797890648,-2.968669547,44.99999998 +126.96,50.42745356,-2.579096993,50.9059,7.06362444,7.071444194,2.4784375,6.830126113,-3.018105262,44.99999998 +126.97,50.4274542,-2.579095997,50.8809,7.067100622,7.070555839,2.5165625,6.8609352,-3.064909153,44.99999998 +126.98,50.42745483,-2.579095003,50.8556,7.077529179,7.070333657,2.5546875,6.890311433,-3.109040368,44.99999998 +126.99,50.42745547,-2.579094008,50.8298,7.084481532,7.071665884,2.5915625,6.918248741,-3.150460518,44.99999998 +127,50.42745611,-2.579093012,50.8037,7.077529108,7.072331936,2.6259375,6.944741278,-3.189133336,44.99999998 +127.01,50.42745674,-2.579092017,50.7773,7.067100494,7.071443578,2.6584375,6.969783487,-3.225025246,44.99999998 +127.02,50.42745738,-2.579091022,50.7505,7.063624276,7.070555221,2.69,6.993370097,-3.25810485,44.99999998 +127.03,50.42745801,-2.579090027,50.7235,7.063624254,7.070333038,2.7215625,7.015496294,-3.288343327,44.99999998 +127.04,50.42745865,-2.579089032,50.6961,7.06710042,7.070332914,2.7534375,7.036157382,-3.315714381,44.99999998 +127.05,50.42745928,-2.579088037,50.6684,7.077528972,7.070332789,2.784375,7.055349004,-3.340194003,44.99999998 +127.06,50.42745992,-2.579087042,50.6404,7.084481333,7.07055472,2.813125,7.073067266,-3.361760993,44.99999998 +127.07,50.42746056,-2.579086047,50.6121,7.077528912,7.071442827,2.8396875,7.089308385,-3.380396446,44.99999998 +127.08,50.42746119,-2.579085052,50.5836,7.067100285,7.072552992,2.8646875,7.104068981,-3.396084145,44.99999998 +127.09,50.42746183,-2.579084056,50.5548,7.063624054,7.072552866,2.8884375,7.117346017,-3.408810397,44.99999998 +127.1,50.42746246,-2.579083061,50.5258,7.063624034,7.071442448,2.91125,7.129136686,-3.418564144,44.99999998 +127.11,50.4274631,-2.579082066,50.4966,7.067100209,7.070554088,2.9334375,7.139438467,-3.425336849,44.99999998 +127.12,50.42746373,-2.579081071,50.4671,7.077528754,7.070331903,2.9546875,7.148249355,-3.429122553,44.99999998 +127.13,50.42746437,-2.579080076,50.4375,7.084481093,7.070553833,2.9746875,7.155567344,-3.429918105,44.99999998 +127.14,50.42746501,-2.579079081,50.4076,7.077528668,7.07121988,2.993125,7.161391059,-3.427722645,44.99999998 +127.15,50.42746564,-2.579078086,50.3776,7.067100067,7.07144181,3.0096875,7.165719125,-3.422538179,44.99999998 +127.16,50.42746628,-2.57907709,50.3474,7.063623856,7.07055345,3.025,7.168550797,-3.414369233,44.99999998 +127.17,50.42746691,-2.579076096,50.3171,7.06362383,7.070331264,3.0396875,7.169885387,-3.403222855,44.99999998 +127.18,50.42746755,-2.579075101,50.2866,7.067099983,7.071663484,3.053125,7.16972261,-3.389108842,44.99999998 +127.19,50.42746818,-2.579074105,50.256,7.077528514,7.07232953,3.064375,7.168062522,-3.372039512,44.99999998 +127.2,50.42746882,-2.57907311,50.2253,7.084480856,7.071441169,3.0734375,7.164905525,-3.352029649,44.99999998 +127.21,50.42746946,-2.579072115,50.1945,7.077528443,7.070552808,3.0815625,7.160252191,-3.329096841,44.99999998 +127.22,50.42747009,-2.57907112,50.1637,7.067099846,7.070552679,3.0896875,7.154103551,-3.303260914,44.99999998 +127.23,50.42747073,-2.579070125,50.1327,7.063623624,7.071218724,3.0965625,7.146460867,-3.274544556,44.99999998 +127.24,50.42747136,-2.57906913,50.1017,7.063623584,7.071440654,3.10125,7.137325743,-3.242972748,44.99999998 +127.25,50.427472,-2.579068134,50.0707,7.067099734,7.070552292,3.105,7.126700069,-3.208573049,44.99999998 +127.26,50.42747263,-2.57906714,50.0396,7.077528275,7.070330105,3.108125,7.114586079,-3.171375369,44.99999998 +127.27,50.42747327,-2.579066145,50.0085,7.084480632,7.071662324,3.1096875,7.100986296,-3.131412193,44.99999998 +127.28,50.42747391,-2.579065149,49.9774,7.077528219,7.072328369,3.1096875,7.085903526,-3.088718414,44.99999998 +127.29,50.42747454,-2.579064154,49.9463,7.067099608,7.071440008,3.108125,7.069340977,-3.043331219,44.99999998 +127.3,50.42747518,-2.579063159,49.9152,7.063623382,7.070551646,3.1046875,7.051302146,-2.995290198,44.99999998 +127.31,50.42747581,-2.579062164,49.8842,7.063623346,7.07032946,3.1,7.031790641,-2.944637233,44.99999998 +127.32,50.42747645,-2.579061169,49.8532,7.063623306,7.070329332,3.0946875,7.010810703,-2.891416559,44.99999998 +127.33,50.42747708,-2.579060174,49.8223,7.063623268,7.070329202,3.088125,6.988366628,-2.835674469,44.99999998 +127.34,50.42747772,-2.579059179,49.7914,7.067099432,7.070551131,3.0796875,6.964463173,-2.777459608,44.99999998 +127.35,50.42747835,-2.579058184,49.7607,7.077527986,7.071439235,3.0696875,6.939105207,-2.716822797,44.99999998 +127.36,50.42747899,-2.579057189,49.73,7.084480345,7.072549397,3.0584375,6.912298116,-2.653816863,44.99999998 +127.37,50.42747963,-2.579056193,49.6995,7.077527922,7.072549268,3.04625,6.884047515,-2.588496752,44.99999998 +127.38,50.42748026,-2.579055198,49.6691,7.067099295,7.071438849,3.033125,6.854359248,-2.520919474,44.99999998 +127.39,50.4274809,-2.579054203,49.6388,7.063623062,7.070550489,3.018125,6.823239504,-2.451143872,44.99999998 +127.4,50.42748153,-2.579053208,49.6087,7.063623041,7.070328303,3.00125,6.790694871,-2.37923085,44.99999998 +127.41,50.42748217,-2.579052213,49.5788,7.067099217,7.070328175,2.9834375,6.756732053,-2.305243091,44.99999998 +127.42,50.4274828,-2.579051218,49.549,7.077527767,7.070328048,2.9646875,6.721358154,-2.229245167,44.99999998 +127.43,50.42748344,-2.579050223,49.5195,7.084480108,7.070327921,2.9446875,6.684580624,-2.151303255,44.99999998 +127.44,50.42748408,-2.579049228,49.4901,7.077527673,7.070549852,2.9234375,6.646407081,-2.071485421,44.99999998 +127.45,50.42748471,-2.579048233,49.461,7.067099063,7.071437957,2.90125,6.606845549,-1.989861166,44.99999998 +127.46,50.42748535,-2.579047238,49.4321,7.063622856,7.07254812,2.878125,6.565904219,-1.906501765,44.99999998 +127.47,50.42748598,-2.579046242,49.4034,7.063622839,7.072547994,2.853125,6.523591745,-1.821479871,44.99999998 +127.48,50.42748662,-2.579045247,49.375,7.067098996,7.071437577,2.82625,6.479916891,-1.734869622,44.99999998 +127.49,50.42748725,-2.579044252,49.3469,7.077527528,7.070549219,2.7984375,6.434888768,-1.646746479,44.99999998 +127.5,50.42748789,-2.579043257,49.319,7.08447987,7.070327036,2.77,6.388516773,-1.557187389,44.99999998 +127.51,50.42748853,-2.579042262,49.2915,7.077527455,7.070326911,2.74125,6.340810645,-1.466270446,44.99999998 +127.52,50.42748916,-2.579041267,49.2642,7.067098861,7.070326786,2.71125,6.291780355,-1.374074833,44.99999998 +127.53,50.4274898,-2.579040272,49.2372,7.063622655,7.07054872,2.678125,6.241436043,-1.280681051,44.99999998 +127.54,50.42749043,-2.579039277,49.2106,7.063622631,7.071436827,2.643125,6.189788309,-1.186170459,44.99999998 +127.55,50.42749107,-2.579038282,49.1844,7.063622591,7.072324936,2.6084375,6.136847926,-1.090625564,44.99999998 +127.56,50.4274917,-2.579037286,49.1584,7.063622552,7.07165864,2.573125,6.08262595,-0.994129559,44.99999998 +127.57,50.42749234,-2.579036291,49.1329,7.067098719,7.070326169,2.53625,6.02713367,-0.896766727,44.99999998 +127.58,50.42749297,-2.579035297,49.1077,7.077527276,7.070548103,2.4984375,5.970382716,-0.798621864,44.99999998 +127.59,50.42749361,-2.579034301,49.0829,7.084479637,7.071436213,2.4596875,5.912384949,-0.699780571,44.99999998 +127.6,50.42749425,-2.579033306,49.0585,7.077527228,7.071214033,2.42,5.8531524,-0.600329078,44.99999998 +127.61,50.42749488,-2.579032311,49.0345,7.067098629,7.070547738,2.3796875,5.79269756,-0.50035413,44.99999998 +127.62,50.42749552,-2.579031316,49.0109,7.063622407,7.07032556,2.338125,5.731032978,-0.399942818,44.99999998 +127.63,50.42749615,-2.579030321,48.9877,7.063622366,7.070547498,2.295,5.668171486,-0.299182747,44.99999998 +127.64,50.42749679,-2.579029326,48.965,7.067098528,7.07143561,2.25125,5.604126321,-0.198161808,44.99999998 +127.65,50.42749742,-2.579028331,48.9427,7.077527092,7.07254578,2.2065625,5.538910775,-0.096968065,44.99999998 +127.66,50.42749806,-2.579027335,48.9208,7.084479469,7.072545661,2.1596875,5.472538542,0.004310247,44.99999998 +127.67,50.4274987,-2.57902634,48.8995,7.077527066,7.071435253,2.111875,5.405023373,0.105584834,44.99999998 +127.68,50.42749933,-2.579025345,48.8786,7.067098453,7.070546903,2.065,5.336379476,0.20676729,44.99999998 +127.69,50.42749997,-2.57902435,48.8582,7.063622221,7.070324728,2.0178125,5.26662112,0.307769494,44.99999998 +127.7,50.4275006,-2.579023355,48.8382,7.063622197,7.070324611,1.968125,5.195762971,0.408503266,44.99999998 +127.71,50.42750124,-2.57902236,48.8188,7.06709838,7.070324496,1.9165625,5.123819698,0.508880831,44.99999998 +127.72,50.42750187,-2.579021365,48.7999,7.077526948,7.070546438,1.865,5.050806368,0.60881464,44.99999998 +127.73,50.42750251,-2.57902037,48.7815,7.08447932,7.071434554,1.813125,4.976738223,0.708217603,44.99999998 +127.74,50.42750315,-2.579019375,48.7636,7.077526912,7.072322671,1.76,4.90163079,0.807002918,44.99999998 +127.75,50.42750378,-2.579018379,48.7463,7.067098301,7.071656384,1.7065625,4.82549971,0.905084584,44.99999998 +127.76,50.42750442,-2.579017384,48.7295,7.063622084,7.070323923,1.653125,4.748360913,1.002376943,44.99999998 +127.77,50.42750505,-2.57901639,48.7132,7.063622077,7.070545869,1.598125,4.67023044,1.098795255,44.99999998 +127.78,50.42750569,-2.579015394,48.6975,7.067098269,7.071433988,1.5415625,4.591124678,1.194255352,44.99999998 +127.79,50.42750632,-2.579014399,48.6824,7.077526834,7.071211819,1.485,4.511060071,1.288674098,44.99999998 +127.8,50.42750696,-2.579013404,48.6678,7.08447919,7.070545534,1.4284375,4.430053407,1.381969103,44.99999998 +127.81,50.4275076,-2.579012409,48.6538,7.077526773,7.070545424,1.37125,4.348121589,1.474058947,44.99999998 +127.82,50.42750823,-2.579011414,48.6404,7.067098182,7.071433546,1.3134375,4.265281746,1.564863419,44.99999998 +127.83,50.42750887,-2.579010419,48.6275,7.063621994,7.072321669,1.255,4.181551127,1.654303334,44.99999998 +127.84,50.4275095,-2.579009423,48.6153,7.063621994,7.071655387,1.19625,4.096947262,1.742300656,44.99999998 +127.85,50.42751014,-2.579008428,48.6036,7.06709817,7.070322932,1.1365625,4.011487799,1.828778665,44.99999998 +127.86,50.42751077,-2.579007434,48.5925,7.07752672,7.070544883,1.075,3.925190558,1.913661962,44.99999998 +127.87,50.42751141,-2.579006438,48.5821,7.084479082,7.071433009,1.0134375,3.838073643,1.996876461,44.99999998 +127.88,50.42751205,-2.579005443,48.5723,7.077526694,7.071210845,0.9534375,3.75015516,2.078349742,44.99999998 +127.89,50.42751268,-2.579004448,48.563,7.067098124,7.070544566,0.8928125,3.661453501,2.158010585,44.99999998 +127.9,50.42751332,-2.579003453,48.5544,7.063621927,7.070322404,0.83,3.57198723,2.235789663,44.99999998 +127.91,50.42751395,-2.579002458,48.5464,7.063621912,7.070544359,0.766875,3.481774968,2.31161908,44.99999998 +127.92,50.42751459,-2.579001463,48.5391,7.063621896,7.071432488,0.705,3.390835565,2.385432774,44.99999998 +127.93,50.42751522,-2.579000468,48.5323,7.063621885,7.072542675,0.643125,3.299188043,2.457166288,44.99999998 +127.94,50.42751586,-2.578999472,48.5262,7.067098076,7.072542573,0.5796875,3.20685154,2.526757112,44.99999998 +127.95,50.42751649,-2.578998477,48.5207,7.077526654,7.071432183,0.515,3.113845307,2.594144626,44.99999998 +127.96,50.42751713,-2.578997482,48.5159,7.084479036,7.070543852,0.4503125,3.020188823,2.659269931,44.99999998 +127.97,50.42751777,-2.578996487,48.5117,7.07752665,7.070321695,0.3865625,2.925901571,2.722076362,44.99999998 +127.98,50.4275184,-2.578995492,48.5082,7.067098074,7.070321596,0.3234375,2.831003316,2.782509085,44.99999998 +127.99,50.42751904,-2.578994497,48.5052,7.063621875,7.070321498,0.26,2.735513826,2.840515447,44.99999998 +128,50.42751967,-2.578993502,48.503,7.063621858,7.070543459,0.19625,2.63945304,2.896044797,44.99999998 +128.01,50.42752031,-2.578992507,48.5013,7.067098042,7.071431594,0.131875,2.542841068,2.949048779,44.99999998 +128.02,50.42752094,-2.578991512,48.5003,7.07752663,7.072319729,0.06625,2.445698022,2.999481097,44.99999998 +128.03,50.42752158,-2.578990516,48.5,7.084479028,7.071653461,0.000625,2.348044242,3.047297863,44.99999998 +128.04,50.42752222,-2.578989521,48.5003,7.077526642,7.07032102,-0.0634375,2.249900124,3.092457365,44.99999998 +128.05,50.42752285,-2.578988527,48.5013,7.067098052,7.070542983,-0.126875,2.151286123,3.134920127,44.99999998 +128.06,50.42752349,-2.578987531,48.5028,7.063621856,7.071431122,-0.1915625,2.052222866,3.17464925,44.99999998 +128.07,50.42752412,-2.578986536,48.5051,7.06362187,7.071208972,-0.2565625,1.952731037,3.211610012,44.99999998 +128.08,50.42752476,-2.578985541,48.508,7.067098082,7.070542707,-0.3196875,1.852831376,3.245770214,44.99999998 +128.09,50.42752539,-2.578984546,48.5115,7.07752667,7.070320559,-0.3821875,1.752544797,3.277100062,44.99999998 +128.1,50.42752603,-2.578983551,48.5156,7.084479053,7.070542527,-0.4465625,1.651892213,3.305572226,44.99999998 +128.11,50.42752667,-2.578982556,48.5204,7.077526659,7.07120861,-0.5115625,1.55089465,3.331161839,44.99999998 +128.12,50.4275273,-2.578981561,48.5259,7.067098078,7.071652637,-0.575,1.449573195,3.35384667,44.99999998 +128.13,50.42752794,-2.578980565,48.5319,7.0636219,7.071430491,-0.638125,1.347948989,3.373606896,44.99999998 +128.14,50.42752857,-2.578979571,48.5386,7.063621924,7.071430405,-0.701875,1.246043345,3.39042527,44.99999998 +128.15,50.42752921,-2.578978575,48.546,7.067098127,7.071652376,-0.7646875,1.143877465,3.404287181,44.99999998 +128.16,50.42752984,-2.57897758,48.5539,7.0775267,7.071208174,-0.8265625,1.041472661,3.415180484,44.99999998 +128.17,50.42753048,-2.578976585,48.5625,7.084479084,7.070541915,-0.8884375,0.938850362,3.423095667,44.99999998 +128.18,50.42753112,-2.57897559,48.5717,7.077526717,7.070319773,-0.9496875,0.836032054,3.428025912,44.99999998 +128.19,50.42753175,-2.578974595,48.5815,7.067098167,7.070541747,-1.01,0.733039109,3.429966806,44.99999998 +128.2,50.42753239,-2.5789736,48.5919,7.063621992,7.071429895,-1.0703125,0.62989307,3.428916746,44.99999998 +128.21,50.42753302,-2.578972605,48.6029,7.063622,7.072318044,-1.1315625,0.526615536,3.424876649,44.99999998 +128.22,50.42753366,-2.578971609,48.6145,7.067098204,7.071651789,-1.193125,0.423227938,3.417850009,44.99999998 +128.23,50.42753429,-2.578970614,48.6268,7.077526793,7.070319361,-1.2528125,0.319752046,3.4078429,44.99999998 +128.24,50.42753493,-2.57896962,48.6396,7.084479186,7.070541338,-1.31,0.216209348,3.394864146,44.99999998 +128.25,50.42753557,-2.578968624,48.653,7.077526813,7.071429489,-1.366875,0.112621444,3.378924975,44.99999998 +128.26,50.4275362,-2.578967629,48.6669,7.067098256,7.071207352,-1.425,0.009010105,3.36003937,44.99999998 +128.27,50.42753684,-2.578966634,48.6815,7.06362209,7.0705411,-1.483125,-0.094603181,3.338223773,44.99999998 +128.28,50.42753747,-2.578965639,48.6966,7.063622114,7.070318965,-1.5396875,-0.198196701,3.313497149,44.99999998 +128.29,50.42753811,-2.578964644,48.7123,7.063622128,7.070540945,-1.595,-0.301748796,3.285881156,44.99999998 +128.3,50.42753874,-2.578963649,48.7285,7.063622131,7.071207042,-1.6496875,-0.405237865,3.255399801,44.99999998 +128.31,50.42753938,-2.578962654,48.7453,7.067098336,7.071651082,-1.7034375,-0.508642366,3.22207967,44.99999998 +128.32,50.42754001,-2.578961658,48.7626,7.077526944,7.071428949,-1.7565625,-0.611940583,3.185949868,44.99999998 +128.33,50.42754065,-2.578960664,48.7804,7.084479365,7.071428873,-1.81,-0.715111031,3.147041851,44.99999998 +128.34,50.42754129,-2.578959668,48.7988,7.077527006,7.071650856,-1.8628125,-0.818132165,3.105389538,44.99999998 +128.35,50.42754192,-2.578958673,48.8177,7.067098437,7.071206667,-1.913125,-0.920982387,3.061029312,44.99999998 +128.36,50.42754256,-2.578957678,48.8371,7.063622249,7.07054042,-1.961875,-1.023640323,3.013999848,44.99999998 +128.37,50.42754319,-2.578956683,48.8569,7.063622272,7.07031829,-2.0115625,-1.12608449,2.964342111,44.99999998 +128.38,50.42754383,-2.578955688,48.8773,7.067098506,7.070540276,-2.0615625,-1.228293457,2.912099419,44.99999998 +128.39,50.42754446,-2.578954693,48.8982,7.07752712,7.071206378,-2.1096875,-1.330245911,2.85731732,44.99999998 +128.4,50.4275451,-2.578953698,48.9195,7.084479525,7.071428364,-2.1565625,-1.431920537,2.800043656,44.99999998 +128.41,50.42754574,-2.578952702,48.9413,7.07752715,7.070540063,-2.203125,-1.533296194,2.740328219,44.99999998 +128.42,50.42754637,-2.578951708,48.9636,7.067098587,7.070317935,-2.248125,-1.634351568,2.678223261,44.99999998 +128.43,50.42754701,-2.578950713,48.9863,7.063622427,7.071650212,-2.2915625,-1.735065688,2.613782812,44.99999998 +128.44,50.42754764,-2.578949717,49.0094,7.063622469,7.072316316,-2.335,-1.835417413,2.54706308,44.99999998 +128.45,50.42754828,-2.578948722,49.033,7.067098693,7.071428016,-2.378125,-1.935385886,2.478122334,44.99999998 +128.46,50.42754891,-2.578947727,49.057,7.077527291,7.070539717,-2.419375,-2.034950137,2.407020564,44.99999998 +128.47,50.42754955,-2.578946732,49.0814,7.084479693,7.07053965,-2.4584375,-2.134089425,2.333819877,44.99999998 +128.48,50.42755019,-2.578945737,49.1062,7.077527325,7.071427813,-2.4965625,-2.232783067,2.258584044,44.99999998 +128.49,50.42755082,-2.578944742,49.1313,7.067098778,7.072315977,-2.5346875,-2.331010378,2.181378726,44.99999998 +128.5,50.42755146,-2.578943746,49.1569,7.063622632,7.071649738,-2.5715625,-2.428750905,2.102271188,44.99999998 +128.51,50.42755209,-2.578942751,49.1828,7.063622675,7.070317326,-2.60625,-2.525984192,2.021330472,44.99999998 +128.52,50.42755273,-2.578941757,49.209,7.063622705,7.070539318,-2.6403125,-2.622690014,1.938627051,44.99999998 +128.53,50.42755336,-2.578940761,49.2356,7.063622733,7.071427483,-2.6746875,-2.718848088,1.854233175,44.99999998 +128.54,50.427554,-2.578939766,49.2625,7.06709895,7.071205361,-2.708125,-2.814438361,1.768222355,44.99999998 +128.55,50.42755463,-2.578938771,49.2898,7.077527543,7.070539123,-2.7396875,-2.909440837,1.680669648,44.99999998 +128.56,50.42755527,-2.578937776,49.3173,7.084479953,7.070317001,-2.7696875,-3.003835806,1.591651373,44.99999998 +128.57,50.42755591,-2.578936781,49.3452,7.07752761,7.070538994,-2.798125,-3.097603386,1.501245107,44.99999998 +128.58,50.42755654,-2.578935786,49.3733,7.067099078,7.071205104,-2.8246875,-3.190724096,1.409529805,44.99999998 +128.59,50.42755718,-2.578934791,49.4017,7.063622915,7.071649156,-2.85,-3.283178457,1.316585279,44.99999998 +128.6,50.42755781,-2.578933795,49.4303,7.063622932,7.071427036,-2.875,-3.374947216,1.222492717,44.99999998 +128.61,50.42755845,-2.578932801,49.4592,7.067099151,7.071426974,-2.8996875,-3.466011123,1.127334168,44.99999998 +128.62,50.42755908,-2.578931805,49.4883,7.077527773,7.071648969,-2.923125,-3.556351154,1.031192537,44.99999998 +128.63,50.42755972,-2.57893081,49.5177,7.084480208,7.071204791,-2.9446875,-3.645948575,0.93415165,44.99999998 +128.64,50.42756036,-2.578929815,49.5472,7.077527862,7.070538556,-2.9646875,-3.734784536,0.836296188,44.99999998 +128.65,50.42756099,-2.57892882,49.577,7.067099311,7.070316437,-2.9834375,-3.822840528,0.737711465,44.99999998 +128.66,50.42756163,-2.578927825,49.6069,7.063623137,7.070538433,-3.00125,-3.910098162,0.638483483,44.99999998 +128.67,50.42756226,-2.57892683,49.637,7.063623157,7.071204544,-3.018125,-3.996539273,0.538698701,44.99999998 +128.68,50.4275629,-2.578925835,49.6673,7.067099385,7.071426541,-3.0328125,-4.082145699,0.438444207,44.99999998 +128.69,50.42756353,-2.578924839,49.6977,7.077528011,7.070538249,-3.045,-4.166899679,0.337807322,44.99999998 +128.7,50.42756417,-2.578923845,49.7282,7.084480447,7.07031613,-3.0565625,-4.250783393,0.236875879,44.99999998 +128.71,50.42756481,-2.57892285,49.7588,7.0775281,7.071648415,-3.068125,-4.333779424,0.135737884,44.99999998 +128.72,50.42756544,-2.578921854,49.7896,7.067099543,7.072314528,-3.078125,-4.41587041,0.034481517,44.99999998 +128.73,50.42756608,-2.578920859,49.8204,7.063623368,7.071426237,-3.08625,-4.497039164,-0.066804874,44.99999998 +128.74,50.42756671,-2.578919864,49.8513,7.063623403,7.070537946,-3.0934375,-4.577268782,-0.168033051,44.99999998 +128.75,50.42756735,-2.578918869,49.8823,7.067099648,7.070315827,-3.0996875,-4.656542478,-0.269114724,44.99999998 +128.76,50.42756798,-2.578917874,49.9133,7.077528276,7.070537824,-3.1046875,-4.73484375,-0.369961656,44.99999998 +128.77,50.42756862,-2.578916879,49.9444,7.084480693,7.071203938,-3.108125,-4.812156211,-0.470486012,44.99999998 +128.78,50.42756926,-2.578915884,49.9755,7.077528326,7.071647993,-3.1096875,-4.888463704,-0.570600131,44.99999998 +128.79,50.42756989,-2.578914888,50.0066,7.067099772,7.071425875,-3.1096875,-4.963750301,-0.670216636,44.99999998 +128.8,50.42757053,-2.578913894,50.0377,7.06362362,7.071425814,-3.108125,-5.038000303,-0.769248724,44.99999998 +128.81,50.42757116,-2.578912898,50.0688,7.063623671,7.071647811,-3.105,-5.111198125,-0.867609993,44.99999998 +128.82,50.4275718,-2.578911903,50.0998,7.067099904,7.071203636,-3.1015625,-5.183328584,-0.965214728,44.99999998 +128.83,50.42757243,-2.578910908,50.1308,7.077528512,7.070537402,-3.098125,-5.254376554,-1.061977732,44.99999998 +128.84,50.42757307,-2.578909913,50.1618,7.084480924,7.070315284,-3.0928125,-5.324327252,-1.15781472,44.99999998 +128.85,50.42757371,-2.578908918,50.1927,7.077528569,7.070537282,-3.0846875,-5.393166011,-1.252642043,44.99999998 +128.86,50.42757434,-2.578907923,50.2235,7.067100028,7.071203394,-3.0746875,-5.46087845,-1.346377079,44.99999998 +128.87,50.42757498,-2.578906928,50.2542,7.063623877,7.071425391,-3.0634375,-5.527450473,-1.43893801,44.99999998 +128.88,50.42757561,-2.578905932,50.2848,7.063623914,7.0705371,-3.0515625,-5.592868159,-1.53024422,44.99999998 +128.89,50.42757625,-2.578904938,50.3152,7.063623948,7.070314982,-3.0396875,-5.65711787,-1.620215955,44.99999998 +128.9,50.42757688,-2.578903943,50.3456,7.06362398,7.071647266,-3.0265625,-5.720186142,-1.70877489,44.99999998 +128.91,50.42757752,-2.578902947,50.3758,7.067100201,7.072313378,-3.0109375,-5.782059797,-1.795843791,44.99999998 +128.92,50.42757815,-2.578901952,50.4058,7.077528811,7.071425085,-2.9934375,-5.842726,-1.881346626,44.99999998 +128.93,50.42757879,-2.578900957,50.4357,7.084481236,7.070536793,-2.9746875,-5.902171976,-1.965208912,44.99999998 +128.94,50.42757943,-2.578899962,50.4653,7.077528892,7.070314674,-2.955,-5.960385405,-2.04735748,44.99999998 +128.95,50.42758006,-2.578898967,50.4948,7.067100352,7.070536669,-2.935,-6.017354025,-2.12772077,44.99999998 +128.96,50.4275807,-2.578897972,50.524,7.063624187,7.07120278,-2.914375,-6.073066035,-2.20622865,44.99999998 +128.97,50.42758133,-2.578896977,50.5531,7.063624205,7.071646833,-2.8915625,-6.127509802,-2.282812653,44.99999998 +128.98,50.42758197,-2.578895981,50.5819,7.067100424,7.071424713,-2.86625,-6.180673869,-2.357406028,44.99999998 +128.99,50.4275826,-2.578894987,50.6104,7.077529048,7.071424649,-2.84,-6.232547176,-2.429943688,44.99999998 +129,50.42758324,-2.578893991,50.6387,7.084481482,7.071646643,-2.813125,-6.283118894,-2.500362379,44.99999998 +129.01,50.42758388,-2.578892996,50.6667,7.077529134,7.071202465,-2.7846875,-6.332378482,-2.568600735,44.99999998 +129.02,50.42758451,-2.578892001,50.6944,7.067100578,7.070536228,-2.755,-6.380315627,-2.634599285,44.99999998 +129.03,50.42758515,-2.578891006,50.7218,7.063624401,7.070314105,-2.7246875,-6.4269203,-2.698300332,44.99999998 +129.04,50.42758578,-2.578890011,50.7489,7.06362442,7.070536098,-2.6934375,-6.47218282,-2.75964847,44.99999998 +129.05,50.42758642,-2.578889016,50.7757,7.067100651,7.071202206,-2.66125,-6.516093732,-2.818590185,44.99999998 +129.06,50.42758705,-2.578888021,50.8021,7.077529277,7.071424198,-2.628125,-6.558643813,-2.875074026,44.99999998 +129.07,50.42758769,-2.578887025,50.8283,7.084481696,7.070535902,-2.593125,-6.59982418,-2.929050719,44.99999998 +129.08,50.42758833,-2.578886031,50.854,7.077529325,7.070313779,-2.55625,-6.639626298,-2.98047328,44.99999998 +129.09,50.42758896,-2.578885036,50.8794,7.067100762,7.071646058,-2.5184375,-6.6780418,-3.02929679,44.99999998 +129.1,50.4275896,-2.57888404,50.9044,7.063624604,7.072312164,-2.4796875,-6.715062666,-3.075478735,44.99999998 +129.11,50.42759023,-2.578883045,50.929,7.063624647,7.071423866,-2.44,-6.750681218,-3.118978837,44.99999998 +129.12,50.42759087,-2.57888205,50.9532,7.067100873,7.070535567,-2.4,-6.784889949,-3.159759108,44.99999998 +129.13,50.4275915,-2.578881055,50.977,7.077529477,7.070535499,-2.3596875,-6.817681756,-3.197784025,44.99999998 +129.14,50.42759214,-2.57888006,51.0004,7.084481888,7.071201603,-2.318125,-6.849049763,-3.233020471,44.99999998 +129.15,50.42759278,-2.578879065,51.0234,7.077529525,7.071423591,-2.2746875,-6.878987438,-3.265437621,44.99999998 +129.16,50.42759341,-2.578878069,51.0459,7.067100963,7.070535291,-2.2296875,-6.907488536,-3.295007285,44.99999998 +129.17,50.42759405,-2.578877075,51.068,7.063624791,7.070313163,-2.1834375,-6.934547041,-3.321703623,44.99999998 +129.18,50.42759468,-2.57887608,51.0896,7.06362482,7.071645438,-2.1365625,-6.960157395,-3.345503431,44.99999998 +129.19,50.42759532,-2.578875084,51.1107,7.063624853,7.072311539,-2.0896875,-6.984314212,-3.366385851,44.99999998 +129.2,50.42759595,-2.578874089,51.1314,7.063624883,7.071423238,-2.0415625,-7.007012451,-3.38433278,44.99999998 +129.21,50.42759659,-2.578873094,51.1516,7.067101095,7.070534936,-1.9915625,-7.028247356,-3.399328518,44.99999998 +129.22,50.42759722,-2.578872099,51.1712,7.077529684,7.070312805,-1.9415625,-7.048014514,-3.411360002,44.99999998 +129.23,50.42759786,-2.578871104,51.1904,7.084482087,7.070534788,-1.8915625,-7.066309744,-3.420416688,44.99999998 +129.24,50.4275985,-2.578870109,51.2091,7.077529732,7.071200887,-1.8396875,-7.083129321,-3.426490728,44.99999998 +129.25,50.42759913,-2.578869114,51.2272,7.067101187,7.071644928,-1.786875,-7.098469636,-3.429576851,44.99999998 +129.26,50.42759977,-2.578868118,51.2448,7.063625018,7.071422795,-1.735,-7.112327537,-3.429672306,44.99999998 +129.27,50.4276004,-2.578867124,51.2619,7.063625024,7.071422719,-1.6828125,-7.124700102,-3.426777035,44.99999998 +129.28,50.42760104,-2.578866128,51.2785,7.067101219,7.0716447,-1.628125,-7.135584811,-3.420893561,44.99999998 +129.29,50.42760167,-2.578865133,51.2945,7.077529819,7.071200508,-1.5715625,-7.144979313,-3.412027039,44.99999998 +129.3,50.42760231,-2.578864138,51.3099,7.084482243,7.070534258,-1.515,-7.152881662,-3.400185147,44.99999998 +129.31,50.42760295,-2.578863143,51.3248,7.077529885,7.070312122,-1.458125,-7.159290252,-3.385378314,44.99999998 +129.32,50.42760358,-2.578862148,51.3391,7.067101316,7.070534101,-1.4,-7.164203709,-3.367619315,44.99999998 +129.33,50.42760422,-2.578861153,51.3528,7.063625123,7.071200194,-1.341875,-7.167621001,-3.346923678,44.99999998 +129.34,50.42760485,-2.578860158,51.3659,7.063625127,7.071422171,-1.2846875,-7.169541441,-3.323309567,44.99999998 +129.35,50.42760549,-2.578859162,51.3785,7.067101342,7.070533861,-1.2265625,-7.169964627,-3.296797377,44.99999998 +129.36,50.42760612,-2.578858168,51.3905,7.077529954,7.070311722,-1.1665625,-7.168890446,-3.267410372,44.99999998 +129.37,50.42760676,-2.578857173,51.4018,7.084482359,7.071643985,-1.1065625,-7.166319126,-3.235174162,44.99999998 +129.38,50.4276074,-2.578856177,51.4126,7.077529977,7.072310074,-1.0465625,-7.162251183,-3.200116822,44.99999998 +129.39,50.42760803,-2.578855182,51.4228,7.067101399,7.071421761,-0.9846875,-7.156687534,-3.162268949,44.99999998 +129.4,50.42760867,-2.578854187,51.4323,7.063625212,7.070533447,-0.921875,-7.149629324,-3.121663488,44.99999998 +129.41,50.4276093,-2.578853192,51.4412,7.063625227,7.070311305,-0.8603125,-7.141077986,-3.078335904,44.99999998 +129.42,50.42760994,-2.578852197,51.4495,7.067101438,7.070533277,-0.7996875,-7.131035297,-3.032323955,44.99999998 +129.43,50.42761057,-2.578851202,51.4572,7.077530031,7.071199363,-0.738125,-7.119503432,-2.983667806,44.99999998 +129.44,50.42761121,-2.578850207,51.4643,7.084482425,7.071643391,-0.675,-7.106484685,-2.932409856,44.99999998 +129.45,50.42761185,-2.578849211,51.4707,7.077530036,7.071421245,-0.6115625,-7.091981863,-2.878594738,44.99999998 +129.46,50.42761248,-2.578848217,51.4765,7.067101453,7.071421157,-0.5484375,-7.075998002,-2.822269491,44.99999998 +129.47,50.42761312,-2.578847221,51.4817,7.063625272,7.071643126,-0.4846875,-7.058536426,-2.763483162,44.99999998 +129.48,50.42761375,-2.578846226,51.4862,7.063625293,7.071198922,-0.42,-7.039600686,-2.702287087,44.99999998 +129.49,50.42761439,-2.578845231,51.4901,7.063625305,7.070532659,-0.3553125,-7.019194852,-2.638734551,44.99999998 +129.5,50.42761502,-2.578844236,51.4933,7.06362531,7.07031051,-0.2915625,-6.997323162,-2.572880959,44.99999998 +129.51,50.42761566,-2.578843241,51.4959,7.0671015,7.070532476,-0.2284375,-6.9739902,-2.504783837,44.99999998 +129.52,50.42761629,-2.578842246,51.4979,7.07753007,7.071198556,-0.1646875,-6.94920078,-2.434502484,44.99999998 +129.53,50.42761693,-2.578841251,51.4992,7.084482453,7.071420521,-0.1,-6.922960058,-2.362098152,44.99999998 +129.54,50.42761757,-2.578840255,51.4999,7.077530078,7.070532196,-0.0353125,-6.895273649,-2.287634093,44.99999998 +129.55,50.4276182,-2.578839261,51.4999,7.067101512,7.070310044,0.0284375,-6.866147225,-2.211175167,44.99999998 +129.56,50.42761884,-2.578838266,51.4993,7.063625325,7.071642293,0.091875,-6.835586859,-2.132788066,44.99999998 +129.57,50.42761947,-2.57883727,51.4981,7.063625318,7.07230837,0.156875,-6.803598969,-2.052541144,44.99999998 +129.58,50.42762011,-2.578836275,51.4962,7.067101495,7.071420044,0.223125,-6.770190259,-1.970504417,44.99999998 +129.59,50.42762074,-2.57883528,51.4936,7.077530064,7.070531716,0.288125,-6.735367717,-1.886749332,44.99999998 +129.6,50.42762138,-2.578834285,51.4904,7.084482455,7.07030956,0.3515625,-6.699138507,-1.801348998,44.99999998 +129.61,50.42762202,-2.57883329,51.4866,7.07753008,7.070531519,0.415,-6.661510306,-1.714377844,44.99999998 +129.62,50.42762265,-2.578832295,51.4821,7.067101496,7.071197592,0.4784375,-6.622490906,-1.625911728,44.99999998 +129.63,50.42762329,-2.5788313,51.477,7.063625284,7.071641607,0.5415625,-6.582088558,-1.536027771,44.99999998 +129.64,50.42762392,-2.578830304,51.4713,7.063625265,7.071419448,0.605,-6.54031157,-1.44480441,44.99999998 +129.65,50.42762456,-2.57882931,51.4649,7.067101453,7.071419346,0.6684375,-6.497168707,-1.352321172,44.99999998 +129.66,50.42762519,-2.578828314,51.4579,7.077530041,7.071641301,0.7315625,-6.452669023,-1.258658616,44.99999998 +129.67,50.42762583,-2.578827319,51.4503,7.084482436,7.071197083,0.795,-6.406821743,-1.163898558,44.99999998 +129.68,50.42762647,-2.578826324,51.442,7.077530047,7.070530807,0.858125,-6.359636548,-1.068123563,44.99999998 +129.69,50.4276271,-2.578825329,51.4331,7.067101449,7.070308645,0.9196875,-6.311123181,-0.971417111,44.99999998 +129.7,50.42762774,-2.578824334,51.4236,7.06362523,7.070530597,0.98,-6.261291781,-0.873863598,44.99999998 +129.71,50.42762837,-2.578823339,51.4135,7.063625209,7.071196664,1.04,-6.210152834,-0.775548051,44.99999998 +129.72,50.42762901,-2.578822344,51.4028,7.067101398,7.071418615,1.1,-6.157716997,-0.676556185,44.99999998 +129.73,50.42762964,-2.578821348,51.3915,7.077529983,7.070530278,1.16,-6.103995156,-0.576974401,44.99999998 +129.74,50.42763028,-2.578820354,51.3796,7.084482361,7.070308112,1.22,-6.048998599,-0.476889446,44.99999998 +129.75,50.42763092,-2.578819359,51.3671,7.077529947,7.071640348,1.2796875,-5.992738784,-0.376388695,44.99999998 +129.76,50.42763155,-2.578818363,51.354,7.06710134,7.072306412,1.338125,-5.935227458,-0.275559697,44.99999998 +129.77,50.42763219,-2.578817368,51.3403,7.063625139,7.071418073,1.395,-5.876476652,-0.1744904,44.99999998 +129.78,50.42763282,-2.578816373,51.3261,7.063625139,7.070529732,1.451875,-5.816498571,-0.073268926,44.99999998 +129.79,50.42763346,-2.578815378,51.3113,7.067101322,7.070529621,1.5096875,-5.755305819,0.028016433,44.99999998 +129.8,50.42763409,-2.578814383,51.2959,7.077529883,7.071417739,1.5665625,-5.692911173,0.129277327,44.99999998 +129.81,50.42763473,-2.578813388,51.2799,7.084482251,7.072305856,1.6215625,-5.629327583,0.23042552,44.99999998 +129.82,50.42763537,-2.578812392,51.2635,7.077529844,7.071639571,1.6765625,-5.564568398,0.331372776,44.99999998 +129.83,50.427636,-2.578811397,51.2464,7.067101238,7.070307114,1.7315625,-5.49864714,0.432031033,44.99999998 +129.84,50.42763664,-2.578810403,51.2288,7.063625021,7.070529057,1.784375,-5.43157756,0.53231257,44.99999998 +129.85,50.42763727,-2.578809407,51.2107,7.063625006,7.071417172,1.835,-5.363373638,0.632129954,44.99999998 +129.86,50.42763791,-2.578808412,51.1921,7.063624995,7.071194999,1.8853125,-5.294049698,0.731396095,44.99999998 +129.87,50.42763854,-2.578807417,51.173,7.063624981,7.070528711,1.9365625,-5.223620122,0.83002442,44.99999998 +129.88,50.42763918,-2.578806422,51.1534,7.067101149,7.070306538,1.988125,-5.152099634,0.927928984,44.99999998 +129.89,50.42763981,-2.578805427,51.1332,7.077529694,7.070528478,2.038125,-5.079503246,1.025024418,44.99999998 +129.9,50.42764045,-2.578804432,51.1126,7.084482052,7.071194532,2.08625,-5.005846026,1.121225922,44.99999998 +129.91,50.42764109,-2.578803437,51.0915,7.077529653,7.071638529,2.1334375,-4.931143445,1.216449789,44.99999998 +129.92,50.42764172,-2.578802441,51.0699,7.067101065,7.071416353,2.1796875,-4.855411029,1.310612824,44.99999998 +129.93,50.42764236,-2.578801447,51.0479,7.063624852,7.071416234,2.2246875,-4.778664651,1.403633038,44.99999998 +129.94,50.42764299,-2.578800451,51.0254,7.063624814,7.071638172,2.2684375,-4.700920294,1.495429242,44.99999998 +129.95,50.42764363,-2.578799456,51.0025,7.067100966,7.071193938,2.3115625,-4.622194174,1.585921394,44.99999998 +129.96,50.42764426,-2.578798461,50.9792,7.077529521,7.070527646,2.355,-4.542502792,1.675030598,44.99999998 +129.97,50.4276449,-2.578797466,50.9554,7.084481901,7.070305467,2.3978125,-4.461862821,1.76267916,44.99999998 +129.98,50.42764554,-2.578796471,50.9312,7.077529501,7.070527402,2.438125,-4.380290992,1.848790649,44.99999998 +129.99,50.42764617,-2.578795476,50.9066,7.067100889,7.07141551,2.4765625,-4.297804378,1.933289949,44.99999998 +130,50.42764681,-2.578794481,50.8817,7.063624653,7.072303617,2.515,-4.214420283,2.016103435,44.99999998 +130.01,50.42764744,-2.578793485,50.8563,7.063624615,7.071637322,2.553125,-4.13015601,2.0971588,44.99999998 +130.02,50.42764808,-2.57879249,50.8306,7.067100787,7.070304855,2.589375,-4.045029207,2.176385399,44.99999998 +130.03,50.42764871,-2.578791496,50.8045,7.077529355,7.070526789,2.6234375,-3.959057692,2.253714189,44.99999998 +130.04,50.42764935,-2.5787905,50.7781,7.084481718,7.071414895,2.6565625,-3.872259341,2.329077734,44.99999998 +130.05,50.42764999,-2.578789505,50.7514,7.077529298,7.071192713,2.69,-3.784652318,2.402410259,44.99999998 +130.06,50.42765062,-2.57878851,50.7243,7.067100686,7.070526416,2.723125,-3.696254957,2.47364782,44.99999998 +130.07,50.42765126,-2.578787515,50.6969,7.06362446,7.070304234,2.754375,-3.60708565,2.542728368,44.99999998 +130.08,50.42765189,-2.57878652,50.6692,7.063624424,7.070526167,2.783125,-3.517163018,2.609591568,44.99999998 +130.09,50.42765253,-2.578785525,50.6412,7.067100583,7.071192213,2.81,-3.426505912,2.67417921,44.99999998 +130.1,50.42765316,-2.57878453,50.613,7.077529137,7.071636201,2.8365625,-3.335133238,2.736434913,44.99999998 +130.11,50.4276538,-2.578783534,50.5845,7.084481502,7.071414017,2.863125,-3.24306402,2.796304419,44.99999998 +130.12,50.42765444,-2.57878254,50.5557,7.07752909,7.07141389,2.888125,-3.150317565,2.853735474,44.99999998 +130.13,50.42765507,-2.578781544,50.5267,7.067100474,7.071635821,2.91125,-3.056913184,2.908678058,44.99999998 +130.14,50.42765571,-2.578780549,50.4975,7.063624234,7.07119158,2.9334375,-2.962870412,2.961084216,44.99999998 +130.15,50.42765634,-2.578779554,50.468,7.063624195,7.070525281,2.9546875,-2.868208903,3.010908282,44.99999998 +130.16,50.42765698,-2.578778559,50.4384,7.063624174,7.070303097,2.9746875,-2.772948425,3.058106769,44.99999998 +130.17,50.42765761,-2.578777564,50.4085,7.063624157,7.070525026,2.993125,-2.6771088,3.102638539,44.99999998 +130.18,50.42765825,-2.578776569,50.3785,7.067100323,7.071413127,3.0096875,-2.580710084,3.144464802,44.99999998 +130.19,50.42765888,-2.578775574,50.3483,7.077528857,7.072301229,3.0246875,-2.4837725,3.183549003,44.99999998 +130.2,50.42765952,-2.578774578,50.318,7.084481193,7.071634929,3.038125,-2.386316161,3.219857109,44.99999998 +130.21,50.42766016,-2.578773583,50.2875,7.077528773,7.070302456,3.05,-2.288361463,3.253357493,44.99999998 +130.22,50.42766079,-2.578772589,50.257,7.067100178,7.070524384,3.0615625,-2.18992886,3.284020877,44.99999998 +130.23,50.42766143,-2.578771593,50.2263,7.063623965,7.071412485,3.073125,-2.091038923,3.311820502,44.99999998 +130.24,50.42766206,-2.578770598,50.1955,7.063623927,7.071190299,3.083125,-1.991712335,3.336732192,44.99999998 +130.25,50.4276627,-2.578769603,50.1646,7.067100071,7.070523999,3.09125,-1.891969779,3.358734229,44.99999998 +130.26,50.42766333,-2.578768608,50.1337,7.077528606,7.070301813,3.098125,-1.791832112,3.377807421,44.99999998 +130.27,50.42766397,-2.578767613,50.1026,7.084480966,7.070523741,3.103125,-1.691320246,3.393935037,44.99999998 +130.28,50.42766461,-2.578766618,50.0716,7.077528561,7.071411841,3.10625,-1.590455152,3.407103154,44.99999998 +130.29,50.42766524,-2.578765623,50.0405,7.067099952,7.072521998,3.1084375,-1.489257913,3.417300199,44.99999998 +130.3,50.42766588,-2.578764627,50.0094,7.063623719,7.072521869,3.109375,-1.387749674,3.42451729,44.99999998 +130.31,50.42766651,-2.578763632,49.9783,7.063623676,7.071411454,3.1084375,-1.285951632,3.428748182,44.99999998 +130.32,50.42766715,-2.578762637,49.9472,7.067099831,7.070523096,3.1065625,-1.183885045,3.429989151,44.99999998 +130.33,50.42766778,-2.578761642,49.9162,7.077528381,7.070300909,3.1046875,-1.081571169,3.428239109,44.99999998 +130.34,50.42766842,-2.578760647,49.8851,7.08448074,7.07030078,3.10125,-0.979031434,3.423499602,44.99999998 +130.35,50.42766906,-2.578759652,49.8541,7.077528323,7.070300652,3.0946875,-0.876287267,3.415774756,44.99999998 +130.36,50.42766969,-2.578758657,49.8232,7.067099708,7.07052258,3.0865625,-0.773360097,3.405071332,44.99999998 +130.37,50.42767033,-2.578757662,49.7924,7.063623473,7.07141068,3.0784375,-0.670271411,3.391398553,44.99999998 +130.38,50.42767096,-2.578756667,49.7616,7.06362343,7.072520837,3.0696875,-0.567042751,3.37476851,44.99999998 +130.39,50.4276716,-2.578755671,49.731,7.067099597,7.072520709,3.059375,-0.46369566,3.355195585,44.99999998 +130.4,50.42767223,-2.578754676,49.7004,7.077528158,7.071410295,3.046875,-0.36025174,3.33269685,44.99999998 +130.41,50.42767287,-2.578753681,49.67,7.084480516,7.070521937,3.0328125,-0.25673259,3.307291958,44.99999998 +130.42,50.42767351,-2.578752686,49.6398,7.07752809,7.070299751,3.0184375,-0.153159869,3.279003084,44.99999998 +130.43,50.42767414,-2.578751691,49.6096,7.06709947,7.070299624,3.0028125,-0.049555062,3.247854864,44.99999998 +130.44,50.42767478,-2.578750696,49.5797,7.06362324,7.070299496,2.9846875,0.05406,3.213874456,44.99999998 +130.45,50.42767541,-2.578749701,49.5499,7.063623212,7.070521426,2.965,0.157663833,3.177091539,44.99999998 +130.46,50.42767605,-2.578748706,49.5204,7.063623189,7.071409527,2.945,0.261234721,3.137538086,44.99999998 +130.47,50.42767668,-2.578747711,49.491,7.063623166,7.072519686,2.9246875,0.364751063,3.095248701,44.99999998 +130.48,50.42767732,-2.578746715,49.4619,7.06709933,7.072519559,2.9028125,0.468191202,3.050260227,44.99999998 +130.49,50.42767795,-2.57874572,49.4329,7.077527864,7.071409147,2.8784375,0.571533594,3.002611853,44.99999998 +130.5,50.42767859,-2.578744725,49.4043,7.084480201,7.070520792,2.8528125,0.674756582,2.952345177,44.99999998 +130.51,50.42767923,-2.57874373,49.3759,7.077527784,7.070298609,2.826875,0.777838736,2.899503973,44.99999998 +130.52,50.42767986,-2.578742735,49.3477,7.067099193,7.070298482,2.7996875,0.8807584,2.844134363,44.99999998 +130.53,50.4276805,-2.57874174,49.3199,7.063622984,7.070298357,2.77125,0.983494145,2.786284648,44.99999998 +130.54,50.42768113,-2.578740745,49.2923,7.063622949,7.070298232,2.741875,1.086024484,2.726005248,44.99999998 +130.55,50.42768177,-2.57873975,49.265,7.067099097,7.070520165,2.7109375,1.188327989,2.663348761,44.99999998 +130.56,50.4276824,-2.578738755,49.2381,7.077527633,7.071408269,2.6784375,1.290383346,2.598369732,44.99999998 +130.57,50.42768304,-2.57873776,49.2114,7.08447999,7.072518429,2.645,1.392169241,2.531124941,44.99999998 +130.58,50.42768368,-2.578736764,49.1852,7.077527589,7.072518306,2.61125,1.493664417,2.461672945,44.99999998 +130.59,50.42768431,-2.578735769,49.1592,7.067098999,7.071407897,2.5765625,1.594847675,2.390074306,44.99999998 +130.6,50.42768495,-2.578734774,49.1336,7.063622785,7.070519546,2.539375,1.695697816,2.316391532,44.99999998 +130.61,50.42768558,-2.578733779,49.1084,7.063622751,7.070297366,2.5,1.796193868,2.240688796,44.99999998 +130.62,50.42768622,-2.578732784,49.0836,7.067098902,7.070297244,2.46,1.896314748,2.163032159,44.99999998 +130.63,50.42768685,-2.578731789,49.0592,7.077527442,7.070297123,2.42,1.996039656,2.083489345,44.99999998 +130.64,50.42768749,-2.578730794,49.0352,7.084479808,7.070519058,2.38,2.095347738,2.002129682,44.99999998 +130.65,50.42768813,-2.578729799,49.0116,7.077527413,7.071407166,2.3396875,2.194218194,1.919024159,44.99999998 +130.66,50.42768876,-2.578728804,48.9884,7.067098812,7.072517331,2.2978125,2.292630457,1.834245198,44.99999998 +130.67,50.4276894,-2.578727808,48.9656,7.063622582,7.072517211,2.253125,2.390563898,1.747866711,44.99999998 +130.68,50.42769003,-2.578726813,48.9433,7.063622547,7.071406806,2.2065625,2.487998064,1.659964099,44.99999998 +130.69,50.42769067,-2.578725818,48.9215,7.067098723,7.070518459,2.16,2.584912729,1.570613967,44.99999998 +130.7,50.4276913,-2.578724823,48.9001,7.077527293,7.070296284,2.1134375,2.681287496,1.479894236,44.99999998 +130.71,50.42769194,-2.578723828,48.8792,7.08447966,7.070518223,2.06625,2.777102369,1.387884032,44.99999998 +130.72,50.42769258,-2.578722833,48.8588,7.077527249,7.071184277,2.018125,2.872337236,1.294663513,44.99999998 +130.73,50.42769321,-2.578721838,48.8388,7.067098648,7.071406217,1.968125,2.966972274,1.200314094,44.99999998 +130.74,50.42769385,-2.578720842,48.8194,7.063622432,7.070517873,1.9165625,3.060987658,1.104917939,44.99999998 +130.75,50.42769448,-2.578719848,48.8005,7.063622405,7.070295701,1.8653125,3.154363851,1.008558298,44.99999998 +130.76,50.42769512,-2.578718853,48.7821,7.063622381,7.071627927,1.8146875,3.247081256,0.911319224,44.99999998 +130.77,50.42769575,-2.578717857,48.7642,7.063622367,7.072293984,1.763125,3.339120566,0.813285401,44.99999998 +130.78,50.42769639,-2.578716862,48.7468,7.06709855,7.071405642,1.7096875,3.430462529,0.71454237,44.99999998 +130.79,50.42769702,-2.578715867,48.73,7.077527116,7.070517301,1.655,3.521088123,0.615176305,44.99999998 +130.8,50.42769766,-2.578714872,48.7137,7.084479479,7.070295131,1.6,3.610978383,0.515273779,44.99999998 +130.81,50.4276983,-2.578713877,48.698,7.077527062,7.070295019,1.5446875,3.700114458,0.414921883,44.99999998 +130.82,50.42769893,-2.578712882,48.6828,7.067098462,7.070294908,1.488125,3.7884779,0.314208221,44.99999998 +130.83,50.42769957,-2.578711887,48.6682,7.063622265,7.070516854,1.43,3.876050145,0.213220571,44.99999998 +130.84,50.4277002,-2.578710892,48.6542,7.063622266,7.071404971,1.371875,3.962812915,0.112046939,44.99999998 +130.85,50.42770084,-2.578709897,48.6408,7.067098448,7.072515147,1.3146875,4.048748047,0.010775617,44.99999998 +130.86,50.42770147,-2.578708901,48.6279,7.077526999,7.072515039,1.2565625,4.133837722,-0.090505044,44.99999998 +130.87,50.42770211,-2.578707906,48.6156,7.084479353,7.071404646,1.1965625,4.218064065,-0.191706865,44.99999998 +130.88,50.42770275,-2.578706911,48.604,7.077526956,7.070516309,1.136875,4.301409543,-0.292741441,44.99999998 +130.89,50.42770338,-2.578705916,48.5929,7.067098385,7.070294145,1.078125,4.383856737,-0.393520821,44.99999998 +130.9,50.42770402,-2.578704921,48.5824,7.063622195,7.070516096,1.0178125,4.465388402,-0.493956999,44.99999998 +130.91,50.42770465,-2.578703926,48.5725,7.063622181,7.071182162,0.955,4.545987521,-0.593962428,44.99999998 +130.92,50.42770529,-2.578702931,48.5633,7.067098348,7.071404114,0.891875,4.625637249,-0.693449903,44.99999998 +130.93,50.42770592,-2.578701935,48.5547,7.077526905,7.070515782,0.8303125,4.704321027,-0.792332735,44.99999998 +130.94,50.42770656,-2.578700941,48.5467,7.084479289,7.070293621,0.7696875,4.782022298,-0.890524638,44.99999998 +130.95,50.4277072,-2.578699946,48.5393,7.077526912,7.07162586,0.708125,4.85872496,-0.987939953,44.99999998 +130.96,50.42770783,-2.57869895,48.5325,7.067098333,7.072291929,0.645,4.934412914,-1.08449377,44.99999998 +130.97,50.42770847,-2.578697955,48.5264,7.063622128,7.0714036,0.5815625,5.009070403,-1.180101919,44.99999998 +130.98,50.4277091,-2.57869696,48.5209,7.063622113,7.070515272,0.518125,5.082681786,-1.274680979,44.99999998 +130.99,50.42770974,-2.578695965,48.516,7.067098297,7.070515171,0.4534375,5.155231708,-1.368148501,44.99999998 +131,50.42771037,-2.57869497,48.5118,7.077526874,7.071403299,0.3884375,5.226705041,-1.460422953,44.99999998 +131.01,50.42771101,-2.578693975,48.5083,7.084479262,7.072291428,0.325,5.29708689,-1.551423949,44.99999998 +131.02,50.42771165,-2.578692979,48.5053,7.077526878,7.07162516,0.2615625,5.366362415,-1.641072019,44.99999998 +131.03,50.42771228,-2.578691984,48.503,7.067098301,7.070292721,0.1965625,5.434517292,-1.729289128,44.99999998 +131.04,50.42771292,-2.57869099,48.5014,7.063622112,7.070514681,0.131875,5.501537254,-1.815998211,44.99999998 +131.05,50.42771355,-2.578689994,48.5004,7.063622107,7.071402813,0.0684375,5.567408321,-1.901123754,44.99999998 +131.06,50.42771419,-2.578688999,48.5,7.067098284,7.071180662,0.0046875,5.632116627,-1.984591444,44.99999998 +131.07,50.42771482,-2.578688004,48.5003,7.077526856,7.070514397,-0.06,5.695648766,-2.066328571,44.99999998 +131.08,50.42771546,-2.578687009,48.5012,7.084479253,7.070292245,-0.125,5.757991444,-2.146263804,44.99999998 +131.09,50.4277161,-2.578686014,48.5028,7.077526885,7.070514209,-0.19,5.819131656,-2.22432747,44.99999998 +131.1,50.42771673,-2.578685019,48.505,7.067098309,7.071180288,-0.2546875,5.879056624,-2.300451502,44.99999998 +131.11,50.42771737,-2.578684024,48.5079,7.063622105,7.07162431,-0.3184375,5.937753801,-2.374569552,44.99999998 +131.12,50.427718,-2.578683028,48.5114,7.063622103,7.071402163,-0.3815625,5.995210983,-2.446616875,44.99999998 +131.13,50.42771864,-2.578682034,48.5155,7.063622119,7.071402073,-0.445,6.05141608,-2.516530732,44.99999998 +131.14,50.42771927,-2.578681038,48.5203,7.063622141,7.071624041,-0.5084375,6.106357461,-2.584250161,44.99999998 +131.15,50.42771991,-2.578680043,48.5257,7.067098346,7.071179838,-0.5715625,6.16002361,-2.649716032,44.99999998 +131.16,50.42772054,-2.578679048,48.5317,7.077526924,7.070513579,-0.6353125,6.212403355,-2.712871336,44.99999998 +131.17,50.42772118,-2.578678053,48.5384,7.084479302,7.070291435,-0.6996875,6.263485636,-2.773661012,44.99999998 +131.18,50.42772182,-2.578677058,48.5457,7.077526915,7.070513406,-0.763125,6.313259912,-2.832031947,44.99999998 +131.19,50.42772245,-2.578676063,48.5537,7.067098354,7.071401547,-0.825,6.361715755,-2.887933377,44.99999998 +131.2,50.42772309,-2.578675068,48.5622,7.063622187,7.072289689,-0.8865625,6.408843023,-2.941316427,44.99999998 +131.21,50.42772372,-2.578674072,48.5714,7.063622203,7.071623434,-0.9484375,6.454631862,-2.992134632,44.99999998 +131.22,50.42772436,-2.578673077,48.5812,7.0670984,7.070291009,-1.0096875,6.499072761,-3.040343645,44.99999998 +131.23,50.42772499,-2.578672083,48.5916,7.077526981,7.070512983,-1.07,6.542156437,-3.085901468,44.99999998 +131.24,50.42772563,-2.578671087,48.6026,7.084479374,7.071401127,-1.13,6.58387378,-3.128768279,44.99999998 +131.25,50.42772627,-2.578670092,48.6142,7.077527007,7.071178989,-1.1896875,6.624216254,-3.16890678,44.99999998 +131.26,50.4277269,-2.578669097,48.6264,7.067098451,7.070512737,-1.2484375,6.663175322,-3.206281963,44.99999998 +131.27,50.42772754,-2.578668102,48.6392,7.063622276,7.0702906,-1.3065625,6.700742846,-3.240861226,44.99999998 +131.28,50.42772817,-2.578667107,48.6525,7.063622291,7.070512577,-1.365,6.736911036,-3.272614375,44.99999998 +131.29,50.42772881,-2.578666112,48.6665,7.067098498,7.071400725,-1.4234375,6.771672271,-3.301513794,44.99999998 +131.3,50.42772944,-2.578665117,48.681,7.077527086,7.072510931,-1.48125,6.805019332,-3.327534214,44.99999998 +131.31,50.42773008,-2.578664121,48.6961,7.084479484,7.072510853,-1.538125,6.836945285,-3.350653003,44.99999998 +131.32,50.42773072,-2.578663126,48.7118,7.077527121,7.071400491,-1.593125,6.867443427,-3.370849937,44.99999998 +131.33,50.42773135,-2.578662131,48.728,7.067098569,7.070512187,-1.646875,6.896507399,-3.388107484,44.99999998 +131.34,50.42773199,-2.578661136,48.7447,7.063622396,7.070290054,-1.7015625,6.924131069,-3.402410516,44.99999998 +131.35,50.42773262,-2.578660141,48.762,7.063622409,7.070289978,-1.7565625,6.950308766,-3.4137466,44.99999998 +131.36,50.42773326,-2.578659146,48.7799,7.067098618,7.070289904,-1.8096875,6.975034989,-3.422105882,44.99999998 +131.37,50.42773389,-2.578658151,48.7982,7.077527221,7.070511886,-1.86125,6.998304524,-3.427480971,44.99999998 +131.38,50.42773453,-2.578657156,48.8171,7.084479634,7.07140004,-1.911875,7.020112615,-3.429867283,44.99999998 +131.39,50.42773517,-2.578656161,48.8365,7.077527274,7.072288193,-1.9615625,7.040454623,-3.429262698,44.99999998 +131.4,50.4277358,-2.578655165,48.8563,7.067098719,7.07162195,-2.0115625,7.059326305,-3.425667789,44.99999998 +131.41,50.42773644,-2.57865417,48.8767,7.063622548,7.070289537,-2.0615625,7.07672371,-3.419085593,44.99999998 +131.42,50.42773707,-2.578653176,48.8976,7.063622565,7.070511522,-2.109375,7.092643285,-3.409521896,44.99999998 +131.43,50.42773771,-2.57865218,48.9189,7.063622587,7.071399679,-2.155,7.107081593,-3.396985064,44.99999998 +131.44,50.42773834,-2.578651185,48.9407,7.063622623,7.071177552,-2.2,7.12003571,-3.381485982,44.99999998 +131.45,50.42773898,-2.57865019,48.9629,7.067098852,7.070511312,-2.245,7.131502945,-3.363038231,44.99999998 +131.46,50.42773961,-2.578649195,48.9856,7.077527452,7.070289185,-2.29,7.141480775,-3.341657852,44.99999998 +131.47,50.42774025,-2.5786482,49.0087,7.084479848,7.070511172,-2.334375,7.149967254,-3.317363525,44.99999998 +131.48,50.42774089,-2.578647205,49.0323,7.077527478,7.071399331,-2.3765625,7.156960548,-3.290176391,44.99999998 +131.49,50.42774152,-2.57864621,49.0563,7.067098934,7.072509547,-2.4165625,7.162459167,-3.260120114,44.99999998 +131.5,50.42774216,-2.578645214,49.0806,7.063622785,7.072509479,-2.4565625,7.166462022,-3.227221049,44.99999998 +131.51,50.42774279,-2.578644219,49.1054,7.063622818,7.071399128,-2.4965625,7.168968254,-3.19150773,44.99999998 +131.52,50.42774343,-2.578643224,49.1306,7.067099032,7.070510834,-2.534375,7.169977347,-3.153011441,44.99999998 +131.53,50.42774406,-2.578642229,49.1561,7.077527629,7.070510768,-2.57,7.169489072,-3.111765642,44.99999998 +131.54,50.4277447,-2.578641234,49.182,7.084480032,7.071176872,-2.605,7.167503545,-3.067806314,44.99999998 +131.55,50.42774534,-2.578640239,49.2082,7.077527679,7.071398863,-2.64,7.164021164,-3.021171847,44.99999998 +131.56,50.42774597,-2.578639243,49.2348,7.067099149,7.07051057,-2.6746875,7.159042677,-2.971902862,44.99999998 +131.57,50.42774661,-2.578638249,49.2617,7.063623,7.070288448,-2.7078125,7.152569113,-2.920042333,44.99999998 +131.58,50.42774724,-2.578637254,49.289,7.063623026,7.071620725,-2.738125,7.144601848,-2.865635464,44.99999998 +131.59,50.42774788,-2.578636258,49.3165,7.067099235,7.072286832,-2.7665625,7.135142544,-2.808729754,44.99999998 +131.6,50.42774851,-2.578635263,49.3443,7.077527834,7.071398541,-2.7953125,7.124193092,-2.749374764,44.99999998 +131.61,50.42774915,-2.578634268,49.3724,7.084480258,7.070510249,-2.824375,7.111755897,-2.687622289,44.99999998 +131.62,50.42774979,-2.578633273,49.4008,7.07752792,7.070288129,-2.8515625,7.097833481,-2.623526131,44.99999998 +131.63,50.42775042,-2.578632278,49.4295,7.067099379,7.070288066,-2.87625,7.082428766,-2.557142267,44.99999998 +131.64,50.42775106,-2.578631283,49.4583,7.063623214,7.070288004,-2.8996875,7.06554496,-2.488528508,44.99999998 +131.65,50.42775169,-2.578630288,49.4875,7.063623245,7.070509999,-2.921875,7.047185616,-2.417744787,44.99999998 +131.66,50.42775233,-2.578629293,49.5168,7.067099469,7.071398163,-2.9428125,7.027354573,-2.344852695,44.99999998 +131.67,50.42775296,-2.578628298,49.5463,7.077528075,7.072508385,-2.9634375,7.006055955,-2.269915831,44.99999998 +131.68,50.4277536,-2.578627302,49.5761,7.08448049,7.072508323,-2.9828125,6.983294233,-2.192999628,44.99999998 +131.69,50.42775424,-2.578626307,49.606,7.077528143,7.071397978,-2.9996875,6.959074104,-2.114171063,44.99999998 +131.7,50.42775487,-2.578625312,49.6361,7.067099607,7.070509689,-3.0153125,6.933400667,-2.033498892,44.99999998 +131.71,50.42775551,-2.578624317,49.6663,7.063623455,7.07028757,-3.03125,6.906279309,-1.951053474,44.99999998 +131.72,50.42775614,-2.578623322,49.6967,7.063623485,7.070509567,-3.04625,6.877715586,-1.866906772,44.99999998 +131.73,50.42775678,-2.578622327,49.7273,7.063623504,7.071175676,-3.058125,6.847715631,-1.781132068,44.99999998 +131.74,50.42775741,-2.578621332,49.7579,7.063623532,7.071397672,-3.068125,6.816285573,-1.69380419,44.99999998 +131.75,50.42775805,-2.578620336,49.7886,7.067099771,7.070509384,-3.0784375,6.783432001,-1.604999284,44.99999998 +131.76,50.42775868,-2.578619342,49.8195,7.077528401,7.070287267,-3.0878125,6.749161848,-1.514794757,44.99999998 +131.77,50.42775932,-2.578618347,49.8504,7.084480826,7.071619547,-3.0946875,6.713482162,-1.423269333,44.99999998 +131.78,50.42775996,-2.578617351,49.8814,7.077528462,7.072285657,-3.1,6.676400505,-1.330502825,44.99999998 +131.79,50.42776059,-2.578616356,49.9124,7.0670999,7.07139737,-3.1046875,6.637924556,-1.236576077,44.99999998 +131.8,50.42776123,-2.578615361,49.9435,7.063623742,7.070509083,-3.108125,6.598062335,-1.141571023,44.99999998 +131.81,50.42776186,-2.578614366,49.9746,7.063623795,7.070286966,-3.109375,6.556822208,-1.045570512,44.99999998 +131.82,50.4277625,-2.578613371,50.0057,7.067100037,7.070508962,-3.1084375,6.514212769,-0.948658254,44.99999998 +131.83,50.42776313,-2.578612376,50.0368,7.077528647,7.071175072,-3.1065625,6.470242957,-0.850918701,44.99999998 +131.84,50.42776377,-2.578611381,50.0678,7.084481053,7.071619125,-3.105,6.424921881,-0.752437168,44.99999998 +131.85,50.42776441,-2.578610385,50.0989,7.077528691,7.071397008,-3.1028125,6.378259052,-0.653299541,44.99999998 +131.86,50.42776504,-2.578609391,50.1299,7.067100153,7.071396948,-3.0978125,6.330264154,-0.553592165,44.99999998 +131.87,50.42776568,-2.578608395,50.1609,7.063624011,7.071618944,-3.0903125,6.280947327,-0.453402072,44.99999998 +131.88,50.42776631,-2.5786074,50.1917,7.06362405,7.07117477,-3.0828125,6.230318771,-0.352816581,44.99999998 +131.89,50.42776695,-2.578606405,50.2225,7.067100272,7.070508539,-3.075,6.178389142,-0.251923469,44.99999998 +131.9,50.42776758,-2.57860541,50.2533,7.077528878,7.070286422,-3.0646875,6.125169213,-0.150810628,44.99999998 +131.91,50.42776822,-2.578604415,50.2838,7.084481295,7.070508418,-3.053125,6.070670097,-0.04956635,44.99999998 +131.92,50.42776886,-2.57860342,50.3143,7.077528947,7.071396584,-3.0415625,6.014903198,0.051721244,44.99999998 +131.93,50.42776949,-2.578602425,50.3447,7.067100408,7.072284749,-3.0278125,5.957880147,0.152963688,44.99999998 +131.94,50.42777013,-2.578601429,50.3749,7.063624251,7.071618518,-3.01125,5.899612917,0.254072748,44.99999998 +131.95,50.42777076,-2.578600434,50.4049,7.063624287,7.070286116,-2.9934375,5.840113599,0.354960246,44.99999998 +131.96,50.4277714,-2.57859944,50.4348,7.067100519,7.070508112,-2.975,5.779394684,0.455538174,44.99999998 +131.97,50.42777203,-2.578598444,50.4644,7.077529129,7.071396276,-2.95625,5.717468775,0.555718927,44.99999998 +131.98,50.42777267,-2.578597449,50.4939,7.084481533,7.071174157,-2.9365625,5.654348879,0.655415074,44.99999998 +131.99,50.42777331,-2.578596454,50.5232,7.077529173,7.070507925,-2.914375,5.590048118,0.754539694,44.99999998 +132,50.42777394,-2.578595459,50.5522,7.067100637,7.070285806,-2.89,5.524579955,0.85300633,44.99999998 +132.01,50.42777458,-2.578594464,50.581,7.063624489,7.0705078,-2.865,5.457958027,0.950729095,44.99999998 +132.02,50.42777521,-2.578593469,50.6095,7.063624519,7.071173907,-2.84,5.390196314,1.047622847,44.99999998 +132.03,50.42777585,-2.578592474,50.6378,7.067100729,7.071617957,-2.8146875,5.32130891,1.143603075,44.99999998 +132.04,50.42777648,-2.578591478,50.6658,7.077529335,7.071395837,-2.7878125,5.251310255,1.238586071,44.99999998 +132.05,50.42777712,-2.578590484,50.6936,7.084481765,7.071395772,-2.758125,5.180214902,1.332488983,44.99999998 +132.06,50.42777776,-2.578589488,50.721,7.077529425,7.071617764,-2.7265625,5.10803769,1.425229937,44.99999998 +132.07,50.42777839,-2.578588493,50.7481,7.067100881,7.071173586,-2.695,5.034793802,1.516728031,44.99999998 +132.08,50.42777903,-2.578587498,50.7749,7.063624712,7.070507351,-2.6628125,4.960498422,1.606903567,44.99999998 +132.09,50.42777966,-2.578586503,50.8014,7.063624726,7.070285229,-2.628125,4.885167077,1.695677877,44.99999998 +132.1,50.4277803,-2.578585508,50.8275,7.063624745,7.07050722,-2.5915625,4.80881558,1.782973497,44.99999998 +132.11,50.42778093,-2.578584513,50.8532,7.063624781,7.071395382,-2.5553125,4.731459804,1.868714339,44.99999998 +132.12,50.42778157,-2.578583518,50.8786,7.067101019,7.072283542,-2.5196875,4.653115904,1.952825632,44.99999998 +132.13,50.4277822,-2.578582522,50.9036,7.077529631,7.071617304,-2.4828125,4.573800325,2.035234037,44.99999998 +132.14,50.42778284,-2.578581527,50.9283,7.084482033,7.070284897,-2.443125,4.493529511,2.115867706,44.99999998 +132.15,50.42778348,-2.578580533,50.9525,7.077529662,7.070506885,-2.4015625,4.412320249,2.194656278,44.99999998 +132.16,50.42778411,-2.578579537,50.9763,7.067101115,7.071395044,-2.36,4.330189614,2.271531057,44.99999998 +132.17,50.42778475,-2.578578542,50.9997,7.063624963,7.071172918,-2.318125,4.247154622,2.346425063,44.99999998 +132.18,50.42778538,-2.578577547,51.0227,7.063624994,7.070506679,-2.2746875,4.163232692,2.41927298,44.99999998 +132.19,50.42778602,-2.578576552,51.0452,7.067101209,7.070506609,-2.23,4.078441298,2.490011209,44.99999998 +132.2,50.42778665,-2.578575557,51.0673,7.077529813,7.071394766,-2.185,3.992798145,2.558578156,44.99999998 +132.21,50.42778729,-2.578574562,51.0889,7.084482224,7.072504978,-2.139375,3.906321224,2.624913949,44.99999998 +132.22,50.42778793,-2.578573566,51.1101,7.077529853,7.072504907,-2.0915625,3.819028468,2.688960776,44.99999998 +132.23,50.42778856,-2.578572571,51.1308,7.067101291,7.071394552,-2.0415625,3.730938155,2.750662773,44.99999998 +132.24,50.4277892,-2.578571576,51.1509,7.063625125,7.070506253,-1.991875,3.642068734,2.809966197,44.99999998 +132.25,50.42778983,-2.578570581,51.1706,7.063625157,7.070284123,-1.9434375,3.552438655,2.866819252,44.99999998 +132.26,50.42779047,-2.578569586,51.1898,7.067101379,7.070506107,-1.894375,3.462066709,2.921172434,44.99999998 +132.27,50.4277911,-2.578568591,51.2085,7.077529978,7.071172203,-1.843125,3.370971748,2.972978247,44.99999998 +132.28,50.42779174,-2.578567596,51.2267,7.084482371,7.071394184,-1.79,3.279172851,3.022191655,44.99999998 +132.29,50.42779238,-2.5785666,51.2443,7.077529997,7.070505882,-1.7365625,3.186689098,3.068769628,44.99999998 +132.3,50.42779301,-2.578565606,51.2614,7.067101444,7.07028375,-1.683125,3.093539854,3.112671603,44.99999998 +132.31,50.42779365,-2.578564611,51.278,7.063625278,7.071616014,-1.628125,2.999744543,3.153859247,44.99999998 +132.32,50.42779428,-2.578563615,51.294,7.063625299,7.072282107,-1.5715625,2.905322818,3.192296693,44.99999998 +132.33,50.42779492,-2.57856262,51.3094,7.063625314,7.071393803,-1.5153125,2.81029433,3.227950425,44.99999998 +132.34,50.42779555,-2.578561625,51.3243,7.063625325,7.070505499,-1.4596875,2.714678961,3.260789329,44.99999998 +132.35,50.42779619,-2.57856063,51.3386,7.067101531,7.070283364,-1.403125,2.61849665,3.290784758,44.99999998 +132.36,50.42779682,-2.578559635,51.3524,7.077530133,7.070505341,-1.345,2.521767509,3.317910585,44.99999998 +132.37,50.42779746,-2.57855864,51.3655,7.084482546,7.07117143,-1.2865625,2.424511705,3.342143205,44.99999998 +132.38,50.4277981,-2.578557645,51.3781,7.077530179,7.071615462,-1.2284375,2.326749578,3.36346136,44.99999998 +132.39,50.42779873,-2.578556649,51.3901,7.067101607,7.071393324,-1.1696875,2.228501582,3.381846545,44.99999998 +132.4,50.42779937,-2.578555655,51.4015,7.063625413,7.071393242,-1.1096875,2.129788116,3.397282715,44.99999998 +132.41,50.4278,-2.578554659,51.4123,7.063625426,7.071615216,-1.0484375,2.03062992,3.40975635,44.99999998 +132.42,50.42780064,-2.578553664,51.4225,7.067101645,7.07117102,-0.9865625,1.931047678,3.419256678,44.99999998 +132.43,50.42780127,-2.578552669,51.432,7.077530243,7.070504766,-0.925,1.831062131,3.425775391,44.99999998 +132.44,50.42780191,-2.578551674,51.441,7.084482635,7.070282624,-0.8634375,1.730694192,3.429306701,44.99999998 +132.45,50.42780255,-2.578550679,51.4493,7.077530246,7.070504595,-0.80125,1.629964831,3.429847688,44.99999998 +132.46,50.42780318,-2.578549684,51.457,7.067101662,7.071170679,-0.7384375,1.528895019,3.427397721,44.99999998 +132.47,50.42780382,-2.578548689,51.4641,7.063625479,7.071392649,-0.675,1.427506012,3.421959033,44.99999998 +132.48,50.42780445,-2.578547693,51.4705,7.063625504,7.070504335,-0.611875,1.325818838,3.413536382,44.99999998 +132.49,50.42780509,-2.578546699,51.4763,7.067101719,7.070282189,-0.55,1.223854753,3.402137043,44.99999998 +132.5,50.42780572,-2.578545704,51.4815,7.077530303,7.07161444,-0.488125,1.121635129,3.387770985,44.99999998 +132.51,50.42780636,-2.578544708,51.4861,7.084482682,7.072280521,-0.4246875,1.019181222,3.370450758,44.99999998 +132.52,50.427807,-2.578543713,51.49,7.077530288,7.071392204,-0.36,0.916514519,3.350191486,44.99999998 +132.53,50.42780763,-2.578542718,51.4933,7.067101717,7.070503886,-0.295,0.813656391,3.327010759,44.99999998 +132.54,50.42780827,-2.578541723,51.4959,7.063625542,7.070281738,-0.23,0.710628323,3.300928804,44.99999998 +132.55,50.4278089,-2.578540728,51.4979,7.063625549,7.070503702,-0.165,0.60745186,3.271968423,44.99999998 +132.56,50.42780954,-2.578539733,51.4992,7.067101739,7.071169779,-0.1,0.504148543,3.240154827,44.99999998 +132.57,50.42781017,-2.578538738,51.4999,7.077530313,7.071613798,-0.0353125,0.400739975,3.205515746,44.99999998 +132.58,50.42781081,-2.578537742,51.4999,7.084482698,7.071391647,0.0284375,0.297247697,3.168081434,44.99999998 +132.59,50.42781145,-2.578536748,51.4993,7.077530314,7.071391552,0.0915625,0.19369331,3.127884492,44.99999998 +132.6,50.42781208,-2.578535752,51.4981,7.067101738,7.071613512,0.1553125,0.09009853,3.084960041,44.99999998 +132.61,50.42781272,-2.578534757,51.4962,7.063625545,7.071169302,0.22,-0.0135151,3.039345381,44.99999998 +132.62,50.42781335,-2.578533762,51.4937,7.063625545,7.070503035,0.2846875,-0.117125923,2.99108039,44.99999998 +132.63,50.42781399,-2.578532767,51.4905,7.067101741,7.070280881,0.3484375,-0.220712281,2.940207181,44.99999998 +132.64,50.42781462,-2.578531772,51.4867,7.077530315,7.070502838,0.4115625,-0.324252515,2.886770043,44.99999998 +132.65,50.42781526,-2.578530777,51.4823,7.084482684,7.071390964,0.4753125,-0.427725083,2.830815558,44.99999998 +132.66,50.4278159,-2.578529782,51.4772,7.077530284,7.072279091,0.54,-0.53110827,2.772392598,44.99999998 +132.67,50.42781653,-2.578528786,51.4715,7.067101708,7.071612821,0.6046875,-0.63438059,2.711552044,44.99999998 +132.68,50.42781717,-2.578527791,51.4651,7.063625523,7.070280379,0.668125,-0.737520384,2.648347007,44.99999998 +132.69,50.4278178,-2.578526797,51.4581,7.06362552,7.070502333,0.73,-0.840506167,2.582832549,44.99999998 +132.7,50.42781844,-2.578525801,51.4505,7.063625499,7.071390456,0.791875,-0.943316453,2.515065851,44.99999998 +132.71,50.42781907,-2.578524806,51.4423,7.063625473,7.071168296,0.8546875,-1.045929699,2.445105928,44.99999998 +132.72,50.42781971,-2.578523811,51.4334,7.067101658,7.070502022,0.9165625,-1.148324534,2.373013857,44.99999998 +132.73,50.42782034,-2.578522816,51.4239,7.077530248,7.070501917,0.9765625,-1.250479586,2.298852549,44.99999998 +132.74,50.42782098,-2.578521821,51.4139,7.084482639,7.071390037,1.036875,-1.352373483,2.222686519,44.99999998 +132.75,50.42782162,-2.578520826,51.4032,7.077530236,7.072500213,1.0984375,-1.453984913,2.144582288,44.99999998 +132.76,50.42782225,-2.57851983,51.3919,7.067101626,7.072500106,1.1596875,-1.555292732,2.064607979,44.99999998 +132.77,50.42782289,-2.578518835,51.38,7.063625409,7.071389716,1.2196875,-1.656275741,1.982833323,44.99999998 +132.78,50.42782352,-2.57851784,51.3675,7.063625403,7.070501382,1.2784375,-1.756912798,1.899329537,44.99999998 +132.79,50.42782416,-2.578516845,51.3544,7.067101598,7.070279216,1.3365625,-1.857183048,1.814169559,44.99999998 +132.8,50.42782479,-2.57851585,51.3408,7.07753017,7.070501162,1.3946875,-1.957065405,1.727427588,44.99999998 +132.81,50.42782543,-2.578514855,51.3265,7.084482536,7.071167221,1.451875,-2.056539015,1.639179253,44.99999998 +132.82,50.42782607,-2.57851386,51.3117,7.077530124,7.071389167,1.5078125,-2.155583192,1.549501561,44.99999998 +132.83,50.4278267,-2.578512864,51.2964,7.067101522,7.070500829,1.56375,-2.254177196,1.458472662,44.99999998 +132.84,50.42782734,-2.57851187,51.2804,7.063625315,7.07027866,1.6196875,-2.352300401,1.366171969,44.99999998 +132.85,50.42782797,-2.578510875,51.264,7.063625304,7.071610886,1.6746875,-2.44993241,1.272679924,44.99999998 +132.86,50.42782861,-2.578509879,51.2469,7.067101482,7.072276942,1.7284375,-2.547052767,1.178078118,44.99999998 +132.87,50.42782924,-2.578508884,51.2294,7.077530045,7.071388602,1.78125,-2.64364119,1.082448998,44.99999998 +132.88,50.42782988,-2.578507889,51.2113,7.084482412,7.070500261,1.8334375,-2.739677568,0.98587593,44.99999998 +132.89,50.42783052,-2.578506894,51.1927,7.077529997,7.07027809,1.885,-2.835141733,0.888443197,44.99999998 +132.9,50.42783115,-2.578505899,51.1736,7.067101391,7.070500031,1.9365625,-2.930013861,0.79023571,44.99999998 +132.91,50.42783179,-2.578504904,51.154,7.06362518,7.071166084,1.9878125,-3.02427407,0.691339183,44.99999998 +132.92,50.42783242,-2.578503909,51.1338,7.063625168,7.07161008,2.0365625,-3.117902707,0.591839734,44.99999998 +132.93,50.42783306,-2.578502913,51.1132,7.063625152,7.071387906,2.083125,-3.210880236,0.491824221,44.99999998 +132.94,50.42783369,-2.578501919,51.0922,7.063625125,7.071387788,2.1303125,-3.303187174,0.39137985,44.99999998 +132.95,50.42783433,-2.578500923,51.0706,7.067101281,7.071609726,2.178125,-3.394804329,0.29059411,44.99999998 +132.96,50.42783496,-2.578499928,51.0486,7.077529832,7.071165494,2.224375,-3.485712448,0.189555065,44.99999998 +132.97,50.4278356,-2.578498933,51.0261,7.084482206,7.070499205,2.2684375,-3.575892682,0.088350665,44.99999998 +132.98,50.42783624,-2.578497938,51.0032,7.07752981,7.070277028,2.31125,-3.665326123,-0.012930741,44.99999998 +132.99,50.42783687,-2.578496943,50.9799,7.067101207,7.070498964,2.3534375,-3.753994092,-0.114200916,44.99999998 +133,50.42783751,-2.578495948,50.9561,7.067101169,7.071165013,2.395,-3.84187814,-0.215371455,44.99999998 +133.01,50.42783814,-2.578494953,50.932,7.077529706,7.071386948,2.43625,-3.928959818,-0.316354235,44.99999998 +133.02,50.42783878,-2.578493957,50.9074,7.084482065,7.070498601,2.4765625,-4.015220963,-0.417061136,44.99999998 +133.03,50.42783942,-2.578492963,50.8824,7.077529662,7.070276422,2.5146875,-4.100643584,-0.517404323,44.99999998 +133.04,50.42784005,-2.578491968,50.8571,7.067101064,7.071608637,2.5515625,-4.185209863,-0.617296363,44.99999998 +133.05,50.42784069,-2.578490972,50.8314,7.063624849,7.072274683,2.588125,-4.268902152,-0.71665011,44.99999998 +133.06,50.42784132,-2.578489977,50.8053,7.063624817,7.071386334,2.623125,-4.351702861,-0.815378931,44.99999998 +133.07,50.42784196,-2.578488982,50.7789,7.063624775,7.070497984,2.6565625,-4.433594802,-0.913396712,44.99999998 +133.08,50.42784259,-2.578487987,50.7522,7.063624746,7.070275804,2.69,-4.514560843,-1.010617967,44.99999998 +133.09,50.42784323,-2.578486992,50.7251,7.067100924,7.070497736,2.7228125,-4.594584083,-1.106958013,44.99999998 +133.1,50.42784386,-2.578485997,50.6977,7.07752948,7.071163781,2.753125,-4.673647789,-1.202332739,44.99999998 +133.11,50.4278445,-2.578485002,50.67,7.084481832,7.071607768,2.7815625,-4.75173552,-1.29665901,44.99999998 +133.12,50.42784514,-2.578484006,50.6421,7.077529413,7.071385586,2.8096875,-4.82883083,-1.389854549,44.99999998 +133.13,50.42784577,-2.578483012,50.6138,7.067100799,7.07138546,2.8365625,-4.904917734,-1.481838167,44.99999998 +133.14,50.42784641,-2.578482016,50.5853,7.063624568,7.071607391,2.8615625,-4.979980305,-1.572529594,44.99999998 +133.15,50.42784704,-2.578481021,50.5566,7.063624533,7.071163151,2.8865625,-5.054002899,-1.661849704,44.99999998 +133.16,50.42784768,-2.578480026,50.5276,7.067100699,7.070496855,2.91125,-5.126969991,-1.749720688,44.99999998 +133.17,50.42784831,-2.578479031,50.4983,7.077529257,7.070274672,2.933125,-5.198866397,-1.836065886,44.99999998 +133.18,50.42784895,-2.578478036,50.4689,7.084481619,7.070496601,2.953125,-5.269677105,-1.920810011,44.99999998 +133.19,50.42784959,-2.578477041,50.4393,7.077529195,7.071384698,2.973125,-5.339387276,-2.003879208,44.99999998 +133.2,50.42785022,-2.578476046,50.4094,7.067100567,7.072272796,2.9915625,-5.407982413,-2.085200942,44.99999998 +133.21,50.42785086,-2.57847505,50.3794,7.063624335,7.0716065,3.0078125,-5.475448136,-2.164704336,44.99999998 +133.22,50.42785149,-2.578474055,50.3493,7.063624311,7.070274034,3.0234375,-5.541770407,-2.242320064,44.99999998 +133.23,50.42785213,-2.578473061,50.3189,7.06710048,7.070495962,3.038125,-5.606935304,-2.317980516,44.99999998 +133.24,50.42785276,-2.578472065,50.2885,7.07752903,7.071384059,3.05125,-5.670929304,-2.39161963,44.99999998 +133.25,50.4278534,-2.57847107,50.2579,7.084481381,7.071161874,3.0634375,-5.733739,-2.463173178,44.99999998 +133.26,50.42785404,-2.578470075,50.2272,7.077528954,7.070495576,3.074375,-5.795351272,-2.532578879,44.99999998 +133.27,50.42785467,-2.57846908,50.1964,7.067100336,7.070495447,3.083125,-5.855753285,-2.599776056,44.99999998 +133.28,50.42785531,-2.578468085,50.1655,7.063624114,7.071383543,3.09,-5.914932376,-2.664706212,44.99999998 +133.29,50.42785594,-2.57846709,50.1346,7.063624089,7.072493697,3.09625,-5.972876171,-2.727312737,44.99999998 +133.3,50.42785658,-2.578466094,50.1036,7.063624062,7.072493568,3.1015625,-6.029572637,-2.787540972,44.99999998 +133.31,50.42785721,-2.578465099,50.0725,7.063624024,7.071383157,3.1046875,-6.085009913,-2.845338434,44.99999998 +133.32,50.42785785,-2.578464104,50.0415,7.067100169,7.070494804,3.1065625,-6.139176426,-2.900654759,44.99999998 +133.33,50.42785848,-2.578463109,50.0104,7.077528708,7.070272618,3.1084375,-6.192060832,-2.953441647,44.99999998 +133.34,50.42785912,-2.578462114,49.9793,7.084481072,7.070494545,3.109375,-6.243652129,-3.003653032,44.99999998 +133.35,50.42785976,-2.578461119,49.9482,7.077528667,7.071160585,3.108125,-6.293939489,-3.051245256,44.99999998 +133.36,50.42786039,-2.578460124,49.9171,7.067100058,7.071382512,3.1046875,-6.342912426,-3.096176721,44.99999998 +133.37,50.42786103,-2.578459128,49.8861,7.06362382,7.070494158,3.1,-6.390560742,-3.138408294,44.99999998 +133.38,50.42786166,-2.578458134,49.8551,7.063623776,7.070271972,3.0946875,-6.436874525,-3.177903134,44.99999998 +133.39,50.4278623,-2.578457139,49.8242,7.067099937,7.071604181,3.088125,-6.481843977,-3.214626749,44.99999998 +133.4,50.42786293,-2.578456143,49.7933,7.07752849,7.072270221,3.0796875,-6.525459816,-3.248547169,44.99999998 +133.41,50.42786357,-2.578455148,49.7626,7.084480845,7.071381868,3.07,-6.567712875,-3.279634827,44.99999998 +133.42,50.42786421,-2.578454153,49.7319,7.077528424,7.070493514,3.0596875,-6.608594388,-3.307862624,44.99999998 +133.43,50.42786484,-2.578453158,49.7014,7.067099802,7.070271329,3.0478125,-6.64809576,-3.333205866,44.99999998 +133.44,50.42786548,-2.578452163,49.6709,7.063623567,7.070493258,3.0334375,-6.686208741,-3.355642549,44.99999998 +133.45,50.42786611,-2.578451168,49.6407,7.063623541,7.071159298,3.018125,-6.722925423,-3.375153022,44.99999998 +133.46,50.42786675,-2.578450173,49.6106,7.067099717,7.071603283,3.003125,-6.758238073,-3.391720326,44.99999998 +133.47,50.42786738,-2.578449177,49.5806,7.077528268,7.071381098,2.98625,-6.792139355,-3.405329965,44.99999998 +133.48,50.42786802,-2.578448183,49.5508,7.084480615,7.071380971,2.9665625,-6.824622223,-3.415970192,44.99999998 +133.49,50.42786866,-2.578447187,49.5213,7.077528189,7.0716029,2.9465625,-6.855679859,-3.423631554,44.99999998 +133.5,50.42786929,-2.578446192,49.4919,7.067099573,7.07115866,2.9265625,-6.88530573,-3.42830752,44.99999998 +133.51,50.42786993,-2.578445197,49.4627,7.063623353,7.070492364,2.904375,-6.913493707,-3.429993907,44.99999998 +133.52,50.42787056,-2.578444202,49.4338,7.063623329,7.070270182,2.8796875,-6.940237887,-3.428689282,44.99999998 +133.53,50.4278712,-2.578443207,49.4051,7.067099493,7.070492112,2.8534375,-6.965532713,-3.424394849,44.99999998 +133.54,50.42787183,-2.578442212,49.3767,7.077528043,7.07138021,2.8265625,-6.989372857,-3.417114217,44.99999998 +133.55,50.42787247,-2.578441217,49.3486,7.084480403,7.072268309,2.8,-7.01175339,-3.40685386,44.99999998 +133.56,50.42787311,-2.578440221,49.3207,7.077527982,7.071602015,2.7728125,-7.032669558,-3.393622661,44.99999998 +133.57,50.42787374,-2.578439226,49.2931,7.067099358,7.070269553,2.743125,-7.052117064,-3.377432191,44.99999998 +133.58,50.42787438,-2.578438232,49.2658,7.063623129,7.070491484,2.7115625,-7.070091838,-3.358296547,44.99999998 +133.59,50.42787501,-2.578437236,49.2389,7.063623111,7.071379584,2.6796875,-7.086590101,-3.3362324,44.99999998 +133.6,50.42787565,-2.578436241,49.2122,7.067099289,7.071157404,2.6465625,-7.101608413,-3.311259004,44.99999998 +133.61,50.42787628,-2.578435246,49.1859,7.077527837,7.070491112,2.61125,-7.115143682,-3.283398186,44.99999998 +133.62,50.42787692,-2.578434251,49.16,7.084480179,7.070268932,2.575,-7.127192984,-3.252674126,44.99999998 +133.63,50.42787756,-2.578433256,49.1344,7.077527759,7.070490865,2.5384375,-7.137753914,-3.219113754,44.99999998 +133.64,50.42787819,-2.578432261,49.1092,7.067099164,7.071378967,2.50125,-7.14682418,-3.182746232,44.99999998 +133.65,50.42787883,-2.578431266,49.0844,7.06362296,7.072489126,2.463125,-7.154401948,-3.143603302,44.99999998 +133.66,50.42787946,-2.57843027,49.0599,7.063622941,7.072489005,2.423125,-7.160485614,-3.101719113,44.99999998 +133.67,50.4278801,-2.578429275,49.0359,7.063622908,7.071378603,2.3815625,-7.165073917,-3.057130163,44.99999998 +133.68,50.42788073,-2.57842828,49.0123,7.063622867,7.070490258,2.34,-7.168165826,-3.009875411,44.99999998 +133.69,50.42788137,-2.578427285,48.9891,7.067099024,7.070268081,2.2978125,-7.169760826,-2.95999594,44.99999998 +133.7,50.427882,-2.57842629,48.9663,7.077527584,7.07026796,2.253125,-7.169858458,-2.907535294,44.99999998 +133.71,50.42788264,-2.578425295,48.944,7.084479961,7.070267841,2.206875,-7.16845878,-2.85253931,44.99999998 +133.72,50.42788328,-2.5784243,48.9222,7.077527557,7.070489779,2.1615625,-7.165562077,-2.795055829,44.99999998 +133.73,50.42788391,-2.578423305,48.9008,7.067098949,7.071377885,2.1165625,-7.161168923,-2.735134986,44.99999998 +133.74,50.42788455,-2.57842231,48.8798,7.063622725,7.072488048,2.069375,-7.155280235,-2.672829092,44.99999998 +133.75,50.42788518,-2.578421314,48.8594,7.063622699,7.072487931,2.02,-7.147897273,-2.608192463,44.99999998 +133.76,50.42788582,-2.578420319,48.8394,7.067098875,7.071377534,1.97,-7.139021583,-2.54128142,44.99999998 +133.77,50.42788645,-2.578419324,48.82,7.077527438,7.070489193,1.9196875,-7.128655001,-2.472154406,44.99999998 +133.78,50.42788709,-2.578418329,48.801,7.084479806,7.07026702,1.8684375,-7.116799644,-2.400871581,44.99999998 +133.79,50.42788773,-2.578417334,48.7826,7.077527401,7.070488961,1.81625,-7.103458036,-2.327495168,44.99999998 +133.8,50.42788836,-2.578416339,48.7647,7.067098802,7.071155015,1.7634375,-7.088632982,-2.252089166,44.99999998 +133.81,50.427889,-2.578415344,48.7473,7.063622584,7.071376958,1.7096875,-7.072327577,-2.174719295,44.99999998 +133.82,50.42788963,-2.578414348,48.7305,7.063622562,7.07048862,1.655,-7.054545202,-2.09545299,44.99999998 +133.83,50.42789027,-2.578413354,48.7142,7.067098741,7.070266452,1.6,-7.03528958,-2.014359466,44.99999998 +133.84,50.4278909,-2.578412359,48.6985,7.077527311,7.071598676,1.545,-7.014564722,-1.931509425,44.99999998 +133.85,50.42789154,-2.578411363,48.6833,7.084479687,7.072264733,1.4896875,-6.992374926,-1.846975003,44.99999998 +133.86,50.42789218,-2.578410368,48.6687,7.077527282,7.071376397,1.433125,-6.96872489,-1.760830053,44.99999998 +133.87,50.42789281,-2.578409373,48.6546,7.067098674,7.070488063,1.375,-6.943619541,-1.673149577,44.99999998 +133.88,50.42789345,-2.578408378,48.6412,7.063622461,7.070487954,1.3165625,-6.917064093,-1.584010121,44.99999998 +133.89,50.42789408,-2.578407383,48.6283,7.063622458,7.071376069,1.2584375,-6.889064104,-1.493489379,44.99999998 +133.9,50.42789472,-2.578406388,48.616,7.063622461,7.072264185,1.1996875,-6.859625418,-1.401666303,44.99999998 +133.91,50.42789535,-2.578405392,48.6043,7.063622453,7.071597909,1.14,-6.828754166,-1.308620994,44.99999998 +133.92,50.42789599,-2.578404397,48.5932,7.067098621,7.070265466,1.0796875,-6.796456879,-1.214434467,44.99999998 +133.93,50.42789662,-2.578403403,48.5827,7.07752717,7.070487415,1.0184375,-6.762740146,-1.119189,44.99999998 +133.94,50.42789726,-2.578402407,48.5728,7.084479545,7.071375534,0.9565625,-6.727611187,-1.022967556,44.99999998 +133.95,50.4278979,-2.578401412,48.5636,7.077527168,7.071153373,0.895,-6.69107722,-0.925854075,44.99999998 +133.96,50.42789853,-2.578400417,48.5549,7.067098595,7.070487101,0.8334375,-6.653145925,-0.827933181,44.99999998 +133.97,50.42789917,-2.578399422,48.5469,7.067098582,7.070264941,0.77125,-6.613825149,-0.729290361,44.99999998 +133.98,50.4278998,-2.578398427,48.5395,7.077527137,7.070486894,0.7084375,-6.573123201,-0.630011615,44.99999998 +133.99,50.42790044,-2.578397432,48.5327,7.084479502,7.071375016,0.645,-6.531048561,-0.530183459,44.99999998 +134,50.42790108,-2.578396437,48.5266,7.077527111,7.072485195,0.581875,-6.487609938,-0.429892984,44.99999998 +134.01,50.42790171,-2.578395441,48.5211,7.067098541,7.072485094,0.52,-6.442816498,-0.329227622,44.99999998 +134.02,50.42790235,-2.578394446,48.5162,7.06362236,7.071374714,0.4578125,-6.396677582,-0.228275209,44.99999998 +134.03,50.42790298,-2.578393451,48.5119,7.06362236,7.070486391,0.393125,-6.349202758,-0.127123693,44.99999998 +134.04,50.42790362,-2.578392456,48.5083,7.063622346,7.070264236,0.326875,-6.300401994,-0.025861367,44.99999998 +134.05,50.42790425,-2.578391461,48.5054,7.063622332,7.070264138,0.261875,-6.250285491,0.075423534,44.99999998 +134.06,50.42790489,-2.578390466,48.5031,7.067098525,7.070264041,0.1984375,-6.198863674,0.176642716,44.99999998 +134.07,50.42790552,-2.578389471,48.5014,7.077527108,7.070486,0.1346875,-6.146147317,0.277707773,44.99999998 +134.08,50.42790616,-2.578388476,48.5004,7.084479495,7.071374129,0.07,-6.09214742,0.378530755,44.99999998 +134.09,50.4279068,-2.578387481,48.5,7.077527113,7.072484314,0.0053125,-6.03687527,0.479023599,44.99999998 +134.1,50.42790743,-2.578386485,48.5003,7.067098541,7.072484219,-0.0584375,-5.980342384,0.579098699,44.99999998 +134.11,50.42790807,-2.57838549,48.5012,7.063622346,7.071373845,-0.121875,-5.922560565,0.678668852,44.99999998 +134.12,50.4279087,-2.578384495,48.5027,7.063622333,7.070485528,-0.1865625,-5.863541901,0.777647197,44.99999998 +134.13,50.42790934,-2.5783835,48.5049,7.067098522,7.07026338,-0.251875,-5.803298712,0.875947446,44.99999998 +134.14,50.42790997,-2.578382505,48.5078,7.077527114,7.070485345,-0.31625,-5.741843545,0.973483827,44.99999998 +134.15,50.42791061,-2.57838151,48.5112,7.084479517,7.071151422,-0.38,-5.67918935,1.070171315,44.99999998 +134.16,50.42791125,-2.578380515,48.5154,7.077527135,7.071373387,-0.4434375,-5.615349075,1.165925568,44.99999998 +134.17,50.42791188,-2.578379519,48.5201,7.067098548,7.070485074,-0.5065625,-5.550336069,1.260663166,44.99999998 +134.18,50.42791252,-2.578378525,48.5255,7.063622356,7.070262929,-0.5703125,-5.484164028,1.354301429,44.99999998 +134.19,50.42791315,-2.57837753,48.5315,7.063622372,7.071595178,-0.6346875,-5.416846643,1.446758712,44.99999998 +134.2,50.42791379,-2.578376534,48.5382,7.067098582,7.072261259,-0.698125,-5.348398011,1.537954456,44.99999998 +134.21,50.42791442,-2.578375539,48.5455,7.077527172,7.071372948,-0.76,-5.278832455,1.62780902,44.99999998 +134.22,50.42791506,-2.578374544,48.5534,7.084479571,7.070484638,-0.821875,-5.208164471,1.716244139,44.99999998 +134.23,50.4279157,-2.578373549,48.5619,7.077527192,7.070262497,-0.885,-5.136408841,1.803182635,44.99999998 +134.24,50.42791633,-2.578372554,48.5711,7.06709861,7.070484468,-0.9478125,-5.063580519,1.888548763,44.99999998 +134.25,50.42791697,-2.578371559,48.5809,7.063622423,7.071150552,-1.008125,-4.989694747,1.972268038,44.99999998 +134.26,50.4279176,-2.578370564,48.5913,7.063622446,7.071594581,-1.066875,-4.914766936,2.054267466,44.99999998 +134.27,50.42791824,-2.578369568,48.6022,7.063622474,7.071372442,-1.126875,-4.838812729,2.134475484,44.99999998 +134.28,50.42791887,-2.578368574,48.6138,7.063622492,7.07137236,-1.188125,-4.761848053,2.212822306,44.99999998 +134.29,50.42791951,-2.578367578,48.626,7.067098686,7.071594336,-1.248125,-4.683888837,2.289239463,44.99999998 +134.3,50.42792014,-2.578366583,48.6388,7.077527261,7.071150144,-1.3065625,-4.604951525,2.363660378,44.99999998 +134.31,50.42792078,-2.578365588,48.6521,7.084479662,7.070483896,-1.365,-4.525052503,2.436020135,44.99999998 +134.32,50.42792142,-2.578364593,48.6661,7.07752731,7.07026176,-1.423125,-4.444208502,2.506255651,44.99999998 +134.33,50.42792205,-2.578363598,48.6806,7.067098763,7.070483737,-1.4796875,-4.362436309,2.574305676,44.99999998 +134.34,50.42792269,-2.578362603,48.6957,7.063622586,7.071371884,-1.535,-4.279753171,2.640110853,44.99999998 +134.35,50.42792332,-2.578361608,48.7113,7.063622595,7.07226003,-1.59,-4.196176218,2.703613828,44.99999998 +134.36,50.42792396,-2.578360612,48.7275,7.067098797,7.071593785,-1.645,-4.111722927,2.764759254,44.99999998 +134.37,50.42792459,-2.578359617,48.7442,7.07752739,7.070261373,-1.6996875,-4.026411001,2.82349373,44.99999998 +134.38,50.42792523,-2.578358623,48.7615,7.0844798,7.070483353,-1.7534375,-3.940258202,2.879766035,44.99999998 +134.39,50.42792587,-2.578357627,48.7793,7.077527441,7.071371502,-1.8065625,-3.853282464,2.933527181,44.99999998 +134.4,50.4279265,-2.578356632,48.7976,7.067098885,7.071149372,-1.8596875,-3.765502121,2.984730299,44.99999998 +134.41,50.42792714,-2.578355637,48.8165,7.063622707,7.07048313,-1.9115625,-3.676935336,3.033330642,44.99999998 +134.42,50.42792777,-2.578354642,48.8359,7.063622725,7.070483058,-1.96125,-3.587600674,3.079285868,44.99999998 +134.43,50.42792841,-2.578353647,48.8557,7.067098945,7.071371209,-2.01,-3.497516811,3.122555869,44.99999998 +134.44,50.42792904,-2.578352652,48.8761,7.077527553,7.072481416,-2.0584375,-3.406702485,3.163103004,44.99999998 +134.45,50.42792968,-2.578351656,48.8969,7.084479964,7.072481344,-2.10625,-3.315176774,3.200891862,44.99999998 +134.46,50.42793032,-2.578350661,48.9182,7.077527605,7.071370994,-2.1534375,-3.222958702,3.2358895,44.99999998 +134.47,50.42793095,-2.578349666,48.94,7.067099057,7.070482699,-2.1996875,-3.130067575,3.268065434,44.99999998 +134.48,50.42793159,-2.578348671,48.9622,7.063622885,7.070260573,-2.245,-3.036522762,3.297391477,44.99999998 +134.49,50.42793222,-2.578347676,48.9849,7.063622895,7.070482559,-2.2896875,-2.942343798,3.323842245,44.99999998 +134.5,50.42793286,-2.578346681,49.008,7.063622915,7.071148658,-2.333125,-2.847550394,3.347394478,44.99999998 +134.51,50.42793349,-2.578345686,49.0316,7.063622953,7.071370645,-2.375,-2.752162261,3.368027777,44.99999998 +134.52,50.42793413,-2.57834469,49.0555,7.067099187,7.070482354,-2.41625,-2.65619945,3.385724094,44.99999998 +134.53,50.42793476,-2.578343696,49.0799,7.077527791,7.070260231,-2.4565625,-2.559681845,3.400468017,44.99999998 +134.54,50.4279354,-2.578342701,49.1047,7.084480189,7.071592499,-2.4946875,-2.462629727,3.412246711,44.99999998 +134.55,50.42793604,-2.578341705,49.1298,7.077527825,7.072258599,-2.5315625,-2.365063323,3.421049864,44.99999998 +134.56,50.42793667,-2.57834071,49.1553,7.067099287,7.071370309,-2.5684375,-2.267003028,3.426869797,44.99999998 +134.57,50.42793731,-2.578339715,49.1812,7.067099332,7.07048202,-2.6046875,-2.168469242,3.429701412,44.99999998 +134.58,50.42793794,-2.57833872,49.2074,7.077527947,7.070259898,-2.6396875,-2.069482647,3.429542302,44.99999998 +134.59,50.42793858,-2.578337725,49.234,7.084480356,7.070481888,-2.6734375,-1.970063812,3.426392581,44.99999998 +134.6,50.42793922,-2.57833673,49.2609,7.077527986,7.071147991,-2.70625,-1.870233594,3.420255,44.99999998 +134.61,50.42793985,-2.578335735,49.2881,7.067099427,7.071592038,-2.738125,-1.770012791,3.411134944,44.99999998 +134.62,50.42794049,-2.578334739,49.3157,7.063623272,7.071369918,-2.768125,-1.669422372,3.399040263,44.99999998 +134.63,50.42794112,-2.578333745,49.3435,7.063623319,7.071369854,-2.79625,-1.568483251,3.383981615,44.99999998 +134.64,50.42794176,-2.578332749,49.3716,7.063623353,7.071591847,-2.8234375,-1.467216628,3.365972061,44.99999998 +134.65,50.42794239,-2.578331754,49.4,7.063623372,7.071147672,-2.8496875,-1.365643587,3.34502736,44.99999998 +134.66,50.42794303,-2.578330759,49.4286,7.067099587,7.070481442,-2.8746875,-1.263785327,3.321165673,44.99999998 +134.67,50.42794366,-2.578329764,49.4575,7.077528205,7.070259322,-2.898125,-1.161663163,3.294407971,44.99999998 +134.68,50.4279443,-2.578328769,49.4866,7.08448064,7.070481315,-2.92,-1.059298409,3.264777459,44.99999998 +134.69,50.42794494,-2.578327774,49.5159,7.077528291,7.071369477,-2.9415625,-0.956712436,3.232299976,44.99999998 +134.7,50.42794557,-2.578326779,49.5454,7.067099741,7.072257639,-2.963125,-0.853926615,3.197003943,44.99999998 +134.71,50.42794621,-2.578325783,49.5752,7.06362358,7.071591409,-2.9828125,-0.750962547,3.158920011,44.99999998 +134.72,50.42794684,-2.578324788,49.6051,7.063623611,7.070259012,-2.9996875,-0.647841545,3.11808147,44.99999998 +134.73,50.42794748,-2.578323794,49.6352,7.067099832,7.070481007,-3.015,-0.544585326,3.074523958,44.99999998 +134.74,50.42794811,-2.578322798,49.6654,7.077528441,7.07136917,-3.03,-0.441215375,3.028285347,44.99999998 +134.75,50.42794875,-2.578321803,49.6958,7.084480867,7.071147052,-3.0446875,-0.337753234,2.979406089,44.99999998 +134.76,50.42794939,-2.578320808,49.7263,7.077528524,7.070480824,-3.0578125,-0.23422062,2.927928753,44.99999998 +134.77,50.42795002,-2.578319813,49.757,7.067099986,7.070258707,-3.0684375,-0.130639018,2.873898145,44.99999998 +134.78,50.42795066,-2.578318818,49.7877,7.063623823,7.070480702,-3.0778125,-0.027030201,2.817361535,44.99999998 +134.79,50.42795129,-2.578317823,49.8185,7.063623842,7.071368865,-3.086875,0.076584289,2.758368081,44.99999998 +134.8,50.42795193,-2.578316828,49.8495,7.067100064,7.072479084,-3.094375,0.180182793,2.696969294,44.99999998 +134.81,50.42795256,-2.578315832,49.8804,7.07752869,7.072479024,-3.0996875,0.283743654,2.633218744,44.99999998 +134.82,50.4279532,-2.578314837,49.9115,7.084481127,7.071368684,-3.1034375,0.387245271,2.567172008,44.99999998 +134.83,50.42795384,-2.578313842,49.9425,7.07752878,7.0704804,-3.10625,0.490665987,2.498886611,44.99999998 +134.84,50.42795447,-2.578312847,49.9736,7.067100222,7.070258284,-3.1084375,0.593984258,2.428422142,44.99999998 +134.85,50.42795511,-2.578311852,50.0047,7.063624047,7.070258224,-3.109375,0.697178483,2.355840077,44.99999998 +134.86,50.42795574,-2.578310857,50.0358,7.063624082,7.070258164,-3.1084375,0.80022712,2.281203673,44.99999998 +134.87,50.42795638,-2.578309862,50.0669,7.063624135,7.070480159,-3.10625,0.903108624,2.204578074,44.99999998 +134.88,50.42795701,-2.578308867,50.0979,7.063624183,7.071368322,-3.103125,1.005801512,2.126029972,44.99999998 +134.89,50.42795765,-2.578307872,50.129,7.067100407,7.072478542,-3.098125,1.10828441,2.045628007,44.99999998 +134.9,50.42795828,-2.578306876,50.1599,7.077529007,7.072478481,-3.09125,1.210535776,1.963442196,44.99999998 +134.91,50.42795892,-2.578305881,50.1908,7.084481418,7.071368141,-3.0834375,1.31253441,1.879544216,44.99999998 +134.92,50.42795956,-2.578304886,50.2216,7.077529073,7.070479857,-3.0746875,1.414258884,1.794007289,44.99999998 +134.93,50.42796019,-2.578303891,50.2523,7.067100543,7.070257741,-3.0646875,1.515688055,1.706905901,44.99999998 +134.94,50.42796083,-2.578302896,50.2829,7.063624388,7.070479736,-3.053125,1.616800668,1.618316141,44.99999998 +134.95,50.42796146,-2.578301901,50.3134,7.063624416,7.071145842,-3.04,1.717575636,1.528315128,44.99999998 +134.96,50.4279621,-2.578300906,50.3437,7.067100633,7.071589892,-3.02625,1.817991875,1.436981416,44.99999998 +134.97,50.42796273,-2.57829991,50.3739,7.077529237,7.071367776,-3.0115625,1.91802853,1.344394645,44.99999998 +134.98,50.42796337,-2.578298916,50.404,7.08448166,7.071367714,-2.9946875,2.017664573,1.250635545,44.99999998 +134.99,50.42796401,-2.57829792,50.4338,7.077529325,7.071589708,-2.9765625,2.116879263,1.15578582,44.99999998 +135,50.42796464,-2.578296925,50.4635,7.067100791,7.071145535,-2.958125,2.215651858,1.059928319,44.99999998 +135.01,50.42796528,-2.57829593,50.493,7.063624631,7.070479305,-2.9378125,2.313961733,0.963146465,44.99999998 +135.02,50.42796591,-2.578294935,50.5223,7.063624662,7.070257187,-2.915,2.411788375,0.86552477,44.99999998 +135.03,50.42796655,-2.57829394,50.5513,7.067100882,7.070479181,-2.8915625,2.509111387,0.767148318,44.99999998 +135.04,50.42796718,-2.578292945,50.5801,7.07752948,7.071367341,-2.868125,2.605910372,0.668102937,44.99999998 +135.05,50.42796782,-2.57829195,50.6087,7.084481893,7.072255501,-2.8428125,2.702165161,0.568474916,44.99999998 +135.06,50.42796846,-2.578290954,50.637,7.077529549,7.07158927,-2.815,2.797855588,0.468351172,44.99999998 +135.07,50.42796909,-2.578289959,50.665,7.067101013,7.070256871,-2.7865625,2.892961769,0.367819023,44.99999998 +135.08,50.42796973,-2.578288965,50.6927,7.063624849,7.070478864,-2.758125,2.987463766,0.266966132,44.99999998 +135.09,50.42797036,-2.578287969,50.7202,7.063624865,7.071367023,-2.728125,3.081341927,0.165880449,44.99999998 +135.1,50.427971,-2.578286974,50.7473,7.067101083,7.071144902,-2.69625,3.174576541,0.064650151,44.99999998 +135.11,50.42797163,-2.578285979,50.7741,7.077529705,7.070478669,-2.6634375,3.267148186,-0.036636583,44.99999998 +135.12,50.42797227,-2.578284984,50.8006,7.084482138,7.070256549,-2.6296875,3.359037496,-0.137891289,44.99999998 +135.13,50.42797291,-2.578283989,50.8267,7.077529787,7.070478539,-2.5946875,3.450225333,-0.239025845,44.99999998 +135.14,50.42797354,-2.578282994,50.8525,7.067101229,7.071366696,-2.558125,3.540692676,-0.339951903,44.99999998 +135.15,50.42797418,-2.578281999,50.8779,7.063625048,7.072476908,-2.52,3.63042056,-0.440581569,44.99999998 +135.16,50.42797481,-2.578281003,50.9029,7.063625064,7.072476841,-2.4815625,3.719390306,-0.54082701,44.99999998 +135.17,50.42797545,-2.578280008,50.9275,7.067101286,7.071366495,-2.443125,3.807583293,-0.640600849,44.99999998 +135.18,50.42797608,-2.578279013,50.9518,7.077529908,7.070478203,-2.403125,3.894981071,-0.739816054,44.99999998 +135.19,50.42797672,-2.578278018,50.9756,7.084482336,7.070256079,-2.36125,3.981565479,-0.838386109,44.99999998 +135.2,50.42797736,-2.578277023,50.999,7.077529973,7.07025601,-2.3184375,4.067318354,-0.936225127,44.99999998 +135.21,50.42797799,-2.578276028,51.022,7.067101402,7.070255941,-2.275,4.152221875,-1.033247737,44.99999998 +135.22,50.42797863,-2.578275033,51.0445,7.063625227,7.070477927,-2.23125,4.236258226,-1.129369314,44.99999998 +135.23,50.42797926,-2.578274038,51.0666,7.063625264,7.07136608,-2.1865625,4.319409871,-1.224506091,44.99999998 +135.24,50.4279799,-2.578273043,51.0883,7.063625304,7.072476289,-2.1396875,4.401659453,-1.318575104,44.99999998 +135.25,50.42798053,-2.578272047,51.1094,7.063625335,7.072476218,-2.091875,4.482989838,-1.411494248,44.99999998 +135.26,50.42798117,-2.578271052,51.1301,7.067101546,7.071365866,-2.045,4.56338401,-1.503182564,44.99999998 +135.27,50.4279818,-2.578270057,51.1503,7.077530135,7.070477571,-1.9978125,4.642825181,-1.593560067,44.99999998 +135.28,50.42798244,-2.578269062,51.1701,7.084482535,7.070255442,-1.9478125,4.721296736,-1.682548033,44.99999998 +135.29,50.42798308,-2.578268067,51.1893,7.077530176,7.070477425,-1.895,4.798782287,-1.770068711,44.99999998 +135.3,50.42798371,-2.578267072,51.208,7.067101631,7.071143518,-1.841875,4.875265736,-1.856045899,44.99999998 +135.31,50.42798435,-2.578266077,51.2261,7.063625462,7.071365499,-1.79,4.950730981,-1.940404595,44.99999998 +135.32,50.42798498,-2.578265081,51.2438,7.063625476,7.070477202,-1.738125,5.025162381,-2.023071175,44.99999998 +135.33,50.42798562,-2.578264087,51.2609,7.067101681,7.07025507,-1.6846875,5.098544352,-2.103973675,44.99999998 +135.34,50.42798625,-2.578263092,51.2775,7.077530278,7.071587328,-1.63,5.170861481,-2.183041449,44.99999998 +135.35,50.42798689,-2.578262096,51.2935,7.084482689,7.072253418,-1.5746875,5.242098813,-2.260205572,44.99999998 +135.36,50.42798753,-2.578261101,51.309,7.077530325,7.071365118,-1.5184375,5.312241395,-2.335398777,44.99999998 +135.37,50.42798816,-2.578260106,51.3239,7.067101762,7.070476816,-1.4615625,5.381274559,-2.40855546,44.99999998 +135.38,50.4279888,-2.578259111,51.3382,7.063625585,7.070254681,-1.405,5.449183923,-2.479611853,44.99999998 +135.39,50.42798943,-2.578258116,51.352,7.063625599,7.070476658,-1.348125,5.515955278,-2.548506017,44.99999998 +135.4,50.42799007,-2.578257121,51.3652,7.067101802,7.071364801,-1.2896875,5.581574702,-2.615177792,44.99999998 +135.41,50.4279907,-2.578256126,51.3778,7.077530394,7.072474999,-1.23,5.646028501,-2.679569138,44.99999998 +135.42,50.42799134,-2.57825513,51.3898,7.084482801,7.072474918,-1.17,5.709303209,-2.741623848,44.99999998 +135.43,50.42799198,-2.578254135,51.4012,7.077530435,7.071364557,-1.1096875,5.771385536,-2.801287834,44.99999998 +135.44,50.42799261,-2.57825314,51.412,7.067101872,7.070476252,-1.0484375,5.832262645,-2.858509014,44.99999998 +135.45,50.42799325,-2.578252145,51.4222,7.063625686,7.070476168,-0.986875,5.891921761,-2.913237599,44.99999998 +135.46,50.42799388,-2.57825115,51.4317,7.063625682,7.071142251,-0.9265625,5.950350393,-2.965425747,44.99999998 +135.47,50.42799452,-2.578250155,51.4407,7.063625686,7.071364222,-0.8665625,6.007536394,-3.015028021,44.99999998 +135.48,50.42799515,-2.578249159,51.4491,7.063625707,7.070475914,-0.804375,6.063467789,-3.062001106,44.99999998 +135.49,50.42799579,-2.578248165,51.4568,7.067101926,7.070253772,-0.7403125,6.11813289,-3.106304094,44.99999998 +135.5,50.42799642,-2.57824717,51.4639,7.077530521,7.07158602,-0.676875,6.171520352,-3.147898366,44.99999998 +135.51,50.42799706,-2.578246174,51.4703,7.084482904,7.072252099,-0.615,6.223618889,-3.186747597,44.99999998 +135.52,50.4279977,-2.578245179,51.4762,7.077530505,7.071363788,-0.553125,6.274417785,-3.222817983,44.99999998 +135.53,50.42799833,-2.578244184,51.4814,7.06710193,7.070475476,-0.4896875,6.323906327,-3.256077954,44.99999998 +135.54,50.42799897,-2.578243189,51.486,7.063625759,7.070253331,-0.425,6.372074144,-3.286498633,44.99999998 +135.55,50.4279996,-2.578242194,51.4899,7.063625777,7.070475297,-0.36,6.418911324,-3.314053433,44.99999998 +135.56,50.42800024,-2.578241199,51.4932,7.067101972,7.071141373,-0.2953125,6.464407897,-3.338718292,44.99999998 +135.57,50.42800087,-2.578240204,51.4958,7.077530542,7.071585392,-0.2315625,6.508554525,-3.360471781,44.99999998 +135.58,50.42800151,-2.578239208,51.4978,7.084482922,7.071363243,-0.168125,6.551341924,-3.379294877,44.99999998 +135.59,50.42800215,-2.578238214,51.4992,7.077530543,7.07136315,-0.1034375,6.592761158,-3.395171136,44.99999998 +135.6,50.42800278,-2.578237218,51.4999,7.067101978,7.071585112,-0.0384375,6.632803574,-3.408086808,44.99999998 +135.61,50.42800342,-2.578236223,51.4999,7.063625789,7.071140906,0.025,6.671460807,-3.418030548,44.99999998 +135.62,50.42800405,-2.578235228,51.4994,7.063625785,7.070474645,0.0884375,6.708724779,-3.424993704,44.99999998 +135.63,50.42800469,-2.578234233,51.4982,7.067101976,7.070252493,0.15375,6.744587754,-3.428970261,44.99999998 +135.64,50.42800532,-2.578233238,51.4963,7.077530555,7.070474452,0.2196875,6.77904217,-3.429956665,44.99999998 +135.65,50.42800596,-2.578232243,51.4938,7.084482934,7.071362577,0.2846875,6.812080922,-3.427952115,44.99999998 +135.66,50.4280066,-2.578231248,51.4906,7.077530539,7.072250701,0.3484375,6.84369702,-3.422958329,44.99999998 +135.67,50.42800723,-2.578230252,51.4868,7.067101958,7.071584435,0.4115625,6.873883874,-3.414979663,44.99999998 +135.68,50.42800787,-2.578229257,51.4824,7.063625768,7.070252002,0.475,6.90263524,-3.404023105,44.99999998 +135.69,50.4280085,-2.578228263,51.4773,7.06362577,7.070473957,0.5384375,6.929945101,-3.390098168,44.99999998 +135.7,50.42800914,-2.578227267,51.4716,7.067101954,7.071362079,0.6015625,6.955807671,-3.373217055,44.99999998 +135.71,50.42800977,-2.578226272,51.4653,7.077530515,7.071139922,0.665,6.980217679,-3.353394434,44.99999998 +135.72,50.42801041,-2.578225277,51.4583,7.084482889,7.070473653,0.728125,7.00316991,-3.330647552,44.99999998 +135.73,50.42801105,-2.578224282,51.4507,7.077530505,7.070251493,0.79,7.024659608,-3.304996346,44.99999998 +135.74,50.42801168,-2.578223287,51.4425,7.067101929,7.070473445,0.8515625,7.044682363,-3.276463105,44.99999998 +135.75,50.42801232,-2.578222292,51.4337,7.063625731,7.071361564,0.9134375,7.063233877,-3.245072753,44.99999998 +135.76,50.42801295,-2.578221297,51.4242,7.063625708,7.072471737,0.975,7.080310312,-3.210852676,44.99999998 +135.77,50.42801359,-2.578220301,51.4142,7.067101874,7.072471631,1.0365625,7.095908171,-3.17383267,44.99999998 +135.78,50.42801422,-2.578219306,51.4035,7.077530445,7.071361246,1.098125,7.110024075,-3.134045048,44.99999998 +135.79,50.42801486,-2.578218311,51.3922,7.084482839,7.070472916,1.158125,7.122655159,-3.091524475,44.99999998 +135.8,50.4280155,-2.578217316,51.3803,7.077530452,7.070250752,1.2165625,7.133798787,-3.046308021,44.99999998 +135.81,50.42801613,-2.578216321,51.3679,7.067101852,7.070250644,1.275,7.14345261,-2.998435163,44.99999998 +135.82,50.42801677,-2.578215326,51.3548,7.063625629,7.070250536,1.3334375,7.151614623,-2.947947612,44.99999998 +135.83,50.4280174,-2.578214331,51.3412,7.063625603,7.070472482,1.3915625,7.158283107,-2.894889428,44.99999998 +135.84,50.42801804,-2.578213336,51.327,7.063625595,7.071360594,1.45,7.163456629,-2.83930685,44.99999998 +135.85,50.42801867,-2.578212341,51.3122,7.063625595,7.07247076,1.5078125,7.167134216,-2.781248349,44.99999998 +135.86,50.42801931,-2.578211345,51.2968,7.067101777,7.072470649,1.563125,7.169315008,-2.720764575,44.99999998 +135.87,50.42801994,-2.57821035,51.2809,7.077530336,7.071360259,1.616875,7.169998604,-2.65790824,44.99999998 +135.88,50.42802058,-2.578209355,51.2645,7.084482695,7.070471923,1.6715625,7.169184775,-2.592734176,44.99999998 +135.89,50.42802122,-2.57820836,51.2475,7.077530278,7.070249754,1.7265625,7.166873807,-2.525299221,44.99999998 +135.9,50.42802185,-2.578207365,51.2299,7.06710168,7.070471696,1.7796875,7.163066158,-2.45566216,44.99999998 +135.91,50.42802249,-2.57820637,51.2119,7.063625484,7.071137748,1.8315625,7.157762517,-2.383883669,44.99999998 +135.92,50.42802312,-2.578205375,51.1933,7.063625477,7.071359688,1.8834375,7.150964144,-2.310026487,44.99999998 +135.93,50.42802376,-2.578204379,51.1742,7.067101647,7.07047135,1.9346875,7.142672356,-2.234154842,44.99999998 +135.94,50.42802439,-2.578203385,51.1546,7.077530192,7.070249179,1.985,7.132888872,-2.156335027,44.99999998 +135.95,50.42802503,-2.57820239,51.1345,7.084482548,7.071581395,2.0346875,7.121615813,-2.076634879,44.99999998 +135.96,50.42802567,-2.578201394,51.1139,7.077530144,7.072247444,2.083125,7.108855527,-1.99512384,44.99999998 +135.97,50.4280263,-2.578200399,51.0928,7.067101555,7.071359104,2.13,7.094610593,-1.911873015,44.99999998 +135.98,50.42802694,-2.578199404,51.0713,7.063625345,7.070470763,2.1765625,7.078884048,-1.826955055,44.99999998 +135.99,50.42802757,-2.578198409,51.0493,7.063625321,7.070248588,2.223125,7.061679214,-1.740443929,44.99999998 +136,50.42802821,-2.578197414,51.0268,7.067101484,7.070470524,2.2678125,7.042999586,-1.652415094,44.99999998 +136.01,50.42802884,-2.578196419,51.0039,7.077530026,7.071358626,2.31,7.022849119,-1.562945328,44.99999998 +136.02,50.42802948,-2.578195424,50.9806,7.084482382,7.072468784,2.351875,7.001232052,-1.472112724,44.99999998 +136.03,50.42803012,-2.578194428,50.9569,7.07752998,7.072468663,2.3946875,6.978152853,-1.379996352,44.99999998 +136.04,50.42803075,-2.578193433,50.9327,7.067101388,7.071358264,2.43625,6.953616337,-1.286676596,44.99999998 +136.05,50.42803139,-2.578192438,50.9081,7.063625174,7.07046992,2.4746875,6.927627716,-1.192234874,44.99999998 +136.06,50.42803202,-2.578191443,50.8832,7.06362514,7.070469798,2.511875,6.900192262,-1.096753462,44.99999998 +136.07,50.42803266,-2.578190448,50.8579,7.067101291,7.071135842,2.55,6.87131582,-1.00031567,44.99999998 +136.08,50.42803329,-2.578189453,50.8322,7.077529832,7.071357774,2.5878125,6.841004404,-0.903005607,44.99999998 +136.09,50.42803393,-2.578188457,50.8061,7.084482191,7.070469428,2.623125,6.809264376,-0.804908127,44.99999998 +136.1,50.42803457,-2.578187463,50.7797,7.077529789,7.070247248,2.65625,6.776102266,-0.706108775,44.99999998 +136.11,50.4280352,-2.578186468,50.753,7.067101192,7.071579457,2.6884375,6.741525066,-0.606693607,44.99999998 +136.12,50.42803584,-2.578185472,50.7259,7.063624966,7.0722455,2.72,6.705539936,-0.506749428,44.99999998 +136.13,50.42803647,-2.578184477,50.6986,7.063624921,7.071357153,2.75125,6.668154497,-0.406363383,44.99999998 +136.14,50.42803711,-2.578183482,50.6709,7.067101078,7.070468806,2.7815625,6.629376484,-0.305622964,44.99999998 +136.15,50.42803774,-2.578182487,50.6429,7.07752964,7.070246625,2.8096875,6.589214033,-0.204616063,44.99999998 +136.16,50.42803838,-2.578181492,50.6147,7.084482013,7.070468554,2.8365625,6.547675453,-0.103430685,44.99999998 +136.17,50.42803902,-2.578180497,50.5862,7.077529601,7.071134595,2.863125,6.504769508,-0.002155123,44.99999998 +136.18,50.42803965,-2.578179502,50.5574,7.067100982,7.071578579,2.8878125,6.460505138,0.099122272,44.99999998 +136.19,50.42804029,-2.578178506,50.5284,7.063624742,7.071356397,2.9096875,6.414891567,0.200313264,44.99999998 +136.2,50.42804092,-2.578177512,50.4992,7.063624699,7.071356269,2.9303125,6.367938363,0.30132962,44.99999998 +136.21,50.42804156,-2.578176516,50.4698,7.063624674,7.071578198,2.9515625,6.31965521,0.402083159,44.99999998 +136.22,50.42804219,-2.578175521,50.4402,7.063624658,7.071133959,2.9728125,6.270052363,0.502486106,44.99999998 +136.23,50.42804283,-2.578174526,50.4103,7.067100821,7.070467666,2.99125,6.21914002,0.602450855,44.99999998 +136.24,50.42804346,-2.578173531,50.3803,7.077529356,7.070245482,3.0065625,6.166928955,0.701890259,44.99999998 +136.25,50.4280441,-2.578172536,50.3502,7.084481699,7.07046741,3.021875,6.113429995,0.800717571,44.99999998 +136.26,50.42804474,-2.578171541,50.3199,7.077529286,7.071355503,3.038125,6.058654313,0.898846735,44.99999998 +136.27,50.42804537,-2.578170546,50.2894,7.067100688,7.072243597,3.0528125,6.002613311,0.996192035,44.99999998 +136.28,50.42804601,-2.57816955,50.2588,7.063624466,7.071577302,3.064375,5.945318792,1.092668617,44.99999998 +136.29,50.42804664,-2.578168555,50.2281,7.063624428,7.070244841,3.0734375,5.886782673,1.188192427,44.99999998 +136.3,50.42804728,-2.578167561,50.1973,7.067100586,7.070466768,3.0815625,5.827017159,1.2826801,44.99999998 +136.31,50.42804791,-2.578166565,50.1665,7.077529131,7.07135486,3.0896875,5.76603474,1.376049245,44.99999998 +136.32,50.42804855,-2.57816557,50.1355,7.084481477,7.071132676,3.0965625,5.703848193,1.468218445,44.99999998 +136.33,50.42804919,-2.578164575,50.1045,7.077529052,7.070466381,3.10125,5.640470409,1.55910737,44.99999998 +136.34,50.42804982,-2.57816358,50.0735,7.067100443,7.070244197,3.105,5.575914739,1.648636667,44.99999998 +136.35,50.42805046,-2.578162585,50.0424,7.063624225,7.070466123,3.108125,5.510194589,1.736728412,44.99999998 +136.36,50.42805109,-2.57816159,50.0113,7.063624198,7.071354215,3.1096875,5.44332371,1.823305658,44.99999998 +136.37,50.42805173,-2.578160595,49.9802,7.067100353,7.072464364,3.1096875,5.375316084,1.908292946,44.99999998 +136.38,50.42805236,-2.578159599,49.9491,7.077528884,7.072464235,3.108125,5.306185861,1.991616193,44.99999998 +136.39,50.428053,-2.578158604,49.918,7.08448123,7.071353828,3.1046875,5.235947538,2.07320269,44.99999998 +136.4,50.42805364,-2.578157609,49.887,7.077528821,7.070465477,3.1,5.164615725,2.152981391,44.99999998 +136.41,50.42805427,-2.578156614,49.856,7.067100223,7.070243293,3.0946875,5.092205319,2.230882623,44.99999998 +136.42,50.42805491,-2.578155619,49.8251,7.063624,7.07046522,3.088125,5.01873156,2.306838435,44.99999998 +136.43,50.42805554,-2.578154624,49.7942,7.063623954,7.071131257,3.0796875,4.944209633,2.380782706,44.99999998 +136.44,50.42805618,-2.578153629,49.7635,7.063623903,7.071575239,3.0696875,4.868655178,2.452650923,44.99999998 +136.45,50.42805681,-2.578152633,49.7328,7.06362387,7.071353055,3.0584375,4.79208401,2.522380345,44.99999998 +136.46,50.42805745,-2.578151639,49.7023,7.067100047,7.071352927,3.04625,4.714511999,2.589910239,44.99999998 +136.47,50.42805808,-2.578150643,49.6719,7.077528607,7.071574854,3.0334375,4.635955474,2.655181706,44.99999998 +136.48,50.42805872,-2.578149648,49.6416,7.084480956,7.071130616,3.0196875,4.556430823,2.718137792,44.99999998 +136.49,50.42805936,-2.578148653,49.6115,7.077528522,7.070464322,3.004375,4.475954546,2.77872361,44.99999998 +136.5,50.42805999,-2.578147658,49.5815,7.067099899,7.070242138,2.9865625,4.394543603,2.836886389,44.99999998 +136.51,50.42806063,-2.578146663,49.5517,7.06362368,7.070464065,2.9665625,4.312214839,2.892575309,44.99999998 +136.52,50.42806126,-2.578145668,49.5222,7.063623664,7.071352159,2.9465625,4.228985558,2.945741896,44.99999998 +136.53,50.4280619,-2.578144673,49.4928,7.067099829,7.072240254,2.9265625,4.144873119,2.996339742,44.99999998 +136.54,50.42806253,-2.578143677,49.4636,7.07752837,7.071573961,2.904375,4.059895055,3.044324728,44.99999998 +136.55,50.42806317,-2.578142682,49.4347,7.084480716,7.070241502,2.88,3.974069129,3.089654971,44.99999998 +136.56,50.42806381,-2.578141688,49.406,7.077528295,7.070463431,2.855,3.887413273,3.132291053,44.99999998 +136.57,50.42806444,-2.578140692,49.3776,7.067099689,7.071351527,2.8296875,3.799945593,3.17219573,44.99999998 +136.58,50.42806508,-2.578139697,49.3494,7.063623473,7.071129345,2.8028125,3.711684367,3.209334166,44.99999998 +136.59,50.42806571,-2.578138702,49.3215,7.063623445,7.070463054,2.773125,3.622647986,3.243674048,44.99999998 +136.6,50.42806635,-2.578137707,49.2939,7.06709961,7.070462929,2.741875,3.532855015,3.275185409,44.99999998 +136.61,50.42806698,-2.578136712,49.2667,7.077528164,7.071351025,2.7115625,3.442324302,3.30384069,44.99999998 +136.62,50.42806762,-2.578135717,49.2397,7.084480516,7.072461177,2.68125,3.3510747,3.329615024,44.99999998 +136.63,50.42806826,-2.578134721,49.213,7.077528086,7.072461052,2.6478125,3.259125287,3.352485895,44.99999998 +136.64,50.42806889,-2.578133726,49.1867,7.067099472,7.071350652,2.6115625,3.166495201,3.372433364,44.99999998 +136.65,50.42806953,-2.578132731,49.1608,7.063623262,7.070462308,2.5753125,3.073203863,3.389439954,44.99999998 +136.66,50.42807016,-2.578131736,49.1352,7.063623248,7.07024013,2.5396875,2.979270699,3.403490942,44.99999998 +136.67,50.4280708,-2.578130741,49.11,7.067099411,7.070462062,2.503125,2.884715359,3.414574066,44.99999998 +136.68,50.42807143,-2.578129746,49.0851,7.077527948,7.071128106,2.4646875,2.789557612,3.422679585,44.99999998 +136.69,50.42807207,-2.578128751,49.0607,7.084480301,7.071350039,2.4246875,2.693817281,3.42780051,44.99999998 +136.7,50.42807271,-2.578127755,49.0366,7.0775279,7.070461697,2.3834375,2.597514363,3.429932314,44.99999998 +136.71,50.42807334,-2.578126761,49.013,7.067099312,7.070239522,2.34125,2.500669026,3.429073164,44.99999998 +136.72,50.42807398,-2.578125766,48.9898,7.0636231,7.071571733,2.2984375,2.403301437,3.425223804,44.99999998 +136.73,50.42807461,-2.57812477,48.967,7.063623069,7.072237779,2.2546875,2.305431938,3.418387616,44.99999998 +136.74,50.42807525,-2.578123775,48.9447,7.067099223,7.071349438,2.2096875,2.207080982,3.408570557,44.99999998 +136.75,50.42807588,-2.57812278,48.9228,7.077527767,7.070461098,2.1634375,2.108269139,3.395781165,44.99999998 +136.76,50.42807652,-2.578121785,48.9014,7.084480136,7.070238925,2.1165625,2.009016978,3.380030555,44.99999998 +136.77,50.42807716,-2.57812079,48.8805,7.077527743,7.070460862,2.0696875,1.90934524,3.361332593,44.99999998 +136.78,50.42807779,-2.578119795,48.86,7.067099147,7.071348965,2.0215625,1.809274838,3.339703436,44.99999998 +136.79,50.42807843,-2.5781188,48.84,7.063622927,7.072459125,1.97125,1.708826513,3.315161992,44.99999998 +136.8,50.42807906,-2.578117804,48.8206,7.063622897,7.072459009,1.9203125,1.60802135,3.287729747,44.99999998 +136.81,50.4280797,-2.578116809,48.8016,7.063622872,7.071348618,1.87,1.506880376,3.257430478,44.99999998 +136.82,50.42808033,-2.578115814,48.7832,7.063622857,7.070460281,1.819375,1.405424734,3.224290771,44.99999998 +136.83,50.42808097,-2.578114819,48.7652,7.067099037,7.070238111,1.7665625,1.303675508,3.188339388,44.99999998 +136.84,50.4280816,-2.578113824,48.7478,7.077527599,7.070237998,1.7115625,1.201654128,3.149607671,44.99999998 +136.85,50.42808224,-2.578112829,48.731,7.084479964,7.070237885,1.656875,1.099381734,3.108129537,44.99999998 +136.86,50.42808288,-2.578111834,48.7147,7.077527553,7.070459827,1.603125,0.996879757,3.063941027,44.99999998 +136.87,50.42808351,-2.578110839,48.6989,7.067098949,7.071347935,1.548125,0.894169566,3.017080699,44.99999998 +136.88,50.42808415,-2.578109844,48.6837,7.063622747,7.0724581,1.49125,0.791272706,2.967589464,44.99999998 +136.89,50.42808478,-2.578108848,48.6691,7.063622747,7.072457989,1.4334375,0.688210547,2.915510408,44.99999998 +136.9,50.42808542,-2.578107853,48.655,7.06709893,7.071347603,1.375,0.585004691,2.860889024,44.99999998 +136.91,50.42808605,-2.578106858,48.6416,7.077527487,7.070459273,1.316875,0.481676623,2.803772867,44.99999998 +136.92,50.42808669,-2.578105863,48.6287,7.08447985,7.070237109,1.26,0.378248001,2.744211841,44.99999998 +136.93,50.42808733,-2.578104868,48.6164,7.077527447,7.070459056,1.2028125,0.274740425,2.682257743,44.99999998 +136.94,50.42808796,-2.578103873,48.6046,7.067098861,7.071125113,1.143125,0.171175381,2.617964716,44.99999998 +136.95,50.4280886,-2.578102878,48.5935,7.063622666,7.071347062,1.0815625,0.067574642,2.551388797,44.99999998 +136.96,50.42808923,-2.578101882,48.583,7.063622664,7.070458735,1.02,-0.036040191,2.482588025,44.99999998 +136.97,50.42808987,-2.578100888,48.5731,7.067098849,7.070236574,0.9584375,-0.139647519,2.411622389,44.99999998 +136.98,50.4280905,-2.578099893,48.5638,7.077527404,7.0715688,0.8965625,-0.243225683,2.338553769,44.99999998 +136.99,50.42809114,-2.578098897,48.5552,7.084479762,7.072234861,0.835,-0.346753084,2.263445877,44.99999998 +137,50.42809178,-2.578097902,48.5471,7.077527369,7.071346536,0.7734375,-0.450208005,2.186364261,44.99999998 +137.01,50.42809241,-2.578096907,48.5397,7.067098801,7.070458213,0.71125,-0.553568961,2.107376127,44.99999998 +137.02,50.42809305,-2.578095912,48.5329,7.063622615,7.070236056,0.6484375,-0.656814294,2.026550289,44.99999998 +137.03,50.42809368,-2.578094917,48.5267,7.063622605,7.07045801,0.5846875,-0.759922461,1.943957277,44.99999998 +137.04,50.42809432,-2.578093922,48.5212,7.067098777,7.071124075,0.5203125,-0.862871918,1.859669112,44.99999998 +137.05,50.42809495,-2.578092927,48.5163,7.077527336,7.071568085,0.4565625,-0.965641181,1.773759304,44.99999998 +137.06,50.42809559,-2.578091931,48.5121,7.084479718,7.07134593,0.3934375,-1.068208762,1.68630274,44.99999998 +137.07,50.42809623,-2.578090937,48.5084,7.077527343,7.071345832,0.3296875,-1.170553291,1.59737568,44.99999998 +137.08,50.42809686,-2.578089941,48.5055,7.067098778,7.071567789,0.265,-1.272653396,1.507055701,44.99999998 +137.09,50.4280975,-2.578088946,48.5031,7.06362259,7.071345636,0.2003125,-1.374487649,1.41542153,44.99999998 +137.1,50.42809813,-2.578087951,48.5015,7.063622582,7.071345539,0.1365625,-1.476034907,1.322553093,44.99999998 +137.11,50.42809877,-2.578086956,48.5004,7.063622566,7.071345444,0.0734375,-1.577273914,1.228531349,44.99999998 +137.12,50.4280994,-2.57808596,48.5,7.063622556,7.070457129,0.009375,-1.67818347,1.133438346,44.99999998 +137.13,50.42810004,-2.578084966,48.5002,7.067098756,7.070234979,-0.05625,-1.778742605,1.03735699,44.99999998 +137.14,50.42810067,-2.578083971,48.5011,7.077527351,7.071567216,-0.121875,-1.878930291,0.940370992,44.99999998 +137.15,50.42810131,-2.578082975,48.5027,7.084479741,7.072233288,-0.18625,-1.978725559,0.842564976,44.99999998 +137.16,50.42810195,-2.57808198,48.5048,7.077527345,7.071344975,-0.25,-2.07810761,0.744024257,44.99999998 +137.17,50.42810258,-2.578080985,48.5077,7.067098761,7.070456663,-0.31375,-2.177055645,0.64483472,44.99999998 +137.18,50.42810322,-2.57807999,48.5111,7.063622579,7.070234518,-0.3778125,-2.275549095,0.545082883,44.99999998 +137.19,50.42810385,-2.578078995,48.5152,7.0636226,7.070456483,-0.4421875,-2.373567277,0.444855777,44.99999998 +137.2,50.42810449,-2.578078,48.52,7.067098803,7.071122559,-0.50625,-2.471089736,0.344240664,44.99999998 +137.21,50.42810512,-2.578077005,48.5253,7.077527383,7.07156658,-0.57,-2.568096189,0.243325435,44.99999998 +137.22,50.42810576,-2.578076009,48.5314,7.084479774,7.071344436,-0.6334375,-2.664566353,0.142197983,44.99999998 +137.23,50.4281064,-2.578075015,48.538,7.077527394,7.071344349,-0.69625,-2.760480004,0.040946543,44.99999998 +137.24,50.42810703,-2.578074019,48.5453,7.067098819,7.071566318,-0.7584375,-2.855817201,-0.060340592,44.99999998 +137.25,50.42810767,-2.578073024,48.5532,7.063622631,7.071122122,-0.82,-2.95055795,-0.16157513,44.99999998 +137.26,50.4281083,-2.578072029,48.5617,7.063622646,7.070455872,-0.8815625,-3.04468254,-0.262668777,44.99999998 +137.27,50.42810894,-2.578071034,48.5708,7.067098858,7.070233732,-0.9434375,-3.138171261,-0.363533356,44.99999998 +137.28,50.42810957,-2.578070039,48.5806,7.077527454,7.070455703,-1.005,-3.231004691,-0.464080917,44.99999998 +137.29,50.42811021,-2.578069044,48.5909,7.084479848,7.07134384,-1.06625,-3.32316329,-0.564223798,44.99999998 +137.3,50.42811085,-2.578068049,48.6019,7.07752746,7.072231977,-1.126875,-3.414627924,-0.663874681,44.99999998 +137.31,50.42811148,-2.578067053,48.6135,7.067098889,7.071565731,-1.18625,-3.505379454,-0.762946647,44.99999998 +137.32,50.42811212,-2.578066058,48.6256,7.063622721,7.070233319,-1.245,-3.595398916,-0.861353294,44.99999998 +137.33,50.42811275,-2.578065064,48.6384,7.063622752,7.070455293,-1.3034375,-3.684667516,-0.959008851,44.99999998 +137.34,50.42811339,-2.578064068,48.6517,7.067098964,7.071343434,-1.3615625,-3.773166635,-1.055828176,44.99999998 +137.35,50.42811402,-2.578063073,48.6656,7.077527545,7.0711213,-1.42,-3.860877821,-1.151726757,44.99999998 +137.36,50.42811466,-2.578062078,48.6801,7.08447993,7.070455056,-1.478125,-3.947782627,-1.246621001,44.99999998 +137.37,50.4281153,-2.578061083,48.6952,7.077527562,7.070232922,-1.5346875,-4.033863062,-1.340428173,44.99999998 +137.38,50.42811593,-2.578060088,48.7108,7.06709902,7.070454901,-1.59,-4.119101019,-1.43306651,44.99999998 +137.39,50.42811657,-2.578059093,48.727,7.063622859,7.071343044,-1.645,-4.203478794,-1.524455169,44.99999998 +137.4,50.4281172,-2.578058098,48.7437,7.063622874,7.072453243,-1.6996875,-4.286978741,-1.614514509,44.99999998 +137.41,50.42811784,-2.578057102,48.761,7.063622878,7.072453167,-1.753125,-4.369583385,-1.703165919,44.99999998 +137.42,50.42811847,-2.578056107,48.7788,7.063622888,7.071342817,-1.805,-4.451275478,-1.790332166,44.99999998 +137.43,50.42811911,-2.578055112,48.7971,7.067099108,7.070454523,-1.8565625,-4.532038004,-1.875937217,44.99999998 +137.44,50.42811974,-2.578054117,48.8159,7.077527724,7.070232394,-1.9084375,-4.611854062,-1.959906417,44.99999998 +137.45,50.42812038,-2.578053122,48.8353,7.084480136,7.070454375,-1.9596875,-4.690706977,-2.042166597,44.99999998 +137.46,50.42812102,-2.578052127,48.8551,7.077527766,7.071120468,-2.0096875,-4.768580307,-2.122645911,44.99999998 +137.47,50.42812165,-2.578051132,48.8755,7.067099203,7.071564506,-2.058125,-4.845457836,-2.201274284,44.99999998 +137.48,50.42812229,-2.578050136,48.8963,7.063623029,7.07134238,-2.105,-4.921323349,-2.277983077,44.99999998 +137.49,50.42812292,-2.578049142,48.9176,7.063623058,7.071342308,-2.1515625,-4.996161206,-2.352705483,44.99999998 +137.5,50.42812356,-2.578048146,48.9393,7.067099282,7.071564293,-2.198125,-5.069955649,-2.425376241,44.99999998 +137.51,50.42812419,-2.578047151,48.9616,7.077527889,7.071120112,-2.2434375,-5.142691266,-2.495932097,44.99999998 +137.52,50.42812483,-2.578046156,48.9842,7.084480302,7.070453877,-2.2878125,-5.214352931,-2.564311401,44.99999998 +137.53,50.42812547,-2.578045161,49.0073,7.077527948,7.070231753,-2.331875,-5.284925632,-2.630454623,44.99999998 +137.54,50.4281261,-2.578044166,49.0309,7.067099391,7.07045374,-2.374375,-5.354394587,-2.694304066,44.99999998 +137.55,50.42812674,-2.578043171,49.0548,7.06362321,7.071341892,-2.4146875,-5.422745416,-2.755803981,44.99999998 +137.56,50.42812737,-2.578042176,49.0792,7.063623231,7.072230044,-2.4534375,-5.489963793,-2.814900853,44.99999998 +137.57,50.42812801,-2.57804118,49.1039,7.067099464,7.071563812,-2.4915625,-5.556035624,-2.871543059,44.99999998 +137.58,50.42812864,-2.578040185,49.129,7.077528084,7.070231415,-2.53,-5.620947101,-2.925681269,44.99999998 +137.59,50.42812928,-2.578039191,49.1545,7.084480497,7.070453403,-2.568125,-5.684684817,-2.977268211,44.99999998 +137.6,50.42812992,-2.578038195,49.1804,7.077528125,7.071341557,-2.6046875,-5.747235307,-3.02625891,44.99999998 +137.61,50.42813055,-2.5780372,49.2066,7.067099569,7.071119436,-2.6396875,-5.808585508,-3.07261068,44.99999998 +137.62,50.42813119,-2.578036205,49.2332,7.063623418,7.070453206,-2.673125,-5.868722757,-3.116283128,44.99999998 +137.63,50.42813182,-2.57803521,49.2601,7.063623464,7.070453141,-2.7046875,-5.927634335,-3.157238093,44.99999998 +137.64,50.42813246,-2.578034215,49.2873,7.067099695,7.071341297,-2.735,-5.985308037,-3.195439883,44.99999998 +137.65,50.42813309,-2.57803322,49.3148,7.077528298,7.072451507,-2.765,-6.041731775,-3.230855206,44.99999998 +137.66,50.42813373,-2.578032224,49.3426,7.084480701,7.072451444,-2.7946875,-6.096893745,-3.263453239,44.99999998 +137.67,50.42813437,-2.578031229,49.3707,7.077528335,7.071341105,-2.823125,-6.150782489,-3.293205447,44.99999998 +137.68,50.428135,-2.578030234,49.3991,7.067099795,7.070452822,-2.8496875,-6.203386718,-3.320085934,44.99999998 +137.69,50.42813564,-2.578029239,49.4277,7.06362365,7.070230704,-2.8746875,-6.254695432,-3.344071208,44.99999998 +137.7,50.42813627,-2.578028244,49.4566,7.063623685,7.070452696,-2.898125,-6.304697917,-3.36514047,44.99999998 +137.71,50.42813691,-2.578027249,49.4857,7.067099898,7.071340854,-2.92,-6.353383803,-3.383275272,44.99999998 +137.72,50.42813754,-2.578026254,49.515,7.077528499,7.072229011,-2.9415625,-6.400742832,-3.3984598,44.99999998 +137.73,50.42813818,-2.578025258,49.5445,7.084480926,7.071562784,-2.963125,-6.446765152,-3.410680818,44.99999998 +137.74,50.42813882,-2.578024263,49.5743,7.077528589,7.070230392,-2.9828125,-6.491441135,-3.419927669,44.99999998 +137.75,50.42813945,-2.578023269,49.6042,7.067100048,7.070452385,-2.9996875,-6.5347615,-3.426192275,44.99999998 +137.76,50.42814009,-2.578022273,49.6343,7.063623884,7.071340544,-3.015,-6.576717136,-3.429469192,44.99999998 +137.77,50.42814072,-2.578021278,49.6645,7.063623916,7.071118429,-3.0296875,-6.617299336,-3.429755614,44.99999998 +137.78,50.42814136,-2.578020283,49.6949,7.063623948,7.070452203,-3.0434375,-6.656499561,-3.427051196,44.99999998 +137.79,50.42814199,-2.578019288,49.7254,7.063623976,7.070230087,-3.05625,-6.694309676,-3.421358344,44.99999998 +137.8,50.42814263,-2.578018293,49.756,7.0671002,7.070452081,-3.068125,-6.730721774,-3.412681987,44.99999998 +137.81,50.42814326,-2.578017298,49.7868,7.077528819,7.07134024,-3.078125,-6.765728235,-3.401029745,44.99999998 +137.82,50.4281439,-2.578016303,49.8176,7.084481247,7.072450454,-3.08625,-6.799321782,-3.386411758,44.99999998 +137.83,50.42814454,-2.578015307,49.8485,7.077528896,7.072450393,-3.0934375,-6.831495368,-3.368840746,44.99999998 +137.84,50.42814517,-2.578014312,49.8795,7.067100344,7.071340058,-3.0996875,-6.862242231,-3.348332123,44.99999998 +137.85,50.42814581,-2.578013317,49.9105,7.063624182,7.070451778,-3.1046875,-6.89155607,-3.32490365,44.99999998 +137.86,50.42814644,-2.578012322,49.9416,7.063624221,7.070229663,-3.108125,-6.919430695,-3.298575838,44.99999998 +137.87,50.42814708,-2.578011327,49.9727,7.067100457,7.070451658,-3.1096875,-6.945860265,-3.269371549,44.99999998 +137.88,50.42814771,-2.578010332,50.0038,7.077529074,7.071117763,-3.1096875,-6.970839276,-3.237316394,44.99999998 +137.89,50.42814835,-2.578009337,50.0349,7.084481497,7.071561812,-3.108125,-6.994362517,-3.202438218,44.99999998 +137.9,50.42814899,-2.578008341,50.066,7.077529143,7.071339697,-3.105,-7.016425059,-3.164767504,44.99999998 +137.91,50.42814962,-2.578007347,50.097,7.067100591,7.071339636,-3.1015625,-7.037022376,-3.124337023,44.99999998 +137.92,50.42815026,-2.578006351,50.128,7.06362443,7.071561631,-3.098125,-7.056150056,-3.081182129,44.99999998 +137.93,50.42815089,-2.578005356,50.159,7.063624476,7.071117461,-3.0928125,-7.073804147,-3.035340349,44.99999998 +137.94,50.42815153,-2.578004361,50.1899,7.067100716,7.070451235,-3.0846875,-7.08998098,-2.986851732,44.99999998 +137.95,50.42815216,-2.578003366,50.2207,7.077529327,7.070229119,-3.075,-7.104677118,-2.935758508,44.99999998 +137.96,50.4281528,-2.578002371,50.2514,7.084481734,7.070451114,-3.0646875,-7.117889582,-2.88210525,44.99999998 +137.97,50.42815344,-2.578001376,50.282,7.07752937,7.071339273,-3.053125,-7.129615564,-2.82593877,44.99999998 +137.98,50.42815407,-2.578000381,50.3125,7.067100831,7.072227432,-3.04,-7.139852601,-2.767308056,44.99999998 +137.99,50.42815471,-2.577999385,50.3428,7.063624687,7.071561206,-3.02625,-7.148598573,-2.706264216,44.99999998 +138,50.42815534,-2.57799839,50.373,7.063624726,7.070228815,-3.0115625,-7.155851646,-2.64286042,44.99999998 +138.01,50.42815598,-2.577997396,50.4031,7.067100947,7.070450809,-2.9946875,-7.16161033,-2.577152016,44.99999998 +138.02,50.42815661,-2.5779964,50.4329,7.077529551,7.071338967,-2.9765625,-7.165873365,-2.509196357,44.99999998 +138.03,50.42815725,-2.577995405,50.4626,7.084481961,7.07111685,-2.958125,-7.168639949,-2.439052571,44.99999998 +138.04,50.42815789,-2.57799441,50.4921,7.077529609,7.070450623,-2.9378125,-7.169909394,-2.366781967,44.99999998 +138.05,50.42815852,-2.577993415,50.5214,7.067101079,7.070228506,-2.915,-7.169681586,-2.292447454,44.99999998 +138.06,50.42815916,-2.57799242,50.5504,7.063624931,7.070450498,-2.8915625,-7.16795641,-2.216113891,44.99999998 +138.07,50.42815979,-2.577991425,50.5792,7.06362496,7.071338655,-2.868125,-7.164734325,-2.137847799,44.99999998 +138.08,50.42816043,-2.57799043,50.6078,7.063624976,7.072448867,-2.843125,-7.16001596,-2.057717531,44.99999998 +138.09,50.42816106,-2.577989434,50.6361,7.063624998,7.072448803,-2.81625,-7.15380229,-1.975792875,44.99999998 +138.1,50.4281617,-2.577988439,50.6641,7.06710123,7.071338465,-2.7884375,-7.14609469,-1.892145334,44.99999998 +138.11,50.42816233,-2.577987444,50.6919,7.077529858,7.070450181,-2.7596875,-7.136894707,-1.806847789,44.99999998 +138.12,50.42816297,-2.577986449,50.7193,7.084482282,7.070450117,-2.7296875,-7.126204288,-1.719974668,44.99999998 +138.13,50.42816361,-2.577985454,50.7465,7.07752992,7.071338272,-2.698125,-7.114025612,-1.631601657,44.99999998 +138.14,50.42816424,-2.577984459,50.7733,7.067101367,7.072226426,-2.6646875,-7.100361313,-1.541805935,44.99999998 +138.15,50.42816488,-2.577983463,50.7998,7.063625201,7.071560196,-2.63,-7.085214143,-1.450665654,44.99999998 +138.16,50.42816551,-2.577982468,50.8259,7.063625224,7.070227801,-2.5946875,-7.068587366,-1.358260453,44.99999998 +138.17,50.42816615,-2.577981474,50.8517,7.067101443,7.07044979,-2.5584375,-7.050484363,-1.264670776,44.99999998 +138.18,50.42816678,-2.577980478,50.8771,7.077530058,7.071337943,-2.52125,-7.030908974,-1.169978271,44.99999998 +138.19,50.42816742,-2.577979483,50.9021,7.084482484,7.071115822,-2.4834375,-7.009865323,-1.074265556,44.99999998 +138.2,50.42816806,-2.577978488,50.9268,7.07753013,7.07044959,-2.4446875,-6.98735765,-0.977616056,44.99999998 +138.21,50.42816869,-2.577977493,50.951,7.067101572,7.070227467,-2.4046875,-6.963390825,-0.880114109,44.99999998 +138.22,50.42816933,-2.577976498,50.9749,7.06362539,7.070449453,-2.3634375,-6.937969776,-0.781844628,44.99999998 +138.23,50.42816996,-2.577975503,50.9983,7.06362541,7.071337604,-2.32125,-6.911099832,-0.682893385,44.99999998 +138.24,50.4281706,-2.577974508,51.0213,7.067101641,7.072447809,-2.278125,-6.882786549,-0.583346666,44.99999998 +138.25,50.42817123,-2.577973512,51.0439,7.077530264,7.072447739,-2.233125,-6.853035888,-0.483291218,44.99999998 +138.26,50.42817187,-2.577972517,51.066,7.084482682,7.071337394,-2.1865625,-6.821854092,-0.38281436,44.99999998 +138.27,50.42817251,-2.577971522,51.0876,7.077530306,7.070449104,-2.14,-6.789247637,-0.282003696,44.99999998 +138.28,50.42817314,-2.577970527,51.1088,7.06710173,7.070226979,-2.0934375,-6.755223341,-0.180947119,44.99999998 +138.29,50.42817378,-2.577969532,51.1295,7.06362556,7.070226907,-2.04625,-6.71978825,-0.079732749,44.99999998 +138.3,50.42817441,-2.577968537,51.1497,7.063625601,7.070226834,-1.998125,-6.682949871,0.021551177,44.99999998 +138.31,50.42817505,-2.577967542,51.1695,7.067101831,7.070448816,-1.948125,-6.644715825,0.122816311,44.99999998 +138.32,50.42817568,-2.577966547,51.1887,7.077530431,7.071336962,-1.8965625,-6.605094132,0.223974301,44.99999998 +138.33,50.42817632,-2.577965552,51.2074,7.084482825,7.072447163,-1.845,-6.564093043,0.324937028,44.99999998 +138.34,50.42817696,-2.577964556,51.2256,7.077530446,7.072447088,-1.793125,-6.521721095,0.42561637,44.99999998 +138.35,50.42817759,-2.577963561,51.2433,7.067101891,7.071336739,-1.7396875,-6.477987169,0.525924606,44.99999998 +138.36,50.42817823,-2.577962566,51.2604,7.063625732,7.070448443,-1.685,-6.432900432,0.625774191,44.99999998 +138.37,50.42817886,-2.577961571,51.277,7.063625756,7.070226312,-1.63,-6.386470282,0.72507809,44.99999998 +138.38,50.4281795,-2.577960576,51.293,7.063625768,7.07044829,-1.575,-6.338706343,0.82374973,44.99999998 +138.39,50.42818013,-2.577959581,51.3085,7.063625777,7.071336433,-1.52,-6.289618699,0.921703053,44.99999998 +138.4,50.42818077,-2.577958586,51.3234,7.067101984,7.072224574,-1.4646875,-6.239217493,1.018852631,44.99999998 +138.41,50.4281814,-2.57795759,51.3378,7.077530588,7.07155833,-1.408125,-6.18751338,1.115113723,44.99999998 +138.42,50.42818204,-2.577956595,51.3516,7.084482999,7.070225922,-1.3496875,-6.134517019,1.210402448,44.99999998 +138.43,50.42818268,-2.577955601,51.3648,7.077530628,7.070447897,-1.29,-6.080239581,1.304635728,44.99999998 +138.44,50.42818331,-2.577954605,51.3774,7.06710206,7.071336036,-1.23,-6.024692354,1.397731286,44.99999998 +138.45,50.42818395,-2.57795361,51.3894,7.063625878,7.071113899,-1.1703125,-5.967886912,1.489607991,44.99999998 +138.46,50.42818458,-2.577952615,51.4008,7.063625885,7.070447652,-1.1115625,-5.909835229,1.5801858,44.99999998 +138.47,50.42818522,-2.57795162,51.4116,7.067102087,7.070225515,-1.0528125,-5.850549281,1.669385588,44.99999998 +138.48,50.42818585,-2.577950625,51.4219,7.077530686,7.070447487,-0.9915625,-5.790041557,1.75712972,44.99999998 +138.49,50.42818649,-2.57794963,51.4315,7.084483095,7.071335622,-0.9284375,-5.728324663,1.843341534,44.99999998 +138.5,50.42818713,-2.577948635,51.4404,7.077530724,7.072445811,-0.866875,-5.665411434,1.927945971,44.99999998 +138.51,50.42818776,-2.577947639,51.4488,7.067102147,7.072445725,-0.8065625,-5.601315104,2.010869236,44.99999998 +138.52,50.4281884,-2.577946644,51.4566,7.063625947,7.071335365,-0.744375,-5.536048966,2.092038964,44.99999998 +138.53,50.42818903,-2.577945649,51.4637,7.063625949,7.070447059,-0.68,-5.469626713,2.171384394,44.99999998 +138.54,50.42818967,-2.577944654,51.4702,7.06710216,7.070224917,-0.6153125,-5.402062212,2.248836313,44.99999998 +138.55,50.4281903,-2.577943659,51.476,7.077530759,7.070446884,-0.551875,-5.333369557,2.324327284,44.99999998 +138.56,50.42819094,-2.577942664,51.4812,7.084483156,7.07111296,-0.49,-5.26356313,2.39779136,44.99999998 +138.57,50.42819158,-2.577941669,51.4858,7.077530771,7.071556979,-0.4278125,-5.192657425,2.46916454,44.99999998 +138.58,50.42819221,-2.577940673,51.4898,7.067102187,7.071334834,-0.3634375,-5.120667341,2.538384603,44.99999998 +138.59,50.42819285,-2.577939679,51.4931,7.063625995,7.071334743,-0.298125,-5.047607831,2.6053911,44.99999998 +138.6,50.42819348,-2.577938683,51.4957,7.063626009,7.071556706,-0.23375,-4.973494193,2.670125705,44.99999998 +138.61,50.42819412,-2.577937688,51.4978,7.067102218,7.071112504,-0.17,-4.898341955,2.732531867,44.99999998 +138.62,50.42819475,-2.577936693,51.4991,7.077530798,7.070446247,-0.10625,-4.8221667,2.79255527,44.99999998 +138.63,50.42819539,-2.577935698,51.4999,7.084483173,7.070224098,-0.041875,-4.744984415,2.850143487,44.99999998 +138.64,50.42819603,-2.577934703,51.5,7.077530774,7.070446058,0.0234375,-4.666811199,2.905246385,44.99999998 +138.65,50.42819666,-2.577933708,51.4994,7.067102198,7.071334182,0.088125,-4.587663383,2.957815836,44.99999998 +138.66,50.4281973,-2.577932713,51.4982,7.063626019,7.072222306,0.151875,-4.507557523,3.007806002,44.99999998 +138.67,50.42819793,-2.577931717,51.4964,7.063626022,7.071556045,0.2165625,-4.426510294,3.05517334,44.99999998 +138.68,50.42819857,-2.577930722,51.4939,7.063626016,7.070223618,0.2815625,-4.344538654,3.099876538,44.99999998 +138.69,50.4281992,-2.577929728,51.4907,7.063626011,7.070445574,0.345,-4.261659679,3.141876579,44.99999998 +138.7,50.42819984,-2.577928732,51.487,7.0671022,7.071333695,0.4084375,-4.177890728,3.181136851,44.99999998 +138.71,50.42820047,-2.577927737,51.4826,7.077530772,7.071333596,0.4734375,-4.093249278,3.217623147,44.99999998 +138.72,50.42820111,-2.577926742,51.4775,7.084483151,7.071333495,0.5378125,-4.007753031,3.251303611,44.99999998 +138.73,50.42820175,-2.577925747,51.4718,7.077530761,7.071555449,0.6,-3.921419808,3.282148909,44.99999998 +138.74,50.42820238,-2.577924751,51.4655,7.067102177,7.071333293,0.661875,-3.834267599,3.31013211,44.99999998 +138.75,50.42820302,-2.577923757,51.4586,7.063625969,7.071333191,0.725,-3.746314681,3.335228808,44.99999998 +138.76,50.42820365,-2.577922761,51.451,7.063625952,7.071555142,0.7884375,-3.657579447,3.357417171,44.99999998 +138.77,50.42820429,-2.577921766,51.4428,7.067102145,7.071110929,0.85125,-3.568080288,3.376677778,44.99999998 +138.78,50.42820492,-2.577920771,51.434,7.077530734,7.07044466,0.9134375,-3.477836055,3.392993897,44.99999998 +138.79,50.42820556,-2.577919776,51.4245,7.084483117,7.0702225,0.9746875,-3.386865483,3.406351319,44.99999998 +138.8,50.4282062,-2.577918781,51.4145,7.077530714,7.070444449,1.035,-3.295187595,3.416738299,44.99999998 +138.81,50.42820683,-2.577917786,51.4038,7.067102118,7.071332562,1.095,-3.202821584,3.424145841,44.99999998 +138.82,50.42820747,-2.577916791,51.3926,7.06362591,7.072220673,1.155,-3.109786646,3.428567471,44.99999998 +138.83,50.4282081,-2.577915795,51.3807,7.063625891,7.071554401,1.215,-3.016102317,3.42999935,44.99999998 +138.84,50.42820874,-2.5779148,51.3683,7.067102068,7.070221964,1.2746875,-2.921788135,3.42844016,44.99999998 +138.85,50.42820937,-2.577913806,51.3552,7.077530641,7.07044391,1.3334375,-2.826863753,3.423891391,44.99999998 +138.86,50.42821001,-2.57791281,51.3416,7.084483024,7.07133202,1.39125,-2.731348996,3.416356938,44.99999998 +138.87,50.42821065,-2.577911815,51.3274,7.077530627,7.071109855,1.4484375,-2.635263859,3.405843335,44.99999998 +138.88,50.42821128,-2.57791082,51.3126,7.067102025,7.070443579,1.5046875,-2.538628339,3.392359804,44.99999998 +138.89,50.42821192,-2.577909825,51.2973,7.063625801,7.070221413,1.56,-2.441462718,3.375918093,44.99999998 +138.9,50.42821255,-2.57790883,51.2814,7.063625784,7.070443356,1.615,-2.343787165,3.356532524,44.99999998 +138.91,50.42821319,-2.577907835,51.265,7.067101974,7.071331462,1.67,-2.245622192,3.334220001,44.99999998 +138.92,50.42821382,-2.57790684,51.248,7.077530543,7.072441622,1.725,-2.146988195,3.308999946,44.99999998 +138.93,50.42821446,-2.577905844,51.2305,7.084482906,7.072441507,1.779375,-2.047905916,3.280894475,44.99999998 +138.94,50.4282151,-2.577904849,51.2124,7.077530487,7.071331119,1.8315625,-1.948395866,3.249927997,44.99999998 +138.95,50.42821573,-2.577903854,51.1938,7.067101874,7.070442784,1.8815625,-1.84847896,3.216127498,44.99999998 +138.96,50.42821637,-2.577902859,51.1748,7.063625662,7.070220614,1.931875,-1.748176051,3.179522485,44.99999998 +138.97,50.428217,-2.577901864,51.1552,7.063625659,7.070442553,1.983125,-1.647507997,3.140144929,44.99999998 +138.98,50.42821764,-2.577900869,51.1351,7.067101844,7.071108601,2.033125,-1.546495939,3.098029093,44.99999998 +138.99,50.42821827,-2.577899874,51.1145,7.0775304,7.071552592,2.0815625,-1.445160904,3.053211704,44.99999998 +139,50.42821891,-2.577898878,51.0935,7.08448275,7.071330419,2.1296875,-1.343524036,3.005731895,44.99999998 +139.01,50.42821955,-2.577897884,51.0719,7.077530328,7.071330301,2.1765625,-1.241606589,2.955631033,44.99999998 +139.02,50.42822018,-2.577896888,51.0499,7.067101729,7.071552237,2.22125,-1.13942988,2.902952835,44.99999998 +139.03,50.42822082,-2.577895893,51.0275,7.063625526,7.071108008,2.265,-1.037015164,2.847743252,44.99999998 +139.04,50.42822145,-2.577894898,51.0046,7.063625506,7.070441724,2.3084375,-0.934383927,2.790050356,44.99999998 +139.05,50.42822209,-2.577893903,50.9813,7.063625474,7.070219549,2.35125,-0.83155754,2.729924451,44.99999998 +139.06,50.42822272,-2.577892908,50.9576,7.06362544,7.070441483,2.393125,-0.728557548,2.667418079,44.99999998 +139.07,50.42822336,-2.577891913,50.9334,7.067101604,7.07132958,2.4334375,-0.62540532,2.60258567,44.99999998 +139.08,50.42822399,-2.577890918,50.9089,7.077530163,7.072439732,2.4728125,-0.522122516,2.535483717,44.99999998 +139.09,50.42822463,-2.577889922,50.884,7.084482531,7.07243961,2.511875,-0.418730677,2.466170836,44.99999998 +139.1,50.42822527,-2.577888927,50.8586,7.077530118,7.071329213,2.5496875,-0.315251406,2.394707414,44.99999998 +139.11,50.4282259,-2.577887932,50.833,7.067101511,7.070440871,2.58625,-0.211706301,2.321155733,44.99999998 +139.12,50.42822654,-2.577886937,50.8069,7.063625293,7.070218693,2.6215625,-0.108116964,2.245579965,44.99999998 +139.13,50.42822717,-2.577885942,50.7805,7.06362526,7.070440625,2.6546875,-0.004505053,2.168046055,44.99999998 +139.14,50.42822781,-2.577884947,50.7538,7.06710141,7.071106664,2.686875,0.099107833,2.088621557,44.99999998 +139.15,50.42822844,-2.577883952,50.7268,7.077529956,7.071328594,2.7196875,0.202699977,2.007375798,44.99999998 +139.16,50.42822908,-2.577882956,50.6994,7.084482325,7.07044025,2.75125,0.30624978,1.924379538,44.99999998 +139.17,50.42822972,-2.577881962,50.6717,7.077529923,7.07021807,2.7796875,0.409735641,1.8397052,44.99999998 +139.18,50.42823035,-2.577880967,50.6438,7.067101316,7.071550272,2.806875,0.513135959,1.753426579,44.99999998 +139.19,50.42823099,-2.577879971,50.6156,7.063625078,7.072216311,2.835,0.616429077,1.665618964,44.99999998 +139.2,50.42823162,-2.577878976,50.5871,7.063625029,7.071327967,2.8628125,0.719593509,1.5763589,44.99999998 +139.21,50.42823226,-2.577877981,50.5583,7.067101192,7.070439622,2.8878125,0.822607596,1.485724253,44.99999998 +139.22,50.42823289,-2.577876986,50.5293,7.07752976,7.070439495,2.9096875,0.925449968,1.393794035,44.99999998 +139.23,50.42823353,-2.577875991,50.5001,7.084482129,7.071327586,2.9303125,1.028099024,1.300648401,44.99999998 +139.24,50.42823417,-2.577874996,50.4707,7.077529705,7.072215677,2.9515625,1.130533392,1.206368539,44.99999998 +139.25,50.4282348,-2.577874,50.4411,7.067101076,7.071549386,2.9728125,1.232731645,1.111036727,44.99999998 +139.26,50.42823544,-2.577873005,50.4112,7.063624839,7.07021693,2.99125,1.334672468,1.014736101,44.99999998 +139.27,50.42823607,-2.577872011,50.3812,7.063624813,7.070438857,3.0065625,1.436334547,0.917550599,44.99999998 +139.28,50.42823671,-2.577871015,50.3511,7.06710099,7.071326947,3.0215625,1.537696682,0.819564961,44.99999998 +139.29,50.42823734,-2.57787002,50.3208,7.077529542,7.07132682,3.0365625,1.638737732,0.720864673,44.99999998 +139.3,50.42823798,-2.577869025,50.2903,7.08448189,7.071326692,3.0496875,1.739436497,0.621535793,44.99999998 +139.31,50.42823862,-2.57786803,50.2598,7.077529461,7.071326563,3.0615625,1.839772007,0.521664894,44.99999998 +139.32,50.42823925,-2.577867034,50.2291,7.067100842,7.070438216,3.073125,1.939723291,0.421339068,44.99999998 +139.33,50.42823989,-2.57786604,50.1983,7.06362462,7.070216033,3.0828125,2.039269551,0.320645861,44.99999998 +139.34,50.42824052,-2.577865045,50.1674,7.063624593,7.071548231,3.09,2.138389874,0.21967305,44.99999998 +139.35,50.42824116,-2.577864049,50.1365,7.063624562,7.072214266,3.0965625,2.237063635,0.1185087,44.99999998 +139.36,50.42824179,-2.577863054,50.1055,7.063624528,7.071325919,3.1028125,2.335270205,0.017240988,44.99999998 +139.37,50.42824243,-2.577862059,50.0744,7.067100686,7.070437572,3.10625,2.432989131,-0.084041736,44.99999998 +139.38,50.42824306,-2.577861064,50.0433,7.077529226,7.070215388,3.1065625,2.530199901,-0.185251235,44.99999998 +139.39,50.4282437,-2.577860069,50.0123,7.084481575,7.070437313,3.106875,2.626882289,-0.286299161,44.99999998 +139.4,50.42824434,-2.577859074,49.9812,7.077529159,7.071103348,3.1084375,2.723016127,-0.387097391,44.99999998 +139.41,50.42824497,-2.577858079,49.9501,7.067100553,7.071547328,3.1090625,2.818581247,-0.487558092,44.99999998 +139.42,50.42824561,-2.577857083,49.919,7.063624333,7.071325145,3.1065625,2.913557768,-0.587593658,44.99999998 +139.43,50.42824624,-2.577856089,49.8879,7.063624295,7.071325016,3.10125,3.007925808,-0.687116828,44.99999998 +139.44,50.42824688,-2.577855093,49.857,7.067100439,7.071546941,3.095,3.101665714,-0.786040799,44.99999998 +139.45,50.42824751,-2.577854098,49.826,7.077528979,7.071102703,3.088125,3.194757834,-0.884279341,44.99999998 +139.46,50.42824815,-2.577853103,49.7952,7.084481344,7.070436411,3.0796875,3.287182801,-0.981746795,44.99999998 +139.47,50.42824879,-2.577852108,49.7644,7.077528939,7.070214227,3.07,3.378921309,-1.078358137,44.99999998 +139.48,50.42824942,-2.577851113,49.7338,7.06710033,7.070436153,3.0596875,3.469954104,-1.17402914,44.99999998 +139.49,50.42825006,-2.577850118,49.7032,7.06362409,7.071324243,3.048125,3.560262279,-1.268676324,44.99999998 +139.5,50.42825069,-2.577849123,49.6728,7.06362404,7.072434387,3.0346875,3.649826927,-1.362217242,44.99999998 +139.51,50.42825133,-2.577848127,49.6425,7.067100198,7.072434259,3.02,3.738629369,-1.454570304,44.99999998 +139.52,50.42825196,-2.577847132,49.6124,7.077528756,7.071323859,3.004375,3.826651042,-1.545654951,44.99999998 +139.53,50.4282526,-2.577846137,49.5824,7.084481121,7.070435513,2.9865625,3.91387361,-1.635391773,44.99999998 +139.54,50.42825324,-2.577845142,49.5526,7.077528709,7.070213331,2.9665625,4.000278739,-1.723702503,44.99999998 +139.55,50.42825387,-2.577844147,49.5231,7.067100093,7.070435258,2.9465625,4.085848496,-1.810510078,44.99999998 +139.56,50.42825451,-2.577843152,49.4937,7.063623855,7.071101294,2.9265625,4.170565005,-1.895738925,44.99999998 +139.57,50.42825514,-2.577842157,49.4645,7.063623823,7.071323221,2.9046875,4.254410502,-1.979314674,44.99999998 +139.58,50.42825578,-2.577841161,49.4356,7.067099998,7.070434877,2.88125,4.337367515,-2.061164388,44.99999998 +139.59,50.42825641,-2.577840167,49.4069,7.077528551,7.070212696,2.8565625,4.419418795,-2.141216734,44.99999998 +139.6,50.42825705,-2.577839172,49.3784,7.0844809,7.071544897,2.8296875,4.500547041,-2.219401924,44.99999998 +139.61,50.42825769,-2.577838176,49.3503,7.077528475,7.072210934,2.8015625,4.580735463,-2.295651778,44.99999998 +139.62,50.42825832,-2.577837181,49.3224,7.067099861,7.071322591,2.7734375,4.659967276,-2.369899774,44.99999998 +139.63,50.42825896,-2.577836186,49.2948,7.063623642,7.070434249,2.7446875,4.738225862,-2.442081169,44.99999998 +139.64,50.42825959,-2.577835191,49.2675,7.063623619,7.07021207,2.7146875,4.815494951,-2.512133052,44.99999998 +139.65,50.42826023,-2.577834196,49.2405,7.063623592,7.070433999,2.6828125,4.891758383,-2.579994345,44.99999998 +139.66,50.42826086,-2.577833201,49.2138,7.063623566,7.071322092,2.648125,4.967000232,-2.645605805,44.99999998 +139.67,50.4282615,-2.577832206,49.1875,7.067099735,7.072432241,2.611875,5.041204798,-2.70891025,44.99999998 +139.68,50.42826213,-2.57783121,49.1616,7.077528281,7.072432117,2.5765625,5.114356555,-2.769852505,44.99999998 +139.69,50.42826277,-2.577830215,49.136,7.084480624,7.071321722,2.5415625,5.18644026,-2.828379399,44.99999998 +139.7,50.42826341,-2.57782922,49.1107,7.077528205,7.070433382,2.5046875,5.257440846,-2.884439938,44.99999998 +139.71,50.42826404,-2.577828225,49.0859,7.067099608,7.07043326,2.46625,5.327343474,-2.937985136,44.99999998 +139.72,50.42826468,-2.57782723,49.0614,7.063623397,7.071099302,2.4265625,5.396133531,-2.98896841,44.99999998 +139.73,50.42826531,-2.577826235,49.0373,7.063623373,7.071321235,2.3846875,5.463796696,-3.037345242,44.99999998 +139.74,50.42826595,-2.577825239,49.0137,7.067099539,7.070432896,2.3415625,5.530318815,-3.08307352,44.99999998 +139.75,50.42826658,-2.577824245,48.9905,7.077528086,7.070210722,2.2984375,5.595686022,-3.12611325,44.99999998 +139.76,50.42826722,-2.57782325,48.9677,7.084480443,7.071542928,2.255,5.659884626,-3.166426961,44.99999998 +139.77,50.42826786,-2.577822254,48.9454,7.077528038,7.072208971,2.21125,5.722901217,-3.203979532,44.99999998 +139.78,50.42826849,-2.577821259,48.9235,7.067099444,7.071320635,2.1665625,5.784722675,-3.238738189,44.99999998 +139.79,50.42826913,-2.577820264,48.902,7.063623235,7.0704323,2.1196875,5.845336052,-3.270672564,44.99999998 +139.8,50.42826976,-2.577819269,48.8811,7.063623208,7.070210127,2.0715625,5.904728743,-3.299754928,44.99999998 +139.81,50.4282704,-2.577818274,48.8606,7.067099363,7.070432064,2.023125,5.962888256,-3.32595984,44.99999998 +139.82,50.42827103,-2.577817279,48.8406,7.077527914,7.071320165,1.973125,6.019802503,-3.34926444,44.99999998 +139.83,50.42827167,-2.577816284,48.8211,7.08448029,7.07243032,1.9215625,6.075459623,-3.369648445,44.99999998 +139.84,50.42827231,-2.577815288,48.8022,7.077527899,7.072430204,1.87,6.129847929,-3.387094036,44.99999998 +139.85,50.42827294,-2.577814293,48.7837,7.067099306,7.071319817,1.8184375,6.182956131,-3.401586087,44.99999998 +139.86,50.42827358,-2.577813298,48.7658,7.063623083,7.070431486,1.76625,6.234773059,-3.413111877,44.99999998 +139.87,50.42827421,-2.577812303,48.7484,7.063623053,7.070209318,1.7134375,6.285287998,-3.421661382,44.99999998 +139.88,50.42827485,-2.577811308,48.7315,7.06709923,7.070209204,1.6596875,6.33449029,-3.427227151,44.99999998 +139.89,50.42827548,-2.577810313,48.7152,7.077527798,7.070209091,1.605,6.38236968,-3.429804315,44.99999998 +139.9,50.42827612,-2.577809318,48.6994,7.084480169,7.070431034,1.5496875,6.428916256,-3.429390697,44.99999998 +139.91,50.42827676,-2.577808323,48.6842,7.077527765,7.07131914,1.493125,6.474120162,-3.425986526,44.99999998 +139.92,50.42827739,-2.577807328,48.6695,7.067099162,7.0724293,1.4353125,6.51797206,-3.419594895,44.99999998 +139.93,50.42827803,-2.577806332,48.6555,7.063622946,7.07242919,1.378125,6.560462782,-3.410221305,44.99999998 +139.94,50.42827866,-2.577805337,48.642,7.063622938,7.07131881,1.3215625,6.601583447,-3.397873893,44.99999998 +139.95,50.4282793,-2.577804342,48.629,7.067099133,7.070430483,1.2628125,6.641325462,-3.382563544,44.99999998 +139.96,50.42827993,-2.577803347,48.6167,7.077527703,7.07020832,1.201875,6.67968046,-3.364303551,44.99999998 +139.97,50.42828057,-2.577802352,48.605,7.08448007,7.070430267,1.141875,6.716640535,-3.343109842,44.99999998 +139.98,50.42828121,-2.577801357,48.5939,7.077527664,7.071318377,1.083125,6.752197894,-3.319000867,44.99999998 +139.99,50.42828184,-2.577800362,48.5833,7.06709907,7.072206488,1.023125,6.786345205,-3.29199771,44.99999998 +140,50.42828248,-2.577799366,48.5734,7.063622872,7.071540219,0.96125,6.819075247,-3.262123862,44.99999998 +140.01,50.42828311,-2.577798371,48.5641,7.063622869,7.070207788,0.89875,6.850381202,-3.229405394,44.99999998 +140.02,50.42828375,-2.577797377,48.5554,7.063622862,7.070429739,0.8365625,6.88025654,-3.193870838,44.99999998 +140.03,50.42828438,-2.577796381,48.5474,7.063622856,7.071317853,0.775,6.908695013,-3.155551134,44.99999998 +140.04,50.42828502,-2.577795386,48.5399,7.067099046,7.07131775,0.713125,6.935690722,-3.1144798,44.99999998 +140.05,50.42828565,-2.577794391,48.5331,7.077527613,7.071317647,0.6496875,6.961237936,-3.070692589,44.99999998 +140.06,50.42828629,-2.577793396,48.5269,7.084479976,7.071317546,0.5853125,6.985331442,-3.02422766,44.99999998 +140.07,50.42828693,-2.5777924,48.5214,7.077527579,7.070429228,0.521875,7.007966139,-2.975125578,44.99999998 +140.08,50.42828756,-2.577791406,48.5165,7.067099007,7.070207073,0.4596875,7.029137331,-2.923429143,44.99999998 +140.09,50.4282882,-2.577790411,48.5122,7.063622824,7.071539299,0.3965625,7.048840547,-2.869183447,44.99999998 +140.1,50.42828883,-2.577789415,48.5085,7.063622818,7.072205364,0.3315625,7.067071721,-2.812435759,44.99999998 +140.11,50.42828947,-2.57778842,48.5056,7.067098993,7.071317049,0.266875,7.083827069,-2.753235583,44.99999998 +140.12,50.4282901,-2.577787425,48.5032,7.077527563,7.070428734,0.2034375,7.099102983,-2.691634541,44.99999998 +140.13,50.42829074,-2.57778643,48.5015,7.084479958,7.070206584,0.1396875,7.112896369,-2.627686378,44.99999998 +140.14,50.42829138,-2.577785435,48.5004,7.077527588,7.070428542,0.075,7.125204305,-2.561446784,44.99999998 +140.15,50.42829201,-2.57778444,48.5,7.067099017,7.07109461,0.01,7.136024269,-2.492973629,44.99999998 +140.16,50.42829265,-2.577783445,48.5002,7.063622818,7.071538623,-0.055,7.145353913,-2.422326501,44.99999998 +140.17,50.42829328,-2.577782449,48.5011,7.063622805,7.071316475,-0.12,7.153191403,-2.349567106,44.99999998 +140.18,50.42829392,-2.577781455,48.5026,7.067098989,7.071316383,-0.1846875,7.159534962,-2.274758872,44.99999998 +140.19,50.42829455,-2.577780459,48.5048,7.077527577,7.071538345,-0.2484375,7.164383388,-2.197967,44.99999998 +140.2,50.42829519,-2.577779464,48.5076,7.084479981,7.071316199,-0.3115625,7.16773565,-2.11925847,44.99999998 +140.21,50.42829583,-2.577778469,48.511,7.077527603,7.071316108,-0.3753125,7.169591002,-2.038701922,44.99999998 +140.22,50.42829646,-2.577777474,48.5151,7.067099017,7.071316018,-0.44,7.169949043,-1.9563676,44.99999998 +140.23,50.4282971,-2.577776478,48.5198,7.063622819,7.070427712,-0.5046875,7.168809774,-1.872327239,44.99999998 +140.24,50.42829773,-2.577775484,48.5252,7.063622832,7.070205569,-0.568125,7.166173366,-1.786654235,44.99999998 +140.25,50.42829837,-2.577774489,48.5312,7.063622855,7.071537806,-0.63,7.162040392,-1.699423244,44.99999998 +140.26,50.428299,-2.577773493,48.5378,7.063622868,7.072203881,-0.691875,7.156411769,-1.610710298,44.99999998 +140.27,50.42829964,-2.577772498,48.545,7.067099065,7.071315578,-0.755,7.149288529,-1.520592803,44.99999998 +140.28,50.42830027,-2.577771503,48.5529,7.07752765,7.070427275,-0.8184375,7.140672332,-1.429149369,44.99999998 +140.29,50.42830091,-2.577770508,48.5614,7.084480044,7.070205136,-0.88125,7.130564841,-1.336459638,44.99999998 +140.3,50.42830155,-2.577769513,48.5705,7.077527663,7.070427105,-0.9434375,7.11896829,-1.24260451,44.99999998 +140.31,50.42830218,-2.577768518,48.5803,7.067099091,7.071093183,-1.0046875,7.10588497,-1.147665804,44.99999998 +140.32,50.42830282,-2.577767523,48.5906,7.063622915,7.071537209,-1.0646875,7.09131769,-1.051726313,44.99999998 +140.33,50.42830345,-2.577766527,48.6016,7.063622937,7.071315072,-1.12375,7.075269486,-0.954869746,44.99999998 +140.34,50.42830409,-2.577765533,48.6131,7.06709915,7.07131499,-1.183125,7.057743739,-0.857180499,44.99999998 +140.35,50.42830472,-2.577764537,48.6252,7.077527738,7.071536963,-1.2434375,7.038744057,-0.758743772,44.99999998 +140.36,50.42830536,-2.577763542,48.638,7.084480123,7.071092775,-1.303125,7.018274395,-0.659645393,44.99999998 +140.37,50.428306,-2.577762547,48.6513,7.077527747,7.070426532,-1.36125,6.99633905,-0.559971821,44.99999998 +140.38,50.42830663,-2.577761552,48.6652,7.067099195,7.070204399,-1.4184375,6.972942662,-0.459809918,44.99999998 +140.39,50.42830727,-2.577760557,48.6797,7.063623035,7.070426374,-1.475,6.948089987,-0.359247059,44.99999998 +140.4,50.4283079,-2.577759562,48.6947,7.063623057,7.071314513,-1.5315625,6.921786354,-0.258370963,44.99999998 +140.41,50.42830854,-2.577758567,48.7103,7.067099255,7.072424706,-1.588125,6.894037149,-0.157269524,44.99999998 +140.42,50.42830917,-2.577757571,48.7265,7.077527834,7.072424629,-1.643125,6.864848272,-0.056030975,44.99999998 +140.43,50.42830981,-2.577756576,48.7432,7.084480239,7.071314282,-1.6965625,6.834225741,0.045256447,44.99999998 +140.44,50.42831045,-2.577755581,48.7604,7.077527891,7.07042599,-1.75,6.802175914,0.146504449,44.99999998 +140.45,50.42831108,-2.577754586,48.7782,7.067099346,7.070203861,-1.8034375,6.76870561,0.247624624,44.99999998 +140.46,50.42831172,-2.577753591,48.7965,7.06362317,7.070425841,-1.85625,6.733821705,0.348528909,44.99999998 +140.47,50.42831235,-2.577752596,48.8153,7.063623176,7.071313983,-1.908125,6.697531533,0.44912924,44.99999998 +140.48,50.42831299,-2.577751601,48.8347,7.067099378,7.072202127,-1.958125,6.659842713,0.549337954,44.99999998 +140.49,50.42831362,-2.577750605,48.8545,7.077527979,7.071535892,-2.0065625,6.62076298,0.649067618,44.99999998 +140.5,50.42831426,-2.57774961,48.8748,7.084480402,7.070203495,-2.0553125,6.580300643,0.748231314,44.99999998 +140.51,50.4283149,-2.577748616,48.8956,7.077528055,7.070425477,-2.1046875,6.538464125,0.846742526,44.99999998 +140.52,50.42831553,-2.57774762,48.9169,7.067099505,7.071313622,-2.1528125,6.495262076,0.944515368,44.99999998 +140.53,50.42831617,-2.577746625,48.9387,7.063623326,7.071091497,-2.198125,6.450703606,1.041464582,44.99999998 +140.54,50.4283168,-2.57774563,48.9609,7.063623341,7.070425265,-2.2415625,6.404797999,1.137505601,44.99999998 +140.55,50.42831744,-2.577744635,48.9835,7.067099562,7.070203141,-2.2853125,6.357554821,1.232554716,44.99999998 +140.56,50.42831807,-2.57774364,49.0066,7.077528174,7.070425127,-2.3296875,6.308983928,1.326529019,44.99999998 +140.57,50.42831871,-2.577742645,49.0301,7.084480589,7.071313274,-2.3728125,6.259095462,1.419346577,44.99999998 +140.58,50.42831935,-2.57774165,49.0541,7.077528232,7.072423476,-2.4134375,6.207899906,1.510926432,44.99999998 +140.59,50.42831998,-2.577740654,49.0784,7.067099685,7.072423408,-2.453125,6.15540792,1.601188714,44.99999998 +140.6,50.42832062,-2.577739659,49.1031,7.063623516,7.071313071,-2.493125,6.101630445,1.690054754,44.99999998 +140.61,50.42832125,-2.577738664,49.1283,7.063623529,7.070424788,-2.53125,6.046578712,1.77744709,44.99999998 +140.62,50.42832189,-2.577737669,49.1538,7.063623552,7.070202667,-2.5665625,5.990264237,1.863289403,44.99999998 +140.63,50.42832252,-2.577736674,49.1796,7.063623592,7.070424655,-2.601875,5.932698766,1.947506922,44.99999998 +140.64,50.42832316,-2.577735679,49.2058,7.067099828,7.071090752,-2.638125,5.873894332,2.030026195,44.99999998 +140.65,50.42832379,-2.577734684,49.2324,7.077528436,7.071534795,-2.6728125,5.813863194,2.110775257,44.99999998 +140.66,50.42832443,-2.577733688,49.2593,7.084480837,7.071312676,-2.7046875,5.752617902,2.189683692,44.99999998 +140.67,50.42832507,-2.577732694,49.2865,7.077528475,7.071312611,-2.735,5.690171289,2.266682688,44.99999998 +140.68,50.4283257,-2.577731698,49.314,7.067099936,7.071534601,-2.7646875,5.626536305,2.341705094,44.99999998 +140.69,50.42832634,-2.577730703,49.3418,7.063623783,7.071090429,-2.793125,5.561726356,2.414685479,44.99999998 +140.7,50.42832697,-2.577729708,49.3699,7.063623819,7.070424203,-2.82,5.495754849,2.485560243,44.99999998 +140.71,50.42832761,-2.577728713,49.3982,7.067100049,7.070202086,-2.8465625,5.428635651,2.554267566,44.99999998 +140.72,50.42832824,-2.577727718,49.4268,7.077528657,7.070424077,-2.873125,5.360382741,2.620747515,44.99999998 +140.73,50.42832888,-2.577726723,49.4557,7.084481061,7.07131223,-2.898125,5.291010386,2.684942165,44.99999998 +140.74,50.42832952,-2.577725728,49.4848,7.077528701,7.072422438,-2.92125,5.220533083,2.74679548,44.99999998 +140.75,50.42833015,-2.577724732,49.5141,7.067100165,7.072422375,-2.943125,5.148965555,2.806253545,44.99999998 +140.76,50.42833079,-2.577723737,49.5437,7.063624021,7.071312043,-2.963125,5.076322699,2.863264507,44.99999998 +140.77,50.42833142,-2.577722742,49.5734,7.063624059,7.070423765,-2.98125,5.002619758,2.917778691,44.99999998 +140.78,50.42833206,-2.577721747,49.6033,7.067100273,7.07020165,-2.9984375,4.927872028,2.969748484,44.99999998 +140.79,50.42833269,-2.577720752,49.6334,7.07752887,7.070423643,-3.0146875,4.852095208,3.01912868,44.99999998 +140.8,50.42833333,-2.577719757,49.6636,7.084481291,7.071089743,-3.0296875,4.775305112,3.065876077,44.99999998 +140.81,50.42833397,-2.577718762,49.694,7.077528956,7.07153379,-3.043125,4.697517727,3.109950053,44.99999998 +140.82,50.4283346,-2.577717766,49.7245,7.067100424,7.071311675,-3.055,4.618749322,3.151312048,44.99999998 +140.83,50.42833524,-2.577716772,49.7551,7.063624261,7.071311615,-3.0665625,4.539016344,3.189926081,44.99999998 +140.84,50.42833587,-2.577715776,49.7858,7.06362428,7.071533608,-3.078125,4.458335464,3.22575846,44.99999998 +140.85,50.42833651,-2.577714781,49.8167,7.063624304,7.071089439,-3.0878125,4.376723527,3.258777903,44.99999998 +140.86,50.42833714,-2.577713786,49.8476,7.063624346,7.070423217,-3.094375,4.294197551,3.288955647,44.99999998 +140.87,50.42833778,-2.577712791,49.8786,7.06710059,7.070201103,-3.0984375,4.210774782,3.316265394,44.99999998 +140.88,50.42833841,-2.577711796,49.9096,7.07752921,7.070423097,-3.1015625,4.126472636,3.340683309,44.99999998 +140.89,50.42833905,-2.577710801,49.9406,7.084481625,7.071311252,-3.105,4.041308763,3.362188076,44.99999998 +140.9,50.42833969,-2.577709806,49.9717,7.077529265,7.072421462,-3.108125,3.955300865,3.380760961,44.99999998 +140.91,50.42834032,-2.57770881,50.0028,7.067100715,7.072421402,-3.1096875,3.868466991,3.396385807,44.99999998 +140.92,50.42834096,-2.577707815,50.0339,7.067100755,7.071311071,-3.1096875,3.780825247,3.409048919,44.99999998 +140.93,50.42834159,-2.57770682,50.065,7.077529377,7.070422795,-3.1078125,3.692393909,3.418739297,44.99999998 +140.94,50.42834223,-2.577705825,50.0961,7.084481802,7.07020068,-3.103125,3.603191485,3.425448518,44.99999998 +140.95,50.42834287,-2.57770483,50.1271,7.07752945,7.070422674,-3.0965625,3.513236539,3.429170624,44.99999998 +140.96,50.4283435,-2.577703835,50.158,7.067100902,7.071088775,-3.0903125,3.422547919,3.42990252,44.99999998 +140.97,50.42834414,-2.57770284,50.1889,7.063624737,7.071310769,-3.0846875,3.331144593,3.427643462,44.99999998 +140.98,50.42834477,-2.577701844,50.2197,7.063624767,7.070422492,-3.0778125,3.239045523,3.422395398,44.99999998 +140.99,50.42834541,-2.57770085,50.2505,7.063624806,7.070200378,-3.0678125,3.146270077,3.414163026,44.99999998 +141,50.42834604,-2.577699855,50.2811,7.06362485,7.071532641,-3.0546875,3.052837506,3.40295345,44.99999998 +141.01,50.42834668,-2.577698859,50.3116,7.067101085,7.072198742,-3.0403125,2.958767461,3.388776412,44.99999998 +141.02,50.42834731,-2.577697864,50.3419,7.077529696,7.071310465,-3.02625,2.864079482,3.371644286,44.99999998 +141.03,50.42834795,-2.577696869,50.3721,7.084482102,7.070422188,-3.0115625,2.768793335,3.351572085,44.99999998 +141.04,50.42834859,-2.577695874,50.4022,7.077529742,7.070200072,-2.9946875,2.672929016,3.328577283,44.99999998 +141.05,50.42834922,-2.577694879,50.432,7.067101206,7.070422064,-2.9765625,2.576506464,3.302679877,44.99999998 +141.06,50.42834986,-2.577693884,50.4617,7.063625061,7.071310219,-2.9584375,2.479545905,3.273902499,44.99999998 +141.07,50.42835049,-2.577692889,50.4912,7.063625101,7.072420427,-2.939375,2.38206745,3.242270187,44.99999998 +141.08,50.42835113,-2.577691893,50.5205,7.067101322,7.072420365,-2.9178125,2.284091552,3.207810614,44.99999998 +141.09,50.42835176,-2.577690898,50.5496,7.077529921,7.071310032,-2.8934375,2.185638667,3.170553747,44.99999998 +141.1,50.4283524,-2.577689903,50.5784,7.08448233,7.070421754,-2.868125,2.086729307,3.13053213,44.99999998 +141.11,50.42835304,-2.577688908,50.6069,7.077529982,7.070199636,-2.843125,1.987384212,3.087780654,44.99999998 +141.12,50.42835367,-2.577687913,50.6353,7.067101448,7.070421627,-2.8165625,1.887624009,3.042336564,44.99999998 +141.13,50.42835431,-2.577686918,50.6633,7.063625288,7.071087725,-2.7878125,1.787469669,2.994239565,44.99999998 +141.14,50.42835494,-2.577685923,50.691,7.063625306,7.071531769,-2.75875,1.686941989,2.943531482,44.99999998 +141.15,50.42835558,-2.577684927,50.7185,7.06710152,7.071309651,-2.7296875,1.586061998,2.890256606,44.99999998 +141.16,50.42835621,-2.577683933,50.7456,7.07753014,7.071309586,-2.699375,1.484850837,2.834461403,44.99999998 +141.17,50.42835685,-2.577682937,50.7725,7.084482574,7.071531575,-2.6665625,1.383329534,2.776194517,44.99999998 +141.18,50.42835749,-2.577681942,50.799,7.07753022,7.071087402,-2.63125,1.281519402,2.715506713,44.99999998 +141.19,50.42835812,-2.577680947,50.8251,7.067101664,7.070421174,-2.5953125,1.179441585,2.652450989,44.99999998 +141.2,50.42835876,-2.577679952,50.8509,7.063625497,7.070199054,-2.5596875,1.077117454,2.587082234,44.99999998 +141.21,50.42835939,-2.577678957,50.8763,7.063625524,7.070421041,-2.523125,0.974568436,2.519457515,44.99999998 +141.22,50.42836003,-2.577677962,50.9014,7.063625545,7.07130919,-2.485,0.871815847,2.449635847,44.99999998 +141.23,50.42836066,-2.577676967,50.926,7.063625569,7.072419393,-2.44625,0.768881172,2.37767802,44.99999998 +141.24,50.4283613,-2.577675971,50.9503,7.067101795,7.072419326,-2.4065625,0.665785953,2.303646831,44.99999998 +141.25,50.42836193,-2.577674976,50.9742,7.077530414,7.071308988,-2.3646875,0.562551736,2.227606794,44.99999998 +141.26,50.42836257,-2.577673981,50.9976,7.084482835,7.070420703,-2.3215625,0.459199947,2.149624316,44.99999998 +141.27,50.42836321,-2.577672986,51.0206,7.077530469,7.070198579,-2.2784375,0.35575236,2.069767292,44.99999998 +141.28,50.42836384,-2.577671991,51.0432,7.067101897,7.070420563,-2.2346875,0.252230403,1.988105394,44.99999998 +141.29,50.42836448,-2.577670996,51.0653,7.063625721,7.071086655,-2.1896875,0.148655791,1.90470984,44.99999998 +141.3,50.42836511,-2.577670001,51.087,7.063625757,7.071530693,-2.143125,0.045050124,1.819653338,44.99999998 +141.31,50.42836575,-2.577669005,51.1082,7.067101991,7.071308568,-2.095,-0.058564938,1.733010145,44.99999998 +141.32,50.42836638,-2.577668011,51.1289,7.077530602,7.071308496,-2.0465625,-0.16216774,1.644855661,44.99999998 +141.33,50.42836702,-2.577667015,51.1491,7.084483,7.071530477,-1.998125,-0.265736737,1.555266891,44.99999998 +141.34,50.42836766,-2.57766602,51.1689,7.077530617,7.071086296,-1.9484375,-0.369250157,1.464321873,44.99999998 +141.35,50.42836829,-2.577665025,51.1881,7.067102056,7.07042006,-1.8978125,-0.472686514,1.372099962,44.99999998 +141.36,50.42836893,-2.57766403,51.2068,7.063625901,7.070197933,-1.846875,-0.576024151,1.278681542,44.99999998 +141.37,50.42836956,-2.577663035,51.2251,7.063625936,7.070419913,-1.7946875,-0.679241523,1.18414809,44.99999998 +141.38,50.4283702,-2.57766204,51.2427,7.067102146,7.071308054,-1.7415625,-0.782317032,1.088582053,44.99999998 +141.39,50.42837083,-2.577661045,51.2599,7.077530733,7.072418247,-1.6884375,-0.885229133,0.992066739,44.99999998 +141.4,50.42837147,-2.577660049,51.2765,7.084483127,7.072418171,-1.634375,-0.987956397,0.894686374,44.99999998 +141.41,50.42837211,-2.577659054,51.2926,7.077530757,7.071307825,-1.5784375,-1.090477283,0.796525812,44.99999998 +141.42,50.42837274,-2.577658059,51.3081,7.067102206,7.070419531,-1.5215625,-1.192770532,0.697670654,44.99999998 +141.43,50.42837338,-2.577657064,51.323,7.063626044,7.070197399,-1.465,-1.294814602,0.598207128,44.99999998 +141.44,50.42837401,-2.577656069,51.3374,7.063626065,7.070419374,-1.408125,-1.396588293,0.498221925,44.99999998 +141.45,50.42837465,-2.577655074,51.3512,7.067102263,7.071085457,-1.3496875,-1.498070348,0.397802305,44.99999998 +141.46,50.42837528,-2.577654079,51.3644,7.077530843,7.071307431,-1.2903125,-1.599239511,0.29703576,44.99999998 +141.47,50.42837592,-2.577653083,51.377,7.084483247,7.070419134,-1.2315625,-1.700074697,0.196010237,44.99999998 +141.48,50.42837656,-2.577652089,51.389,7.07753089,7.070196999,-1.1734375,-1.800554879,0.094813743,44.99999998 +141.49,50.42837719,-2.577651094,51.4005,7.067102334,7.07152924,-1.1146875,-1.900659028,-0.00646537,44.99999998 +141.5,50.42837783,-2.577650098,51.4113,7.063626152,7.072195319,-1.0546875,-2.000366232,-0.107738927,44.99999998 +141.51,50.42837846,-2.577649103,51.4216,7.063626162,7.07130702,-0.9934375,-2.099655693,-0.20891846,44.99999998 +141.52,50.4283791,-2.577648108,51.4312,7.067102361,7.070418721,-0.93125,-2.198506669,-0.309915851,44.99999998 +141.53,50.42837973,-2.577647113,51.4402,7.077530939,7.070196582,-0.86875,-2.296898534,-0.410642977,44.99999998 +141.54,50.42838037,-2.577646118,51.4486,7.084483332,7.07041855,-0.8065625,-2.394810661,-0.511012005,44.99999998 +141.55,50.42838101,-2.577645123,51.4563,7.077530963,7.07130668,-0.7446875,-2.492222711,-0.610935443,44.99999998 +141.56,50.42838164,-2.577644128,51.4635,7.067102402,7.072416862,-0.681875,-2.589114286,-0.710326145,44.99999998 +141.57,50.42838228,-2.577643132,51.47,7.063626214,7.072416775,-0.618125,-2.685465161,-0.809097423,44.99999998 +141.58,50.42838291,-2.577642137,51.4758,7.063626205,7.071306418,-0.5553125,-2.781255224,-0.90716316,44.99999998 +141.59,50.42838355,-2.577641142,51.4811,7.063626205,7.070418113,-0.493125,-2.876464423,-1.004437815,44.99999998 +141.6,50.42838418,-2.577640147,51.4857,7.06362622,7.07019597,-0.4296875,-2.971072933,-1.100836589,44.99999998 +141.61,50.42838482,-2.577639152,51.4897,7.067102428,7.070417934,-0.365,-3.06506093,-1.196275429,44.99999998 +141.62,50.42838545,-2.577638157,51.493,7.077531021,7.071084005,-0.3,-3.158408875,-1.290671085,44.99999998 +141.63,50.42838609,-2.577637162,51.4957,7.084483417,7.07152802,-0.2353125,-3.251097232,-1.383941281,44.99999998 +141.64,50.42838673,-2.577636166,51.4977,7.077531027,7.071305873,-0.1715625,-3.343106634,-1.476004655,44.99999998 +141.65,50.42838736,-2.577635172,51.4991,7.067102431,7.07130578,-0.108125,-3.434417829,-1.566780879,44.99999998 +141.66,50.428388,-2.577634176,51.4999,7.063626232,7.07152774,-0.043125,-3.525011795,-1.656190886,44.99999998 +141.67,50.42838863,-2.577633181,51.5,7.063626244,7.071083538,0.023125,-3.614869683,-1.744156695,44.99999998 +141.68,50.42838927,-2.577632186,51.4994,7.067102451,7.070417282,0.088125,-3.703972584,-1.830601531,44.99999998 +141.69,50.4283899,-2.577631191,51.4982,7.077531032,7.070195132,0.1515625,-3.792301935,-1.915450106,44.99999998 +141.7,50.42839054,-2.577630196,51.4964,7.084483404,7.070417089,0.215,-3.879839401,-1.998628337,44.99999998 +141.71,50.42839118,-2.577629201,51.4939,7.077531006,7.071305207,0.2784375,-3.966566533,-2.080063745,44.99999998 +141.72,50.42839181,-2.577628206,51.4908,7.067102432,7.072415378,0.3415625,-4.05246534,-2.159685341,44.99999998 +141.73,50.42839245,-2.57762721,51.4871,7.063626249,7.07241528,0.4053125,-4.13751783,-2.237423624,44.99999998 +141.74,50.42839308,-2.577626215,51.4827,7.063626252,7.071304911,0.47,-4.221706243,-2.313210814,44.99999998 +141.75,50.42839372,-2.57762522,51.4777,7.067102435,7.070416595,0.5346875,-4.305012989,-2.386980906,44.99999998 +141.76,50.42839435,-2.577624225,51.472,7.077530997,7.07019444,0.5984375,-4.387420764,-2.4586695,44.99999998 +141.77,50.42839499,-2.57762323,51.4657,7.084483368,7.070416392,0.6615625,-4.468912207,-2.528214086,44.99999998 +141.78,50.42839563,-2.577622235,51.4588,7.077530979,7.071082451,0.725,-4.549470417,-2.595553988,44.99999998 +141.79,50.42839626,-2.57762124,51.4512,7.067102404,7.071526456,0.788125,-4.629078491,-2.660630591,44.99999998 +141.8,50.4283969,-2.577620244,51.443,7.063626206,7.071304299,0.8496875,-4.70771987,-2.72338706,44.99999998 +141.81,50.42839753,-2.57761925,51.4342,7.06362619,7.071304194,0.91,-4.785378112,-2.783768733,44.99999998 +141.82,50.42839817,-2.577618254,51.4248,7.063626172,7.071526143,0.9703125,-4.862036942,-2.841722841,44.99999998 +141.83,50.4283988,-2.577617259,51.4148,7.063626157,7.07108193,1.0315625,-4.937680435,-2.897198964,44.99999998 +141.84,50.42839944,-2.577616264,51.4042,7.067102345,7.070415662,1.093125,-5.012292775,-2.950148744,44.99999998 +141.85,50.42840007,-2.577615269,51.3929,7.077530923,7.070193501,1.1534375,-5.085858321,-3.000525886,44.99999998 +141.86,50.42840071,-2.577614274,51.3811,7.084483301,7.070415447,1.213125,-5.158361776,-3.048286502,44.99999998 +141.87,50.42840135,-2.577613279,51.3687,7.0775309,7.071303553,1.2734375,-5.229787955,-3.093389052,44.99999998 +141.88,50.42840198,-2.577612284,51.3556,7.067102301,7.072413714,1.3328125,-5.300121962,-3.135794059,44.99999998 +141.89,50.42840262,-2.577611288,51.342,7.063626086,7.072413604,1.3896875,-5.36934913,-3.175464626,44.99999998 +141.9,50.42840325,-2.577610293,51.3278,7.063626066,7.071303225,1.4453125,-5.437454961,-3.212366087,44.99999998 +141.91,50.42840389,-2.577609298,51.3131,7.067102249,7.070414899,1.5015625,-5.504425248,-3.246466415,44.99999998 +141.92,50.42840452,-2.577608303,51.2978,7.077530825,7.070192734,1.5584375,-5.570245952,-3.277735701,44.99999998 +141.93,50.42840516,-2.577607308,51.2819,7.084483203,7.070414675,1.6146875,-5.634903437,-3.306146788,44.99999998 +141.94,50.4284058,-2.577606313,51.2655,7.077530793,7.071302777,1.6696875,-5.698384181,-3.331674865,44.99999998 +141.95,50.42840643,-2.577605318,51.2485,7.067102177,7.072190879,1.7234375,-5.760674835,-3.354297645,44.99999998 +141.96,50.42840707,-2.577604322,51.231,7.063625957,7.071524603,1.7765625,-5.821762449,-3.373995418,44.99999998 +141.97,50.4284077,-2.577603327,51.213,7.063625949,7.070192166,1.8296875,-5.881634304,-3.390751054,44.99999998 +141.98,50.42840834,-2.577602333,51.1944,7.067102139,7.070414104,1.8815625,-5.940277795,-3.404549883,44.99999998 +141.99,50.42840897,-2.577601337,51.1753,7.077530705,7.071302204,1.9315625,-5.997680775,-3.415379931,44.99999998 +142,50.42840961,-2.577600342,51.1558,7.08448306,7.071080034,1.9815625,-6.053831211,-3.423231687,44.99999998 +142.01,50.42841025,-2.577599347,51.1357,7.077530632,7.070413755,2.0315625,-6.108717417,-3.428098333,44.99999998 +142.02,50.42841088,-2.577598352,51.1151,7.067102027,7.070191584,2.0796875,-6.162327817,-3.42997563,44.99999998 +142.03,50.42841152,-2.577597357,51.0941,7.063625828,7.070413521,2.1265625,-6.214651355,-3.428861914,44.99999998 +142.04,50.42841215,-2.577596362,51.0726,7.063625819,7.071301617,2.1734375,-6.265677028,-3.424758219,44.99999998 +142.05,50.42841279,-2.577595367,51.0506,7.067101985,7.072411767,2.2196875,-6.31539418,-3.417668095,44.99999998 +142.06,50.42841342,-2.577594371,51.0282,7.077530528,7.072411647,2.2646875,-6.36379244,-3.407597674,44.99999998 +142.07,50.42841406,-2.577593376,51.0053,7.08448288,7.071301258,2.308125,-6.410861725,-3.39455578,44.99999998 +142.08,50.4284147,-2.577592381,50.982,7.077530474,7.070412923,2.35,-6.45659218,-3.378553813,44.99999998 +142.09,50.42841533,-2.577591386,50.9583,7.067101881,7.070190748,2.3915625,-6.500974236,-3.359605641,44.99999998 +142.1,50.42841597,-2.577590391,50.9342,7.063625665,7.07041268,2.433125,-6.543998668,-3.337727878,44.99999998 +142.11,50.4284166,-2.577589396,50.9096,7.063625632,7.07107872,2.473125,-6.585656481,-3.312939603,44.99999998 +142.12,50.42841724,-2.577588401,50.8847,7.067101791,7.071522705,2.51125,-6.625938966,-3.285262361,44.99999998 +142.13,50.42841787,-2.577587405,50.8594,7.077530341,7.071300529,2.5484375,-6.664837644,-3.254720273,44.99999998 +142.14,50.42841851,-2.577586411,50.8337,7.084482706,7.071300406,2.5846875,-6.70234455,-3.221340096,44.99999998 +142.15,50.42841915,-2.577585415,50.8077,7.077530297,7.071522337,2.6196875,-6.738451663,-3.185150821,44.99999998 +142.16,50.42841978,-2.57758442,50.7813,7.067101688,7.071300159,2.6534375,-6.773151591,-3.146184076,44.99999998 +142.17,50.42842042,-2.577583425,50.7546,7.063625468,7.071300034,2.68625,-6.806437058,-3.10447378,44.99999998 +142.18,50.42842105,-2.57758243,50.7276,7.063625443,7.07129991,2.7184375,-6.838301018,-3.060056373,44.99999998 +142.19,50.42842169,-2.577581434,50.7002,7.063625409,7.07041157,2.7496875,-6.868736937,-3.012970529,44.99999998 +142.2,50.42842232,-2.57758044,50.6726,7.063625364,7.070189391,2.7796875,-6.897738399,-2.96325733,44.99999998 +142.21,50.42842296,-2.577579445,50.6446,7.067101521,7.071521588,2.808125,-6.92529933,-2.910960092,44.99999998 +142.22,50.42842359,-2.577578449,50.6164,7.077530083,7.072187623,2.8346875,-6.951414059,-2.856124536,44.99999998 +142.23,50.42842423,-2.577577454,50.5879,7.084482455,7.071299282,2.86,-6.976077027,-2.798798332,44.99999998 +142.24,50.42842487,-2.577576459,50.5592,7.077530041,7.070410941,2.8846875,-6.999283136,-2.739031558,44.99999998 +142.25,50.4284255,-2.577575464,50.5302,7.067101415,7.07018876,2.908125,-7.021027572,-2.676876294,44.99999998 +142.26,50.42842614,-2.577574469,50.501,7.063625171,7.070410688,2.93,-7.041305694,-2.612386743,44.99999998 +142.27,50.42842677,-2.577573474,50.4716,7.06362514,7.071298775,2.95125,-7.060113377,-2.545619169,44.99999998 +142.28,50.42842741,-2.577572479,50.442,7.067101319,7.072408916,2.9715625,-7.077446611,-2.476631785,44.99999998 +142.29,50.42842804,-2.577571483,50.4121,7.077529881,7.072408788,2.9896875,-7.093301843,-2.40548475,44.99999998 +142.3,50.42842868,-2.577570488,50.3822,7.084482232,7.071298392,3.0065625,-7.107675693,-2.332240118,44.99999998 +142.31,50.42842932,-2.577569493,50.352,7.077529797,7.070410049,3.023125,-7.120565238,-2.256961657,44.99999998 +142.32,50.42842995,-2.577568498,50.3217,7.067101171,7.070187867,3.0378125,-7.131967728,-2.179715143,44.99999998 +142.33,50.42843059,-2.577567503,50.2912,7.063624951,7.070187739,3.05,-7.141880815,-2.100567899,44.99999998 +142.34,50.42843122,-2.577566508,50.2607,7.063624934,7.070187611,3.0615625,-7.150302377,-2.019588909,44.99999998 +142.35,50.42843186,-2.577565513,50.23,7.067101098,7.070409536,3.073125,-7.157230698,-1.936848819,44.99999998 +142.36,50.42843249,-2.577564518,50.1992,7.077529639,7.071297622,3.0828125,-7.162664343,-1.852419763,44.99999998 +142.37,50.42843313,-2.577563523,50.1683,7.084481982,7.072407761,3.0896875,-7.16660211,-1.766375311,44.99999998 +142.38,50.42843377,-2.577562527,50.1374,7.077529551,7.072407631,3.095,-7.169043254,-1.678790633,44.99999998 +142.39,50.4284344,-2.577561532,50.1064,7.067100938,7.071297234,3.1,-7.169987259,-1.589741991,44.99999998 +142.4,50.42843504,-2.577560537,50.0754,7.063624728,7.070408891,3.1046875,-7.169433897,-1.499307077,44.99999998 +142.41,50.42843567,-2.577559542,50.0443,7.063624708,7.070186709,3.108125,-7.167383281,-1.407564732,44.99999998 +142.42,50.42843631,-2.577558547,50.0132,7.063624674,7.070408634,3.1096875,-7.163835812,-1.314594995,44.99999998 +142.43,50.42843694,-2.577557552,49.9821,7.063624638,7.071296719,3.1096875,-7.158792294,-1.220478885,44.99999998 +142.44,50.42843758,-2.577556557,49.951,7.067100792,7.072184804,3.108125,-7.152253814,-1.125298506,44.99999998 +142.45,50.42843821,-2.577555561,49.9199,7.077529323,7.071518514,3.1046875,-7.144221576,-1.029136879,44.99999998 +142.46,50.42843885,-2.577554566,49.8889,7.08448167,7.070186064,3.1,-7.134697414,-0.932077829,44.99999998 +142.47,50.42843949,-2.577553572,49.8579,7.07752926,7.070407988,3.095,-7.123683274,-0.834205923,44.99999998 +142.48,50.42844012,-2.577552576,49.827,7.06710066,7.071296073,3.089375,-7.111181392,-0.735606648,44.99999998 +142.49,50.42844076,-2.577551581,49.7961,7.067100624,7.071295945,3.0815625,-7.097194461,-0.636365888,44.99999998 +142.5,50.42844139,-2.577550586,49.7653,7.077529155,7.071295816,3.07125,-7.081725403,-0.53657022,44.99999998 +142.51,50.42844203,-2.577549591,49.7347,7.084481503,7.071295687,3.06,-7.064777368,-0.436306616,44.99999998 +142.52,50.42844267,-2.577548595,49.7041,7.077529094,7.070407344,3.048125,-7.046353968,-0.335662626,44.99999998 +142.53,50.4284433,-2.577547601,49.6737,7.067100496,7.070185163,3.0346875,-7.02645904,-0.234725854,44.99999998 +142.54,50.42844394,-2.577546606,49.6434,7.063624276,7.071517356,3.02,-7.005096709,-0.133584422,44.99999998 +142.55,50.42844457,-2.57754561,49.6133,7.063624237,7.072183389,3.0046875,-6.982271446,-0.032326508,44.99999998 +142.56,50.42844521,-2.577544615,49.5833,7.063624189,7.071295047,2.9878125,-6.957988062,0.068959596,44.99999998 +142.57,50.42844584,-2.57754362,49.5535,7.063624144,7.070406705,2.968125,-6.932251543,0.170185539,44.99999998 +142.58,50.42844648,-2.577542625,49.5239,7.067100305,7.070184525,2.946875,-6.905067331,0.271263144,44.99999998 +142.59,50.42844711,-2.57754163,49.4946,7.077528866,7.07040645,2.9265625,-6.876441099,0.372104174,44.99999998 +142.6,50.42844775,-2.577540635,49.4654,7.084481235,7.071294537,2.90625,-6.846378806,0.472620681,44.99999998 +142.61,50.42844839,-2.57753964,49.4364,7.077528815,7.072404679,2.8828125,-6.814886696,0.572725117,44.99999998 +142.62,50.42844902,-2.577538644,49.4077,7.067100188,7.072404552,2.8565625,-6.781971417,0.672330105,44.99999998 +142.63,50.42844966,-2.577537649,49.3793,7.063623957,7.071294158,2.83,-6.747639786,0.771348786,44.99999998 +142.64,50.42845029,-2.577536654,49.3511,7.063623938,7.070405818,2.803125,-6.711899022,0.869694872,44.99999998 +142.65,50.42845093,-2.577535659,49.3232,7.067100117,7.070405693,2.7746875,-6.674756575,0.967282533,44.99999998 +142.66,50.42845156,-2.577534664,49.2956,7.077528673,7.071071729,2.745,-6.636220178,1.064026743,44.99999998 +142.67,50.4284522,-2.577533669,49.2683,7.084481023,7.071293657,2.7146875,-6.596297912,1.159843106,44.99999998 +142.68,50.42845284,-2.577532673,49.2413,7.077528592,7.070405318,2.683125,-6.554998025,1.254648083,44.99999998 +142.69,50.42845347,-2.577531679,49.2146,7.067099973,7.07018314,2.6496875,-6.512329285,1.34835894,44.99999998 +142.7,50.42845411,-2.577530684,49.1883,7.063623758,7.071515337,2.6146875,-6.468300515,1.44089403,44.99999998 +142.71,50.42845474,-2.577529688,49.1623,7.063623745,7.072181375,2.5784375,-6.422920883,1.532172681,44.99999998 +142.72,50.42845538,-2.577528693,49.1367,7.067099913,7.071293038,2.5415625,-6.376199899,1.622115195,44.99999998 +142.73,50.42845601,-2.577527698,49.1115,7.077528452,7.070404702,2.5046875,-6.328147361,1.710643248,44.99999998 +142.74,50.42845665,-2.577526703,49.0866,7.0844808,7.070182526,2.4665625,-6.278773296,1.797679548,44.99999998 +142.75,50.42845729,-2.577525708,49.0621,7.077528394,7.070404457,2.42625,-6.22808796,1.883148292,44.99999998 +142.76,50.42845792,-2.577524713,49.0381,7.067099805,7.07129255,2.385,-6.176101952,1.966974825,44.99999998 +142.77,50.42845856,-2.577523718,49.0144,7.063623591,7.072402697,2.3434375,-6.122826159,2.049086209,44.99999998 +142.78,50.42845919,-2.577522722,48.9912,7.063623561,7.072402576,2.30125,-6.068271696,2.129410709,44.99999998 +142.79,50.42845983,-2.577521727,48.9684,7.063623534,7.071292189,2.258125,-6.012449965,2.207878368,44.99999998 +142.8,50.42846046,-2.577520732,48.946,7.063623508,7.070403857,2.213125,-5.955372597,2.284420716,44.99999998 +142.81,50.4284611,-2.577519737,48.9241,7.067099671,7.070181684,2.1665625,-5.897051509,2.358971005,44.99999998 +142.82,50.42846173,-2.577518742,48.9027,7.077528223,7.070403619,2.12,-5.837498907,2.431464204,44.99999998 +142.83,50.42846237,-2.577517747,48.8817,7.084480591,7.071069661,2.073125,-5.776727221,2.501837172,44.99999998 +142.84,50.42846301,-2.577516752,48.8612,7.077528192,7.071513651,2.0246875,-5.714749173,2.570028489,44.99999998 +142.85,50.42846364,-2.577515756,48.8412,7.067099598,7.071291481,1.9746875,-5.651577654,2.635978739,44.99999998 +142.86,50.42846428,-2.577514762,48.8217,7.06362338,7.071291364,1.9234375,-5.587225842,2.699630339,44.99999998 +142.87,50.42846491,-2.577513766,48.8027,7.063623344,7.071513302,1.8715625,-5.521707259,2.760927828,44.99999998 +142.88,50.42846555,-2.577512771,48.7843,7.06709951,7.07106908,1.82,-5.455035483,2.819817747,44.99999998 +142.89,50.42846618,-2.577511776,48.7663,7.077528081,7.070402806,1.768125,-5.387224553,2.876248705,44.99999998 +142.9,50.42846682,-2.577510781,48.7489,7.084480464,7.070180638,1.7146875,-5.318288506,2.930171596,44.99999998 +142.91,50.42846746,-2.577509786,48.732,7.077528065,7.070402578,1.6603125,-5.248241837,2.981539325,44.99999998 +142.92,50.42846809,-2.577508791,48.7157,7.067099455,7.071290679,1.60625,-5.177099157,3.030307086,44.99999998 +142.93,50.42846873,-2.577507796,48.6999,7.063623228,7.072400834,1.5515625,-5.104875249,3.076432366,44.99999998 +142.94,50.42846936,-2.5775068,48.6846,7.063623212,7.072400722,1.4946875,-5.031585295,3.119874943,44.99999998 +142.95,50.42847,-2.577505805,48.67,7.067099407,7.071290345,1.436875,-4.957244594,3.160596944,44.99999998 +142.96,50.42847063,-2.57750481,48.6559,7.077527984,7.070402021,1.38,-4.881868559,3.198562904,44.99999998 +142.97,50.42847127,-2.577503815,48.6424,7.084480351,7.070179858,1.323125,-4.805473059,3.233739647,44.99999998 +142.98,50.42847191,-2.57750282,48.6294,7.077527936,7.070401802,1.2646875,-4.728073967,3.266096522,44.99999998 +142.99,50.42847254,-2.577501825,48.6171,7.067099334,7.071289907,1.205,-4.649687496,3.295605281,44.99999998 +143,50.42847318,-2.57750083,48.6053,7.063623135,7.072178013,1.145,-4.570330034,3.322240255,44.99999998 +143.01,50.42847381,-2.577499834,48.5942,7.063623139,7.071511746,1.0846875,-4.490018024,3.345978183,44.99999998 +143.02,50.42847445,-2.577498839,48.5836,7.067099325,7.070179319,1.0234375,-4.408768426,3.366798324,44.99999998 +143.03,50.42847508,-2.577497845,48.5737,7.077527887,7.070401267,0.9615625,-4.326598085,3.384682628,44.99999998 +143.04,50.42847572,-2.577496849,48.5644,7.084480254,7.071289376,0.9003125,-4.243524133,3.399615398,44.99999998 +143.05,50.42847636,-2.577495854,48.5557,7.077527855,7.071067217,0.8396875,-4.159564043,3.411583684,44.99999998 +143.06,50.42847699,-2.577494859,48.5476,7.067099273,7.070400954,0.778125,-4.074735235,3.420577002,44.99999998 +143.07,50.42847763,-2.577493864,48.5401,7.06362308,7.070178798,0.715,-3.989055528,3.426587558,44.99999998 +143.08,50.42847826,-2.577492869,48.5333,7.063623075,7.07040075,0.6515625,-3.902542682,3.429610025,44.99999998 +143.09,50.4284789,-2.577491874,48.5271,7.067099264,7.071288861,0.5884375,-3.815214919,3.429641824,44.99999998 +143.1,50.42847953,-2.577490879,48.5215,7.077527841,7.072399027,0.525,-3.727090343,3.426682956,44.99999998 +143.11,50.42848017,-2.577489883,48.5166,7.084480218,7.072398927,0.4615625,-3.638187404,3.420735998,44.99999998 +143.12,50.42848081,-2.577488888,48.5123,7.077527813,7.071288561,0.398125,-3.548524723,3.411806049,44.99999998 +143.13,50.42848144,-2.577487893,48.5086,7.067099224,7.070400248,0.3334375,-3.458120978,3.39990096,44.99999998 +143.14,50.42848208,-2.577486898,48.5056,7.06362304,7.07040015,0.268125,-3.36699502,3.385031101,44.99999998 +143.15,50.42848271,-2.577485903,48.5033,7.063623051,7.071288266,0.20375,-3.275165928,3.367209478,44.99999998 +143.16,50.42848335,-2.577484908,48.5015,7.063623048,7.072176383,0.14,-3.18265284,3.346451618,44.99999998 +143.17,50.42848398,-2.577483912,48.5005,7.063623032,7.071510127,0.07625,-3.089475063,3.32277557,44.99999998 +143.18,50.42848462,-2.577482917,48.5,7.067099219,7.070177713,0.011875,-2.995652135,3.296201959,44.99999998 +143.19,50.42848525,-2.577481923,48.5002,7.077527809,7.070399672,-0.0534375,-2.901203595,3.266754106,44.99999998 +143.2,50.42848589,-2.577480927,48.5011,7.084480212,7.071287791,-0.118125,-2.806149209,3.234457564,44.99999998 +143.21,50.42848653,-2.577479932,48.5026,7.077527835,7.071287698,-0.1815625,-2.710508745,3.199340465,44.99999998 +143.22,50.42848716,-2.577478937,48.5047,7.067099254,7.071287606,-0.2453125,-2.614302255,3.161433577,44.99999998 +143.23,50.4284878,-2.577477942,48.5075,7.063623049,7.071287514,-0.31,-2.517549795,3.120769845,44.99999998 +143.24,50.42848843,-2.577476946,48.5109,7.063623043,7.07039921,-0.3746875,-2.420271531,3.077384736,44.99999998 +143.25,50.42848907,-2.577475952,48.515,7.067099247,7.070177066,-0.4384375,-2.32248786,3.031316122,44.99999998 +143.26,50.4284897,-2.577474957,48.5197,7.077527847,7.071509296,-0.5015625,-2.224219181,2.98260411,44.99999998 +143.27,50.42849034,-2.577473961,48.525,7.084480242,7.072175368,-0.565,-2.125486005,2.93129127,44.99999998 +143.28,50.42849098,-2.577472966,48.531,7.07752785,7.071287066,-0.6284375,-2.026308959,2.877422294,44.99999998 +143.29,50.42849161,-2.577471971,48.5376,7.067099269,7.070398766,-0.69125,-1.926708726,2.821044164,44.99999998 +143.3,50.42849225,-2.577470976,48.5448,7.063623091,7.070176626,-0.7534375,-1.826706105,2.762206039,44.99999998 +143.31,50.42849288,-2.577469981,48.5527,7.063623116,7.070398594,-0.8153125,-1.726322009,2.700959257,44.99999998 +143.32,50.42849352,-2.577468986,48.5611,7.067099324,7.071286722,-0.878125,-1.625577407,2.63735716,44.99999998 +143.33,50.42849415,-2.577467991,48.5702,7.077527909,7.072396903,-0.9415625,-1.524493328,2.571455268,44.99999998 +143.34,50.42849479,-2.577466995,48.58,7.084480302,7.072396819,-1.0028125,-1.423090856,2.503310991,44.99999998 +143.35,50.42849543,-2.577466,48.5903,7.077527919,7.071286469,-1.061875,-1.321391192,2.432983802,44.99999998 +143.36,50.42849606,-2.577465005,48.6012,7.067099345,7.070398173,-1.121875,-1.21941559,2.360535065,44.99999998 +143.37,50.4284967,-2.57746401,48.6127,7.063623172,7.070176038,-1.183125,-1.117185309,2.286027863,44.99999998 +143.38,50.42849733,-2.577463015,48.6249,7.063623202,7.070398011,-1.243125,-1.01472172,2.209527226,44.99999998 +143.39,50.42849797,-2.57746202,48.6376,7.063623223,7.07106409,-1.30125,-0.91204625,2.131099846,44.99999998 +143.4,50.4284986,-2.577461025,48.6509,7.063623239,7.071508117,-1.35875,-0.809180273,2.050814078,44.99999998 +143.41,50.42849924,-2.577460029,48.6648,7.067099441,7.071285984,-1.41625,-0.70614533,1.968739993,44.99999998 +143.42,50.42849987,-2.577459035,48.6792,7.077528021,7.071285905,-1.4734375,-0.602962907,1.884949156,44.99999998 +143.43,50.42850051,-2.577458039,48.6943,7.084480418,7.071507881,-1.53,-0.499654549,1.799514617,44.99999998 +143.44,50.42850115,-2.577457044,48.7098,7.077528061,7.071063697,-1.58625,-0.396241912,1.712510861,44.99999998 +143.45,50.42850178,-2.577456049,48.726,7.067099517,7.07039746,-1.641875,-0.292746426,1.624013805,44.99999998 +143.46,50.42850242,-2.577455054,48.7427,7.063623347,7.07017533,-1.69625,-0.189189862,1.534100513,44.99999998 +143.47,50.42850305,-2.577454059,48.7599,7.063623354,7.070397308,-1.75,-0.085593821,1.442849535,44.99999998 +143.48,50.42850369,-2.577453064,48.7777,7.06709955,7.071285446,-1.803125,0.018020153,1.350340343,44.99999998 +143.49,50.42850432,-2.577452069,48.796,7.07752815,7.072395638,-1.8546875,0.121630346,1.256653607,44.99999998 +143.5,50.42850496,-2.577451073,48.8148,7.084480575,7.072395565,-1.905,0.225215156,1.16187109,44.99999998 +143.51,50.4285056,-2.577450078,48.8341,7.077528225,7.071285225,-1.955,0.328752927,1.066075354,44.99999998 +143.52,50.42850623,-2.577449083,48.8539,7.067099664,7.070396939,-2.005,0.432222,0.969350051,44.99999998 +143.53,50.42850687,-2.577448088,48.8742,7.063623479,7.070174813,-2.0546875,0.535600832,0.871779407,44.99999998 +143.54,50.4285075,-2.577447093,48.895,7.063623489,7.070396795,-2.103125,0.638867823,0.773448562,44.99999998 +143.55,50.42850814,-2.577446098,48.9163,7.067099707,7.071284937,-2.1496875,0.742001372,0.674443288,44.99999998 +143.56,50.42850877,-2.577445103,48.938,7.077528324,7.072173079,-2.195,0.844979993,0.574849874,44.99999998 +143.57,50.42850941,-2.577444107,48.9602,7.084480751,7.071506849,-2.24,0.947782144,0.474755178,44.99999998 +143.58,50.42851005,-2.577443112,48.9828,7.077528397,7.070174459,-2.2846875,1.050386394,0.374246521,44.99999998 +143.59,50.42851068,-2.577442118,49.0059,7.067099838,7.070396444,-2.3284375,1.152771202,0.273411449,44.99999998 +143.6,50.42851132,-2.577441122,49.0294,7.063623656,7.071284588,-2.37125,1.25491531,0.172338027,44.99999998 +143.61,50.42851195,-2.577440127,49.0533,7.063623672,7.071062468,-2.413125,1.356797348,0.071114261,44.99999998 +143.62,50.42851259,-2.577439132,49.0777,7.0670999,7.07039624,-2.453125,1.458396057,-0.030171442,44.99999998 +143.63,50.42851322,-2.577438137,49.1024,7.077528523,7.070396173,-2.49125,1.559690183,-0.131430903,44.99999998 +143.64,50.42851386,-2.577437142,49.1275,7.08448094,7.071284318,-2.5284375,1.660658582,-0.232575716,44.99999998 +143.65,50.4285145,-2.577436147,49.153,7.077528569,7.072394518,-2.565,1.761280169,-0.333517759,44.99999998 +143.66,50.42851513,-2.577435151,49.1788,7.067100008,7.072394451,-2.60125,1.861533975,-0.434168911,44.99999998 +143.67,50.42851577,-2.577434156,49.205,7.063623852,7.071284119,-2.6365625,1.961398972,-0.534441509,44.99999998 +143.68,50.4285164,-2.577433161,49.2316,7.063623897,7.070395841,-2.6696875,2.060854361,-0.634248065,44.99999998 +143.69,50.42851704,-2.577432166,49.2584,7.067100126,7.070173724,-2.7015625,2.159879401,-0.733501543,44.99999998 +143.7,50.42851767,-2.577431171,49.2856,7.077528732,7.070395713,-2.7334375,2.258453352,-0.832115372,44.99999998 +143.71,50.42851831,-2.577430176,49.3131,7.084481147,7.071283861,-2.7646875,2.356555644,-0.930003607,44.99999998 +143.72,50.42851895,-2.577429181,49.3409,7.07752879,7.07217201,-2.7946875,2.454165823,-1.02708082,44.99999998 +143.73,50.42851958,-2.577428185,49.369,7.067100236,7.071505787,-2.8228125,2.551263491,-1.123262443,44.99999998 +143.74,50.42852022,-2.57742719,49.3974,7.06362407,7.070173404,-2.848125,2.647828308,-1.218464595,44.99999998 +143.75,50.42852085,-2.577426196,49.426,7.063624107,7.070395394,-2.8715625,2.743840221,-1.312604196,44.99999998 +143.76,50.42852149,-2.5774252,49.4548,7.063624149,7.071283544,-2.8953125,2.839279061,-1.405599143,44.99999998 +143.77,50.42852212,-2.577424205,49.4839,7.063624188,7.071283482,-2.9196875,2.934125005,-1.497368475,44.99999998 +143.78,50.42852276,-2.57742321,49.5132,7.067100411,7.07128342,-2.9428125,3.02835817,-1.587831979,44.99999998 +143.79,50.42852339,-2.577422215,49.5428,7.077529009,7.071283357,-2.9628125,3.121958905,-1.676910931,44.99999998 +143.8,50.42852403,-2.577421219,49.5725,7.084481423,7.070395083,-2.98,3.214907671,-1.764527579,44.99999998 +143.81,50.42852467,-2.577420225,49.6024,7.077529081,7.070172968,-2.996875,3.307185045,-1.85060555,44.99999998 +143.82,50.4285253,-2.57741923,49.6324,7.06710055,7.071505226,-3.0146875,3.398771718,-1.935069785,44.99999998 +143.83,50.42852594,-2.577418234,49.6627,7.063624395,7.072171324,-3.03125,3.489648611,-2.017846544,44.99999998 +143.84,50.42852657,-2.577417239,49.6931,7.063624417,7.071283051,-3.044375,3.579796759,-2.098863751,44.99999998 +143.85,50.42852721,-2.577416244,49.7236,7.067100627,7.070394778,-3.055,3.669197312,-2.178050701,44.99999998 +143.86,50.42852784,-2.577415249,49.7542,7.077529242,7.070172663,-3.065,3.757831591,-2.25533841,44.99999998 +143.87,50.42852848,-2.577414254,49.7849,7.084481682,7.070394655,-3.075,3.84568109,-2.330659384,44.99999998 +143.88,50.42852912,-2.577413259,49.8157,7.077529343,7.071282807,-3.0846875,3.932727474,-2.403947963,44.99999998 +143.89,50.42852975,-2.577412264,49.8466,7.067100793,7.072393012,-3.093125,4.01895258,-2.475140318,44.99999998 +143.9,50.42853039,-2.577411268,49.8776,7.063624619,7.072392952,-3.0996875,4.10433836,-2.544174284,44.99999998 +143.91,50.42853102,-2.577410273,49.9086,7.063624643,7.071282626,-3.1046875,4.188866996,-2.6109897,44.99999998 +143.92,50.42853166,-2.577409278,49.9397,7.067100879,7.070394354,-3.108125,4.272520839,-2.675528296,44.99999998 +143.93,50.42853229,-2.577408283,49.9708,7.07752951,7.07017224,-3.1096875,4.355282415,-2.737733808,44.99999998 +143.94,50.42853293,-2.577407288,50.0019,7.084481937,7.070394233,-3.1096875,4.437134478,-2.79755192,44.99999998 +143.95,50.42853357,-2.577406293,50.033,7.077529579,7.071060331,-3.108125,4.518059839,-2.854930549,44.99999998 +143.96,50.4285342,-2.577405298,50.0641,7.067101024,7.071504378,-3.105,4.598041711,-2.909819677,44.99999998 +143.97,50.42853484,-2.577404302,50.0951,7.063624861,7.071282265,-3.1015625,4.677063362,-2.962171346,44.99999998 +143.98,50.42853547,-2.577403308,50.1261,7.063624901,7.071282204,-3.098125,4.755108236,-3.011940007,44.99999998 +143.99,50.42853611,-2.577402312,50.1571,7.067101136,7.071504197,-3.0928125,4.832160058,-3.059082173,44.99999998 +144,50.42853674,-2.577401317,50.188,7.077529755,7.071282083,-3.0846875,4.90820273,-3.103556818,44.99999998 +144.01,50.42853738,-2.577400322,50.2188,7.084482177,7.071282023,-3.075,4.983220438,-3.14532504,44.99999998 +144.02,50.42853802,-2.577399327,50.2495,7.077529822,7.071281962,-3.065,5.057197426,-3.184350571,44.99999998 +144.03,50.42853865,-2.577398331,50.2801,7.067101269,7.070393688,-3.0546875,5.13011828,-3.220599261,44.99999998 +144.04,50.42853929,-2.577397337,50.3106,7.063625105,7.070171574,-3.043125,5.201967818,-3.254039542,44.99999998 +144.05,50.42853992,-2.577396342,50.341,7.063625144,7.071503832,-3.029375,5.27273097,-3.284642249,44.99999998 +144.06,50.42854056,-2.577395346,50.3712,7.067101379,7.07216993,-3.013125,5.342392955,-3.312380683,44.99999998 +144.07,50.42854119,-2.577394351,50.4013,7.077529995,7.071281657,-2.995,5.410939276,-3.337230722,44.99999998 +144.08,50.42854183,-2.577393356,50.4311,7.08448241,7.070393382,-2.9765625,5.478355611,-3.359170594,44.99999998 +144.09,50.42854247,-2.577392361,50.4608,7.077530051,7.070171267,-2.9584375,5.544627805,-3.378181276,44.99999998 +144.1,50.4285431,-2.577391366,50.4903,7.067101507,7.070393258,-2.939375,5.60974211,-3.394246096,44.99999998 +144.11,50.42854374,-2.577390371,50.5196,7.063625356,7.071281408,-2.918125,5.673684887,-3.407351073,44.99999998 +144.12,50.42854437,-2.577389376,50.5487,7.063625397,7.072391612,-2.8946875,5.736442788,-3.417484806,44.99999998 +144.13,50.42854501,-2.57738838,50.5775,7.063625434,7.072391549,-2.8696875,5.798002691,-3.42463847,44.99999998 +144.14,50.42854564,-2.577387385,50.6061,7.06362546,7.07128122,-2.8434375,5.858351763,-3.428805764,44.99999998 +144.15,50.42854628,-2.57738639,50.6344,7.067101671,7.070392945,-2.8165625,5.917477398,-3.429983078,44.99999998 +144.16,50.42854691,-2.577385395,50.6624,7.077530274,7.070170828,-2.7896875,5.975367277,-3.42816938,44.99999998 +144.17,50.42854755,-2.5773844,50.6902,7.0844827,7.070392817,-2.7615625,6.032009254,-3.423366332,44.99999998 +144.18,50.42854819,-2.577383405,50.7177,7.077530359,7.071058912,-2.73125,6.087391527,-3.415578002,44.99999998 +144.19,50.42854882,-2.57738241,50.7448,7.06710181,7.071502954,-2.6996875,6.141502463,-3.404811266,44.99999998 +144.2,50.42854946,-2.577381414,50.7717,7.063625633,7.071280835,-2.6665625,6.194330891,-3.391075462,44.99999998 +144.21,50.42855009,-2.57738042,50.7982,7.063625652,7.07128077,-2.6315625,6.245865694,-3.374382623,44.99999998 +144.22,50.42855073,-2.577379424,50.8243,7.067101883,7.071502757,-2.5965625,6.296096159,-3.354747245,44.99999998 +144.23,50.42855136,-2.577378429,50.8501,7.07753051,7.071058585,-2.5615625,6.345011743,-3.332186516,44.99999998 +144.24,50.428552,-2.577377434,50.8756,7.084482931,7.070392359,-2.5246875,6.392602248,-3.306720032,44.99999998 +144.25,50.42855264,-2.577376439,50.9006,7.077530567,7.070170239,-2.4865625,6.438857704,-3.278370023,44.99999998 +144.26,50.42855327,-2.577375444,50.9253,7.067102009,7.070392225,-2.448125,6.483768542,-3.247161241,44.99999998 +144.27,50.42855391,-2.577374449,50.9496,7.063625833,7.071280369,-2.4078125,6.52732531,-3.213120902,44.99999998 +144.28,50.42855454,-2.577373454,50.9735,7.063625852,7.072390566,-2.365,6.569518896,-3.176278684,44.99999998 +144.29,50.42855518,-2.577372458,50.9969,7.067102079,7.072390498,-2.321875,6.610340592,-3.136666674,44.99999998 +144.3,50.42855581,-2.577371463,51.0199,7.077530704,7.071280164,-2.2796875,6.649781746,-3.094319478,44.99999998 +144.31,50.42855645,-2.577370468,51.0425,7.08448312,7.070391882,-2.23625,6.687834222,-3.049273995,44.99999998 +144.32,50.42855709,-2.577369473,51.0647,7.077530744,7.070169758,-2.19,6.724489999,-3.001569471,44.99999998 +144.33,50.42855772,-2.577368478,51.0863,7.067102175,7.07039174,-2.143125,6.759741457,-2.951247505,44.99999998 +144.34,50.42855836,-2.577367483,51.1075,7.063626011,7.07127988,-2.096875,6.793581203,-2.898352041,44.99999998 +144.35,50.42855899,-2.577366488,51.1283,7.063626051,7.072168021,-2.049375,6.826002249,-2.842929203,44.99999998 +144.36,50.42855963,-2.577365492,51.1485,7.063626081,7.071501791,-2,6.856997719,-2.785027235,44.99999998 +144.37,50.42856026,-2.577364497,51.1683,7.063626105,7.0701694,-1.95,6.886561253,-2.724696727,44.99999998 +144.38,50.4285609,-2.577363503,51.1875,7.067102322,7.07039138,-1.8996875,6.914686548,-2.661990163,44.99999998 +144.39,50.42856153,-2.577362507,51.2063,7.077530913,7.071279518,-1.8484375,6.941367874,-2.596962375,44.99999998 +144.4,50.42856217,-2.577361512,51.2245,7.084483305,7.07105739,-1.79625,6.966599503,-2.529669972,44.99999998 +144.41,50.42856281,-2.577360517,51.2422,7.077530937,7.070391155,-1.7434375,6.990376335,-2.460171681,44.99999998 +144.42,50.42856344,-2.577359522,51.2594,7.067102391,7.070169027,-1.6896875,7.01269327,-2.388528064,44.99999998 +144.43,50.42856408,-2.577358527,51.276,7.063626229,7.070391004,-1.6346875,7.033545668,-2.314801631,44.99999998 +144.44,50.42856471,-2.577357532,51.2921,7.063626244,7.071279139,-1.5784375,7.052929232,-2.239056668,44.99999998 +144.45,50.42856535,-2.577356537,51.3076,7.06710244,7.072389327,-1.521875,7.070839892,-2.161359179,44.99999998 +144.46,50.42856598,-2.577355541,51.3225,7.077531028,7.072389249,-1.4665625,7.087273869,-2.081776946,44.99999998 +144.47,50.42856662,-2.577354546,51.3369,7.084483433,7.071278905,-1.41125,7.102227781,-2.00037941,44.99999998 +144.48,50.42856726,-2.577353551,51.3508,7.077531074,7.070390613,-1.353125,7.115698477,-1.917237505,44.99999998 +144.49,50.42856789,-2.577352556,51.364,7.067102522,7.070390533,-1.293125,7.12768315,-1.832423708,44.99999998 +144.5,50.42856853,-2.577351561,51.3766,7.063626346,7.071278664,-1.23375,7.138179278,-1.746012047,44.99999998 +144.51,50.42856916,-2.577350566,51.3887,7.063626347,7.072388848,-1.175,7.147184742,-1.658077808,44.99999998 +144.52,50.4285698,-2.57734957,51.4001,7.067102537,7.072388766,-1.11625,7.154697537,-1.568697767,44.99999998 +144.53,50.42857043,-2.577348575,51.411,7.077531134,7.071278419,-1.0565625,7.160716229,-1.477949732,44.99999998 +144.54,50.42857107,-2.57734758,51.4213,7.084483552,7.070390123,-0.9946875,7.165239444,-1.385912943,44.99999998 +144.55,50.42857171,-2.577346585,51.4309,7.077531188,7.070167985,-0.931875,7.168266323,-1.292667557,44.99999998 +144.56,50.42857234,-2.57734559,51.4399,7.067102611,7.070389954,-0.8703125,7.169796178,-1.198294991,44.99999998 +144.57,50.42857298,-2.577344595,51.4483,7.063626411,7.071056028,-0.8096875,7.169828722,-1.102877464,44.99999998 +144.58,50.42857361,-2.5773436,51.4561,7.06362641,7.071277996,-0.748125,7.168363955,-1.006498228,44.99999998 +144.59,50.42857425,-2.577342604,51.4633,7.06710262,7.070389697,-0.6846875,7.165402164,-0.909241336,44.99999998 +144.6,50.42857488,-2.57734161,51.4698,7.077531226,7.070167556,-0.6203125,7.16094398,-0.811191584,44.99999998 +144.61,50.42857552,-2.577340615,51.4757,7.084483627,7.071499785,-0.5565625,7.154990318,-0.712434401,44.99999998 +144.62,50.42857616,-2.577339619,51.4809,7.077531238,7.072165855,-0.4934375,7.147542382,-0.613056017,44.99999998 +144.63,50.42857679,-2.577338624,51.4856,7.067102652,7.071277554,-0.43,7.138601834,-0.513143007,44.99999998 +144.64,50.42857743,-2.577337629,51.4895,7.063626458,7.070389251,-0.3665625,7.12817045,-0.412782516,44.99999998 +144.65,50.42857806,-2.577336634,51.4929,7.063626467,7.070167108,-0.3034375,7.116250464,-0.312062093,44.99999998 +144.66,50.4285787,-2.577335639,51.4956,7.067102672,7.07038907,-0.239375,7.102844341,-0.211069573,44.99999998 +144.67,50.42857933,-2.577334644,51.4977,7.077531261,7.071277189,-0.17375,7.087954829,-0.109892961,44.99999998 +144.68,50.42857997,-2.577333649,51.4991,7.084483654,7.072387361,-0.1084375,7.071585138,-0.008620494,44.99999998 +144.69,50.42858061,-2.577332653,51.4998,7.077531271,7.072387266,-0.045,7.053738592,0.092659422,44.99999998 +144.7,50.42858124,-2.577331658,51.5,7.067102684,7.071276907,0.0184375,7.034419028,0.193858551,44.99999998 +144.71,50.42858188,-2.577330663,51.4995,7.063626474,7.0703886,0.08375,7.013630343,0.294888657,44.99999998 +144.72,50.42858251,-2.577329668,51.4983,7.063626467,7.070166451,0.1496875,6.991377006,0.39566162,44.99999998 +144.73,50.42858315,-2.577328673,51.4965,7.063626477,7.070388408,0.2146875,6.9676636,0.496089548,44.99999998 +144.74,50.42858378,-2.577327678,51.494,7.063626491,7.071054469,0.2784375,6.942495054,0.596084893,44.99999998 +144.75,50.42858442,-2.577326683,51.4909,7.067102687,7.071498477,0.3415625,6.915876696,0.69556045,44.99999998 +144.76,50.42858505,-2.577325687,51.4872,7.077531254,7.071276325,0.405,6.887814025,0.794429417,44.99999998 +144.77,50.42858569,-2.577324693,51.4828,7.084483621,7.071276226,0.4684375,6.858312944,0.892605678,44.99999998 +144.78,50.42858633,-2.577323697,51.4778,7.077531227,7.071498178,0.5315625,6.827379583,0.990003518,44.99999998 +144.79,50.42858696,-2.577322702,51.4722,7.067102656,7.071053972,0.595,6.795020359,1.08653814,44.99999998 +144.8,50.4285876,-2.577321707,51.4659,7.063626469,7.070387712,0.6584375,6.761242148,1.182125205,44.99999998 +144.81,50.42858823,-2.577320712,51.459,7.063626457,7.070165557,0.7215625,6.726051882,1.276681519,44.99999998 +144.82,50.42858887,-2.577319717,51.4515,7.067102629,7.070387507,0.785,6.68945701,1.370124461,44.99999998 +144.83,50.4285895,-2.577318722,51.4433,7.077531193,7.071275614,0.848125,6.651465153,1.462372728,44.99999998 +144.84,50.42859014,-2.577317727,51.4345,7.084483579,7.072385774,0.9096875,6.612084159,1.553345706,44.99999998 +144.85,50.42859078,-2.577316731,51.4251,7.077531196,7.072385669,0.97,6.571322338,1.642964155,44.99999998 +144.86,50.42859141,-2.577315736,51.4151,7.067102607,7.071275298,1.03,6.529188225,1.73114998,44.99999998 +144.87,50.42859205,-2.577314741,51.4045,7.063626395,7.07038698,1.0903125,6.485690529,1.817826119,44.99999998 +144.88,50.42859268,-2.577313746,51.3933,7.063626374,7.070164821,1.1515625,6.440838419,1.902917169,44.99999998 +144.89,50.42859332,-2.577312751,51.3815,7.067102552,7.070386766,1.213125,6.394641176,1.98634882,44.99999998 +144.9,50.42859395,-2.577311756,51.369,7.077531127,7.071274869,1.2728125,6.347108482,2.068048304,44.99999998 +144.91,50.42859459,-2.577310761,51.356,7.084483509,7.072162972,1.3296875,6.298250309,2.147944461,44.99999998 +144.92,50.42859523,-2.577309765,51.3424,7.077531108,7.071496703,1.3853125,6.248076853,2.225967562,44.99999998 +144.93,50.42859586,-2.57730877,51.3283,7.06710251,7.070164276,1.441875,6.196598543,2.302049654,44.99999998 +144.94,50.4285965,-2.577307776,51.3136,7.063626297,7.070386217,1.5,6.143826151,2.376124216,44.99999998 +144.95,50.42859713,-2.57730678,51.2983,7.063626275,7.071274318,1.558125,6.089770677,2.448126848,44.99999998 +144.96,50.42859777,-2.577305785,51.2824,7.067102448,7.071274205,1.6146875,6.034443466,2.517994639,44.99999998 +144.97,50.4285984,-2.57730479,51.266,7.077531018,7.071274093,1.6696875,5.977855977,2.585666684,44.99999998 +144.98,50.42859904,-2.577303795,51.249,7.084483397,7.071496032,1.723125,5.920020184,2.651084026,44.99999998 +144.99,50.42859968,-2.577302799,51.2315,7.077530997,7.071273865,1.775,5.860948006,2.71418954,44.99999998 +145,50.42860031,-2.577301805,51.2135,7.06710239,7.071273751,1.8265625,5.800651876,2.77492828,44.99999998 +145.01,50.42860095,-2.577300809,51.195,7.06362616,7.071495688,1.8784375,5.739144284,2.833247248,44.99999998 +145.02,50.42860158,-2.577299814,51.1759,7.063626133,7.071051466,1.9296875,5.676438236,2.889095564,44.99999998 +145.03,50.42860222,-2.577298819,51.1564,7.063626124,7.070385192,1.98,5.612546681,2.942424528,44.99999998 +145.04,50.42860285,-2.577297824,51.1363,7.063626118,7.070163023,2.03,5.547483026,2.993187672,44.99999998 +145.05,50.42860349,-2.577296829,51.1158,7.067102294,7.070384958,2.079375,5.481260908,3.041340706,44.99999998 +145.06,50.42860412,-2.577295834,51.0947,7.077530841,7.071273051,2.1265625,5.41389402,3.086841634,44.99999998 +145.07,50.42860476,-2.577294839,51.0732,7.084483189,7.072383197,2.1715625,5.345396572,3.129650806,44.99999998 +145.08,50.4286054,-2.577293843,51.0513,7.077530777,7.072383078,2.216875,5.275782772,3.169730923,44.99999998 +145.09,50.42860603,-2.577292848,51.0289,7.067102188,7.071272694,2.263125,5.205067176,3.207046919,44.99999998 +145.1,50.42860667,-2.577291853,51.006,7.063625982,7.070384363,2.3078125,5.133264563,3.241566366,44.99999998 +145.11,50.4286073,-2.577290858,50.9827,7.063625953,7.07016219,2.3496875,5.060390004,3.273259068,44.99999998 +145.12,50.42860794,-2.577289863,50.959,7.067102106,7.070384122,2.39,4.986458567,3.302097466,44.99999998 +145.13,50.42860857,-2.577288868,50.9349,7.077530652,7.071272212,2.43,4.911485836,3.328056407,44.99999998 +145.14,50.42860921,-2.577287873,50.9104,7.08448302,7.072160301,2.47,4.835487339,3.351113203,44.99999998 +145.15,50.42860985,-2.577286877,50.8855,7.077530621,7.07149402,2.5096875,4.758479061,3.371247799,44.99999998 +145.16,50.42861048,-2.577285882,50.8602,7.067102015,7.070161581,2.548125,4.680477045,3.388442607,44.99999998 +145.17,50.42861112,-2.577284888,50.8345,7.063625789,7.07038351,2.5846875,4.601497506,3.40268267,44.99999998 +145.18,50.42861175,-2.577283892,50.8085,7.063625759,7.071271598,2.6196875,4.521557059,3.4139555,44.99999998 +145.19,50.42861239,-2.577282897,50.7821,7.067101922,7.071271475,2.653125,4.440672321,3.422251299,44.99999998 +145.2,50.42861302,-2.577281902,50.7554,7.077530469,7.07127135,2.685,4.35886025,3.427562904,44.99999998 +145.21,50.42861366,-2.577280907,50.7284,7.084482824,7.071271225,2.7165625,4.276137864,3.429885561,44.99999998 +145.22,50.4286143,-2.577279911,50.7011,7.07753041,7.070382889,2.748125,4.192522409,3.429217377,44.99999998 +145.23,50.42861493,-2.577278917,50.6734,7.067101803,7.070160711,2.778125,4.108031474,3.425558813,44.99999998 +145.24,50.42861557,-2.577277922,50.6455,7.063625572,7.071492903,2.80625,4.022682592,3.418913132,44.99999998 +145.25,50.4286162,-2.577276926,50.6173,7.063625532,7.072158936,2.8334375,3.936493583,3.409286066,44.99999998 +145.26,50.42861684,-2.577275931,50.5888,7.067101702,7.071270599,2.8596875,3.84948255,3.396686094,44.99999998 +145.27,50.42861747,-2.577274936,50.5601,7.077530269,7.070382261,2.8846875,3.761667601,3.381124159,44.99999998 +145.28,50.42861811,-2.577273941,50.5311,7.08448263,7.070160081,2.908125,3.673067069,3.362613841,44.99999998 +145.29,50.42861875,-2.577272946,50.5019,7.077530206,7.070382006,2.9296875,3.583699404,3.341171239,44.99999998 +145.3,50.42861938,-2.577271951,50.4725,7.06710159,7.07127009,2.95,3.493583399,3.31681509,44.99999998 +145.31,50.42862002,-2.577270956,50.4429,7.063625361,7.072380227,2.97,3.402737789,3.28956665,44.99999998 +145.32,50.42862065,-2.57726996,50.4131,7.063625323,7.072380099,2.9896875,3.31118154,3.259449639,44.99999998 +145.33,50.42862129,-2.577268965,50.3831,7.063625288,7.071269708,3.0078125,3.218933845,3.226490356,44.99999998 +145.34,50.42862192,-2.57726797,50.3529,7.063625266,7.070381369,3.023125,3.126013842,3.190717564,44.99999998 +145.35,50.42862256,-2.577266975,50.3226,7.067101438,7.070159189,3.0365625,3.032441067,3.152162375,44.99999998 +145.36,50.42862319,-2.57726598,50.2922,7.077529983,7.070381113,3.05,2.938235003,3.11085842,44.99999998 +145.37,50.42862383,-2.577264985,50.2616,7.084482322,7.071047142,3.0628125,2.843415301,3.066841797,44.99999998 +145.38,50.42862447,-2.57726399,50.2309,7.07752989,7.071491118,3.073125,2.748001785,3.020150836,44.99999998 +145.39,50.4286251,-2.577262994,50.2001,7.067101281,7.071268937,3.08125,2.652014395,2.970826275,44.99999998 +145.4,50.42862574,-2.577262,50.1693,7.06362507,7.071268808,3.0884375,2.555473184,2.918911085,44.99999998 +145.41,50.42862637,-2.577261004,50.1383,7.063625041,7.071490732,3.095,2.458398262,2.864450529,44.99999998 +145.42,50.42862701,-2.577260009,50.1074,7.067101194,7.071268551,3.10125,2.360809971,2.807492165,44.99999998 +145.43,50.42862764,-2.577259014,50.0763,7.077529731,7.071268422,3.1065625,2.262728591,2.748085666,44.99999998 +145.44,50.42862828,-2.577258019,50.0452,7.084482073,7.071268293,3.109375,2.164174751,2.686282714,44.99999998 +145.45,50.42862892,-2.577257023,50.0141,7.077529655,7.070379953,3.1096875,2.065168905,2.622137339,44.99999998 +145.46,50.42862955,-2.577256029,49.983,7.067101057,7.070157771,3.1084375,1.965731793,2.555705403,44.99999998 +145.47,50.42863019,-2.577255034,49.9519,7.063624843,7.071489958,3.1065625,1.865884157,2.487044891,44.99999998 +145.48,50.42863082,-2.577254038,49.9209,7.063624805,7.072155987,3.1046875,1.765646852,2.41621562,44.99999998 +145.49,50.42863146,-2.577253043,49.8898,7.06710095,7.071267647,3.1015625,1.665040792,2.343279353,44.99999998 +145.5,50.42863209,-2.577252048,49.8588,7.077529486,7.070379308,3.0959375,1.564087061,2.268299689,44.99999998 +145.51,50.42863273,-2.577251053,49.8279,7.084481846,7.070157126,3.0884375,1.462806629,2.191342061,44.99999998 +145.52,50.42863337,-2.577250058,49.797,7.077529441,7.07037905,3.0796875,1.361220754,2.112473561,44.99999998 +145.53,50.428634,-2.577249063,49.7663,7.067100831,7.071267132,3.07,1.259350577,2.031762944,44.99999998 +145.54,50.42863464,-2.577248068,49.7356,7.063624598,7.072377267,3.06,1.157217412,1.949280628,44.99999998 +145.55,50.42863527,-2.577247072,49.7051,7.063624556,7.072377138,3.049375,1.054842574,1.86509846,44.99999998 +145.56,50.42863591,-2.577246077,49.6746,7.067100712,7.071266747,3.0365625,0.95224749,1.779289894,44.99999998 +145.57,50.42863654,-2.577245082,49.6443,7.077529264,7.070378408,3.02125,0.849453476,1.691929816,44.99999998 +145.58,50.42863718,-2.577244087,49.6142,7.084481625,7.070156228,3.005,0.746482131,1.603094314,44.99999998 +145.59,50.42863782,-2.577243092,49.5842,7.077529208,7.070378152,2.988125,0.643354828,1.51286091,44.99999998 +145.6,50.42863845,-2.577242097,49.5544,7.067100597,7.071044182,2.969375,0.540093222,1.42130827,44.99999998 +145.61,50.42863909,-2.577241102,49.5248,7.063624376,7.07148816,2.9484375,0.436718745,1.328516208,44.99999998 +145.62,50.42863972,-2.577240106,49.4954,7.06362434,7.07126598,2.9265625,0.333253167,1.234565626,44.99999998 +145.63,50.42864036,-2.577239112,49.4663,7.063624293,7.071265853,2.9046875,0.229717917,1.13953857,44.99999998 +145.64,50.42864099,-2.577238116,49.4373,7.063624255,7.07148778,2.8815625,0.126134711,1.043517719,44.99999998 +145.65,50.42864163,-2.577237121,49.4086,7.067100429,7.071043549,2.85625,0.022525205,0.946587011,44.99999998 +145.66,50.42864226,-2.577236126,49.3802,7.077528991,7.070377264,2.8303125,-0.081089055,0.848830786,44.99999998 +145.67,50.4286429,-2.577235131,49.352,7.084481345,7.070155085,2.8046875,-0.184686356,0.750334413,44.99999998 +145.68,50.42864354,-2.577234136,49.3241,7.077528913,7.070377012,2.7778125,-0.288245097,0.651183723,44.99999998 +145.69,50.42864417,-2.577233141,49.2964,7.067100296,7.071265098,2.748125,-0.391743678,0.551465174,44.99999998 +145.7,50.42864481,-2.577232146,49.2691,7.063624085,7.072375236,2.71625,-0.495160382,0.451265742,44.99999998 +145.71,50.42864544,-2.57723115,49.2421,7.063624071,7.072375111,2.6834375,-0.598473726,0.350672802,44.99999998 +145.72,50.42864608,-2.577230155,49.2154,7.067100242,7.071264724,2.6496875,-0.701662049,0.249774075,44.99999998 +145.73,50.42864671,-2.57722916,49.1891,7.077528787,7.07037639,2.615,-0.804703868,0.148657567,44.99999998 +145.74,50.42864735,-2.577228165,49.1631,7.08448113,7.070154214,2.5796875,-0.907577638,0.047411398,44.99999998 +145.75,50.42864799,-2.57722717,49.1375,7.077528705,7.070376143,2.543125,-1.010261816,-0.053876081,44.99999998 +145.76,50.42864862,-2.577226175,49.1122,7.067100104,7.071264231,2.505,-1.112735089,-0.155116635,44.99999998 +145.77,50.42864926,-2.57722518,49.0874,7.0636239,7.072374372,2.4665625,-1.214975912,-0.256221856,44.99999998 +145.78,50.42864989,-2.577224184,49.0629,7.063623876,7.07237425,2.428125,-1.31696303,-0.357103738,44.99999998 +145.79,50.42865053,-2.577223189,49.0388,7.06710003,7.071263866,2.3878125,-1.418675128,-0.45767416,44.99999998 +145.8,50.42865116,-2.577222194,49.0151,7.077528573,7.070375536,2.345,-1.52009095,-0.55784546,44.99999998 +145.81,50.4286518,-2.577221199,48.9919,7.084480941,7.070153363,2.3015625,-1.621189353,-0.657530376,44.99999998 +145.82,50.42865244,-2.577220204,48.9691,7.077528545,7.070375295,2.2584375,-1.721949137,-0.756641876,44.99999998 +145.83,50.42865307,-2.577219209,48.9467,7.067099946,7.071041332,2.2146875,-1.822349334,-0.855093558,44.99999998 +145.84,50.42865371,-2.577218214,48.9248,7.063623725,7.071263267,2.1696875,-1.922368972,-0.952799592,44.99999998 +145.85,50.42865434,-2.577217218,48.9033,7.0636237,7.070374938,2.123125,-2.021987139,-1.049674838,44.99999998 +145.86,50.42865498,-2.577216224,48.8823,7.067099868,7.070152768,2.0746875,-2.121183035,-1.145634669,44.99999998 +145.87,50.42865561,-2.577215229,48.8618,7.077528419,7.071484965,2.025,-2.219935978,-1.240595548,44.99999998 +145.88,50.42865625,-2.577214233,48.8418,7.084480779,7.072151006,1.975,-2.318225283,-1.334474568,44.99999998 +145.89,50.42865689,-2.577213238,48.8223,7.077528377,7.07126268,1.925,-2.41603044,-1.427189911,44.99999998 +145.9,50.42865752,-2.577212243,48.8033,7.067099786,7.070374354,1.8746875,-2.513331049,-1.518660732,44.99999998 +145.91,50.42865816,-2.577211248,48.7848,7.06362358,7.070374239,1.823125,-2.610106829,-1.608807276,44.99999998 +145.92,50.42865879,-2.577210253,48.7668,7.063623556,7.071262334,1.77,-2.706337497,-1.697550876,44.99999998 +145.93,50.42865943,-2.577209258,48.7494,7.067099715,7.072372483,1.7165625,-2.802002943,-1.784814239,44.99999998 +145.94,50.42866006,-2.577208262,48.7325,7.07752827,7.07237237,1.663125,-2.897083283,-1.870521162,44.99999998 +145.95,50.4286607,-2.577207267,48.7161,7.084480649,7.071261995,1.608125,-2.991558581,-1.954596989,44.99999998 +145.96,50.42866134,-2.577206272,48.7003,7.077528262,7.070373673,1.5515625,-3.085409125,-2.036968381,44.99999998 +145.97,50.42866197,-2.577205277,48.6851,7.067099671,7.070151508,1.495,-3.178615321,-2.117563489,44.99999998 +145.98,50.42866261,-2.577204282,48.6704,7.06362345,7.070373449,1.4384375,-3.271157688,-2.196312069,44.99999998 +145.99,50.42866324,-2.577203287,48.6563,7.063623417,7.071261549,1.3815625,-3.363016917,-2.273145423,44.99999998 +146,50.42866388,-2.577202292,48.6428,7.063623403,7.072371702,1.3246875,-3.454173872,-2.347996572,44.99999998 +146.01,50.42866451,-2.577201296,48.6298,7.063623407,7.072371594,1.2665625,-3.544609416,-2.420800199,44.99999998 +146.02,50.42866515,-2.577200301,48.6174,7.0670996,7.071261223,1.20625,-3.634304698,-2.491492935,44.99999998 +146.03,50.42866578,-2.577199306,48.6057,7.077528162,7.070372905,1.1453125,-3.72324104,-2.560012957,44.99999998 +146.04,50.42866642,-2.577198311,48.5945,7.084480521,7.070150745,1.085,-3.811399822,-2.626300679,44.99999998 +146.05,50.42866706,-2.577197316,48.584,7.077528113,7.070372691,1.025,-3.89876265,-2.690298174,44.99999998 +146.06,50.42866769,-2.577196321,48.574,7.067099531,7.071260795,0.965,-3.985311306,-2.751949693,44.99999998 +146.07,50.42866833,-2.577195326,48.5647,7.063623344,7.072148901,0.904375,-4.071027625,-2.811201494,44.99999998 +146.08,50.42866896,-2.57719433,48.5559,7.063623339,7.07148264,0.841875,-4.15589379,-2.868001894,44.99999998 +146.09,50.4286696,-2.577193335,48.5478,7.067099518,7.070150221,0.778125,-4.239892038,-2.922301333,44.99999998 +146.1,50.42867023,-2.577192341,48.5404,7.07752808,7.07037217,0.7153125,-4.323004838,-2.974052486,44.99999998 +146.11,50.42867087,-2.577191345,48.5335,7.084480455,7.071260278,0.6534375,-4.405214828,-3.023210259,44.99999998 +146.12,50.42867151,-2.57719035,48.5273,7.077528067,7.071038124,0.59125,-4.486504819,-3.069731682,44.99999998 +146.13,50.42867214,-2.577189355,48.5217,7.067099489,7.070371865,0.528125,-4.56685791,-3.113576303,44.99999998 +146.14,50.42867278,-2.57718836,48.5167,7.063623294,7.070149712,0.4634375,-4.646257255,-3.154705792,44.99999998 +146.15,50.42867341,-2.577187365,48.5124,7.063623292,7.070371666,0.3984375,-4.724686297,-3.193084396,44.99999998 +146.16,50.42867405,-2.57718637,48.5088,7.067099486,7.071259777,0.335,-4.802128647,-3.228678539,44.99999998 +146.17,50.42867468,-2.577185375,48.5057,7.077528058,7.072369941,0.2715625,-4.878568093,-3.261457226,44.99999998 +146.18,50.42867532,-2.577184379,48.5033,7.084480427,7.072369844,0.2065625,-4.953988762,-3.291391864,44.99999998 +146.19,50.42867596,-2.577183384,48.5016,7.077528033,7.071259485,0.141875,-5.028374841,-3.318456385,44.99999998 +146.2,50.42867659,-2.577182389,48.5005,7.067099463,7.07037118,0.0784375,-5.101710803,-3.342627182,44.99999998 +146.21,50.42867723,-2.577181394,48.5,7.063623279,7.070149032,0.0146875,-5.17398135,-3.363883114,44.99999998 +146.22,50.42867786,-2.577180399,48.5002,7.063623282,7.07037099,-0.05,-5.245171356,-3.382205732,44.99999998 +146.23,50.4286785,-2.577179404,48.501,7.067099474,7.071259106,-0.115,-5.315265982,-3.397578992,44.99999998 +146.24,50.42867913,-2.577178409,48.5025,7.077528049,7.072369275,-0.18,-5.384250616,-3.409989487,44.99999998 +146.25,50.42867977,-2.577177413,48.5046,7.084480433,7.072369182,-0.2446875,-5.452110763,-3.419426445,44.99999998 +146.26,50.42868041,-2.577176418,48.5074,7.077528056,7.071258829,-0.3084375,-5.518832329,-3.425881617,44.99999998 +146.27,50.42868104,-2.577175423,48.5108,7.06709949,7.070370528,-0.3715625,-5.58440139,-3.429349387,44.99999998 +146.28,50.42868168,-2.577174428,48.5148,7.063623309,7.070148386,-0.4353125,-5.648804195,-3.429826661,44.99999998 +146.29,50.42868231,-2.577173433,48.5195,7.063623311,7.070370348,-0.5,-5.71202728,-3.427313095,44.99999998 +146.3,50.42868295,-2.577172438,48.5248,7.063623304,7.071036417,-0.5646875,-5.774057524,-3.421810924,44.99999998 +146.31,50.42868358,-2.577171443,48.5308,7.063623312,7.071480434,-0.628125,-5.834881922,-3.413324789,44.99999998 +146.32,50.42868422,-2.577170447,48.5374,7.067099526,7.071258294,-0.69,-5.89448781,-3.401862252,44.99999998 +146.33,50.42868485,-2.577169453,48.5446,7.077528118,7.071258207,-0.751875,-5.952862698,-3.387433227,44.99999998 +146.34,50.42868549,-2.577168457,48.5524,7.084480507,7.071480174,-0.815,-6.009994382,-3.37005026,44.99999998 +146.35,50.42868613,-2.577167462,48.5609,7.077528122,7.071258036,-0.878125,-6.065870945,-3.349728593,44.99999998 +146.36,50.42868676,-2.577166467,48.57,7.06709955,7.071257951,-0.9396875,-6.120480756,-3.32648593,44.99999998 +146.37,50.4286874,-2.577165472,48.5797,7.063623373,7.071257867,-1,-6.173812355,-3.300342496,44.99999998 +146.38,50.42868803,-2.577164476,48.59,7.063623392,7.070369575,-1.06,-6.225854685,-3.271321152,44.99999998 +146.39,50.42868867,-2.577163482,48.6009,7.0670996,7.07014744,-1.12,-6.276596801,-3.239447109,44.99999998 +146.4,50.4286893,-2.577162487,48.6124,7.07752819,7.071479672,-1.18,-6.326028105,-3.204748269,44.99999998 +146.41,50.42868994,-2.577161491,48.6245,7.084480581,7.072145748,-1.2396875,-6.374138282,-3.167254828,44.99999998 +146.42,50.42869058,-2.577160496,48.6372,7.077528201,7.071257458,-1.2984375,-6.420917364,-3.126999501,44.99999998 +146.43,50.42869121,-2.577159501,48.6505,7.067099644,7.070369168,-1.3565625,-6.466355495,-3.084017353,44.99999998 +146.44,50.42869185,-2.577158506,48.6643,7.063623483,7.070147036,-1.415,-6.510443223,-3.038345913,44.99999998 +146.45,50.42869248,-2.577157511,48.6788,7.063623504,7.07036901,-1.473125,-6.553171264,-2.990025002,44.99999998 +146.46,50.42869312,-2.577156516,48.6938,7.067099708,7.071257141,-1.5296875,-6.594530852,-2.939096732,44.99999998 +146.47,50.42869375,-2.577155521,48.7094,7.077528296,7.072367326,-1.585,-6.634513165,-2.885605564,44.99999998 +146.48,50.42869439,-2.577154525,48.7255,7.084480697,7.072367249,-1.6396875,-6.673110009,-2.829598022,44.99999998 +146.49,50.42869503,-2.57715353,48.7422,7.077528334,7.071256911,-1.6934375,-6.710313247,-2.771123096,44.99999998 +146.5,50.42869566,-2.577152535,48.7594,7.067099782,7.070368626,-1.7465625,-6.746115088,-2.71023172,44.99999998 +146.51,50.4286963,-2.57715154,48.7771,7.063623611,7.070146499,-1.8,-6.78050814,-2.64697695,44.99999998 +146.52,50.42869693,-2.577150545,48.7954,7.063623632,7.070368476,-1.853125,-6.813485127,-2.581413962,44.99999998 +146.53,50.42869757,-2.57714955,48.8142,7.067099845,7.071034559,-1.9046875,-6.84503923,-2.513599938,44.99999998 +146.54,50.4286982,-2.577148555,48.8335,7.07752844,7.071478591,-1.955,-6.875163862,-2.443594064,44.99999998 +146.55,50.42869884,-2.577147559,48.8533,7.084480844,7.071256466,-2.0046875,-6.903852661,-2.371457303,44.99999998 +146.56,50.42869948,-2.577146565,48.8736,7.077528486,7.071256394,-2.053125,-6.931099669,-2.297252622,44.99999998 +146.57,50.42870011,-2.577145569,48.8944,7.067099939,7.071478374,-2.1,-6.956899271,-2.221044651,44.99999998 +146.58,50.42870075,-2.577144574,48.9156,7.063623777,7.071034198,-2.1465625,-6.981245966,-2.142899969,44.99999998 +146.59,50.42870138,-2.577143579,48.9373,7.063623797,7.07036797,-2.1934375,-7.004134713,-2.062886585,44.99999998 +146.6,50.42870202,-2.577142584,48.9595,7.063623807,7.070145848,-2.2396875,-7.025560699,-1.9810744,44.99999998 +146.61,50.42870265,-2.577141589,48.9821,7.063623826,7.070367832,-2.2846875,-7.045519569,-1.897534632,44.99999998 +146.62,50.42870329,-2.577140594,49.0052,7.067100057,7.071255972,-2.328125,-7.064007027,-1.812340162,44.99999998 +146.63,50.42870392,-2.577139599,49.0287,7.077528679,7.072366164,-2.3696875,-7.081019232,-1.725565361,44.99999998 +146.64,50.42870456,-2.577138603,49.0526,7.084481099,7.072366096,-2.41,-7.096552691,-1.637285857,44.99999998 +146.65,50.4287052,-2.577137608,49.0769,7.077528734,7.071255767,-2.45,-7.110604137,-1.547578543,44.99999998 +146.66,50.42870583,-2.577136613,49.1016,7.067100167,7.07036749,-2.4896875,-7.123170649,-1.456521798,44.99999998 +146.67,50.42870647,-2.577135618,49.1267,7.063623991,7.070145371,-2.528125,-7.134249532,-1.364194863,44.99999998 +146.68,50.4287071,-2.577134623,49.1522,7.063624027,7.070367356,-2.565,-7.143838497,-1.270678411,44.99999998 +146.69,50.42870774,-2.577133628,49.178,7.067100265,7.0712555,-2.60125,-7.151935594,-1.176053858,44.99999998 +146.7,50.42870837,-2.577132633,49.2042,7.077528877,7.072365695,-2.6365625,-7.158539104,-1.080403768,44.99999998 +146.71,50.42870901,-2.577131637,49.2308,7.08448128,7.07236563,-2.6696875,-7.163647653,-0.983811563,44.99999998 +146.72,50.42870965,-2.577130642,49.2576,7.077528913,7.071255304,-2.7015625,-7.167260152,-0.886361469,44.99999998 +146.73,50.42871028,-2.577129647,49.2848,7.067100371,7.07036703,-2.7334375,-7.169375856,-0.788138398,44.99999998 +146.74,50.42871092,-2.577128652,49.3123,7.063624224,7.070144913,-2.764375,-7.169994364,-0.68922812,44.99999998 +146.75,50.42871155,-2.577127657,49.3401,7.06362426,7.070366902,-2.793125,-7.169115447,-0.589716811,44.99999998 +146.76,50.42871219,-2.577126662,49.3682,7.067100481,7.071032996,-2.82,-7.166739391,-0.489691271,44.99999998 +146.77,50.42871282,-2.577125667,49.3965,7.077529091,7.071477037,-2.84625,-7.162866654,-0.389238706,44.99999998 +146.78,50.42871346,-2.577124671,49.4251,7.084481509,7.071254921,-2.8715625,-7.15749804,-0.288446721,44.99999998 +146.79,50.4287141,-2.577123677,49.454,7.077529148,7.071254858,-2.895,-7.150634693,-0.18740315,44.99999998 +146.8,50.42871473,-2.577122681,49.483,7.067100596,7.071476847,-2.918125,-7.142277989,-0.086196229,44.99999998 +146.81,50.42871537,-2.577121686,49.5123,7.06362444,7.071032681,-2.9415625,-7.132429704,0.015085864,44.99999998 +146.82,50.428716,-2.577120691,49.5419,7.063624483,7.070366462,-2.9625,-7.121091958,0.116354837,44.99999998 +146.83,50.42871664,-2.577119696,49.5716,7.067100716,7.070144348,-2.98,-7.108267042,0.217522338,44.99999998 +146.84,50.42871727,-2.577118701,49.6015,7.077529327,7.070366339,-2.9965625,-7.093957593,0.318500134,44.99999998 +146.85,50.42871791,-2.577117706,49.6315,7.084481732,7.071254487,-3.013125,-7.078166762,0.419200216,44.99999998 +146.86,50.42871855,-2.577116711,49.6618,7.077529373,7.072364686,-3.0284375,-7.060897699,0.519534695,44.99999998 +146.87,50.42871918,-2.577115715,49.6921,7.067100838,7.072364626,-3.0428125,-7.042154015,0.619416193,44.99999998 +146.88,50.42871982,-2.57711472,49.7226,7.063624694,7.071254304,-3.0565625,-7.021939721,0.718757506,44.99999998 +146.89,50.42872045,-2.577113725,49.7533,7.063624733,7.070366034,-3.0678125,-7.000258998,0.817472118,44.99999998 +146.9,50.42872109,-2.57711273,49.784,7.067100948,7.07014392,-3.0765625,-6.977116315,0.915473799,44.99999998 +146.91,50.42872172,-2.577111735,49.8148,7.077529547,7.070365912,-3.085,-6.952516602,1.012677234,44.99999998 +146.92,50.42872236,-2.57711074,49.8457,7.084481967,7.07125406,-3.093125,-6.926464898,1.10899757,44.99999998 +146.93,50.428723,-2.577109745,49.8767,7.077529626,7.072364261,-3.099375,-6.898966706,1.204350868,44.99999998 +146.94,50.42872363,-2.577108749,49.9077,7.067101091,7.072364201,-3.103125,-6.870027753,1.298653934,44.99999998 +146.95,50.42872427,-2.577107754,49.9388,7.063624939,7.07125388,-3.105,-6.839654057,1.39182455,44.99999998 +146.96,50.4287249,-2.577106759,49.9698,7.06362497,7.070365611,-3.1065625,-6.807852035,1.483781525,44.99999998 +146.97,50.42872554,-2.577105764,50.0009,7.063624992,7.070143498,-3.1084375,-6.774628275,1.574444534,44.99999998 +146.98,50.42872617,-2.577104769,50.032,7.063625027,7.07036549,-3.109375,-6.739989711,1.663734677,44.99999998 +146.99,50.42872681,-2.577103774,50.0631,7.067101269,7.071253639,-3.108125,-6.703943561,1.751573978,44.99999998 +147,50.42872744,-2.577102779,50.0942,7.07752989,7.072141787,-3.1046875,-6.666497388,1.837885887,44.99999998 +147.01,50.42872808,-2.577101783,50.1252,7.084482307,7.07147557,-3.0996875,-6.627659043,1.922595176,44.99999998 +147.02,50.42872872,-2.577100788,50.1562,7.077529945,7.070143196,-3.093125,-6.587436546,2.005627876,44.99999998 +147.03,50.42872935,-2.577099794,50.1871,7.067101394,7.070365188,-3.0846875,-6.545838378,2.086911679,44.99999998 +147.04,50.42872999,-2.577098798,50.2179,7.06362524,7.071253337,-3.075,-6.50287319,2.166375654,44.99999998 +147.05,50.42873062,-2.577097803,50.2486,7.063625281,7.071253276,-3.065,-6.45854992,2.243950473,44.99999998 +147.06,50.42873126,-2.577096808,50.2792,7.067101512,7.071253215,-3.0546875,-6.412877907,2.319568583,44.99999998 +147.07,50.42873189,-2.577095813,50.3097,7.077530131,7.071253155,-3.043125,-6.365866662,2.393163981,44.99999998 +147.08,50.42873253,-2.577094817,50.3401,7.084482557,7.070364885,-3.029375,-6.317525984,2.464672494,44.99999998 +147.09,50.42873317,-2.577093823,50.3703,7.077530199,7.070142771,-3.013125,-6.267865898,2.534031785,44.99999998 +147.1,50.4287338,-2.577092828,50.4004,7.067101636,7.071475022,-2.995,-6.216896948,2.60118135,44.99999998 +147.11,50.42873444,-2.577091832,50.4302,7.063625469,7.072141117,-2.9765625,-6.164629618,2.66606269,44.99999998 +147.12,50.42873507,-2.577090837,50.4599,7.063625512,7.071252846,-2.9584375,-6.111074909,2.728619139,44.99999998 +147.13,50.42873571,-2.577089842,50.4894,7.067101746,7.070364575,-2.939375,-6.056243937,2.788796208,44.99999998 +147.14,50.42873634,-2.577088847,50.5187,7.077530357,7.070142461,-2.918125,-6.000148275,2.846541416,44.99999998 +147.15,50.42873698,-2.577087852,50.5478,7.084482774,7.070364451,-2.8946875,-5.942799497,2.901804398,44.99999998 +147.16,50.42873762,-2.577086857,50.5766,7.077530423,7.071252597,-2.87,-5.884209635,2.954536913,44.99999998 +147.17,50.42873825,-2.577085862,50.6052,7.06710188,7.072362795,-2.845,-5.82439095,3.004693065,44.99999998 +147.18,50.42873889,-2.577084866,50.6335,7.06362572,7.072362732,-2.819375,-5.763355933,3.052229082,44.99999998 +147.19,50.42873952,-2.577083871,50.6616,7.063625754,7.071252407,-2.7915625,-5.701117304,3.097103537,44.99999998 +147.2,50.42874016,-2.577082876,50.6894,7.06362579,7.070364135,-2.7615625,-5.637688069,3.139277242,44.99999998 +147.21,50.42874079,-2.577081881,50.7168,7.063625817,7.07036407,-2.7315625,-5.573081462,3.178713411,44.99999998 +147.22,50.42874143,-2.577080886,50.744,7.067102026,7.071252214,-2.70125,-5.507311007,3.215377782,44.99999998 +147.23,50.42874206,-2.577079891,50.7709,7.077530633,7.072140358,-2.668125,-5.440390396,3.249238213,44.99999998 +147.24,50.4287427,-2.577078895,50.7974,7.084483063,7.071474136,-2.633125,-5.372333667,3.28026531,44.99999998 +147.25,50.42874334,-2.5770779,50.8235,7.077530719,7.070141757,-2.5984375,-5.303154972,3.308431973,44.99999998 +147.26,50.42874397,-2.577076906,50.8494,7.067102171,7.070363744,-2.563125,-5.232868749,3.333713563,44.99999998 +147.27,50.42874461,-2.57707591,50.8748,7.063625994,7.071251886,-2.52625,-5.161489724,3.356088196,44.99999998 +147.28,50.42874524,-2.577074915,50.8999,7.063626012,7.071251819,-2.488125,-5.089032851,3.375536217,44.99999998 +147.29,50.42874588,-2.57707392,50.9246,7.067102236,7.071251751,-2.448125,-5.015513142,3.392040724,44.99999998 +147.3,50.42874651,-2.577072925,50.9489,7.077530854,7.071251684,-2.4065625,-4.940946008,3.405587337,44.99999998 +147.31,50.42874715,-2.577071929,50.9727,7.084483272,7.070363407,-2.365,-4.865347034,3.416164195,44.99999998 +147.32,50.42874779,-2.577070935,50.9962,7.077530908,7.070141286,-2.3234375,-4.788731977,3.423762132,44.99999998 +147.33,50.42874842,-2.57706994,51.0192,7.067102342,7.071473529,-2.28125,-4.71111688,3.428374499,44.99999998 +147.34,50.42874906,-2.577068944,51.0418,7.063626165,7.072139616,-2.238125,-4.632517899,3.429997287,44.99999998 +147.35,50.42874969,-2.577067949,51.064,7.063626197,7.071251337,-2.193125,-4.552951479,3.428629064,44.99999998 +147.36,50.42875033,-2.577066954,51.0857,7.067102432,7.070363058,-2.14625,-4.472434293,3.424270975,44.99999998 +147.37,50.42875096,-2.577065959,51.1069,7.077531043,7.070140935,-2.0984375,-4.390983014,3.416926917,44.99999998 +147.38,50.4287516,-2.577064964,51.1277,7.084483449,7.070362916,-2.05,-4.308614774,3.406603249,44.99999998 +147.39,50.42875224,-2.577063969,51.1479,7.077531075,7.071251052,-2.00125,-4.22534676,3.393308966,44.99999998 +147.4,50.42875287,-2.577062974,51.1677,7.06710251,7.072361239,-1.951875,-4.141196277,3.377055643,44.99999998 +147.41,50.42875351,-2.577061978,51.187,7.063626342,7.072361166,-1.90125,-4.056180971,3.357857547,44.99999998 +147.42,50.42875414,-2.577060983,51.2057,7.06362637,7.071250832,-1.85,-3.970318604,3.335731292,44.99999998 +147.43,50.42875478,-2.577059988,51.224,7.067102588,7.070362549,-1.798125,-3.883627111,3.310696245,44.99999998 +147.44,50.42875541,-2.577058993,51.2417,7.077531192,7.070140421,-1.7446875,-3.796124538,3.282774178,44.99999998 +147.45,50.42875605,-2.577057998,51.2589,7.084483598,7.070362397,-1.69,-3.707829221,3.251989556,44.99999998 +147.46,50.42875669,-2.577057003,51.2755,7.077531222,7.07125053,-1.635,-3.618759551,3.218369081,44.99999998 +147.47,50.42875732,-2.577056008,51.2916,7.067102653,7.072360714,-1.58,-3.52893415,3.1819422,44.99999998 +147.48,50.42875796,-2.577055012,51.3071,7.063626481,7.072360637,-1.5246875,-3.438371753,3.142740542,44.99999998 +147.49,50.42875859,-2.577054017,51.3221,7.063626507,7.071250298,-1.4684375,-3.347091326,3.100798427,44.99999998 +147.5,50.42875923,-2.577053022,51.3365,7.067102725,7.070362011,-1.4115625,-3.25511189,3.056152353,44.99999998 +147.51,50.42875986,-2.577052027,51.3503,7.07753132,7.070139879,-1.3546875,-3.16245264,3.00884128,44.99999998 +147.52,50.4287605,-2.577051032,51.3636,7.084483709,7.070361851,-1.2965625,-3.069132998,2.958906461,44.99999998 +147.53,50.42876114,-2.577050037,51.3763,7.077531328,7.071027927,-1.2365625,-2.975172389,2.906391441,44.99999998 +147.54,50.42876177,-2.577049042,51.3883,7.06710277,7.07147195,-1.1765625,-2.880590464,2.851341943,44.99999998 +147.55,50.42876241,-2.577048046,51.3998,7.063626604,7.071249816,-1.116875,-2.785406934,2.793806094,44.99999998 +147.56,50.42876304,-2.577047052,51.4107,7.063626621,7.071249733,-1.05625,-2.689641736,2.733833971,44.99999998 +147.57,50.42876368,-2.577046056,51.4209,7.06362662,7.071471701,-0.9953125,-2.593314869,2.671477943,44.99999998 +147.58,50.42876431,-2.577045061,51.4306,7.063626614,7.071027514,-0.935,-2.496446384,2.606792326,44.99999998 +147.59,50.42876495,-2.577044066,51.4396,7.06710282,7.070361273,-0.874375,-2.399056508,2.539833498,44.99999998 +147.6,50.42876558,-2.577043071,51.4481,7.077531431,7.070139135,-0.811875,-2.301165694,2.47065996,44.99999998 +147.61,50.42876622,-2.577042076,51.4559,7.084483843,7.070361101,-0.748125,-2.202794284,2.399331928,44.99999998 +147.62,50.42876686,-2.577041081,51.463,7.077531458,7.071249223,-0.6853125,-2.103962846,2.325911684,44.99999998 +147.63,50.42876749,-2.577040086,51.4696,7.067102867,7.072359396,-0.623125,-2.004692006,2.250463169,44.99999998 +147.64,50.42876813,-2.57703909,51.4755,7.063626669,7.072359308,-0.5596875,-1.905002507,2.173052274,44.99999998 +147.65,50.42876876,-2.577038095,51.4808,7.063626682,7.071248959,-0.4953125,-1.804915202,2.093746378,44.99999998 +147.66,50.4287694,-2.5770371,51.4854,7.067102898,7.070360661,-0.4315625,-1.704450949,2.012614752,44.99999998 +147.67,50.42877003,-2.577036105,51.4894,7.077531491,7.070138518,-0.3684375,-1.603630774,1.929728099,44.99999998 +147.68,50.42877067,-2.57703511,51.4928,7.084483878,7.070360479,-0.3046875,-1.502475649,1.845158669,44.99999998 +147.69,50.42877131,-2.577034115,51.4955,7.077531484,7.071248596,-0.24,-1.401006771,1.758980202,44.99999998 +147.7,50.42877194,-2.57703312,51.4976,7.067102899,7.072358764,-0.1753125,-1.299245341,1.671267926,44.99999998 +147.71,50.42877258,-2.577032124,51.499,7.063626711,7.072358671,-0.1115625,-1.197212559,1.582098276,44.99999998 +147.72,50.42877321,-2.577031129,51.4998,7.063626719,7.071248317,-0.048125,-1.094929738,1.491549,44.99999998 +147.73,50.42877385,-2.577030134,51.5,7.067102917,7.070360015,0.016875,-0.992418249,1.399699052,44.99999998 +147.74,50.42877448,-2.577029139,51.4995,7.077531503,7.070137867,0.083125,-0.889699521,1.30662859,44.99999998 +147.75,50.42877512,-2.577028144,51.4983,7.084483897,7.070359823,0.148125,-0.786794983,1.212418687,44.99999998 +147.76,50.42877576,-2.577027149,51.4965,7.077531502,7.071247934,0.2115625,-0.683726179,1.117151562,44.99999998 +147.77,50.42877639,-2.577026154,51.4941,7.067102901,7.072358097,0.275,-0.580514535,1.020910294,44.99999998 +147.78,50.42877703,-2.577025158,51.491,7.063626697,7.072357999,0.3384375,-0.477181712,0.923778707,44.99999998 +147.79,50.42877766,-2.577024163,51.4873,7.063626704,7.07124764,0.4015625,-0.373749193,0.825841656,44.99999998 +147.8,50.4287783,-2.577023168,51.483,7.06710291,7.070359333,0.4653125,-0.270238638,0.727184397,44.99999998 +147.81,50.42877893,-2.577022173,51.478,7.077531494,7.070137181,0.53,-0.166671589,0.627893046,44.99999998 +147.82,50.42877957,-2.577021178,51.4724,7.084483864,7.070359131,0.5946875,-0.063069819,0.528054119,44.99999998 +147.83,50.42878021,-2.577020183,51.4661,7.077531451,7.071025186,0.658125,0.040545186,0.427754763,44.99999998 +147.84,50.42878084,-2.577019188,51.4592,7.067102861,7.071469188,0.72,0.144151712,0.327082411,44.99999998 +147.85,50.42878148,-2.577018192,51.4517,7.063626676,7.071247033,0.781875,0.2477281,0.226124784,44.99999998 +147.86,50.42878211,-2.577017198,51.4436,7.063626681,7.071246929,0.845,0.35125275,0.124970002,44.99999998 +147.87,50.42878275,-2.577016202,51.4348,7.067102862,7.071468877,0.908125,0.454704062,0.023706243,44.99999998 +147.88,50.42878338,-2.577015207,51.4254,7.077531421,7.071024667,0.9696875,0.558060434,-0.077578142,44.99999998 +147.89,50.42878402,-2.577014212,51.4154,7.084483787,7.070358405,1.03,0.661300267,-0.178794918,44.99999998 +147.9,50.42878466,-2.577013217,51.4048,7.077531387,7.070136247,1.09,0.764401959,-0.279855792,44.99999998 +147.91,50.42878529,-2.577012222,51.3936,7.067102804,7.070358193,1.15,0.867344026,-0.380672643,44.99999998 +147.92,50.42878593,-2.577011227,51.3818,7.063626613,7.071246293,1.2096875,0.970104981,-0.481157523,44.99999998 +147.93,50.42878656,-2.577010232,51.3694,7.063626604,7.072356444,1.2684375,1.072663337,-0.581222769,44.99999998 +147.94,50.4287872,-2.577009236,51.3564,7.06362658,7.072356335,1.3265625,1.174997667,-0.680781233,44.99999998 +147.95,50.42878783,-2.577008241,51.3429,7.063626554,7.071245966,1.385,1.277086657,-0.779746056,44.99999998 +147.96,50.42878847,-2.577007246,51.3287,7.067102736,7.070357648,1.443125,1.378908878,-0.878030949,44.99999998 +147.97,50.4287891,-2.577006251,51.314,7.077531311,7.070135484,1.4996875,1.480443187,-0.975550142,44.99999998 +147.98,50.42878974,-2.577005256,51.2987,7.084483686,7.070357425,1.555,1.581668271,-1.072218665,44.99999998 +147.99,50.42879038,-2.577004261,51.2829,7.077531283,7.071245521,1.61,1.682563102,-1.167952177,44.99999998 +148,50.42879101,-2.577003266,51.2665,7.067102686,7.072133616,1.665,1.783106481,-1.2626672,44.99999998 +148.01,50.42879165,-2.57700227,51.2496,7.063626469,7.071467346,1.7196875,1.883277551,-1.356281227,44.99999998 +148.02,50.42879228,-2.577001275,51.2321,7.063626435,7.070134921,1.7734375,1.983055287,-1.448712498,44.99999998 +148.03,50.42879292,-2.577000281,51.2141,7.067102604,7.070356859,1.82625,2.082418888,-1.539880453,44.99999998 +148.04,50.42879355,-2.576999285,51.1956,7.077531178,7.071244951,1.8784375,2.181347614,-1.629705683,44.99999998 +148.05,50.42879419,-2.57699829,51.1765,7.08448356,7.071244835,1.9296875,2.279820782,-1.718109747,44.99999998 +148.06,50.42879483,-2.576997295,51.157,7.077531148,7.071244719,1.9796875,2.377817822,-1.805015585,44.99999998 +148.07,50.42879546,-2.5769963,51.1369,7.067102528,7.071244602,2.0284375,2.475318336,-1.890347392,44.99999998 +148.08,50.4287961,-2.576995304,51.1164,7.063626305,7.070356277,2.07625,2.572301871,-1.974030858,44.99999998 +148.09,50.42879673,-2.57699431,51.0954,7.063626291,7.070134106,2.1234375,2.6687482,-2.055992871,44.99999998 +148.1,50.42879737,-2.576993315,51.0739,7.067102471,7.0714663,2.17,2.764637214,-2.1361621,44.99999998 +148.11,50.428798,-2.576992319,51.052,7.077531035,7.072132337,2.21625,2.859948857,-2.214468528,44.99999998 +148.12,50.42879864,-2.576991324,51.0296,7.084483405,7.07124401,2.2615625,2.954663307,-2.290843917,44.99999998 +148.13,50.42879928,-2.576990329,51.0067,7.077530987,7.070355682,2.3046875,3.048760624,-2.365221631,44.99999998 +148.14,50.42879991,-2.576989334,50.9835,7.067102363,7.070355561,2.346875,3.142221271,-2.437536812,44.99999998 +148.15,50.42880055,-2.576988339,50.9598,7.063626137,7.071243648,2.39,3.235025709,-2.507726491,44.99999998 +148.16,50.42880118,-2.576987344,50.9357,7.063626122,7.072353787,2.4325,3.327154572,-2.575729362,44.99999998 +148.17,50.42880182,-2.576986348,50.9111,7.063626109,7.072353665,2.4715625,3.418588609,-2.641486181,44.99999998 +148.18,50.42880245,-2.576985353,50.8862,7.06362608,7.071243284,2.508125,3.509308684,-2.704939538,44.99999998 +148.19,50.42880309,-2.576984358,50.861,7.067102231,7.070354953,2.5453125,3.599295888,-2.766034199,44.99999998 +148.2,50.42880372,-2.576983363,50.8353,7.07753078,7.070132778,2.583125,3.688531429,-2.824716823,44.99999998 +148.21,50.42880436,-2.576982368,50.8093,7.084483151,7.070354706,2.619375,3.776996686,-2.880936244,44.99999998 +148.22,50.428805,-2.576981373,50.7829,7.07753075,7.07124279,2.653125,3.864673151,-2.934643417,44.99999998 +148.23,50.42880563,-2.576980378,50.7562,7.067102145,7.072352925,2.6846875,3.951542548,-2.985791589,44.99999998 +148.24,50.42880627,-2.576979382,50.7292,7.063625917,7.072352801,2.7153125,4.037586714,-3.034336068,44.99999998 +148.25,50.4288069,-2.576978387,50.7019,7.063625879,7.071242417,2.7465625,4.122787658,-3.080234571,44.99999998 +148.26,50.42880754,-2.576977392,50.6743,7.067102034,7.070354085,2.7778125,4.207127619,-3.123447105,44.99999998 +148.27,50.42880817,-2.576976397,50.6463,7.077530582,7.070131907,2.8065625,4.290588948,-3.163935913,44.99999998 +148.28,50.42880881,-2.576975402,50.6181,7.084482944,7.070353833,2.8328125,4.373154287,-3.201665699,44.99999998 +148.29,50.42880945,-2.576974407,50.5897,7.077530532,7.071241914,2.8584375,4.45480633,-3.236603577,44.99999998 +148.3,50.42881008,-2.576973412,50.5609,7.067101918,7.072129995,2.883125,4.535528062,-3.268719122,44.99999998 +148.31,50.42881072,-2.576972416,50.532,7.063625686,7.071463712,2.90625,4.61530258,-3.297984316,44.99999998 +148.32,50.42881135,-2.576971421,50.5028,7.06362565,7.070131274,2.9284375,4.694113269,-3.324373607,44.99999998 +148.33,50.42881199,-2.576970427,50.4734,7.067101817,7.070353199,2.9496875,4.771943626,-3.347863959,44.99999998 +148.34,50.42881262,-2.576969431,50.4438,7.077530374,7.07124128,2.97,4.848777439,-3.36843492,44.99999998 +148.35,50.42881326,-2.576968436,50.414,7.084482732,7.071241152,2.9896875,4.924598663,-3.386068613,44.99999998 +148.36,50.4288139,-2.576967441,50.384,7.077530311,7.071241024,3.0078125,4.999391427,-3.400749568,44.99999998 +148.37,50.42881453,-2.576966446,50.3538,7.067101694,7.071240896,3.023125,5.073140148,-3.412465008,44.99999998 +148.38,50.42881517,-2.57696545,50.3235,7.063625461,7.07035256,3.03625,5.145829413,-3.421204734,44.99999998 +148.39,50.4288158,-2.576964456,50.2931,7.063625423,7.07013038,3.0484375,5.217444038,-3.426961127,44.99999998 +148.4,50.42881644,-2.576963461,50.2625,7.067101589,7.071462562,3.06,5.287969069,-3.4297292,44.99999998 +148.41,50.42881707,-2.576962465,50.2319,7.077530146,7.072128589,3.07125,5.357389724,-3.429506434,44.99999998 +148.42,50.42881771,-2.57696147,50.2011,7.084482507,7.071240253,3.0815625,5.425691622,-3.426293115,44.99999998 +148.43,50.42881835,-2.576960475,50.1702,7.077530082,7.070351917,3.0896875,5.492860381,-3.420091993,44.99999998 +148.44,50.42881898,-2.57695948,50.1393,7.067101451,7.070129736,3.09625,5.558882079,-3.410908568,44.99999998 +148.45,50.42881962,-2.576958485,50.1083,7.063625217,7.07035166,3.1015625,5.623742849,-3.39875069,44.99999998 +148.46,50.42882025,-2.57695749,50.0772,7.063625194,7.071239738,3.1046875,5.687429171,-3.383629131,44.99999998 +148.47,50.42882089,-2.576956495,50.0462,7.06710137,7.072349868,3.1065625,5.749927751,-3.365556953,44.99999998 +148.48,50.42882152,-2.576955499,50.0151,7.077529922,7.072349739,3.1084375,5.811225526,-3.344549971,44.99999998 +148.49,50.42882216,-2.576954504,49.984,7.084482263,7.071239351,3.109375,5.871309662,-3.320626463,44.99999998 +148.5,50.4288228,-2.576953509,49.9529,7.077529824,7.070351014,3.108125,5.930167725,-3.293807339,44.99999998 +148.51,50.42882343,-2.576952514,49.9218,7.067101209,7.070350885,3.105,5.987787283,-3.264115979,44.99999998 +148.52,50.42882407,-2.576951519,49.8908,7.063624999,7.071238963,3.10125,6.044156418,-3.231578221,44.99999998 +148.53,50.4288247,-2.576950524,49.8598,7.063624978,7.072349093,3.0965625,6.09926327,-3.196222543,44.99999998 +148.54,50.42882534,-2.576949528,49.8288,7.063624941,7.072348964,3.0896875,6.153096436,-3.158079654,44.99999998 +148.55,50.42882597,-2.576948533,49.798,7.063624892,7.071238577,3.08125,6.205644515,-3.1171829,44.99999998 +148.56,50.42882661,-2.576947538,49.7672,7.067101041,7.070350241,3.071875,6.256896679,-3.073567921,44.99999998 +148.57,50.42882724,-2.576946543,49.7365,7.077529595,7.070128061,3.0609375,6.306842155,-3.027272759,44.99999998 +148.58,50.42882788,-2.576945548,49.706,7.084481965,7.070349984,3.0484375,6.355470572,-2.978337751,44.99999998 +148.59,50.42882852,-2.576944553,49.6755,7.077529549,7.071238062,3.035,6.402771676,-2.926805584,44.99999998 +148.6,50.42882915,-2.576943558,49.6453,7.067100929,7.072126142,3.02125,6.448735668,-2.872721175,44.99999998 +148.61,50.42882979,-2.576942562,49.6151,7.063624694,7.071459859,3.0065625,6.493352923,-2.816131738,44.99999998 +148.62,50.42883042,-2.576941567,49.5851,7.063624657,7.07012742,2.989375,6.536614101,-2.757086604,44.99999998 +148.63,50.42883106,-2.576940573,49.5553,7.067100823,7.070349344,2.97,6.578510208,-2.695637224,44.99999998 +148.64,50.42883169,-2.576939577,49.5257,7.077529378,7.071237423,2.9496875,6.619032476,-2.631837228,44.99999998 +148.65,50.42883233,-2.576938582,49.4963,7.084481735,7.071237296,2.928125,6.658172426,-2.565742192,44.99999998 +148.66,50.42883297,-2.576937587,49.4671,7.077529319,7.071237169,2.905,6.695921922,-2.497409813,44.99999998 +148.67,50.4288336,-2.576936592,49.4382,7.067100711,7.071237042,2.8815625,6.732273058,-2.426899678,44.99999998 +148.68,50.42883424,-2.576935596,49.4095,7.063624482,7.07034871,2.858125,6.767218269,-2.354273267,44.99999998 +148.69,50.42883487,-2.576934602,49.381,7.063624436,7.070126532,2.8328125,6.800750166,-2.279593833,44.99999998 +148.7,50.42883551,-2.576933607,49.3528,7.067100592,7.071458716,2.805,6.832861872,-2.20292658,44.99999998 +148.71,50.42883614,-2.576932611,49.3249,7.077529154,7.072124746,2.7765625,6.863546627,-2.124338371,44.99999998 +148.72,50.42883678,-2.576931616,49.2973,7.084481524,7.071236414,2.7478125,6.892797956,-2.043897675,44.99999998 +148.73,50.42883742,-2.576930621,49.2699,7.077529106,7.070348082,2.7165625,6.9206099,-1.961674679,44.99999998 +148.74,50.42883805,-2.576929626,49.2429,7.067100481,7.070125905,2.683125,6.946976501,-1.877741117,44.99999998 +148.75,50.42883869,-2.576928631,49.2163,7.063624252,7.070347832,2.65,6.971892316,-1.7921701,44.99999998 +148.76,50.42883932,-2.576927636,49.1899,7.063624234,7.071235916,2.6165625,6.995352187,-1.705036283,44.99999998 +148.77,50.42883996,-2.576926641,49.1639,7.063624222,7.072346051,2.58125,7.017351131,-1.61641564,44.99999998 +148.78,50.42884059,-2.576925645,49.1383,7.063624201,7.072345928,2.545,7.037884563,-1.526385464,44.99999998 +148.79,50.42884123,-2.57692465,49.113,7.06710036,7.071235548,2.508125,7.056948301,-1.43502425,44.99999998 +148.8,50.42884186,-2.576923655,49.0881,7.077528898,7.070347219,2.4696875,7.07453822,-1.342411695,44.99999998 +148.81,50.4288425,-2.57692266,49.0636,7.084481247,7.070125045,2.4296875,7.09065071,-1.248628531,44.99999998 +148.82,50.42884314,-2.576921665,49.0395,7.077528841,7.070346975,2.3884375,7.105282448,-1.153756518,44.99999998 +148.83,50.42884377,-2.57692067,49.0158,7.067100251,7.071235061,2.34625,7.11843034,-1.057878448,44.99999998 +148.84,50.42884441,-2.576919675,48.9926,7.067100231,7.072345199,2.3034375,7.130091635,-0.961077859,44.99999998 +148.85,50.42884504,-2.576918679,48.9697,7.077528779,7.072345079,2.2596875,7.14026387,-0.863439204,44.99999998 +148.86,50.42884568,-2.576917684,48.9474,7.084481131,7.071234701,2.2146875,7.148944983,-0.765047626,44.99999998 +148.87,50.42884632,-2.576916689,48.9254,7.07752871,7.070346375,2.1684375,7.156133082,-0.665988952,44.99999998 +148.88,50.42884695,-2.576915694,48.904,7.067100109,7.070124205,2.1215625,7.161826793,-0.566349472,44.99999998 +148.89,50.42884759,-2.576914699,48.883,7.063623911,7.070346139,2.075,7.166024798,-0.466216159,44.99999998 +148.9,50.42884822,-2.576913704,48.8625,7.063623902,7.071012177,2.0278125,7.168726294,-0.365676275,44.99999998 +148.91,50.42884886,-2.576912709,48.8424,7.063623879,7.071456164,1.978125,7.169930651,-0.264817483,44.99999998 +148.92,50.42884949,-2.576911713,48.8229,7.063623849,7.071233996,1.9265625,7.169637698,-0.163727847,44.99999998 +148.93,50.42885013,-2.576910719,48.8039,7.067100013,7.07123388,1.8753125,7.167847434,-0.062495372,44.99999998 +148.94,50.42885076,-2.576909723,48.7854,7.077528568,7.071455816,1.8246875,7.16456026,0.038791535,44.99999998 +148.95,50.4288514,-2.576908728,48.7674,7.08448094,7.07123365,1.773125,7.159776865,0.140044693,44.99999998 +148.96,50.42885204,-2.576907733,48.7499,7.077528544,7.071233536,1.7196875,7.153498279,0.241175698,44.99999998 +148.97,50.42885267,-2.576906738,48.733,7.067099953,7.071233422,1.665,7.145725705,0.342096369,44.99999998 +148.98,50.42885331,-2.576905742,48.7166,7.063623738,7.070345103,1.61,7.13646092,0.442718759,44.99999998 +148.99,50.42885394,-2.576904748,48.7008,7.063623706,7.07012294,1.5546875,7.1257057,0.542955032,44.99999998 +149,50.42885458,-2.576903753,48.6855,7.067099876,7.071455138,1.498125,7.113462394,0.642717928,44.99999998 +149.01,50.42885521,-2.576902757,48.6708,7.077528451,7.072121182,1.44,7.099733581,0.741920299,44.99999998 +149.02,50.42885585,-2.576901762,48.6567,7.084480838,7.071232865,1.381875,7.08452201,0.840475743,44.99999998 +149.03,50.42885649,-2.576900767,48.6432,7.077528444,7.070344549,1.325,7.067830947,0.93829826,44.99999998 +149.04,50.42885712,-2.576899772,48.6302,7.067099844,7.070122389,1.268125,7.049663888,1.035302536,44.99999998 +149.05,50.42885776,-2.576898777,48.6178,7.063623623,7.070344331,1.209375,7.030024556,1.131404059,44.99999998 +149.06,50.42885839,-2.576897782,48.606,7.063623597,7.07123243,1.1484375,7.008917135,1.226519006,44.99999998 +149.07,50.42885903,-2.576896787,48.5948,7.067099779,7.072342581,1.086875,6.986345921,1.320564356,44.99999998 +149.08,50.42885966,-2.576895791,48.5843,7.07752836,7.072342474,1.0265625,6.962315784,1.413458175,44.99999998 +149.09,50.4288603,-2.576894796,48.5743,7.08448075,7.071232111,0.9665625,6.936831596,1.505119448,44.99999998 +149.1,50.42886094,-2.576893801,48.5649,7.077528352,7.0703438,0.9046875,6.909898798,1.595468188,44.99999998 +149.11,50.42886157,-2.576892806,48.5562,7.067099748,7.070121644,0.841875,6.881522891,1.684425673,44.99999998 +149.12,50.42886221,-2.576891811,48.5481,7.06362354,7.070343591,0.78,6.851709892,1.77191438,44.99999998 +149.13,50.42886284,-2.576890816,48.5406,7.063623544,7.071231695,0.718125,6.820465987,1.857857878,44.99999998 +149.14,50.42886348,-2.576889821,48.5337,7.063623552,7.072341851,0.655,6.787797767,1.942181337,44.99999998 +149.15,50.42886411,-2.576888825,48.5275,7.063623553,7.072341749,0.591875,6.753711935,2.024811133,44.99999998 +149.16,50.42886475,-2.57688783,48.5219,7.067099734,7.071231391,0.5296875,6.71821571,2.105675302,44.99999998 +149.17,50.42886538,-2.576886835,48.5169,7.077528293,7.070343085,0.4665625,6.681316483,2.184703314,44.99999998 +149.18,50.42886602,-2.57688584,48.5125,7.084480664,7.070120933,0.4015625,6.643021932,2.261826183,44.99999998 +149.19,50.42886666,-2.576884845,48.5089,7.077528281,7.070342886,0.336875,6.603340079,2.336976702,44.99999998 +149.2,50.42886729,-2.57688385,48.5058,7.067099715,7.071230993,0.2734375,6.56227923,2.410089383,44.99999998 +149.21,50.42886793,-2.576882855,48.5034,7.063623522,7.072341154,0.2096875,6.519847867,2.481100454,44.99999998 +149.22,50.42886856,-2.576881859,48.5016,7.063623507,7.072341058,0.145,6.476054983,2.549947922,44.99999998 +149.23,50.4288692,-2.576880864,48.5005,7.067099689,7.071230704,0.08,6.430909633,2.616571799,44.99999998 +149.24,50.42886983,-2.576879869,48.5,7.077528275,7.070342403,0.015,6.384421213,2.680913985,44.99999998 +149.25,50.42887047,-2.576878874,48.5002,7.084480677,7.070120257,-0.05,6.336599577,2.742918389,44.99999998 +149.26,50.42887111,-2.576877879,48.501,7.077528297,7.070342215,-0.1146875,6.287454581,2.802530923,44.99999998 +149.27,50.42887174,-2.576876884,48.5025,7.067099716,7.071008276,-0.1784375,6.236996537,2.859699621,44.99999998 +149.28,50.42887238,-2.576875889,48.5046,7.063623524,7.071452286,-0.2415625,6.185235988,2.914374577,44.99999998 +149.29,50.42887301,-2.576874893,48.5073,7.063623526,7.071230144,-0.3053125,6.132183706,2.966508178,44.99999998 +149.3,50.42887365,-2.576873899,48.5107,7.067099717,7.071230053,-0.37,6.077850805,3.016054933,44.99999998 +149.31,50.42887428,-2.576872903,48.5147,7.077528297,7.071452014,-0.4346875,6.022248632,3.062971639,44.99999998 +149.32,50.42887492,-2.576871908,48.5194,7.084480693,7.071007821,-0.4984375,5.965388759,3.107217446,44.99999998 +149.33,50.42887556,-2.576870913,48.5247,7.077528323,7.070341578,-0.5615625,5.907283103,3.148753677,44.99999998 +149.34,50.42887619,-2.576869918,48.5306,7.067099757,7.070119439,-0.625,5.847943813,3.187544123,44.99999998 +149.35,50.42887683,-2.576868923,48.5372,7.063623568,7.070341402,-0.688125,5.787383262,3.223554979,44.99999998 +149.36,50.42887746,-2.576867928,48.5444,7.063623561,7.071229522,-0.75,5.725614057,3.256754904,44.99999998 +149.37,50.4288781,-2.576866933,48.5522,7.063623564,7.072339694,-0.811875,5.662649147,3.287114849,44.99999998 +149.38,50.42887873,-2.576865937,48.5606,7.063623585,7.072339608,-0.8746875,5.598501652,3.314608343,44.99999998 +149.39,50.42887937,-2.576864942,48.5697,7.067099805,7.071229266,-0.9365625,5.533184979,3.339211495,44.99999998 +149.4,50.42888,-2.576863947,48.5794,7.0775284,7.070340976,-0.9965625,5.466712822,3.360902817,44.99999998 +149.41,50.42888064,-2.576862952,48.5896,7.084480785,7.070118841,-1.056875,5.399098932,3.379663403,44.99999998 +149.42,50.42888128,-2.576861957,48.6005,7.077528394,7.07034081,-1.1184375,5.330357575,3.395476809,44.99999998 +149.43,50.42888191,-2.576860962,48.612,7.067099828,7.071228934,-1.1796875,5.260503019,3.408329341,44.99999998 +149.44,50.42888255,-2.576859967,48.6241,7.06709986,7.07233911,-1.2396875,5.189549874,3.418209769,44.99999998 +149.45,50.42888318,-2.576858971,48.6368,7.077528467,7.072339029,-1.298125,5.117512922,3.425109442,44.99999998 +149.46,50.42888382,-2.576857976,48.6501,7.084480865,7.071228692,-1.355,5.044407289,3.4290224,44.99999998 +149.47,50.42888446,-2.576856981,48.6639,7.077528479,7.070340406,-1.411875,4.970248215,3.429945148,44.99999998 +149.48,50.42888509,-2.576855986,48.6783,7.067099905,7.070118277,-1.47,4.895051114,3.427877,44.99999998 +149.49,50.42888573,-2.576854991,48.6933,7.063623736,7.07034025,-1.528125,4.818831799,3.422819616,44.99999998 +149.5,50.42888636,-2.576853996,48.7089,7.06362377,7.071228379,-1.584375,4.741606084,3.414777523,44.99999998 +149.51,50.428887,-2.576853001,48.725,7.063623793,7.072338559,-1.6384375,4.663390126,3.403757711,44.99999998 +149.52,50.42888763,-2.576852005,48.7417,7.063623805,7.072338482,-1.6915625,4.584200368,3.389769749,44.99999998 +149.53,50.42888827,-2.57685101,48.7588,7.06710001,7.07122815,-1.745,4.504053199,3.37282584,44.99999998 +149.54,50.4288889,-2.576850015,48.7766,7.077528605,7.070339869,-1.7984375,4.422965404,3.352940824,44.99999998 +149.55,50.42888954,-2.57684902,48.7948,7.084481017,7.070117743,-1.85125,4.340953944,3.330131947,44.99999998 +149.56,50.42889018,-2.576848025,48.8136,7.077528659,7.070339721,-1.9034375,4.25803595,3.304419205,44.99999998 +149.57,50.42889081,-2.57684703,48.8329,7.067100104,7.071005801,-1.954375,4.174228669,3.275824887,44.99999998 +149.58,50.42889145,-2.576846035,48.8527,7.063623935,7.071449831,-2.0034375,4.089549689,3.244374031,44.99999998 +149.59,50.42889208,-2.576845039,48.873,7.063623963,7.071227708,-2.0515625,4.004016659,3.21009408,44.99999998 +149.6,50.42889272,-2.576844045,48.8937,7.067100176,7.071227636,-2.0996875,3.917647454,3.17301483,44.99999998 +149.61,50.42889335,-2.576843049,48.915,7.077528764,7.071449616,-2.146875,3.830460122,3.133168652,44.99999998 +149.62,50.42889399,-2.576842054,48.9367,7.084481169,7.071005443,-2.1928125,3.74247277,3.090590325,44.99999998 +149.63,50.42889463,-2.576841059,48.9588,7.077528819,7.070339218,-2.2384375,3.653703903,3.045316976,44.99999998 +149.64,50.42889526,-2.576840064,48.9815,7.067100278,7.070117098,-2.283125,3.564172028,2.997388025,44.99999998 +149.65,50.4288959,-2.576839069,49.0045,7.063624109,7.07033908,-2.32625,3.473895767,2.946845355,44.99999998 +149.66,50.42889653,-2.576838074,49.028,7.06362412,7.071227217,-2.3684375,3.382894026,2.89373297,44.99999998 +149.67,50.42889717,-2.576837079,49.0519,7.067100334,7.072337405,-2.4096875,3.291185828,2.838097164,44.99999998 +149.68,50.4288978,-2.576836083,49.0762,7.077528953,7.072337338,-2.4496875,3.198790368,2.779986524,44.99999998 +149.69,50.42889844,-2.576835088,49.1009,7.084481384,7.071227013,-2.4884375,3.105726781,2.719451699,44.99999998 +149.7,50.42889908,-2.576834093,49.126,7.077529032,7.070338741,-2.52625,3.012014664,2.656545517,44.99999998 +149.71,50.42889971,-2.576833098,49.1514,7.067100474,7.070116623,-2.5634375,2.917673496,2.591322752,44.99999998 +149.72,50.42890035,-2.576832103,49.1773,7.063624295,7.070338608,-2.5996875,2.822723045,2.523840298,44.99999998 +149.73,50.42890098,-2.576831108,49.2034,7.063624313,7.071226748,-2.6346875,2.727183077,2.454156999,44.99999998 +149.74,50.42890162,-2.576830113,49.23,7.06362435,7.07233694,-2.6684375,2.63107359,2.382333703,44.99999998 +149.75,50.42890225,-2.576829117,49.2568,7.063624396,7.072336875,-2.7009375,2.534414635,2.308432919,44.99999998 +149.76,50.42890289,-2.576828122,49.284,7.067100623,7.071226554,-2.731875,2.437226383,2.232519163,44.99999998 +149.77,50.42890352,-2.576827127,49.3115,7.077529221,7.070338284,-2.76125,2.339529172,2.15465861,44.99999998 +149.78,50.42890416,-2.576826132,49.3392,7.084481627,7.070116168,-2.79,2.241343343,2.074919214,44.99999998 +149.79,50.4289048,-2.576825137,49.3673,7.077529271,7.070338156,-2.8184375,2.142689464,1.993370418,44.99999998 +149.8,50.42890543,-2.576824142,49.3956,7.067100736,7.071226298,-2.84625,2.043588106,1.910083382,44.99999998 +149.81,50.42890607,-2.576823147,49.4242,7.063624591,7.072114441,-2.8728125,1.944059951,1.8251307,44.99999998 +149.82,50.4289067,-2.576822151,49.4531,7.06362463,7.071448223,-2.8965625,1.844125856,1.738586514,44.99999998 +149.83,50.42890734,-2.576821156,49.4822,7.06710085,7.070115853,-2.918125,1.743806618,1.650526224,44.99999998 +149.84,50.42890797,-2.576820162,49.5114,7.077529449,7.070337842,-2.94,1.643123208,1.561026664,44.99999998 +149.85,50.42890861,-2.576819166,49.541,7.084481859,7.071225985,-2.96125,1.542096597,1.470165871,44.99999998 +149.86,50.42890925,-2.576818171,49.5707,7.077529512,7.071225923,-2.979375,1.440747983,1.378023028,44.99999998 +149.87,50.42890988,-2.576817176,49.6006,7.06710098,7.071447913,-2.9953125,1.33909851,1.284678577,44.99999998 +149.88,50.42891052,-2.576816181,49.6306,7.063624827,7.072336057,-3.0115625,1.237169375,1.190213879,44.99999998 +149.89,50.42891115,-2.576815185,49.6608,7.063624861,7.072335996,-3.028125,1.134981837,1.094711269,44.99999998 +149.9,50.42891179,-2.57681419,49.6912,7.067101083,7.071225678,-3.043125,1.032557323,0.998254053,44.99999998 +149.91,50.42891242,-2.576813195,49.7217,7.077529683,7.070337412,-3.05625,0.929917148,0.900926343,44.99999998 +149.92,50.42891306,-2.5768122,49.7523,7.084482099,7.0701153,-3.068125,0.82708274,0.80281305,44.99999998 +149.93,50.4289137,-2.576811205,49.7831,7.077529757,7.07033729,-3.0778125,0.724075643,0.70399966,44.99999998 +149.94,50.42891433,-2.57681021,49.8139,7.067101226,7.071003383,-3.085,0.620917342,0.604572346,44.99999998 +149.95,50.42891497,-2.576809215,49.8448,7.063625072,7.071447426,-3.0915625,0.517629324,0.504617853,44.99999998 +149.96,50.4289156,-2.576808219,49.8757,7.063625094,7.071225315,-3.098125,0.414233245,0.404223329,44.99999998 +149.97,50.42891624,-2.576807225,49.9068,7.067101305,7.071225255,-3.103125,0.31075065,0.303476321,44.99999998 +149.98,50.42891687,-2.576806229,49.9378,7.07752992,7.071447245,-3.10625,0.207203139,0.202464721,44.99999998 +149.99,50.42891751,-2.576805234,49.9689,7.084482354,7.071003082,-3.1084375,0.103612427,0.101276536,44.99999998 +150,50.42891815,-2.576804239,50,7.077530012,7.070336867,-3.109375,0,0,44.99999998 +150.01,50.42891878,-2.576803244,50.0311,7.067101473,7.070114756,-3.1084375,-0.103612427,-0.101276536,44.99999998 +150.02,50.42891942,-2.576802249,50.0622,7.06362531,7.070336747,-3.10625,-0.207203139,-0.202464721,44.99999998 +150.03,50.42892005,-2.576801254,50.0932,7.063625329,7.071224892,-3.103125,-0.31075065,-0.303476321,44.99999998 +150.04,50.42892069,-2.576800259,50.1243,7.067101552,7.072335088,-3.098125,-0.414233245,-0.404223329,44.99999998 +150.05,50.42892132,-2.576799263,50.1552,7.07753018,7.072335028,-3.0915625,-0.517629324,-0.504617853,44.99999998 +150.06,50.42892196,-2.576798268,50.1861,7.084482618,7.07122471,-3.085,-0.620917342,-0.604572346,44.99999998 +150.07,50.4289226,-2.576797273,50.2169,7.07753027,7.070336444,-3.0778125,-0.724075643,-0.70399966,44.99999998 +150.08,50.42892323,-2.576796278,50.2477,7.067101709,7.070114332,-3.068125,-0.82708274,-0.80281305,44.99999998 +150.09,50.42892387,-2.576795283,50.2783,7.063625532,7.070336324,-3.05625,-0.929917148,-0.900926343,44.99999998 +150.1,50.4289245,-2.576794288,50.3088,7.063625567,7.071224468,-3.043125,-1.032557323,-0.998254053,44.99999998 +150.11,50.42892514,-2.576793293,50.3392,7.063625619,7.072334663,-3.028125,-1.134981837,-1.094711269,44.99999998 +150.12,50.42892577,-2.576792297,50.3694,7.063625666,7.072334602,-3.0115625,-1.237169375,-1.190213879,44.99999998 +150.13,50.42892641,-2.576791302,50.3994,7.06710189,7.071224285,-2.9953125,-1.33909851,-1.284678577,44.99999998 +150.14,50.42892704,-2.576790307,50.4293,7.077530491,7.070336018,-2.979375,-1.440747983,-1.378023028,44.99999998 +150.15,50.42892768,-2.576789312,50.459,7.084482902,7.070113904,-2.96125,-1.542096597,-1.470165871,44.99999998 +150.16,50.42892832,-2.576788317,50.4886,7.077530554,7.070335893,-2.94,-1.643123208,-1.561026664,44.99999998 +150.17,50.42892895,-2.576787322,50.5178,7.06710202,7.071224036,-2.918125,-1.743806618,-1.650526224,44.99999998 +150.18,50.42892959,-2.576786327,50.5469,7.063625863,7.072112179,-2.8965625,-1.844125856,-1.738586514,44.99999998 +150.19,50.42893022,-2.576785331,50.5758,7.063625892,7.071445963,-2.8728125,-1.944059951,-1.8251307,44.99999998 +150.2,50.42893086,-2.576784336,50.6044,7.067102116,7.070113592,-2.84625,-2.043588106,-1.910083382,44.99999998 +150.21,50.42893149,-2.576783342,50.6327,7.077530729,7.07033558,-2.8184375,-2.142689464,-1.993370418,44.99999998 +150.22,50.42893213,-2.576782346,50.6608,7.084483143,7.071223721,-2.79,-2.241343343,-2.074919214,44.99999998 +150.23,50.42893277,-2.576781351,50.6885,7.077530781,7.071223657,-2.76125,-2.339529172,-2.15465861,44.99999998 +150.24,50.4289334,-2.576780356,50.716,7.067102234,7.071223593,-2.731875,-2.437226383,-2.232519163,44.99999998 +150.25,50.42893404,-2.576779361,50.7432,7.06362608,7.07144558,-2.7009375,-2.534414635,-2.308432919,44.99999998 +150.26,50.42893467,-2.576778365,50.77,7.063626117,7.071223463,-2.6684375,-2.63107359,-2.382333703,44.99999998 +150.27,50.42893531,-2.576777371,50.7966,7.067102337,7.071223398,-2.6346875,-2.727183077,-2.454156999,44.99999998 +150.28,50.42893594,-2.576776375,50.8227,7.077530934,7.071445384,-2.5996875,-2.822723045,-2.523840298,44.99999998 +150.29,50.42893658,-2.57677538,50.8486,7.084483346,7.071001215,-2.5634375,-2.917673496,-2.591322752,44.99999998 +150.3,50.42893722,-2.576774385,50.874,7.077530997,7.070334994,-2.52625,-3.012014664,-2.656545517,44.99999998 +150.31,50.42893785,-2.57677339,50.8991,7.067102458,7.070112876,-2.4884375,-3.105726781,-2.719451699,44.99999998 +150.32,50.42893849,-2.576772395,50.9238,7.063626296,7.07033486,-2.4496875,-3.198790368,-2.779986524,44.99999998 +150.33,50.42893912,-2.5767714,50.9481,7.063626311,7.071222997,-2.4096875,-3.291185828,-2.838097164,44.99999998 +150.34,50.42893976,-2.576770405,50.972,7.06362632,7.072333186,-2.3684375,-3.382894026,-2.89373297,44.99999998 +150.35,50.42894039,-2.576769409,50.9955,7.063626347,7.072333117,-2.32625,-3.473895767,-2.946845355,44.99999998 +150.36,50.42894103,-2.576768414,51.0185,7.067102586,7.071222792,-2.283125,-3.564172028,-2.997388025,44.99999998 +150.37,50.42894166,-2.576767419,51.0412,7.077531208,7.070334517,-2.2384375,-3.653703903,-3.045316976,44.99999998 +150.38,50.4289423,-2.576766424,51.0633,7.084483618,7.070112395,-2.1928125,-3.74247277,-3.090590325,44.99999998 +150.39,50.42894294,-2.576765429,51.085,7.077531238,7.070334375,-2.146875,-3.830460122,-3.133168652,44.99999998 +150.4,50.42894357,-2.576764434,51.1063,7.067102668,7.07122251,-2.0996875,-3.917647454,-3.17301483,44.99999998 +150.41,50.42894421,-2.576763439,51.127,7.063626504,7.072332695,-2.0515625,-4.004016659,-3.21009408,44.99999998 +150.42,50.42894484,-2.576762443,51.1473,7.063626543,7.072332623,-2.0034375,-4.089549689,-3.244374031,44.99999998 +150.43,50.42894548,-2.576761448,51.1671,7.067102764,7.071222293,-1.954375,-4.174228669,-3.275824887,44.99999998 +150.44,50.42894611,-2.576760453,51.1864,7.077531364,7.070334015,-1.9034375,-4.25803595,-3.304419205,44.99999998 +150.45,50.42894675,-2.576759458,51.2052,7.084483766,7.07011189,-1.85125,-4.340953944,-3.330131947,44.99999998 +150.46,50.42894739,-2.576758463,51.2234,7.077531393,7.070333866,-1.7984375,-4.422965404,-3.352940824,44.99999998 +150.47,50.42894802,-2.576757468,51.2412,7.067102834,7.071221996,-1.745,-4.504053199,-3.37282584,44.99999998 +150.48,50.42894866,-2.576756473,51.2583,7.063626666,7.072332177,-1.6915625,-4.584200368,-3.389769749,44.99999998 +150.49,50.42894929,-2.576755477,51.275,7.063626687,7.072332101,-1.6384375,-4.663390126,-3.403757711,44.99999998 +150.5,50.42894993,-2.576754482,51.2911,7.067102901,7.071221768,-1.584375,-4.741606084,-3.414777523,44.99999998 +150.51,50.42895056,-2.576753487,51.3067,7.0775315,7.070333486,-1.528125,-4.818831799,-3.422819616,44.99999998 +150.52,50.4289512,-2.576752492,51.3217,7.0844839,7.070111356,-1.47,-4.895051114,-3.427877,44.99999998 +150.53,50.42895184,-2.576751497,51.3361,7.077531523,7.070333328,-1.411875,-4.970248215,-3.429945148,44.99999998 +150.54,50.42895247,-2.576750502,51.3499,7.06710296,7.071221453,-1.355,-5.044407289,-3.4290224,44.99999998 +150.55,50.42895311,-2.576749507,51.3632,7.06362679,7.072109578,-1.298125,-5.117512922,-3.425109442,44.99999998 +150.56,50.42895374,-2.576748511,51.3759,7.063626811,7.071443344,-1.2396875,-5.189549874,-3.418209769,44.99999998 +150.57,50.42895438,-2.576747516,51.388,7.067103016,7.070110956,-1.1796875,-5.260503019,-3.408329341,44.99999998 +150.58,50.42895501,-2.576746522,51.3995,7.077531598,7.070332926,-1.1184375,-5.330357575,-3.395476809,44.99999998 +150.59,50.42895565,-2.576745526,51.4104,7.084483993,7.071221048,-1.056875,-5.399098932,-3.379663403,44.99999998 +150.6,50.42895629,-2.576744531,51.4206,7.077531627,7.071220964,-0.9965625,-5.466712822,-3.360902817,44.99999998 +150.61,50.42895692,-2.576743536,51.4303,7.06710307,7.07122088,-0.9365625,-5.533184979,-3.339211495,44.99999998 +150.62,50.42895756,-2.576742541,51.4394,7.063626893,7.071220795,-0.8746875,-5.598501652,-3.314608343,44.99999998 +150.63,50.42895819,-2.576741545,51.4478,7.063626896,7.070332506,-0.811875,-5.662649147,-3.287114849,44.99999998 +150.64,50.42895883,-2.576740551,51.4556,7.067103085,7.070110368,-0.75,-5.725614057,-3.256754904,44.99999998 +150.65,50.42895946,-2.576739556,51.4628,7.077531667,7.071442588,-0.688125,-5.787383262,-3.223554979,44.99999998 +150.66,50.4289601,-2.57673856,51.4694,7.084484071,7.072108655,-0.625,-5.847943813,-3.187544123,44.99999998 +150.67,50.42896074,-2.576737565,51.4753,7.077531704,7.071220362,-0.5615625,-5.907283103,-3.148753677,44.99999998 +150.68,50.42896137,-2.57673657,51.4806,7.067103129,7.070332068,-0.4984375,-5.965388759,-3.107217446,44.99999998 +150.69,50.42896201,-2.576735575,51.4853,7.063626927,7.070331979,-0.4346875,-6.022248632,-3.062971639,44.99999998 +150.7,50.42896264,-2.57673458,51.4893,7.063626921,7.071220093,-0.37,-6.077850805,-3.016054933,44.99999998 +150.71,50.42896328,-2.576733585,51.4927,7.063626932,7.072330258,-0.3053125,-6.132183706,-2.966508178,44.99999998 +150.72,50.42896391,-2.576732589,51.4954,7.063626952,7.072330167,-0.2415625,-6.185235988,-2.914374577,44.99999998 +150.73,50.42896455,-2.576731594,51.4975,7.067103154,7.071219819,-0.1784375,-6.236996537,-2.859699621,44.99999998 +150.74,50.42896518,-2.576730599,51.499,7.077531736,7.070331521,-0.1146875,-6.287454581,-2.802530923,44.99999998 +150.75,50.42896582,-2.576729604,51.4998,7.084484123,7.070109376,-0.05,-6.336599577,-2.742918389,44.99999998 +150.76,50.42896646,-2.576728609,51.5,7.077531726,7.070331332,0.015,-6.384421213,-2.680913985,44.99999998 +150.77,50.42896709,-2.576727614,51.4995,7.067103133,7.071219441,0.08,-6.430909633,-2.616571799,44.99999998 +150.78,50.42896773,-2.576726619,51.4984,7.063626944,7.072329602,0.145,-6.476054983,-2.549947922,44.99999998 +150.79,50.42896836,-2.576725623,51.4966,7.063626958,7.072329506,0.2096875,-6.519847867,-2.481100454,44.99999998 +150.8,50.428969,-2.576724628,51.4942,7.067103154,7.071219152,0.2734375,-6.56227923,-2.410089383,44.99999998 +150.81,50.42896963,-2.576723633,51.4911,7.077531722,7.070330849,0.336875,-6.603340079,-2.336976702,44.99999998 +150.82,50.42897027,-2.576722638,51.4875,7.084484097,7.0701087,0.4015625,-6.643021932,-2.261826183,44.99999998 +150.83,50.42897091,-2.576721643,51.4831,7.07753171,7.070330651,0.4665625,-6.681316483,-2.184703314,44.99999998 +150.84,50.42897154,-2.576720648,51.4781,7.067103137,7.071218755,0.5296875,-6.71821571,-2.105675302,44.99999998 +150.85,50.42897218,-2.576719653,51.4725,7.063626943,7.07232891,0.591875,-6.753711935,-2.024811133,44.99999998 +150.86,50.42897281,-2.576718657,51.4663,7.063626939,7.072328809,0.655,-6.787797767,-1.942181337,44.99999998 +150.87,50.42897345,-2.576717662,51.4594,7.067103127,7.071218451,0.718125,-6.820465987,-1.857857878,44.99999998 +150.88,50.42897408,-2.576716667,51.4519,7.07753169,7.070330143,0.78,-6.851709892,-1.77191438,44.99999998 +150.89,50.42897472,-2.576715672,51.4438,7.084484054,7.070107989,0.841875,-6.881522891,-1.684425673,44.99999998 +150.9,50.42897536,-2.576714677,51.4351,7.077531656,7.070329936,0.9046875,-6.909898798,-1.595468188,44.99999998 +150.91,50.42897599,-2.576713682,51.4257,7.06710308,7.071218035,0.9665625,-6.936831596,-1.505119448,44.99999998 +150.92,50.42897663,-2.576712687,51.4157,7.063626888,7.072106133,1.0265625,-6.962315784,-1.413458175,44.99999998 +150.93,50.42897726,-2.576711691,51.4052,7.063626872,7.071439874,1.086875,-6.986345921,-1.320564356,44.99999998 +150.94,50.4289779,-2.576710696,51.394,7.06710304,7.07010746,1.1484375,-7.008917135,-1.226519006,44.99999998 +150.95,50.42897853,-2.576709702,51.3822,7.077531598,7.070329404,1.209375,-7.030024556,-1.131404059,44.99999998 +150.96,50.42897917,-2.576708706,51.3698,7.084483975,7.0712175,1.268125,-7.049663888,-1.035302536,44.99999998 +150.97,50.42897981,-2.576707711,51.3568,7.077531585,7.071217391,1.325,-7.067830947,-0.93829826,44.99999998 +150.98,50.42898044,-2.576706716,51.3433,7.067103002,7.071217281,1.381875,-7.08452201,-0.840475743,44.99999998 +150.99,50.42898108,-2.576705721,51.3292,7.063626797,7.071217171,1.44,-7.099733581,-0.741920299,44.99999998 +151,50.42898171,-2.576704725,51.3145,7.063626769,7.070328856,1.498125,-7.113462394,-0.642717928,44.99999998 +151.01,50.42898235,-2.576703731,51.2992,7.067102929,7.070106693,1.5546875,-7.1257057,-0.542955032,44.99999998 +151.02,50.42898298,-2.576702736,51.2834,7.077531496,7.071438887,1.61,-7.13646092,-0.442718759,44.99999998 +151.03,50.42898362,-2.57670174,51.267,7.084483886,7.072104927,1.665,-7.145725705,-0.342096369,44.99999998 +151.04,50.42898426,-2.576700745,51.2501,7.077531492,7.071438661,1.7196875,-7.153498279,-0.241175698,44.99999998 +151.05,50.42898489,-2.57669975,51.2326,7.067102885,7.071216496,1.773125,-7.159776865,-0.140044693,44.99999998 +151.06,50.42898553,-2.576698755,51.2146,7.063626656,7.071216381,1.8246875,-7.16456026,-0.038791535,44.99999998 +151.07,50.42898616,-2.576697759,51.1961,7.063626625,7.070328061,1.8753125,-7.167847434,0.062495372,44.99999998 +151.08,50.4289868,-2.576696765,51.1771,7.063626611,7.070105895,1.9265625,-7.169637698,0.163727847,44.99999998 +151.09,50.42898743,-2.57669577,51.1576,7.063626606,7.071438085,1.978125,-7.169930651,0.264817483,44.99999998 +151.1,50.42898807,-2.576694774,51.1375,7.067102784,7.072104122,2.0278125,-7.168726294,0.365676275,44.99999998 +151.11,50.4289887,-2.576693779,51.117,7.077531339,7.0712158,2.075,-7.166024798,0.466216159,44.99999998 +151.12,50.42898934,-2.576692784,51.096,7.084483696,7.070327478,2.1215625,-7.161826793,0.566349472,44.99999998 +151.13,50.42898998,-2.576691789,51.0746,7.07753128,7.07032736,2.1684375,-7.156133082,0.665988952,44.99999998 +151.14,50.42899061,-2.576690794,51.0526,7.067102677,7.071215445,2.2146875,-7.148944983,0.765047626,44.99999998 +151.15,50.42899125,-2.576689799,51.0303,7.063626465,7.072325581,2.2596875,-7.14026387,0.863439204,44.99999998 +151.16,50.42899188,-2.576688803,51.0074,7.063626443,7.072325461,2.3034375,-7.130091635,0.961077859,44.99999998 +151.17,50.42899252,-2.576687808,50.9842,7.067102615,7.071215085,2.34625,-7.11843034,1.057878448,44.99999998 +151.18,50.42899315,-2.576686813,50.9605,7.077531177,7.07032676,2.3884375,-7.105282448,1.153756518,44.99999998 +151.19,50.42899379,-2.576685818,50.9364,7.084483536,7.070104587,2.4296875,-7.09065071,1.248628531,44.99999998 +151.2,50.42899443,-2.576684823,50.9119,7.077531105,7.070326517,2.4696875,-7.07453822,1.342411695,44.99999998 +151.21,50.42899506,-2.576683828,50.887,7.067102488,7.071214599,2.508125,-7.056948301,1.43502425,44.99999998 +151.22,50.4289957,-2.576682833,50.8617,7.063626277,7.072324731,2.545,-7.037884563,1.526385464,44.99999998 +151.23,50.42899633,-2.576681837,50.8361,7.063626263,7.072324609,2.58125,-7.017351131,1.61641564,44.99999998 +151.24,50.42899697,-2.576680842,50.8101,7.067102427,7.071214231,2.6165625,-6.995352187,1.705036283,44.99999998 +151.25,50.4289976,-2.576679847,50.7837,7.077530966,7.070325902,2.65,-6.971892316,1.7921701,44.99999998 +151.26,50.42899824,-2.576678852,50.7571,7.08448332,7.070103727,2.683125,-6.946976501,1.877741117,44.99999998 +151.27,50.42899888,-2.576677857,50.7301,7.077530913,7.070325653,2.7165625,-6.9206099,1.961674679,44.99999998 +151.28,50.42899951,-2.576676862,50.7027,7.067102316,7.071213732,2.7478125,-6.892797956,2.043897675,44.99999998 +151.29,50.42900015,-2.576675867,50.6751,7.063626098,7.072323862,2.7765625,-6.863546627,2.124338371,44.99999998 +151.3,50.42900078,-2.576674871,50.6472,7.063626061,7.072323736,2.805,-6.832861872,2.20292658,44.99999998 +151.31,50.42900142,-2.576673876,50.619,7.063626015,7.071213356,2.8328125,-6.800750166,2.279593833,44.99999998 +151.32,50.42900205,-2.576672881,50.5905,7.063625974,7.070325026,2.858125,-6.767218269,2.354273267,44.99999998 +151.33,50.42900269,-2.576671886,50.5618,7.067102143,7.070102848,2.8815625,-6.732273058,2.426899678,44.99999998 +151.34,50.42900332,-2.576670891,50.5329,7.07753071,7.070324773,2.905,-6.695921922,2.497409813,44.99999998 +151.35,50.42900396,-2.576669896,50.5037,7.084483072,7.07121285,2.928125,-6.658172426,2.565742192,44.99999998 +151.36,50.4290046,-2.576668901,50.4743,7.077530645,7.072100926,2.9496875,-6.619032476,2.631837228,44.99999998 +151.37,50.42900523,-2.576667905,50.4447,7.067102021,7.071434646,2.97,-6.578510208,2.695637224,44.99999998 +151.38,50.42900587,-2.57666691,50.4149,7.06362579,7.070102212,2.989375,-6.536614101,2.757086604,44.99999998 +151.39,50.4290065,-2.576665916,50.3849,7.063625762,7.070324136,3.0065625,-6.493352923,2.816131738,44.99999998 +151.4,50.42900714,-2.57666492,50.3547,7.06710193,7.071212212,3.02125,-6.448735668,2.872721175,44.99999998 +151.41,50.42900777,-2.576663925,50.3245,7.077530482,7.071212083,3.035,-6.402771676,2.926805584,44.99999998 +151.42,50.42900841,-2.57666293,50.294,7.084482837,7.071211955,3.0484375,-6.355470572,2.978337751,44.99999998 +151.43,50.42900905,-2.576661935,50.2635,7.077530414,7.071211827,3.0609375,-6.306842155,3.027272759,44.99999998 +151.44,50.42900968,-2.576660939,50.2328,7.067101792,7.070323495,3.071875,-6.256896679,3.073567921,44.99999998 +151.45,50.42901032,-2.576659945,50.202,7.06362556,7.070101314,3.08125,-6.205644515,3.1171829,44.99999998 +151.46,50.42901095,-2.57665895,50.1712,7.063625531,7.071433491,3.0896875,-6.153096436,3.158079654,44.99999998 +151.47,50.42901159,-2.576657954,50.1402,7.0671017,7.072099516,3.0965625,-6.09926327,3.196222543,44.99999998 +151.48,50.42901222,-2.576656959,50.1092,7.077530255,7.071211183,3.10125,-6.044156418,3.231578221,44.99999998 +151.49,50.42901286,-2.576655964,50.0782,7.084482605,7.07032285,3.105,-5.987787283,3.264115979,44.99999998 +151.5,50.4290135,-2.576654969,50.0471,7.077530168,7.07032272,3.108125,-5.930167725,3.293807339,44.99999998 +151.51,50.42901413,-2.576653974,50.016,7.067101546,7.071210795,3.109375,-5.871309662,3.320626463,44.99999998 +151.52,50.42901477,-2.576652979,49.9849,7.063625329,7.07232092,3.1084375,-5.811225526,3.344549971,44.99999998 +151.53,50.4290154,-2.576651983,49.9538,7.063625311,7.072320792,3.1065625,-5.749927751,3.365556953,44.99999998 +151.54,50.42901604,-2.576650988,49.9228,7.067101476,7.071210409,3.1046875,-5.687429171,3.383629131,44.99999998 +151.55,50.42901667,-2.576649993,49.8917,7.07753001,7.070322076,3.1015625,-5.623742849,3.39875069,44.99999998 +151.56,50.42901731,-2.576648998,49.8607,7.084482347,7.070099896,3.09625,-5.558882079,3.410908568,44.99999998 +151.57,50.42901795,-2.576648003,49.8298,7.077529926,7.070321818,3.0896875,-5.492860381,3.420091993,44.99999998 +151.58,50.42901858,-2.576647008,49.7989,7.067101328,7.071209892,3.0815625,-5.425691622,3.426293115,44.99999998 +151.59,50.42901922,-2.576646013,49.7681,7.063625114,7.072320018,3.07125,-5.357389724,3.429506434,44.99999998 +151.6,50.42901985,-2.576645017,49.7375,7.063625077,7.07231989,3.06,-5.287969069,3.4297292,44.99999998 +151.61,50.42902049,-2.576644022,49.7069,7.067101222,7.071209508,3.0484375,-5.217444038,3.426961127,44.99999998 +151.62,50.42902112,-2.576643027,49.6765,7.077529759,7.070321176,3.03625,-5.145829413,3.421204734,44.99999998 +151.63,50.42902176,-2.576642032,49.6462,7.084482121,7.070098996,3.023125,-5.073140148,3.412465008,44.99999998 +151.64,50.4290224,-2.576641037,49.616,7.077529716,7.070320918,3.0078125,-4.999391427,3.400749568,44.99999998 +151.65,50.42902303,-2.576640042,49.586,7.067101107,7.071208994,2.9896875,-4.924598663,3.386068613,44.99999998 +151.66,50.42902367,-2.576639047,49.5562,7.063624876,7.072319121,2.97,-4.848777439,3.36843492,44.99999998 +151.67,50.4290243,-2.576638051,49.5266,7.063624842,7.072318994,2.9496875,-4.771943626,3.347863959,44.99999998 +151.68,50.42902494,-2.576637056,49.4972,7.063624808,7.071208612,2.9284375,-4.694113269,3.324373607,44.99999998 +151.69,50.42902557,-2.576636061,49.468,7.06362477,7.070320282,2.90625,-4.61530258,3.297984316,44.99999998 +151.7,50.42902621,-2.576635066,49.4391,7.067100928,7.070098105,2.883125,-4.535528062,3.268719122,44.99999998 +151.71,50.42902684,-2.576634071,49.4103,7.077529482,7.070320029,2.8584375,-4.45480633,3.236603577,44.99999998 +151.72,50.42902748,-2.576633076,49.3819,7.084481843,7.071208106,2.8328125,-4.373154287,3.201665699,44.99999998 +151.73,50.42902812,-2.576632081,49.3537,7.077529418,7.072096183,2.8065625,-4.290588948,3.163935913,44.99999998 +151.74,50.42902875,-2.576631085,49.3257,7.067100799,7.071429905,2.7778125,-4.207127619,3.123447105,44.99999998 +151.75,50.42902939,-2.57663009,49.2981,7.063624582,7.070097475,2.7465625,-4.122787658,3.080234571,44.99999998 +151.76,50.42903002,-2.576629096,49.2708,7.063624568,7.070319401,2.7153125,-4.037586714,3.034336068,44.99999998 +151.77,50.42903066,-2.5766281,49.2438,7.067100736,7.07120748,2.6846875,-3.951542548,2.985791589,44.99999998 +151.78,50.42903129,-2.576627105,49.2171,7.077529284,7.071207356,2.653125,-3.864673151,2.934643417,44.99999998 +151.79,50.42903193,-2.57662611,49.1907,7.08448164,7.071429283,2.619375,-3.776996686,2.880936244,44.99999998 +151.8,50.42903257,-2.576625115,49.1647,7.077529223,7.072095311,2.583125,-3.688531429,2.824716823,44.99999998 +151.81,50.4290332,-2.576624119,49.139,7.067100608,7.071429036,2.5453125,-3.599295888,2.766034199,44.99999998 +151.82,50.42903384,-2.576623124,49.1138,7.063624385,7.070096609,2.508125,-3.509308684,2.704939538,44.99999998 +151.83,50.42903447,-2.57662213,49.0889,7.063624369,7.070318537,2.4715625,-3.418588609,2.641486181,44.99999998 +151.84,50.42903511,-2.576621134,49.0643,7.067100547,7.071206619,2.4325,-3.327154572,2.575729362,44.99999998 +151.85,50.42903574,-2.576620139,49.0402,7.077529097,7.071206497,2.39,-3.235025709,2.507726491,44.99999998 +151.86,50.42903638,-2.576619144,49.0165,7.084481443,7.071206376,2.346875,-3.142221271,2.437536812,44.99999998 +151.87,50.42903702,-2.576618149,48.9933,7.07752902,7.071206256,2.3046875,-3.048760624,2.365221631,44.99999998 +151.88,50.42903765,-2.576617153,48.9704,7.067100422,7.070317933,2.2615625,-2.954663307,2.290843917,44.99999998 +151.89,50.42903829,-2.576616159,48.948,7.06362422,7.070095763,2.21625,-2.859948857,2.214468528,44.99999998 +151.9,50.42903892,-2.576615164,48.9261,7.063624201,7.071427948,2.17,-2.764637214,2.1361621,44.99999998 +151.91,50.42903956,-2.576614168,48.9046,7.067100365,7.072093982,2.1234375,-2.6687482,2.055992871,44.99999998 +151.92,50.42904019,-2.576613173,48.8836,7.077528911,7.071205662,2.07625,-2.572301871,1.974030858,44.99999998 +151.93,50.42904083,-2.576612178,48.8631,7.084481265,7.070317342,2.0284375,-2.475318336,1.890347392,44.99999998 +151.94,50.42904147,-2.576611183,48.843,7.077528859,7.070317224,1.9796875,-2.377817822,1.805015585,44.99999998 +151.95,50.4290421,-2.576610188,48.8235,7.067100276,7.07120531,1.9296875,-2.279820782,1.718109747,44.99999998 +151.96,50.42904274,-2.576609193,48.8044,7.063624075,7.072315448,1.8784375,-2.181347614,1.629705683,44.99999998 +151.97,50.42904337,-2.576608197,48.7859,7.063624051,7.072315333,1.82625,-2.082418888,1.539880453,44.99999998 +151.98,50.42904401,-2.576607202,48.7679,7.063624017,7.071204965,1.7734375,-1.983055287,1.448712498,44.99999998 +151.99,50.42904464,-2.576606207,48.7504,7.063623987,7.070316649,1.7196875,-1.883277551,1.356281227,44.99999998 +152,50.42904528,-2.576605212,48.7335,7.067100169,7.070094485,1.665,-1.783106481,1.2626672,44.99999998 +152.01,50.42904591,-2.576604217,48.7171,7.077528747,7.070316423,1.61,-1.682563102,1.167952177,44.99999998 +152.02,50.42904655,-2.576603222,48.7013,7.084481121,7.071204513,1.555,-1.581668271,1.072218665,44.99999998 +152.03,50.42904719,-2.576602227,48.686,7.077528712,7.072314655,1.4996875,-1.480443187,0.975550142,44.99999998 +152.04,50.42904782,-2.576601231,48.6713,7.067100107,7.072314544,1.443125,-1.378908878,0.878030949,44.99999998 +152.05,50.42904846,-2.576600236,48.6571,7.063623895,7.071204181,1.385,-1.277086657,0.779746056,44.99999998 +152.06,50.42904909,-2.576599241,48.6436,7.063623885,7.070315868,1.3265625,-1.174997667,0.680781233,44.99999998 +152.07,50.42904973,-2.576598246,48.6306,7.067100071,7.070093708,1.2684375,-1.072663337,0.581222769,44.99999998 +152.08,50.42905036,-2.576597251,48.6182,7.07752864,7.07031565,1.2096875,-0.970104981,0.481157523,44.99999998 +152.09,50.429051,-2.576596256,48.6064,7.084481016,7.071203745,1.15,-0.867344026,0.380672643,44.99999998 +152.1,50.42905164,-2.576595261,48.5952,7.077528623,7.072313891,1.09,-0.764401959,0.279855792,44.99999998 +152.11,50.42905227,-2.576594265,48.5846,7.067100028,7.072313785,1.03,-0.661300267,0.178794918,44.99999998 +152.12,50.42905291,-2.57659327,48.5746,7.063623809,7.071203426,0.9696875,-0.558060434,0.077578142,44.99999998 +152.13,50.42905354,-2.576592275,48.5652,7.063623793,7.070315118,0.908125,-0.454704062,-0.023706243,44.99999998 +152.14,50.42905418,-2.57659128,48.5564,7.067099988,7.070092963,0.845,-0.35125275,-0.124970002,44.99999998 +152.15,50.42905481,-2.576590285,48.5483,7.077528572,7.070314911,0.781875,-0.2477281,-0.226124784,44.99999998 +152.16,50.42905545,-2.57658929,48.5408,7.084480949,7.07120301,0.72,-0.144151712,-0.327082411,44.99999998 +152.17,50.42905609,-2.576588295,48.5339,7.07752854,7.072313161,0.658125,-0.040545186,-0.427754763,44.99999998 +152.18,50.42905672,-2.576587299,48.5276,7.067099948,7.072313059,0.5946875,0.063069819,-0.528054119,44.99999998 +152.19,50.42905736,-2.576586304,48.522,7.06362376,7.071202705,0.53,0.166671589,-0.627893046,44.99999998 +152.2,50.42905799,-2.576585309,48.517,7.063623771,7.070314403,0.4653125,0.270238638,-0.727184397,44.99999998 +152.21,50.42905863,-2.576584314,48.5127,7.067099967,7.070092252,0.4015625,0.373749193,-0.825841656,44.99999998 +152.22,50.42905926,-2.576583319,48.509,7.077528536,7.070314204,0.3384375,0.477181712,-0.923778707,44.99999998 +152.23,50.4290599,-2.576582324,48.5059,7.084480905,7.071202309,0.275,0.580514535,-1.020910294,44.99999998 +152.24,50.42906054,-2.576581329,48.5035,7.077528505,7.072090414,0.2115625,0.683726179,-1.117151562,44.99999998 +152.25,50.42906117,-2.576580333,48.5017,7.067099931,7.071424165,0.148125,0.786794983,-1.212418687,44.99999998 +152.26,50.42906181,-2.576579338,48.5005,7.063623753,7.070091766,0.083125,0.889699521,-1.30662859,44.99999998 +152.27,50.42906244,-2.576578344,48.5,7.063623756,7.070313721,0.016875,0.992418249,-1.399699052,44.99999998 +152.28,50.42906308,-2.576577348,48.5002,7.063623743,7.071201829,-0.048125,1.094929738,-1.491549,44.99999998 +152.29,50.42906371,-2.576576353,48.501,7.063623734,7.071201735,-0.1115625,1.197212559,-1.582098276,44.99999998 +152.3,50.42906435,-2.576575358,48.5024,7.067099936,7.071201643,-0.1753125,1.299245341,-1.671267926,44.99999998 +152.31,50.42906498,-2.576574363,48.5045,7.077528534,7.071423601,-0.24,1.401006771,-1.758980202,44.99999998 +152.32,50.42906562,-2.576573367,48.5072,7.084480929,7.071201459,-0.3046875,1.502475649,-1.845158669,44.99999998 +152.33,50.42906626,-2.576572373,48.5106,7.077528542,7.071201367,-0.3684375,1.603630774,-1.929728099,44.99999998 +152.34,50.42906689,-2.576571377,48.5146,7.067099966,7.071423327,-0.4315625,1.704450949,-2.012614752,44.99999998 +152.35,50.42906753,-2.576570382,48.5192,7.063623776,7.070979137,-0.4953125,1.804915202,-2.093746378,44.99999998 +152.36,50.42906816,-2.576569387,48.5245,7.063623776,7.070534947,-0.5596875,1.905002507,-2.173052274,44.99999998 +152.37,50.4290688,-2.576568392,48.5304,7.067099972,7.07097896,-0.623125,2.004692006,-2.250463169,44.99999998 +152.38,50.42906943,-2.576567397,48.537,7.077528564,7.071422974,-0.6853125,2.103962846,-2.325911684,44.99999998 +152.39,50.42907007,-2.576566401,48.5441,7.084480968,7.071200837,-0.748125,2.202794284,-2.399331928,44.99999998 +152.4,50.42907071,-2.576565407,48.5519,7.077528598,7.07120075,-0.811875,2.301165694,-2.47065996,44.99999998 +152.41,50.42907134,-2.576564411,48.5604,7.067100024,7.071422715,-0.874375,2.399056508,-2.539833498,44.99999998 +152.42,50.42907198,-2.576563416,48.5694,7.063623826,7.07097853,-0.935,2.496446384,-2.606792326,44.99999998 +152.43,50.42907261,-2.576562421,48.5791,7.063623831,7.070312294,-0.9953125,2.593314869,-2.671477943,44.99999998 +152.44,50.42907325,-2.576561426,48.5893,7.067100045,7.07009016,-1.05625,2.689641736,-2.733833971,44.99999998 +152.45,50.42907388,-2.576560431,48.6002,7.077528647,7.070312128,-1.116875,2.785406934,-2.793806094,44.99999998 +152.46,50.42907452,-2.576559436,48.6117,7.084481049,7.071200248,-1.1765625,2.880590464,-2.851341943,44.99999998 +152.47,50.42907516,-2.576558441,48.6237,7.077528674,7.07231042,-1.2365625,2.975172389,-2.906391441,44.99999998 +152.48,50.42907579,-2.576557445,48.6364,7.067100103,7.072310339,-1.2965625,3.069132998,-2.958906461,44.99999998 +152.49,50.42907643,-2.57655645,48.6497,7.063623923,7.071200007,-1.3546875,3.16245264,-3.00884128,44.99999998 +152.5,50.42907706,-2.576555455,48.6635,7.06362395,7.070311725,-1.4115625,3.25511189,-3.056152353,44.99999998 +152.51,50.4290777,-2.57655446,48.6779,7.067100171,7.070089596,-1.4684375,3.347091326,-3.100798427,44.99999998 +152.52,50.42907833,-2.576553465,48.6929,7.077528764,7.070311568,-1.5246875,3.438371753,-3.142740542,44.99999998 +152.53,50.42907897,-2.57655247,48.7084,7.084481153,7.071199693,-1.58,3.52893415,-3.1819422,44.99999998 +152.54,50.42907961,-2.576551475,48.7245,7.077528774,7.072309869,-1.635,3.618759551,-3.218369081,44.99999998 +152.55,50.42908024,-2.576550479,48.7411,7.06710022,7.072309792,-1.69,3.707829221,-3.251989556,44.99999998 +152.56,50.42908088,-2.576549484,48.7583,7.063624062,7.071199463,-1.7446875,3.796124538,-3.282774178,44.99999998 +152.57,50.42908151,-2.576548489,48.776,7.063624087,7.070311187,-1.798125,3.883627111,-3.310696245,44.99999998 +152.58,50.42908215,-2.576547494,48.7943,7.063624101,7.070089062,-1.85,3.970318604,-3.335731292,44.99999998 +152.59,50.42908278,-2.576546499,48.813,7.063624114,7.070311038,-1.90125,4.056180971,-3.357857547,44.99999998 +152.6,50.42908342,-2.576545504,48.8323,7.067100325,7.071199167,-1.951875,4.141196277,-3.377055643,44.99999998 +152.61,50.42908405,-2.576544509,48.8521,7.077528932,7.072309347,-2.00125,4.22534676,-3.393308966,44.99999998 +152.62,50.42908469,-2.576543513,48.8723,7.084481349,7.072309274,-2.05,4.308614774,-3.406603249,44.99999998 +152.63,50.42908533,-2.576542518,48.8931,7.077528988,7.07119895,-2.0984375,4.390983014,-3.416926917,44.99999998 +152.64,50.42908596,-2.576541523,48.9143,7.06710043,7.070310677,-2.14625,4.472434293,-3.424270975,44.99999998 +152.65,50.4290866,-2.576540528,48.936,7.063624253,7.070088556,-2.193125,4.552951479,-3.428629064,44.99999998 +152.66,50.42908723,-2.576539533,48.9582,7.063624269,7.070310537,-2.238125,4.632517899,-3.429997287,44.99999998 +152.67,50.42908787,-2.576538538,48.9808,7.067100495,7.071198669,-2.28125,4.71111688,-3.428374499,44.99999998 +152.68,50.4290885,-2.576537543,49.0038,7.077529117,7.072086802,-2.3234375,4.788731977,-3.423762132,44.99999998 +152.69,50.42908914,-2.576536547,49.0273,7.084481535,7.071420581,-2.365,4.865347034,-3.416164195,44.99999998 +152.7,50.42908978,-2.576535552,49.0511,7.077529171,7.07008821,-2.4065625,4.940946008,-3.405587337,44.99999998 +152.71,50.42909041,-2.576534558,49.0754,7.067100616,7.070310192,-2.448125,5.015513142,-3.392040724,44.99999998 +152.72,50.42909105,-2.576533562,49.1001,7.063624449,7.071198327,-2.488125,5.089032851,-3.375536217,44.99999998 +152.73,50.42909168,-2.576532567,49.1252,7.063624471,7.07119826,-2.52625,5.161489724,-3.356088196,44.99999998 +152.74,50.42909232,-2.576531572,49.1506,7.067100689,7.071420244,-2.563125,5.232868749,-3.333713563,44.99999998 +152.75,50.42909295,-2.576530577,49.1765,7.077529303,7.07230838,-2.5984375,5.303154972,-3.308431973,44.99999998 +152.76,50.42909359,-2.576529581,49.2026,7.084481729,7.072308315,-2.633125,5.372333667,-3.28026531,44.99999998 +152.77,50.42909423,-2.576528586,49.2291,7.077529379,7.071197997,-2.668125,5.440390396,-3.249238213,44.99999998 +152.78,50.42909486,-2.576527591,49.256,7.067100824,7.070309729,-2.70125,5.507311007,-3.215377782,44.99999998 +152.79,50.4290955,-2.576526596,49.2832,7.063624648,7.070087614,-2.7315625,5.573081462,-3.178713411,44.99999998 +152.8,50.42909613,-2.576525601,49.3106,7.063624679,7.070309601,-2.7615625,5.637688069,-3.139277242,44.99999998 +152.81,50.42909677,-2.576524606,49.3384,7.067100918,7.070975689,-2.7915625,5.701117304,-3.097103537,44.99999998 +152.82,50.4290974,-2.576523611,49.3665,7.077529535,7.071419726,-2.819375,5.763355933,-3.052229082,44.99999998 +152.83,50.42909804,-2.576522615,49.3948,7.084481948,7.071197611,-2.845,5.82439095,-3.004693065,44.99999998 +152.84,50.42909868,-2.576521621,49.4234,7.077529582,7.071197548,-2.87,5.884209635,-2.954536913,44.99999998 +152.85,50.42909931,-2.576520625,49.4522,7.067101023,7.071419536,-2.8946875,5.942799497,-2.901804398,44.99999998 +152.86,50.42909995,-2.57651963,49.4813,7.063624864,7.070975373,-2.918125,6.000148275,-2.846541416,44.99999998 +152.87,50.42910058,-2.576518635,49.5106,7.063624915,7.07030916,-2.939375,6.056243937,-2.788796208,44.99999998 +152.88,50.42910122,-2.57651764,49.5401,7.067101156,7.070087047,-2.9584375,6.111074909,-2.728619139,44.99999998 +152.89,50.42910185,-2.576516645,49.5698,7.077529766,7.070309035,-2.9765625,6.164629618,-2.66606269,44.99999998 +152.9,50.42910249,-2.57651565,49.5996,7.084482172,7.071197175,-2.995,6.216896948,-2.60118135,44.99999998 +152.91,50.42910313,-2.576514655,49.6297,7.077529808,7.072307366,-3.013125,6.267865898,-2.534031785,44.99999998 +152.92,50.42910376,-2.576513659,49.6599,7.067101267,7.072307305,-3.029375,6.317525984,-2.464672494,44.99999998 +152.93,50.4291044,-2.576512664,49.6903,7.063625123,7.071196992,-3.043125,6.365866662,-2.393163981,44.99999998 +152.94,50.42910503,-2.576511669,49.7208,7.063625162,7.070308729,-3.0546875,6.412877907,-2.319568583,44.99999998 +152.95,50.42910567,-2.576510674,49.7514,7.06362519,7.070086618,-3.065,6.45854992,-2.243950473,44.99999998 +152.96,50.4291063,-2.576509679,49.7821,7.063625216,7.070308608,-3.075,6.50287319,-2.166375654,44.99999998 +152.97,50.42910694,-2.576508684,49.8129,7.067101441,7.071196749,-3.0846875,6.545838378,-2.086911679,44.99999998 +152.98,50.42910757,-2.576507689,49.8438,7.077530062,7.072306941,-3.093125,6.587436546,-2.005627876,44.99999998 +152.99,50.42910821,-2.576506693,49.8748,7.084482491,7.072306881,-3.0996875,6.627659043,-1.922595176,44.99999998 +153,50.42910885,-2.576505698,49.9058,7.077530141,7.071196568,-3.1046875,6.666497388,-1.837885887,44.99999998 +153.01,50.42910948,-2.576504703,49.9369,7.067101594,7.070308305,-3.108125,6.703943561,-1.751573978,44.99999998 +153.02,50.42911012,-2.576503708,49.968,7.063625433,7.070086195,-3.109375,6.739989711,-1.663734677,44.99999998 +153.03,50.42911075,-2.576502713,49.9991,7.063625462,7.070308185,-3.1084375,6.774628275,-1.574444534,44.99999998 +153.04,50.42911139,-2.576501718,50.0302,7.067101687,7.071196327,-3.1065625,6.807852035,-1.483781525,44.99999998 +153.05,50.42911202,-2.576500723,50.0612,7.077530309,7.072306518,-3.105,6.839654057,-1.39182455,44.99999998 +153.06,50.42911266,-2.576499727,50.0923,7.084482741,7.072306458,-3.103125,6.870027753,-1.298653934,44.99999998 +153.07,50.4291133,-2.576498732,50.1233,7.077530395,7.071196146,-3.099375,6.898966706,-1.204350868,44.99999998 +153.08,50.42911393,-2.576497737,50.1543,7.067101843,7.070307884,-3.093125,6.926464898,-1.10899757,44.99999998 +153.09,50.42911457,-2.576496742,50.1852,7.063625669,7.070085772,-3.085,6.952516602,-1.012677234,44.99999998 +153.1,50.4291152,-2.576495747,50.216,7.063625697,7.070307762,-3.0765625,6.977116315,-0.915473799,44.99999998 +153.11,50.42911584,-2.576494752,50.2467,7.067101937,7.071195903,-3.0678125,7.000258998,-0.817472118,44.99999998 +153.12,50.42911647,-2.576493757,50.2774,7.07753057,7.072306095,-3.0565625,7.021939721,-0.718757506,44.99999998 +153.13,50.42911711,-2.576492761,50.3079,7.084482997,7.072306034,-3.0428125,7.042154015,-0.619416193,44.99999998 +153.14,50.42911775,-2.576491766,50.3382,7.07753063,7.071195721,-3.0284375,7.060897699,-0.519534695,44.99999998 +153.15,50.42911838,-2.576490771,50.3685,7.067102064,7.070307458,-3.013125,7.078166762,-0.419200216,44.99999998 +153.16,50.42911902,-2.576489776,50.3985,7.063625904,7.070085345,-2.9965625,7.093957593,-0.318500134,44.99999998 +153.17,50.42911965,-2.576488781,50.4284,7.063625955,7.070307334,-2.98,7.108267042,-0.217522338,44.99999998 +153.18,50.42912029,-2.576487786,50.4581,7.067102197,7.071195474,-2.9625,7.121091958,-0.116354837,44.99999998 +153.19,50.42912092,-2.576486791,50.4877,7.077530808,7.072305665,-2.9415625,7.132429704,-0.015085864,44.99999998 +153.2,50.42912156,-2.576485795,50.517,7.084483215,7.072305603,-2.918125,7.142277989,0.086196229,44.99999998 +153.21,50.4291222,-2.5764848,50.546,7.077530848,7.071195288,-2.895,7.150634693,0.18740315,44.99999998 +153.22,50.42912283,-2.576483805,50.5749,7.067102305,7.070307023,-2.8715625,7.15749804,0.288446721,44.99999998 +153.23,50.42912347,-2.57648281,50.6035,7.063626158,7.07008491,-2.84625,7.162866654,0.389238706,44.99999998 +153.24,50.4291241,-2.576481815,50.6318,7.063626195,7.070306897,-2.82,7.166739391,0.489691271,44.99999998 +153.25,50.42912474,-2.57648082,50.6599,7.063626222,7.071195035,-2.793125,7.169115447,0.589716811,44.99999998 +153.26,50.42912537,-2.576479825,50.6877,7.063626252,7.072305223,-2.764375,7.169994364,0.68922812,44.99999998 +153.27,50.42912601,-2.576478829,50.7152,7.067102475,7.072305159,-2.7334375,7.169375856,0.788138398,44.99999998 +153.28,50.42912664,-2.576477834,50.7424,7.077531083,7.071194842,-2.7015625,7.167260152,0.886361469,44.99999998 +153.29,50.42912728,-2.576476839,50.7692,7.084483498,7.070306576,-2.6696875,7.163647653,0.983811563,44.99999998 +153.3,50.42912792,-2.576475844,50.7958,7.077531143,7.07008446,-2.6365625,7.158539104,1.080403768,44.99999998 +153.31,50.42912855,-2.576474849,50.822,7.067102599,7.070306444,-2.60125,7.151935594,1.176053858,44.99999998 +153.32,50.42912919,-2.576473854,50.8478,7.06362644,7.070972529,-2.565,7.143838497,1.270678411,44.99999998 +153.33,50.42912982,-2.576472859,50.8733,7.063626465,7.071416564,-2.528125,7.134249532,1.364194863,44.99999998 +153.34,50.42913046,-2.576471863,50.8984,7.067102673,7.071194447,-2.4896875,7.123170649,1.456521798,44.99999998 +153.35,50.42913109,-2.576470869,50.9231,7.077531278,7.071194379,-2.45,7.110604137,1.547578543,44.99999998 +153.36,50.42913173,-2.576469873,50.9474,7.084483706,7.071416362,-2.41,7.096552691,1.637285857,44.99999998 +153.37,50.42913237,-2.576468878,50.9713,7.077531359,7.070972193,-2.3696875,7.081019232,1.725565361,44.99999998 +153.38,50.429133,-2.576467883,50.9948,7.067102807,7.070528024,-2.328125,7.064007027,1.812340162,44.99999998 +153.39,50.42913364,-2.576466888,51.0179,7.063626625,7.070972055,-2.2846875,7.045519569,1.897534632,44.99999998 +153.4,50.42913427,-2.576465893,51.0405,7.063626634,7.071416086,-2.2396875,7.025560699,1.9810744,44.99999998 +153.41,50.42913491,-2.576464897,51.0627,7.067102851,7.071193966,-2.1934375,7.004134713,2.062886585,44.99999998 +153.42,50.42913554,-2.576463903,51.0844,7.077531471,7.071193896,-2.1465625,6.981245966,2.142899969,44.99999998 +153.43,50.42913618,-2.576462907,51.1056,7.084483896,7.071415874,-2.1,6.956899271,2.221044651,44.99999998 +153.44,50.42913682,-2.576461912,51.1264,7.077531537,7.070971701,-2.053125,6.931099669,2.297252622,44.99999998 +153.45,50.42913745,-2.576460917,51.1467,7.067102972,7.070305478,-2.0046875,6.903852661,2.371457303,44.99999998 +153.46,50.42913809,-2.576459922,51.1665,7.063626787,7.070083355,-1.955,6.875163862,2.443594064,44.99999998 +153.47,50.42913872,-2.576458927,51.1858,7.063626809,7.070305332,-1.9046875,6.84503923,2.513599938,44.99999998 +153.48,50.42913936,-2.576457932,51.2046,7.067103038,7.07119346,-1.853125,6.813485127,2.581413962,44.99999998 +153.49,50.42913999,-2.576456937,51.2229,7.077531648,7.072303637,-1.8,6.78050814,2.64697695,44.99999998 +153.5,50.42914063,-2.576455941,51.2406,7.084484051,7.072303562,-1.7465625,6.746115088,2.71023172,44.99999998 +153.51,50.42914127,-2.576454946,51.2578,7.077531673,7.071415285,-1.6934375,6.710313247,2.771123096,44.99999998 +153.52,50.4291419,-2.576453951,51.2745,7.067103103,7.071193159,-1.6396875,6.673110009,2.829598022,44.99999998 +153.53,50.42914254,-2.576452956,51.2906,7.063626932,7.071193082,-1.585,6.634513165,2.885605564,44.99999998 +153.54,50.42914317,-2.57645196,51.3062,7.063626957,7.070304803,-1.5296875,6.594530852,2.939096732,44.99999998 +153.55,50.42914381,-2.576450966,51.3212,7.063626976,7.070082674,-1.473125,6.553171264,2.990025002,44.99999998 +153.56,50.42914444,-2.576449971,51.3357,7.063626995,7.071414898,-1.415,6.510443223,3.038345913,44.99999998 +153.57,50.42914508,-2.576448975,51.3495,7.06710321,7.072080969,-1.3565625,6.466355495,3.084017353,44.99999998 +153.58,50.42914571,-2.57644798,51.3628,7.077531806,7.071192688,-1.2984375,6.420917364,3.126999501,44.99999998 +153.59,50.42914635,-2.576446985,51.3755,7.084484195,7.070304407,-1.2396875,6.374138282,3.167254828,44.99999998 +153.6,50.42914699,-2.57644599,51.3876,7.077531813,7.070082275,-1.18,6.326028105,3.204748269,44.99999998 +153.61,50.42914762,-2.576444995,51.3991,7.067103251,7.070304243,-1.12,6.276596801,3.239447109,44.99999998 +153.62,50.42914826,-2.576444,51.41,7.063627075,7.071192362,-1.06,6.225854685,3.271321152,44.99999998 +153.63,50.42914889,-2.576443005,51.4203,7.063627083,7.07230253,-1,6.173812355,3.300342496,44.99999998 +153.64,50.42914953,-2.576442009,51.43,7.067103285,7.072302446,-0.9396875,6.120480756,3.32648593,44.99999998 +153.65,50.42915016,-2.576441014,51.4391,7.077531885,7.07119211,-0.878125,6.065870945,3.349728593,44.99999998 +153.66,50.4291508,-2.576440019,51.4476,7.084484291,7.070303823,-0.815,6.009994382,3.37005026,44.99999998 +153.67,50.42915144,-2.576439024,51.4554,7.077531913,7.070081687,-0.751875,5.952862698,3.387433227,44.99999998 +153.68,50.42915207,-2.576438029,51.4626,7.06710334,7.070303651,-0.69,5.89448781,3.401862252,44.99999998 +153.69,50.42915271,-2.576437034,51.4692,7.063627158,7.071191765,-0.628125,5.834881922,3.413324789,44.99999998 +153.7,50.42915334,-2.576436039,51.4752,7.063627161,7.072301928,-0.5646875,5.774057524,3.421810924,44.99999998 +153.71,50.42915398,-2.576435043,51.4805,7.067103347,7.072301839,-0.5,5.71202728,3.427313095,44.99999998 +153.72,50.42915461,-2.576434048,51.4852,7.07753193,7.071191498,-0.4353125,5.648804195,3.429826661,44.99999998 +153.73,50.42915525,-2.576433053,51.4892,7.084484336,7.070303207,-0.3715625,5.58440139,3.429349387,44.99999998 +153.74,50.42915589,-2.576432058,51.4926,7.077531965,7.070081065,-0.3084375,5.518832329,3.425881617,44.99999998 +153.75,50.42915652,-2.576431063,51.4954,7.067103382,7.070303024,-0.2446875,5.452110763,3.419426445,44.99999998 +153.76,50.42915716,-2.576430068,51.4975,7.063627177,7.071191133,-0.18,5.384250616,3.409989487,44.99999998 +153.77,50.42915779,-2.576429073,51.499,7.063627179,7.072301291,-0.115,5.315265982,3.397578992,44.99999998 +153.78,50.42915843,-2.576428077,51.4998,7.067103389,7.072301198,-0.05,5.245171356,3.382205732,44.99999998 +153.79,50.42915906,-2.576427082,51.5,7.077531979,7.071190852,0.0146875,5.17398135,3.363883114,44.99999998 +153.8,50.4291597,-2.576426087,51.4995,7.084484364,7.070302556,0.0784375,5.101710803,3.342627182,44.99999998 +153.81,50.42916034,-2.576425092,51.4984,7.07753197,7.070080409,0.141875,5.028374841,3.318456385,44.99999998 +153.82,50.42916097,-2.576424097,51.4967,7.067103375,7.070302363,0.2065625,4.953988762,3.291391864,44.99999998 +153.83,50.42916161,-2.576423102,51.4943,7.06362717,7.071190467,0.2715625,4.878568093,3.261457226,44.99999998 +153.84,50.42916224,-2.576422107,51.4912,7.063627174,7.07230062,0.335,4.802128647,3.228678539,44.99999998 +153.85,50.42916288,-2.576421111,51.4876,7.067103381,7.072300522,0.3984375,4.724686297,3.193084396,44.99999998 +153.86,50.42916351,-2.576420116,51.4833,7.077531966,7.071190171,0.4634375,4.646257255,3.154705792,44.99999998 +153.87,50.42916415,-2.576419121,51.4783,7.084484344,7.07030187,0.528125,4.56685791,3.113576303,44.99999998 +153.88,50.42916479,-2.576418126,51.4727,7.07753194,7.070079718,0.59125,4.486504819,3.069731682,44.99999998 +153.89,50.42916542,-2.576417131,51.4665,7.067103345,7.070301666,0.6534375,4.405214828,3.023210259,44.99999998 +153.9,50.42916606,-2.576416136,51.4596,7.063627148,7.070967715,0.7153125,4.323004838,2.974052486,44.99999998 +153.91,50.42916669,-2.576415141,51.4522,7.063627147,7.071411713,0.778125,4.239892038,2.922301333,44.99999998 +153.92,50.42916733,-2.576414145,51.4441,7.063627141,7.07118956,0.841875,4.15589379,2.868001894,44.99999998 +153.93,50.42916796,-2.576413151,51.4353,7.063627132,7.071189456,0.904375,4.071027625,2.811201494,44.99999998 +153.94,50.4291686,-2.576412155,51.426,7.067103315,7.071411401,0.965,3.985311306,2.751949693,44.99999998 +153.95,50.42916923,-2.57641116,51.416,7.077531883,7.071189245,1.025,3.89876265,2.690298174,44.99999998 +153.96,50.42916987,-2.576410165,51.4055,7.084484257,7.071411188,1.085,3.811399822,2.626300679,44.99999998 +153.97,50.42917051,-2.57640917,51.3943,7.07753186,7.072077232,1.1453125,3.72324104,2.560012957,44.99999998 +153.98,50.42917114,-2.576408174,51.3826,7.067103272,7.071410974,1.20625,3.634304698,2.491492935,44.99999998 +153.99,50.42917178,-2.576407179,51.3702,7.063627071,7.070078564,1.2665625,3.544609416,2.420800199,44.99999998 +154,50.42917241,-2.576406185,51.3572,7.063627053,7.070300505,1.3246875,3.454173872,2.347996572,44.99999998 +154.01,50.42917305,-2.576405189,51.3437,7.067103218,7.071188596,1.3815625,3.363016917,2.273145423,44.99999998 +154.02,50.42917368,-2.576404194,51.3296,7.077531781,7.071188487,1.4384375,3.271157688,2.196312069,44.99999998 +154.03,50.42917432,-2.576403199,51.3149,7.084484166,7.071188376,1.495,3.178615321,2.117563489,44.99999998 +154.04,50.42917496,-2.576402204,51.2997,7.077531776,7.071188264,1.5515625,3.085409125,2.036968381,44.99999998 +154.05,50.42917559,-2.576401208,51.2839,7.067103179,7.07029995,1.608125,2.991558581,1.954596989,44.99999998 +154.06,50.42917623,-2.576400214,51.2675,7.063626954,7.070077788,1.663125,2.897083283,1.870521162,44.99999998 +154.07,50.42917686,-2.576399219,51.2506,7.063626918,7.071409975,1.7165625,2.802002943,1.784814239,44.99999998 +154.08,50.4291775,-2.576398223,51.2332,7.067103094,7.072076012,1.77,2.706337497,1.697550876,44.99999998 +154.09,50.42917813,-2.576397228,51.2152,7.077531677,7.071409747,1.823125,2.610106829,1.608807276,44.99999998 +154.1,50.42917877,-2.576396233,51.1967,7.08448406,7.071187582,1.8746875,2.513331049,1.518660732,44.99999998 +154.11,50.42917941,-2.576395238,51.1777,7.077531646,7.071187466,1.925,2.41603044,1.427189911,44.99999998 +154.12,50.42918004,-2.576394242,51.1582,7.067103026,7.070299149,1.975,2.318225283,1.334474568,44.99999998 +154.13,50.42918068,-2.576393248,51.1382,7.063626798,7.070076982,2.025,2.219935978,1.240595548,44.99999998 +154.14,50.42918131,-2.576392253,51.1177,7.063626783,7.071409166,2.0746875,2.121183035,1.145634669,44.99999998 +154.15,50.42918195,-2.576391257,51.0967,7.063626776,7.072075198,2.123125,2.021987139,1.049674838,44.99999998 +154.16,50.42918258,-2.576390262,51.0752,7.063626758,7.07118688,2.1696875,1.922368972,0.952799592,44.99999998 +154.17,50.42918322,-2.576389267,51.0533,7.067102922,7.070298561,2.2146875,1.822349334,0.855093558,44.99999998 +154.18,50.42918385,-2.576388272,51.0309,7.077531473,7.070076391,2.2584375,1.721949137,0.756641876,44.99999998 +154.19,50.42918449,-2.576387277,51.0081,7.084483833,7.07029832,2.3015625,1.621189353,0.657530376,44.99999998 +154.2,50.42918513,-2.576386282,50.9849,7.077531423,7.0711864,2.345,1.52009095,0.55784546,44.99999998 +154.21,50.42918576,-2.576385287,50.9612,7.067102821,7.07229653,2.3878125,1.418675128,0.45767416,44.99999998 +154.22,50.4291864,-2.576384291,50.9371,7.063626603,7.072296409,2.428125,1.31696303,0.357103738,44.99999998 +154.23,50.42918703,-2.576383296,50.9126,7.063626578,7.071186037,2.4665625,1.214975912,0.256221856,44.99999998 +154.24,50.42918767,-2.576382301,50.8878,7.067102751,7.070297714,2.505,1.112735089,0.155116635,44.99999998 +154.25,50.4291883,-2.576381306,50.8625,7.077531302,7.070075542,2.543125,1.010261816,0.053876081,44.99999998 +154.26,50.42918894,-2.576380311,50.8369,7.084483648,7.070297468,2.5796875,0.907577638,-0.047411398,44.99999998 +154.27,50.42918958,-2.576379316,50.8109,7.077531225,7.071185545,2.615,0.804703868,-0.148657567,44.99999998 +154.28,50.42919021,-2.576378321,50.7846,7.067102624,7.072295672,2.6496875,0.701662049,-0.249774075,44.99999998 +154.29,50.42919085,-2.576377325,50.7579,7.063626416,7.072295549,2.6834375,0.598473726,-0.350672802,44.99999998 +154.3,50.42919148,-2.57637633,50.7309,7.063626391,7.071185173,2.71625,0.495160382,-0.451265742,44.99999998 +154.31,50.42919212,-2.576375335,50.7036,7.067102543,7.070296848,2.748125,0.391743678,-0.551465174,44.99999998 +154.32,50.42919275,-2.57637434,50.6759,7.077531079,7.070296723,2.7778125,0.288245097,-0.651183723,44.99999998 +154.33,50.42919339,-2.576373345,50.648,7.084483437,7.071184797,2.8046875,0.184686356,-0.750334413,44.99999998 +154.34,50.42919403,-2.57637235,50.6198,7.077531036,7.072294922,2.8303125,0.081089055,-0.848830786,44.99999998 +154.35,50.42919466,-2.576371354,50.5914,7.067102435,7.072294795,2.85625,-0.022525205,-0.946587011,44.99999998 +154.36,50.4291953,-2.576370359,50.5627,7.063626205,7.071184419,2.8815625,-0.126134711,-1.043517719,44.99999998 +154.37,50.42919593,-2.576369364,50.5337,7.063626158,7.070296092,2.9046875,-0.229717917,-1.13953857,44.99999998 +154.38,50.42919657,-2.576368369,50.5046,7.067102308,7.070073915,2.9265625,-0.333253167,-1.234565626,44.99999998 +154.39,50.4291972,-2.576367374,50.4752,7.077530859,7.070295838,2.9484375,-0.436718745,-1.328516208,44.99999998 +154.4,50.42919784,-2.576366379,50.4456,7.084483229,7.071183911,2.969375,-0.540093222,-1.42130827,44.99999998 +154.41,50.42919848,-2.576365384,50.4158,7.077530824,7.072294033,2.988125,-0.643354828,-1.51286091,44.99999998 +154.42,50.42919911,-2.576364388,50.3858,7.067102213,7.072293905,3.005,-0.746482131,-1.603094314,44.99999998 +154.43,50.42919975,-2.576363393,50.3557,7.063625975,7.071183527,3.02125,-0.849453476,-1.691929816,44.99999998 +154.44,50.42920038,-2.576362398,50.3254,7.063625931,7.070295199,3.0365625,-0.95224749,-1.779289894,44.99999998 +154.45,50.42920102,-2.576361403,50.2949,7.067102094,7.07007302,3.049375,-1.054842574,-1.86509846,44.99999998 +154.46,50.42920165,-2.576360408,50.2644,7.07753065,7.070294942,3.06,-1.157217412,-1.949280628,44.99999998 +154.47,50.42920229,-2.576359413,50.2337,7.084483008,7.071183014,3.07,-1.259350577,-2.031762944,44.99999998 +154.48,50.42920293,-2.576358418,50.203,7.077530586,7.072293135,3.0796875,-1.361220754,-2.112473561,44.99999998 +154.49,50.42920356,-2.576357422,50.1721,7.067101968,7.072293006,3.0884375,-1.462806629,-2.191342061,44.99999998 +154.5,50.4292042,-2.576356427,50.1412,7.063625734,7.071182627,3.0959375,-1.564087061,-2.268299689,44.99999998 +154.51,50.42920483,-2.576355432,50.1102,7.063625696,7.070294299,3.1015625,-1.665040792,-2.343279353,44.99999998 +154.52,50.42920547,-2.576354437,50.0791,7.063625666,7.07007212,3.1046875,-1.765646852,-2.41621562,44.99999998 +154.53,50.4292061,-2.576353442,50.0481,7.063625642,7.07029404,3.1065625,-1.865884157,-2.487044891,44.99999998 +154.54,50.42920674,-2.576352447,50.017,7.067101809,7.071182111,3.1084375,-1.965731793,-2.555705403,44.99999998 +154.55,50.42920737,-2.576351452,49.9859,7.077530353,7.072292232,3.1096875,-2.065168905,-2.622137339,44.99999998 +154.56,50.42920801,-2.576350456,49.9548,7.084482692,7.072292103,3.109375,-2.164174751,-2.686282714,44.99999998 +154.57,50.42920865,-2.576349461,49.9237,7.077530263,7.071181724,3.1065625,-2.262728591,-2.748085666,44.99999998 +154.58,50.42920928,-2.576348466,49.8926,7.067101656,7.070293395,3.10125,-2.360809971,-2.807492165,44.99999998 +154.59,50.42920992,-2.576347471,49.8617,7.063625437,7.070071216,3.095,-2.458398262,-2.864450529,44.99999998 +154.6,50.42921055,-2.576346476,49.8307,7.063625408,7.070293137,3.0884375,-2.555473184,-2.918911085,44.99999998 +154.61,50.42921119,-2.576345481,49.7999,7.067101573,7.071181208,3.08125,-2.652014395,-2.970826275,44.99999998 +154.62,50.42921182,-2.576344486,49.7691,7.077530117,7.07206928,3.073125,-2.748001785,-3.020150836,44.99999998 +154.63,50.42921246,-2.57634349,49.7384,7.084482457,7.071403002,3.0628125,-2.843415301,-3.066841797,44.99999998 +154.64,50.4292131,-2.576342495,49.7078,7.077530029,7.070070573,3.05,-2.938235003,-3.11085842,44.99999998 +154.65,50.42921373,-2.576341501,49.6774,7.067101425,7.070292494,3.0365625,-3.032441067,-3.152162375,44.99999998 +154.66,50.42921437,-2.576340505,49.6471,7.063625212,7.071180566,3.023125,-3.126013842,-3.190717564,44.99999998 +154.67,50.429215,-2.57633951,49.6169,7.063625177,7.071180438,3.0078125,-3.218933845,-3.226490356,44.99999998 +154.68,50.42921564,-2.576338515,49.5869,7.067101323,7.07140236,2.9896875,-3.31118154,-3.259449639,44.99999998 +154.69,50.42921627,-2.57633752,49.5571,7.077529865,7.072068383,2.97,-3.402737789,-3.28956665,44.99999998 +154.7,50.42921691,-2.576336524,49.5275,7.084482232,7.071402105,2.95,-3.493583399,-3.31681509,44.99999998 +154.71,50.42921755,-2.576335529,49.4981,7.077529828,7.070069678,2.9296875,-3.583699404,-3.341171239,44.99999998 +154.72,50.42921818,-2.576334535,49.4689,7.067101222,7.070291601,2.908125,-3.673067069,-3.362613841,44.99999998 +154.73,50.42921882,-2.576333539,49.4399,7.06362499,7.071179674,2.8846875,-3.761667601,-3.381124159,44.99999998 +154.74,50.42921945,-2.576332544,49.4112,7.063624943,7.071179548,2.8596875,-3.84948255,-3.396686094,44.99999998 +154.75,50.42922009,-2.576331549,49.3827,7.067101095,7.071179422,2.8334375,-3.936493583,-3.409286066,44.99999998 +154.76,50.42922072,-2.576330554,49.3545,7.077529653,7.071401345,2.80625,-4.022682592,-3.418913132,44.99999998 +154.77,50.42922136,-2.576329558,49.3266,7.084482025,7.07117917,2.778125,-4.108031474,-3.425558813,44.99999998 +154.78,50.429222,-2.576328564,49.2989,7.07752961,7.071179045,2.748125,-4.192522409,-3.429217377,44.99999998 +154.79,50.42922263,-2.576327568,49.2716,7.067100986,7.07140097,2.7165625,-4.276137864,-3.429885561,44.99999998 +154.8,50.42922327,-2.576326573,49.2446,7.063624752,7.070956745,2.685,-4.35886025,-3.427562904,44.99999998 +154.81,50.4292239,-2.576325578,49.2179,7.06362473,7.070512521,2.653125,-4.440672321,-3.422251299,44.99999998 +154.82,50.42922454,-2.576324583,49.1915,7.067100911,7.070956498,2.6196875,-4.521557059,-3.4139555,44.99999998 +154.83,50.42922517,-2.576323588,49.1655,7.077529468,7.071400474,2.5846875,-4.601497506,-3.40268267,44.99999998 +154.84,50.42922581,-2.576322592,49.1398,7.084481823,7.071178301,2.548125,-4.680477045,-3.388442607,44.99999998 +154.85,50.42922645,-2.576321598,49.1145,7.077529407,7.071178178,2.5096875,-4.758479061,-3.371247799,44.99999998 +154.86,50.42922708,-2.576320602,49.0896,7.067100797,7.071400106,2.47,-4.835487339,-3.351113203,44.99999998 +154.87,50.42922772,-2.576319607,49.0651,7.06362457,7.070955884,2.43,-4.911485836,-3.328056407,44.99999998 +154.88,50.42922835,-2.576318612,49.041,7.06362454,7.070289613,2.39,-4.986458567,-3.302097466,44.99999998 +154.89,50.42922899,-2.576317617,49.0173,7.063624519,7.070067443,2.3496875,-5.060390004,-3.273259068,44.99999998 +154.9,50.42922962,-2.576316622,48.994,7.063624502,7.070289372,2.3078125,-5.133264563,-3.241566366,44.99999998 +154.91,50.42923026,-2.576315627,48.9711,7.067100678,7.071177452,2.263125,-5.205067176,-3.207046919,44.99999998 +154.92,50.42923089,-2.576314632,48.9487,7.07752923,7.072287581,2.216875,-5.275782772,-3.169730923,44.99999998 +154.93,50.42923153,-2.576313636,48.9268,7.084481578,7.072287462,2.1715625,-5.345396572,-3.129650806,44.99999998 +154.94,50.42923217,-2.576312641,48.9053,7.077529161,7.071177094,2.1265625,-5.41389402,-3.086841634,44.99999998 +154.95,50.4292328,-2.576311646,48.8842,7.067100569,7.070288777,2.079375,-5.481260908,-3.041340706,44.99999998 +154.96,50.42923344,-2.576310651,48.8637,7.063624369,7.070066611,2.03,-5.547483026,-2.993187672,44.99999998 +154.97,50.42923407,-2.576309656,48.8436,7.063624352,7.070288544,1.98,-5.612546681,-2.942424528,44.99999998 +154.98,50.42923471,-2.576308661,48.8241,7.067100512,7.071176627,1.9296875,-5.676438236,-2.889095564,44.99999998 +154.99,50.42923534,-2.576307666,48.805,7.077529054,7.07228676,1.8784375,-5.739144284,-2.833247248,44.99999998 +155,50.42923598,-2.57630667,48.7865,7.084481421,7.072286645,1.8265625,-5.800651876,-2.77492828,44.99999998 +155.01,50.42923662,-2.576305675,48.7685,7.077529033,7.071176281,1.775,-5.860948006,-2.71418954,44.99999998 +155.02,50.42923725,-2.57630468,48.751,7.067100447,7.070287967,1.723125,-5.920020184,-2.651084026,44.99999998 +155.03,50.42923789,-2.576303685,48.734,7.063624231,7.070065804,1.6696875,-5.977855977,-2.585666684,44.99999998 +155.04,50.42923852,-2.57630269,48.7176,7.063624198,7.070287741,1.6146875,-6.034443466,-2.517994639,44.99999998 +155.05,50.42923916,-2.576301695,48.7017,7.067100364,7.071175828,1.558125,-6.089770677,-2.448126848,44.99999998 +155.06,50.42923979,-2.5763007,48.6864,7.077528934,7.072285966,1.5,-6.143826151,-2.376124216,44.99999998 +155.07,50.42924043,-2.576299704,48.6717,7.084481321,7.072285855,1.441875,-6.196598543,-2.302049654,44.99999998 +155.08,50.42924107,-2.576298709,48.6576,7.077528924,7.071175496,1.3853125,-6.248076853,-2.225967562,44.99999998 +155.09,50.4292417,-2.576297714,48.644,7.067100323,7.070287187,1.3296875,-6.298250309,-2.147944461,44.99999998 +155.1,50.42924234,-2.576296719,48.631,7.063624107,7.070065027,1.2728125,-6.347108482,-2.068048304,44.99999998 +155.11,50.42924297,-2.576295724,48.6185,7.06362409,7.070286969,1.213125,-6.394641176,-1.98634882,44.99999998 +155.12,50.42924361,-2.576294729,48.6067,7.063624082,7.07117506,1.1515625,-6.440838419,-1.902917169,44.99999998 +155.13,50.42924424,-2.576293734,48.5955,7.063624077,7.072285202,1.0903125,-6.485690529,-1.817826119,44.99999998 +155.14,50.42924488,-2.576292738,48.5849,7.067100261,7.072285096,1.03,-6.529188225,-1.73114998,44.99999998 +155.15,50.42924551,-2.576291743,48.5749,7.077528833,7.071174741,0.97,-6.571322338,-1.642964155,44.99999998 +155.16,50.42924615,-2.576290748,48.5655,7.084481214,7.070286437,0.9096875,-6.612084159,-1.553345706,44.99999998 +155.17,50.42924679,-2.576289753,48.5567,7.077528814,7.070064283,0.848125,-6.651465153,-1.462372728,44.99999998 +155.18,50.42924742,-2.576288758,48.5485,7.067100211,7.070286229,0.785,-6.68945701,-1.370124461,44.99999998 +155.19,50.42924806,-2.576287763,48.541,7.063624003,7.071174325,0.7215625,-6.726051882,-1.276681519,44.99999998 +155.2,50.42924869,-2.576286768,48.5341,7.063624007,7.072284472,0.6584375,-6.761242148,-1.182125205,44.99999998 +155.21,50.42924933,-2.576285772,48.5278,7.067100208,7.07228437,0.595,-6.795020359,-1.08653814,44.99999998 +155.22,50.42924996,-2.576284777,48.5222,7.07752878,7.07117402,0.5315625,-6.827379583,-0.990003518,44.99999998 +155.23,50.4292506,-2.576283782,48.5172,7.084481146,7.070285722,0.4684375,-6.858312944,-0.892605678,44.99999998 +155.24,50.42925124,-2.576282787,48.5128,7.077528749,7.070063572,0.405,-6.887814025,-0.794429417,44.99999998 +155.25,50.42925187,-2.576281792,48.5091,7.067100177,7.070285522,0.3415625,-6.915876696,-0.69556045,44.99999998 +155.26,50.42925251,-2.576280797,48.506,7.063623996,7.071173623,0.2784375,-6.942495054,-0.596084893,44.99999998 +155.27,50.42925314,-2.576279802,48.5035,7.063624001,7.072283775,0.2146875,-6.9676636,-0.496089548,44.99999998 +155.28,50.42925378,-2.576278806,48.5017,7.067100186,7.072283678,0.1496875,-6.991377006,-0.39566162,44.99999998 +155.29,50.42925441,-2.576277811,48.5005,7.07752875,7.071173334,0.08375,-7.013630343,-0.294888657,44.99999998 +155.3,50.42925505,-2.576276816,48.5,7.084481124,7.07028504,0.0184375,-7.034419028,-0.193858551,44.99999998 +155.31,50.42925569,-2.576275821,48.5002,7.077528738,7.070062896,-0.045,-7.053738592,-0.092659422,44.99999998 +155.32,50.42925632,-2.576274826,48.5009,7.067100173,7.070284851,-0.1084375,-7.071585138,0.008620494,44.99999998 +155.33,50.42925696,-2.576273831,48.5023,7.063623998,7.071172957,-0.17375,-7.087954829,0.109892961,44.99999998 +155.34,50.42925759,-2.576272836,48.5044,7.063624005,7.072283113,-0.239375,-7.102844341,0.211069573,44.99999998 +155.35,50.42925823,-2.57627184,48.5071,7.067100189,7.072283021,-0.3034375,-7.116250464,0.312062093,44.99999998 +155.36,50.42925886,-2.576270845,48.5105,7.077528756,7.071172682,-0.3665625,-7.12817045,0.412782516,44.99999998 +155.37,50.4292595,-2.57626985,48.5144,7.084481147,7.070284392,-0.43,-7.138601834,0.513143007,44.99999998 +155.38,50.42926014,-2.576268855,48.5191,7.077528784,7.070062253,-0.4934375,-7.147542382,0.613056017,44.99999998 +155.39,50.42926077,-2.57626786,48.5243,7.067100224,7.070284215,-0.5565625,-7.154990318,0.712434401,44.99999998 +155.4,50.42926141,-2.576266865,48.5302,7.063624036,7.071172325,-0.6203125,-7.16094398,0.811191584,44.99999998 +155.41,50.42926204,-2.57626587,48.5367,7.063624035,7.072282486,-0.6846875,-7.165402164,0.909241336,44.99999998 +155.42,50.42926268,-2.576264874,48.5439,7.067100229,7.072282399,-0.748125,-7.168363955,1.006498228,44.99999998 +155.43,50.42926331,-2.576263879,48.5517,7.077528814,7.071172064,-0.8096875,-7.169828722,1.102877464,44.99999998 +155.44,50.42926395,-2.576262884,48.5601,7.084481215,7.07028378,-0.8703125,-7.169796178,1.198294991,44.99999998 +155.45,50.42926459,-2.576261889,48.5691,7.077528848,7.070061647,-0.931875,-7.168266323,1.292667557,44.99999998 +155.46,50.42926522,-2.576260894,48.5787,7.067100286,7.070283612,-0.9946875,-7.165239444,1.385912943,44.99999998 +155.47,50.42926586,-2.576259899,48.589,7.0636241,7.071171727,-1.0565625,-7.160716229,1.477949732,44.99999998 +155.48,50.42926649,-2.576258904,48.5999,7.063624098,7.072281893,-1.11625,-7.154697537,1.568697767,44.99999998 +155.49,50.42926713,-2.576257908,48.6113,7.063624104,7.072281811,-1.175,-7.147184742,1.658077808,44.99999998 +155.5,50.42926776,-2.576256913,48.6234,7.063624127,7.071171481,-1.23375,-7.138179278,1.746012047,44.99999998 +155.51,50.4292684,-2.576255918,48.636,7.067100344,7.070283202,-1.293125,-7.12768315,1.832423708,44.99999998 +155.52,50.42926903,-2.576254923,48.6492,7.077528942,7.070283122,-1.353125,-7.115698477,1.917237505,44.99999998 +155.53,50.42926967,-2.576253928,48.6631,7.084481343,7.071171242,-1.41125,-7.102227781,2.00037941,44.99999998 +155.54,50.42927031,-2.576252933,48.6775,7.077528966,7.072281411,-1.4665625,-7.087273869,2.081776946,44.99999998 +155.55,50.42927094,-2.576251937,48.6924,7.067100399,7.072281332,-1.521875,-7.070839892,2.161359179,44.99999998 +155.56,50.42927158,-2.576250942,48.7079,7.063624228,7.071171007,-1.5784375,-7.052929232,2.239056668,44.99999998 +155.57,50.42927221,-2.576249947,48.724,7.063624255,7.070282732,-1.6346875,-7.033545668,2.314801631,44.99999998 +155.58,50.42927285,-2.576248952,48.7406,7.067100475,7.070060606,-1.6896875,-7.01269327,2.388528064,44.99999998 +155.59,50.42927348,-2.576247957,48.7578,7.07752907,7.070282579,-1.7434375,-6.990376335,2.460171681,44.99999998 +155.6,50.42927412,-2.576246962,48.7755,7.084481462,7.071170702,-1.79625,-6.966599503,2.529669972,44.99999998 +155.61,50.42927476,-2.576245967,48.7937,7.07752909,7.072058827,-1.8484375,-6.941367874,2.596962375,44.99999998 +155.62,50.42927539,-2.576244971,48.8125,7.067100542,7.071392604,-1.8996875,-6.914686548,2.661990163,44.99999998 +155.63,50.42927603,-2.576243976,48.8317,7.063624386,7.070060233,-1.95,-6.886561253,2.724696727,44.99999998 +155.64,50.42927666,-2.576242982,48.8515,7.063624413,7.07028221,-2,-6.856997719,2.785027235,44.99999998 +155.65,50.4292773,-2.576241986,48.8717,7.067100617,7.071170337,-2.049375,-6.826002249,2.842929203,44.99999998 +155.66,50.42927793,-2.576240991,48.8925,7.077529203,7.071170265,-2.096875,-6.793581203,2.898352041,44.99999998 +155.67,50.42927857,-2.576239996,48.9137,7.084481614,7.071392243,-2.143125,-6.759741457,2.951247505,44.99999998 +155.68,50.42927921,-2.576239001,48.9353,7.07752927,7.072058321,-2.19,-6.724489999,3.001569471,44.99999998 +155.69,50.42927984,-2.576238005,48.9575,7.067100728,7.071392102,-2.23625,-6.687834222,3.049273995,44.99999998 +155.7,50.42928048,-2.57623701,48.9801,7.063624556,7.070059734,-2.2796875,-6.649781746,3.094319478,44.99999998 +155.71,50.42928111,-2.576236016,49.0031,7.063624567,7.070281714,-2.321875,-6.610340592,3.136666674,44.99999998 +155.72,50.42928175,-2.57623502,49.0265,7.063624582,7.071169844,-2.365,-6.569518896,3.176278684,44.99999998 +155.73,50.42928238,-2.576234025,49.0504,7.063624616,7.071169776,-2.4078125,-6.52732531,3.213120902,44.99999998 +155.74,50.42928302,-2.57623303,49.0747,7.067100853,7.071391758,-2.448125,-6.483768542,3.247161241,44.99999998 +155.75,50.42928365,-2.576232035,49.0994,7.077529466,7.07205784,-2.4865625,-6.438857704,3.278370023,44.99999998 +155.76,50.42928429,-2.576231039,49.1244,7.084481878,7.071391624,-2.5246875,-6.392602248,3.306720032,44.99999998 +155.77,50.42928493,-2.576230044,49.1499,7.077529517,7.07005926,-2.5615625,-6.345011743,3.332186516,44.99999998 +155.78,50.42928556,-2.57622905,49.1757,7.067100963,7.070281243,-2.5965625,-6.296096159,3.354747245,44.99999998 +155.79,50.4292862,-2.576228054,49.2018,7.067100987,7.071169376,-2.6315625,-6.245865694,3.374382623,44.99999998 +155.8,50.42928683,-2.576227059,49.2283,7.077529593,7.07116931,-2.6665625,-6.194330891,3.391075462,44.99999998 +155.81,50.42928747,-2.576226064,49.2552,7.084482016,7.071169245,-2.6996875,-6.141502463,3.404811266,44.99999998 +155.82,50.42928811,-2.576225069,49.2823,7.077529668,7.07116918,-2.73125,-6.087391527,3.415578002,44.99999998 +155.83,50.42928874,-2.576224073,49.3098,7.067101125,7.070280918,-2.7615625,-6.032009254,3.423366332,44.99999998 +155.84,50.42928938,-2.576223079,49.3376,7.063624958,7.070058804,-2.7896875,-5.975367277,3.42816938,44.99999998 +155.85,50.42929001,-2.576222084,49.3656,7.063624975,7.071391038,-2.8165625,-5.917477398,3.429983078,44.99999998 +155.86,50.42929065,-2.576221088,49.3939,7.063625,7.072057124,-2.8434375,-5.858351763,3.428805764,44.99999998 +155.87,50.42929128,-2.576220093,49.4225,7.063625044,7.071390912,-2.8696875,-5.798002691,3.42463847,44.99999998 +155.88,50.42929192,-2.576219098,49.4513,7.067101286,7.0711688,-2.8946875,-5.736442788,3.417484806,44.99999998 +155.89,50.42929255,-2.576218103,49.4804,7.077529905,7.071390787,-2.918125,-5.673684887,3.407351073,44.99999998 +155.9,50.42929319,-2.576217107,49.5097,7.084482312,7.071168675,-2.939375,-5.60974211,3.394246096,44.99999998 +155.91,50.42929383,-2.576216113,49.5392,7.07752994,7.071168613,-2.9584375,-5.544627805,3.378181276,44.99999998 +155.92,50.42929446,-2.576215117,49.5689,7.067101392,7.071390601,-2.9765625,-5.478355611,3.359170594,44.99999998 +155.93,50.4292951,-2.576214122,49.5987,7.06362525,7.070946439,-2.995,-5.410939276,3.337230722,44.99999998 +155.94,50.42929573,-2.576213127,49.6288,7.063625298,7.070502279,-3.013125,-5.342392955,3.312380683,44.99999998 +155.95,50.42929637,-2.576212132,49.659,7.067101521,7.070946317,-3.029375,-5.27273097,3.284642249,44.99999998 +155.96,50.429297,-2.576211137,49.6894,7.077530122,7.071390355,-3.043125,-5.201967818,3.254039542,44.99999998 +155.97,50.42929764,-2.576210141,49.7199,7.084482534,7.071168245,-3.0546875,-5.13011828,3.220599261,44.99999998 +155.98,50.42929828,-2.576209147,49.7505,7.077530187,7.071168184,-3.065,-5.057197426,3.184350571,44.99999998 +155.99,50.42929891,-2.576208151,49.7812,7.067101655,7.071390173,-3.075,-4.983220438,3.14532504,44.99999998 +156,50.42929955,-2.576207156,49.812,7.063625501,7.070946013,-3.0846875,-4.90820273,3.103556818,44.99999998 +156.01,50.42930018,-2.576206161,49.8429,7.063625529,7.070279804,-3.0928125,-4.832160058,3.059082173,44.99999998 +156.02,50.42930082,-2.576205166,49.8739,7.067101749,7.070057694,-3.098125,-4.755108236,3.011940007,44.99999998 +156.03,50.42930145,-2.576204171,49.9049,7.077530362,7.070279683,-3.1015625,-4.677063362,2.962171346,44.99999998 +156.04,50.42930209,-2.576203176,49.9359,7.08448279,7.071167821,-3.105,-4.598041711,2.909819677,44.99999998 +156.05,50.42930273,-2.576202181,49.967,7.077530444,7.072278008,-3.108125,-4.518059839,2.854930549,44.99999998 +156.06,50.42930336,-2.576201185,49.9981,7.067101899,7.072277948,-3.1096875,-4.437134478,2.79755192,44.99999998 +156.07,50.429304,-2.57620019,50.0292,7.063625742,7.07116764,-3.1096875,-4.355282415,2.737733808,44.99999998 +156.08,50.42930463,-2.576199195,50.0603,7.063625782,7.070279381,-3.108125,-4.272520839,2.675528296,44.99999998 +156.09,50.42930527,-2.5761982,50.0914,7.063625813,7.070057271,-3.1046875,-4.188866996,2.6109897,44.99999998 +156.1,50.4293059,-2.576197205,50.1224,7.063625832,7.070279261,-3.0996875,-4.10433836,2.544174284,44.99999998 +156.11,50.42930654,-2.57619621,50.1534,7.067102055,7.0711674,-3.093125,-4.01895258,2.475140318,44.99999998 +156.12,50.42930717,-2.576195215,50.1843,7.077530684,7.072277586,-3.0846875,-3.932727474,2.403947963,44.99999998 +156.13,50.42930781,-2.576194219,50.2151,7.084483121,7.072277525,-3.075,-3.84568109,2.330659384,44.99999998 +156.14,50.42930845,-2.576193224,50.2458,7.077530765,7.071167217,-3.065,-3.757831591,2.25533841,44.99999998 +156.15,50.42930908,-2.576192229,50.2764,7.067102201,7.070278958,-3.055,-3.669197312,2.178050701,44.99999998 +156.16,50.42930972,-2.576191234,50.3069,7.063626035,7.070056847,-3.044375,-3.579796759,2.098863751,44.99999998 +156.17,50.42931035,-2.576190239,50.3373,7.06362608,7.070278836,-3.03125,-3.489648611,2.017846544,44.99999998 +156.18,50.42931099,-2.576189244,50.3676,7.067102325,7.071166973,-3.0146875,-3.398771718,1.935069785,44.99999998 +156.19,50.42931162,-2.576188249,50.3976,7.077530948,7.072277159,-2.996875,-3.307185045,1.85060555,44.99999998 +156.2,50.42931226,-2.576187253,50.4275,7.084483364,7.072277097,-2.98,-3.214907671,1.764527579,44.99999998 +156.21,50.4293129,-2.576186258,50.4572,7.077530994,7.071166788,-2.9628125,-3.121958905,1.676910931,44.99999998 +156.22,50.42931353,-2.576185263,50.4868,7.067102433,7.070278529,-2.9428125,-3.02835817,1.587831979,44.99999998 +156.23,50.42931417,-2.576184268,50.5161,7.063626279,7.070056417,-2.9196875,-2.934125005,1.497368475,44.99999998 +156.24,50.4293148,-2.576183273,50.5452,7.063626327,7.070278403,-2.8953125,-2.839279061,1.405599143,44.99999998 +156.25,50.42931544,-2.576182278,50.574,7.067102557,7.071166538,-2.8715625,-2.743840221,1.312604196,44.99999998 +156.26,50.42931607,-2.576181283,50.6026,7.077531159,7.072276723,-2.848125,-2.647828308,1.218464595,44.99999998 +156.27,50.42931671,-2.576180287,50.631,7.084483567,7.07227666,-2.8228125,-2.551263491,1.123262443,44.99999998 +156.28,50.42931735,-2.576179292,50.6591,7.07753121,7.071166349,-2.7946875,-2.454165823,1.02708082,44.99999998 +156.29,50.42931798,-2.576178297,50.6869,7.067102672,7.070278087,-2.7646875,-2.356555644,0.930003607,44.99999998 +156.3,50.42931862,-2.576177302,50.7144,7.063626524,7.070055973,-2.7334375,-2.258453352,0.832115372,44.99999998 +156.31,50.42931925,-2.576176307,50.7416,7.063626561,7.070277957,-2.7015625,-2.159879401,0.733501543,44.99999998 +156.32,50.42931989,-2.576175312,50.7684,7.063626587,7.071166091,-2.6696875,-2.060854361,0.634248065,44.99999998 +156.33,50.42932052,-2.576174317,50.795,7.063626609,7.072276273,-2.6365625,-1.961398972,0.534441509,44.99999998 +156.34,50.42932116,-2.576173321,50.8212,7.067102824,7.072276208,-2.60125,-1.861533975,0.434168911,44.99999998 +156.35,50.42932179,-2.576172326,50.847,7.077531433,7.071165894,-2.565,-1.761280169,0.333517759,44.99999998 +156.36,50.42932243,-2.576171331,50.8725,7.084483856,7.07027763,-2.5284375,-1.660658582,0.232575716,44.99999998 +156.37,50.42932307,-2.576170336,50.8976,7.077531504,7.070055513,-2.49125,-1.559690183,0.131430903,44.99999998 +156.38,50.4293237,-2.576169341,50.9223,7.067102955,7.070277495,-2.453125,-1.458396057,0.030171442,44.99999998 +156.39,50.42932434,-2.576168346,50.9467,7.067102978,7.071165625,-2.413125,-1.356797348,-0.071114261,44.99999998 +156.4,50.42932497,-2.576167351,50.9706,7.077531574,7.072275805,-2.37125,-1.25491531,-0.172338027,44.99999998 +156.41,50.42932561,-2.576166355,50.9941,7.084483984,7.072275736,-2.3284375,-1.152771202,-0.273411449,44.99999998 +156.42,50.42932625,-2.57616536,51.0172,7.077531632,7.071165419,-2.2846875,-1.050386394,-0.374246521,44.99999998 +156.43,50.42932688,-2.576164365,51.0398,7.067103089,7.070277151,-2.24,-0.947782144,-0.474755178,44.99999998 +156.44,50.42932752,-2.57616337,51.062,7.063626924,7.070055032,-2.195,-0.844979993,-0.574849874,44.99999998 +156.45,50.42932815,-2.576162375,51.0837,7.063626936,7.070277011,-2.1496875,-0.742001372,-0.674443288,44.99999998 +156.46,50.42932879,-2.57616138,51.105,7.063626942,7.071165138,-2.103125,-0.638867823,-0.773448562,44.99999998 +156.47,50.42932942,-2.576160385,51.1258,7.063626964,7.072275313,-2.0546875,-0.535600832,-0.871779407,44.99999998 +156.48,50.42933006,-2.576159389,51.1461,7.067103193,7.072275242,-2.005,-0.432222,-0.969350051,44.99999998 +156.49,50.42933069,-2.576158394,51.1659,7.077531811,7.071164922,-1.955,-0.328752927,-1.066075354,44.99999998 +156.5,50.42933133,-2.576157399,51.1852,7.08448423,7.07027665,-1.905,-0.225215156,-1.16187109,44.99999998 +156.51,50.42933197,-2.576156404,51.204,7.077531857,7.070054526,-1.8546875,-0.121630346,-1.256653607,44.99999998 +156.52,50.4293326,-2.576155409,51.2223,7.067103278,7.070276502,-1.803125,-0.018020153,-1.350340343,44.99999998 +156.53,50.42933324,-2.576154414,51.2401,7.063627098,7.071164625,-1.75,0.085593821,-1.442849535,44.99999998 +156.54,50.42933387,-2.576153419,51.2573,7.063627128,7.072274796,-1.69625,0.189189862,-1.534100513,44.99999998 +156.55,50.42933451,-2.576152423,51.274,7.067103358,7.07227472,-1.641875,0.292746426,-1.624013805,44.99999998 +156.56,50.42933514,-2.576151428,51.2902,7.077531966,7.071164396,-1.58625,0.396241912,-1.712510861,44.99999998 +156.57,50.42933578,-2.576150433,51.3057,7.08448436,7.070276121,-1.53,0.499654549,-1.799514617,44.99999998 +156.58,50.42933642,-2.576149438,51.3208,7.07753197,7.070053993,-1.4734375,0.602962907,-1.884949156,44.99999998 +156.59,50.42933705,-2.576148443,51.3352,7.067103402,7.070275964,-1.41625,0.70614533,-1.968739993,44.99999998 +156.6,50.42933769,-2.576147448,51.3491,7.063627241,7.071164082,-1.35875,0.809180273,-2.050814078,44.99999998 +156.61,50.42933832,-2.576146453,51.3624,7.06362727,7.07227425,-1.30125,0.91204625,-2.131099846,44.99999998 +156.62,50.42933896,-2.576145457,51.3751,7.067103476,7.072274169,-1.243125,1.01472172,-2.209527226,44.99999998 +156.63,50.42933959,-2.576144462,51.3873,7.077532059,7.071163841,-1.183125,1.117185309,-2.286027863,44.99999998 +156.64,50.42934023,-2.576143467,51.3988,7.084484451,7.070275561,-1.121875,1.21941559,-2.360535065,44.99999998 +156.65,50.42934087,-2.576142472,51.4097,7.077532081,7.070275478,-1.061875,1.321391192,-2.432983802,44.99999998 +156.66,50.4293415,-2.576141477,51.42,7.067103524,7.071163592,-1.0028125,1.423090856,-2.503310991,44.99999998 +156.67,50.42934214,-2.576140482,51.4298,7.063627345,7.072273756,-0.9415625,1.524493328,-2.571455268,44.99999998 +156.68,50.42934277,-2.576139486,51.4389,7.063627349,7.072273672,-0.878125,1.625577407,-2.63735716,44.99999998 +156.69,50.42934341,-2.576138491,51.4473,7.063627351,7.071163339,-0.8153125,1.726322009,-2.700959257,44.99999998 +156.7,50.42934404,-2.576137496,51.4552,7.063627356,7.070275056,-0.7534375,1.826706105,-2.762206039,44.99999998 +156.71,50.42934468,-2.576136501,51.4624,7.067103564,7.07005292,-0.69125,1.926708726,-2.821044164,44.99999998 +156.72,50.42934531,-2.576135506,51.469,7.077532163,7.070274882,-0.6284375,2.026308959,-2.877422294,44.99999998 +156.73,50.42934595,-2.576134511,51.475,7.084484563,7.071162991,-0.565,2.125486005,-2.93129127,44.99999998 +156.74,50.42934659,-2.576133516,51.4803,7.077532182,7.072273149,-0.5015625,2.224219181,-2.98260411,44.99999998 +156.75,50.42934722,-2.57613252,51.485,7.067103607,7.072273059,-0.4384375,2.32248786,-3.031316122,44.99999998 +156.76,50.42934786,-2.576131525,51.4891,7.063627413,7.071162722,-0.3746875,2.420271531,-3.077384736,44.99999998 +156.77,50.42934849,-2.57613053,51.4925,7.063627402,7.070274434,-0.31,2.517549795,-3.120769845,44.99999998 +156.78,50.42934913,-2.576129535,51.4953,7.067103595,7.070052293,-0.2453125,2.614302255,-3.161433577,44.99999998 +156.79,50.42934976,-2.57612854,51.4974,7.077532194,7.070274251,-0.1815625,2.710508745,-3.199340465,44.99999998 +156.8,50.4293504,-2.576127545,51.4989,7.084484599,7.071162355,-0.118125,2.806149209,-3.234457564,44.99999998 +156.81,50.42935104,-2.57612655,51.4998,7.077532209,7.072272508,-0.0534375,2.901203595,-3.266754106,44.99999998 +156.82,50.42935167,-2.576125554,51.5,7.06710361,7.072272414,0.011875,2.995652135,-3.296201959,44.99999998 +156.83,50.42935231,-2.576124559,51.4995,7.063627408,7.071162072,0.07625,3.089475063,-3.32277557,44.99999998 +156.84,50.42935294,-2.576123564,51.4985,7.063627419,7.070273778,0.14,3.18265284,-3.346451618,44.99999998 +156.85,50.42935358,-2.576122569,51.4967,7.067103628,7.070051632,0.20375,3.275165928,-3.367209478,44.99999998 +156.86,50.42935421,-2.576121574,51.4944,7.077532218,7.070273584,0.268125,3.36699502,-3.385031101,44.99999998 +156.87,50.42935485,-2.576120579,51.4914,7.084484599,7.071161684,0.3334375,3.458120978,-3.39990096,44.99999998 +156.88,50.42935549,-2.576119584,51.4877,7.07753219,7.072271831,0.398125,3.548524723,-3.411806049,44.99999998 +156.89,50.42935612,-2.576118588,51.4834,7.06710359,7.072271732,0.4615625,3.638187404,-3.420735998,44.99999998 +156.9,50.42935676,-2.576117593,51.4785,7.063627397,7.071161385,0.525,3.727090343,-3.426682956,44.99999998 +156.91,50.42935739,-2.576116598,51.4729,7.063627407,7.070273087,0.5884375,3.815214919,-3.429641824,44.99999998 +156.92,50.42935803,-2.576115603,51.4667,7.0671036,7.070050936,0.6515625,3.902542682,-3.429610025,44.99999998 +156.93,50.42935866,-2.576114608,51.4599,7.077532172,7.070272884,0.715,3.989055528,-3.426587558,44.99999998 +156.94,50.4293593,-2.576113613,51.4524,7.084484545,7.071160978,0.778125,4.074735235,-3.420577002,44.99999998 +156.95,50.42935994,-2.576112618,51.4443,7.077532143,7.072271121,0.8396875,4.159564043,-3.411583684,44.99999998 +156.96,50.42936057,-2.576111622,51.4356,7.067103554,7.072271016,0.9003125,4.243524133,-3.399615398,44.99999998 +156.97,50.42936121,-2.576110627,51.4263,7.063627356,7.071160665,0.9615625,4.326598085,-3.384682628,44.99999998 +156.98,50.42936184,-2.576109632,51.4164,7.063627348,7.070272362,1.0234375,4.408768426,-3.366798324,44.99999998 +156.99,50.42936248,-2.576108637,51.4058,7.067103532,7.070050206,1.0846875,4.490018024,-3.345978183,44.99999998 +157,50.42936311,-2.576107642,51.3947,7.077532103,7.070272149,1.145,4.570330034,-3.322240255,44.99999998 +157.01,50.42936375,-2.576106647,51.3829,7.084484474,7.071160238,1.205,4.649687496,-3.295605281,44.99999998 +157.02,50.42936439,-2.576105652,51.3706,7.077532066,7.072270376,1.2646875,4.728073967,-3.266096522,44.99999998 +157.03,50.42936502,-2.576104656,51.3576,7.067103473,7.072270267,1.323125,4.805473059,-3.233739647,44.99999998 +157.04,50.42936566,-2.576103661,51.3441,7.063627272,7.071159911,1.38,4.881868559,-3.198562904,44.99999998 +157.05,50.42936629,-2.576102666,51.33,7.063627264,7.070271604,1.436875,4.957244594,-3.160596944,44.99999998 +157.06,50.42936693,-2.576101671,51.3154,7.063627244,7.070049444,1.4946875,5.031585295,-3.119874943,44.99999998 +157.07,50.42936756,-2.576100676,51.3001,7.063627213,7.070271381,1.5515625,5.104875249,-3.076432366,44.99999998 +157.08,50.4293682,-2.576099681,51.2843,7.067103384,7.071159466,1.60625,5.177099157,-3.030307086,44.99999998 +157.09,50.42936883,-2.576098686,51.268,7.077531962,7.0722696,1.6603125,5.248241837,-2.981539325,44.99999998 +157.1,50.42936947,-2.57609769,51.2511,7.08448435,7.072269487,1.7146875,5.318288506,-2.930171596,44.99999998 +157.11,50.42937011,-2.576096695,51.2337,7.077531948,7.071159126,1.768125,5.387224553,-2.876248705,44.99999998 +157.12,50.42937074,-2.5760957,51.2157,7.067103338,7.070270815,1.82,5.455035483,-2.819817747,44.99999998 +157.13,50.42937138,-2.576094705,51.1973,7.063627108,7.070048651,1.8715625,5.521707259,-2.760927828,44.99999998 +157.14,50.42937201,-2.57609371,51.1783,7.063627076,7.070270584,1.9234375,5.587225842,-2.699630339,44.99999998 +157.15,50.42937265,-2.576092715,51.1588,7.067103257,7.071158665,1.9746875,5.651577654,-2.635978739,44.99999998 +157.16,50.42937328,-2.57609172,51.1388,7.077531835,7.072268795,2.0246875,5.714749173,-2.570028489,44.99999998 +157.17,50.42937392,-2.576090724,51.1183,7.084484205,7.072268677,2.073125,5.776727221,-2.501837172,44.99999998 +157.18,50.42937456,-2.576089729,51.0973,7.07753178,7.071158313,2.12,5.837498907,-2.431464204,44.99999998 +157.19,50.42937519,-2.576088734,51.0759,7.067103162,7.070269998,2.1665625,5.897051509,-2.358971005,44.99999998 +157.2,50.42937583,-2.576087739,51.054,7.06362695,7.07004783,2.213125,5.955372597,-2.284420716,44.99999998 +157.21,50.42937646,-2.576086744,51.0316,7.063626941,7.070269759,2.258125,6.012449965,-2.207878368,44.99999998 +157.22,50.4293771,-2.576085749,51.0088,7.067103116,7.071157836,2.30125,6.068271696,-2.129410709,44.99999998 +157.23,50.42937773,-2.576084754,50.9856,7.077531671,7.072267963,2.3434375,6.122826159,-2.049086209,44.99999998 +157.24,50.42937837,-2.576083758,50.9619,7.08448403,7.072267842,2.385,6.176101952,-1.966974825,44.99999998 +157.25,50.42937901,-2.576082763,50.9379,7.077531606,7.071157473,2.42625,6.22808796,-1.883148292,44.99999998 +157.26,50.42937964,-2.576081768,50.9134,7.067102987,7.070269155,2.4665625,6.278773296,-1.797679548,44.99999998 +157.27,50.42938028,-2.576080773,50.8885,7.063626772,7.070046984,2.5046875,6.328147361,-1.710643248,44.99999998 +157.28,50.42938091,-2.576079778,50.8633,7.06362676,7.070268911,2.5415625,6.376199899,-1.622115195,44.99999998 +157.29,50.42938155,-2.576078783,50.8377,7.063626739,7.071156985,2.5784375,6.422920883,-1.532172681,44.99999998 +157.3,50.42938218,-2.576077788,50.8117,7.063626711,7.072267107,2.6146875,6.468300515,-1.44089403,44.99999998 +157.31,50.42938282,-2.576076792,50.7854,7.067102871,7.072266984,2.6496875,6.512329285,-1.34835894,44.99999998 +157.32,50.42938345,-2.576075797,50.7587,7.07753141,7.071156613,2.683125,6.554998025,-1.254648083,44.99999998 +157.33,50.42938409,-2.576074802,50.7317,7.084483764,7.070268291,2.7146875,6.596297912,-1.159843106,44.99999998 +157.34,50.42938473,-2.576073807,50.7044,7.077531356,7.070046118,2.745,6.636220178,-1.064026743,44.99999998 +157.35,50.42938536,-2.576072812,50.6768,7.067102758,7.070268042,2.7746875,6.674756575,-0.967282533,44.99999998 +157.36,50.429386,-2.576071817,50.6489,7.063626538,7.071156113,2.803125,6.711899022,-0.869694872,44.99999998 +157.37,50.42938663,-2.576070822,50.6207,7.063626494,7.072266233,2.83,6.747639786,-0.771348786,44.99999998 +157.38,50.42938727,-2.576069826,50.5923,7.06710264,7.072266107,2.8565625,6.781971417,-0.672330105,44.99999998 +157.39,50.4293879,-2.576068831,50.5636,7.077531193,7.071155735,2.8828125,6.814886696,-0.572725117,44.99999998 +157.4,50.42938854,-2.576067836,50.5346,7.084483568,7.070267412,2.90625,6.846378806,-0.472620681,44.99999998 +157.41,50.42938918,-2.576066841,50.5054,7.077531161,7.070267284,2.9265625,6.876441099,-0.372104174,44.99999998 +157.42,50.42938981,-2.576065846,50.4761,7.067102541,7.071155353,2.946875,6.905067331,-0.271263144,44.99999998 +157.43,50.42939045,-2.576064851,50.4465,7.063626299,7.072265472,2.968125,6.932251543,-0.170185539,44.99999998 +157.44,50.42939108,-2.576063855,50.4167,7.063626254,7.072265345,2.9878125,6.957988062,-0.068959596,44.99999998 +157.45,50.42939172,-2.57606286,50.3867,7.067102416,7.071154972,3.0046875,6.982271446,0.032326508,44.99999998 +157.46,50.42939235,-2.576061865,50.3566,7.077530979,7.070266647,3.02,7.005096709,0.133584422,44.99999998 +157.47,50.42939299,-2.57606087,50.3263,7.084483351,7.070044469,3.0346875,7.02645904,0.234725854,44.99999998 +157.48,50.42939363,-2.576059875,50.2959,7.077530934,7.070266389,3.048125,7.046353968,0.335662626,44.99999998 +157.49,50.42939426,-2.57605888,50.2653,7.067102304,7.071154457,3.06,7.064777368,0.436306616,44.99999998 +157.5,50.4293949,-2.576057885,50.2347,7.063626059,7.072042526,3.07125,7.081725403,0.53657022,44.99999998 +157.51,50.42939553,-2.576056889,50.2039,7.063626026,7.07137625,3.0815625,7.097194461,0.636365888,44.99999998 +157.52,50.42939617,-2.576055894,50.173,7.067102204,7.070043827,3.089375,7.111181392,0.735606648,44.99999998 +157.53,50.4293968,-2.5760549,50.1421,7.077530767,7.070265747,3.095,7.123683274,0.834205923,44.99999998 +157.54,50.42939744,-2.576053904,50.1111,7.084483117,7.071153814,3.1,7.134697414,0.932077829,44.99999998 +157.55,50.42939808,-2.576052909,50.0801,7.07753068,7.071153684,3.1046875,7.144221576,1.029136879,44.99999998 +157.56,50.42939871,-2.576051914,50.049,7.067102052,7.071375605,3.108125,7.152253814,1.125298506,44.99999998 +157.57,50.42939935,-2.576050919,50.0179,7.063625831,7.072041624,3.1096875,7.158792294,1.220478885,44.99999998 +157.58,50.42939998,-2.576049923,49.9868,7.063625813,7.071375348,3.1096875,7.163835812,1.314594995,44.99999998 +157.59,50.42940062,-2.576048928,49.9557,7.067101977,7.070042923,3.108125,7.167383281,1.407564732,44.99999998 +157.6,50.42940125,-2.576047934,49.9246,7.077530519,7.070264843,3.1046875,7.169433897,1.499307077,44.99999998 +157.61,50.42940189,-2.576046938,49.8936,7.084482865,7.071152911,3.1,7.169987259,1.589741991,44.99999998 +157.62,50.42940253,-2.576045943,49.8626,7.077530439,7.071152782,3.095,7.169043254,1.678790633,44.99999998 +157.63,50.42940316,-2.576044948,49.8317,7.067101828,7.071374702,3.0896875,7.16660211,1.766375311,44.99999998 +157.64,50.4294038,-2.576043953,49.8008,7.063625607,7.07204072,3.0828125,7.162664343,1.852419763,44.99999998 +157.65,50.42940443,-2.576042957,49.77,7.063625576,7.071374445,3.073125,7.157230698,1.936848819,44.99999998 +157.66,50.42940507,-2.576041962,49.7393,7.063625545,7.070042022,3.0615625,7.150302377,2.019588909,44.99999998 +157.67,50.4294057,-2.576040968,49.7088,7.063625516,7.070263942,3.05,7.141880815,2.100567899,44.99999998 +157.68,50.42940634,-2.576039972,49.6783,7.067101672,7.07115201,3.0378125,7.131967728,2.179715143,44.99999998 +157.69,50.42940697,-2.576038977,49.648,7.077530206,7.071151882,3.023125,7.120565238,2.256961657,44.99999998 +157.7,50.42940761,-2.576037982,49.6178,7.084482555,7.071373803,3.0065625,7.107675693,2.332240118,44.99999998 +157.71,50.42940825,-2.576036987,49.5879,7.077530145,7.072039822,2.9896875,7.093301843,2.40548475,44.99999998 +157.72,50.42940888,-2.576035991,49.558,7.067101545,7.071373547,2.9715625,7.077446611,2.476631785,44.99999998 +157.73,50.42940952,-2.576034996,49.5284,7.063625316,7.070041125,2.95125,7.060113377,2.545619169,44.99999998 +157.74,50.42941015,-2.576034002,49.499,7.063625269,7.070263047,2.93,7.041305694,2.612386743,44.99999998 +157.75,50.42941079,-2.576033006,49.4698,7.067101425,7.071151117,2.908125,7.021027572,2.676876294,44.99999998 +157.76,50.42941142,-2.576032011,49.4408,7.077529986,7.07115099,2.8846875,6.999283136,2.739031558,44.99999998 +157.77,50.42941206,-2.576031016,49.4121,7.084482358,7.071372913,2.86,6.976077027,2.798798332,44.99999998 +157.78,50.4294127,-2.576030021,49.3836,7.077529946,7.072038933,2.8346875,6.951414059,2.856124536,44.99999998 +157.79,50.42941333,-2.576029025,49.3554,7.067101328,7.07137266,2.808125,6.92529933,2.910960092,44.99999998 +157.8,50.42941397,-2.57602803,49.3274,7.063625088,7.07004024,2.7796875,6.897738399,2.96325733,44.99999998 +157.81,50.4294146,-2.576027036,49.2998,7.063625047,7.070262164,2.7496875,6.868736937,3.012970529,44.99999998 +157.82,50.42941524,-2.57602604,49.2724,7.067101218,7.071150235,2.7184375,6.838301018,3.060056373,44.99999998 +157.83,50.42941587,-2.576025045,49.2454,7.077529786,7.071150111,2.68625,6.806437058,3.10447378,44.99999998 +157.84,50.42941651,-2.57602405,49.2187,7.084482147,7.071372036,2.6534375,6.773151591,3.146184076,44.99999998 +157.85,50.42941715,-2.576023055,49.1923,7.077529717,7.072260108,2.6196875,6.738451663,3.185150821,44.99999998 +157.86,50.42941778,-2.576022059,49.1663,7.067101097,7.072259984,2.5846875,6.70234455,3.221340096,44.99999998 +157.87,50.42941842,-2.576021064,49.1406,7.063624882,7.071149617,2.5484375,6.664837644,3.254720273,44.99999998 +157.88,50.42941905,-2.576020069,49.1153,7.06362487,7.070261298,2.51125,6.625938966,3.285262361,44.99999998 +157.89,50.42941969,-2.576019074,49.0904,7.067101042,7.070039127,2.473125,6.585656481,3.312939603,44.99999998 +157.9,50.42942032,-2.576018079,49.0658,7.077529592,7.070261054,2.433125,6.543998668,3.337727878,44.99999998 +157.91,50.42942096,-2.576017084,49.0417,7.084481951,7.071149128,2.3915625,6.500974236,3.359605641,44.99999998 +157.92,50.4294216,-2.576016089,49.018,7.077529536,7.072259252,2.35,6.45659218,3.378553813,44.99999998 +157.93,50.42942223,-2.576015093,48.9947,7.067100923,7.072259131,2.308125,6.410861725,3.39455578,44.99999998 +157.94,50.42942287,-2.576014098,48.9718,7.0636247,7.071148767,2.2646875,6.36379244,3.407597674,44.99999998 +157.95,50.4294235,-2.576013103,48.9494,7.063624681,7.070260452,2.2196875,6.31539418,3.417668095,44.99999998 +157.96,50.42942414,-2.576012108,48.9274,7.067100857,7.070038284,2.1734375,6.265677028,3.424758219,44.99999998 +157.97,50.42942477,-2.576011113,48.9059,7.077529415,7.070260214,2.1265625,6.214651355,3.428861914,44.99999998 +157.98,50.42942541,-2.576010118,48.8849,7.084481773,7.071148292,2.0796875,6.162327817,3.42997563,44.99999998 +157.99,50.42942605,-2.576009123,48.8643,7.07752936,7.072258419,2.0315625,6.108717417,3.428098333,44.99999998 +158,50.42942668,-2.576008127,48.8442,7.067100762,7.072258303,1.9815625,6.053831211,3.423231687,44.99999998 +158.01,50.42942732,-2.576007132,48.8247,7.063624556,7.071147942,1.9315625,5.997680775,3.415379931,44.99999998 +158.02,50.42942795,-2.576006137,48.8056,7.063624545,7.07025963,1.8815625,5.940277795,3.404549883,44.99999998 +158.03,50.42942859,-2.576005142,48.787,7.063624527,7.070037466,1.8296875,5.881634304,3.390751054,44.99999998 +158.04,50.42942922,-2.576004147,48.769,7.063624495,7.0702594,1.7765625,5.821762449,3.373995418,44.99999998 +158.05,50.42942986,-2.576003152,48.7515,7.067100652,7.071147482,1.7234375,5.760674835,3.354297645,44.99999998 +158.06,50.42943049,-2.576002157,48.7345,7.077529214,7.072257613,1.6696875,5.698384181,3.331674865,44.99999998 +158.07,50.42943113,-2.576001161,48.7181,7.084481602,7.0722575,1.6146875,5.634903437,3.306146788,44.99999998 +158.08,50.42943177,-2.576000166,48.7022,7.077529211,7.071147143,1.5584375,5.570245952,3.277735701,44.99999998 +158.09,50.4294324,-2.575999171,48.6869,7.06710061,7.070258836,1.5015625,5.504425248,3.246466415,44.99999998 +158.1,50.42943304,-2.575998176,48.6722,7.063624385,7.070036677,1.4453125,5.437454961,3.212366087,44.99999998 +158.11,50.42943367,-2.575997181,48.658,7.063624359,7.070258616,1.3896875,5.36934913,3.175464626,44.99999998 +158.12,50.42943431,-2.575996186,48.6444,7.067100545,7.070924652,1.3328125,5.300121962,3.135794059,44.99999998 +158.13,50.42943494,-2.575995191,48.6313,7.077529127,7.07136864,1.2734375,5.229787955,3.093389052,44.99999998 +158.14,50.42943558,-2.575994195,48.6189,7.084481506,7.071146483,1.213125,5.158361776,3.048286502,44.99999998 +158.15,50.42943622,-2.575993201,48.6071,7.077529102,7.071146375,1.1534375,5.085858321,3.000525886,44.99999998 +158.16,50.42943685,-2.575992205,48.5958,7.067100506,7.071368317,1.093125,5.012292775,2.950148744,44.99999998 +158.17,50.42943749,-2.57599121,48.5852,7.063624292,7.071146162,1.0315625,4.937680435,2.897198964,44.99999998 +158.18,50.42943812,-2.575990215,48.5752,7.063624273,7.071368105,0.9703125,4.862036942,2.841722841,44.99999998 +158.19,50.42943876,-2.57598922,48.5658,7.067100463,7.072034147,0.91,4.785378112,2.783768733,44.99999998 +158.2,50.42943939,-2.575988224,48.557,7.07752905,7.071367896,0.8496875,4.70771987,2.72338706,44.99999998 +158.21,50.42944003,-2.575987229,48.5488,7.084481431,7.070035499,0.788125,4.629078491,2.660630591,44.99999998 +158.22,50.42944067,-2.575986235,48.5412,7.077529023,7.070257445,0.725,4.549470417,2.595553988,44.99999998 +158.23,50.4294413,-2.575985239,48.5343,7.067100425,7.071145538,0.6615625,4.468912207,2.528214086,44.99999998 +158.24,50.42944194,-2.575984244,48.528,7.063624232,7.071145435,0.5984375,4.387420764,2.4586695,44.99999998 +158.25,50.42944257,-2.575983249,48.5223,7.063624242,7.071367383,0.5346875,4.305012989,2.386980906,44.99999998 +158.26,50.42944321,-2.575982254,48.5173,7.063624244,7.07203343,0.47,4.221706243,2.313210814,44.99999998 +158.27,50.42944384,-2.575981258,48.5129,7.063624242,7.071367184,0.4053125,4.13751783,2.237423624,44.99999998 +158.28,50.42944448,-2.575980263,48.5092,7.067100432,7.070034793,0.3415625,4.05246534,2.159685341,44.99999998 +158.29,50.42944511,-2.575979269,48.5061,7.077528996,7.070256743,0.2784375,3.966566533,2.080063745,44.99999998 +158.3,50.42944575,-2.575978273,48.5036,7.084481363,7.071144841,0.215,3.879839401,1.998628337,44.99999998 +158.31,50.42944639,-2.575977278,48.5018,7.077528975,7.071144744,0.1515625,3.792301935,1.915450106,44.99999998 +158.32,50.42944702,-2.575976283,48.5006,7.067100412,7.071366697,0.088125,3.703972584,1.830601531,44.99999998 +158.33,50.42944766,-2.575975288,48.5,7.063624232,7.072032748,0.023125,3.614869683,1.744156695,44.99999998 +158.34,50.42944829,-2.575974292,48.5001,7.063624229,7.071366508,-0.043125,3.525011795,1.656190886,44.99999998 +158.35,50.42944893,-2.575973297,48.5009,7.067100408,7.070034121,-0.108125,3.434417829,1.566780879,44.99999998 +158.36,50.42944956,-2.575972303,48.5023,7.077528978,7.070256077,-0.1715625,3.343106634,1.476004655,44.99999998 +158.37,50.4294502,-2.575971307,48.5043,7.084481367,7.071144179,-0.2353125,3.251097232,1.383941281,44.99999998 +158.38,50.42945084,-2.575970312,48.507,7.077528998,7.071144087,-0.3,3.158408875,1.290671085,44.99999998 +158.39,50.42945147,-2.575969317,48.5103,7.067100437,7.071366045,-0.365,3.06506093,1.196275429,44.99999998 +158.4,50.42945211,-2.575968322,48.5143,7.063624254,7.072032102,-0.4296875,2.971072933,1.100836589,44.99999998 +158.41,50.42945274,-2.575967326,48.5189,7.063624246,7.071365866,-0.493125,2.876464423,1.004437815,44.99999998 +158.42,50.42945338,-2.575966331,48.5242,7.067100429,7.070033484,-0.5553125,2.781255224,0.90716316,44.99999998 +158.43,50.42945401,-2.575965337,48.53,7.077529016,7.070255444,-0.618125,2.685465161,0.809097423,44.99999998 +158.44,50.42945465,-2.575964341,48.5365,7.084481429,7.071143552,-0.681875,2.589114286,0.710326145,44.99999998 +158.45,50.42945529,-2.575963346,48.5437,7.077529064,7.071143465,-0.7446875,2.492222711,0.610935443,44.99999998 +158.46,50.42945592,-2.575962351,48.5514,7.067100488,7.071365428,-0.8065625,2.394810661,0.511012005,44.99999998 +158.47,50.42945656,-2.575961356,48.5598,7.06362429,7.072031489,-0.86875,2.296898534,0.410642977,44.99999998 +158.48,50.42945719,-2.57596036,48.5688,7.063624289,7.071365258,-0.93125,2.198506669,0.309915851,44.99999998 +158.49,50.42945783,-2.575959365,48.5784,7.067100501,7.070032881,-0.9934375,2.099655693,0.20891846,44.99999998 +158.5,50.42945846,-2.575958371,48.5887,7.077529109,7.070254846,-1.0546875,2.000366232,0.107738927,44.99999998 +158.51,50.4294591,-2.575957375,48.5995,7.084481513,7.071142959,-1.1146875,1.900659028,0.00646537,44.99999998 +158.52,50.42945974,-2.57595638,48.611,7.077529133,7.071142877,-1.1734375,1.800554879,-0.094813743,44.99999998 +158.53,50.42946037,-2.575955385,48.623,7.067100558,7.071364845,-1.2315625,1.700074697,-0.196010237,44.99999998 +158.54,50.42946101,-2.57595439,48.6356,7.063624375,7.07203091,-1.2903125,1.599239511,-0.29703576,44.99999998 +158.55,50.42946164,-2.575953394,48.6488,7.063624394,7.071364683,-1.3496875,1.498070348,-0.397802305,44.99999998 +158.56,50.42946228,-2.575952399,48.6626,7.067100611,7.070032312,-1.408125,1.396588293,-0.498221925,44.99999998 +158.57,50.42946291,-2.575951405,48.677,7.07752921,7.070254282,-1.465,1.294814602,-0.598207128,44.99999998 +158.58,50.42946355,-2.575950409,48.6919,7.084481614,7.071142398,-1.5215625,1.192770532,-0.697670654,44.99999998 +158.59,50.42946419,-2.575949414,48.7074,7.077529243,7.07114232,-1.5784375,1.090477283,-0.796525812,44.99999998 +158.6,50.42946482,-2.575948419,48.7235,7.067100675,7.071364292,-1.634375,0.987956397,-0.894686374,44.99999998 +158.61,50.42946546,-2.575947424,48.7401,7.063624496,7.072252411,-1.6884375,0.885229133,-0.992066739,44.99999998 +158.62,50.42946609,-2.575946428,48.7573,7.06362452,7.072252336,-1.7415625,0.782317032,-1.088582053,44.99999998 +158.63,50.42946673,-2.575945433,48.7749,7.063624549,7.071142017,-1.7946875,0.679241523,-1.18414809,44.99999998 +158.64,50.42946736,-2.575944438,48.7932,7.063624577,7.070253748,-1.846875,0.576024151,-1.278681542,44.99999998 +158.65,50.429468,-2.575943443,48.8119,7.067100788,7.070031625,-1.8978125,0.472686514,-1.372099962,44.99999998 +158.66,50.42946863,-2.575942448,48.8311,7.077529375,7.0702536,-1.9484375,0.369250157,-1.464321873,44.99999998 +158.67,50.42946927,-2.575941453,48.8509,7.084481778,7.071141722,-1.998125,0.265736737,-1.555266891,44.99999998 +158.68,50.42946991,-2.575940458,48.8711,7.077529425,7.072251894,-2.0465625,0.16216774,-1.644855661,44.99999998 +158.69,50.42947054,-2.575939462,48.8918,7.067100884,7.072251822,-2.095,0.058564938,-1.733010145,44.99999998 +158.7,50.42947118,-2.575938467,48.913,7.063624721,7.071141507,-2.143125,-0.045050124,-1.819653338,44.99999998 +158.71,50.42947181,-2.575937472,48.9347,7.063624739,7.070253241,-2.1896875,-0.148655791,-1.90470984,44.99999998 +158.72,50.42947245,-2.575936477,48.9568,7.067100942,7.070031122,-2.2346875,-0.252230403,-1.988105394,44.99999998 +158.73,50.42947308,-2.575935482,48.9794,7.077529538,7.070253101,-2.2784375,-0.35575236,-2.069767292,44.99999998 +158.74,50.42947372,-2.575934487,49.0024,7.084481959,7.071141228,-2.3215625,-0.459199947,-2.149624316,44.99999998 +158.75,50.42947436,-2.575933492,49.0258,7.077529613,7.072251402,-2.3646875,-0.562551736,-2.227606794,44.99999998 +158.76,50.42947499,-2.575932496,49.0497,7.067101062,7.072251334,-2.4065625,-0.665785953,-2.303646831,44.99999998 +158.77,50.42947563,-2.575931501,49.074,7.063624882,7.071141022,-2.44625,-0.768881172,-2.37767802,44.99999998 +158.78,50.42947626,-2.575930506,49.0986,7.0636249,7.07025276,-2.485,-0.871815847,-2.449635847,44.99999998 +158.79,50.4294769,-2.575929511,49.1237,7.067101128,7.070030645,-2.523125,-0.974568436,-2.519457515,44.99999998 +158.8,50.42947753,-2.575928516,49.1491,7.077529754,7.070252627,-2.5596875,-1.077117454,-2.587082234,44.99999998 +158.81,50.42947817,-2.575927521,49.1749,7.084482176,7.071140755,-2.5953125,-1.179441585,-2.652450989,44.99999998 +158.82,50.42947881,-2.575926526,49.201,7.077529813,7.072250933,-2.63125,-1.281519402,-2.715506713,44.99999998 +158.83,50.42947944,-2.57592553,49.2275,7.06710126,7.072250868,-2.6665625,-1.383329534,-2.776194517,44.99999998 +158.84,50.42948008,-2.575924535,49.2544,7.063625094,7.071140559,-2.699375,-1.484850837,-2.834461403,44.99999998 +158.85,50.42948071,-2.57592354,49.2815,7.063625119,7.0702523,-2.7296875,-1.586061998,-2.890256606,44.99999998 +158.86,50.42948135,-2.575922545,49.309,7.067101339,7.070030187,-2.75875,-1.686941989,-2.943531482,44.99999998 +158.87,50.42948198,-2.57592155,49.3367,7.077529957,7.070252171,-2.7878125,-1.787469669,-2.994239565,44.99999998 +158.88,50.42948262,-2.575920555,49.3647,7.084482385,7.071140302,-2.8165625,-1.887624009,-3.042336564,44.99999998 +158.89,50.42948326,-2.57591956,49.3931,7.077530036,7.072250482,-2.843125,-1.987384212,-3.087780654,44.99999998 +158.9,50.42948389,-2.575918564,49.4216,7.067101483,7.07225042,-2.868125,-2.086729307,-3.13053213,44.99999998 +158.91,50.42948453,-2.575917569,49.4504,7.063625306,7.071140113,-2.8934375,-2.185638667,-3.170553747,44.99999998 +158.92,50.42948516,-2.575916574,49.4795,7.063625332,7.070251856,-2.9178125,-2.284091552,-3.207810614,44.99999998 +158.93,50.4294858,-2.575915579,49.5088,7.063625377,7.070251794,-2.939375,-2.38206745,-3.242270187,44.99999998 +158.94,50.42948643,-2.575914584,49.5383,7.063625426,7.071139927,-2.9584375,-2.479545905,-3.273902499,44.99999998 +158.95,50.42948707,-2.575913589,49.568,7.067101658,7.072250108,-2.9765625,-2.576506464,-3.302679877,44.99999998 +158.96,50.4294877,-2.575912593,49.5978,7.07753026,7.072250047,-2.9946875,-2.672929016,-3.328577283,44.99999998 +158.97,50.42948834,-2.575911598,49.6279,7.084482665,7.071139742,-3.0115625,-2.768793335,-3.351572085,44.99999998 +158.98,50.42948898,-2.575910603,49.6581,7.077530311,7.070251485,-3.02625,-2.864079482,-3.371644286,44.99999998 +158.99,50.42948961,-2.575909608,49.6884,7.067101781,7.070029375,-3.0403125,-2.958767461,-3.388776412,44.99999998 +159,50.42949025,-2.575908613,49.7189,7.063625635,7.070251363,-3.0546875,-3.052837506,-3.40295345,44.99999998 +159.01,50.42949088,-2.575907618,49.7495,7.063625665,7.071139498,-3.0678125,-3.146270077,-3.414163026,44.99999998 +159.02,50.42949152,-2.575906623,49.7803,7.067101879,7.07224968,-3.0778125,-3.239045523,-3.422395398,44.99999998 +159.03,50.42949215,-2.575905627,49.8111,7.077530485,7.07224962,-3.0846875,-3.331144593,-3.427643462,44.99999998 +159.04,50.42949279,-2.575904632,49.842,7.084482915,7.071139316,-3.0903125,-3.422547919,-3.42990252,44.99999998 +159.05,50.42949343,-2.575903637,49.8729,7.077530577,7.070251061,-3.0965625,-3.513236539,-3.429170624,44.99999998 +159.06,50.42949406,-2.575902642,49.9039,7.067102034,7.070028952,-3.103125,-3.603191485,-3.425448518,44.99999998 +159.07,50.4294947,-2.575901647,49.935,7.063625869,7.07025094,-3.1078125,-3.692393909,-3.418739297,44.99999998 +159.08,50.42949533,-2.575900652,49.9661,7.063625895,7.071139074,-3.1096875,-3.780825247,-3.409048919,44.99999998 +159.09,50.42949597,-2.575899657,49.9972,7.06710212,7.072249257,-3.1096875,-3.868466991,-3.396385807,44.99999998 +159.1,50.4294966,-2.575898661,50.0283,7.077530743,7.072249197,-3.108125,-3.955300865,-3.380760961,44.99999998 +159.11,50.42949724,-2.575897666,50.0594,7.084483173,7.071138893,-3.105,-4.041308763,-3.362188076,44.99999998 +159.12,50.42949788,-2.575896671,50.0904,7.077530822,7.070250639,-3.1015625,-4.126472636,-3.340683309,44.99999998 +159.13,50.42949851,-2.575895676,50.1214,7.067102272,7.07002853,-3.0984375,-4.210774782,-3.316265394,44.99999998 +159.14,50.42949915,-2.575894681,50.1524,7.063626104,7.070250517,-3.094375,-4.294197551,-3.288955647,44.99999998 +159.15,50.42949978,-2.575893686,50.1833,7.06362613,7.071138651,-3.0878125,-4.376723527,-3.258777903,44.99999998 +159.16,50.42950042,-2.575892691,50.2142,7.067102366,7.072248834,-3.078125,-4.458335464,-3.22575846,44.99999998 +159.17,50.42950105,-2.575891695,50.2449,7.077530999,7.072248774,-3.0665625,-4.539016344,-3.189926081,44.99999998 +159.18,50.42950169,-2.5758907,50.2755,7.084483427,7.07113847,-3.055,-4.618749322,-3.151312048,44.99999998 +159.19,50.42950233,-2.575889705,50.306,7.077531066,7.070250214,-3.043125,-4.697517727,-3.109950053,44.99999998 +159.2,50.42950296,-2.57588871,50.3364,7.067102509,7.070028105,-3.0296875,-4.775305112,-3.065876077,44.99999998 +159.21,50.4295036,-2.575887715,50.3666,7.063626344,7.070250092,-3.0146875,-4.852095208,-3.01912868,44.99999998 +159.22,50.42950423,-2.57588672,50.3967,7.063626383,7.071138225,-2.9984375,-4.927872028,-2.969748484,44.99999998 +159.23,50.42950487,-2.575885725,50.4266,7.063626426,7.072248407,-2.98125,-5.002619758,-2.917778691,44.99999998 +159.24,50.4295055,-2.575884729,50.4563,7.063626468,7.072248345,-2.963125,-5.076322699,-2.863264507,44.99999998 +159.25,50.42950614,-2.575883734,50.4859,7.067102701,7.07113804,-2.943125,-5.148965555,-2.806253545,44.99999998 +159.26,50.42950677,-2.575882739,50.5152,7.077531311,7.070249783,-2.92125,-5.220533083,-2.74679548,44.99999998 +159.27,50.42950741,-2.575881744,50.5443,7.084483718,7.070027672,-2.898125,-5.291010386,-2.684942165,44.99999998 +159.28,50.42950805,-2.575880749,50.5732,7.07753135,7.070249658,-2.873125,-5.360382741,-2.620747515,44.99999998 +159.29,50.42950868,-2.575879754,50.6018,7.067102806,7.071137789,-2.8465625,-5.428635651,-2.554267566,44.99999998 +159.3,50.42950932,-2.575878759,50.6301,7.063626659,7.072247969,-2.82,-5.495754849,-2.485560243,44.99999998 +159.31,50.42950995,-2.575877763,50.6582,7.063626695,7.072247906,-2.793125,-5.561726356,-2.414685479,44.99999998 +159.32,50.42951059,-2.575876768,50.686,7.067102915,7.071137599,-2.7646875,-5.626536305,-2.341705094,44.99999998 +159.33,50.42951122,-2.575875773,50.7135,7.077531519,7.07024934,-2.735,-5.690171289,-2.266682688,44.99999998 +159.34,50.42951186,-2.575874778,50.7407,7.084483928,7.070027226,-2.7046875,-5.752617902,-2.189683692,44.99999998 +159.35,50.4295125,-2.575873783,50.7676,7.077531571,7.070249211,-2.6728125,-5.813863194,-2.110775257,44.99999998 +159.36,50.42951313,-2.575872788,50.7942,7.067103035,7.07113734,-2.638125,-5.873894332,-2.030026195,44.99999998 +159.37,50.42951377,-2.575871793,50.8204,7.063626884,7.072247517,-2.601875,-5.932698766,-1.947506922,44.99999998 +159.38,50.4295144,-2.575870797,50.8462,7.063626909,7.072247451,-2.5665625,-5.990264237,-1.863289403,44.99999998 +159.39,50.42951504,-2.575869802,50.8717,7.067103117,7.071137142,-2.53125,-6.046578712,-1.77744709,44.99999998 +159.4,50.42951567,-2.575868807,50.8969,7.077531719,7.07024888,-2.493125,-6.101630445,-1.690054754,44.99999998 +159.41,50.42951631,-2.575867812,50.9216,7.084484143,7.070026764,-2.453125,-6.15540792,-1.601188714,44.99999998 +159.42,50.42951695,-2.575866817,50.9459,7.077531797,7.070248744,-2.4134375,-6.207899906,-1.510926432,44.99999998 +159.43,50.42951758,-2.575865822,50.9699,7.067103244,7.07113687,-2.3728125,-6.259095462,-1.419346577,44.99999998 +159.44,50.42951822,-2.575864827,50.9934,7.06362707,7.072247045,-2.3296875,-6.308983928,-1.326529019,44.99999998 +159.45,50.42951885,-2.575863831,51.0165,7.063627087,7.072246976,-2.2853125,-6.357554821,-1.232554716,44.99999998 +159.46,50.42951949,-2.575862836,51.0391,7.067103304,7.071136664,-2.2415625,-6.404797999,-1.137505601,44.99999998 +159.47,50.42952012,-2.575861841,51.0613,7.077531918,7.0702484,-2.198125,-6.450703606,-1.041464582,44.99999998 +159.48,50.42952076,-2.575860846,51.0831,7.084484339,7.07002628,-2.1528125,-6.495262076,-0.944515368,44.99999998 +159.49,50.4295214,-2.575859851,51.1044,7.077531976,7.070248257,-2.1046875,-6.538464125,-0.846742526,44.99999998 +159.5,50.42952203,-2.575858856,51.1252,7.067103415,7.07113638,-2.0553125,-6.580300643,-0.748231314,44.99999998 +159.51,50.42952267,-2.575857861,51.1455,7.063627242,7.072246551,-2.0065625,-6.62076298,-0.649067618,44.99999998 +159.52,50.4295233,-2.575856865,51.1653,7.063627258,7.072246478,-1.958125,-6.659842713,-0.549337954,44.99999998 +159.53,50.42952394,-2.57585587,51.1847,7.063627276,7.071136162,-1.908125,-6.697531533,-0.44912924,44.99999998 +159.54,50.42952457,-2.575854875,51.2035,7.063627302,7.070247894,-1.85625,-6.733821705,-0.348528909,44.99999998 +159.55,50.42952521,-2.57585388,51.2218,7.067103526,7.070025771,-1.8034375,-6.76870561,-0.247624624,44.99999998 +159.56,50.42952584,-2.575852885,51.2396,7.077532138,7.070247744,-1.75,-6.802175914,-0.146504449,44.99999998 +159.57,50.42952648,-2.57585189,51.2568,7.084484544,7.071135863,-1.6965625,-6.834225741,-0.045256447,44.99999998 +159.58,50.42952712,-2.575850895,51.2735,7.077532158,7.07224603,-1.643125,-6.864848272,0.056030975,44.99999998 +159.59,50.42952775,-2.575849899,51.2897,7.067103585,7.072245952,-1.588125,-6.894037149,0.157269524,44.99999998 +159.6,50.42952839,-2.575848904,51.3053,7.063627419,7.071135632,-1.5315625,-6.921786354,0.258370963,44.99999998 +159.61,50.42952902,-2.575847909,51.3203,7.063627452,7.070247361,-1.475,-6.948089987,0.359247059,44.99999998 +159.62,50.42952966,-2.575846914,51.3348,7.067103668,7.070025234,-1.4184375,-6.972942662,0.459809918,44.99999998 +159.63,50.42953029,-2.575845919,51.3487,7.077532256,7.070247202,-1.36125,-6.99633905,0.559971821,44.99999998 +159.64,50.42953093,-2.575844924,51.362,7.084484644,7.071135316,-1.303125,-7.018274395,0.659645393,44.99999998 +159.65,50.42953157,-2.575843929,51.3748,7.077532269,7.072245479,-1.2434375,-7.038744057,0.758743772,44.99999998 +159.66,50.4295322,-2.575842933,51.3869,7.067103716,7.072245398,-1.183125,-7.057743739,0.857180499,44.99999998 +159.67,50.42953284,-2.575841938,51.3984,7.063627548,7.071135073,-1.12375,-7.075269486,0.954869746,44.99999998 +159.68,50.42953347,-2.575840943,51.4094,7.063627556,7.070246796,-1.0646875,-7.09131769,1.051726313,44.99999998 +159.69,50.42953411,-2.575839948,51.4197,7.067103748,7.070246714,-1.0046875,-7.10588497,1.147665804,44.99999998 +159.7,50.42953474,-2.575838953,51.4295,7.077532334,7.071134824,-0.9434375,-7.11896829,1.24260451,44.99999998 +159.71,50.42953538,-2.575837958,51.4386,7.084484741,7.072244981,-0.88125,-7.130564841,1.336459638,44.99999998 +159.72,50.42953602,-2.575836962,51.4471,7.077532377,7.072244896,-0.8184375,-7.140672332,1.429149369,44.99999998 +159.73,50.42953665,-2.575835967,51.455,7.067103805,7.071134568,-0.755,-7.149288529,1.520592803,44.99999998 +159.74,50.42953729,-2.575834972,51.4622,7.063627615,7.070246287,-0.691875,-7.156411769,1.610710298,44.99999998 +159.75,50.42953792,-2.575833977,51.4688,7.063627621,7.070024151,-0.63,-7.162040392,1.699423244,44.99999998 +159.76,50.42953856,-2.575832982,51.4748,7.067103821,7.070246111,-0.568125,-7.166173366,1.786654235,44.99999998 +159.77,50.42953919,-2.575831987,51.4802,7.077532406,7.071134216,-0.5046875,-7.168809774,1.872327239,44.99999998 +159.78,50.42953983,-2.575830992,51.4849,7.084484798,7.07224437,-0.44,-7.169949043,1.9563676,44.99999998 +159.79,50.42954047,-2.575829996,51.489,7.077532418,7.07224428,-0.3753125,-7.169591002,2.038701922,44.99999998 +159.8,50.4295411,-2.575829001,51.4924,7.067103846,7.071133946,-0.3115625,-7.16773565,2.11925847,44.99999998 +159.81,50.42954174,-2.575828006,51.4952,7.063627661,7.07024566,-0.2484375,-7.164383388,2.197967,44.99999998 +159.82,50.42954237,-2.575827011,51.4974,7.06362766,7.070023519,-0.1846875,-7.159534962,2.274758872,44.99999998 +159.83,50.42954301,-2.575826016,51.4989,7.067103842,7.070245475,-0.12,-7.153191403,2.349567106,44.99999998 +159.84,50.42954364,-2.575825021,51.4998,7.077532422,7.071133576,-0.055,-7.145353913,2.422326501,44.99999998 +159.85,50.42954428,-2.575824026,51.5,7.084484825,7.072243724,0.01,-7.136024269,2.492973629,44.99999998 +159.86,50.42954492,-2.57582303,51.4996,7.07753245,7.072243628,0.075,-7.125204305,2.561446784,44.99999998 +159.87,50.42954555,-2.575822035,51.4985,7.067103869,7.07113329,0.1396875,-7.112896369,2.627686378,44.99999998 +159.88,50.42954619,-2.57582104,51.4968,7.06362766,7.070244999,0.2034375,-7.099102983,2.691634541,44.99999998 +159.89,50.42954682,-2.575820045,51.4944,7.06362764,7.070022853,0.266875,-7.083827069,2.753235583,44.99999998 +159.9,50.42954746,-2.57581905,51.4915,7.063627638,7.070244804,0.3315625,-7.067071721,2.812435759,44.99999998 +159.91,50.42954809,-2.575818055,51.4878,7.063627652,7.0711329,0.3965625,-7.048840547,2.869183447,44.99999998 +159.92,50.42954873,-2.57581706,51.4835,7.067103856,7.072243043,0.4596875,-7.029137331,2.923429143,44.99999998 +159.93,50.42954936,-2.575816064,51.4786,7.077532432,7.072242943,0.521875,-7.007966139,2.975125578,44.99999998 +159.94,50.42955,-2.575815069,51.4731,7.084484802,7.071132599,0.5853125,-6.985331442,3.02422766,44.99999998 +159.95,50.42955064,-2.575814074,51.4669,7.077532394,7.070244304,0.6496875,-6.961237936,3.070692589,44.99999998 +159.96,50.42955127,-2.575813079,51.4601,7.067103809,7.070022154,0.713125,-6.935690722,3.1144798,44.99999998 +159.97,50.42955191,-2.575812084,51.4526,7.063627622,7.070244099,0.775,-6.908695013,3.155551134,44.99999998 +159.98,50.42955254,-2.575811089,51.4446,7.063627618,7.071132189,0.8365625,-6.88025654,3.193870838,44.99999998 +159.99,50.42955318,-2.575810094,51.4359,7.067103798,7.072242327,0.89875,-6.850381202,3.229405394,44.99999998 +160,50.42955381,-2.575809098,51.4266,7.077532365,7.072242223,0.96125,-6.819075247,3.262123862,44.99999998 +160.01,50.42955445,-2.575808103,51.4167,7.08448474,7.071353923,1.023125,-6.786345205,3.29199771,44.99999998 +160.02,50.42955509,-2.575807108,51.4061,7.077532344,7.071131768,1.083125,-6.752197894,3.319000867,44.99999998 +160.03,50.42955572,-2.575806113,51.395,7.067103753,7.071131661,1.141875,-6.716640535,3.343109842,44.99999998 +160.04,50.42955636,-2.575805117,51.3833,7.063627548,7.070243359,1.201875,-6.67968046,3.364303551,44.99999998 +160.05,50.42955699,-2.575804123,51.371,7.063627538,7.070021202,1.2628125,-6.641325462,3.382563544,44.99999998 +160.06,50.42955763,-2.575803128,51.358,7.067103724,7.071353384,1.3215625,-6.601583447,3.397873893,44.99999998 +160.07,50.42955826,-2.575802132,51.3445,7.07753229,7.07201942,1.378125,-6.560462782,3.410221305,44.99999998 +160.08,50.4295589,-2.575801137,51.3305,7.08448465,7.071353165,1.4353125,-6.51797206,3.419594895,44.99999998 +160.09,50.42955954,-2.575800142,51.3158,7.077532238,7.071353054,1.493125,-6.474120162,3.425986526,44.99999998 +160.1,50.42956017,-2.575799147,51.3006,7.067103645,7.072019087,1.5496875,-6.428916256,3.429390697,44.99999998 +160.11,50.42956081,-2.575798151,51.2848,7.06362744,7.07135283,1.605,-6.38236968,3.429804315,44.99999998 +160.12,50.42956144,-2.575797156,51.2685,7.063627419,7.070020427,1.6596875,-6.33449029,3.427227151,44.99999998 +160.13,50.42956208,-2.575796162,51.2516,7.067103591,7.070242363,1.7134375,-6.285287998,3.421661382,44.99999998 +160.14,50.42956271,-2.575795166,51.2342,7.077532162,7.071130442,1.76625,-6.234773059,3.413111877,44.99999998 +160.15,50.42956335,-2.575794171,51.2163,7.084484539,7.071130327,1.8184375,-6.182956131,3.401586087,44.99999998 +160.16,50.42956399,-2.575793176,51.1978,7.077532132,7.07135226,1.87,-6.129847929,3.387094036,44.99999998 +160.17,50.42956462,-2.575792181,51.1789,7.067103529,7.072018289,1.9215625,-6.075459623,3.369648445,44.99999998 +160.18,50.42956526,-2.575791185,51.1594,7.063627318,7.071352029,1.973125,-6.019802503,3.34926444,44.99999998 +160.19,50.42956589,-2.57579019,51.1394,7.063627292,7.070019622,2.023125,-5.962888256,3.32595984,44.99999998 +160.2,50.42956653,-2.575789196,51.1189,7.063627257,7.070241553,2.0715625,-5.904728743,3.299754928,44.99999998 +160.21,50.42956716,-2.5757882,51.098,7.063627234,7.071129628,2.1196875,-5.845336052,3.270672564,44.99999998 +160.22,50.4295678,-2.575787205,51.0765,7.06710342,7.071129511,2.1665625,-5.784722675,3.238738189,44.99999998 +160.23,50.42956843,-2.57578621,51.0546,7.077531983,7.07135144,2.21125,-5.722901217,3.203979532,44.99999998 +160.24,50.42956907,-2.575785215,51.0323,7.084484335,7.072017465,2.255,-5.659884626,3.166426961,44.99999998 +160.25,50.42956971,-2.575784219,51.0095,7.07753191,7.0713512,2.2984375,-5.595686022,3.12611325,44.99999998 +160.26,50.42957034,-2.575783224,50.9863,7.067103307,7.070018789,2.3415625,-5.530318815,3.08307352,44.99999998 +160.27,50.42957098,-2.57578223,50.9627,7.063627102,7.070240717,2.3846875,-5.463796696,3.037345242,44.99999998 +160.28,50.42957161,-2.575781234,50.9386,7.063627081,7.071128789,2.4265625,-5.396133531,2.98896841,44.99999998 +160.29,50.42957225,-2.575780239,50.9141,7.067103245,7.071128668,2.46625,-5.327343474,2.937985136,44.99999998 +160.3,50.42957288,-2.575779244,50.8893,7.077531798,7.071350594,2.5046875,-5.257440846,2.884439938,44.99999998 +160.31,50.42957352,-2.575778249,50.864,7.084484152,7.072016616,2.5415625,-5.18644026,2.828379399,44.99999998 +160.32,50.42957416,-2.575777253,50.8384,7.077531726,7.071350348,2.5765625,-5.114356555,2.769852505,44.99999998 +160.33,50.42957479,-2.575776258,50.8125,7.06710312,7.070017935,2.611875,-5.041204798,2.70891025,44.99999998 +160.34,50.42957543,-2.575775264,50.7862,7.063626912,7.070239859,2.648125,-4.967000232,2.645605805,44.99999998 +160.35,50.42957606,-2.575774268,50.7595,7.063626886,7.071127928,2.6828125,-4.891758383,2.579994345,44.99999998 +160.36,50.4295767,-2.575773273,50.7325,7.067103038,7.071127804,2.7146875,-4.815494951,2.512133052,44.99999998 +160.37,50.42957733,-2.575772278,50.7052,7.077531581,7.071349728,2.7446875,-4.738225862,2.442081169,44.99999998 +160.38,50.42957797,-2.575771283,50.6776,7.084483948,7.072015747,2.7734375,-4.659967276,2.369899774,44.99999998 +160.39,50.42957861,-2.575770287,50.6497,7.077531544,7.071349477,2.8015625,-4.580735463,2.295651778,44.99999998 +160.4,50.42957924,-2.575769292,50.6216,7.067102934,7.070017061,2.8296875,-4.500547041,2.219401924,44.99999998 +160.41,50.42957988,-2.575768298,50.5931,7.063626704,7.070238983,2.8565625,-4.419418795,2.141216734,44.99999998 +160.42,50.42958051,-2.575767302,50.5644,7.063626671,7.07112705,2.88125,-4.337367515,2.061164388,44.99999998 +160.43,50.42958115,-2.575766307,50.5355,7.067102832,7.071126923,2.9046875,-4.254410502,1.979314674,44.99999998 +160.44,50.42958178,-2.575765312,50.5063,7.077531377,7.071348844,2.9265625,-4.170565005,1.895738925,44.99999998 +160.45,50.42958242,-2.575764317,50.4769,7.08448373,7.07223691,2.9465625,-4.085848496,1.810510078,44.99999998 +160.46,50.42958306,-2.575763321,50.4474,7.077531313,7.072236783,2.9665625,-4.000278739,1.723702503,44.99999998 +160.47,50.42958369,-2.575762326,50.4176,7.067102706,7.071126415,2.9865625,-3.91387361,1.635391773,44.99999998 +160.48,50.42958433,-2.575761331,50.3876,7.063626486,7.070238094,3.004375,-3.826651042,1.545654951,44.99999998 +160.49,50.42958496,-2.575760336,50.3575,7.063626449,7.070015917,3.02,-3.738629369,1.454570304,44.99999998 +160.5,50.4295856,-2.575759341,50.3272,7.063626401,7.070237837,3.0346875,-3.649826927,1.362217242,44.99999998 +160.51,50.42958623,-2.575758346,50.2968,7.063626361,7.071125902,3.048125,-3.560262279,1.268676324,44.99999998 +160.52,50.42958687,-2.575757351,50.2662,7.067102534,7.072236015,3.0596875,-3.469954104,1.17402914,44.99999998 +160.53,50.4295875,-2.575756355,50.2356,7.077531099,7.072235886,3.07,-3.378921309,1.078358137,44.99999998 +160.54,50.42958814,-2.57575536,50.2048,7.084483459,7.071125517,3.0796875,-3.287182801,0.981746795,44.99999998 +160.55,50.42958878,-2.575754365,50.174,7.077531024,7.070237195,3.088125,-3.194757834,0.884279341,44.99999998 +160.56,50.42958941,-2.57575337,50.143,7.067102389,7.070015018,3.095,-3.101665714,0.786040799,44.99999998 +160.57,50.42959005,-2.575752375,50.1121,7.063626161,7.070236937,3.10125,-3.007925808,0.687116828,44.99999998 +160.58,50.42959068,-2.57575138,50.081,7.063626145,7.071125001,3.1065625,-2.913557768,0.587593658,44.99999998 +160.59,50.42959132,-2.575750385,50.0499,7.067102319,7.072235112,3.1090625,-2.818581247,0.487558092,44.99999998 +160.6,50.42959195,-2.575749389,50.0188,7.077530864,7.072234983,3.1084375,-2.723016127,0.387097391,44.99999998 +160.61,50.42959259,-2.575748394,49.9877,7.084483203,7.071124613,3.106875,-2.626882289,0.286299161,44.99999998 +160.62,50.42959323,-2.575747399,49.9567,7.07753077,7.070236292,3.1065625,-2.530199901,0.185251235,44.99999998 +160.63,50.42959386,-2.575746404,49.9256,7.06710216,7.070014115,3.10625,-2.432989131,0.084041736,44.99999998 +160.64,50.4295945,-2.575745409,49.8945,7.063625948,7.070236034,3.1028125,-2.335270205,-0.017240988,44.99999998 +160.65,50.42959513,-2.575744414,49.8635,7.063625919,7.071124097,3.0965625,-2.237063635,-0.1185087,44.99999998 +160.66,50.42959577,-2.575743419,49.8326,7.067102073,7.072234209,3.09,-2.138389874,-0.21967305,44.99999998 +160.67,50.4295964,-2.575742423,49.8017,7.077530613,7.072234081,3.0828125,-2.039269551,-0.320645861,44.99999998 +160.68,50.42959704,-2.575741428,49.7709,7.084482963,7.071123711,3.073125,-1.939723291,-0.421339068,44.99999998 +160.69,50.42959768,-2.575740433,49.7402,7.077530546,7.07023539,3.0615625,-1.839772007,-0.521664894,44.99999998 +160.7,50.42959831,-2.575739438,49.7097,7.067101937,7.070013213,3.0496875,-1.739436497,-0.621535793,44.99999998 +160.71,50.42959895,-2.575738443,49.6792,7.063625712,7.070235133,3.0365625,-1.638737732,-0.720864673,44.99999998 +160.72,50.42959958,-2.575737448,49.6489,7.063625682,7.071123198,3.0215625,-1.537696682,-0.819564961,44.99999998 +160.73,50.42960022,-2.575736453,49.6188,7.067101848,7.07223331,3.0065625,-1.436334547,-0.917550599,44.99999998 +160.74,50.42960085,-2.575735457,49.5888,7.077530393,7.072233183,2.99125,-1.334672468,-1.014736101,44.99999998 +160.75,50.42960149,-2.575734462,49.5589,7.084482733,7.071122814,2.9728125,-1.232731645,-1.111036727,44.99999998 +160.76,50.42960213,-2.575733467,49.5293,7.077530307,7.070234493,2.9515625,-1.130533392,-1.206368539,44.99999998 +160.77,50.42960276,-2.575732472,49.4999,7.067101704,7.070234366,2.9303125,-1.028099024,-1.300648401,44.99999998 +160.78,50.4296034,-2.575731477,49.4707,7.063625493,7.071122432,2.9096875,-0.925449968,-1.393794035,44.99999998 +160.79,50.42960403,-2.575730482,49.4417,7.063625467,7.072232546,2.8878125,-0.822607596,-1.485724253,44.99999998 +160.8,50.42960467,-2.575729486,49.4129,7.067101616,7.07223242,2.8628125,-0.719593509,-1.5763589,44.99999998 +160.81,50.4296053,-2.575728491,49.3844,7.077530149,7.071122053,2.835,-0.616429077,-1.665618964,44.99999998 +160.82,50.42960594,-2.575727496,49.3562,7.084482505,7.070233735,2.806875,-0.513135959,-1.753426579,44.99999998 +160.83,50.42960658,-2.575726501,49.3283,7.077530098,7.07001156,2.7796875,-0.409735641,-1.8397052,44.99999998 +160.84,50.42960721,-2.575725506,49.3006,7.067101497,7.070233483,2.75125,-0.30624978,-1.924379538,44.99999998 +160.85,50.42960785,-2.575724511,49.2732,7.06362528,7.071121551,2.7196875,-0.202699977,-2.007375798,44.99999998 +160.86,50.42960848,-2.575723516,49.2462,7.063625247,7.072231667,2.686875,-0.099107833,-2.088621557,44.99999998 +160.87,50.42960912,-2.57572252,49.2195,7.063625204,7.072231543,2.6546875,0.004505053,-2.168046055,44.99999998 +160.88,50.42960975,-2.575721525,49.1931,7.063625176,7.071121178,2.6215625,0.108116964,-2.245579965,44.99999998 +160.89,50.42961039,-2.57572053,49.167,7.067101355,7.070232863,2.58625,0.211706301,-2.321155733,44.99999998 +160.9,50.42961102,-2.575719535,49.1414,7.077529913,7.070010692,2.5496875,0.315251406,-2.394707414,44.99999998 +160.91,50.42961166,-2.57571854,49.116,7.084482267,7.070232617,2.511875,0.418730677,-2.466170836,44.99999998 +160.92,50.4296123,-2.575717545,49.0911,7.077529844,7.071120687,2.4728125,0.522122516,-2.535483717,44.99999998 +160.93,50.42961293,-2.57571655,49.0666,7.067101231,7.072230805,2.4334375,0.62540532,-2.60258567,44.99999998 +160.94,50.42961357,-2.575715554,49.0424,7.063625016,7.072230684,2.393125,0.728557548,-2.667418079,44.99999998 +160.95,50.4296142,-2.575714559,49.0187,7.063624997,7.071120323,2.35125,0.83155754,-2.729924451,44.99999998 +160.96,50.42961484,-2.575713564,48.9954,7.067101168,7.070232011,2.3084375,0.934383927,-2.790050356,44.99999998 +160.97,50.42961547,-2.575712569,48.9725,7.077529725,7.070009843,2.265,1.037015164,-2.847743252,44.99999998 +160.98,50.42961611,-2.575711574,48.9501,7.084482086,7.070231771,2.22125,1.13942988,-2.902952835,44.99999998 +160.99,50.42961675,-2.575710579,48.9281,7.077529668,7.071119843,2.1765625,1.241606589,-2.955631033,44.99999998 +161,50.42961738,-2.575709584,48.9065,7.067101059,7.072229965,2.1296875,1.343524036,-3.005731895,44.99999998 +161.01,50.42961802,-2.575708588,48.8855,7.063624847,7.072229848,2.0815625,1.445160904,-3.053211704,44.99999998 +161.02,50.42961865,-2.575707593,48.8649,7.063624832,7.07111949,2.033125,1.546495939,-3.098029093,44.99999998 +161.03,50.42961929,-2.575706598,48.8448,7.067101004,7.070231181,1.983125,1.647507997,-3.140144929,44.99999998 +161.04,50.42961992,-2.575705603,48.8252,7.077529558,7.070009017,1.931875,1.748176051,-3.179522485,44.99999998 +161.05,50.42962056,-2.575704608,48.8062,7.08448192,7.070230949,1.8815625,1.84847896,-3.216127498,44.99999998 +161.06,50.4296212,-2.575703613,48.7876,7.077529518,7.071119025,1.8315625,1.948395866,-3.249927997,44.99999998 +161.07,50.42962183,-2.575702618,48.7695,7.067100924,7.072229151,1.779375,2.047905916,-3.280894475,44.99999998 +161.08,50.42962247,-2.575701622,48.752,7.063624714,7.072229038,1.725,2.146988195,-3.308999946,44.99999998 +161.09,50.4296231,-2.575700627,48.735,7.063624696,7.071340732,1.67,2.245622192,-3.334220001,44.99999998 +161.1,50.42962374,-2.575699632,48.7186,7.063624676,7.071340619,1.615,2.343787165,-3.356532524,44.99999998 +161.11,50.42962437,-2.575698637,48.7027,7.063624653,7.072006651,1.56,2.441462718,-3.375918093,44.99999998 +161.12,50.42962501,-2.575697641,48.6874,7.067100826,7.071340396,1.5046875,2.538628339,-3.392359804,44.99999998 +161.13,50.42962564,-2.575696646,48.6726,7.077529395,7.070007997,1.4484375,2.635263859,-3.405843335,44.99999998 +161.14,50.42962628,-2.575695652,48.6584,7.084481776,7.070229933,1.39125,2.731348996,-3.416356938,44.99999998 +161.15,50.42962692,-2.575694656,48.6448,7.077529381,7.071118015,1.3334375,2.826863753,-3.423891391,44.99999998 +161.16,50.42962755,-2.575693661,48.6317,7.067100783,7.071117907,1.2746875,2.921788135,-3.42844016,44.99999998 +161.17,50.42962819,-2.575692666,48.6193,7.063624563,7.071339846,1.215,3.016102317,-3.42999935,44.99999998 +161.18,50.42962882,-2.575691671,48.6074,7.06362455,7.072005882,1.155,3.109786646,-3.428567471,44.99999998 +161.19,50.42962946,-2.575690675,48.5962,7.067100745,7.071339632,1.095,3.202821584,-3.424145841,44.99999998 +161.2,50.42963009,-2.57568968,48.5855,7.077529319,7.070007237,1.035,3.295187595,-3.416738299,44.99999998 +161.21,50.42963073,-2.575688686,48.5755,7.084481692,7.070229179,0.9746875,3.386865483,-3.406351319,44.99999998 +161.22,50.42963137,-2.57568769,48.566,7.077529291,7.071117266,0.9134375,3.477836055,-3.392993897,44.99999998 +161.23,50.429632,-2.575686695,48.5572,7.067100692,7.071117161,0.85125,3.568080288,-3.376677778,44.99999998 +161.24,50.42963264,-2.5756857,48.549,7.063624481,7.071339106,0.7884375,3.657579447,-3.357417171,44.99999998 +161.25,50.42963327,-2.575684705,48.5414,7.06362448,7.072005146,0.725,3.746314681,-3.335228808,44.99999998 +161.26,50.42963391,-2.575683709,48.5345,7.067100683,7.0713389,0.661875,3.834267599,-3.31013211,44.99999998 +161.27,50.42963454,-2.575682714,48.5282,7.077529259,7.070006511,0.6,3.921419808,-3.282148909,44.99999998 +161.28,50.42963518,-2.57568172,48.5225,7.084481627,7.070228458,0.5378125,4.007753031,-3.251303611,44.99999998 +161.29,50.42963582,-2.575680724,48.5174,7.077529224,7.071116549,0.4734375,4.093249278,-3.217623147,44.99999998 +161.3,50.42963645,-2.575679729,48.513,7.067100646,7.07111645,0.4084375,4.177890728,-3.181136851,44.99999998 +161.31,50.42963709,-2.575678734,48.5093,7.063624465,7.071338399,0.345,4.261659679,-3.141876579,44.99999998 +161.32,50.42963772,-2.575677739,48.5061,7.063624467,7.072004445,0.2815625,4.344538654,-3.099876538,44.99999998 +161.33,50.42963836,-2.575676743,48.5036,7.067100654,7.071338203,0.2165625,4.426510294,-3.05517334,44.99999998 +161.34,50.42963899,-2.575675748,48.5018,7.077529231,7.070005819,0.151875,4.507557523,-3.007806002,44.99999998 +161.35,50.42963963,-2.575674754,48.5006,7.084481615,7.070227771,0.088125,4.587663383,-2.957815836,44.99999998 +161.36,50.42964027,-2.575673758,48.5,7.077529222,7.071115867,0.0234375,4.666811199,-2.905246385,44.99999998 +161.37,50.4296409,-2.575672763,48.5001,7.067100638,7.071115773,-0.041875,4.744984415,-2.850143487,44.99999998 +161.38,50.42964154,-2.575671768,48.5009,7.06362445,7.071337727,-0.10625,4.8221667,-2.79255527,44.99999998 +161.39,50.42964217,-2.575670773,48.5022,7.063624461,7.072225825,-0.17,4.898341955,-2.732531867,44.99999998 +161.4,50.42964281,-2.575669777,48.5043,7.067100664,7.072225733,-0.23375,4.973494193,-2.670125705,44.99999998 +161.41,50.42964344,-2.575668782,48.5069,7.077529244,7.071115402,-0.298125,5.047607831,-2.6053911,44.99999998 +161.42,50.42964408,-2.575667787,48.5102,7.08448162,7.07022712,-0.3634375,5.120667341,-2.538384603,44.99999998 +161.43,50.42964472,-2.575666792,48.5142,7.077529232,7.070004981,-0.4278125,5.192657425,-2.46916454,44.99999998 +161.44,50.42964535,-2.575665797,48.5188,7.067100668,7.070226939,-0.49,5.26356313,-2.39779136,44.99999998 +161.45,50.42964599,-2.575664802,48.524,7.063624497,7.071115041,-0.551875,5.333369557,-2.324327284,44.99999998 +161.46,50.42964662,-2.575663807,48.5298,7.063624508,7.072225193,-0.6153125,5.402062212,-2.248836313,44.99999998 +161.47,50.42964726,-2.575662811,48.5363,7.063624503,7.072225106,-0.68,5.469626713,-2.171384394,44.99999998 +161.48,50.42964789,-2.575661816,48.5434,7.063624494,7.07111478,-0.744375,5.536048966,-2.092038964,44.99999998 +161.49,50.42964853,-2.575660821,48.5512,7.067100697,7.070226503,-0.8065625,5.601315104,-2.010869236,44.99999998 +161.5,50.42964916,-2.575659826,48.5596,7.077529305,7.070004369,-0.866875,5.665411434,-1.927945971,44.99999998 +161.51,50.4296498,-2.575658831,48.5685,7.084481716,7.070226332,-0.9284375,5.728324663,-1.843341534,44.99999998 +161.52,50.42965044,-2.575657836,48.5781,7.077529336,7.071114439,-0.9915625,5.790041557,-1.75712972,44.99999998 +161.53,50.42965107,-2.575656841,48.5884,7.067100752,7.072224596,-1.0528125,5.850549281,-1.669385588,44.99999998 +161.54,50.42965171,-2.575655845,48.5992,7.06362456,7.072224513,-1.1115625,5.909835229,-1.5801858,44.99999998 +161.55,50.42965234,-2.57565485,48.6106,7.06362458,7.071114191,-1.1703125,5.967886912,-1.489607991,44.99999998 +161.56,50.42965298,-2.575653855,48.6226,7.067100804,7.070225918,-1.23,6.024692354,-1.397731286,44.99999998 +161.57,50.42965361,-2.57565286,48.6352,7.077529404,7.07000379,-1.29,6.080239581,-1.304635728,44.99999998 +161.58,50.42965425,-2.575651865,48.6484,7.084481799,7.070225758,-1.3496875,6.134517019,-1.210402448,44.99999998 +161.59,50.42965489,-2.57565087,48.6622,7.077529419,7.07111387,-1.408125,6.18751338,-1.115113723,44.99999998 +161.6,50.42965552,-2.575649875,48.6766,7.067100851,7.07222403,-1.4646875,6.239217493,-1.018852631,44.99999998 +161.61,50.42965616,-2.575648879,48.6915,7.063624679,7.072223952,-1.52,6.289618699,-0.921703053,44.99999998 +161.62,50.42965679,-2.575647884,48.707,7.063624704,7.071113635,-1.575,6.338706343,-0.82374973,44.99999998 +161.63,50.42965743,-2.575646889,48.723,7.067100918,7.070225367,-1.63,6.386470282,-0.72507809,44.99999998 +161.64,50.42965806,-2.575645894,48.7396,7.07752952,7.070003243,-1.685,6.432900432,-0.625774191,44.99999998 +161.65,50.4296587,-2.575644899,48.7567,7.084481932,7.070225215,-1.7396875,6.477987169,-0.525924606,44.99999998 +161.66,50.42965934,-2.575643904,48.7744,7.077529561,7.071113331,-1.793125,6.521721095,-0.42561637,44.99999998 +161.67,50.42965997,-2.575642909,48.7926,7.067100985,7.072223495,-1.845,6.564093043,-0.324937028,44.99999998 +161.68,50.42966061,-2.575641913,48.8113,7.063624806,7.072223421,-1.8965625,6.605094132,-0.223974301,44.99999998 +161.69,50.42966124,-2.575640918,48.8305,7.063624839,7.071113109,-1.948125,6.644715825,-0.122816311,44.99999998 +161.7,50.42966188,-2.575639923,48.8503,7.063624875,7.070224845,-1.998125,6.682949871,-0.021551177,44.99999998 +161.71,50.42966251,-2.575638928,48.8705,7.063624896,7.070002725,-2.04625,6.71978825,0.079732749,44.99999998 +161.72,50.42966315,-2.575637933,48.8912,7.067101098,7.070224701,-2.0934375,6.755223341,0.180947119,44.99999998 +161.73,50.42966378,-2.575636938,48.9124,7.077529697,7.071112821,-2.14,6.789247637,0.282003696,44.99999998 +161.74,50.42966442,-2.575635943,48.934,7.08448212,7.072222989,-2.1865625,6.821854092,0.38281436,44.99999998 +161.75,50.42966506,-2.575634947,48.9561,7.077529774,7.072222919,-2.233125,6.853035888,0.483291218,44.99999998 +161.76,50.42966569,-2.575633952,48.9787,7.067101225,7.07111261,-2.278125,6.882786549,0.583346666,44.99999998 +161.77,50.42966633,-2.575632957,49.0017,7.067101245,7.070224349,-2.32125,6.911099832,0.682893385,44.99999998 +161.78,50.42966696,-2.575631962,49.0251,7.077529837,7.070002233,-2.3634375,6.937969776,0.781844628,44.99999998 +161.79,50.4296676,-2.575630967,49.049,7.084482239,7.070224212,-2.4046875,6.963390825,0.880114109,44.99999998 +161.8,50.42966824,-2.575629972,49.0732,7.077529879,7.071112336,-2.4446875,6.98735765,0.977616056,44.99999998 +161.81,50.42966887,-2.575628977,49.0979,7.067101339,7.072222508,-2.4834375,7.009865323,1.074265556,44.99999998 +161.82,50.42966951,-2.575627981,49.1229,7.063625189,7.072222441,-2.52125,7.030908974,1.169978271,44.99999998 +161.83,50.42967014,-2.575626986,49.1483,7.063625222,7.071334183,-2.5584375,7.050484363,1.264670776,44.99999998 +161.84,50.42967078,-2.575625991,49.1741,7.063625241,7.071112069,-2.5946875,7.068587366,1.358260453,44.99999998 +161.85,50.42967141,-2.575624996,49.2002,7.063625259,7.071334051,-2.63,7.085214143,1.450665654,44.99999998 +161.86,50.42967205,-2.575624,49.2267,7.067101485,7.071111938,-2.6646875,7.100361313,1.541805935,44.99999998 +161.87,50.42967268,-2.575623006,49.2535,7.077530104,7.071111873,-2.698125,7.114025612,1.631601657,44.99999998 +161.88,50.42967332,-2.57562201,49.2807,7.084482525,7.071333856,-2.7296875,7.126204288,1.719974668,44.99999998 +161.89,50.42967396,-2.575621015,49.3081,7.077530169,7.070889696,-2.7596875,7.136894707,1.806847789,44.99999998 +161.9,50.42967459,-2.57562002,49.3359,7.067101616,7.070445536,-2.7884375,7.14609469,1.892145334,44.99999998 +161.91,50.42967523,-2.575619025,49.3639,7.063625447,7.070889568,-2.81625,7.15380229,1.975792875,44.99999998 +161.92,50.42967586,-2.57561803,49.3922,7.063625475,7.071333601,-2.843125,7.16001596,2.057717531,44.99999998 +161.93,50.4296765,-2.575617034,49.4208,7.067101706,7.07111149,-2.868125,7.164734325,2.137847799,44.99999998 +161.94,50.42967713,-2.57561604,49.4496,7.07753033,7.071111427,-2.8915625,7.16795641,2.216113891,44.99999998 +161.95,50.42967777,-2.575615044,49.4786,7.084482757,7.071333412,-2.915,7.169681586,2.292447454,44.99999998 +161.96,50.42967841,-2.575614049,49.5079,7.077530398,7.070889254,-2.9378125,7.169909394,2.366781967,44.99999998 +161.97,50.42967904,-2.575613054,49.5374,7.067101834,7.070445096,-2.958125,7.168639949,2.439052571,44.99999998 +161.98,50.42967968,-2.575612059,49.5671,7.063625667,7.071111178,-2.9765625,7.165873365,2.509196357,44.99999998 +161.99,50.42968031,-2.575611064,49.5969,7.06362571,7.072221355,-2.9946875,7.16161033,2.577152016,44.99999998 +162,50.42968095,-2.575610068,49.627,7.067101947,7.072221294,-3.0115625,7.155851646,2.64286042,44.99999998 +162.01,50.42968158,-2.575609073,49.6572,7.077530566,7.071110994,-3.02625,7.148598573,2.706264216,44.99999998 +162.02,50.42968222,-2.575608078,49.6875,7.084482986,7.070222742,-3.04,7.139852601,2.767308056,44.99999998 +162.03,50.42968286,-2.575607083,49.718,7.077530626,7.070000633,-3.053125,7.129615564,2.82593877,44.99999998 +162.04,50.42968349,-2.575606088,49.7486,7.067102073,7.07022262,-3.0646875,7.117889582,2.88210525,44.99999998 +162.05,50.42968413,-2.575605093,49.7793,7.063625918,7.07111075,-3.075,7.104677118,2.935758508,44.99999998 +162.06,50.42968476,-2.575604098,49.8101,7.063625962,7.072220928,-3.0846875,7.08998098,2.986851732,44.99999998 +162.07,50.4296854,-2.575603102,49.841,7.063626004,7.072220868,-3.0928125,7.073804147,3.035340349,44.99999998 +162.08,50.42968603,-2.575602107,49.872,7.063626035,7.071110569,-3.098125,7.056150056,3.081182129,44.99999998 +162.09,50.42968667,-2.575601112,49.903,7.067102248,7.070222318,-3.1015625,7.037022376,3.124337023,44.99999998 +162.1,50.4296873,-2.575600117,49.934,7.07753086,7.07000021,-3.105,7.016425059,3.164767504,44.99999998 +162.11,50.42968794,-2.575599122,49.9651,7.084483295,7.070222197,-3.108125,6.994362517,3.202438218,44.99999998 +162.12,50.42968858,-2.575598127,49.9962,7.077530957,7.071110327,-3.1096875,6.970839276,3.237316394,44.99999998 +162.13,50.42968921,-2.575597132,50.0273,7.067102414,7.072220506,-3.1096875,6.945860265,3.269371549,44.99999998 +162.14,50.42968985,-2.575596136,50.0584,7.063626244,7.072220446,-3.108125,6.919430695,3.298575838,44.99999998 +162.15,50.42969048,-2.575595141,50.0895,7.063626268,7.071110147,-3.1046875,6.89155607,3.32490365,44.99999998 +162.16,50.42969112,-2.575594146,50.1205,7.0671025,7.070221895,-3.0996875,6.862242231,3.348332123,44.99999998 +162.17,50.42969175,-2.575593151,50.1515,7.077531125,7.069999787,-3.0934375,6.831495368,3.368840746,44.99999998 +162.18,50.42969239,-2.575592156,50.1824,7.084483551,7.070221774,-3.08625,6.799321782,3.386411758,44.99999998 +162.19,50.42969303,-2.575591161,50.2132,7.077531195,7.071109904,-3.078125,6.765728235,3.401029745,44.99999998 +162.2,50.42969366,-2.575590166,50.244,7.067102637,7.072220082,-3.068125,6.730721774,3.412681987,44.99999998 +162.21,50.4296943,-2.57558917,50.2746,7.063626469,7.072220022,-3.05625,6.694309676,3.421358344,44.99999998 +162.22,50.42969493,-2.575588175,50.3051,7.06362651,7.071109723,-3.0434375,6.656499561,3.427051196,44.99999998 +162.23,50.42969557,-2.57558718,50.3355,7.067102754,7.070221471,-3.0296875,6.617299336,3.429755614,44.99999998 +162.24,50.4296962,-2.575586185,50.3657,7.077531377,7.07022141,-3.015,6.576717136,3.429469192,44.99999998 +162.25,50.42969684,-2.57558519,50.3958,7.084483793,7.071109539,-2.9996875,6.5347615,3.426192275,44.99999998 +162.26,50.42969748,-2.575584195,50.4257,7.077531429,7.072219716,-2.9828125,6.491441135,3.419927669,44.99999998 +162.27,50.42969811,-2.575583199,50.4555,7.067102875,7.072219654,-2.963125,6.446765152,3.410680818,44.99999998 +162.28,50.42969875,-2.575582204,50.485,7.063626718,7.071109353,-2.9415625,6.400742832,3.3984598,44.99999998 +162.29,50.42969938,-2.575581209,50.5143,7.063626758,7.0702211,-2.92,6.353383803,3.383275272,44.99999998 +162.3,50.42970002,-2.575580214,50.5434,7.067102988,7.06999899,-2.898125,6.304697917,3.36514047,44.99999998 +162.31,50.42970065,-2.575579219,50.5723,7.077531607,7.070220975,-2.8746875,6.254695432,3.344071208,44.99999998 +162.32,50.42970129,-2.575578224,50.6009,7.084484033,7.071109103,-2.8496875,6.203386718,3.320085934,44.99999998 +162.33,50.42970193,-2.575577229,50.6293,7.077531672,7.072219278,-2.823125,6.150782489,3.293205447,44.99999998 +162.34,50.42970256,-2.575576233,50.6574,7.067103104,7.072219214,-2.7946875,6.096893745,3.263453239,44.99999998 +162.35,50.4297032,-2.575575238,50.6852,7.063626934,7.071108912,-2.765,6.041731775,3.230855206,44.99999998 +162.36,50.42970383,-2.575574243,50.7127,7.063626977,7.070220658,-2.735,5.985308037,3.195439883,44.99999998 +162.37,50.42970447,-2.575573248,50.7399,7.067103218,7.069998545,-2.7046875,5.927634335,3.157238093,44.99999998 +162.38,50.4297051,-2.575572253,50.7668,7.077531837,7.070220527,-2.673125,5.868722757,3.116283128,44.99999998 +162.39,50.42970574,-2.575571258,50.7934,7.084484244,7.071108653,-2.6396875,5.808585508,3.07261068,44.99999998 +162.4,50.42970638,-2.575570263,50.8196,7.077531866,7.072218825,-2.6046875,5.747235307,3.02625891,44.99999998 +162.41,50.42970701,-2.575569267,50.8455,7.067103311,7.072218759,-2.568125,5.684684817,2.977268211,44.99999998 +162.42,50.42970765,-2.575568272,50.871,7.063627163,7.071108454,-2.53,5.620947101,2.925681269,44.99999998 +162.43,50.42970828,-2.575567277,50.8961,7.063627205,7.070220197,-2.4915625,5.556035624,2.871543059,44.99999998 +162.44,50.42970892,-2.575566282,50.9208,7.063627229,7.069998083,-2.4534375,5.489963793,2.814900853,44.99999998 +162.45,50.42970955,-2.575565287,50.9452,7.063627241,7.070220062,-2.4146875,5.422745416,2.755803981,44.99999998 +162.46,50.42971019,-2.575564292,50.9691,7.067103452,7.071108185,-2.374375,5.354394587,2.694304066,44.99999998 +162.47,50.42971082,-2.575563297,50.9927,7.077532071,7.072218355,-2.331875,5.284925632,2.630454623,44.99999998 +162.48,50.42971146,-2.575562301,51.0158,7.084484502,7.072218286,-2.2878125,5.214352931,2.564311401,44.99999998 +162.49,50.4297121,-2.575561306,51.0384,7.077532143,7.071107977,-2.2434375,5.142691266,2.495932097,44.99999998 +162.5,50.42971273,-2.575560311,51.0607,7.067103577,7.070219716,-2.198125,5.069955649,2.425376241,44.99999998 +162.51,50.42971337,-2.575559316,51.0824,7.063627398,7.069997598,-2.1515625,4.996161206,2.352705483,44.99999998 +162.52,50.429714,-2.575558321,51.1037,7.063627418,7.070219575,-2.105,4.921323349,2.277983077,44.99999998 +162.53,50.42971464,-2.575557326,51.1245,7.067103641,7.071107694,-2.058125,4.845457836,2.201274284,44.99999998 +162.54,50.42971527,-2.575556331,51.1449,7.077532256,7.07221786,-2.0096875,4.768580307,2.122645911,44.99999998 +162.55,50.42971591,-2.575555335,51.1647,7.084484671,7.072217788,-1.9596875,4.690706977,2.042166597,44.99999998 +162.56,50.42971655,-2.57555434,51.1841,7.077532305,7.071329523,-1.9084375,4.611854062,1.959906417,44.99999998 +162.57,50.42971718,-2.575553345,51.2029,7.067103747,7.071329449,-1.8565625,4.532038004,1.875937217,44.99999998 +162.58,50.42971782,-2.57555235,51.2212,7.063627568,7.071995518,-1.805,4.451275478,1.790332166,44.99999998 +162.59,50.42971845,-2.575551354,51.239,7.063627573,7.0713293,-1.753125,4.369583385,1.703165919,44.99999998 +162.6,50.42971909,-2.575550359,51.2563,7.067103782,7.069996939,-1.6996875,4.286978741,1.614514509,44.99999998 +162.61,50.42971972,-2.575549365,51.273,7.077532397,7.070218911,-1.645,4.203478794,1.524455169,44.99999998 +162.62,50.42972036,-2.575548369,51.2892,7.084484819,7.071107024,-1.59,4.119101019,1.43306651,44.99999998 +162.63,50.429721,-2.575547374,51.3048,7.077532445,7.071106946,-1.5346875,4.033863062,1.340428173,44.99999998 +162.64,50.42972163,-2.575546379,51.3199,7.067103862,7.071328916,-1.478125,3.947782627,1.246621001,44.99999998 +162.65,50.42972227,-2.575545384,51.3344,7.063627677,7.071994981,-1.42,3.860877821,1.151726757,44.99999998 +162.66,50.4297229,-2.575544388,51.3483,7.063627704,7.071328759,-1.3615625,3.773166635,1.055828176,44.99999998 +162.67,50.42972354,-2.575543393,51.3616,7.063627735,7.069996393,-1.3034375,3.684667516,0.959008851,44.99999998 +162.68,50.42972417,-2.575542399,51.3744,7.063627757,7.070218359,-1.245,3.595398916,0.861353294,44.99999998 +162.69,50.42972481,-2.575541403,51.3865,7.067103959,7.071106469,-1.18625,3.505379454,0.762946647,44.99999998 +162.7,50.42972544,-2.575540408,51.3981,7.077532543,7.071106388,-1.126875,3.414627924,0.663874681,44.99999998 +162.71,50.42972608,-2.575539413,51.4091,7.084484935,7.071328353,-1.06625,3.32316329,0.564223798,44.99999998 +162.72,50.42972672,-2.575538418,51.4194,7.077532564,7.07221646,-1.005,3.231004691,0.464080917,44.99999998 +162.73,50.42972735,-2.575537422,51.4292,7.067104005,7.072216375,-0.9434375,3.138171261,0.363533356,44.99999998 +162.74,50.42972799,-2.575536427,51.4383,7.063627823,7.071106053,-0.8815625,3.04468254,0.262668777,44.99999998 +162.75,50.42972862,-2.575535432,51.4468,7.06362782,7.070217777,-0.82,2.95055795,0.16157513,44.99999998 +162.76,50.42972926,-2.575534437,51.4547,7.067104012,7.069995644,-0.7584375,2.855817201,0.060340592,44.99999998 +162.77,50.42972989,-2.575533442,51.462,7.077532606,7.070217605,-0.69625,2.760480004,-0.040946543,44.99999998 +162.78,50.42973053,-2.575532447,51.4686,7.084485018,7.071105708,-0.6334375,2.664566353,-0.142197983,44.99999998 +162.79,50.42973117,-2.575531452,51.4747,7.07753265,7.072215857,-0.57,2.568096189,-0.243325435,44.99999998 +162.8,50.4297318,-2.575530456,51.48,7.067104078,7.072215769,-0.50625,2.471089736,-0.344240664,44.99999998 +162.81,50.42973244,-2.575529461,51.4848,7.063627885,7.071105441,-0.4421875,2.373567277,-0.444855777,44.99999998 +162.82,50.42973307,-2.575528466,51.4889,7.063627881,7.070217161,-0.3778125,2.275549095,-0.545082883,44.99999998 +162.83,50.42973371,-2.575527471,51.4923,7.067104072,7.069995023,-0.31375,2.177055645,-0.64483472,44.99999998 +162.84,50.42973434,-2.575526476,51.4952,7.077532657,7.070216979,-0.25,2.07810761,-0.744024257,44.99999998 +162.85,50.42973498,-2.575525481,51.4973,7.084485055,7.071105077,-0.18625,1.978725559,-0.842564976,44.99999998 +162.86,50.42973562,-2.575524486,51.4989,7.077532676,7.072215221,-0.121875,1.878930291,-0.940370992,44.99999998 +162.87,50.42973625,-2.57552349,51.4998,7.067104099,7.072215128,-0.05625,1.778742605,-1.03735699,44.99999998 +162.88,50.42973689,-2.575522495,51.5,7.0636279,7.071104796,0.009375,1.67818347,-1.133438346,44.99999998 +162.89,50.42973752,-2.5755215,51.4996,7.063627885,7.070216511,0.0734375,1.577273914,-1.228531349,44.99999998 +162.9,50.42973816,-2.575520505,51.4985,7.067104073,7.069994367,0.1365625,1.476034907,-1.322553093,44.99999998 +162.91,50.42973879,-2.57551951,51.4969,7.077532669,7.070216317,0.2003125,1.374487649,-1.41542153,44.99999998 +162.92,50.42973943,-2.575518515,51.4945,7.084485073,7.071104411,0.265,1.272653396,-1.507055701,44.99999998 +162.93,50.42974007,-2.57551752,51.4916,7.077532684,7.07221455,0.3296875,1.170553291,-1.59737568,44.99999998 +162.94,50.4297407,-2.575516524,51.4879,7.067104082,7.072214452,0.3934375,1.068208762,-1.68630274,44.99999998 +162.95,50.42974134,-2.575515529,51.4837,7.063627866,7.071104116,0.4565625,0.965641181,-1.773759304,44.99999998 +162.96,50.42974197,-2.575514534,51.4788,7.063627859,7.070215825,0.5203125,0.862871918,-1.859669112,44.99999998 +162.97,50.42974261,-2.575513539,51.4733,7.06710406,7.069993677,0.5846875,0.759922461,-1.943957277,44.99999998 +162.98,50.42974324,-2.575512544,51.4671,7.07753265,7.070215623,0.6484375,0.656814294,-2.026550289,44.99999998 +162.99,50.42974388,-2.575511549,51.4603,7.08448504,7.07110371,0.71125,0.553568961,-2.107376127,44.99999998 +163,50.42974452,-2.575510554,51.4529,7.077532638,7.072213845,0.7734375,0.450208005,-2.186364261,44.99999998 +163.01,50.42974515,-2.575509558,51.4448,7.067104029,7.072213741,0.835,0.346753084,-2.263445877,44.99999998 +163.02,50.42974579,-2.575508563,51.4362,7.063627818,7.071325447,0.8965625,0.243225683,-2.338553769,44.99999998 +163.03,50.42974642,-2.575507568,51.4269,7.06362782,7.071103294,0.9584375,0.139647519,-2.411622389,44.99999998 +163.04,50.42974706,-2.575506573,51.417,7.063627825,7.071103189,1.02,0.036040191,-2.482588025,44.99999998 +163.05,50.42974769,-2.575505577,51.4065,7.063627819,7.070214893,1.0815625,-0.067574642,-2.551388797,44.99999998 +163.06,50.42974833,-2.575504583,51.3954,7.067103989,7.069992739,1.143125,-0.171175381,-2.617964716,44.99999998 +163.07,50.42974896,-2.575503588,51.3836,7.077532545,7.071324916,1.2028125,-0.274740425,-2.682257743,44.99999998 +163.08,50.4297496,-2.575502592,51.3713,7.084484922,7.07199095,1.26,-0.378248001,-2.744211841,44.99999998 +163.09,50.42975024,-2.575501597,51.3584,7.077532536,7.071324698,1.316875,-0.481676623,-2.803772867,44.99999998 +163.1,50.42975087,-2.575500602,51.345,7.06710395,7.071102542,1.375,-0.585004691,-2.860889024,44.99999998 +163.11,50.42975151,-2.575499607,51.3309,7.063627735,7.071102432,1.4334375,-0.688210547,-2.915510408,44.99999998 +163.12,50.42975214,-2.575498611,51.3163,7.063627704,7.070214131,1.49125,-0.791272706,-2.967589464,44.99999998 +163.13,50.42975278,-2.575497617,51.3011,7.067103872,7.069991971,1.548125,-0.894169566,-3.017080699,44.99999998 +163.14,50.42975341,-2.575496622,51.2853,7.077532447,7.071324144,1.603125,-0.996879757,-3.063941027,44.99999998 +163.15,50.42975405,-2.575495626,51.269,7.084484836,7.071990174,1.656875,-1.099381734,-3.108129537,44.99999998 +163.16,50.42975469,-2.575494631,51.2522,7.077532432,7.071323918,1.7115625,-1.201654128,-3.149607671,44.99999998 +163.17,50.42975532,-2.575493636,51.2348,7.067103822,7.071323804,1.7665625,-1.303675508,-3.188339388,44.99999998 +163.18,50.42975596,-2.575492641,51.2168,7.063627599,7.071989833,1.819375,-1.405424734,-3.224290771,44.99999998 +163.19,50.42975659,-2.575491645,51.1984,7.063627575,7.071323576,1.87,-1.506880376,-3.257430478,44.99999998 +163.2,50.42975723,-2.57549065,51.1794,7.067103754,7.069991175,1.9203125,-1.60802135,-3.287729747,44.99999998 +163.21,50.42975786,-2.575489656,51.16,7.077532325,7.070213105,1.97125,-1.708826513,-3.315161992,44.99999998 +163.22,50.4297585,-2.57548866,51.14,7.084484696,7.071101178,2.0215625,-1.809274838,-3.339703436,44.99999998 +163.23,50.42975914,-2.575487665,51.1195,7.077532286,7.071101061,2.0696875,-1.90934524,-3.361332593,44.99999998 +163.24,50.42975977,-2.57548667,51.0986,7.067103683,7.07132299,2.1165625,-2.009016978,-3.380030555,44.99999998 +163.25,50.42976041,-2.575485675,51.0772,7.063627461,7.071989015,2.1634375,-2.108269139,-3.395781165,44.99999998 +163.26,50.42976104,-2.575484679,51.0553,7.063627422,7.071322754,2.2096875,-2.207080982,-3.408570557,44.99999998 +163.27,50.42976168,-2.575483684,51.033,7.063627391,7.06999035,2.2546875,-2.305431938,-3.418387616,44.99999998 +163.28,50.42976231,-2.57548269,51.0102,7.063627378,7.070212277,2.2984375,-2.403301437,-3.425223804,44.99999998 +163.29,50.42976295,-2.575481694,50.987,7.067103561,7.071100347,2.34125,-2.500669026,-3.429073164,44.99999998 +163.3,50.42976358,-2.575480699,50.9634,7.077532118,7.071100226,2.3834375,-2.597514363,-3.429932314,44.99999998 +163.31,50.42976422,-2.575479704,50.9393,7.084484466,7.071322152,2.4246875,-2.693817281,-3.42780051,44.99999998 +163.32,50.42976486,-2.575478709,50.9149,7.077532044,7.07221022,2.4646875,-2.789557612,-3.422679585,44.99999998 +163.33,50.42976549,-2.575477713,50.89,7.067103443,7.072210098,2.503125,-2.884715359,-3.414574066,44.99999998 +163.34,50.42976613,-2.575476718,50.8648,7.067103432,7.071099738,2.5396875,-2.979270699,-3.403490942,44.99999998 +163.35,50.42976676,-2.575475723,50.8392,7.077531995,7.070211425,2.5753125,-3.073203863,-3.389439954,44.99999998 +163.36,50.4297674,-2.575474728,50.8133,7.08448435,7.069989254,2.6115625,-3.166495201,-3.372433364,44.99999998 +163.37,50.42976804,-2.575473733,50.787,7.077531917,7.070211178,2.6478125,-3.259125287,-3.352485895,44.99999998 +163.38,50.42976867,-2.575472738,50.7603,7.067103292,7.071099244,2.68125,-3.3510747,-3.329615024,44.99999998 +163.39,50.42976931,-2.575471743,50.7333,7.063627075,7.072209357,2.7115625,-3.442324302,-3.30384069,44.99999998 +163.4,50.42976994,-2.575470747,50.7061,7.063627061,7.072209232,2.741875,-3.532855015,-3.275185409,44.99999998 +163.41,50.42977058,-2.575469752,50.6785,7.063627036,7.071098869,2.773125,-3.622647986,-3.243674048,44.99999998 +163.42,50.42977121,-2.575468757,50.6506,7.063626999,7.070210554,2.8028125,-3.711684367,-3.209334166,44.99999998 +163.43,50.42977185,-2.575467762,50.6224,7.067103154,7.069988381,2.8296875,-3.799945593,-3.17219573,44.99999998 +163.44,50.42977248,-2.575466767,50.594,7.077531703,7.070210303,2.855,-3.887413273,-3.132291053,44.99999998 +163.45,50.42977312,-2.575465772,50.5653,7.084484066,7.071098366,2.88,-3.974069129,-3.089654971,44.99999998 +163.46,50.42977376,-2.575464777,50.5364,7.077531652,7.072208475,2.904375,-4.059895055,-3.044324728,44.99999998 +163.47,50.42977439,-2.575463781,50.5072,7.067103039,7.072208348,2.9265625,-4.144873119,-2.996339742,44.99999998 +163.48,50.42977503,-2.575462786,50.4778,7.063626812,7.071097985,2.9465625,-4.228985558,-2.945741896,44.99999998 +163.49,50.42977566,-2.575461791,50.4483,7.063626778,7.070209668,2.9665625,-4.312214839,-2.892575309,44.99999998 +163.5,50.4297763,-2.575460796,50.4185,7.067102934,7.069987493,2.9865625,-4.394543603,-2.836886389,44.99999998 +163.51,50.42977693,-2.575459801,50.3885,7.077531481,7.070209413,3.004375,-4.475954546,-2.77872361,44.99999998 +163.52,50.42977757,-2.575458806,50.3584,7.084483842,7.071097474,3.0196875,-4.556430823,-2.718137792,44.99999998 +163.53,50.42977821,-2.575457811,50.3281,7.077531429,7.072207583,3.0334375,-4.635955474,-2.655181706,44.99999998 +163.54,50.42977884,-2.575456815,50.2977,7.067102819,7.072207454,3.04625,-4.714511999,-2.589910239,44.99999998 +163.55,50.42977948,-2.57545582,50.2672,7.063626586,7.071319136,3.0584375,-4.79208401,-2.522380345,44.99999998 +163.56,50.42978011,-2.575454825,50.2365,7.063626538,7.071096961,3.0696875,-4.868655178,-2.452650923,44.99999998 +163.57,50.42978075,-2.57545383,50.2058,7.067102692,7.071096832,3.0796875,-4.944209633,-2.380782706,44.99999998 +163.58,50.42978138,-2.575452834,50.1749,7.077531253,7.070208513,3.088125,-5.01873156,-2.306838435,44.99999998 +163.59,50.42978202,-2.57545184,50.144,7.084483624,7.069986337,3.0946875,-5.092205319,-2.230882623,44.99999998 +163.6,50.42978266,-2.575450845,50.113,7.077531206,7.071318493,3.1,-5.164615725,-2.152981391,44.99999998 +163.61,50.42978329,-2.575449849,50.082,7.067102576,7.071984506,3.1046875,-5.235947538,-2.07320269,44.99999998 +163.62,50.42978393,-2.575448854,50.0509,7.06362633,7.071318234,3.108125,-5.306185861,-1.991616193,44.99999998 +163.63,50.42978456,-2.575447859,50.0198,7.063626296,7.071096058,3.1096875,-5.375316084,-1.908292946,44.99999998 +163.64,50.4297852,-2.575446864,49.9887,7.06362628,7.071317976,3.1096875,-5.44332371,-1.823305658,44.99999998 +163.65,50.42978583,-2.575445868,49.9576,7.06362626,7.0710958,3.108125,-5.510194589,-1.736728412,44.99999998 +163.66,50.42978647,-2.575444874,49.9265,7.067102416,7.071095671,3.105,-5.575914739,-1.648636667,44.99999998 +163.67,50.4297871,-2.575443878,49.8955,7.07753095,7.07131759,3.10125,-5.640470409,-1.55910737,44.99999998 +163.68,50.42978774,-2.575442883,49.8645,7.084483292,7.070873366,3.0965625,-5.703848193,-1.468218445,44.99999998 +163.69,50.42978838,-2.575441888,49.8335,7.07753087,7.070429142,3.0896875,-5.76603474,-1.376049245,44.99999998 +163.7,50.42978901,-2.575440893,49.8027,7.067102267,7.071095155,3.0815625,-5.827017159,-1.2826801,44.99999998 +163.71,50.42978965,-2.575439898,49.7719,7.063626055,7.072205263,3.0734375,-5.886782673,-1.188192427,44.99999998 +163.72,50.42979028,-2.575438902,49.7412,7.063626028,7.072205134,3.064375,-5.945318792,-1.092668617,44.99999998 +163.73,50.42979092,-2.575437907,49.7106,7.067102182,7.07109477,3.0528125,-6.002613311,-0.996192035,44.99999998 +163.74,50.42979155,-2.575436912,49.6801,7.077530717,7.070206452,3.038125,-6.058654313,-0.898846735,44.99999998 +163.75,50.42979219,-2.575435917,49.6498,7.084483061,7.069984277,3.021875,-6.113429995,-0.800717571,44.99999998 +163.76,50.42979283,-2.575434922,49.6197,7.077530647,7.070206195,3.0065625,-6.166928955,-0.701890259,44.99999998 +163.77,50.42979346,-2.575433927,49.5897,7.067102047,7.071094256,2.99125,-6.21914002,-0.602450855,44.99999998 +163.78,50.4297941,-2.575432932,49.5598,7.063625827,7.072204366,2.9728125,-6.270052363,-0.502486106,44.99999998 +163.79,50.42979473,-2.575431936,49.5302,7.063625795,7.072204239,2.9515625,-6.31965521,-0.402083159,44.99999998 +163.8,50.42979537,-2.575430941,49.5008,7.067101951,7.071093875,2.9303125,-6.367938363,-0.30132962,44.99999998 +163.81,50.429796,-2.575429946,49.4716,7.077530486,7.070205559,2.9096875,-6.414891567,-0.200313264,44.99999998 +163.82,50.42979664,-2.575428951,49.4426,7.084482836,7.069983385,2.8878125,-6.460505138,-0.099122272,44.99999998 +163.83,50.42979728,-2.575427956,49.4138,7.077530428,7.070205306,2.863125,-6.504769508,0.002155123,44.99999998 +163.84,50.42979791,-2.575426961,49.3853,7.06710183,7.071093368,2.8365625,-6.547675453,0.103430685,44.99999998 +163.85,50.42979855,-2.575425966,49.3571,7.06362561,7.072203478,2.8096875,-6.589214033,0.204616063,44.99999998 +163.86,50.42979918,-2.57542497,49.3291,7.063625567,7.072203353,2.7815625,-6.629376484,0.305622964,44.99999998 +163.87,50.42979982,-2.575423975,49.3014,7.067101713,7.071092991,2.75125,-6.668154497,0.406363383,44.99999998 +163.88,50.42980045,-2.57542298,49.2741,7.077530263,7.070204677,2.72,-6.705539936,0.506749428,44.99999998 +163.89,50.42980109,-2.575421985,49.247,7.084482633,7.069982506,2.6884375,-6.741525066,0.606693607,44.99999998 +163.9,50.42980173,-2.57542099,49.2203,7.077530228,7.070204429,2.65625,-6.776102266,0.706108775,44.99999998 +163.91,50.42980236,-2.575419995,49.1939,7.067101624,7.071092494,2.623125,-6.809264376,0.804908127,44.99999998 +163.92,50.429803,-2.575419,49.1678,7.063625397,7.072202606,2.5878125,-6.841004404,0.903005607,44.99999998 +163.93,50.42980363,-2.575418004,49.1421,7.063625354,7.072202483,2.55,-6.87131582,1.00031567,44.99999998 +163.94,50.42980427,-2.575417009,49.1168,7.067101514,7.071092125,2.511875,-6.900192262,1.096753462,44.99999998 +163.95,50.4298049,-2.575416014,49.0919,7.07753008,7.070203814,2.4746875,-6.927627716,1.192234874,44.99999998 +163.96,50.42980554,-2.575415019,49.0673,7.084482457,7.070203691,2.43625,-6.953616337,1.286676596,44.99999998 +163.97,50.42980618,-2.575414024,49.0431,7.077530047,7.071091758,2.3946875,-6.978152853,1.379996352,44.99999998 +163.98,50.42980681,-2.575413029,49.0194,7.067101427,7.072201873,2.351875,-7.001232052,1.472112724,44.99999998 +163.99,50.42980745,-2.575412033,48.9961,7.06362519,7.072201753,2.31,-7.022849119,1.562945328,44.99999998 +164,50.42980808,-2.575411038,48.9732,7.063625166,7.071091398,2.2678125,-7.042999586,1.652415094,44.99999998 +164.01,50.42980872,-2.575410043,48.9507,7.063625159,7.07020309,2.223125,-7.061679214,1.740443929,44.99999998 +164.02,50.42980935,-2.575409048,48.9287,7.063625149,7.069980924,2.1765625,-7.078884048,1.826955055,44.99999998 +164.03,50.42980999,-2.575408053,48.9072,7.067101315,7.070202852,2.13,-7.094610593,1.911873015,44.99999998 +164.04,50.42981062,-2.575407058,48.8861,7.077529858,7.071090922,2.083125,-7.108855527,1.99512384,44.99999998 +164.05,50.42981126,-2.575406063,48.8655,7.084482213,7.072201041,2.0346875,-7.121615813,2.076634879,44.99999998 +164.06,50.4298119,-2.575405067,48.8454,7.077529811,7.072200924,1.985,-7.132888872,2.156335027,44.99999998 +164.07,50.42981253,-2.575404072,48.8258,7.067101224,7.071090572,1.9346875,-7.142672356,2.234154842,44.99999998 +164.08,50.42981317,-2.575403077,48.8067,7.063625014,7.070424315,1.8834375,-7.150964144,2.310026487,44.99999998 +164.09,50.4298138,-2.575402082,48.7881,7.063624987,7.070868294,1.8315625,-7.157762517,2.383883669,44.99999998 +164.1,50.42981444,-2.575401087,48.7701,7.067101153,7.071312273,1.7796875,-7.163066158,2.45566216,44.99999998 +164.11,50.42981507,-2.575400091,48.7525,7.077529711,7.071090112,1.7265625,-7.166873807,2.525299221,44.99999998 +164.12,50.42981571,-2.575399097,48.7355,7.084482085,7.071089998,1.6715625,-7.169184775,2.592734176,44.99999998 +164.13,50.42981635,-2.575398101,48.7191,7.077529687,7.071311933,1.616875,-7.169998604,2.65790824,44.99999998 +164.14,50.42981698,-2.575397106,48.7032,7.067101091,7.070867726,1.563125,-7.169315008,2.720764575,44.99999998 +164.15,50.42981762,-2.575396111,48.6878,7.063624883,7.070423521,1.5078125,-7.167134216,2.781248349,44.99999998 +164.16,50.42981825,-2.575395116,48.673,7.063624872,7.071089551,1.45,-7.163456629,2.83930685,44.99999998 +164.17,50.42981889,-2.575394121,48.6588,7.067101046,7.072199676,1.3915625,-7.158283107,2.894889428,44.99999998 +164.18,50.42981952,-2.575393125,48.6452,7.077529598,7.072199566,1.3334375,-7.151614623,2.947947612,44.99999998 +164.19,50.42982016,-2.57539213,48.6321,7.084481965,7.071089222,1.275,-7.14345261,2.998435163,44.99999998 +164.2,50.4298208,-2.575391135,48.6197,7.077529575,7.070200925,1.2165625,-7.133798787,3.046308021,44.99999998 +164.21,50.42982143,-2.57539014,48.6078,7.067100995,7.069978769,1.158125,-7.122655159,3.091524475,44.99999998 +164.22,50.42982207,-2.575389145,48.5965,7.063624787,7.070200709,1.098125,-7.110024075,3.134045048,44.99999998 +164.23,50.4298227,-2.57538815,48.5858,7.063624761,7.071088792,1.0365625,-7.095908171,3.17383267,44.99999998 +164.24,50.42982334,-2.575387155,48.5758,7.063624744,7.072198922,0.975,-7.080310312,3.210852676,44.99999998 +164.25,50.42982397,-2.575386159,48.5663,7.063624745,7.072198816,0.9134375,-7.063233877,3.245072753,44.99999998 +164.26,50.42982461,-2.575385164,48.5575,7.067100945,7.071088476,0.8515625,-7.044682363,3.276463105,44.99999998 +164.27,50.42982524,-2.575384169,48.5493,7.077529525,7.070200185,0.79,-7.024659608,3.304996346,44.99999998 +164.28,50.42982588,-2.575383174,48.5417,7.084481898,7.069978035,0.728125,-7.00316991,3.330647552,44.99999998 +164.29,50.42982652,-2.575382179,48.5347,7.077529488,7.070199979,0.665,-6.980217679,3.353394434,44.99999998 +164.3,50.42982715,-2.575381184,48.5284,7.06710089,7.071088065,0.6015625,-6.955807671,3.373217055,44.99999998 +164.31,50.42982779,-2.575380189,48.5227,7.063624697,7.0721982,0.5384375,-6.929945101,3.390098168,44.99999998 +164.32,50.42982842,-2.575379193,48.5176,7.063624708,7.072198099,0.475,-6.90263524,3.404023105,44.99999998 +164.33,50.42982906,-2.575378198,48.5132,7.067100899,7.071087765,0.4115625,-6.873883874,3.414979663,44.99999998 +164.34,50.42982969,-2.575377203,48.5094,7.077529464,7.070199478,0.3484375,-6.84369702,3.422958329,44.99999998 +164.35,50.42983033,-2.575376208,48.5062,7.084481837,7.07019938,0.2846875,-6.812080922,3.427952115,44.99999998 +164.36,50.42983097,-2.575375213,48.5037,7.077529454,7.07108747,0.2196875,-6.77904217,3.429956665,44.99999998 +164.37,50.4298316,-2.575374218,48.5018,7.067100888,7.072197608,0.15375,-6.744587754,3.428970261,44.99999998 +164.38,50.42983224,-2.575373222,48.5006,7.063624698,7.072197512,0.0884375,-6.708724779,3.424993704,44.99999998 +164.39,50.42983287,-2.575372227,48.5001,7.063624694,7.071087181,0.025,-6.671460807,3.418030548,44.99999998 +164.4,50.42983351,-2.575371232,48.5001,7.067100886,7.070198899,-0.0384375,-6.632803574,3.408086808,44.99999998 +164.41,50.42983414,-2.575370237,48.5008,7.077529466,7.069976759,-0.1034375,-6.592761158,3.395171136,44.99999998 +164.42,50.42983478,-2.575369242,48.5022,7.084481849,7.070198713,-0.168125,-6.551341924,3.379294877,44.99999998 +164.43,50.42983542,-2.575368247,48.5042,7.07752946,7.071086808,-0.2315625,-6.508554525,3.360471781,44.99999998 +164.44,50.42983605,-2.575367252,48.5068,7.067100888,7.072196951,-0.2953125,-6.464407897,3.338718292,44.99999998 +164.45,50.42983669,-2.575366256,48.5101,7.063624707,7.07219686,-0.36,-6.418911324,3.314053433,44.99999998 +164.46,50.42983732,-2.575365261,48.514,7.063624719,7.071086535,-0.425,-6.372074144,3.286498633,44.99999998 +164.47,50.42983796,-2.575364266,48.5186,7.067100914,7.070420304,-0.4896875,-6.323906327,3.256077954,44.99999998 +164.48,50.42983859,-2.575363271,48.5238,7.077529486,7.070864309,-0.553125,-6.274417785,3.222817983,44.99999998 +164.49,50.42983923,-2.575362276,48.5297,7.084481874,7.071308315,-0.615,-6.223618889,3.186747597,44.99999998 +164.5,50.42983987,-2.57536128,48.5361,7.077529506,7.07108618,-0.676875,-6.171520352,3.147898366,44.99999998 +164.51,50.4298405,-2.575360286,48.5432,7.067100949,7.071086093,-0.7403125,-6.11813289,3.106304094,44.99999998 +164.52,50.42984114,-2.57535929,48.5509,7.063624769,7.071308054,-0.804375,-6.063467789,3.062001106,44.99999998 +164.53,50.42984177,-2.575358295,48.5593,7.063624766,7.070863876,-0.8665625,-6.007536394,3.015028021,44.99999998 +164.54,50.42984241,-2.5753573,48.5683,7.067100953,7.070419697,-0.9265625,-5.950350393,2.965425747,44.99999998 +164.55,50.42984304,-2.575356305,48.5778,7.077529545,7.070863706,-0.986875,-5.891921761,2.913237599,44.99999998 +164.56,50.42984368,-2.57535531,48.588,7.084481962,7.071307717,-1.0484375,-5.832262645,2.858509014,44.99999998 +164.57,50.42984432,-2.575354314,48.5988,7.077529601,7.071085587,-1.1096875,-5.771385536,2.801287834,44.99999998 +164.58,50.42984495,-2.57535332,48.6102,7.067101029,7.071085505,-1.17,-5.709303209,2.741623848,44.99999998 +164.59,50.42984559,-2.575352324,48.6222,7.063624834,7.071307471,-1.23,-5.646028501,2.679569138,44.99999998 +164.6,50.42984622,-2.575351329,48.6348,7.063624837,7.070863296,-1.2896875,-5.581574702,2.615177792,44.99999998 +164.61,50.42984686,-2.575350334,48.648,7.063624859,7.070419122,-1.348125,-5.515955278,2.548506017,44.99999998 +164.62,50.42984749,-2.575349339,48.6618,7.063624891,7.071085184,-1.405,-5.449183923,2.479611853,44.99999998 +164.63,50.42984813,-2.575348344,48.6761,7.067101106,7.07219534,-1.4615625,-5.381274559,2.40855546,44.99999998 +164.64,50.42984876,-2.575347348,48.691,7.077529698,7.072195262,-1.5184375,-5.312241395,2.335398777,44.99999998 +164.65,50.4298494,-2.575346353,48.7065,7.084482092,7.071084949,-1.5746875,-5.242098813,2.260205572,44.99999998 +164.66,50.42985004,-2.575345358,48.7225,7.077529712,7.070196684,-1.63,-5.170861481,2.183041449,44.99999998 +164.67,50.42985067,-2.575344363,48.7391,7.067101152,7.070196608,-1.6846875,-5.098544352,2.103973675,44.99999998 +164.68,50.42985131,-2.575343368,48.7562,7.063624996,7.07108472,-1.738125,-5.025162381,2.023071175,44.99999998 +164.69,50.42985194,-2.575342373,48.7739,7.063625029,7.07219488,-1.79,-4.950730981,1.940404595,44.99999998 +164.7,50.42985258,-2.575341377,48.792,7.06710124,7.072194805,-1.841875,-4.875265736,1.856045899,44.99999998 +164.71,50.42985321,-2.575340382,48.8107,7.077529827,7.071084496,-1.895,-4.798782287,1.770068711,44.99999998 +164.72,50.42985385,-2.575339387,48.8299,7.084482226,7.070196235,-1.9478125,-4.721296736,1.682548033,44.99999998 +164.73,50.42985449,-2.575338392,48.8497,7.077529867,7.069974115,-1.9978125,-4.642825181,1.593560067,44.99999998 +164.74,50.42985512,-2.575337397,48.8699,7.067101324,7.07019609,-2.045,-4.56338401,1.503182564,44.99999998 +164.75,50.42985576,-2.575336402,48.8906,7.063625161,7.071084206,-2.091875,-4.482989838,1.411494248,44.99999998 +164.76,50.42985639,-2.575335407,48.9117,7.063625185,7.07219437,-2.1396875,-4.401659453,1.318575104,44.99999998 +164.77,50.42985703,-2.575334411,48.9334,7.067101397,7.072194299,-2.1865625,-4.319409871,1.224506091,44.99999998 +164.78,50.42985766,-2.575333416,48.9555,7.077529989,7.071083994,-2.23125,-4.236258226,1.129369314,44.99999998 +164.79,50.4298583,-2.575332421,48.978,7.084482396,7.070195736,-2.275,-4.152221875,1.033247737,44.99999998 +164.8,50.42985894,-2.575331426,49.001,7.077530045,7.06997362,-2.3184375,-4.067318354,0.936225127,44.99999998 +164.81,50.42985957,-2.575330431,49.0244,7.067101506,7.070195598,-2.36125,-3.981565479,0.838386109,44.99999998 +164.82,50.42986021,-2.575329436,49.0482,7.063625346,7.071083717,-2.403125,-3.894981071,0.739816054,44.99999998 +164.83,50.42986084,-2.575328441,49.0725,7.063625367,7.072193884,-2.443125,-3.807583293,0.640600849,44.99999998 +164.84,50.42986148,-2.575327445,49.0971,7.067101573,7.072193817,-2.4815625,-3.719390306,0.54082701,44.99999998 +164.85,50.42986211,-2.57532645,49.1221,7.07753017,7.071083515,-2.52,-3.63042056,0.440581569,44.99999998 +164.86,50.42986275,-2.575325455,49.1475,7.084482587,7.070195261,-2.558125,-3.540692676,0.339951903,44.99999998 +164.87,50.42986339,-2.57532446,49.1733,7.077530242,7.069973148,-2.5946875,-3.450225333,0.239025845,44.99999998 +164.88,50.42986402,-2.575323465,49.1994,7.067101705,7.070195129,-2.6296875,-3.359037496,0.137891289,44.99999998 +164.89,50.42986466,-2.57532247,49.2259,7.063625546,7.071083251,-2.6634375,-3.267148186,0.036636583,44.99999998 +164.9,50.42986529,-2.575321475,49.2527,7.063625563,7.072193421,-2.69625,-3.174576541,-0.064650151,44.99999998 +164.91,50.42986593,-2.575320479,49.2798,7.063625576,7.072193356,-2.728125,-3.081341927,-0.165880449,44.99999998 +164.92,50.42986656,-2.575319484,49.3073,7.063625607,7.071083058,-2.758125,-2.987463766,-0.266966132,44.99999998 +164.93,50.4298672,-2.575318489,49.335,7.06710185,7.070416853,-2.7865625,-2.892961769,-0.367819023,44.99999998 +164.94,50.42986783,-2.575317494,49.363,7.077530478,7.070860883,-2.815,-2.797855588,-0.468351172,44.99999998 +164.95,50.42986847,-2.575316499,49.3913,7.084482894,7.071304913,-2.8428125,-2.702165161,-0.568474916,44.99999998 +164.96,50.42986911,-2.575315503,49.4199,7.077530523,7.071082803,-2.868125,-2.605910372,-0.668102937,44.99999998 +164.97,50.42986974,-2.575314509,49.4487,7.067101962,7.07108274,-2.8915625,-2.509111387,-0.767148318,44.99999998 +164.98,50.42987038,-2.575313513,49.4777,7.063625807,7.071304725,-2.915,-2.411788375,-0.86552477,44.99999998 +164.99,50.42987101,-2.575312518,49.507,7.063625856,7.071082616,-2.9378125,-2.313961733,-0.963146465,44.99999998 +165,50.42987165,-2.575311523,49.5365,7.067102088,7.0713046,-2.958125,-2.215651858,-1.059928319,44.99999998 +165.01,50.42987228,-2.575310528,49.5662,7.077530698,7.072192726,-2.9765625,-2.116879263,-1.15578582,44.99999998 +165.02,50.42987292,-2.575309532,49.596,7.084483111,7.072192664,-2.9946875,-2.017664573,-1.250635545,44.99999998 +165.03,50.42987356,-2.575308537,49.6261,7.077530752,7.071082368,-3.0115625,-1.91802853,-1.344394645,44.99999998 +165.04,50.42987419,-2.575307542,49.6563,7.067102208,7.07019412,-3.02625,-1.817991875,-1.436981416,44.99999998 +165.05,50.42987483,-2.575306547,49.6866,7.063626055,7.069972012,-3.04,-1.717575636,-1.528315128,44.99999998 +165.06,50.42987546,-2.575305552,49.7171,7.063626092,7.070193998,-3.053125,-1.616800668,-1.618316141,44.99999998 +165.07,50.4298761,-2.575304557,49.7477,7.067102321,7.071082124,-3.0646875,-1.515688055,-1.706905901,44.99999998 +165.08,50.42987673,-2.575303562,49.7784,7.077530937,7.072192298,-3.0746875,-1.414258884,-1.794007289,44.99999998 +165.09,50.42987737,-2.575302566,49.8092,7.084483354,7.072192238,-3.0834375,-1.31253441,-1.879544216,44.99999998 +165.1,50.42987801,-2.575301571,49.8401,7.077530995,7.071081943,-3.09125,-1.210535776,-1.963442196,44.99999998 +165.11,50.42987864,-2.575300576,49.871,7.067102452,7.070193694,-3.098125,-1.10828441,-2.045628007,44.99999998 +165.12,50.42987928,-2.575299581,49.9021,7.063626302,7.069971587,-3.103125,-1.005801512,-2.126029972,44.99999998 +165.13,50.42987991,-2.575298586,49.9331,7.063626343,7.070193574,-3.10625,-0.903108624,-2.204578074,44.99999998 +165.14,50.42988055,-2.575297591,49.9642,7.067102569,7.071081702,-3.1084375,-0.80022712,-2.281203673,44.99999998 +165.15,50.42988118,-2.575296596,49.9953,7.077531172,7.072191875,-3.109375,-0.697178483,-2.355840077,44.99999998 +165.16,50.42988182,-2.5752956,50.0264,7.084483589,7.072191815,-3.1084375,-0.593984258,-2.428422142,44.99999998 +165.17,50.42988246,-2.575294605,50.0575,7.077531247,7.07108152,-3.10625,-0.490665987,-2.498886611,44.99999998 +165.18,50.42988309,-2.57529361,50.0885,7.067102714,7.070193272,-3.1034375,-0.387245271,-2.567172008,44.99999998 +165.19,50.42988373,-2.575292615,50.1196,7.063626561,7.069971165,-3.0996875,-0.283743654,-2.633218744,44.99999998 +165.2,50.42988436,-2.57529162,50.1505,7.06362659,7.070193152,-3.094375,-0.180182793,-2.696969294,44.99999998 +165.21,50.429885,-2.575290625,50.1815,7.063626609,7.071081279,-3.086875,-0.076584289,-2.758368081,44.99999998 +165.22,50.42988563,-2.57528963,50.2123,7.063626633,7.072191452,-3.0778125,0.027030201,-2.817361535,44.99999998 +165.23,50.42988627,-2.575288634,50.243,7.067102869,7.072191392,-3.0684375,0.130639018,-2.873898145,44.99999998 +165.24,50.4298869,-2.575287639,50.2737,7.077531503,7.071081097,-3.0578125,0.23422062,-2.927928753,44.99999998 +165.25,50.42988754,-2.575286644,50.3042,7.084483929,7.070192849,-3.0446875,0.337753234,-2.979406089,44.99999998 +165.26,50.42988818,-2.575285649,50.3346,7.077531561,7.069970741,-3.03,0.441215375,-3.028285347,44.99999998 +165.27,50.42988881,-2.575284654,50.3648,7.067103001,7.070192726,-3.015,0.544585326,-3.074523958,44.99999998 +165.28,50.42988945,-2.575283659,50.3949,7.063626847,7.071080852,-2.9996875,0.647841545,-3.11808147,44.99999998 +165.29,50.42989008,-2.575282664,50.4248,7.063626896,7.072191025,-2.9828125,0.750962547,-3.158920011,44.99999998 +165.3,50.42989072,-2.575281668,50.4546,7.067103129,7.072190963,-2.963125,0.853926615,-3.197003943,44.99999998 +165.31,50.42989135,-2.575280673,50.4841,7.077531742,7.071302714,-2.9415625,0.956712436,-3.232299976,44.99999998 +165.32,50.42989199,-2.575279678,50.5134,7.084484163,7.071302652,-2.92,1.059298409,-3.264777459,44.99999998 +165.33,50.42989263,-2.575278683,50.5425,7.077531804,7.071968729,-2.898125,1.161663163,-3.294407971,44.99999998 +165.34,50.42989326,-2.575277687,50.5714,7.067103246,7.071302526,-2.8746875,1.263785327,-3.321165673,44.99999998 +165.35,50.4298939,-2.575276692,50.6,7.063627079,7.069970182,-2.8496875,1.365643587,-3.34502736,44.99999998 +165.36,50.42989453,-2.575275698,50.6284,7.063627116,7.070192166,-2.8234375,1.467216628,-3.365972061,44.99999998 +165.37,50.42989517,-2.575274702,50.6565,7.067103352,7.07108029,-2.79625,1.568483251,-3.383981615,44.99999998 +165.38,50.4298958,-2.575273707,50.6843,7.077531974,7.071080226,-2.768125,1.669422372,-3.399040263,44.99999998 +165.39,50.42989644,-2.575272712,50.7119,7.084484391,7.071302208,-2.738125,1.770012791,-3.411134944,44.99999998 +165.4,50.42989708,-2.575271717,50.7391,7.077532017,7.07219033,-2.70625,1.870233594,-3.420255,44.99999998 +165.41,50.42989771,-2.575270721,50.766,7.067103456,7.072190266,-2.6734375,1.970063812,-3.426392581,44.99999998 +165.42,50.42989835,-2.575269726,50.7926,7.063627303,7.071079967,-2.6396875,2.069482647,-3.429542302,44.99999998 +165.43,50.42989898,-2.575268731,50.8188,7.063627348,7.070191714,-2.6046875,2.168469242,-3.429701412,44.99999998 +165.44,50.42989962,-2.575267736,50.8447,7.067103577,7.069969601,-2.5684375,2.267003028,-3.426869797,44.99999998 +165.45,50.42990025,-2.575266741,50.8702,7.077532177,7.070191581,-2.5315625,2.365063323,-3.421049864,44.99999998 +165.46,50.42990089,-2.575265746,50.8953,7.084484578,7.071079701,-2.4946875,2.462629727,-3.412246711,44.99999998 +165.47,50.42990153,-2.575264751,50.9201,7.077532217,7.072189868,-2.4565625,2.559681845,-3.400468017,44.99999998 +165.48,50.42990216,-2.575263755,50.9445,7.067103677,7.0721898,-2.41625,2.65619945,-3.385724094,44.99999998 +165.49,50.4299028,-2.57526276,50.9684,7.063627523,7.071079498,-2.375,2.752162261,-3.368027777,44.99999998 +165.5,50.42990343,-2.575261765,50.992,7.063627545,7.070191243,-2.333125,2.847550394,-3.347394478,44.99999998 +165.51,50.42990407,-2.57526077,51.0151,7.067103751,7.069969127,-2.2896875,2.942343798,-3.323842245,44.99999998 +165.52,50.4299047,-2.575259775,51.0378,7.077532351,7.070191104,-2.245,3.036522762,-3.297391477,44.99999998 +165.53,50.42990534,-2.57525878,51.06,7.084484773,7.071079221,-2.1996875,3.130067575,-3.268065434,44.99999998 +165.54,50.42990598,-2.575257785,51.0818,7.077532424,7.072189385,-2.1534375,3.222958702,-3.2358895,44.99999998 +165.55,50.42990661,-2.575256789,51.1031,7.067103867,7.072189313,-2.10625,3.315176774,-3.200891862,44.99999998 +165.56,50.42990725,-2.575255794,51.1239,7.063627689,7.071079007,-2.0584375,3.406702485,-3.163103004,44.99999998 +165.57,50.42990788,-2.575254799,51.1443,7.063627704,7.070190748,-2.01,3.497516811,-3.122555869,44.99999998 +165.58,50.42990852,-2.575253804,51.1641,7.063627722,7.069968629,-1.96125,3.587600674,-3.079285868,44.99999998 +165.59,50.42990915,-2.575252809,51.1835,7.063627749,7.070190603,-1.9115625,3.676935336,-3.033330642,44.99999998 +165.6,50.42990979,-2.575251814,51.2024,7.067103972,7.071078716,-1.8596875,3.765502121,-2.984730299,44.99999998 +165.61,50.42991042,-2.575250819,51.2207,7.077532581,7.072188875,-1.8065625,3.853282464,-2.933527181,44.99999998 +165.62,50.42991106,-2.575249823,51.2385,7.08448499,7.0721888,-1.7534375,3.940258202,-2.879766035,44.99999998 +165.63,50.4299117,-2.575248828,51.2558,7.07753261,7.07107849,-1.6996875,4.026411001,-2.82349373,44.99999998 +165.64,50.42991233,-2.575247833,51.2725,7.067104035,7.070412274,-1.645,4.111722927,-2.764759254,44.99999998 +165.65,50.42991297,-2.575246838,51.2887,7.063627866,7.070856291,-1.59,4.196176218,-2.703613828,44.99999998 +165.66,50.4299136,-2.575245843,51.3043,7.063627899,7.071300308,-1.535,4.279753171,-2.640110853,44.99999998 +165.67,50.42991424,-2.575244847,51.3194,7.067104116,7.071078183,-1.4796875,4.362436309,-2.574305676,44.99999998 +165.68,50.42991487,-2.575243853,51.3339,7.077532712,7.071078104,-1.423125,4.444208502,-2.506255651,44.99999998 +165.69,50.42991551,-2.575242857,51.3479,7.08448511,7.071300071,-1.365,4.525052503,-2.436020135,44.99999998 +165.7,50.42991615,-2.575241862,51.3612,7.077532731,7.071077944,-1.3065625,4.604951525,-2.363660378,44.99999998 +165.71,50.42991678,-2.575240867,51.374,7.067104164,7.071299911,-1.248125,4.683888837,-2.289239463,44.99999998 +165.72,50.42991742,-2.575239872,51.3862,7.063627992,7.071965971,-1.188125,4.761848053,-2.212822306,44.99999998 +165.73,50.42991805,-2.575238876,51.3978,7.063628015,7.071299749,-1.126875,4.838812729,-2.134475484,44.99999998 +165.74,50.42991869,-2.575237881,51.4087,7.067104227,7.069967385,-1.066875,4.914766936,-2.054267466,44.99999998 +165.75,50.42991932,-2.575236887,51.4191,7.077532819,7.070189348,-1.008125,4.989694747,-1.972268038,44.99999998 +165.76,50.42991996,-2.575235891,51.4289,7.084485206,7.071077451,-0.9478125,5.063580519,-1.888548763,44.99999998 +165.77,50.4299206,-2.575234896,51.4381,7.077532815,7.071077367,-0.885,5.136408841,-1.803182635,44.99999998 +165.78,50.42992123,-2.575233901,51.4466,7.067104246,7.071299328,-0.821875,5.208164471,-1.716244139,44.99999998 +165.79,50.42992187,-2.575232906,51.4545,7.063628076,7.072187429,-0.76,5.278832455,-1.62780902,44.99999998 +165.8,50.4299225,-2.57523191,51.4618,7.063628087,7.072187343,-0.698125,5.348398011,-1.537954456,44.99999998 +165.81,50.42992314,-2.575230915,51.4685,7.067104277,7.071077022,-0.6346875,5.416846643,-1.446758712,44.99999998 +165.82,50.42992377,-2.57522992,51.4745,7.077532857,7.070188747,-0.5703125,5.484164028,-1.354301429,44.99999998 +165.83,50.42992441,-2.575228925,51.4799,7.084485254,7.069966611,-0.5065625,5.550336069,-1.260663166,44.99999998 +165.84,50.42992505,-2.57522793,51.4846,7.077532883,7.070188569,-0.4434375,5.615349075,-1.165925568,44.99999998 +165.85,50.42992568,-2.575226935,51.4888,7.067104318,7.071076665,-0.38,5.67918935,-1.070171315,44.99999998 +165.86,50.42992632,-2.57522594,51.4922,7.063628134,7.072186808,-0.31625,5.741843545,-0.973483827,44.99999998 +165.87,50.42992695,-2.575224944,51.4951,7.063628131,7.072186717,-0.251875,5.803298712,-0.875947446,44.99999998 +165.88,50.42992759,-2.575223949,51.4973,7.063628119,7.071076391,-0.1865625,5.863541901,-0.777647197,44.99999998 +165.89,50.42992822,-2.575222954,51.4988,7.06362811,7.070188112,-0.121875,5.922560565,-0.678668852,44.99999998 +165.9,50.42992886,-2.575221959,51.4997,7.067104314,7.069965971,-0.0584375,5.980342384,-0.579098699,44.99999998 +165.91,50.42992949,-2.575220964,51.5,7.077532917,7.070187924,0.0053125,6.03687527,-0.479023599,44.99999998 +165.92,50.42993013,-2.575219969,51.4996,7.08448531,7.071076015,0.07,6.09214742,-0.378530755,44.99999998 +165.93,50.42993077,-2.575218974,51.4986,7.077532906,7.072186153,0.1346875,6.146147317,-0.277707773,44.99999998 +165.94,50.4299314,-2.575217978,51.4969,7.067104308,7.072186056,0.1984375,6.198863674,-0.176642716,44.99999998 +165.95,50.42993204,-2.575216983,51.4946,7.063628117,7.071075726,0.261875,6.250285491,-0.075423534,44.99999998 +165.96,50.42993267,-2.575215988,51.4917,7.06362813,7.070187441,0.326875,6.300401994,0.025861367,44.99999998 +165.97,50.42993331,-2.575214993,51.4881,7.067104327,7.069965295,0.393125,6.349202758,0.127123693,44.99999998 +165.98,50.42993394,-2.575213998,51.4838,7.077532904,7.070187243,0.4578125,6.396677582,0.228275209,44.99999998 +165.99,50.42993458,-2.575213003,51.4789,7.084485288,7.07107533,0.52,6.442816498,0.329227622,44.99999998 +166,50.42993522,-2.575212008,51.4734,7.07753289,7.072185462,0.581875,6.487609938,0.429892984,44.99999998 +166.01,50.42993585,-2.575211012,51.4673,7.067104291,7.07218536,0.645,6.531048561,0.530183459,44.99999998 +166.02,50.42993649,-2.575210017,51.4605,7.063628085,7.071297072,0.7084375,6.573123201,0.630011615,44.99999998 +166.03,50.42993712,-2.575209022,51.4531,7.063628082,7.071296969,0.77125,6.613825149,0.729290361,44.99999998 +166.04,50.42993776,-2.575208027,51.4451,7.067104278,7.071963005,0.8334375,6.653145925,0.827933181,44.99999998 +166.05,50.42993839,-2.575207031,51.4364,7.077532861,7.071296761,0.895,6.69107722,0.925854075,44.99999998 +166.06,50.42993903,-2.575206036,51.4272,7.084485238,7.069964377,0.9565625,6.727611187,1.022967556,44.99999998 +166.07,50.42993967,-2.575205042,51.4173,7.077532822,7.070186317,1.0184375,6.762740146,1.119189,44.99999998 +166.08,50.4299403,-2.575204046,51.4068,7.067104219,7.071074397,1.0796875,6.796456879,1.214434467,44.99999998 +166.09,50.42994094,-2.575203051,51.3957,7.063628023,7.07107429,1.14,6.828754166,1.308620994,44.99999998 +166.1,50.42994157,-2.575202056,51.384,7.063628026,7.071296229,1.1996875,6.859625418,1.401666303,44.99999998 +166.11,50.42994221,-2.575201061,51.3717,7.067104213,7.072184308,1.2584375,6.889064104,1.493489379,44.99999998 +166.12,50.42994284,-2.575200065,51.3588,7.077532772,7.072184199,1.3165625,6.917064093,1.584010121,44.99999998 +166.13,50.42994348,-2.57519907,51.3454,7.08448513,7.071073857,1.375,6.943619541,1.673149577,44.99999998 +166.14,50.42994412,-2.575198075,51.3313,7.077532725,7.07018556,1.433125,6.96872489,1.760830053,44.99999998 +166.15,50.42994475,-2.57519708,51.3167,7.067104142,7.069963402,1.4896875,6.992374926,1.846975003,44.99999998 +166.16,50.42994539,-2.575196085,51.3015,7.063627944,7.070185337,1.545,7.014564722,1.931509425,44.99999998 +166.17,50.42994602,-2.57519509,51.2858,7.063627923,7.071073412,1.6,7.03528958,2.014359466,44.99999998 +166.18,50.42994666,-2.575194095,51.2695,7.06362789,7.072183532,1.655,7.054545202,2.09545299,44.99999998 +166.19,50.42994729,-2.575193099,51.2527,7.063627861,7.072183419,1.7096875,7.072327577,2.174719295,44.99999998 +166.2,50.42994793,-2.575192104,51.2353,7.067104044,7.071073072,1.7634375,7.088632982,2.252089166,44.99999998 +166.21,50.42994856,-2.575191109,51.2174,7.077532626,7.070184771,1.81625,7.103458036,2.327495168,44.99999998 +166.22,50.4299492,-2.575190114,51.199,7.084485001,7.06996261,1.8684375,7.116799644,2.400871581,44.99999998 +166.23,50.42994984,-2.575189119,51.18,7.077532586,7.07018454,1.9196875,7.128655001,2.472154406,44.99999998 +166.24,50.42995047,-2.575188124,51.1606,7.067103978,7.07107261,1.97,7.139021583,2.54128142,44.99999998 +166.25,50.42995111,-2.575187129,51.1406,7.063627759,7.072182726,2.02,7.147897273,2.608192463,44.99999998 +166.26,50.42995174,-2.575186133,51.1202,7.063627731,7.072182609,2.069375,7.155280235,2.672829092,44.99999998 +166.27,50.42995238,-2.575185138,51.0992,7.067103899,7.071072259,2.1165625,7.161168923,2.735134986,44.99999998 +166.28,50.42995301,-2.575184143,51.0778,7.077532466,7.070183955,2.1615625,7.165562077,2.795055829,44.99999998 +166.29,50.42995365,-2.575183148,51.056,7.084484841,7.069961789,2.206875,7.16845878,2.85253931,44.99999998 +166.3,50.42995429,-2.575182153,51.0337,7.077532434,7.070183716,2.253125,7.169858458,2.907535294,44.99999998 +166.31,50.42995492,-2.575181158,51.0109,7.06710382,7.071071782,2.2978125,7.169760826,2.95999594,44.99999998 +166.32,50.42995556,-2.575180163,50.9877,7.063627584,7.072181894,2.34,7.168165826,3.009875411,44.99999998 +166.33,50.42995619,-2.575179167,50.9641,7.063627552,7.072181774,2.3815625,7.165073917,3.057130163,44.99999998 +166.34,50.42995683,-2.575178172,50.9401,7.06710373,7.071293466,2.423125,7.160485614,3.101719113,44.99999998 +166.35,50.42995746,-2.575177177,50.9156,7.077532298,7.071293345,2.463125,7.154401948,3.143603302,44.99999998 +166.36,50.4299581,-2.575176182,50.8908,7.084484663,7.071959362,2.50125,7.14682418,3.182746232,44.99999998 +166.37,50.42995874,-2.575175186,50.8656,7.077532244,7.0712931,2.5384375,7.137753914,3.219113754,44.99999998 +166.38,50.42995937,-2.575174191,50.84,7.067103625,7.069960698,2.575,7.127192984,3.252674126,44.99999998 +166.39,50.42996001,-2.575173197,50.8141,7.063627399,7.070182621,2.61125,7.115143682,3.283398186,44.99999998 +166.4,50.42996064,-2.575172201,50.7878,7.063627382,7.071070683,2.6465625,7.101608413,3.311259004,44.99999998 +166.41,50.42996128,-2.575171206,50.7611,7.067103559,7.071070559,2.6796875,7.086590101,3.3362324,44.99999998 +166.42,50.42996191,-2.575170211,50.7342,7.077532111,7.071292481,2.7115625,7.070091838,3.358296547,44.99999998 +166.43,50.42996255,-2.575169216,50.7069,7.084484455,7.072180542,2.743125,7.052117064,3.377432191,44.99999998 +166.44,50.42996319,-2.57516822,50.6793,7.077532025,7.072180417,2.7728125,7.032669558,3.393622661,44.99999998 +166.45,50.42996382,-2.575167225,50.6514,7.067103417,7.071070059,2.8,7.01175339,3.40685386,44.99999998 +166.46,50.42996446,-2.57516623,50.6233,7.063627207,7.070181747,2.8265625,6.989372857,3.417114217,44.99999998 +166.47,50.42996509,-2.575165235,50.5949,7.06362718,7.069959575,2.8534375,6.965532713,3.424394849,44.99999998 +166.48,50.42996573,-2.57516424,50.5662,7.063627143,7.070181495,2.8796875,6.940237887,3.428689282,44.99999998 +166.49,50.42996636,-2.575163245,50.5373,7.063627103,7.071069554,2.904375,6.913493707,3.429993907,44.99999998 +166.5,50.429967,-2.57516225,50.5081,7.067103262,7.07217966,2.9265625,6.88530573,3.42830752,44.99999998 +166.51,50.42996763,-2.575161254,50.4787,7.077531818,7.072179533,2.9465625,6.855679859,3.423631554,44.99999998 +166.52,50.42996827,-2.575160259,50.4492,7.084484183,7.071069173,2.9665625,6.824622223,3.415970192,44.99999998 +166.53,50.42996891,-2.575159264,50.4194,7.077531763,7.070180859,2.98625,6.792139355,3.405329965,44.99999998 +166.54,50.42996954,-2.575158269,50.3894,7.067103144,7.069958685,3.003125,6.758238073,3.391720326,44.99999998 +166.55,50.42997018,-2.575157274,50.3593,7.063626908,7.070180604,3.018125,6.722925423,3.375153022,44.99999998 +166.56,50.42997081,-2.575156279,50.3291,7.063626866,7.071068662,3.0334375,6.686208741,3.355642549,44.99999998 +166.57,50.42997145,-2.575155284,50.2986,7.067103035,7.072178766,3.0478125,6.64809576,3.333205866,44.99999998 +166.58,50.42997208,-2.575154288,50.2681,7.077531601,7.072178637,3.0596875,6.608594388,3.307862624,44.99999998 +166.59,50.42997272,-2.575153293,50.2374,7.084483962,7.071068276,3.07,6.567712875,3.279634827,44.99999998 +166.6,50.42997336,-2.575152298,50.2067,7.077531532,7.070179961,3.0796875,6.525459816,3.248547169,44.99999998 +166.61,50.42997399,-2.575151303,50.1758,7.067102906,7.069957786,3.088125,6.481843977,3.214626749,44.99999998 +166.62,50.42997463,-2.575150308,50.1449,7.063626674,7.070179704,3.0946875,6.436874525,3.177903134,44.99999998 +166.63,50.42997526,-2.575149313,50.1139,7.063626645,7.071067761,3.1,6.390560742,3.138408294,44.99999998 +166.64,50.4299759,-2.575148318,50.0829,7.067102812,7.072177864,3.1046875,6.342912426,3.096176721,44.99999998 +166.65,50.42997653,-2.575147322,50.0518,7.077531364,7.072177735,3.108125,6.293939489,3.051245256,44.99999998 +166.66,50.42997717,-2.575146327,50.0207,7.08448372,7.071067374,3.109375,6.243652129,3.003653032,44.99999998 +166.67,50.42997781,-2.575145332,49.9896,7.077531295,7.070401106,3.1084375,6.192060832,2.953441647,44.99999998 +166.68,50.42997844,-2.575144337,49.9585,7.067102671,7.070845069,3.1065625,6.139176426,2.900654759,44.99999998 +166.69,50.42997908,-2.575143342,49.9275,7.06362644,7.071289032,3.1046875,6.085009913,2.845338434,44.99999998 +166.7,50.42997971,-2.575142346,49.8964,7.063626418,7.071066857,3.1015625,6.029572637,2.787540972,44.99999998 +166.71,50.42998035,-2.575141352,49.8654,7.06710259,7.071066728,3.09625,5.972876171,2.727312737,44.99999998 +166.72,50.42998098,-2.575140356,49.8345,7.077531135,7.071288646,3.09,5.914932376,2.664706212,44.99999998 +166.73,50.42998162,-2.575139361,49.8036,7.084483475,7.071066471,3.083125,5.855753285,2.599776056,44.99999998 +166.74,50.42998226,-2.575138366,49.7728,7.07753104,7.071288389,3.074375,5.795351272,2.532578879,44.99999998 +166.75,50.42998289,-2.575137371,49.7421,7.067102423,7.072176445,3.0634375,5.733739,2.463173178,44.99999998 +166.76,50.42998353,-2.575136375,49.7115,7.063626209,7.072176316,3.05125,5.670929304,2.39161963,44.99999998 +166.77,50.42998416,-2.57513538,49.6811,7.063626191,7.071065957,3.038125,5.606935304,2.317980516,44.99999998 +166.78,50.4299848,-2.575134385,49.6507,7.067102359,7.070177643,3.0234375,5.541770407,2.242320064,44.99999998 +166.79,50.42998543,-2.57513339,49.6206,7.077530903,7.069955468,3.0078125,5.475448136,2.164704336,44.99999998 +166.8,50.42998607,-2.575132395,49.5906,7.084483244,7.070177387,2.9915625,5.407982413,2.085200942,44.99999998 +166.81,50.42998671,-2.5751314,49.5607,7.077530812,7.071065444,2.973125,5.339387276,2.003879208,44.99999998 +166.82,50.42998734,-2.575130405,49.5311,7.067102203,7.072175548,2.953125,5.269677105,1.920810011,44.99999998 +166.83,50.42998798,-2.575129409,49.5017,7.063625993,7.072175421,2.933125,5.198866397,1.836065886,44.99999998 +166.84,50.42998861,-2.575128414,49.4724,7.063625963,7.071065063,2.91125,5.126969991,1.749720688,44.99999998 +166.85,50.42998925,-2.575127419,49.4434,7.063625919,7.070176752,2.8865625,5.054002899,1.661849704,44.99999998 +166.86,50.42998988,-2.575126424,49.4147,7.063625877,7.069954579,2.8615625,4.979980305,1.572529594,44.99999998 +166.87,50.42999052,-2.575125429,49.3862,7.067102047,7.070176498,2.8365625,4.904917734,1.481838167,44.99999998 +166.88,50.42999115,-2.575124434,49.3579,7.077530614,7.071064557,2.8096875,4.82883083,1.389854549,44.99999998 +166.89,50.42999179,-2.575123439,49.33,7.084482977,7.072174663,2.7815625,4.75173552,1.29665901,44.99999998 +166.9,50.42999243,-2.575122443,49.3023,7.077530554,7.072174538,2.753125,4.673647789,1.202332739,44.99999998 +166.91,50.42999306,-2.575121448,49.2749,7.06710194,7.071064182,2.7228125,4.594584083,1.106958013,44.99999998 +166.92,50.4299937,-2.575120453,49.2478,7.063625714,7.070175873,2.69,4.514560843,1.010617967,44.99999998 +166.93,50.42999433,-2.575119458,49.2211,7.063625679,7.069953702,2.6565625,4.433594802,0.913396712,44.99999998 +166.94,50.42999497,-2.575118463,49.1947,7.06710184,7.070175624,2.623125,4.351702861,0.815378931,44.99999998 +166.95,50.4299956,-2.575117468,49.1686,7.077530398,7.071063685,2.588125,4.268902152,0.71665011,44.99999998 +166.96,50.42999624,-2.575116473,49.1429,7.084482768,7.072173794,2.5515625,4.185209863,0.617296363,44.99999998 +166.97,50.42999688,-2.575115477,49.1176,7.077530359,7.072173671,2.5146875,4.100643584,0.517404323,44.99999998 +166.98,50.42999751,-2.575114482,49.0926,7.067101745,7.071063318,2.4765625,4.015220963,0.417061136,44.99999998 +166.99,50.42999815,-2.575113487,49.068,7.063625509,7.070397057,2.43625,3.928959818,0.316354235,44.99999998 +167,50.42999878,-2.575112492,49.0439,7.063625477,7.070841028,2.395,3.84187814,0.215371455,44.99999998 +167.01,50.42999942,-2.575111497,49.0201,7.067101656,7.071284999,2.3534375,3.753994092,0.114200916,44.99999998 +167.02,50.43000005,-2.575110501,48.9968,7.077530229,7.071062833,2.31125,3.665326123,0.012930741,44.99999998 +167.03,50.43000069,-2.575109507,48.9739,7.084482596,7.071062713,2.2684375,3.575892682,-0.088350665,44.99999998 +167.04,50.43000133,-2.575108511,48.9514,7.077530171,7.07128464,2.224375,3.485712448,-0.189555065,44.99999998 +167.05,50.43000196,-2.575107516,48.9294,7.067101548,7.071062474,2.178125,3.394804329,-0.29059411,44.99999998 +167.06,50.4300026,-2.575106521,48.9078,7.063625331,7.071284401,2.1303125,3.303187174,-0.39137985,44.99999998 +167.07,50.43000323,-2.575105526,48.8868,7.063625326,7.072172469,2.083125,3.210880236,-0.491824221,44.99999998 +167.08,50.43000387,-2.57510453,48.8662,7.063625317,7.072172351,2.0365625,3.117902707,-0.591839734,44.99999998 +167.09,50.4300045,-2.575103535,48.846,7.063625291,7.071062004,1.9878125,3.02427407,-0.691339183,44.99999998 +167.1,50.43000514,-2.57510254,48.8264,7.067101448,7.070173703,1.9365625,2.930013861,-0.79023571,44.99999998 +167.11,50.43000577,-2.575101545,48.8073,7.077529999,7.069951541,1.885,2.835141733,-0.888443197,44.99999998 +167.12,50.43000641,-2.57510055,48.7887,7.084482373,7.070173472,1.8334375,2.739677568,-0.98587593,44.99999998 +167.13,50.43000705,-2.575099555,48.7706,7.077529982,7.071061541,1.78125,2.64364119,-1.082448998,44.99999998 +167.14,50.43000768,-2.57509856,48.7531,7.067101386,7.072171658,1.7284375,2.547052767,-1.178078118,44.99999998 +167.15,50.43000832,-2.575097564,48.736,7.063625167,7.072171545,1.6746875,2.44993241,-1.272679924,44.99999998 +167.16,50.43000895,-2.575096569,48.7196,7.063625141,7.071061201,1.6196875,2.352300401,-1.366171969,44.99999998 +167.17,50.43000959,-2.575095574,48.7036,7.067101313,7.070172903,1.56375,2.254177196,-1.458472662,44.99999998 +167.18,50.43001022,-2.575094579,48.6883,7.077529883,7.069950746,1.5078125,2.155583192,-1.549501561,44.99999998 +167.19,50.43001086,-2.575093584,48.6735,7.084482262,7.070172681,1.451875,2.056539015,-1.639179253,44.99999998 +167.2,50.4300115,-2.575092589,48.6592,7.077529861,7.071060755,1.3946875,1.957065405,-1.727427588,44.99999998 +167.21,50.43001213,-2.575091594,48.6456,7.067101268,7.072170876,1.3365625,1.857183048,-1.814169559,44.99999998 +167.22,50.43001277,-2.575090598,48.6325,7.063625065,7.072170767,1.2784375,1.756912798,-1.899329537,44.99999998 +167.23,50.4300134,-2.575089603,48.62,7.063625047,7.071060428,1.2196875,1.656275741,-1.982833323,44.99999998 +167.24,50.43001404,-2.575088608,48.6081,7.067101213,7.070394182,1.1596875,1.555292732,-2.064607979,44.99999998 +167.25,50.43001467,-2.575087613,48.5968,7.077529776,7.070838167,1.0984375,1.453984913,-2.144582288,44.99999998 +167.26,50.43001531,-2.575086618,48.5861,7.084482163,7.071282153,1.036875,1.352373483,-2.222686519,44.99999998 +167.27,50.43001595,-2.575085622,48.5761,7.077529781,7.071060001,0.9765625,1.250479586,-2.298852549,44.99999998 +167.28,50.43001658,-2.575084628,48.5666,7.067101194,7.071059895,0.9165625,1.148324534,-2.373013857,44.99999998 +167.29,50.43001722,-2.575083632,48.5577,7.063624978,7.071281837,0.8546875,1.045929699,-2.445105928,44.99999998 +167.3,50.43001785,-2.575082637,48.5495,7.063624952,7.070837641,0.791875,0.943316453,-2.515065851,44.99999998 +167.31,50.43001849,-2.575081642,48.5419,7.067101136,7.070393446,0.73,0.840506167,-2.582832549,44.99999998 +167.32,50.43001912,-2.575080647,48.5349,7.077529721,7.071059482,0.668125,0.737520384,-2.648347007,44.99999998 +167.33,50.43001976,-2.575079652,48.5285,7.084482114,7.072169611,0.6046875,0.63438059,-2.711552044,44.99999998 +167.34,50.4300204,-2.575078656,48.5228,7.077529727,7.07216951,0.54,0.53110827,-2.772392598,44.99999998 +167.35,50.43002103,-2.575077661,48.5177,7.067101137,7.071059178,0.4753125,0.427725083,-2.830815558,44.99999998 +167.36,50.43002167,-2.575076666,48.5133,7.063624926,7.070170894,0.4115625,0.324252515,-2.886770043,44.99999998 +167.37,50.4300223,-2.575075671,48.5095,7.063624922,7.070170796,0.3484375,0.220712281,-2.940207181,44.99999998 +167.38,50.43002294,-2.575074676,48.5063,7.067101126,7.071058882,0.2846875,0.117125923,-2.99108039,44.99999998 +167.39,50.43002357,-2.575073681,48.5038,7.07752971,7.072169015,0.22,0.0135151,-3.039345381,44.99999998 +167.4,50.43002421,-2.575072685,48.5019,7.08448209,7.072168918,0.1553125,-0.09009853,-3.084960041,44.99999998 +167.41,50.43002485,-2.57507169,48.5007,7.077529693,7.071058592,0.0915625,-0.19369331,-3.127884492,44.99999998 +167.42,50.43002548,-2.575070695,48.5001,7.067101107,7.070170312,0.0284375,-0.297247697,-3.168081434,44.99999998 +167.43,50.43002612,-2.5750697,48.5001,7.063624919,7.069948171,-0.0353125,-0.400739975,-3.205515746,44.99999998 +167.44,50.43002675,-2.575068705,48.5008,7.063624927,7.070170123,-0.1,-0.504148543,-3.240154827,44.99999998 +167.45,50.43002739,-2.57506771,48.5021,7.063624931,7.071058215,-0.165,-0.60745186,-3.271968423,44.99999998 +167.46,50.43002802,-2.575066715,48.5041,7.063624934,7.072168353,-0.23,-0.710628323,-3.300928804,44.99999998 +167.47,50.43002866,-2.575065719,48.5067,7.067101129,7.072168261,-0.295,-0.813656391,-3.327010759,44.99999998 +167.48,50.43002929,-2.575064724,48.51,7.077529708,7.07105794,-0.36,-0.916514519,-3.350191486,44.99999998 +167.49,50.43002993,-2.575063729,48.5139,7.084482097,7.070169665,-0.4246875,-1.019181222,-3.370450758,44.99999998 +167.5,50.43003057,-2.575062734,48.5185,7.077529719,7.069947529,-0.488125,-1.121635129,-3.387770985,44.99999998 +167.51,50.4300312,-2.575061739,48.5237,7.067101151,7.070169486,-0.55,-1.223854753,-3.402137043,44.99999998 +167.52,50.43003184,-2.575060744,48.5295,7.063624965,7.071057582,-0.611875,-1.325818838,-3.413536382,44.99999998 +167.53,50.43003247,-2.575059749,48.5359,7.063624966,7.072167725,-0.675,-1.427506012,-3.421959033,44.99999998 +167.54,50.43003311,-2.575058753,48.543,7.067101164,7.072167638,-0.7384375,-1.528895019,-3.427397721,44.99999998 +167.55,50.43003374,-2.575057758,48.5507,7.077529759,7.071057322,-0.80125,-1.629964831,-3.429847688,44.99999998 +167.56,50.43003438,-2.575056763,48.559,7.084482163,7.070391098,-0.8634375,-1.730694192,-3.429306701,44.99999998 +167.57,50.43003502,-2.575055768,48.568,7.077529789,7.070835105,-0.925,-1.831062131,-3.425775391,44.99999998 +167.58,50.43003565,-2.575054773,48.5775,7.067101219,7.071279113,-0.9865625,-1.931047678,-3.419256678,44.99999998 +167.59,50.43003629,-2.575053777,48.5877,7.063625035,7.071056985,-1.0484375,-2.03062992,-3.40975635,44.99999998 +167.6,50.43003692,-2.575052783,48.5985,7.063625041,7.071056902,-1.1096875,-2.129788116,-3.397282715,44.99999998 +167.61,50.43003756,-2.575051787,48.6099,7.067101244,7.071278865,-1.1696875,-2.228501582,-3.381846545,44.99999998 +167.62,50.43003819,-2.575050792,48.6219,7.077529844,7.070834692,-1.2284375,-2.326749578,-3.36346136,44.99999998 +167.63,50.43003883,-2.575049797,48.6345,7.084482255,7.070390519,-1.2865625,-2.424511705,-3.342143205,44.99999998 +167.64,50.43003947,-2.575048802,48.6476,7.077529889,7.071056577,-1.345,-2.521767509,-3.317910585,44.99999998 +167.65,50.4300401,-2.575047807,48.6614,7.067101319,7.072166728,-1.403125,-2.61849665,-3.290784758,44.99999998 +167.66,50.43004074,-2.575046811,48.6757,7.063625129,7.072166649,-1.4596875,-2.714678961,-3.260789329,44.99999998 +167.67,50.43004137,-2.575045816,48.6906,7.063625146,7.07105634,-1.5153125,-2.81029433,-3.227950425,44.99999998 +167.68,50.43004201,-2.575044821,48.706,7.067101371,7.070168078,-1.5715625,-2.905322818,-3.192296693,44.99999998 +167.69,50.43004264,-2.575043826,48.722,7.077529976,7.070168001,-1.628125,-2.999744543,-3.153859247,44.99999998 +167.7,50.43004328,-2.575042831,48.7386,7.084482376,7.071056109,-1.683125,-3.093539854,-3.112671603,44.99999998 +167.71,50.43004392,-2.575041836,48.7557,7.077529997,7.072166264,-1.7365625,-3.186689098,-3.068769628,44.99999998 +167.72,50.43004455,-2.57504084,48.7733,7.067101424,7.072166189,-1.79,-3.279172851,-3.022191655,44.99999998 +167.73,50.43004519,-2.575039845,48.7915,7.063625254,7.071055885,-1.843125,-3.370971748,-2.972978247,44.99999998 +167.74,50.43004582,-2.57503885,48.8102,7.063625293,7.070167627,-1.894375,-3.462066709,-2.921172434,44.99999998 +167.75,50.43004646,-2.575037855,48.8294,7.067101522,7.069945507,-1.9434375,-3.552438655,-2.866819252,44.99999998 +167.76,50.43004709,-2.57503686,48.8491,7.077530122,7.07016748,-1.991875,-3.642068734,-2.809966197,44.99999998 +167.77,50.43004773,-2.575035865,48.8692,7.084482518,7.071055591,-2.0415625,-3.730938155,-2.750662773,44.99999998 +167.78,50.43004837,-2.57503487,48.8899,7.077530142,7.072165749,-2.0915625,-3.819028468,-2.688960776,44.99999998 +167.79,50.430049,-2.575033874,48.9111,7.067101591,7.072165678,-2.139375,-3.906321224,-2.624913949,44.99999998 +167.8,50.43004964,-2.575032879,48.9327,7.063625438,7.071055377,-2.185,-3.992798145,-2.558578156,44.99999998 +167.81,50.43005027,-2.575031884,48.9548,7.063625467,7.070389169,-2.23,-4.078441298,-2.490011209,44.99999998 +167.82,50.43005091,-2.575030889,48.9773,7.063625489,7.070833192,-2.2746875,-4.163232692,-2.41927298,44.99999998 +167.83,50.43005154,-2.575029894,49.0003,7.063625513,7.071277215,-2.318125,-4.247154622,-2.346425063,44.99999998 +167.84,50.43005218,-2.575028898,49.0237,7.067101731,7.0710551,-2.36,-4.330189614,-2.271531057,44.99999998 +167.85,50.43005281,-2.575027904,49.0475,7.077530334,7.071055031,-2.4015625,-4.412320249,-2.194656278,44.99999998 +167.86,50.43005345,-2.575026908,49.0717,7.084482745,7.071277009,-2.443125,-4.493529511,-2.115867706,44.99999998 +167.87,50.43005409,-2.575025913,49.0964,7.07753039,7.07083285,-2.4828125,-4.573800325,-2.035234037,44.99999998 +167.88,50.43005472,-2.575024918,49.1214,7.067101845,7.070388691,-2.5196875,-4.653115904,-1.952825632,44.99999998 +167.89,50.43005536,-2.575023923,49.1468,7.063625686,7.071054762,-2.5553125,-4.731459804,-1.868714339,44.99999998 +167.9,50.43005599,-2.575022928,49.1725,7.063625711,7.072164926,-2.5915625,-4.80881558,-1.782973497,44.99999998 +167.91,50.43005663,-2.575021932,49.1986,7.06710192,7.07216486,-2.628125,-4.885167077,-1.695677877,44.99999998 +167.92,50.43005726,-2.575020937,49.2251,7.077530526,7.071054565,-2.6628125,-4.960498422,-1.606903567,44.99999998 +167.93,50.4300579,-2.575019942,49.2519,7.084482955,7.070166316,-2.695,-5.034793802,-1.516728031,44.99999998 +167.94,50.43005854,-2.575018947,49.279,7.077530613,7.069944205,-2.7265625,-5.10803769,-1.425229937,44.99999998 +167.95,50.43005917,-2.575017952,49.3064,7.067102066,7.070166186,-2.758125,-5.180214902,-1.332488983,44.99999998 +167.96,50.43005981,-2.575016957,49.3342,7.063625891,7.071054307,-2.7878125,-5.251310255,-1.238586071,44.99999998 +167.97,50.43006044,-2.575015962,49.3622,7.063625905,7.072164473,-2.8146875,-5.32130891,-1.143603075,44.99999998 +167.98,50.43006108,-2.575014966,49.3905,7.067102131,7.07216441,-2.84,-5.390196314,-1.047622847,44.99999998 +167.99,50.43006171,-2.575013971,49.419,7.077530764,7.071054117,-2.865,-5.457958027,-0.950729095,44.99999998 +168,50.43006235,-2.575012976,49.4478,7.084483198,7.07016587,-2.89,-5.524579955,-0.85300633,44.99999998 +168.01,50.43006299,-2.575011981,49.4768,7.077530838,7.069943761,-2.914375,-5.590048118,-0.754539694,44.99999998 +168.02,50.43006362,-2.575010986,49.5061,7.067102273,7.070165744,-2.9365625,-5.654348879,-0.655415074,44.99999998 +168.03,50.43006426,-2.575009991,49.5356,7.063626101,7.071053866,-2.95625,-5.717468775,-0.555718927,44.99999998 +168.04,50.43006489,-2.575008996,49.5652,7.063626142,7.072164035,-2.975,-5.779394684,-0.455538174,44.99999998 +168.05,50.43006553,-2.575008,49.5951,7.063626191,7.072163974,-2.9934375,-5.840113599,-0.354960246,44.99999998 +168.06,50.43006616,-2.575007005,49.6251,7.063626229,7.071053682,-3.01125,-5.899612917,-0.254072748,44.99999998 +168.07,50.4300668,-2.57500601,49.6553,7.067102451,7.070165437,-3.0278125,-5.957880147,-0.152963688,44.99999998 +168.08,50.43006743,-2.575005015,49.6857,7.07753106,7.070165376,-3.0415625,-6.014903198,-0.051721244,44.99999998 +168.09,50.43006807,-2.57500402,49.7162,7.084483479,7.071053499,-3.053125,-6.070670097,0.04956635,44.99999998 +168.1,50.43006871,-2.575003025,49.7467,7.077531129,7.072163667,-3.0646875,-6.125169213,0.150810628,44.99999998 +168.11,50.43006934,-2.575002029,49.7775,7.067102588,7.072163607,-3.075,-6.178389142,0.251923469,44.99999998 +168.12,50.43006998,-2.575001034,49.8083,7.06362643,7.071053317,-3.0828125,-6.230318771,0.352816581,44.99999998 +168.13,50.43007061,-2.575000039,49.8391,7.063626468,7.070387118,-3.0903125,-6.280947327,0.453402072,44.99999998 +168.14,50.43007125,-2.574999044,49.8701,7.067102702,7.071053195,-3.0978125,-6.330264154,0.553592165,44.99999998 +168.15,50.43007188,-2.574998049,49.9011,7.077531316,7.072163365,-3.1028125,-6.378259052,0.653299541,44.99999998 +168.16,50.43007252,-2.574997053,49.9322,7.084483725,7.072163305,-3.105,-6.424921881,0.752437168,44.99999998 +168.17,50.43007316,-2.574996058,49.9632,7.077531364,7.071053015,-3.1065625,-6.470242957,0.850918701,44.99999998 +168.18,50.43007379,-2.574995063,49.9943,7.067102827,7.070164771,-3.1084375,-6.514212769,0.948658254,44.99999998 +168.19,50.43007443,-2.574994068,50.0254,7.063626681,7.069942664,-3.109375,-6.556822208,1.045570512,44.99999998 +168.2,50.43007506,-2.574993073,50.0565,7.063626714,7.070164649,-3.108125,-6.598062335,1.141571023,44.99999998 +168.21,50.4300757,-2.574992078,50.0876,7.067102928,7.071052773,-3.1046875,-6.637924556,1.236576077,44.99999998 +168.22,50.43007633,-2.574991083,50.1186,7.077531541,7.072162943,-3.1,-6.676400505,1.330502825,44.99999998 +168.23,50.43007697,-2.574990087,50.1496,7.084483976,7.072162883,-3.0946875,-6.713482162,1.423269333,44.99999998 +168.24,50.43007761,-2.574989092,50.1805,7.077531637,7.071052592,-3.0878125,-6.749161848,1.514794757,44.99999998 +168.25,50.43007824,-2.574988097,50.2114,7.067103095,7.070164348,-3.0784375,-6.783432001,1.604999284,44.99999998 +168.26,50.43007888,-2.574987102,50.2421,7.063626929,7.069942241,-3.068125,-6.816285573,1.69380419,44.99999998 +168.27,50.43007951,-2.574986107,50.2727,7.063626948,7.070164227,-3.058125,-6.847715631,1.781132068,44.99999998 +168.28,50.43008015,-2.574985112,50.3033,7.067103164,7.071052349,-3.04625,-6.877715586,1.866906772,44.99999998 +168.29,50.43008078,-2.574984117,50.3337,7.077531783,7.072162518,-3.03125,-6.906279309,1.951053474,44.99999998 +168.3,50.43008142,-2.574983121,50.3639,7.08448422,7.072162457,-3.0153125,-6.933400667,2.033498892,44.99999998 +168.31,50.43008206,-2.574982126,50.394,7.077531878,7.071052165,-2.9996875,-6.959074104,2.114171063,44.99999998 +168.32,50.43008269,-2.574981131,50.4239,7.067103325,7.07016392,-2.9828125,-6.983294233,2.192999628,44.99999998 +168.33,50.43008333,-2.574980136,50.4537,7.063627151,7.069941812,-2.9634375,-7.006055955,2.269915831,44.99999998 +168.34,50.43008396,-2.574979141,50.4832,7.063627184,7.070163797,-2.9428125,-7.027354573,2.344852695,44.99999998 +168.35,50.4300846,-2.574978146,50.5125,7.067103426,7.071051918,-2.921875,-7.047185616,2.417744787,44.99999998 +168.36,50.43008523,-2.574977151,50.5417,7.077532048,7.072162085,-2.8996875,-7.06554496,2.488528508,44.99999998 +168.37,50.43008587,-2.574976155,50.5705,7.084484466,7.072162022,-2.87625,-7.082428766,2.557142267,44.99999998 +168.38,50.43008651,-2.57497516,50.5992,7.077532106,7.071273775,-2.8515625,-7.097833481,2.623526131,44.99999998 +168.39,50.43008714,-2.574974165,50.6276,7.067103552,7.071051666,-2.824375,-7.111755897,2.687622289,44.99999998 +168.4,50.43008778,-2.57497317,50.6557,7.063627382,7.071273649,-2.7953125,-7.124193092,2.749374764,44.99999998 +168.41,50.43008841,-2.574972174,50.6835,7.063627409,7.071051539,-2.7665625,-7.135142544,2.808729754,44.99999998 +168.42,50.43008905,-2.57497118,50.711,7.063627445,7.071051474,-2.738125,-7.144601848,2.865635464,44.99999998 +168.43,50.43008968,-2.574970184,50.7383,7.063627485,7.071273456,-2.7078125,-7.152569113,2.920042333,44.99999998 +168.44,50.43009032,-2.574969189,50.7652,7.067103717,7.0708293,-2.6746875,-7.159042677,2.971902862,44.99999998 +168.45,50.43009095,-2.574968194,50.7918,7.077532328,7.070385143,-2.64,-7.164021164,3.021171847,44.99999998 +168.46,50.43009159,-2.574967199,50.818,7.084484732,7.071051215,-2.605,-7.167503545,3.067806314,44.99999998 +168.47,50.43009223,-2.574966204,50.8439,7.077532365,7.072161378,-2.57,-7.169489072,3.111765642,44.99999998 +168.48,50.43009286,-2.574965208,50.8694,7.067103818,7.072161311,-2.534375,-7.169977347,3.153011441,44.99999998 +168.49,50.4300935,-2.574964213,50.8946,7.06362766,7.071051015,-2.4965625,-7.168968254,3.19150773,44.99999998 +168.5,50.43009413,-2.574963218,50.9194,7.063627691,7.070162764,-2.4565625,-7.166462022,3.227221049,44.99999998 +168.51,50.43009477,-2.574962223,50.9437,7.067103912,7.069940651,-2.4165625,-7.162459167,3.260120114,44.99999998 +168.52,50.4300954,-2.574961228,50.9677,7.077532518,7.070162629,-2.3765625,-7.156960548,3.290176391,44.99999998 +168.53,50.43009604,-2.574960233,50.9913,7.08448493,7.071050743,-2.334375,-7.149967254,3.317363525,44.99999998 +168.54,50.43009668,-2.574959238,51.0144,7.077532571,7.072160903,-2.29,-7.141480775,3.341657852,44.99999998 +168.55,50.43009731,-2.574958242,51.0371,7.06710402,7.072160834,-2.245,-7.131502945,3.363038231,44.99999998 +168.56,50.43009795,-2.574957247,51.0593,7.063627857,7.071050535,-2.2,-7.12003571,3.381485982,44.99999998 +168.57,50.43009858,-2.574956252,51.0811,7.063627878,7.070162281,-2.155,-7.107081593,3.396985064,44.99999998 +168.58,50.43009922,-2.574955257,51.1024,7.067104082,7.069940163,-2.109375,-7.092643285,3.409521896,44.99999998 +168.59,50.43009985,-2.574954262,51.1233,7.077532685,7.070162137,-2.0615625,-7.07672371,3.419085593,44.99999998 +168.6,50.43010049,-2.574953267,51.1437,7.08448511,7.071050249,-2.0115625,-7.059326305,3.425667789,44.99999998 +168.61,50.43010113,-2.574952272,51.1635,7.077532757,7.072160405,-1.9615625,-7.040454623,3.429262698,44.99999998 +168.62,50.43010176,-2.574951276,51.1829,7.067104198,7.072160333,-1.911875,-7.020112615,3.429867283,44.99999998 +168.63,50.4301024,-2.574950281,51.2018,7.063628014,7.071272076,-1.86125,-6.998304524,3.427480971,44.99999998 +168.64,50.43010303,-2.574949286,51.2201,7.063628024,7.071049955,-1.8096875,-6.975034989,3.422105882,44.99999998 +168.65,50.43010367,-2.574948291,51.238,7.063628047,7.07104988,-1.7565625,-6.950308766,3.4137466,44.99999998 +168.66,50.4301043,-2.574947295,51.2553,7.063628073,7.070161621,-1.7015625,-6.924131069,3.402410516,44.99999998 +168.67,50.43010494,-2.574946301,51.272,7.06710429,7.0699395,-1.646875,-6.896507399,3.388107484,44.99999998 +168.68,50.43010557,-2.574945306,51.2882,7.077532893,7.071271698,-1.593125,-6.867443427,3.370849937,44.99999998 +168.69,50.43010621,-2.57494431,51.3039,7.084485292,7.071937758,-1.538125,-6.836945285,3.350653003,44.99999998 +168.7,50.43010685,-2.574943315,51.319,7.077532911,7.071271542,-1.48125,-6.805019332,3.327534214,44.99999998 +168.71,50.43010748,-2.57494232,51.3335,7.067104348,7.071271463,-1.4234375,-6.771672271,3.301513794,44.99999998 +168.72,50.43010812,-2.574941325,51.3475,7.06710438,7.072159567,-1.365,-6.736911036,3.272614375,44.99999998 +168.73,50.43010875,-2.574940329,51.3608,7.077532986,7.072159488,-1.3065625,-6.700742846,3.240861226,44.99999998 +168.74,50.43010939,-2.574939334,51.3736,7.084485385,7.071049178,-1.2484375,-6.663175322,3.206281963,44.99999998 +168.75,50.43011003,-2.574938339,51.3858,7.077533,7.070160914,-1.1896875,-6.624216254,3.16890678,44.99999998 +168.76,50.43011066,-2.574937344,51.3974,7.067104423,7.069938786,-1.13,-6.58387378,3.128768279,44.99999998 +168.77,50.4301113,-2.574936349,51.4084,7.063628245,7.070160749,-1.07,-6.542156437,3.085901468,44.99999998 +168.78,50.43011193,-2.574935354,51.4188,7.063628264,7.07104885,-1.0096875,-6.499072761,3.040343645,44.99999998 +168.79,50.43011257,-2.574934359,51.4286,7.063628278,7.072158995,-0.9484375,-6.454631862,2.992134632,44.99999998 +168.8,50.4301132,-2.574933363,51.4378,7.063628291,7.07215891,-0.8865625,-6.408843023,2.941316427,44.99999998 +168.81,50.43011384,-2.574932368,51.4463,7.067104501,7.071048596,-0.825,-6.361715755,2.887933377,44.99999998 +168.82,50.43011447,-2.574931373,51.4543,7.077533092,7.070160327,-0.763125,-6.313259912,2.832031947,44.99999998 +168.83,50.43011511,-2.574930378,51.4616,7.084485476,7.069938194,-0.6996875,-6.263485636,2.773661012,44.99999998 +168.84,50.43011575,-2.574929383,51.4683,7.077533087,7.070160153,-0.6353125,-6.212403355,2.712871336,44.99999998 +168.85,50.43011638,-2.574928388,51.4743,7.067104519,7.071048248,-0.5715625,-6.16002361,2.649716032,44.99999998 +168.86,50.43011702,-2.574927393,51.4797,7.063628346,7.072158388,-0.5084375,-6.106357461,2.584250161,44.99999998 +168.87,50.43011765,-2.574926397,51.4845,7.063628357,7.072158299,-0.445,-6.05141608,2.516530732,44.99999998 +168.88,50.43011829,-2.574925402,51.4886,7.067104544,7.071270025,-0.3815625,-5.995210983,2.446616875,44.99999998 +168.89,50.43011892,-2.574924407,51.4921,7.077533118,7.071269935,-0.3184375,-5.937753801,2.374569552,44.99999998 +168.9,50.43011956,-2.574923412,51.495,7.084485512,7.07193598,-0.2546875,-5.879056624,2.300451502,44.99999998 +168.91,50.4301202,-2.574922416,51.4972,7.077533142,7.071269751,-0.19,-5.819131656,2.22432747,44.99999998 +168.92,50.43012083,-2.574921421,51.4988,7.067104572,7.069937384,-0.125,-5.757991444,2.146263804,44.99999998 +168.93,50.43012147,-2.574920427,51.4997,7.063628374,7.070159336,-0.06,-5.695648766,2.066328571,44.99999998 +168.94,50.4301221,-2.574919431,51.5,7.063628359,7.071047425,0.0046875,-5.632116627,1.984591444,44.99999998 +168.95,50.43012274,-2.574918436,51.4996,7.067104544,7.071047329,0.0684375,-5.567408321,1.901123754,44.99999998 +168.96,50.43012337,-2.574917441,51.4986,7.077533137,7.071269279,0.131875,-5.501537254,1.815998211,44.99999998 +168.97,50.43012401,-2.574916446,51.497,7.084485542,7.072157366,0.1965625,-5.434517292,1.729289128,44.99999998 +168.98,50.43012465,-2.57491545,51.4947,7.077533154,7.072157269,0.2615625,-5.366362415,1.641072019,44.99999998 +168.99,50.43012528,-2.574914455,51.4917,7.067104559,7.071046942,0.325,-5.29708689,1.551423949,44.99999998 +169,50.43012592,-2.57491346,51.4882,7.063628351,7.070158661,0.3884375,-5.226705041,1.460422953,44.99999998 +169.01,50.43012655,-2.574912465,51.484,7.063628343,7.069936516,0.4534375,-5.155231708,1.368148501,44.99999998 +169.02,50.43012719,-2.57491147,51.4791,7.063628343,7.070158461,0.518125,-5.082681786,1.274680979,44.99999998 +169.03,50.43012782,-2.574910475,51.4736,7.063628344,7.071046543,0.5815625,-5.009070403,1.180101919,44.99999998 +169.04,50.43012846,-2.57490948,51.4675,7.067104535,7.07215667,0.645,-4.934412914,1.08449377,44.99999998 +169.05,50.43012909,-2.574908484,51.4607,7.077533115,7.072156568,0.708125,-4.85872496,0.987939953,44.99999998 +169.06,50.43012973,-2.574907489,51.4533,7.084485496,7.071046236,0.7696875,-4.782022298,0.890524638,44.99999998 +169.07,50.43013037,-2.574906494,51.4453,7.077533091,7.07015795,0.8303125,-4.704321027,0.792332735,44.99999998 +169.08,50.430131,-2.574905499,51.4367,7.067104491,7.069935801,0.891875,-4.625637249,0.693449903,44.99999998 +169.09,50.43013164,-2.574904504,51.4275,7.063628291,7.070157742,0.955,-4.545987521,0.593962428,44.99999998 +169.1,50.43013227,-2.574903509,51.4176,7.063628289,7.071045819,1.0178125,-4.465388402,0.493956999,44.99999998 +169.11,50.43013291,-2.574902514,51.4071,7.067104481,7.072155941,1.078125,-4.383856737,0.393520821,44.99999998 +169.12,50.43013354,-2.574901518,51.396,7.077533051,7.072155834,1.136875,-4.301409543,0.292741441,44.99999998 +169.13,50.43013418,-2.574900523,51.3844,7.084485414,7.071267544,1.1965625,-4.218064065,0.191706865,44.99999998 +169.14,50.43013482,-2.574899528,51.3721,7.077533004,7.071267435,1.2565625,-4.133837722,0.090505044,44.99999998 +169.15,50.43013545,-2.574898533,51.3592,7.067104415,7.071933464,1.3146875,-4.048748047,-0.010775617,44.99999998 +169.16,50.43013609,-2.574897537,51.3458,7.063628221,7.071267217,1.371875,-3.962812915,-0.112046939,44.99999998 +169.17,50.43013672,-2.574896542,51.3318,7.063628213,7.069934832,1.43,-3.876050145,-0.213220571,44.99999998 +169.18,50.43013736,-2.574895548,51.3172,7.067104386,7.070156767,1.488125,-3.7884779,-0.314208221,44.99999998 +169.19,50.43013799,-2.574894552,51.302,7.077532941,7.071044838,1.5446875,-3.700114458,-0.414921883,44.99999998 +169.2,50.43013863,-2.574893557,51.2863,7.084485302,7.071044727,1.6,-3.610978383,-0.515273779,44.99999998 +169.21,50.43013927,-2.574892562,51.27,7.077532894,7.07126666,1.655,-3.521088123,-0.615176305,44.99999998 +169.22,50.4301399,-2.574891567,51.2532,7.067104303,7.072154729,1.7096875,-3.430462529,-0.71454237,44.99999998 +169.23,50.43014054,-2.574890571,51.2358,7.063628103,7.072154615,1.763125,-3.339120566,-0.813285401,44.99999998 +169.24,50.43014117,-2.574889576,51.2179,7.063628081,7.071044272,1.8146875,-3.247081256,-0.911319224,44.99999998 +169.25,50.43014181,-2.574888581,51.1995,7.063628048,7.070155975,1.8653125,-3.154363851,-1.008558298,44.99999998 +169.26,50.43014244,-2.574887586,51.1806,7.063628028,7.069933814,1.9165625,-3.060987658,-1.104917939,44.99999998 +169.27,50.43014308,-2.574886591,51.1612,7.067104216,7.070155744,1.968125,-2.966972274,-1.200314094,44.99999998 +169.28,50.43014371,-2.574885596,51.1412,7.077532785,7.071043809,2.018125,-2.872337236,-1.294663513,44.99999998 +169.29,50.43014435,-2.574884601,51.1208,7.084485149,7.07215392,2.06625,-2.777102369,-1.387884032,44.99999998 +169.3,50.43014499,-2.574883605,51.0999,7.077532734,7.072153802,2.1134375,-2.681287496,-1.479894236,44.99999998 +169.31,50.43014562,-2.57488261,51.0785,7.067104123,7.071265501,2.16,-2.584912729,-1.570613967,44.99999998 +169.32,50.43014626,-2.574881615,51.0567,7.067104093,7.071043336,2.2065625,-2.487998064,-1.659964099,44.99999998 +169.33,50.43014689,-2.57488062,51.0344,7.07753265,7.071043217,2.253125,-2.390563898,-1.747866711,44.99999998 +169.34,50.43014753,-2.574879624,51.0116,7.08448502,7.070154915,2.2978125,-2.292630457,-1.834245198,44.99999998 +169.35,50.43014817,-2.57487863,50.9884,7.077532614,7.069932748,2.3396875,-2.194218194,-1.919024159,44.99999998 +169.36,50.4301488,-2.574877635,50.9648,7.06710401,7.071264901,2.38,-2.095347738,-2.002129682,44.99999998 +169.37,50.43014944,-2.574876639,50.9408,7.063627784,7.071930917,2.42,-1.996039656,-2.083489345,44.99999998 +169.38,50.43015007,-2.574875644,50.9164,7.063627743,7.071264659,2.46,-1.896314748,-2.163032159,44.99999998 +169.39,50.43015071,-2.574874649,50.8916,7.063627709,7.071264537,2.5,-1.796193868,-2.240688796,44.99999998 +169.4,50.43015134,-2.574873654,50.8664,7.063627691,7.071930551,2.539375,-1.695697816,-2.316391532,44.99999998 +169.41,50.43015198,-2.574872658,50.8408,7.067103867,7.071264292,2.5765625,-1.594847675,-2.390074306,44.99999998 +169.42,50.43015261,-2.574871663,50.8148,7.077532427,7.069931895,2.61125,-1.493664417,-2.461672945,44.99999998 +169.43,50.43015325,-2.574870669,50.7886,7.084484786,7.070153816,2.645,-1.392169241,-2.531124941,44.99999998 +169.44,50.43015389,-2.574869673,50.7619,7.077532361,7.071041874,2.6784375,-1.290383346,-2.598369732,44.99999998 +169.45,50.43015452,-2.574868678,50.735,7.067103742,7.07104175,2.7109375,-1.188327989,-2.663348761,44.99999998 +169.46,50.43015516,-2.574867683,50.7077,7.063627522,7.071263671,2.741875,-1.086024484,-2.726005248,44.99999998 +169.47,50.43015579,-2.574866688,50.6801,7.063627501,7.072151728,2.77125,-0.983494145,-2.786284648,44.99999998 +169.48,50.43015643,-2.574865692,50.6523,7.067103673,7.072151602,2.7996875,-0.8807584,-2.844134363,44.99999998 +169.49,50.43015706,-2.574864697,50.6241,7.077532223,7.071041249,2.826875,-0.777838736,-2.899503973,44.99999998 +169.5,50.4301577,-2.574863702,50.5957,7.084484566,7.070152941,2.8528125,-0.674756582,-2.952345177,44.99999998 +169.51,50.43015834,-2.574862707,50.5671,7.077532139,7.069930768,2.8784375,-0.571533594,-3.002611853,44.99999998 +169.52,50.43015897,-2.574861712,50.5381,7.067103534,7.070152687,2.9028125,-0.468191202,-3.050260227,44.99999998 +169.53,50.43015961,-2.574860717,50.509,7.063627323,7.071040743,2.9246875,-0.364751063,-3.095248701,44.99999998 +169.54,50.43016024,-2.574859722,50.4796,7.063627295,7.072150843,2.945,-0.261234721,-3.137538086,44.99999998 +169.55,50.43016088,-2.574858726,50.4501,7.067103445,7.072150716,2.965,-0.157663833,-3.177091539,44.99999998 +169.56,50.43016151,-2.574857731,50.4203,7.07753198,7.071040361,2.9846875,-0.05406,-3.213874456,44.99999998 +169.57,50.43016215,-2.574856736,50.3904,7.084484337,7.07015205,3.0028125,0.049555062,-3.247854864,44.99999998 +169.58,50.43016279,-2.574855741,50.3602,7.077531932,7.069929876,3.0184375,0.153159869,-3.279003084,44.99999998 +169.59,50.43016342,-2.574854746,50.33,7.067103328,7.070151794,3.0328125,0.25673259,-3.307291958,44.99999998 +169.6,50.43016406,-2.574853751,50.2996,7.063627096,7.071039848,3.046875,0.36025174,-3.33269685,44.99999998 +169.61,50.43016469,-2.574852756,50.269,7.063627048,7.072149948,3.059375,0.46369566,-3.355195585,44.99999998 +169.62,50.43016533,-2.57485176,50.2384,7.063627003,7.072149819,3.0696875,0.567042751,-3.37476851,44.99999998 +169.63,50.43016596,-2.574850765,50.2076,7.063626977,7.071039463,3.0784375,0.670271411,-3.391398553,44.99999998 +169.64,50.4301666,-2.57484977,50.1768,7.067103154,7.070373198,3.0865625,0.773360097,-3.405071332,44.99999998 +169.65,50.43016723,-2.574848775,50.1459,7.077531709,7.071039206,3.0946875,0.876287267,-3.415774756,44.99999998 +169.66,50.43016787,-2.57484778,50.1149,7.084484058,7.072149304,3.10125,0.979031434,-3.423499602,44.99999998 +169.67,50.43016851,-2.574846784,50.0838,7.077531626,7.072149174,3.1046875,1.081571169,-3.428239109,44.99999998 +169.68,50.43016914,-2.574845789,50.0528,7.067103004,7.071038818,3.1065625,1.183885045,-3.429989151,44.99999998 +169.69,50.43016978,-2.574844794,50.0217,7.06362678,7.070150506,3.1084375,1.285951632,-3.428748182,44.99999998 +169.7,50.43017041,-2.574843799,49.9906,7.063626753,7.070150378,3.109375,1.387749674,-3.42451729,44.99999998 +169.71,50.43017105,-2.574842804,49.9595,7.067102916,7.071038431,3.1084375,1.489257913,-3.417300199,44.99999998 +169.72,50.43017168,-2.574841809,49.9284,7.077531468,7.07214853,3.10625,1.590455152,-3.407103154,44.99999998 +169.73,50.43017232,-2.574840813,49.8974,7.084483828,7.0721484,3.103125,1.691320246,-3.393935037,44.99999998 +169.74,50.43017296,-2.574839818,49.8663,7.077531401,7.071038044,3.098125,1.791832112,-3.377807421,44.99999998 +169.75,50.43017359,-2.574838823,49.8354,7.067102768,7.070149733,3.09125,1.891969779,-3.358734229,44.99999998 +169.76,50.43017423,-2.574837828,49.8045,7.063626534,7.069927559,3.083125,1.991712335,-3.336732192,44.99999998 +169.77,50.43017486,-2.574836833,49.7737,7.063626511,7.070149475,3.073125,2.091038923,-3.311820502,44.99999998 +169.78,50.4301755,-2.574835838,49.743,7.067102686,7.071037529,3.0615625,2.18992886,-3.284020877,44.99999998 +169.79,50.43017613,-2.574834843,49.7125,7.077531234,7.072147627,3.05,2.288361463,-3.253357493,44.99999998 +169.8,50.43017677,-2.574833847,49.682,7.084483574,7.072147499,3.038125,2.386316161,-3.219857109,44.99999998 +169.81,50.43017741,-2.574832852,49.6517,7.077531146,7.071037143,3.0246875,2.4837725,-3.183549003,44.99999998 +169.82,50.43017804,-2.574831857,49.6215,7.067102541,7.070370879,3.0096875,2.580710084,-3.144464802,44.99999998 +169.83,50.43017868,-2.574830862,49.5915,7.06362633,7.070814843,2.993125,2.6771088,-3.102638539,44.99999998 +169.84,50.43017931,-2.574829867,49.5616,7.063626304,7.071258806,2.9746875,2.772948425,-3.058106769,44.99999998 +169.85,50.43017995,-2.574828871,49.532,7.067102459,7.071036633,2.9546875,2.868208903,-3.010908282,44.99999998 +169.86,50.43018058,-2.574827877,49.5025,7.077530995,7.071036505,2.9334375,2.962870412,-2.961084216,44.99999998 +169.87,50.43018122,-2.574826881,49.4733,7.084483341,7.071258423,2.91125,3.056913184,-2.908678058,44.99999998 +169.88,50.43018186,-2.574825886,49.4443,7.077530928,7.070814206,2.888125,3.150317565,-2.853735474,44.99999998 +169.89,50.43018249,-2.574824891,49.4155,7.067102329,7.070369989,2.863125,3.24306402,-2.796304419,44.99999998 +169.9,50.43018313,-2.574823896,49.387,7.063626108,7.071035999,2.8365625,3.335133238,-2.736434913,44.99999998 +169.91,50.43018376,-2.574822901,49.3588,7.063626071,7.0721461,2.81,3.426505912,-2.67417921,44.99999998 +169.92,50.4301844,-2.574821905,49.3308,7.067102226,7.072145974,2.783125,3.517163018,-2.609591568,44.99999998 +169.93,50.43018503,-2.57482091,49.3031,7.077530775,7.071035622,2.754375,3.60708565,-2.542728368,44.99999998 +169.94,50.43018567,-2.574819915,49.2757,7.084483138,7.070147316,2.723125,3.696254957,-2.47364782,44.99999998 +169.95,50.43018631,-2.57481892,49.2486,7.077530727,7.069925145,2.69,3.784652318,-2.402410259,44.99999998 +169.96,50.43018694,-2.574817925,49.2219,7.067102118,7.070147066,2.6565625,3.872259341,-2.329077734,44.99999998 +169.97,50.43018758,-2.57481693,49.1955,7.063625895,7.071035124,2.6234375,3.959057692,-2.253714189,44.99999998 +169.98,50.43018821,-2.574815935,49.1694,7.063625865,7.072145228,2.589375,4.045029207,-2.176385399,44.99999998 +169.99,50.43018885,-2.574814939,49.1437,7.06362583,7.072145105,2.553125,4.13015601,-2.0971588,44.99999998 +170,50.43018948,-2.574813944,49.1183,7.063625799,7.071034755,2.515,4.214420283,-2.016103435,44.99999998 +170.01,50.43019012,-2.574812949,49.0934,7.06710197,7.070146452,2.4765625,4.297804378,-1.933289949,44.99999998 +170.02,50.43019075,-2.574811954,49.0688,7.077530535,7.07014633,2.438125,4.380290992,-1.848790649,44.99999998 +170.03,50.43019139,-2.574810959,49.0446,7.084482904,7.071034389,2.3978125,4.461862821,-1.76267916,44.99999998 +170.04,50.43019203,-2.574809964,49.0208,7.077530486,7.072144495,2.355,4.542502792,-1.675030598,44.99999998 +170.05,50.43019266,-2.574808968,48.9975,7.067101863,7.072144375,2.3115625,4.622194174,-1.585921394,44.99999998 +170.06,50.4301933,-2.574807973,48.9746,7.063625637,7.071034028,2.2684375,4.700920294,-1.495429242,44.99999998 +170.07,50.43019393,-2.574806978,48.9521,7.063625624,7.070367772,2.2246875,4.778664651,-1.403633038,44.99999998 +170.08,50.43019457,-2.574805983,48.9301,7.06710181,7.070811744,2.1796875,4.855411029,-1.310612824,44.99999998 +170.09,50.4301952,-2.574804988,48.9085,7.077530374,7.071255716,2.1334375,4.931143445,-1.216449789,44.99999998 +170.1,50.43019584,-2.574803992,48.8874,7.084482726,7.071033553,2.08625,5.005846026,-1.121225922,44.99999998 +170.11,50.43019648,-2.574802998,48.8668,7.077530298,7.071033435,2.038125,5.079503246,-1.025024418,44.99999998 +170.12,50.43019711,-2.574802002,48.8466,7.067101694,7.071255364,1.988125,5.152099634,-0.927928984,44.99999998 +170.13,50.43019775,-2.574801007,48.827,7.063625497,7.070811157,1.9365625,5.223620122,-0.83002442,44.99999998 +170.14,50.43019838,-2.574800012,48.8079,7.06362549,7.07036695,1.8853125,5.294049698,-0.731396095,44.99999998 +170.15,50.43019902,-2.574799017,48.7893,7.06710166,7.071032971,1.835,5.363373638,-0.632129954,44.99999998 +170.16,50.43019965,-2.574798022,48.7712,7.077530207,7.072143083,1.784375,5.43157756,-0.53231257,44.99999998 +170.17,50.43020029,-2.574797026,48.7536,7.084482563,7.072142969,1.7315625,5.49864714,-0.432031033,44.99999998 +170.18,50.43020093,-2.574796031,48.7365,7.077530157,7.071032629,1.6765625,5.564568398,-0.331372776,44.99999998 +170.19,50.43020156,-2.574795036,48.7201,7.06710157,7.070144334,1.6215625,5.629327583,-0.23042552,44.99999998 +170.2,50.4302022,-2.574794041,48.7041,7.063625375,7.069922177,1.5665625,5.692911173,-0.129277327,44.99999998 +170.21,50.43020283,-2.574793046,48.6887,7.063625363,7.07014411,1.5096875,5.755305819,-0.028016433,44.99999998 +170.22,50.43020347,-2.574792051,48.6739,7.063625337,7.07103218,1.451875,5.816498571,0.073268926,44.99999998 +170.23,50.4302041,-2.574791056,48.6597,7.063625311,7.072142297,1.395,5.876476652,0.1744904,44.99999998 +170.24,50.43020474,-2.57479006,48.646,7.067101492,7.072142188,1.338125,5.935227458,0.275559697,44.99999998 +170.25,50.43020537,-2.574789065,48.6329,7.077530067,7.071031852,1.2796875,5.992738784,0.376388695,44.99999998 +170.26,50.43020601,-2.57478807,48.6204,7.084482444,7.070143562,1.22,6.048998599,0.476889446,44.99999998 +170.27,50.43020665,-2.574787075,48.6085,7.077530046,7.069921409,1.16,6.103995156,0.576974401,44.99999998 +170.28,50.43020728,-2.57478608,48.5972,7.067101457,7.070143347,1.1,6.157716997,0.676556185,44.99999998 +170.29,50.43020792,-2.574785085,48.5865,7.063625247,7.071031421,1.04,6.210152834,0.775548051,44.99999998 +170.3,50.43020855,-2.57478409,48.5764,7.063625221,7.072141542,0.98,6.261291781,0.873863598,44.99999998 +170.31,50.43020919,-2.574783094,48.5669,7.067101399,7.072141437,0.9196875,6.311123181,0.971417111,44.99999998 +170.32,50.43020982,-2.574782099,48.558,7.077529983,7.071253151,0.858125,6.359636548,1.068123563,44.99999998 +170.33,50.43021046,-2.574781104,48.5497,7.084482377,7.071253047,0.795,6.406821743,1.163898558,44.99999998 +170.34,50.4302111,-2.574780109,48.5421,7.077529986,7.072141125,0.7315625,6.452669023,1.258658616,44.99999998 +170.35,50.43021173,-2.574779113,48.5351,7.067101384,7.072141023,0.6684375,6.497168707,1.352321172,44.99999998 +170.36,50.43021237,-2.574778118,48.5287,7.063625167,7.071030695,0.605,6.54031157,1.44480441,44.99999998 +170.37,50.430213,-2.574777123,48.523,7.063625159,7.070142412,0.5415625,6.582088558,1.536027771,44.99999998 +170.38,50.43021364,-2.574776128,48.5179,7.067101359,7.069920267,0.4784375,6.622490906,1.625911728,44.99999998 +170.39,50.43021427,-2.574775133,48.5134,7.077529947,7.070142213,0.415,6.661510306,1.714377844,44.99999998 +170.4,50.43021491,-2.574774138,48.5096,7.084482338,7.071030295,0.3515625,6.699138507,1.801348998,44.99999998 +170.41,50.43021555,-2.574773143,48.5064,7.077529943,7.072140423,0.288125,6.735367717,1.886749332,44.99999998 +170.42,50.43021618,-2.574772147,48.5038,7.067101344,7.072140325,0.223125,6.770190259,1.970504417,44.99999998 +170.43,50.43021682,-2.574771152,48.5019,7.063625142,7.071030002,0.156875,6.803598969,2.052541144,44.99999998 +170.44,50.43021745,-2.574770157,48.5007,7.063625153,7.070141725,0.091875,6.835586859,2.132788066,44.99999998 +170.45,50.43021809,-2.574769162,48.5001,7.067101362,7.069919585,0.0284375,6.866147225,2.211175167,44.99999998 +170.46,50.43021872,-2.574768167,48.5001,7.077529949,7.070141536,-0.0353125,6.895273649,2.287634093,44.99999998 +170.47,50.43021936,-2.574767172,48.5008,7.084482325,7.071029623,-0.1,6.922960058,2.362098152,44.99999998 +170.48,50.43022,-2.574766177,48.5021,7.077529922,7.072139755,-0.1646875,6.94920078,2.434502484,44.99999998 +170.49,50.43022063,-2.574765181,48.5041,7.067101343,7.072139662,-0.2284375,6.9739902,2.504783837,44.99999998 +170.5,50.43022127,-2.574764186,48.5067,7.063625171,7.07125139,-0.2915625,6.997323162,2.572880959,44.99999998 +170.51,50.4302219,-2.574763191,48.5099,7.063625188,7.071029253,-0.3553125,7.019194852,2.638734551,44.99999998 +170.52,50.43022254,-2.574762196,48.5138,7.067101383,7.071029163,-0.42,7.039600686,2.702287087,44.99999998 +170.53,50.43022317,-2.5747612,48.5183,7.077529955,7.070140893,-0.4846875,7.058536426,2.763483162,44.99999998 +170.54,50.43022381,-2.574760206,48.5235,7.084482338,7.069918759,-0.5484375,7.075998002,2.822269491,44.99999998 +170.55,50.43022445,-2.574759211,48.5293,7.077529964,7.071250942,-0.6115625,7.091981863,2.878594738,44.99999998 +170.56,50.43022508,-2.574758215,48.5357,7.067101406,7.07191699,-0.675,7.106484685,2.932409856,44.99999998 +170.57,50.43022572,-2.57475722,48.5428,7.063625225,7.071250767,-0.738125,7.119503432,2.983667806,44.99999998 +170.58,50.43022635,-2.574756225,48.5505,7.063625228,7.071250681,-0.7996875,7.131035297,3.032323955,44.99999998 +170.59,50.43022699,-2.57475523,48.5588,7.063625229,7.072138776,-0.8603125,7.141077986,3.078335904,44.99999998 +170.6,50.43022762,-2.574754234,48.5677,7.063625235,7.072138692,-0.921875,7.149629324,3.121663488,44.99999998 +170.61,50.43022826,-2.574753239,48.5772,7.067101445,7.071028382,-0.9846875,7.156687534,3.162268949,44.99999998 +170.62,50.43022889,-2.574752244,48.5874,7.077530045,7.070140117,-1.0465625,7.162251183,3.200116822,44.99999998 +170.63,50.43022953,-2.574751249,48.5982,7.084482448,7.069917989,-1.1065625,7.166319126,3.235174162,44.99999998 +170.64,50.43023017,-2.574750254,48.6095,7.077530076,7.070139953,-1.1665625,7.168890446,3.267410372,44.99999998 +170.65,50.4302308,-2.574749259,48.6215,7.067101512,7.071028052,-1.2265625,7.169964627,3.296797377,44.99999998 +170.66,50.43023144,-2.574748264,48.6341,7.063625329,7.072138197,-1.2846875,7.169541441,3.323309567,44.99999998 +170.67,50.43023207,-2.574747268,48.6472,7.063625329,7.072138117,-1.341875,7.167621001,3.346923678,44.99999998 +170.68,50.43023271,-2.574746273,48.6609,7.067101532,7.071249857,-1.4,7.164203709,3.367619315,44.99999998 +170.69,50.43023334,-2.574745278,48.6752,7.077530141,7.071027733,-1.458125,7.159290252,3.385378314,44.99999998 +170.7,50.43023398,-2.574744283,48.6901,7.08448256,7.071027654,-1.515,7.152881662,3.400185147,44.99999998 +170.71,50.43023462,-2.574743287,48.7055,7.077530188,7.070139395,-1.5715625,7.144979313,3.412027039,44.99999998 +170.72,50.43023525,-2.574742293,48.7215,7.067101609,7.069917273,-1.628125,7.135584811,3.420893561,44.99999998 +170.73,50.43023589,-2.574741298,48.7381,7.063625427,7.071249468,-1.6828125,7.124700102,3.426777035,44.99999998 +170.74,50.43023652,-2.574740302,48.7552,7.063625458,7.071915528,-1.735,7.112327537,3.429672306,44.99999998 +170.75,50.43023716,-2.574739307,48.7728,7.067101688,7.071249318,-1.786875,7.098469636,3.429576851,44.99999998 +170.76,50.43023779,-2.574738312,48.7909,7.077530297,7.071249244,-1.8396875,7.083129321,3.426490728,44.99999998 +170.77,50.43023843,-2.574737317,48.8096,7.0844827,7.071915304,-1.8915625,7.066309744,3.420416688,44.99999998 +170.78,50.43023907,-2.574736321,48.8288,7.077530319,7.071249095,-1.9415625,7.048014514,3.411360002,44.99999998 +170.79,50.4302397,-2.574735326,48.8484,7.067101748,7.069916751,-1.9915625,7.028247356,3.399328518,44.99999998 +170.8,50.43024034,-2.574734332,48.8686,7.063625584,7.070138724,-2.0415625,7.007012451,3.38433278,44.99999998 +170.81,50.43024097,-2.574733336,48.8893,7.063625623,7.071026833,-2.0896875,6.984314212,3.366385851,44.99999998 +170.82,50.43024161,-2.574732341,48.9104,7.067101844,7.071026762,-2.1365625,6.960157395,3.345503431,44.99999998 +170.83,50.43024224,-2.574731346,48.932,7.077530437,7.071248736,-2.1834375,6.934547041,3.321703623,44.99999998 +170.84,50.43024288,-2.574730351,48.9541,7.08448284,7.072136846,-2.2296875,6.907488536,3.295007285,44.99999998 +170.85,50.43024352,-2.574729355,48.9766,7.077530484,7.072136776,-2.2746875,6.878987438,3.265437621,44.99999998 +170.86,50.43024415,-2.57472836,48.9996,7.067101943,7.071026482,-2.318125,6.849049763,3.233020471,44.99999998 +170.87,50.43024479,-2.574727365,49.023,7.06362578,7.070138233,-2.3596875,6.817681756,3.197784025,44.99999998 +170.88,50.43024542,-2.57472637,49.0468,7.063625803,7.069916119,-2.4,6.784889949,3.159759108,44.99999998 +170.89,50.43024606,-2.574725375,49.071,7.067102023,7.070138096,-2.44,6.750681218,3.118978837,44.99999998 +170.9,50.43024669,-2.57472438,49.0956,7.077530631,7.071026209,-2.4796875,6.715062666,3.075478735,44.99999998 +170.91,50.43024733,-2.574723385,49.1206,7.084483041,7.072136367,-2.5184375,6.6780418,3.02929679,44.99999998 +170.92,50.43024797,-2.574722389,49.146,7.077530677,7.072136301,-2.55625,6.639626298,2.98047328,44.99999998 +170.93,50.4302486,-2.574721394,49.1717,7.067102129,7.071248055,-2.593125,6.59982418,2.929050719,44.99999998 +170.94,50.43024924,-2.574720399,49.1979,7.063625973,7.071247989,-2.628125,6.558643813,2.875074026,44.99999998 +170.95,50.43024987,-2.574719404,49.2243,7.06362601,7.071914058,-2.66125,6.516093732,2.818590185,44.99999998 +170.96,50.43025051,-2.574718408,49.2511,7.063626036,7.071247858,-2.6934375,6.47218282,2.75964847,44.99999998 +170.97,50.43025114,-2.574717413,49.2782,7.063626051,7.069915523,-2.7246875,6.4269203,2.698300332,44.99999998 +170.98,50.43025178,-2.574716419,49.3056,7.06710227,7.070137504,-2.755,6.380315627,2.634599285,44.99999998 +170.99,50.43025241,-2.574715423,49.3333,7.077530895,7.07102562,-2.7846875,6.332378482,2.568600735,44.99999998 +171,50.43025305,-2.574714428,49.3613,7.084483331,7.071025556,-2.813125,6.283118894,2.500362379,44.99999998 +171.01,50.43025369,-2.574713433,49.3896,7.077530979,7.071247538,-2.84,6.232547176,2.429943688,44.99999998 +171.02,50.43025432,-2.574712438,49.4181,7.067102415,7.072135655,-2.86625,6.180673869,2.357406028,44.99999998 +171.03,50.43025496,-2.574711442,49.4469,7.063626236,7.072135592,-2.8915625,6.127509802,2.282812653,44.99999998 +171.04,50.43025559,-2.574710447,49.476,7.063626269,7.071025305,-2.914375,6.073066035,2.20622865,44.99999998 +171.05,50.43025623,-2.574709452,49.5052,7.067102514,7.070137063,-2.935,6.017354025,2.12772077,44.99999998 +171.06,50.43025686,-2.574708457,49.5347,7.077531144,7.069914955,-2.955,5.960385405,2.04735748,44.99999998 +171.07,50.4302575,-2.574707462,49.5643,7.084483562,7.070136938,-2.9746875,5.902171976,1.965208912,44.99999998 +171.08,50.43025814,-2.574706467,49.5942,7.077531192,7.071025057,-2.9934375,5.842726,1.881346626,44.99999998 +171.09,50.43025877,-2.574705472,49.6242,7.067102631,7.072135221,-3.0109375,5.782059797,1.795843791,44.99999998 +171.1,50.43025941,-2.574704476,49.6544,7.063626478,7.072135159,-3.0265625,5.720186142,1.70877489,44.99999998 +171.11,50.43026004,-2.574703481,49.6848,7.063626528,7.071024873,-3.0396875,5.65711787,1.620215955,44.99999998 +171.12,50.43026068,-2.574702486,49.7152,7.067102761,7.070136632,-3.0515625,5.592868159,1.53024422,44.99999998 +171.13,50.43026131,-2.574701491,49.7458,7.077531373,7.069914526,-3.0634375,5.527450473,1.43893801,44.99999998 +171.14,50.43026195,-2.574700496,49.7765,7.084483786,7.07013651,-3.0746875,5.46087845,1.346377079,44.99999998 +171.15,50.43026259,-2.574699501,49.8073,7.077531421,7.07102463,-3.0846875,5.393166011,1.252642043,44.99999998 +171.16,50.43026322,-2.574698506,49.8382,7.067102874,7.072134795,-3.0928125,5.324327252,1.15781472,44.99999998 +171.17,50.43026386,-2.57469751,49.8692,7.063626732,7.072134734,-3.098125,5.254376554,1.061977732,44.99999998 +171.18,50.43026449,-2.574696515,49.9002,7.063626781,7.071024448,-3.1015625,5.183328584,0.965214728,44.99999998 +171.19,50.43026513,-2.57469552,49.9312,7.063626816,7.070358253,-3.105,5.111198125,0.867609993,44.99999998 +171.2,50.43026576,-2.574694525,49.9623,7.063626849,7.071024328,-3.108125,5.038000303,0.769248724,44.99999998 +171.21,50.4302664,-2.57469353,49.9934,7.067103072,7.072134493,-3.1096875,4.963750301,0.670216636,44.99999998 +171.22,50.43026703,-2.574692534,50.0245,7.077531676,7.072134433,-3.1096875,4.888463704,0.570600131,44.99999998 +171.23,50.43026767,-2.574691539,50.0556,7.084484094,7.071024147,-3.108125,4.812156211,0.470486012,44.99999998 +171.24,50.43026831,-2.574690544,50.0867,7.077531751,7.070135906,-3.1046875,4.73484375,0.369961656,44.99999998 +171.25,50.43026894,-2.574689549,50.1177,7.067103215,7.069913801,-3.0996875,4.656542478,0.269114724,44.99999998 +171.26,50.43026958,-2.574688554,50.1487,7.063627053,7.070135785,-3.0934375,4.577268782,0.168033051,44.99999998 +171.27,50.43027021,-2.574687559,50.1796,7.063627073,7.071023906,-3.08625,4.497039164,0.066804874,44.99999998 +171.28,50.43027085,-2.574686564,50.2104,7.067103296,7.07213407,-3.078125,4.41587041,-0.034481517,44.99999998 +171.29,50.43027148,-2.574685568,50.2412,7.077531927,7.072134009,-3.068125,4.333779424,-0.135737884,44.99999998 +171.3,50.43027212,-2.574684573,50.2718,7.084484366,7.071023724,-3.0565625,4.250783393,-0.236875879,44.99999998 +171.31,50.43027276,-2.574683578,50.3023,7.077532018,7.070135483,-3.045,4.166899679,-0.337807322,44.99999998 +171.32,50.43027339,-2.574682583,50.3327,7.067103461,7.070135422,-3.0328125,4.082145699,-0.438444207,44.99999998 +171.33,50.43027403,-2.574681588,50.363,7.063627285,7.07102354,-3.018125,3.996539273,-0.538698701,44.99999998 +171.34,50.43027466,-2.574680593,50.3931,7.063627306,7.072133704,-3.00125,3.910098162,-0.638483483,44.99999998 +171.35,50.4302753,-2.574679597,50.423,7.067103535,7.072133642,-2.9834375,3.822840528,-0.737711465,44.99999998 +171.36,50.43027593,-2.574678602,50.4528,7.077532167,7.071023355,-2.9646875,3.734784536,-0.836296188,44.99999998 +171.37,50.43027657,-2.574677607,50.4823,7.084484604,7.070357158,-2.9446875,3.645948575,-0.93415165,44.99999998 +171.38,50.43027721,-2.574676612,50.5117,7.077532245,7.071023231,-2.923125,3.556351154,-1.031192537,44.99999998 +171.39,50.43027784,-2.574675617,50.5408,7.067103677,7.072133393,-2.8996875,3.466011123,-1.127334168,44.99999998 +171.4,50.43027848,-2.574674621,50.5697,7.063627509,7.072133331,-2.875,3.374947216,-1.222492717,44.99999998 +171.41,50.43027911,-2.574673626,50.5983,7.063627552,7.071023044,-2.85,3.283178457,-1.316585279,44.99999998 +171.42,50.43027975,-2.574672631,50.6267,7.067103795,7.070134801,-2.8246875,3.190724096,-1.409529805,44.99999998 +171.43,50.43028038,-2.574671636,50.6548,7.077532419,7.069912692,-2.798125,3.097603386,-1.501245107,44.99999998 +171.44,50.43028102,-2.574670641,50.6827,7.084484834,7.070134672,-2.7696875,3.003835806,-1.591651373,44.99999998 +171.45,50.43028166,-2.574669646,50.7102,7.07753246,7.071022788,-2.7396875,2.909440837,-1.680669648,44.99999998 +171.46,50.43028229,-2.574668651,50.7375,7.067103894,7.072132948,-2.708125,2.814438361,-1.768222355,44.99999998 +171.47,50.43028293,-2.574667655,50.7644,7.063627736,7.072132883,-2.6746875,2.718848088,-1.854233175,44.99999998 +171.48,50.43028356,-2.57466666,50.791,7.063627782,7.071022593,-2.6403125,2.622690014,-1.938627051,44.99999998 +171.49,50.4302842,-2.574665665,50.8172,7.067104012,7.070134348,-2.60625,2.525984192,-2.021330472,44.99999998 +171.5,50.43028483,-2.57466467,50.8431,7.07753262,7.069912237,-2.5715625,2.428750905,-2.102271188,44.99999998 +171.51,50.43028547,-2.574663675,50.8687,7.08448503,7.070134215,-2.5346875,2.331010378,-2.181378726,44.99999998 +171.52,50.43028611,-2.57466268,50.8938,7.077532664,7.071022328,-2.4965625,2.232783067,-2.258584044,44.99999998 +171.53,50.43028674,-2.574661685,50.9186,7.067104111,7.072132486,-2.4584375,2.134089425,-2.333819877,44.99999998 +171.54,50.43028738,-2.574660689,50.943,7.063627951,7.072132418,-2.419375,2.034950137,-2.407020564,44.99999998 +171.55,50.43028801,-2.574659694,50.967,7.06362798,7.07124417,-2.378125,1.935385886,-2.478122334,44.99999998 +171.56,50.43028865,-2.574658699,50.9906,7.063628007,7.071022057,-2.335,1.835417413,-2.54706308,44.99999998 +171.57,50.43028928,-2.574657704,51.0137,7.063628031,7.071021989,-2.2915625,1.735065688,-2.613782812,44.99999998 +171.58,50.43028992,-2.574656708,51.0364,7.067104246,7.070133739,-2.248125,1.634351568,-2.678223261,44.99999998 +171.59,50.43029055,-2.574655714,51.0587,7.077532853,7.069911623,-2.203125,1.533296194,-2.740328219,44.99999998 +171.6,50.43029119,-2.574654719,51.0805,7.084485273,7.071243823,-2.1565625,1.431920537,-2.800043656,44.99999998 +171.61,50.43029183,-2.574653723,51.1018,7.077532916,7.071909887,-2.1096875,1.330245911,-2.85731732,44.99999998 +171.62,50.43029246,-2.574652728,51.1227,7.06710436,7.07124368,-2.0615625,1.228293457,-2.912099419,44.99999998 +171.63,50.4302931,-2.574651733,51.1431,7.063628184,7.071243607,-2.0115625,1.12608449,-2.964342111,44.99999998 +171.64,50.43029373,-2.574650738,51.1629,7.063628191,7.072131715,-1.961875,1.023640323,-3.013999848,44.99999998 +171.65,50.43029437,-2.574649742,51.1823,7.067104402,7.072131642,-1.913125,0.920982387,-3.061029312,44.99999998 +171.66,50.430295,-2.574648747,51.2012,7.077533021,7.071021343,-1.8628125,0.818132165,-3.105389538,44.99999998 +171.67,50.43029564,-2.574647752,51.2196,7.084485448,7.070133089,-1.81,0.715111031,-3.147041851,44.99999998 +171.68,50.43029628,-2.574646757,51.2374,7.077533085,7.06991097,-1.7565625,0.611940583,-3.185949868,44.99999998 +171.69,50.43029691,-2.574645762,51.2547,7.067104512,7.070132939,-1.7034375,0.508642366,-3.22207967,44.99999998 +171.7,50.43029755,-2.574644767,51.2715,7.06362832,7.071021042,-1.6496875,0.405237865,-3.255399801,44.99999998 +171.71,50.43029818,-2.574643772,51.2877,7.063628328,7.07213119,-1.595,0.301748796,-3.285881156,44.99999998 +171.72,50.43029882,-2.574642776,51.3034,7.067104548,7.072131113,-1.5396875,0.198196701,-3.313497149,44.99999998 +171.73,50.43029945,-2.574641781,51.3185,7.077533168,7.071242855,-1.483125,0.094603181,-3.338223773,44.99999998 +171.74,50.43030009,-2.574640786,51.3331,7.084485578,7.071020732,-1.425,-0.009010105,-3.36003937,44.99999998 +171.75,50.43030073,-2.574639791,51.347,7.07753319,7.071020652,-1.366875,-0.112621444,-3.378924975,44.99999998 +171.76,50.43030136,-2.574638795,51.3604,7.067104608,7.070132392,-1.31,-0.216209348,-3.394864146,44.99999998 +171.77,50.430302,-2.574637801,51.3732,7.063628434,7.069910267,-1.2528125,-0.319752046,-3.4078429,44.99999998 +171.78,50.43030263,-2.574636806,51.3855,7.063628464,7.071242456,-1.193125,-0.423227938,-3.417850009,44.99999998 +171.79,50.43030327,-2.57463581,51.3971,7.067104678,7.071908509,-1.1315625,-0.526615536,-3.424876649,44.99999998 +171.8,50.4303039,-2.574634815,51.4081,7.077533273,7.071242292,-1.0703125,-0.62989307,-3.428916746,44.99999998 +171.81,50.43030454,-2.57463382,51.4185,7.084485674,7.071242208,-1.01,-0.733039109,-3.429966806,44.99999998 +171.82,50.43030518,-2.574632825,51.4283,7.077533292,7.072130304,-0.9496875,-0.836032054,-3.428025912,44.99999998 +171.83,50.43030581,-2.574631829,51.4375,7.06710471,7.072130219,-0.8884375,-0.938850362,-3.423095667,44.99999998 +171.84,50.43030645,-2.574630834,51.4461,7.06362852,7.07101991,-0.8265625,-1.041472661,-3.415180484,44.99999998 +171.85,50.43030708,-2.574629839,51.454,7.063628534,7.070131644,-0.7646875,-1.143877465,-3.404287181,44.99999998 +171.86,50.43030772,-2.574628844,51.4614,7.063628552,7.069909513,-0.701875,-1.246043345,-3.39042527,44.99999998 +171.87,50.43030835,-2.574627849,51.4681,7.063628567,7.070131471,-0.638125,-1.347948989,-3.373606896,44.99999998 +171.88,50.43030899,-2.574626854,51.4741,7.067104766,7.071019562,-0.575,-1.449573195,-3.35384667,44.99999998 +171.89,50.43030962,-2.574625859,51.4796,7.077533343,7.072129698,-0.5115625,-1.55089465,-3.331161839,44.99999998 +171.9,50.43031026,-2.574624863,51.4844,7.084485734,7.072129609,-0.4465625,-1.651892213,-3.305572226,44.99999998 +171.91,50.4303109,-2.574623868,51.4885,7.077533359,7.071241339,-0.3821875,-1.752544797,-3.277100062,44.99999998 +171.92,50.43031153,-2.574622873,51.492,7.067104793,7.071019203,-0.3196875,-1.852831376,-3.245770214,44.99999998 +171.93,50.43031217,-2.574621878,51.4949,7.063628606,7.071019112,-0.2565625,-1.952731037,-3.211610012,44.99999998 +171.94,50.4303128,-2.574620882,51.4972,7.063628596,7.070130841,-0.1915625,-2.052222866,-3.17464925,44.99999998 +171.95,50.43031344,-2.574619888,51.4987,7.067104776,7.069908703,-0.126875,-2.151286123,-3.134920127,44.99999998 +171.96,50.43031407,-2.574618893,51.4997,7.077533365,7.071240878,-0.0634375,-2.249900124,-3.092457365,44.99999998 +171.97,50.43031471,-2.574617897,51.5,7.084485775,7.071906918,0.000625,-2.348044242,-3.047297863,44.99999998 +171.98,50.43031535,-2.574616902,51.4997,7.077533397,7.071240688,0.06625,-2.445698022,-2.999481097,44.99999998 +171.99,50.43031598,-2.574615907,51.4987,7.067104806,7.071240592,0.131875,-2.542841068,-2.949048779,44.99999998 +172,50.43031662,-2.574614912,51.497,7.063628594,7.072128675,0.19625,-2.63945304,-2.896044797,44.99999998 +172.01,50.43031725,-2.574613916,51.4948,7.063628581,7.072128578,0.26,-2.735513826,-2.840515447,44.99999998 +172.02,50.43031789,-2.574612921,51.4918,7.067104781,7.071018256,0.3234375,-2.831003316,-2.782509085,44.99999998 +172.03,50.43031852,-2.574611926,51.4883,7.077533379,7.070129978,0.3865625,-2.925901571,-2.722076362,44.99999998 +172.04,50.43031916,-2.574610931,51.4841,7.084485771,7.069907835,0.4503125,-3.020188823,-2.659269931,44.99999998 +172.05,50.4303198,-2.574609936,51.4793,7.077533369,7.070129779,0.515,-3.113845307,-2.594144626,44.99999998 +172.06,50.43032043,-2.574608941,51.4738,7.067104766,7.071017858,0.5796875,-3.20685154,-2.526757112,44.99999998 +172.07,50.43032107,-2.574607946,51.4677,7.063628553,7.07212798,0.643125,-3.299188043,-2.457166288,44.99999998 +172.08,50.4303217,-2.57460695,51.4609,7.063628549,7.072127878,0.705,-3.390835565,-2.385432774,44.99999998 +172.09,50.43032234,-2.574605955,51.4536,7.067104755,7.071017552,0.766875,-3.481774968,-2.31161908,44.99999998 +172.1,50.43032297,-2.57460496,51.4456,7.077533346,7.070129268,0.83,-3.57198723,-2.235789663,44.99999998 +172.11,50.43032361,-2.574603965,51.437,7.084485724,7.069907119,0.8928125,-3.661453501,-2.158010585,44.99999998 +172.12,50.43032425,-2.57460297,51.4277,7.077533308,7.070129059,0.9534375,-3.75015516,-2.078349742,44.99999998 +172.13,50.43032488,-2.574601975,51.4179,7.067104701,7.071017133,1.0134375,-3.838073643,-1.996876461,44.99999998 +172.14,50.43032552,-2.57460098,51.4075,7.063628501,7.072127251,1.075,-3.925190558,-1.913661962,44.99999998 +172.15,50.43032615,-2.574599984,51.3964,7.063628505,7.072127144,1.1365625,-4.011487799,-1.828778665,44.99999998 +172.16,50.43032679,-2.574598989,51.3847,7.063628499,7.071016813,1.19625,-4.096947262,-1.742300656,44.99999998 +172.17,50.43032742,-2.574597994,51.3725,7.063628486,7.07035057,1.255,-4.181551127,-1.654303334,44.99999998 +172.18,50.43032806,-2.574596999,51.3596,7.067104662,7.071016595,1.3134375,-4.265281746,-1.564863419,44.99999998 +172.19,50.43032869,-2.574596004,51.3462,7.077533219,7.07212671,1.37125,-4.348121589,-1.474058947,44.99999998 +172.2,50.43032933,-2.574595008,51.3322,7.084485588,7.0721266,1.4284375,-4.430053407,-1.381969103,44.99999998 +172.21,50.43032997,-2.574594013,51.3176,7.077533193,7.071016265,1.485,-4.511060071,-1.288674098,44.99999998 +172.22,50.4303306,-2.574593018,51.3025,7.067104606,7.070127974,1.5415625,-4.591124678,-1.194255352,44.99999998 +172.23,50.43033124,-2.574592023,51.2868,7.063628401,7.070127863,1.598125,-4.67023044,-1.098795255,44.99999998 +172.24,50.43033187,-2.574591028,51.2705,7.063628377,7.071015929,1.653125,-4.748360913,-1.002376943,44.99999998 +172.25,50.43033251,-2.574590033,51.2537,7.067104539,7.07212604,1.7065625,-4.82549971,-0.905084584,44.99999998 +172.26,50.43033314,-2.574589037,51.2364,7.077533093,7.072125926,1.76,-4.90163079,-0.807002918,44.99999998 +172.27,50.43033378,-2.574588042,51.2185,7.084485465,7.071015587,1.813125,-4.976738223,-0.708217603,44.99999998 +172.28,50.43033442,-2.574587047,51.2001,7.077533068,7.070127293,1.865,-5.050806368,-0.60881464,44.99999998 +172.29,50.43033505,-2.574586052,51.1812,7.067104475,7.069905132,1.9165625,-5.123819698,-0.508880831,44.99999998 +172.3,50.43033569,-2.574585057,51.1618,7.063628257,7.070127061,1.968125,-5.195762971,-0.408503266,44.99999998 +172.31,50.43033632,-2.574584062,51.1418,7.06362822,7.071015124,2.0178125,-5.26662112,-0.307769494,44.99999998 +172.32,50.43033696,-2.574583067,51.1214,7.067104387,7.07212523,2.065,-5.336379476,-0.20676729,44.99999998 +172.33,50.43033759,-2.574582071,51.1005,7.077532961,7.072125112,2.111875,-5.405023373,-0.105584834,44.99999998 +172.34,50.43033823,-2.574581076,51.0792,7.084485345,7.071014771,2.1596875,-5.472538542,-0.004310247,44.99999998 +172.35,50.43033887,-2.574580081,51.0573,7.077532937,7.070348518,2.2065625,-5.538910775,0.096968065,44.99999998 +172.36,50.4303395,-2.574579086,51.035,7.067104321,7.070792488,2.25125,-5.604126321,0.198161808,44.99999998 +172.37,50.43034014,-2.574578091,51.0123,7.063628085,7.071236457,2.295,-5.668171486,0.299182747,44.99999998 +172.38,50.43034077,-2.574577095,50.9891,7.063628049,7.071014291,2.338125,-5.731032978,0.399942818,44.99999998 +172.39,50.43034141,-2.574576101,50.9655,7.067104226,7.071014171,2.3796875,-5.79269756,0.50035413,44.99999998 +172.4,50.43034204,-2.574575105,50.9415,7.077532801,7.071236095,2.42,-5.8531524,0.600329078,44.99999998 +172.41,50.43034268,-2.57457411,50.9171,7.084485168,7.070791884,2.4596875,-5.912384949,0.699780571,44.99999998 +172.42,50.43034332,-2.574573115,50.8923,7.077532737,7.070347673,2.4984375,-5.970382716,0.798621864,44.99999998 +172.43,50.43034395,-2.57457212,50.8671,7.067104113,7.071013684,2.53625,-6.02713367,0.896766727,44.99999998 +172.44,50.43034459,-2.574571125,50.8416,7.063627897,7.072123784,2.573125,-6.08262595,0.994129559,44.99999998 +172.45,50.43034522,-2.574570129,50.8156,7.063627885,7.072123661,2.6084375,-6.136847926,1.090625564,44.99999998 +172.46,50.43034586,-2.574569134,50.7894,7.063627861,7.071013314,2.643125,-6.189788309,1.186170459,44.99999998 +172.47,50.43034649,-2.574568139,50.7628,7.063627828,7.070125011,2.678125,-6.241436043,1.280681051,44.99999998 +172.48,50.43034713,-2.574567144,50.7358,7.067103991,7.069902842,2.71125,-6.291780355,1.374074833,44.99999998 +172.49,50.43034776,-2.574566149,50.7085,7.077532545,7.070124762,2.74125,-6.340810645,1.466270446,44.99999998 +172.5,50.4303484,-2.574565154,50.681,7.084484899,7.071012815,2.77,-6.388516773,1.557187389,44.99999998 +172.51,50.43034904,-2.574564159,50.6531,7.077532474,7.072122913,2.7984375,-6.434888768,1.646746479,44.99999998 +172.52,50.43034967,-2.574563163,50.625,7.067103863,7.072122787,2.82625,-6.479916891,1.734869622,44.99999998 +172.53,50.43035031,-2.574562168,50.5966,7.063627646,7.071234483,2.853125,-6.523591745,1.821479871,44.99999998 +172.54,50.43035094,-2.574561173,50.5679,7.063627622,7.071012312,2.878125,-6.565904219,1.906501765,44.99999998 +172.55,50.43035158,-2.574560178,50.539,7.067103781,7.07123423,2.90125,-6.606845549,1.989861166,44.99999998 +172.56,50.43035221,-2.574559182,50.5099,7.077532319,7.071012058,2.9234375,-6.646407081,2.071485421,44.99999998 +172.57,50.43035285,-2.574558188,50.4805,7.084484671,7.071011931,2.9446875,-6.684580624,2.151303255,44.99999998 +172.58,50.43035349,-2.574557192,50.451,7.07753226,7.071233848,2.9646875,-6.721358154,2.229245167,44.99999998 +172.59,50.43035412,-2.574556197,50.4212,7.067103658,7.070789631,2.9834375,-6.756732053,2.305243091,44.99999998 +172.6,50.43035476,-2.574555202,50.3913,7.063627435,7.070345414,3.00125,-6.790694871,2.37923085,44.99999998 +172.61,50.43035539,-2.574554207,50.3612,7.063627389,7.07101142,3.018125,-6.823239504,2.451143872,44.99999998 +172.62,50.43035603,-2.574553212,50.3309,7.067103534,7.072121515,3.033125,-6.854359248,2.520919474,44.99999998 +172.63,50.43035666,-2.574552216,50.3005,7.077532085,7.072121387,3.04625,-6.884047515,2.588496752,44.99999998 +172.64,50.4303573,-2.574551221,50.27,7.08448446,7.071011035,3.0584375,-6.912298116,2.653816863,44.99999998 +172.65,50.43035794,-2.574550226,50.2393,7.07753205,7.070122728,3.0696875,-6.939105207,2.716822797,44.99999998 +172.66,50.43035857,-2.574549231,50.2086,7.067103428,7.069900555,3.0796875,-6.964463173,2.777459608,44.99999998 +172.67,50.43035921,-2.574548236,50.1777,7.063627184,7.070122471,3.088125,-6.988366628,2.835674469,44.99999998 +172.68,50.43035984,-2.574547241,50.1468,7.063627139,7.071010521,3.0946875,-7.010810703,2.891416559,44.99999998 +172.69,50.43036048,-2.574546246,50.1158,7.067103307,7.072120614,3.1,-7.031790641,2.944637233,44.99999998 +172.7,50.43036111,-2.57454525,50.0848,7.077531873,7.072120485,3.1046875,-7.051302146,2.995290198,44.99999998 +172.71,50.43036175,-2.574544255,50.0537,7.084484234,7.071232178,3.108125,-7.069340977,3.043331219,44.99999998 +172.72,50.43036239,-2.57454326,50.0226,7.077531804,7.071232049,3.1096875,-7.085903526,3.088718414,44.99999998 +172.73,50.43036302,-2.574542265,49.9915,7.067103177,7.071898053,3.1096875,-7.100986296,3.131412193,44.99999998 +172.74,50.43036366,-2.574541269,49.9604,7.063626944,7.07123179,3.108125,-7.114586079,3.171375369,44.99999998 +172.75,50.43036429,-2.574540274,49.9293,7.063626915,7.069899394,3.105,-7.126700069,3.208573049,44.99999998 +172.76,50.43036493,-2.57453928,49.8983,7.067103083,7.07012131,3.10125,-7.137325743,3.242972748,44.99999998 +172.77,50.43036556,-2.574538284,49.8673,7.077531635,7.071009359,3.0965625,-7.146460867,3.274544556,44.99999998 +172.78,50.4303662,-2.574537289,49.8363,7.084483993,7.07100923,3.0896875,-7.154103551,3.303260914,44.99999998 +172.79,50.43036684,-2.574536294,49.8055,7.077531575,7.071231145,3.0815625,-7.160252191,3.329096841,44.99999998 +172.8,50.43036747,-2.574535299,49.7747,7.067102953,7.072119195,3.0734375,-7.164905525,3.352029649,44.99999998 +172.81,50.43036811,-2.574534303,49.744,7.06362671,7.072119067,3.064375,-7.168062522,3.372039512,44.99999998 +172.82,50.43036874,-2.574533308,49.7134,7.06362667,7.071008716,3.053125,-7.16972261,3.389108842,44.99999998 +172.83,50.43036938,-2.574532313,49.6829,7.063626648,7.070120409,3.0396875,-7.169885387,3.403222855,44.99999998 +172.84,50.43037001,-2.574531318,49.6526,7.063626631,7.069898236,3.025,-7.168550797,3.414369233,44.99999998 +172.85,50.43037065,-2.574530323,49.6224,7.067102797,7.070120153,3.0096875,-7.165719125,3.422538179,44.99999998 +172.86,50.43037128,-2.574529328,49.5924,7.077531335,7.071008203,2.993125,-7.161391059,3.427722645,44.99999998 +172.87,50.43037192,-2.574528333,49.5625,7.084483674,7.072118298,2.9746875,-7.155567344,3.429918105,44.99999998 +172.88,50.43037256,-2.574527337,49.5329,7.077531253,7.072118171,2.9546875,-7.148249355,3.429122553,44.99999998 +172.89,50.43037319,-2.574526342,49.5034,7.067102655,7.071229866,2.9334375,-7.139438467,3.425336849,44.99999998 +172.9,50.43037383,-2.574525347,49.4742,7.063626442,7.071229738,2.91125,-7.129136686,3.418564144,44.99999998 +172.91,50.43037446,-2.574524352,49.4452,7.063626406,7.071895745,2.8884375,-7.117346017,3.408810397,44.99999998 +172.92,50.4303751,-2.574523356,49.4164,7.067102554,7.071229485,2.8646875,-7.104068981,3.396084145,44.99999998 +172.93,50.43037573,-2.574522361,49.3879,7.077531096,7.069897091,2.8396875,-7.089308385,3.380396446,44.99999998 +172.94,50.43037637,-2.574521367,49.3596,7.084483461,7.07011901,2.813125,-7.073067266,3.361760993,44.99999998 +172.95,50.43037701,-2.574520371,49.3316,7.077531057,7.071007062,2.784375,-7.055349004,3.340194003,44.99999998 +172.96,50.43037764,-2.574519376,49.3039,7.067102448,7.071006937,2.7534375,-7.036157382,3.315714381,44.99999998 +172.97,50.43037828,-2.574518381,49.2765,7.063626218,7.071228857,2.7215625,-7.015496294,3.288343327,44.99999998 +172.98,50.43037891,-2.574517386,49.2495,7.06362618,7.07211691,2.69,-6.993370097,3.25810485,44.99999998 +172.99,50.43037955,-2.57451639,49.2227,7.067102341,7.072116786,2.6584375,-6.969783487,3.225025246,44.99999998 +173,50.43038018,-2.574515395,49.1963,7.077530899,7.07100644,2.6259375,-6.944741278,3.189133336,44.99999998 +173.01,50.43038082,-2.5745144,49.1702,7.084483267,7.070118139,2.5915625,-6.918248741,3.150460518,44.99999998 +173.02,50.43038146,-2.574513405,49.1444,7.077530852,7.06989597,2.5546875,-6.890311433,3.109040368,44.99999998 +173.03,50.43038209,-2.57451241,49.1191,7.06710224,7.070117891,2.5165625,-6.8609352,3.064909153,44.99999998 +173.04,50.43038273,-2.574511415,49.0941,7.06362601,7.071005947,2.4784375,-6.830126113,3.018105262,44.99999998 +173.05,50.43038336,-2.57451042,49.0695,7.063625975,7.072116048,2.439375,-6.797890648,2.968669547,44.99999998 +173.06,50.430384,-2.574509424,49.0453,7.063625955,7.072115927,2.3984375,-6.764235508,2.916645151,44.99999998 +173.07,50.43038463,-2.574508429,49.0215,7.063625945,7.071005584,2.35625,-6.729167798,2.862077338,44.99999998 +173.08,50.43038527,-2.574507434,48.9982,7.067102119,7.07033933,2.3134375,-6.692694737,2.805013779,44.99999998 +173.09,50.4303859,-2.574506439,48.9752,7.07753067,7.070783299,2.27,-6.654824061,2.745504205,44.99999998 +173.1,50.43038654,-2.574505444,48.9528,7.084483025,7.071227268,2.22625,-6.61556356,2.683600469,44.99999998 +173.11,50.43038718,-2.574504448,48.9307,7.077530609,7.071005104,2.1815625,-6.574921487,2.61935666,44.99999998 +173.12,50.43038781,-2.574503454,48.9091,7.067102008,7.071004986,2.1346875,-6.53290632,2.552828697,44.99999998 +173.13,50.43038845,-2.574502458,48.888,7.0636258,7.071226912,2.0865625,-6.489526825,2.484074621,44.99999998 +173.14,50.43038908,-2.574501463,48.8674,7.063625786,7.070782706,2.0384375,-6.444792114,2.413154421,44.99999998 +173.15,50.43038972,-2.574500468,48.8472,7.067101961,7.0703385,1.9896875,-6.398711468,2.340129861,44.99999998 +173.16,50.43039035,-2.574499473,48.8276,7.077530509,7.071004517,1.9396875,-6.351294569,2.265064712,44.99999998 +173.17,50.43039099,-2.574498478,48.8084,7.084482859,7.072114623,1.8884375,-6.302551216,2.188024406,44.99999998 +173.18,50.43039163,-2.574497482,48.7898,7.077530451,7.072114508,1.83625,-6.252491722,2.109076093,44.99999998 +173.19,50.43039226,-2.574496487,48.7717,7.067101867,7.071004171,1.78375,-6.201126399,2.028288643,44.99999998 +173.2,50.4303929,-2.574495492,48.7541,7.063625668,7.070115879,1.73125,-6.148466135,1.945732472,44.99999998 +173.21,50.43039353,-2.574494497,48.7371,7.063625645,7.070115765,1.678125,-6.094521815,1.861479659,44.99999998 +173.22,50.43039417,-2.574493502,48.7205,7.067101806,7.07100383,1.623125,-6.039304726,1.775603541,44.99999998 +173.23,50.4303948,-2.574492507,48.7046,7.077530358,7.07211394,1.5665625,-5.982826385,1.688179062,44.99999998 +173.24,50.43039544,-2.574491511,48.6892,7.08448273,7.072113829,1.5103125,-5.925098596,1.59928254,44.99999998 +173.25,50.43039608,-2.574490516,48.6744,7.07753034,7.071003495,1.4546875,-5.866133446,1.508991325,44.99999998 +173.26,50.43039671,-2.574489521,48.6601,7.067101758,7.070337251,1.398125,-5.805943256,1.417384311,44.99999998 +173.27,50.43039735,-2.574488526,48.6464,7.063625556,7.07078123,1.34,-5.744540572,1.324541314,44.99999998 +173.28,50.43039798,-2.574487531,48.6333,7.063625536,7.07122521,1.2815625,-5.681938172,1.23054329,44.99999998 +173.29,50.43039862,-2.574486535,48.6208,7.067101701,7.071003058,1.223125,-5.618149177,1.135472231,44.99999998 +173.3,50.43039925,-2.574485541,48.6088,7.07753026,7.07100295,1.163125,-5.553186935,1.039410987,44.99999998 +173.31,50.43039989,-2.574484545,48.5975,7.084482642,7.071224887,1.101875,-5.48706497,0.94244338,44.99999998 +173.32,50.43040053,-2.57448355,48.5868,7.077530259,7.070780691,1.0415625,-5.419797089,0.844653923,44.99999998 +173.33,50.43040116,-2.574482555,48.5767,7.067101669,7.070336496,0.9815625,-5.351397388,0.746127929,44.99999998 +173.34,50.4304018,-2.57448156,48.5671,7.063625451,7.071002524,0.92,-5.281880075,0.646951341,44.99999998 +173.35,50.43040243,-2.574480565,48.5583,7.063625431,7.072112642,0.858125,-5.211259703,0.547210562,44.99999998 +173.36,50.43040307,-2.574479569,48.55,7.067101624,7.072112538,0.796875,-5.139551056,0.446992623,44.99999998 +173.37,50.4304037,-2.574478574,48.5423,7.077530213,7.071002214,0.734375,-5.066769087,0.346384844,44.99999998 +173.38,50.43040434,-2.574477579,48.5353,7.084482599,7.070113934,0.6703125,-4.992928979,0.245475058,44.99999998 +173.39,50.43040498,-2.574476584,48.5289,7.0775302,7.069891787,0.606875,-4.918046145,0.144351216,44.99999998 +173.4,50.43040561,-2.574475589,48.5232,7.06710161,7.07011373,0.5446875,-4.842136228,0.043101495,44.99999998 +173.41,50.43040625,-2.574474594,48.518,7.063625409,7.071001807,0.4815625,-4.765215097,-0.058185812,44.99999998 +173.42,50.43040688,-2.574473599,48.5135,7.063625398,7.07211193,0.4165625,-4.687298852,-0.159422355,44.99999998 +173.43,50.43040752,-2.574472603,48.5097,7.06362539,7.072111831,0.351875,-4.60840371,-0.260519899,44.99999998 +173.44,50.43040815,-2.574471608,48.5065,7.063625392,7.071223555,0.2884375,-4.528546113,-0.361390264,44.99999998 +173.45,50.43040879,-2.574470613,48.5039,7.067101593,7.071223458,0.2246875,-4.447742849,-0.461945503,44.99999998 +173.46,50.43040942,-2.574469618,48.502,7.07753018,7.071889494,0.16,-4.366010706,-0.562097896,44.99999998 +173.47,50.43041006,-2.574468622,48.5007,7.084482563,7.071223265,0.0953125,-4.283366815,-0.66176018,44.99999998 +173.48,50.4304107,-2.574467627,48.5001,7.077530159,7.069890904,0.0315625,-4.199828308,-0.760845324,44.99999998 +173.49,50.43041133,-2.574466633,48.5001,7.067101572,7.070112854,-0.031875,-4.115412775,-0.859267097,44.99999998 +173.5,50.43041197,-2.574465637,48.5007,7.06362539,7.071000937,-0.096875,-4.030137805,-0.956939499,44.99999998 +173.51,50.4304126,-2.574464642,48.502,7.063625408,7.071000843,-0.163125,-3.944021217,-1.053777445,44.99999998 +173.52,50.43041324,-2.574463647,48.504,7.067101609,7.071222795,-0.228125,-3.857080887,-1.149696481,44.99999998 +173.53,50.43041387,-2.574462652,48.5066,7.077530182,7.072110881,-0.2915625,-3.769335094,-1.244613014,44.99999998 +173.54,50.43041451,-2.574461656,48.5098,7.084482556,7.072110789,-0.355,-3.680802171,-1.338444192,44.99999998 +173.55,50.43041515,-2.574460661,48.5137,7.077530173,7.071000477,-0.4184375,-3.591500511,-1.431108198,44.99999998 +173.56,50.43041578,-2.574459666,48.5182,7.067101615,7.07011221,-0.4815625,-3.501448791,-1.522524301,44.99999998 +173.57,50.43041642,-2.574458671,48.5233,7.063625441,7.069890077,-0.5453125,-3.410665863,-1.61261269,44.99999998 +173.58,50.43041705,-2.574457676,48.5291,7.063625443,7.070112033,-0.6096875,-3.319170691,-1.701294926,44.99999998 +173.59,50.43041769,-2.574456681,48.5355,7.06710163,7.071000123,-0.673125,-3.226982298,-1.788493544,44.99999998 +173.6,50.43041832,-2.574455686,48.5426,7.077530209,7.072110258,-0.735,-3.134120049,-1.874132629,44.99999998 +173.61,50.43041896,-2.57445469,48.5502,7.084482613,7.072110171,-0.796875,-3.040603252,-1.958137409,44.99999998 +173.62,50.4304196,-2.574453695,48.5585,7.077530251,7.071221908,-0.86,-2.946451447,-2.040434661,44.99999998 +173.63,50.43042023,-2.5744527,48.5674,7.067101684,7.071221823,-0.9228125,-2.851684342,-2.120952591,44.99999998 +173.64,50.43042087,-2.574451705,48.577,7.063625495,7.071887872,-0.9834375,-2.756321705,-2.199621072,44.99999998 +173.65,50.4304215,-2.574450709,48.5871,7.063625498,7.071221656,-1.043125,-2.660383417,-2.276371461,44.99999998 +173.66,50.43042214,-2.574449714,48.5978,7.0671017,7.069889308,-1.10375,-2.563889533,-2.351136781,44.99999998 +173.67,50.43042277,-2.57444872,48.6092,7.0775303,7.07011127,-1.1646875,-2.466860219,-2.423851886,44.99999998 +173.68,50.43042341,-2.574447724,48.6211,7.084482709,7.070999366,-1.2246875,-2.369315758,-2.49445335,44.99999998 +173.69,50.43042405,-2.574446729,48.6337,7.077530337,7.070999284,-1.2834375,-2.271276492,-2.562879637,44.99999998 +173.7,50.43042468,-2.574445734,48.6468,7.067101773,7.071221249,-1.34125,-2.172762873,-2.629070987,44.99999998 +173.71,50.43042532,-2.574444739,48.6605,7.063625599,7.072109347,-1.39875,-2.073795529,-2.692969819,44.99999998 +173.72,50.43042595,-2.574443743,48.6748,7.063625611,7.072109268,-1.45625,-1.974395087,-2.754520326,44.99999998 +173.73,50.43042659,-2.574442748,48.6896,7.067101807,7.070998968,-1.5134375,-1.874582344,-2.813668822,44.99999998 +173.74,50.43042722,-2.574441753,48.7051,7.077530401,7.070110713,-1.5696875,-1.774378042,-2.870363798,44.99999998 +173.75,50.43042786,-2.574440758,48.721,7.084482818,7.069888593,-1.6246875,-1.673803265,-2.92455575,44.99999998 +173.76,50.4304285,-2.574439763,48.7376,7.077530463,7.07011056,-1.67875,-1.572878926,-2.976197468,44.99999998 +173.77,50.43042913,-2.574438768,48.7546,7.067101898,7.070998661,-1.7328125,-1.471626054,-3.025243858,44.99999998 +173.78,50.43042977,-2.574437773,48.7722,7.063625708,7.072108807,-1.786875,-1.370065904,-3.071652236,44.99999998 +173.79,50.4304304,-2.574436777,48.7904,7.063625723,7.072108732,-1.839375,-1.26821962,-3.115382094,44.99999998 +173.8,50.43043104,-2.574435782,48.809,7.063625755,7.071220481,-1.89,-1.166108456,-3.156395215,44.99999998 +173.81,50.43043167,-2.574434787,48.8282,7.063625793,7.071220408,-1.9403125,-1.063753786,-3.194655962,44.99999998 +173.82,50.43043231,-2.574433792,48.8478,7.067102016,7.072108513,-1.99125,-0.96117698,-3.23013093,44.99999998 +173.83,50.43043294,-2.574432796,48.868,7.077530615,7.072108441,-2.0415625,-0.858399467,-3.262789181,44.99999998 +173.84,50.43043358,-2.574431801,48.8887,7.084483012,7.070998147,-2.089375,-0.755442618,-3.292602237,44.99999998 +173.85,50.43043422,-2.574430806,48.9098,7.077530636,7.070109898,-2.135,-0.652328034,-3.319544031,44.99999998 +173.86,50.43043485,-2.574429811,48.9314,7.067102085,7.069887783,-2.1803125,-0.549077258,-3.343591184,44.99999998 +173.87,50.43043549,-2.574428816,48.9534,7.063625932,7.070109758,-2.22625,-0.445711776,-3.36472267,44.99999998 +173.88,50.43043612,-2.574427821,48.9759,7.06362596,7.070997865,-2.2715625,-0.342253245,-3.382920096,44.99999998 +173.89,50.43043676,-2.574426826,48.9989,7.067102167,7.072108017,-2.3146875,-0.238723209,-3.398167534,44.99999998 +173.9,50.43043739,-2.57442583,49.0222,7.077530765,7.072107947,-2.356875,-0.135143326,-3.410451692,44.99999998 +173.91,50.43043803,-2.574424835,49.046,7.084483188,7.070997658,-2.3996875,-0.031535196,-3.419761912,44.99999998 +173.92,50.43043867,-2.57442384,49.0702,7.077530842,7.070109413,-2.44125,0.072079466,-3.426090059,44.99999998 +173.93,50.4304393,-2.574422845,49.0949,7.067102292,7.069887302,-2.48,0.175679116,-3.429430632,44.99999998 +173.94,50.43043994,-2.57442185,49.1198,7.063626121,7.070109279,-2.518125,0.279242097,-3.429780652,44.99999998 +173.95,50.43044057,-2.574420855,49.1452,7.063626148,7.070997389,-2.5565625,0.382746693,-3.427139832,44.99999998 +173.96,50.43044121,-2.57441986,49.171,7.06710237,7.072107544,-2.5928125,0.48617142,-3.421510522,44.99999998 +173.97,50.43044184,-2.574418864,49.1971,7.077530976,7.072107478,-2.6265625,0.589494618,-3.412897591,44.99999998 +173.98,50.43044248,-2.574417869,49.2235,7.08448339,7.070997191,-2.66,0.69269463,-3.401308603,44.99999998 +173.99,50.43044312,-2.574416874,49.2503,7.077531036,7.070330994,-2.693125,0.795750085,-3.386753584,44.99999998 +174,50.43044375,-2.574415879,49.2774,7.067102491,7.070997062,-2.7246875,0.898639267,-3.369245255,44.99999998 +174.01,50.43044439,-2.574414884,49.3048,7.063626327,7.072107219,-2.7546875,1.001340863,-3.348798912,44.99999998 +174.02,50.43044502,-2.574413888,49.3325,7.063626352,7.072107154,-2.7834375,1.103833273,-3.325432375,44.99999998 +174.03,50.43044566,-2.574412893,49.3605,7.06362638,7.07099687,-2.8115625,1.206095181,-3.299166042,44.99999998 +174.04,50.43044629,-2.574411898,49.3887,7.063626416,7.07010863,-2.8396875,1.308105217,-3.270022715,44.99999998 +174.05,50.43044693,-2.574410903,49.4173,7.06710265,7.069886523,-2.86625,1.409842067,-3.23802795,44.99999998 +174.06,50.43044756,-2.574409908,49.4461,7.077531268,7.070108504,-2.8896875,1.511284531,-3.203209534,44.99999998 +174.07,50.4304482,-2.574408913,49.4751,7.08448369,7.070996618,-2.9115625,1.612411353,-3.165597834,44.99999998 +174.08,50.43044884,-2.574407918,49.5043,7.077531332,7.072106776,-2.9334375,1.71320139,-3.125225738,44.99999998 +174.09,50.43044947,-2.574406922,49.5338,7.067102775,7.072106714,-2.9546875,1.813633729,-3.082128426,44.99999998 +174.1,50.43045011,-2.574405927,49.5634,7.063626612,7.070996431,-2.9746875,1.913687286,-3.036343426,44.99999998 +174.11,50.43045074,-2.574404932,49.5933,7.063626657,7.070108193,-2.993125,2.013341148,-2.987910673,44.99999998 +174.12,50.43045138,-2.574403937,49.6233,7.067102897,7.070108132,-3.0096875,2.112574631,-2.936872395,44.99999998 +174.13,50.43045201,-2.574402942,49.6535,7.07753151,7.070996248,-3.025,2.211366879,-2.883273167,44.99999998 +174.14,50.43045265,-2.574401947,49.6838,7.084483919,7.072106407,-3.0396875,2.309697322,-2.827159686,44.99999998 +174.15,50.43045329,-2.574400951,49.7143,7.077531553,7.072106346,-3.053125,2.407545393,-2.768580825,44.99999998 +174.16,50.43045392,-2.574399956,49.7449,7.06710301,7.070996064,-3.0646875,2.504890693,-2.707587749,44.99999998 +174.17,50.43045456,-2.574398961,49.7756,7.063626866,7.070329871,-3.0746875,2.601712883,-2.644233628,44.99999998 +174.18,50.43045519,-2.574397966,49.8064,7.063626905,7.070995943,-3.083125,2.697991737,-2.578573696,44.99999998 +174.19,50.43045583,-2.574396971,49.8373,7.067103128,7.072106103,-3.09,2.793707144,-2.510665191,44.99999998 +174.2,50.43045646,-2.574395975,49.8682,7.077531737,7.072106043,-3.0965625,2.888839166,-2.440567357,44.99999998 +174.21,50.4304571,-2.57439498,49.8992,7.08448415,7.070995761,-3.103125,2.983367805,-2.368341329,44.99999998 +174.22,50.43045774,-2.574393985,49.9303,7.077531798,7.070107525,-3.1078125,3.077273468,-2.294050074,44.99999998 +174.23,50.43045837,-2.57439299,49.9614,7.067103267,7.069885421,-3.1096875,3.170536501,-2.217758337,44.99999998 +174.24,50.43045901,-2.574391995,49.9925,7.06362712,7.070107404,-3.1096875,3.263137367,-2.139532696,44.99999998 +174.25,50.43045964,-2.574391,50.0236,7.063627151,7.07099552,-3.108125,3.355056757,-2.05944139,44.99999998 +174.26,50.43046028,-2.574390005,50.0547,7.067103366,7.072105681,-3.105,3.446275534,-1.977554147,44.99999998 +174.27,50.43046091,-2.574389009,50.0857,7.077531975,7.07210562,-3.1015625,3.536774562,-1.89394253,44.99999998 +174.28,50.43046155,-2.574388014,50.1167,7.084484406,7.071217383,-3.0984375,3.626534989,-1.808679306,44.99999998 +174.29,50.43046219,-2.574387019,50.1477,7.077532067,7.070995279,-3.094375,3.715538081,-1.7218389,44.99999998 +174.3,50.43046282,-2.574386024,50.1786,7.067103522,7.070995219,-3.088125,3.803765216,-1.633497059,44.99999998 +174.31,50.43046346,-2.574385028,50.2095,7.063627357,7.070106981,-3.0796875,3.891197946,-1.54373073,44.99999998 +174.32,50.43046409,-2.574384034,50.2402,7.06362739,7.069884876,-3.0696875,3.977818106,-1.452618294,44.99999998 +174.33,50.43046473,-2.574383039,50.2709,7.067103618,7.071217081,-3.0584375,4.063607535,-1.360239105,44.99999998 +174.34,50.43046536,-2.574382043,50.3014,7.077532231,7.071883153,-3.04625,4.148548299,-1.266673779,44.99999998 +174.35,50.430466,-2.574381048,50.3318,7.084484651,7.071216959,-3.033125,4.232622694,-1.172003906,44.99999998 +174.36,50.43046664,-2.574380053,50.3621,7.077532299,7.071216897,-3.018125,4.315813186,-1.076312047,44.99999998 +174.37,50.43046727,-2.574379058,50.3922,7.067103757,7.072105012,-3.00125,4.398102416,-0.979681626,44.99999998 +174.38,50.43046791,-2.574378062,50.4221,7.063627603,7.072104951,-2.9834375,4.47947308,-0.882196868,44.99999998 +174.39,50.43046854,-2.574377067,50.4519,7.063627632,7.070994668,-2.9646875,4.559908333,-0.783942857,44.99999998 +174.4,50.43046918,-2.574376072,50.4814,7.06362765,7.07010643,-2.9446875,4.639391273,-0.68500525,44.99999998 +174.41,50.43046981,-2.574375077,50.5108,7.063627677,7.069884324,-2.9234375,4.717905284,-0.585470277,44.99999998 +174.42,50.43047045,-2.574374082,50.5399,7.067103916,7.070106306,-2.9009375,4.795434094,-0.485424741,44.99999998 +174.43,50.43047108,-2.574373087,50.5688,7.07753255,7.07099442,-2.876875,4.871961431,-0.384955961,44.99999998 +174.44,50.43047172,-2.574372092,50.5975,7.084484977,7.072104577,-2.85125,4.94747131,-0.284151486,44.99999998 +174.45,50.43047236,-2.574371096,50.6258,7.077532606,7.072104514,-2.825,5.021947973,-0.183099206,44.99999998 +174.46,50.43047299,-2.574370101,50.654,7.067104035,7.071216274,-2.798125,5.095375838,-0.081887243,44.99999998 +174.47,50.43047363,-2.574369106,50.6818,7.063627871,7.07121621,-2.7696875,5.167739605,0.019396111,44.99999998 +174.48,50.43047426,-2.574368111,50.7094,7.06362792,7.071882278,-2.74,5.239024207,0.120662505,44.99999998 +174.49,50.4304749,-2.574367115,50.7366,7.06710416,7.071216081,-2.709375,5.309214688,0.221823762,44.99999998 +174.5,50.43047553,-2.57436612,50.7636,7.077532772,7.069883752,-2.6765625,5.378296381,0.32279153,44.99999998 +174.51,50.43047617,-2.574365126,50.7902,7.084485177,7.07010573,-2.6415625,5.446254905,0.423477805,44.99999998 +174.52,50.43047681,-2.57436413,50.8164,7.077532805,7.070993841,-2.606875,5.513076051,0.523794865,44.99999998 +174.53,50.43047744,-2.574363135,50.8423,7.067104255,7.070993775,-2.573125,5.578745838,0.623655106,44.99999998 +174.54,50.43047808,-2.57436214,50.8679,7.063628105,7.071215753,-2.5378125,5.643250572,0.722971553,44.99999998 +174.55,50.43047871,-2.574361145,50.8931,7.063628138,7.072103862,-2.4996875,5.70657679,0.821657517,44.99999998 +174.56,50.43047935,-2.574360149,50.9179,7.067104355,7.072103795,-2.4596875,5.768711312,0.919626998,44.99999998 +174.57,50.43047998,-2.574359154,50.9423,7.07753296,7.070993507,-2.4184375,5.829641077,1.016794566,44.99999998 +174.58,50.43048062,-2.574358159,50.9663,7.084485373,7.070105263,-2.3765625,5.889353363,1.113075483,44.99999998 +174.59,50.43048126,-2.574357164,50.9898,7.077533014,7.06988315,-2.335,5.947835796,1.208385752,44.99999998 +174.6,50.43048189,-2.574356169,51.013,7.067104461,7.070105125,-2.293125,6.005076055,1.302642294,44.99999998 +174.61,50.43048253,-2.574355174,51.0357,7.063628294,7.070993232,-2.2496875,6.061062225,1.395762947,44.99999998 +174.62,50.43048316,-2.574354179,51.058,7.063628319,7.072103382,-2.2046875,6.115782674,1.487666409,44.99999998 +174.63,50.4304838,-2.574353183,51.0798,7.063628342,7.072103311,-2.158125,6.169225885,1.578272636,44.99999998 +174.64,50.43048443,-2.574352188,51.1012,7.06362836,7.07099302,-2.1103125,6.221380687,1.66750262,44.99999998 +174.65,50.43048507,-2.574351193,51.122,7.067104575,7.070326817,-2.063125,6.272236306,1.755278493,44.99999998 +174.66,50.4304857,-2.574350198,51.1424,7.077533189,7.070992876,-2.0165625,6.321782029,1.84152371,44.99999998 +174.67,50.43048634,-2.574349203,51.1624,7.084485612,7.072103024,-1.9675,6.370007486,1.926163156,44.99999998 +174.68,50.43048698,-2.574348207,51.1818,7.07753325,7.072102951,-1.915,6.416902706,2.009122918,44.99999998 +174.69,50.43048761,-2.574347212,51.2007,7.067104681,7.070992657,-1.861875,6.462457835,2.09033069,44.99999998 +174.7,50.43048825,-2.574346217,51.219,7.067104686,7.070104407,-1.81,6.506663306,2.169715654,44.99999998 +174.71,50.43048888,-2.574345222,51.2369,7.077533287,7.070104332,-1.7584375,6.549510006,2.247208597,44.99999998 +174.72,50.43048952,-2.574344227,51.2542,7.084485707,7.070992432,-1.7059375,6.590988885,2.322741967,44.99999998 +174.73,50.43049016,-2.574343232,51.271,7.077533344,7.072102576,-1.651875,6.631091347,2.396249874,44.99999998 +174.74,50.43049079,-2.574342236,51.2873,7.06710478,7.072102499,-1.59625,6.66980897,2.467668204,44.99999998 +174.75,50.43049143,-2.574341241,51.3029,7.063628607,7.070992201,-1.54,6.707133675,2.536934676,44.99999998 +174.76,50.43049206,-2.574340246,51.3181,7.063628621,7.070103947,-1.4834375,6.743057728,2.603988901,44.99999998 +174.77,50.4304927,-2.574339251,51.3326,7.063628624,7.069881825,-1.4265625,6.777573565,2.668772436,44.99999998 +174.78,50.43049333,-2.574338256,51.3466,7.06362864,7.07010379,-1.37,6.810673967,2.731228732,44.99999998 +174.79,50.43049397,-2.574337261,51.36,7.067104865,7.070991887,-1.3128125,6.842352058,2.791303357,44.99999998 +174.8,50.4304946,-2.574336266,51.3729,7.077533469,7.072102026,-1.2534375,6.872601251,2.848943942,44.99999998 +174.81,50.43049524,-2.57433527,51.3851,7.084485861,7.072101945,-1.193125,6.901415126,2.904100183,44.99999998 +174.82,50.43049588,-2.574334275,51.3967,7.077533473,7.070991643,-1.1334375,6.928787784,2.956724007,44.99999998 +174.83,50.43049651,-2.57433328,51.4078,7.067104905,7.070325428,-1.073125,6.954713379,3.006769579,44.99999998 +174.84,50.43049715,-2.574332285,51.4182,7.063628738,7.070991477,-1.0115625,6.979186641,3.054193124,44.99999998 +174.85,50.43049778,-2.57433129,51.428,7.063628754,7.072101613,-0.9503125,7.002202356,3.098953446,44.99999998 +174.86,50.43049842,-2.574330294,51.4372,7.067104956,7.072101529,-0.89,7.023755768,3.141011356,44.99999998 +174.87,50.43049905,-2.574329299,51.4458,7.077533551,7.070991224,-0.8296875,7.04384235,3.180330298,44.99999998 +174.88,50.43049969,-2.574328304,51.4538,7.08448595,7.070102962,-0.768125,7.062457921,3.216875953,44.99999998 +174.89,50.43050033,-2.574327309,51.4612,7.077533561,7.069880831,-0.7046875,7.079598583,3.250616463,44.99999998 +174.9,50.43050096,-2.574326314,51.4679,7.067104978,7.070102788,-0.64,7.095260786,3.281522322,44.99999998 +174.91,50.4305016,-2.574325319,51.474,7.063628794,7.070990876,-0.5753125,7.109441205,3.309566716,44.99999998 +174.92,50.43050223,-2.574324324,51.4794,7.063628805,7.072101007,-0.5115625,7.122136918,3.334725063,44.99999998 +174.93,50.43050287,-2.574323328,51.4842,7.067105,7.072100919,-0.4484375,7.133345233,3.356975478,44.99999998 +174.94,50.4305035,-2.574322333,51.4884,7.077533584,7.071212653,-0.385,7.143063858,3.376298594,44.99999998 +174.95,50.43050414,-2.574321338,51.4919,7.084485986,7.070990517,-0.3215625,7.151290787,3.39267751,44.99999998 +174.96,50.43050478,-2.574320343,51.4948,7.077533615,7.070990426,-0.2584375,7.158024244,3.406097957,44.99999998 +174.97,50.43050541,-2.574319347,51.4971,7.067105035,7.070102158,-0.1946875,7.163262797,3.416548249,44.99999998 +174.98,50.43050605,-2.574318353,51.4987,7.063628838,7.069880021,-0.13,7.167005415,3.424019275,44.99999998 +174.99,50.43050668,-2.574317358,51.4997,7.063628837,7.071212191,-0.065,7.169251295,3.428504503,44.99999998 +175,50.43050732,-2.574316362,51.5,7.063628836,7.071878229,-1.56E-12,7.169999979,3.42999998,44.99999998 +175.01,50.43050795,-2.574315367,51.4997,7.06362883,7.071212002,0.065,7.169251295,3.428504503,44.99999998 +175.02,50.43050859,-2.574314372,51.4987,7.067105021,7.071211906,0.13,7.167005415,3.424019275,44.99999998 +175.03,50.43050922,-2.574313377,51.4971,7.077533611,7.072099985,0.1946875,7.163262797,3.416548249,44.99999998 +175.04,50.43050986,-2.574312381,51.4948,7.08448601,7.072099888,0.2584375,7.158024244,3.406097957,44.99999998 +175.05,50.4305105,-2.574311386,51.4919,7.077533623,7.070989571,0.3215625,7.151290787,3.39267751,44.99999998 +175.06,50.43051113,-2.574310391,51.4884,7.067105028,7.070101296,0.385,7.143063858,3.376298594,44.99999998 +175.07,50.43051177,-2.574309396,51.4842,7.063628815,7.069879153,0.4484375,7.133345233,3.356975478,44.99999998 +175.08,50.4305124,-2.574308401,51.4794,7.063628811,7.070101098,0.5115625,7.122136918,3.334725063,44.99999998 +175.09,50.43051304,-2.574307406,51.474,7.067105015,7.070989173,0.5753125,7.109441205,3.309566716,44.99999998 +175.1,50.43051367,-2.574306411,51.4679,7.0775336,7.072099291,0.64,7.095260786,3.281522322,44.99999998 +175.11,50.43051431,-2.574305415,51.4612,7.084485978,7.072099188,0.7046875,7.079598583,3.250616463,44.99999998 +175.12,50.43051495,-2.57430442,51.4538,7.077533568,7.071210909,0.768125,7.062457921,3.216875953,44.99999998 +175.13,50.43051558,-2.574303425,51.4458,7.067104962,7.071210806,0.8296875,7.04384235,3.180330298,44.99999998 +175.14,50.43051622,-2.57430243,51.4372,7.06362876,7.071876834,0.89,7.023755768,3.141011356,44.99999998 +175.15,50.43051685,-2.574301434,51.428,7.063628768,7.071210598,0.9503125,7.002202356,3.098953446,44.99999998 +175.16,50.43051749,-2.574300439,51.4182,7.067104967,7.069878229,1.0115625,6.979186641,3.054193124,44.99999998 +175.17,50.43051812,-2.574299445,51.4078,7.077533539,7.070100166,1.073125,6.954713379,3.006769579,44.99999998 +175.18,50.43051876,-2.574298449,51.3967,7.084485903,7.070988234,1.1334375,6.928787784,2.956724007,44.99999998 +175.19,50.4305194,-2.574297454,51.3851,7.077533489,7.070988127,1.193125,6.901415126,2.904100183,44.99999998 +175.2,50.43052003,-2.574296459,51.3729,7.067104896,7.071210063,1.2534375,6.872601251,2.848943942,44.99999998 +175.21,50.43052067,-2.574295464,51.36,7.063628702,7.072098129,1.3128125,6.842352058,2.791303357,44.99999998 +175.22,50.4305213,-2.574294468,51.3466,7.063628692,7.07209802,1.37,6.810673967,2.731228732,44.99999998 +175.23,50.43052194,-2.574293473,51.3326,7.063628671,7.070987691,1.4265625,6.777573565,2.668772436,44.99999998 +175.24,50.43052257,-2.574292478,51.3181,7.063628647,7.070099404,1.4834375,6.743057728,2.603988901,44.99999998 +175.25,50.43052321,-2.574291483,51.3029,7.067104822,7.069877249,1.54,6.707133675,2.536934676,44.99999998 +175.26,50.43052384,-2.574290488,51.2873,7.077533396,7.070099181,1.59625,6.66980897,2.467668204,44.99999998 +175.27,50.43052448,-2.574289493,51.271,7.084485777,7.070987244,1.651875,6.631091347,2.396249874,44.99999998 +175.28,50.43052512,-2.574288498,51.2542,7.07753337,7.07209735,1.7059375,6.590988885,2.322741967,44.99999998 +175.29,50.43052575,-2.574287502,51.2369,7.067104767,7.072097236,1.7584375,6.549510006,2.247208597,44.99999998 +175.3,50.43052639,-2.574286507,51.219,7.067104753,7.071208946,1.81,6.506663306,2.169715654,44.99999998 +175.31,50.43052702,-2.574285512,51.2007,7.077533315,7.071208831,1.861875,6.462457835,2.09033069,44.99999998 +175.32,50.43052766,-2.574284517,51.1818,7.084485671,7.07209689,1.915,6.416902706,2.009122918,44.99999998 +175.33,50.4305283,-2.574283521,51.1624,7.077533252,7.072096774,1.9675,6.370007486,1.926163156,44.99999998 +175.34,50.43052893,-2.574282526,51.1424,7.067104655,7.070986438,2.0165625,6.321782029,1.84152371,44.99999998 +175.35,50.43052957,-2.574281531,51.122,7.063628454,7.070098146,2.063125,6.272236306,1.755278493,44.99999998 +175.36,50.4305302,-2.574280536,51.1012,7.063628436,7.069875984,2.1103125,6.221380687,1.66750262,44.99999998 +175.37,50.43053084,-2.574279541,51.0798,7.063628399,7.07009791,2.158125,6.169225885,1.578272636,44.99999998 +175.38,50.43053147,-2.574278546,51.058,7.063628358,7.070985967,2.2046875,6.115782674,1.487666409,44.99999998 +175.39,50.43053211,-2.574277551,51.0357,7.06710453,7.072096067,2.2496875,6.061062225,1.395762947,44.99999998 +175.4,50.43053274,-2.574276555,51.013,7.077533109,7.072095947,2.293125,6.005076055,1.302642294,44.99999998 +175.41,50.43053338,-2.57427556,50.9898,7.084485489,7.070985608,2.335,5.947835796,1.208385752,44.99999998 +175.42,50.43053402,-2.574274565,50.9663,7.077533068,7.070319355,2.3765625,5.889353363,1.113075483,44.99999998 +175.43,50.43053465,-2.57427357,50.9423,7.067104441,7.070763321,2.4184375,5.829641077,1.016794566,44.99999998 +175.44,50.43053529,-2.574272575,50.9179,7.063628208,7.071207287,2.4596875,5.768711312,0.919626998,44.99999998 +175.45,50.43053592,-2.574271579,50.8931,7.063628188,7.070985122,2.4996875,5.70657679,0.821657517,44.99999998 +175.46,50.43053656,-2.574270585,50.8679,7.067104371,7.070984999,2.5378125,5.643250572,0.722971553,44.99999998 +175.47,50.43053719,-2.574269589,50.8423,7.077532934,7.07120692,2.573125,5.578745838,0.623655106,44.99999998 +175.48,50.43053783,-2.574268594,50.8164,7.08448529,7.070762709,2.606875,5.513076051,0.523794865,44.99999998 +175.49,50.43053847,-2.574267599,50.7902,7.077532863,7.070318498,2.6415625,5.446254905,0.423477805,44.99999998 +175.5,50.4305391,-2.574266604,50.7636,7.067104243,7.070984505,2.6765625,5.378296381,0.32279153,44.99999998 +175.51,50.43053974,-2.574265609,50.7366,7.063628024,7.072094599,2.709375,5.309214688,0.221823762,44.99999998 +175.52,50.43054037,-2.574264613,50.7094,7.063628001,7.072094474,2.74,5.239024207,0.120662505,44.99999998 +175.53,50.43054101,-2.574263618,50.6818,7.067104168,7.07098413,2.7696875,5.167739605,0.019396111,44.99999998 +175.54,50.43054164,-2.574262623,50.654,7.077532724,7.070095829,2.798125,5.095375838,-0.081887243,44.99999998 +175.55,50.43054228,-2.574261628,50.6258,7.084485082,7.06987366,2.825,5.021947973,-0.183099206,44.99999998 +175.56,50.43054292,-2.574260633,50.5975,7.077532654,7.070095578,2.85125,4.94747131,-0.284151486,44.99999998 +175.57,50.43054355,-2.574259638,50.5688,7.067104033,7.070983627,2.876875,4.871961431,-0.384955961,44.99999998 +175.58,50.43054419,-2.574258643,50.5399,7.063627811,7.072093719,2.9009375,4.795434094,-0.485424741,44.99999998 +175.59,50.43054482,-2.574257647,50.5108,7.063627788,7.072093592,2.9234375,4.717905284,-0.585470277,44.99999998 +175.6,50.43054546,-2.574256652,50.4814,7.063627763,7.071205289,2.9446875,4.639391273,-0.68500525,44.99999998 +175.61,50.43054609,-2.574255657,50.4519,7.063627727,7.071205162,2.9646875,4.559908333,-0.783942857,44.99999998 +175.62,50.43054673,-2.574254662,50.4221,7.067103874,7.071871166,2.9834375,4.47947308,-0.882196868,44.99999998 +175.63,50.43054736,-2.574253666,50.3922,7.07753242,7.071204908,3.00125,4.398102416,-0.979681626,44.99999998 +175.64,50.430548,-2.574252671,50.3621,7.084484789,7.069872517,3.018125,4.315813186,-1.076312047,44.99999998 +175.65,50.43054864,-2.574251677,50.3318,7.077532382,7.070094432,3.033125,4.232622694,-1.172003906,44.99999998 +175.66,50.43054927,-2.574250681,50.3014,7.067103768,7.070982479,3.04625,4.148548299,-1.266673779,44.99999998 +175.67,50.43054991,-2.574249686,50.2709,7.063627527,7.07098235,3.0584375,4.063607535,-1.360239105,44.99999998 +175.68,50.43055054,-2.574248691,50.2402,7.063627476,7.071204266,3.0696875,3.977818106,-1.452618294,44.99999998 +175.69,50.43055118,-2.574247696,50.2095,7.067103635,7.072092312,3.0796875,3.891197946,-1.54373073,44.99999998 +175.7,50.43055181,-2.5742467,50.1786,7.077532198,7.072092183,3.088125,3.803765216,-1.633497059,44.99999998 +175.71,50.43055245,-2.574245705,50.1477,7.084484565,7.071203879,3.094375,3.715538081,-1.7218389,44.99999998 +175.72,50.43055309,-2.57424471,50.1167,7.077532148,7.070981706,3.0984375,3.626534989,-1.808679306,44.99999998 +175.73,50.43055372,-2.574243715,50.0857,7.067103525,7.070981578,3.1015625,3.536774562,-1.89394253,44.99999998 +175.74,50.43055436,-2.574242719,50.0547,7.063627284,7.070093274,3.105,3.446275534,-1.977554147,44.99999998 +175.75,50.43055499,-2.574241725,50.0236,7.06362725,7.069871101,3.108125,3.355056757,-2.05944139,44.99999998 +175.76,50.43055563,-2.57424073,49.9925,7.067103424,7.071203234,3.1096875,3.263137367,-2.139532696,44.99999998 +175.77,50.43055626,-2.574239734,49.9614,7.07753198,7.071869236,3.1096875,3.170536501,-2.217758337,44.99999998 +175.78,50.4305569,-2.574238739,49.9303,7.084484329,7.071202976,3.1078125,3.077273468,-2.294050074,44.99999998 +175.79,50.43055754,-2.574237744,49.8992,7.077531897,7.071202846,3.103125,2.983367805,-2.368341329,44.99999998 +175.8,50.43055817,-2.574236749,49.8682,7.067103274,7.072090893,3.0965625,2.888839166,-2.440567357,44.99999998 +175.81,50.43055881,-2.574235753,49.8373,7.06362705,7.072090764,3.09,2.793707144,-2.510665191,44.99999998 +175.82,50.43055944,-2.574234758,49.8064,7.063627024,7.070980417,3.083125,2.697991737,-2.578573696,44.99999998 +175.83,50.43056008,-2.574233763,49.7756,7.067103187,7.070092113,3.0746875,2.601712883,-2.644233628,44.99999998 +175.84,50.43056071,-2.574232768,49.7449,7.07753174,7.069869941,3.0646875,2.504890693,-2.707587749,44.99999998 +175.85,50.43056135,-2.574231773,49.7143,7.084484101,7.070091856,3.053125,2.407545393,-2.768580825,44.99999998 +175.86,50.43056199,-2.574230778,49.6838,7.077531674,7.070979903,3.0396875,2.309697322,-2.827159686,44.99999998 +175.87,50.43056262,-2.574229783,49.6535,7.067103042,7.072089992,3.025,2.211366879,-2.883273167,44.99999998 +175.88,50.43056326,-2.574228787,49.6233,7.063626808,7.072089864,3.0096875,2.112574631,-2.936872395,44.99999998 +175.89,50.43056389,-2.574227792,49.5933,7.063626784,7.070979518,2.993125,2.013341148,-2.987910673,44.99999998 +175.9,50.43056453,-2.574226797,49.5634,7.067102955,7.07031326,2.9746875,1.913687286,-3.036343426,44.99999998 +175.91,50.43056516,-2.574225802,49.5338,7.077531509,7.070757219,2.9546875,1.813633729,-3.082128426,44.99999998 +175.92,50.4305658,-2.574224807,49.5043,7.084483864,7.071201179,2.9334375,1.71320139,-3.125225738,44.99999998 +175.93,50.43056644,-2.574223811,49.4751,7.077531437,7.070979008,2.9115625,1.612411353,-3.165597834,44.99999998 +175.94,50.43056707,-2.574222817,49.4461,7.067102817,7.070978881,2.8896875,1.511284531,-3.203209534,44.99999998 +175.95,50.43056771,-2.574221821,49.4173,7.063626596,7.071200799,2.86625,1.409842067,-3.23802795,44.99999998 +175.96,50.43056834,-2.574220826,49.3887,7.063626574,7.070978629,2.8396875,1.308105217,-3.270022715,44.99999998 +175.97,50.43056898,-2.574219831,49.3605,7.06362655,7.071200547,2.8115625,1.206095181,-3.299166042,44.99999998 +175.98,50.43056961,-2.574218836,49.3325,7.063626515,7.072088596,2.7834375,1.103833273,-3.325432375,44.99999998 +175.99,50.43057025,-2.57421784,49.3048,7.067102664,7.072088471,2.7546875,1.001340863,-3.348798912,44.99999998 +176,50.43057088,-2.574216845,49.2774,7.077531212,7.070978128,2.7246875,0.898639267,-3.369245255,44.99999998 +176.01,50.43057152,-2.57421585,49.2503,7.084483582,7.070089828,2.693125,0.795750085,-3.386753584,44.99999998 +176.02,50.43057216,-2.574214855,49.2235,7.07753118,7.06986766,2.66,0.69269463,-3.401308603,44.99999998 +176.03,50.43057279,-2.57421386,49.1971,7.067102573,7.07008958,2.6265625,0.589494618,-3.412897591,44.99999998 +176.04,50.43057343,-2.574212865,49.171,7.063626339,7.070977631,2.5928125,0.48617142,-3.421510522,44.99999998 +176.05,50.43057406,-2.57421187,49.1452,7.0636263,7.072087726,2.5565625,0.382746693,-3.427139832,44.99999998 +176.06,50.4305747,-2.574210874,49.1198,7.067102469,7.072087603,2.518125,0.279242097,-3.429780652,44.99999998 +176.07,50.43057533,-2.574209879,49.0949,7.077531032,7.070977263,2.48,0.175679116,-3.429430632,44.99999998 +176.08,50.43057597,-2.574208884,49.0702,7.084483397,7.07031101,2.44125,0.072079466,-3.426090059,44.99999998 +176.09,50.43057661,-2.574207889,49.046,7.07753098,7.070977019,2.3996875,-0.031535196,-3.419761912,44.99999998 +176.1,50.43057724,-2.574206894,49.0222,7.067102362,7.072087116,2.356875,-0.135143326,-3.410451692,44.99999998 +176.11,50.43057788,-2.574205898,48.9989,7.063626134,7.072086996,2.3146875,-0.238723209,-3.398167534,44.99999998 +176.12,50.43057851,-2.574204903,48.9759,7.063626116,7.070976658,2.2715625,-0.342253245,-3.382920096,44.99999998 +176.13,50.43057915,-2.574203908,48.9534,7.067102301,7.070088364,2.22625,-0.445711776,-3.36472267,44.99999998 +176.14,50.43057978,-2.574202913,48.9314,7.077530865,7.069866202,2.1803125,-0.549077258,-3.343591184,44.99999998 +176.15,50.43058042,-2.574201918,48.9098,7.084483224,7.070088127,2.135,-0.652328034,-3.319544031,44.99999998 +176.16,50.43058106,-2.574200923,48.8887,7.077530804,7.070976183,2.089375,-0.755442618,-3.292602237,44.99999998 +176.17,50.43058169,-2.574199928,48.868,7.067102194,7.072086282,2.0415625,-0.858399467,-3.262789181,44.99999998 +176.18,50.43058233,-2.574198932,48.8478,7.063625983,7.072086165,1.99125,-0.96117698,-3.23013093,44.99999998 +176.19,50.43058296,-2.574197937,48.8282,7.063625968,7.071197875,1.9403125,-1.063753786,-3.194655962,44.99999998 +176.2,50.4305836,-2.574196942,48.809,7.06362595,7.070975716,1.89,-1.166108456,-3.156395215,44.99999998 +176.21,50.43058423,-2.574195947,48.7904,7.063625933,7.070975601,1.839375,-1.26821962,-3.115382094,44.99999998 +176.22,50.43058487,-2.574194951,48.7722,7.067102112,7.070087312,1.786875,-1.370065904,-3.071652236,44.99999998 +176.23,50.4305855,-2.574193957,48.7546,7.077530671,7.069865154,1.7328125,-1.471626054,-3.025243858,44.99999998 +176.24,50.43058614,-2.574192962,48.7376,7.084483026,7.071197301,1.67875,-1.572878926,-2.976197468,44.99999998 +176.25,50.43058678,-2.574191966,48.721,7.077530614,7.071863319,1.6246875,-1.673803265,-2.92455575,44.99999998 +176.26,50.43058741,-2.574190971,48.7051,7.067102025,7.071197077,1.5696875,-1.774378042,-2.870363798,44.99999998 +176.27,50.43058805,-2.574189976,48.6896,7.063625828,7.071196965,1.5134375,-1.874582344,-2.813668822,44.99999998 +176.28,50.43058868,-2.574188981,48.6748,7.06362581,7.072085028,1.45625,-1.974395087,-2.754520326,44.99999998 +176.29,50.43058932,-2.574187985,48.6605,7.067101974,7.072084917,1.39875,-2.073795529,-2.692969819,44.99999998 +176.3,50.43058995,-2.57418699,48.6468,7.077530535,7.07097459,1.34125,-2.172762873,-2.629070987,44.99999998 +176.31,50.43059059,-2.574185995,48.6337,7.084482921,7.070086306,1.2834375,-2.271276492,-2.562879637,44.99999998 +176.32,50.43059123,-2.574185,48.6211,7.077530535,7.069864154,1.2246875,-2.369315758,-2.49445335,44.99999998 +176.33,50.43059186,-2.574184005,48.6092,7.067101946,7.07008609,1.1646875,-2.466860219,-2.423851886,44.99999998 +176.34,50.4305925,-2.57418301,48.5978,7.063625734,7.070974157,1.10375,-2.563889533,-2.351136781,44.99999998 +176.35,50.43059313,-2.574182015,48.5871,7.063625707,7.072084268,1.043125,-2.660383417,-2.276371461,44.99999998 +176.36,50.43059377,-2.574181019,48.577,7.06710188,7.072084162,0.9834375,-2.756321705,-2.199621072,44.99999998 +176.37,50.4305944,-2.574180024,48.5674,7.077530459,7.071195883,0.9228125,-2.851684342,-2.120952591,44.99999998 +176.38,50.43059504,-2.574179029,48.5585,7.084482854,7.071195778,0.86,-2.946451447,-2.040434661,44.99999998 +176.39,50.43059568,-2.574178034,48.5502,7.077530461,7.072083848,0.796875,-3.040603252,-1.958137409,44.99999998 +176.4,50.43059631,-2.574177038,48.5426,7.067101865,7.072083745,0.735,-3.134120049,-1.874132629,44.99999998 +176.41,50.43059695,-2.574176043,48.5355,7.063625655,7.070973425,0.673125,-3.226982298,-1.788493544,44.99999998 +176.42,50.43059758,-2.574175048,48.5291,7.063625644,7.07008515,0.6096875,-3.319170691,-1.701294926,44.99999998 +176.43,50.43059822,-2.574174053,48.5233,7.067101837,7.069863005,0.5453125,-3.410665863,-1.61261269,44.99999998 +176.44,50.43059885,-2.574173058,48.5182,7.077530421,7.070084949,0.4815625,-3.501448791,-1.522524301,44.99999998 +176.45,50.43059949,-2.574172063,48.5137,7.084482807,7.070973023,0.4184375,-3.591500511,-1.431108198,44.99999998 +176.46,50.43060013,-2.574171068,48.5098,7.077530415,7.07208314,0.355,-3.680802171,-1.338444192,44.99999998 +176.47,50.43060076,-2.574170072,48.5066,7.067101828,7.072083042,0.2915625,-3.769335094,-1.244613014,44.99999998 +176.48,50.4306014,-2.574169077,48.504,7.063625625,7.070972727,0.228125,-3.857080887,-1.149696481,44.99999998 +176.49,50.43060203,-2.574168082,48.502,7.063625619,7.0703065,0.163125,-3.944021217,-1.053777445,44.99999998 +176.5,50.43060267,-2.574167087,48.5007,7.067101817,7.070750491,0.096875,-4.030137805,-0.956939499,44.99999998 +176.51,50.4306033,-2.574166092,48.5001,7.077530408,7.071194483,0.031875,-4.115412775,-0.859267097,44.99999998 +176.52,50.43060394,-2.574165096,48.5001,7.084482804,7.070972345,-0.0315625,-4.199828308,-0.760845324,44.99999998 +176.53,50.43060458,-2.574164102,48.5007,7.077530413,7.070972251,-0.0953125,-4.283366815,-0.66176018,44.99999998 +176.54,50.43060521,-2.574163106,48.502,7.067101817,7.071194201,-0.16,-4.366010706,-0.562097896,44.99999998 +176.55,50.43060585,-2.574162111,48.5039,7.063625619,7.070972065,-0.2246875,-4.447742849,-0.461945503,44.99999998 +176.56,50.43060648,-2.574161116,48.5065,7.063625634,7.071194017,-0.2884375,-4.528546113,-0.361390264,44.99999998 +176.57,50.43060712,-2.574160121,48.5097,7.063625654,7.072082099,-0.351875,-4.60840371,-0.260519899,44.99999998 +176.58,50.43060775,-2.574159125,48.5135,7.063625663,7.072082008,-0.4165625,-4.687298852,-0.159422355,44.99999998 +176.59,50.43060839,-2.57415813,48.518,7.06710185,7.070971702,-0.4815625,-4.765215097,-0.058185812,44.99999998 +176.6,50.43060902,-2.574157135,48.5232,7.077530421,7.070083439,-0.5446875,-4.842136228,0.043101495,44.99999998 +176.61,50.43060966,-2.57415614,48.5289,7.084482816,7.069861307,-0.606875,-4.918046145,0.144351216,44.99999998 +176.62,50.4306103,-2.574155145,48.5353,7.077530454,7.070083263,-0.6703125,-4.992928979,0.245475058,44.99999998 +176.63,50.43061093,-2.57415415,48.5423,7.067101893,7.07097135,-0.734375,-5.066769087,0.346384844,44.99999998 +176.64,50.43061157,-2.574153155,48.55,7.063625704,7.072081481,-0.796875,-5.139551056,0.446992623,44.99999998 +176.65,50.4306122,-2.574152159,48.5583,7.063625698,7.072081395,-0.858125,-5.211259703,0.547210562,44.99999998 +176.66,50.43061284,-2.574151164,48.5671,7.06710189,7.070971094,-0.92,-5.281880075,0.646951341,44.99999998 +176.67,50.43061347,-2.574150169,48.5767,7.077530484,7.070304879,-0.9815625,-5.351397388,0.746127929,44.99999998 +176.68,50.43061411,-2.574149174,48.5868,7.084482897,7.070970926,-1.0415625,-5.419797089,0.844653923,44.99999998 +176.69,50.43061475,-2.574148179,48.5975,7.077530537,7.07208106,-1.101875,-5.48706497,0.94244338,44.99999998 +176.7,50.43061538,-2.574147183,48.6088,7.067101972,7.072080977,-1.163125,-5.553186935,1.039410987,44.99999998 +176.71,50.43061602,-2.574146188,48.6208,7.063625781,7.070970679,-1.223125,-5.618149177,1.135472231,44.99999998 +176.72,50.43061665,-2.574145193,48.6333,7.063625785,7.070082425,-1.2815625,-5.681938172,1.23054329,44.99999998 +176.73,50.43061729,-2.574144198,48.6464,7.067101997,7.069860302,-1.34,-5.744540572,1.324541314,44.99999998 +176.74,50.43061792,-2.574143203,48.6601,7.077530602,7.070082266,-1.398125,-5.805943256,1.417384311,44.99999998 +176.75,50.43061856,-2.574142208,48.6744,7.084483009,7.07097036,-1.4546875,-5.866133446,1.508991325,44.99999998 +176.76,50.4306192,-2.574141213,48.6892,7.07753064,7.072080498,-1.5103125,-5.925098596,1.59928254,44.99999998 +176.77,50.43061983,-2.574140217,48.7046,7.06710208,7.07208042,-1.5665625,-5.982826385,1.688179062,44.99999998 +176.78,50.43062047,-2.574139222,48.7205,7.063625899,7.07119217,-1.623125,-6.039304726,1.775603541,44.99999998 +176.79,50.4306211,-2.574138227,48.7371,7.063625903,7.07097005,-1.678125,-6.094521815,1.861479659,44.99999998 +176.8,50.43062174,-2.574137232,48.7541,7.06710211,7.070969975,-1.73125,-6.148466135,1.945732472,44.99999998 +176.81,50.43062237,-2.574136236,48.7717,7.077530724,7.070081726,-1.78375,-6.201126399,2.028288643,44.99999998 +176.82,50.43062301,-2.574135242,48.7898,7.084483147,7.069859608,-1.83625,-6.252491722,2.109076093,44.99999998 +176.83,50.43062365,-2.574134247,48.8084,7.077530778,7.071191794,-1.8884375,-6.302551216,2.188024406,44.99999998 +176.84,50.43062428,-2.574133251,48.8276,7.067102201,7.071857851,-1.9396875,-6.351294569,2.265064712,44.99999998 +176.85,50.43062492,-2.574132256,48.8472,7.063626023,7.071191648,-1.9896875,-6.398711468,2.340129861,44.99999998 +176.86,50.43062555,-2.574131261,48.8674,7.063626055,7.071191575,-2.0384375,-6.444792114,2.413154421,44.99999998 +176.87,50.43062619,-2.574130266,48.888,7.067102282,7.072079677,-2.0865625,-6.489526825,2.484074621,44.99999998 +176.88,50.43062682,-2.57412927,48.9091,7.077530893,7.072079606,-2.1346875,-6.53290632,2.552828697,44.99999998 +176.89,50.43062746,-2.574128275,48.9307,7.084483311,7.070969318,-2.1815625,-6.574921487,2.61935666,44.99999998 +176.9,50.4306281,-2.57412728,48.9528,7.077530943,7.070081074,-2.22625,-6.61556356,2.683600469,44.99999998 +176.91,50.43062873,-2.574126285,48.9752,7.067102371,7.069858961,-2.27,-6.654824061,2.745504205,44.99999998 +176.92,50.43062937,-2.57412529,48.9982,7.063626196,7.070080935,-2.3134375,-6.692694737,2.805013779,44.99999998 +176.93,50.43063,-2.574124295,49.0215,7.063626233,7.07096904,-2.35625,-6.729167798,2.862077338,44.99999998 +176.94,50.43063064,-2.5741233,49.0453,7.063626276,7.072079188,-2.3984375,-6.764235508,2.916645151,44.99999998 +176.95,50.43063127,-2.574122304,49.0695,7.063626308,7.07207912,-2.439375,-6.797890648,2.968669547,44.99999998 +176.96,50.43063191,-2.574121309,49.0941,7.067102517,7.07119088,-2.4784375,-6.830126113,3.018105262,44.99999998 +176.97,50.43063254,-2.574120314,49.1191,7.077531111,7.071190813,-2.5165625,-6.8609352,3.064909153,44.99999998 +176.98,50.43063318,-2.574119319,49.1444,7.084483529,7.072078919,-2.5546875,-6.890311433,3.109040368,44.99999998 +176.99,50.43063382,-2.574118323,49.1702,7.077531187,7.072078852,-2.5915625,-6.918248741,3.150460518,44.99999998 +177,50.43063445,-2.574117328,49.1963,7.067102647,7.070968569,-2.6259375,-6.944741278,3.189133336,44.99999998 +177.01,50.43063509,-2.574116333,49.2227,7.06362648,7.070080331,-2.6584375,-6.969783487,3.225025246,44.99999998 +177.02,50.43063572,-2.574115338,49.2495,7.063626502,7.069858223,-2.69,-6.993370097,3.25810485,44.99999998 +177.03,50.43063636,-2.574114343,49.2765,7.067102718,7.070080203,-2.7215625,-7.015496294,3.288343327,44.99999998 +177.04,50.43063699,-2.574113348,49.3039,7.077531329,7.070968311,-2.7534375,-7.036157382,3.315714381,44.99999998 +177.05,50.43063763,-2.574112353,49.3316,7.084483754,7.072078463,-2.784375,-7.055349004,3.340194003,44.99999998 +177.06,50.43063827,-2.574111357,49.3596,7.077531403,7.072078399,-2.813125,-7.073067266,3.361760993,44.99999998 +177.07,50.4306389,-2.574110362,49.3879,7.067102851,7.070968119,-2.8396875,-7.089308385,3.380396446,44.99999998 +177.08,50.43063954,-2.574109367,49.4164,7.063626683,7.070301926,-2.8646875,-7.104068981,3.396084145,44.99999998 +177.09,50.43064017,-2.574108372,49.4452,7.063626711,7.07074595,-2.8884375,-7.117346017,3.408810397,44.99999998 +177.1,50.43064081,-2.574107377,49.4742,7.067102943,7.071189975,-2.91125,-7.129136686,3.418564144,44.99999998 +177.11,50.43064144,-2.574106381,49.5034,7.077531567,7.070967869,-2.9334375,-7.139438467,3.425336849,44.99999998 +177.12,50.43064208,-2.574105387,49.5329,7.084483992,7.070967806,-2.9546875,-7.148249355,3.429122553,44.99999998 +177.13,50.43064272,-2.574104391,49.5625,7.077531636,7.071189787,-2.9746875,-7.155567344,3.429918105,44.99999998 +177.14,50.43064335,-2.574103396,49.5924,7.067103084,7.070967683,-2.993125,-7.161391059,3.427722645,44.99999998 +177.15,50.43064399,-2.574102401,49.6224,7.063626916,7.071189665,-3.0096875,-7.165719125,3.422538179,44.99999998 +177.16,50.43064462,-2.574101406,49.6526,7.063626946,7.072077777,-3.025,-7.168550797,3.414369233,44.99999998 +177.17,50.43064526,-2.57410041,49.6829,7.063626985,7.072077716,-3.0396875,-7.169885387,3.403222855,44.99999998 +177.18,50.43064589,-2.574099415,49.7134,7.063627028,7.070967438,-3.053125,-7.16972261,3.389108842,44.99999998 +177.19,50.43064653,-2.57409842,49.744,7.067103264,7.070079204,-3.064375,-7.168062522,3.372039512,44.99999998 +177.2,50.43064716,-2.574097425,49.7747,7.077531879,7.0698571,-3.0734375,-7.164905525,3.352029649,44.99999998 +177.21,50.4306478,-2.57409643,49.8055,7.084484288,7.070079083,-3.0815625,-7.160252191,3.329096841,44.99999998 +177.22,50.43064844,-2.574095435,49.8363,7.077531927,7.070967196,-3.0896875,-7.154103551,3.303260914,44.99999998 +177.23,50.43064907,-2.57409444,49.8673,7.067103389,7.072077351,-3.0965625,-7.146460867,3.274544556,44.99999998 +177.24,50.43064971,-2.574093444,49.8983,7.063627244,7.072077291,-3.10125,-7.137325743,3.242972748,44.99999998 +177.25,50.43065034,-2.574092449,49.9293,7.063627286,7.070967014,-3.105,-7.126700069,3.208573049,44.99999998 +177.26,50.43065098,-2.574091454,49.9604,7.06710351,7.070300824,-3.108125,-7.114586079,3.171375369,44.99999998 +177.27,50.43065161,-2.574090459,49.9915,7.077532114,7.070966894,-3.1096875,-7.100986296,3.131412193,44.99999998 +177.28,50.43065225,-2.574089464,50.0226,7.084484528,7.07207705,-3.1096875,-7.085903526,3.088718414,44.99999998 +177.29,50.43065289,-2.574088468,50.0537,7.07753218,7.072076989,-3.108125,-7.069340977,3.043331219,44.99999998 +177.3,50.43065352,-2.574087473,50.0848,7.067103646,7.070966712,-3.1046875,-7.051302146,2.995290198,44.99999998 +177.31,50.43065416,-2.574086478,50.1158,7.063627489,7.070078479,-3.1,-7.031790641,2.944637233,44.99999998 +177.32,50.43065479,-2.574085483,50.1468,7.06362751,7.069856376,-3.0946875,-7.010810703,2.891416559,44.99999998 +177.33,50.43065543,-2.574084488,50.1777,7.06710373,7.070078359,-3.088125,-6.988366628,2.835674469,44.99999998 +177.34,50.43065606,-2.574083493,50.2086,7.077532356,7.070966471,-3.0796875,-6.964463173,2.777459608,44.99999998 +177.35,50.4306567,-2.574082498,50.2393,7.084484797,7.072076626,-3.0696875,-6.939105207,2.716822797,44.99999998 +177.36,50.43065734,-2.574081502,50.27,7.077532446,7.072076566,-3.0584375,-6.912298116,2.653816863,44.99999998 +177.37,50.43065797,-2.574080507,50.3005,7.067103891,7.071188332,-3.04625,-6.884047515,2.588496752,44.99999998 +177.38,50.43065861,-2.574079512,50.3309,7.063627728,7.071188271,-3.033125,-6.854359248,2.520919474,44.99999998 +177.39,50.43065924,-2.574078517,50.3612,7.06362776,7.07185434,-3.018125,-6.823239504,2.451143872,44.99999998 +177.4,50.43065988,-2.574077521,50.3913,7.067103983,7.071188149,-3.00125,-6.790694871,2.37923085,44.99999998 +177.41,50.43066051,-2.574076526,50.4212,7.077532598,7.069855827,-2.9834375,-6.756732053,2.305243091,44.99999998 +177.42,50.43066115,-2.574075532,50.451,7.084485026,7.070077808,-2.9646875,-6.721358154,2.229245167,44.99999998 +177.43,50.43066179,-2.574074536,50.4805,7.077532678,7.070965919,-2.9446875,-6.684580624,2.151303255,44.99999998 +177.44,50.43066242,-2.574073541,50.5099,7.067104133,7.070965858,-2.9234375,-6.646407081,2.071485421,44.99999998 +177.45,50.43066306,-2.574072546,50.539,7.063627966,7.071187839,-2.90125,-6.606845549,1.989861166,44.99999998 +177.46,50.43066369,-2.574071551,50.5679,7.063627983,7.072075949,-2.878125,-6.565904219,1.906501765,44.99999998 +177.47,50.43066433,-2.574070555,50.5966,7.067104205,7.072075885,-2.853125,-6.523591745,1.821479871,44.99999998 +177.48,50.43066496,-2.57406956,50.625,7.077532834,7.071187649,-2.82625,-6.479916891,1.734869622,44.99999998 +177.49,50.4306656,-2.574068565,50.6531,7.084485272,7.070965542,-2.7984375,-6.434888768,1.646746479,44.99999998 +177.5,50.43066624,-2.57406757,50.681,7.077532917,7.070965479,-2.77,-6.388516773,1.557187389,44.99999998 +177.51,50.43066687,-2.574066574,50.7085,7.067104349,7.070077242,-2.74125,-6.340810645,1.466270446,44.99999998 +177.52,50.43066751,-2.57406558,50.7358,7.063628167,7.069855134,-2.71125,-6.291780355,1.374074833,44.99999998 +177.53,50.43066814,-2.574064585,50.7628,7.063628198,7.071187328,-2.678125,-6.241436043,1.280681051,44.99999998 +177.54,50.43066878,-2.574063589,50.7894,7.063628246,7.071853393,-2.643125,-6.189788309,1.186170459,44.99999998 +177.55,50.43066941,-2.574062594,50.8156,7.063628289,7.071187197,-2.6084375,-6.136847926,1.090625564,44.99999998 +177.56,50.43067005,-2.574061599,50.8416,7.06710451,7.071187131,-2.573125,-6.08262595,0.994129559,44.99999998 +177.57,50.43067068,-2.574060604,50.8671,7.07753311,7.072075238,-2.53625,-6.02713367,0.896766727,44.99999998 +177.58,50.43067132,-2.574059608,50.8923,7.084485516,7.072075172,-2.4984375,-5.970382716,0.798621864,44.99999998 +177.59,50.43067196,-2.574058613,50.9171,7.077533153,7.070964888,-2.4596875,-5.912384949,0.699780571,44.99999998 +177.6,50.43067259,-2.574057618,50.9415,7.067104608,7.070076647,-2.42,-5.8531524,0.600329078,44.99999998 +177.61,50.43067323,-2.574056623,50.9655,7.063628456,7.069854536,-2.3796875,-5.79269756,0.50035413,44.99999998 +177.62,50.43067386,-2.574055628,50.9891,7.063628487,7.070076511,-2.338125,-5.731032978,0.399942818,44.99999998 +177.63,50.4306745,-2.574054633,51.0123,7.067104696,7.070964615,-2.295,-5.668171486,0.299182747,44.99999998 +177.64,50.43067513,-2.574053638,51.035,7.07753329,7.072074761,-2.25125,-5.604126321,0.198161808,44.99999998 +177.65,50.43067577,-2.574052642,51.0573,7.084485707,7.072074691,-2.2065625,-5.538910775,0.096968065,44.99999998 +177.66,50.43067641,-2.574051647,51.0792,7.077533359,7.070964404,-2.1596875,-5.472538542,-0.004310247,44.99999998 +177.67,50.43067704,-2.574050652,51.1005,7.06710481,7.070298203,-2.111875,-5.405023373,-0.105584834,44.99999998 +177.68,50.43067768,-2.574049657,51.1214,7.063628638,7.070964262,-2.065,-5.336379476,-0.20676729,44.99999998 +177.69,50.43067831,-2.574048662,51.1418,7.063628659,7.072074406,-2.0178125,-5.26662112,-0.307769494,44.99999998 +177.7,50.43067895,-2.574047666,51.1618,7.067104871,7.072074333,-1.968125,-5.195762971,-0.408503266,44.99999998 +177.71,50.43067958,-2.574046671,51.1812,7.077533465,7.070964044,-1.9165625,-5.123819698,-0.508880831,44.99999998 +177.72,50.43068022,-2.574045676,51.2001,7.084485871,7.070075798,-1.865,-5.050806368,-0.60881464,44.99999998 +177.73,50.43068086,-2.574044681,51.2185,7.077533512,7.070075724,-1.813125,-4.976738223,-0.708217603,44.99999998 +177.74,50.43068149,-2.574043686,51.2364,7.067104959,7.070963821,-1.76,-4.90163079,-0.807002918,44.99999998 +177.75,50.43068213,-2.574042691,51.2537,7.063628781,7.072073961,-1.7065625,-4.82549971,-0.905084584,44.99999998 +177.76,50.43068276,-2.574041695,51.2705,7.063628785,7.072073885,-1.653125,-4.748360913,-1.002376943,44.99999998 +177.77,50.4306834,-2.5740407,51.2868,7.067104993,7.070963593,-1.598125,-4.67023044,-1.098795255,44.99999998 +177.78,50.43068403,-2.574039705,51.3025,7.077533607,7.070297386,-1.5415625,-4.591124678,-1.194255352,44.99999998 +177.79,50.43068467,-2.57403871,51.3176,7.084486025,7.070963437,-1.485,-4.511060071,-1.288674098,44.99999998 +177.8,50.43068531,-2.574037715,51.3322,7.077533655,7.072073575,-1.4284375,-4.430053407,-1.381969103,44.99999998 +177.81,50.43068594,-2.574036719,51.3462,7.067105088,7.072073495,-1.37125,-4.348121589,-1.474058947,44.99999998 +177.82,50.43068658,-2.574035724,51.3596,7.063628904,7.070963199,-1.3134375,-4.265281746,-1.564863419,44.99999998 +177.83,50.43068721,-2.574034729,51.3725,7.063628904,7.070074947,-1.255,-4.181551127,-1.654303334,44.99999998 +177.84,50.43068785,-2.574033734,51.3847,7.063628911,7.069852823,-1.19625,-4.096947262,-1.742300656,44.99999998 +177.85,50.43068848,-2.574032739,51.3964,7.063628936,7.070074784,-1.1365625,-4.011487799,-1.828778665,44.99999998 +177.86,50.43068912,-2.574031744,51.4075,7.067105158,7.070962874,-1.075,-3.925190558,-1.913661962,44.99999998 +177.87,50.43068975,-2.574030749,51.4179,7.077533755,7.072073007,-1.0134375,-3.838073643,-1.996876461,44.99999998 +177.88,50.43069039,-2.574029753,51.4277,7.084486143,7.072072923,-0.9534375,-3.75015516,-2.078349742,44.99999998 +177.89,50.43069103,-2.574028758,51.437,7.077533756,7.071184665,-0.8928125,-3.661453501,-2.158010585,44.99999998 +177.9,50.43069166,-2.574027763,51.4456,7.06710519,7.070962537,-0.83,-3.57198723,-2.235789663,44.99999998 +177.91,50.4306923,-2.574026768,51.4536,7.06362902,7.070962452,-0.766875,-3.481774968,-2.31161908,44.99999998 +177.92,50.43069293,-2.574025772,51.4609,7.063629035,7.070074193,-0.705,-3.390835565,-2.385432774,44.99999998 +177.93,50.43069357,-2.574024778,51.4677,7.067105232,7.069852063,-0.643125,-3.299188043,-2.457166288,44.99999998 +177.94,50.4306942,-2.574023783,51.4738,7.077533812,7.071184233,-0.5796875,-3.20685154,-2.526757112,44.99999998 +177.95,50.43069484,-2.574022787,51.4793,7.084486199,7.071850274,-0.515,-3.113845307,-2.594144626,44.99999998 +177.96,50.43069548,-2.574021792,51.4841,7.07753382,7.071184055,-0.4503125,-3.020188823,-2.659269931,44.99999998 +177.97,50.43069611,-2.574020797,51.4883,7.067105254,7.071183965,-0.3865625,-2.925901571,-2.722076362,44.99999998 +177.98,50.43069675,-2.574019802,51.4918,7.063629067,7.072072047,-0.3234375,-2.831003316,-2.782509085,44.99999998 +177.99,50.43069738,-2.574018806,51.4948,7.063629065,7.072071956,-0.26,-2.735513826,-2.840515447,44.99999998 +178,50.43069802,-2.574017811,51.497,7.067105255,7.070961648,-0.19625,-2.63945304,-2.896044797,44.99999998 +178.01,50.43069865,-2.574016816,51.4987,7.07753384,7.070073383,-0.131875,-2.542841068,-2.949048779,44.99999998 +178.02,50.43069929,-2.574015821,51.4997,7.084486238,7.069851246,-0.06625,-2.445698022,-2.999481097,44.99999998 +178.03,50.43069993,-2.574014826,51.5,7.077533855,7.070073195,-0.000625,-2.348044242,-3.047297863,44.99999998 +178.04,50.43070056,-2.574013831,51.4997,7.06710527,7.070961272,0.0634375,-2.249900124,-3.092457365,44.99999998 +178.05,50.4307012,-2.574012836,51.4987,7.063629074,7.072071391,0.126875,-2.151286123,-3.134920127,44.99999998 +178.06,50.43070183,-2.57401184,51.4972,7.063629071,7.072071295,0.1915625,-2.052222866,-3.17464925,44.99999998 +178.07,50.43070247,-2.574010845,51.4949,7.067105258,7.071183026,0.2565625,-1.952731037,-3.211610012,44.99999998 +178.08,50.4307031,-2.57400985,51.492,7.077533839,7.071182928,0.3196875,-1.852831376,-3.245770214,44.99999998 +178.09,50.43070374,-2.574008855,51.4885,7.084486231,7.072071002,0.3821875,-1.752544797,-3.277100062,44.99999998 +178.1,50.43070438,-2.574007859,51.4844,7.077533845,7.072070903,0.4465625,-1.651892213,-3.305572226,44.99999998 +178.11,50.43070501,-2.574006864,51.4796,7.06710526,7.070960587,0.5115625,-1.55089465,-3.331161839,44.99999998 +178.12,50.43070565,-2.574005869,51.4741,7.063629054,7.070072314,0.575,-1.449573195,-3.35384667,44.99999998 +178.13,50.43070628,-2.574004874,51.4681,7.063629033,7.06985017,0.638125,-1.347948989,-3.373606896,44.99999998 +178.14,50.43070692,-2.574003879,51.4614,7.063629019,7.070072111,0.701875,-1.246043345,-3.39042527,44.99999998 +178.15,50.43070755,-2.574002884,51.454,7.063629023,7.07096018,0.7646875,-1.143877465,-3.404287181,44.99999998 +178.16,50.43070819,-2.574001889,51.4461,7.067105226,7.072070292,0.8265625,-1.041472661,-3.415180484,44.99999998 +178.17,50.43070882,-2.574000893,51.4375,7.077533809,7.072070188,0.8884375,-0.938850362,-3.423095667,44.99999998 +178.18,50.43070946,-2.573999898,51.4283,7.084486178,7.070959867,0.9496875,-0.836032054,-3.428025912,44.99999998 +178.19,50.4307101,-2.573998903,51.4185,7.077533759,7.070293633,1.01,-0.733039109,-3.429966806,44.99999998 +178.2,50.43071073,-2.573997908,51.4081,7.067105161,7.070737613,1.0703125,-0.62989307,-3.428916746,44.99999998 +178.21,50.43071137,-2.573996913,51.3971,7.063628971,7.071181593,1.1315625,-0.526615536,-3.424876649,44.99999998 +178.22,50.430712,-2.573995917,51.3855,7.063628973,7.070959442,1.193125,-0.423227938,-3.417850009,44.99999998 +178.23,50.43071264,-2.573994923,51.3732,7.067105151,7.070959334,1.2528125,-0.319752046,-3.4078429,44.99999998 +178.24,50.43071327,-2.573993927,51.3604,7.077533709,7.071181267,1.31,-0.216209348,-3.394864146,44.99999998 +178.25,50.43071391,-2.573992932,51.347,7.084486076,7.070737072,1.366875,-0.112621444,-3.378924975,44.99999998 +178.26,50.43071455,-2.573991937,51.3331,7.077533676,7.070292876,1.425,-0.009010105,-3.36003937,44.99999998 +178.27,50.43071518,-2.573990942,51.3185,7.067105089,7.070958894,1.483125,0.094603181,-3.338223773,44.99999998 +178.28,50.43071582,-2.573989947,51.3034,7.063628882,7.072068998,1.5396875,0.198196701,-3.313497149,44.99999998 +178.29,50.43071645,-2.573988951,51.2877,7.063628861,7.072068886,1.595,0.301748796,-3.285881156,44.99999998 +178.3,50.43071709,-2.573987956,51.2715,7.067105037,7.071180601,1.6496875,0.405237865,-3.255399801,44.99999998 +178.31,50.43071772,-2.573986961,51.2547,7.077533604,7.070958445,1.7034375,0.508642366,-3.22207967,44.99999998 +178.32,50.43071836,-2.573985966,51.2374,7.08448597,7.071180374,1.7565625,0.611940583,-3.185949868,44.99999998 +178.33,50.430719,-2.57398497,51.2196,7.077533556,7.070958217,1.81,0.715111031,-3.147041851,44.99999998 +178.34,50.43071963,-2.573983976,51.2012,7.067104953,7.070958102,1.8628125,0.818132165,-3.105389538,44.99999998 +178.35,50.43072027,-2.57398298,51.1823,7.063628746,7.071180029,1.913125,0.920982387,-3.061029312,44.99999998 +178.36,50.4307209,-2.573981985,51.1629,7.063628732,7.070735827,1.961875,1.023640323,-3.013999848,44.99999998 +178.37,50.43072154,-2.57398099,51.1431,7.067104902,7.070291624,2.0115625,1.12608449,-2.964342111,44.99999998 +178.38,50.43072217,-2.573979995,51.1227,7.077533452,7.070957636,2.0615625,1.228293457,-2.912099419,44.99999998 +178.39,50.43072281,-2.573979,51.1018,7.084485814,7.072067733,2.1096875,1.330245911,-2.85731732,44.99999998 +178.4,50.43072345,-2.573978004,51.0805,7.077533411,7.072067615,2.1565625,1.431920537,-2.800043656,44.99999998 +178.41,50.43072408,-2.573977009,51.0587,7.067104816,7.070957281,2.203125,1.533296194,-2.740328219,44.99999998 +178.42,50.43072472,-2.573976014,51.0364,7.063628601,7.070068991,2.248125,1.634351568,-2.678223261,44.99999998 +178.43,50.43072535,-2.573975019,51.0137,7.063628564,7.069846828,2.2915625,1.735065688,-2.613782812,44.99999998 +178.44,50.43072599,-2.573974024,50.9906,7.063628521,7.070068751,2.335,1.835417413,-2.54706308,44.99999998 +178.45,50.43072662,-2.573973029,50.967,7.063628496,7.070956801,2.378125,1.935385886,-2.478122334,44.99999998 +178.46,50.43072726,-2.573972034,50.943,7.067104683,7.072066895,2.419375,2.034950137,-2.407020564,44.99999998 +178.47,50.43072789,-2.573971038,50.9186,7.077533257,7.072066773,2.4584375,2.134089425,-2.333819877,44.99999998 +178.48,50.43072853,-2.573970043,50.8938,7.084485616,7.071178479,2.4965625,2.232783067,-2.258584044,44.99999998 +178.49,50.43072917,-2.573969048,50.8687,7.077533183,7.071178356,2.5346875,2.331010378,-2.181378726,44.99999998 +178.5,50.4307298,-2.573968053,50.8431,7.067104558,7.072066405,2.5715625,2.428750905,-2.102271188,44.99999998 +178.51,50.43073044,-2.573967057,50.8172,7.063628341,7.072066282,2.60625,2.525984192,-2.021330472,44.99999998 +178.52,50.43073107,-2.573966062,50.791,7.063628328,7.070955944,2.6403125,2.622690014,-1.938627051,44.99999998 +178.53,50.43073171,-2.573965067,50.7644,7.067104499,7.070067649,2.6746875,2.718848088,-1.854233175,44.99999998 +178.54,50.43073234,-2.573964072,50.7375,7.07753305,7.069845481,2.708125,2.814438361,-1.768222355,44.99999998 +178.55,50.43073298,-2.573963077,50.7102,7.0844854,7.070067399,2.7396875,2.909440837,-1.680669648,44.99999998 +178.56,50.43073362,-2.573962082,50.6827,7.077532969,7.070955445,2.7696875,3.003835806,-1.591651373,44.99999998 +178.57,50.43073425,-2.573961087,50.6548,7.067104355,7.072065535,2.798125,3.097603386,-1.501245107,44.99999998 +178.58,50.43073489,-2.573960091,50.6267,7.063628147,7.072065409,2.8246875,3.190724096,-1.409529805,44.99999998 +178.59,50.43073552,-2.573959096,50.5983,7.063628129,7.071177111,2.85,3.283178457,-1.316585279,44.99999998 +178.6,50.43073616,-2.573958101,50.5697,7.067104289,7.071176984,2.875,3.374947216,-1.222492717,44.99999998 +178.61,50.43073679,-2.573957106,50.5408,7.077532828,7.072065029,2.8996875,3.466011123,-1.127334168,44.99999998 +178.62,50.43073743,-2.57395611,50.5117,7.084485176,7.072064903,2.923125,3.556351154,-1.031192537,44.99999998 +178.63,50.43073807,-2.573955115,50.4823,7.077532761,7.070954561,2.9446875,3.645948575,-0.93415165,44.99999998 +178.64,50.4307387,-2.57395412,50.4528,7.067104158,7.070066262,2.9646875,3.734784536,-0.836296188,44.99999998 +178.65,50.43073934,-2.573953125,50.423,7.063627937,7.069844092,2.9834375,3.822840528,-0.737711465,44.99999998 +178.66,50.43073997,-2.57395213,50.3931,7.063627905,7.070066007,3.00125,3.910098162,-0.638483483,44.99999998 +178.67,50.43074061,-2.573951135,50.363,7.067104061,7.07095405,3.018125,3.996539273,-0.538698701,44.99999998 +178.68,50.43074124,-2.57395014,50.3327,7.077532598,7.072064136,3.0328125,4.082145699,-0.438444207,44.99999998 +178.69,50.43074188,-2.573949144,50.3023,7.084484949,7.072064008,3.045,4.166899679,-0.337807322,44.99999998 +178.7,50.43074252,-2.573948149,50.2718,7.077532537,7.070953666,3.0565625,4.250783393,-0.236875879,44.99999998 +178.71,50.43074315,-2.573947154,50.2412,7.067103933,7.070287408,3.068125,4.333779424,-0.135737884,44.99999998 +178.72,50.43074379,-2.573946159,50.2104,7.063627712,7.070731365,3.078125,4.41587041,-0.034481517,44.99999998 +178.73,50.43074442,-2.573945164,50.1796,7.063627672,7.071175322,3.08625,4.497039164,0.066804874,44.99999998 +178.74,50.43074506,-2.573944168,50.1487,7.067103818,7.070953151,3.0934375,4.577268782,0.168033051,44.99999998 +178.75,50.43074569,-2.573943174,50.1177,7.077532356,7.070953022,3.0996875,4.656542478,0.269114724,44.99999998 +178.76,50.43074633,-2.573942178,50.0867,7.084484713,7.071174936,3.1046875,4.73484375,0.369961656,44.99999998 +178.77,50.43074697,-2.573941183,50.0556,7.077532302,7.07073072,3.108125,4.812156211,0.470486012,44.99999998 +178.78,50.4307476,-2.573940188,50.0245,7.067103697,7.070286505,3.1096875,4.888463704,0.570600131,44.99999998 +178.79,50.43074824,-2.573939193,49.9934,7.063627466,7.070952505,3.1096875,4.963750301,0.670216636,44.99999998 +178.8,50.43074887,-2.573938198,49.9623,7.063627416,7.07206259,3.108125,5.038000303,0.769248724,44.99999998 +178.81,50.43074951,-2.573937202,49.9312,7.063627376,7.072062462,3.105,5.111198125,0.867609993,44.99999998 +178.82,50.43075014,-2.573936207,49.9002,7.063627354,7.070952119,3.1015625,5.183328584,0.965214728,44.99999998 +178.83,50.43075078,-2.573935212,49.8692,7.06710353,7.070063819,3.098125,5.254376554,1.061977732,44.99999998 +178.84,50.43075141,-2.573934217,49.8382,7.077532088,7.069841647,3.0928125,5.324327252,1.15781472,44.99999998 +178.85,50.43075205,-2.573933222,49.8073,7.084484438,7.070063561,3.0846875,5.393166011,1.252642043,44.99999998 +178.86,50.43075269,-2.573932227,49.7765,7.077531999,7.070951603,3.0746875,5.46087845,1.346377079,44.99999998 +178.87,50.43075332,-2.573931232,49.7458,7.06710337,7.072061688,3.0634375,5.527450473,1.43893801,44.99999998 +178.88,50.43075396,-2.573930236,49.7152,7.063627149,7.072061559,3.0515625,5.592868159,1.53024422,44.99999998 +178.89,50.43075459,-2.573929241,49.6848,7.063627131,7.07117326,3.0396875,5.65711787,1.620215955,44.99999998 +178.9,50.43075523,-2.573928246,49.6544,7.067103296,7.071173132,3.0265625,5.720186142,1.70877489,44.99999998 +178.91,50.43075586,-2.573927251,49.6242,7.077531834,7.072061175,3.0109375,5.782059797,1.795843791,44.99999998 +178.92,50.4307565,-2.573926255,49.5942,7.08448418,7.072061047,2.9934375,5.842726,1.881346626,44.99999998 +178.93,50.43075714,-2.57392526,49.5643,7.077531765,7.070950706,2.9746875,5.902171976,1.965208912,44.99999998 +178.94,50.43075777,-2.573924265,49.5347,7.067103164,7.070062407,2.955,5.960385405,2.04735748,44.99999998 +178.95,50.43075841,-2.57392327,49.5052,7.063626942,7.069840237,2.935,6.017354025,2.12772077,44.99999998 +178.96,50.43075904,-2.573922275,49.476,7.063626906,7.070062153,2.914375,6.073066035,2.20622865,44.99999998 +178.97,50.43075968,-2.57392128,49.4469,7.067103067,7.070950198,2.8915625,6.127509802,2.282812653,44.99999998 +178.98,50.43076031,-2.573920285,49.4181,7.077531617,7.072060285,2.86625,6.180673869,2.357406028,44.99999998 +178.99,50.43076095,-2.573919289,49.3896,7.084483969,7.072060158,2.84,6.232547176,2.429943688,44.99999998 +179,50.43076159,-2.573918294,49.3613,7.077531545,7.07117186,2.813125,6.283118894,2.500362379,44.99999998 +179.01,50.43076222,-2.573917299,49.3333,7.067102935,7.071171735,2.7846875,6.332378482,2.568600735,44.99999998 +179.02,50.43076286,-2.573916304,49.3056,7.063626719,7.07205978,2.755,6.380315627,2.634599285,44.99999998 +179.03,50.43076349,-2.573915308,49.2782,7.063626696,7.072059656,2.7246875,6.4269203,2.698300332,44.99999998 +179.04,50.43076413,-2.573914313,49.2511,7.063626663,7.070949318,2.6934375,6.47218282,2.75964847,44.99999998 +179.05,50.43076476,-2.573913318,49.2243,7.063626618,7.070061023,2.66125,6.516093732,2.818590185,44.99999998 +179.06,50.4307654,-2.573912323,49.1979,7.067102778,7.069838856,2.628125,6.558643813,2.875074026,44.99999998 +179.07,50.43076603,-2.573911328,49.1717,7.077531344,7.070060775,2.593125,6.59982418,2.929050719,44.99999998 +179.08,50.43076667,-2.573910333,49.146,7.084483721,7.070948822,2.55625,6.639626298,2.98047328,44.99999998 +179.09,50.43076731,-2.573909338,49.1206,7.077531309,7.072058913,2.5184375,6.6780418,3.02929679,44.99999998 +179.1,50.43076794,-2.573908342,49.0956,7.067102685,7.072058791,2.4796875,6.715062666,3.075478735,44.99999998 +179.11,50.43076858,-2.573907347,49.071,7.063626446,7.070948456,2.44,6.750681218,3.118978837,44.99999998 +179.12,50.43076921,-2.573906352,49.0468,7.06362642,7.070282207,2.4,6.784889949,3.159759108,44.99999998 +179.13,50.43076985,-2.573905357,49.023,7.067102607,7.070948214,2.3596875,6.817681756,3.197784025,44.99999998 +179.14,50.43077048,-2.573904362,48.9996,7.077531178,7.072058306,2.318125,6.849049763,3.233020471,44.99999998 +179.15,50.43077112,-2.573903366,48.9766,7.084483538,7.072058186,2.2746875,6.878987438,3.265437621,44.99999998 +179.16,50.43077176,-2.573902371,48.9541,7.07753111,7.070947853,2.2296875,6.907488536,3.295007285,44.99999998 +179.17,50.43077239,-2.573901376,48.932,7.067102492,7.070059563,2.1834375,6.934547041,3.321703623,44.99999998 +179.18,50.43077303,-2.573900381,48.9104,7.063626281,7.069837402,2.1365625,6.960157395,3.345503431,44.99999998 +179.19,50.43077366,-2.573899386,48.8893,7.063626273,7.070059327,2.0896875,6.984314212,3.366385851,44.99999998 +179.2,50.4307743,-2.573898391,48.8686,7.06710245,7.07094738,2.0415625,7.007012451,3.38433278,44.99999998 +179.21,50.43077493,-2.573897396,48.8484,7.077531005,7.072057476,1.9915625,7.028247356,3.399328518,44.99999998 +179.22,50.43077557,-2.5738964,48.8288,7.084483364,7.07205736,1.9415625,7.048014514,3.411360002,44.99999998 +179.23,50.43077621,-2.573895405,48.8096,7.07753095,7.071169074,1.8915625,7.066309744,3.420416688,44.99999998 +179.24,50.43077684,-2.57389441,48.7909,7.067102352,7.070946916,1.8396875,7.083129321,3.426490728,44.99999998 +179.25,50.43077748,-2.573893415,48.7728,7.063626145,7.071168843,1.786875,7.098469636,3.429576851,44.99999998 +179.26,50.43077811,-2.573892419,48.7552,7.063626128,7.070946687,1.735,7.112327537,3.429672306,44.99999998 +179.27,50.43077875,-2.573891425,48.7381,7.067102306,7.070946573,1.6828125,7.124700102,3.426777035,44.99999998 +179.28,50.43077938,-2.573890429,48.7215,7.077530876,7.071168502,1.628125,7.135584811,3.420893561,44.99999998 +179.29,50.43078002,-2.573889434,48.7055,7.084483243,7.070724304,1.5715625,7.144979313,3.412027039,44.99999998 +179.3,50.43078066,-2.573888439,48.6901,7.077530823,7.070280108,1.515,7.152881662,3.400185147,44.99999998 +179.31,50.43078129,-2.573887444,48.6752,7.067102218,7.070946124,1.458125,7.159290252,3.385378314,44.99999998 +179.32,50.43078193,-2.573886449,48.6609,7.063626019,7.072056227,1.4,7.164203709,3.367619315,44.99999998 +179.33,50.43078256,-2.573885453,48.6472,7.063626018,7.072056117,1.341875,7.167621001,3.346923678,44.99999998 +179.34,50.4307832,-2.573884458,48.6341,7.067102197,7.071167838,1.2846875,7.169541441,3.323309567,44.99999998 +179.35,50.43078383,-2.573883463,48.6215,7.077530751,7.070945687,1.2265625,7.169964627,3.296797377,44.99999998 +179.36,50.43078447,-2.573882468,48.6095,7.08448312,7.070945579,1.1665625,7.168890446,3.267410372,44.99999998 +179.37,50.43078511,-2.573881472,48.5982,7.077530731,7.070057301,1.1065625,7.166319126,3.235174162,44.99999998 +179.38,50.43078574,-2.573880478,48.5874,7.067102152,7.069835152,1.0465625,7.162251183,3.200116822,44.99999998 +179.39,50.43078638,-2.573879483,48.5772,7.063625954,7.071167301,0.9846875,7.156687534,3.162268949,44.99999998 +179.4,50.43078701,-2.573878487,48.5677,7.063625938,7.071833324,0.921875,7.149629324,3.121663488,44.99999998 +179.41,50.43078765,-2.573877492,48.5588,7.063625913,7.071167092,0.8603125,7.141077986,3.078335904,44.99999998 +179.42,50.43078828,-2.573876497,48.5505,7.063625894,7.071166988,0.7996875,7.131035297,3.032323955,44.99999998 +179.43,50.43078892,-2.573875502,48.5428,7.067102087,7.072055055,0.738125,7.119503432,2.983667806,44.99999998 +179.44,50.43078955,-2.573874506,48.5357,7.077530678,7.072054952,0.675,7.106484685,2.932409856,44.99999998 +179.45,50.43079019,-2.573873511,48.5293,7.084483064,7.070944638,0.6115625,7.091981863,2.878594738,44.99999998 +179.46,50.43079083,-2.573872516,48.5235,7.077530664,7.070056367,0.5484375,7.075998002,2.822269491,44.99999998 +179.47,50.43079146,-2.573871521,48.5183,7.067102067,7.069834223,0.4846875,7.058536426,2.763483162,44.99999998 +179.48,50.4307921,-2.573870526,48.5138,7.063625864,7.070056166,0.42,7.039600686,2.702287087,44.99999998 +179.49,50.43079273,-2.573869531,48.5099,7.063625865,7.070944237,0.3553125,7.019194852,2.638734551,44.99999998 +179.5,50.43079337,-2.573868536,48.5067,7.067102063,7.072054352,0.2915625,6.997323162,2.572880959,44.99999998 +179.51,50.430794,-2.57386754,48.5041,7.077530646,7.072054255,0.2284375,6.9739902,2.504783837,44.99999998 +179.52,50.43079464,-2.573866545,48.5021,7.084483031,7.071165988,0.1646875,6.94920078,2.434502484,44.99999998 +179.53,50.43079528,-2.57386555,48.5008,7.077530633,7.071165892,0.1,6.922960058,2.362098152,44.99999998 +179.54,50.43079591,-2.573864555,48.5001,7.067102041,7.072053966,0.0353125,6.895273649,2.287634093,44.99999998 +179.55,50.43079655,-2.573863559,48.5001,7.063625855,7.072053871,-0.0284375,6.866147225,2.211175167,44.99999998 +179.56,50.43079718,-2.573862564,48.5007,7.063625872,7.070943565,-0.091875,6.835586859,2.132788066,44.99999998 +179.57,50.43079782,-2.573861569,48.5019,7.067102072,7.070055302,-0.156875,6.803598969,2.052541144,44.99999998 +179.58,50.43079845,-2.573860574,48.5038,7.077530651,7.069833166,-0.223125,6.770190259,1.970504417,44.99999998 +179.59,50.43079909,-2.573859579,48.5064,7.084483034,7.070055116,-0.288125,6.735367717,1.886749332,44.99999998 +179.6,50.43079973,-2.573858584,48.5096,7.077530646,7.070943195,-0.3515625,6.699138507,1.801348998,44.99999998 +179.61,50.43080036,-2.573857589,48.5134,7.067102073,7.072053317,-0.415,6.661510306,1.714377844,44.99999998 +179.62,50.430801,-2.573856593,48.5179,7.063625893,7.072053228,-0.4784375,6.622490906,1.625911728,44.99999998 +179.63,50.43080163,-2.573855598,48.523,7.063625908,7.070942927,-0.5415625,6.582088558,1.536027771,44.99999998 +179.64,50.43080227,-2.573854603,48.5287,7.067102112,7.070276711,-0.605,6.54031157,1.44480441,44.99999998 +179.65,50.4308029,-2.573853608,48.5351,7.077530689,7.070942751,-0.6684375,6.497168707,1.352321172,44.99999998 +179.66,50.43080354,-2.573852613,48.5421,7.084483068,7.072052876,-0.7315625,6.452669023,1.258658616,44.99999998 +179.67,50.43080418,-2.573851617,48.5497,7.077530689,7.07205279,-0.795,6.406821743,1.163898558,44.99999998 +179.68,50.43080481,-2.573850622,48.558,7.067102134,7.070942492,-0.858125,6.359636548,1.068123563,44.99999998 +179.69,50.43080545,-2.573849627,48.5669,7.063625964,7.070054237,-0.9196875,6.311123181,0.971417111,44.99999998 +179.7,50.43080608,-2.573848632,48.5764,7.063625971,7.06983211,-0.98,6.261291781,0.873863598,44.99999998 +179.71,50.43080672,-2.573847637,48.5865,7.067102161,7.07005407,-1.04,6.210152834,0.775548051,44.99999998 +179.72,50.43080735,-2.573846642,48.5972,7.077530744,7.070942157,-1.1,6.157716997,0.676556185,44.99999998 +179.73,50.43080799,-2.573845647,48.6085,7.084483145,7.072052286,-1.16,6.103995156,0.576974401,44.99999998 +179.74,50.43080863,-2.573844651,48.6204,7.077530784,7.072052205,-1.22,6.048998599,0.476889446,44.99999998 +179.75,50.43080926,-2.573843656,48.6329,7.067102231,7.071163954,-1.2796875,5.992738784,0.376388695,44.99999998 +179.76,50.4308099,-2.573842661,48.646,7.063626059,7.071163874,-1.338125,5.935227458,0.275559697,44.99999998 +179.77,50.43081053,-2.573841666,48.6597,7.063626068,7.071829922,-1.395,5.876476652,0.1744904,44.99999998 +179.78,50.43081117,-2.57384067,48.6739,7.06362607,7.071163716,-1.451875,5.816498571,0.073268926,44.99999998 +179.79,50.4308118,-2.573839675,48.6887,7.063626076,7.069831383,-1.5096875,5.755305819,-0.028016433,44.99999998 +179.8,50.43081244,-2.573838681,48.7041,7.067102294,7.070053348,-1.5665625,5.692911173,-0.129277327,44.99999998 +179.81,50.43081307,-2.573837685,48.7201,7.077530911,7.07094144,-1.6215625,5.629327583,-0.23042552,44.99999998 +179.82,50.43081371,-2.57383669,48.7365,7.084483321,7.070941364,-1.6765625,5.564568398,-0.331372776,44.99999998 +179.83,50.43081435,-2.573835695,48.7536,7.077530939,7.071163331,-1.7315625,5.49864714,-0.432031033,44.99999998 +179.84,50.43081498,-2.5738347,48.7712,7.067102365,7.072051425,-1.784375,5.43157756,-0.53231257,44.99999998 +179.85,50.43081562,-2.573833704,48.7893,7.063626198,7.07205135,-1.835,5.363373638,-0.632129954,44.99999998 +179.86,50.43081625,-2.573832709,48.8079,7.063626235,7.071163107,-1.8853125,5.294049698,-0.731396095,44.99999998 +179.87,50.43081689,-2.573831714,48.827,7.067102456,7.071163033,-1.9365625,5.223620122,-0.83002442,44.99999998 +179.88,50.43081752,-2.573830719,48.8466,7.077531057,7.071829088,-1.988125,5.152099634,-0.927928984,44.99999998 +179.89,50.43081816,-2.573829723,48.8668,7.084483467,7.071162888,-2.038125,5.079503246,-1.025024418,44.99999998 +179.9,50.4308188,-2.573828728,48.8874,7.0775311,7.069830561,-2.08625,5.005846026,-1.121225922,44.99999998 +179.91,50.43081943,-2.573827734,48.9085,7.067102534,7.070052532,-2.1334375,4.931143445,-1.216449789,44.99999998 +179.92,50.43082007,-2.573826738,48.9301,7.06362636,7.070940631,-2.1796875,4.855411029,-1.310612824,44.99999998 +179.93,50.4308207,-2.573825743,48.9521,7.063626389,7.070940562,-2.2246875,4.778664651,-1.403633038,44.99999998 +179.94,50.43082134,-2.573824748,48.9746,7.067102618,7.071162534,-2.2684375,4.700920294,-1.495429242,44.99999998 +179.95,50.43082197,-2.573823753,48.9975,7.077531235,7.072050634,-2.3115625,4.622194174,-1.585921394,44.99999998 +179.96,50.43082261,-2.573822757,49.0208,7.084483646,7.072050565,-2.355,4.542502792,-1.675030598,44.99999998 +179.97,50.43082325,-2.573821762,49.0446,7.077531268,7.070940285,-2.3978125,4.461862821,-1.76267916,44.99999998 +179.98,50.43082388,-2.573820767,49.0688,7.067102706,7.070052047,-2.438125,4.380290992,-1.848790649,44.99999998 +179.99,50.43082452,-2.573819772,49.0934,7.06362655,7.069829937,-2.4765625,4.297804378,-1.933289949,44.99999998 +180,50.43082515,-2.573818777,49.1183,7.063626594,7.070051913,-2.515,4.214420283,-2.016103435,44.99999998 +180.01,50.43082579,-2.573817782,49.1437,7.063626628,7.070940016,-2.553125,4.129342181,-2.0971588,45.00001253 +180.02,50.43082642,-2.573816787,49.1694,7.063626644,7.072050161,-2.589375,4.038518802,-2.176385399,45.00010036 +180.03,50.43082706,-2.573815791,49.1955,7.06710285,7.072050096,-2.6234375,3.93708499,-2.253714189,45.00033865 +180.04,50.43082769,-2.573814796,49.2219,7.077531464,7.070939819,-2.6565625,3.820175988,-2.329077734,45.00080269 +180.05,50.43082833,-2.573813801,49.2486,7.084483902,7.070273626,-2.69,3.682927042,-2.402410259,45.0015677 +180.06,50.43082897,-2.573812806,49.2757,7.077531556,7.070939688,-2.723125,3.520473683,-2.47364782,45.00270904 +180.07,50.4308296,-2.573811811,49.3031,7.067102999,7.072271878,-2.754375,3.327951499,-2.542728368,45.00430186 +180.08,50.43083024,-2.573810815,49.3308,7.063626821,7.073159984,-2.783125,3.100496364,-2.609591568,45.0064214 +180.09,50.43083087,-2.57380982,49.3588,7.063626841,7.07315992,-2.81,2.834871812,-2.67417921,45.00914295 +180.1,50.43083151,-2.573808824,49.387,7.067103075,7.072493729,-2.8365625,2.534351954,-2.736434913,45.01254179 +180.11,50.43083214,-2.573807829,49.4155,7.077531707,7.072271624,-2.863125,2.203838786,-2.796304419,45.01666806 +180.12,50.43083278,-2.573806834,49.4443,7.084484133,7.073603815,-2.888125,1.848234249,-2.853735474,45.02147157 +180.13,50.43083342,-2.573805838,49.4733,7.07753177,7.075380091,-2.91125,1.472440571,-2.908678058,45.02687708 +180.14,50.43083405,-2.573804842,49.5025,7.06710321,7.075602071,-2.9334375,1.081360034,-2.961084216,45.03280937 +180.15,50.43083469,-2.573803846,49.532,7.063627044,7.074935882,-2.9546875,0.679895096,-3.010908282,45.03919316 +180.16,50.43083532,-2.573802851,49.5616,7.063627082,7.07582399,-2.9746875,0.272948385,-3.058106769,45.0459532 +180.17,50.43083596,-2.573801855,49.5915,7.063627123,7.078044352,-2.993125,-0.134577416,-3.102638539,45.05301422 +180.18,50.43083659,-2.573800858,49.6215,7.063627159,7.079154503,-3.0096875,-0.537779447,-3.144464802,45.06030098 +180.19,50.43083723,-2.573799862,49.6517,7.063627196,7.079376483,-3.0246875,-0.931754853,-3.183549003,45.06773831 +180.2,50.43083786,-2.573798866,49.682,7.06015104,7.080708676,-3.038125,-1.311600546,-3.219857109,45.07525082 +180.21,50.4308385,-2.573797869,49.7125,7.049722485,7.082706996,-3.05,-1.672413269,-3.253357493,45.08277593 +180.22,50.43083913,-2.573796872,49.743,7.042770116,7.083595105,-3.0615625,-2.009289878,-3.284020877,45.09030099 +180.23,50.43083976,-2.573795875,49.7737,7.049722541,7.082928917,-3.073125,-2.317326943,-3.311820502,45.0978261 +180.24,50.4308404,-2.573794878,49.8045,7.060151174,7.082040688,-3.083125,-2.591621034,-3.336732192,45.10535116 +180.25,50.43084103,-2.573793882,49.8354,7.063627408,7.082928797,-3.09125,-2.828896092,-3.358734229,45.11287627 +180.26,50.43084167,-2.573792885,49.8663,7.063627437,7.085371202,-3.098125,-3.032386636,-3.377807421,45.12040133 +180.27,50.4308423,-2.573791887,49.8974,7.063627461,7.087369522,-3.103125,-3.206954501,-3.393935037,45.12792644 +180.28,50.43084294,-2.57379089,49.9284,7.063627485,7.088701716,-3.10625,-3.357461518,-3.407103154,45.1354515 +180.29,50.43084357,-2.573789892,49.9595,7.060151327,7.090033911,-3.1084375,-3.488769407,-3.417300199,45.14297661 +180.3,50.43084421,-2.573788894,49.9906,7.049722795,7.09092202,-3.109375,-3.605739887,-3.42451729,45.15050167 +180.31,50.43084484,-2.573787896,50.0217,7.042770453,7.091144003,-3.1084375,-3.713234562,-3.428748182,45.15802678 +180.32,50.43084547,-2.573786898,50.0528,7.046246684,7.091143942,-3.1065625,-3.816114978,-3.429989151,45.16555183 +180.33,50.43084611,-2.5737859,50.0838,7.046246716,7.091365924,-3.1046875,-3.918428796,-3.428239109,45.17307695 +180.34,50.43084674,-2.573784902,50.1149,7.04277055,7.092254033,-3.10125,-4.020968532,-3.423499602,45.180602 +180.35,50.43084737,-2.573783904,50.1459,7.046246767,7.093586227,-3.0946875,-4.123712699,-3.415774756,45.18812712 +180.36,50.43084801,-2.573782905,50.1768,7.046246802,7.094696378,-3.0865625,-4.226639868,-3.405071332,45.19565217 +180.37,50.43084864,-2.573781907,50.2076,7.042770655,7.095806529,-3.0784375,-4.329728555,-3.391398553,45.20317729 +180.38,50.43084927,-2.573780908,50.2384,7.046246889,7.097138721,-3.0696875,-4.432957215,-3.37476851,45.21070234 +180.39,50.43084991,-2.573779909,50.269,7.046246917,7.09802683,-3.059375,-4.536304305,-3.355195585,45.2182274 +180.4,50.43085054,-2.57377891,50.2996,7.042770747,7.098470855,-3.046875,-4.639748226,-3.33269685,45.22575251 +180.41,50.43085117,-2.573777911,50.33,7.046246973,7.099358964,-3.0328125,-4.743267375,-3.307291958,45.23327757 +180.42,50.43085181,-2.573776912,50.3602,7.046247011,7.100691157,-3.0184375,-4.846840154,-3.279003084,45.24080268 +180.43,50.43085244,-2.573775912,50.3904,7.042770859,7.101801307,-3.0028125,-4.950444903,-3.247854864,45.24832774 +180.44,50.43085307,-2.573774913,50.4203,7.046247097,7.102911456,-2.9846875,-5.054060023,-3.213874456,45.25585285 +180.45,50.43085371,-2.573773913,50.4501,7.042770939,7.104243649,-2.965,-5.157663799,-3.177091539,45.2633779 +180.46,50.43085434,-2.573772913,50.4796,7.028866185,7.105131756,-2.945,-5.261234687,-3.137538086,45.27090302 +180.47,50.43085497,-2.573771913,50.509,7.028866203,7.105353736,-2.9246875,-5.364751029,-3.095248701,45.27842807 +180.48,50.4308556,-2.573770913,50.5381,7.042771006,7.105575716,-2.9028125,-5.468191225,-3.050260227,45.28595319 +180.49,50.43085624,-2.573769913,50.5671,7.042771045,7.106463823,-2.8784375,-5.57153356,-3.002611853,45.29347824 +180.5,50.43085687,-2.573768913,50.5957,7.025390116,7.107796014,-2.8528125,-5.674756605,-2.952345177,45.30100335 +180.51,50.4308575,-2.573767912,50.6241,7.014961569,7.108906163,-2.826875,-5.777838702,-2.899503973,45.30852841 +180.52,50.43085813,-2.573766912,50.6523,7.025390187,7.110016311,-2.7996875,-5.880758366,-2.844134363,45.31605352 +180.53,50.43085876,-2.573765911,50.6801,7.042771189,7.111348501,-2.77125,-5.98349411,-2.786284648,45.32357858 +180.54,50.4308594,-2.57376491,50.7077,7.042771207,7.112458648,-2.741875,-6.086024449,-2.726005248,45.33110369 +180.55,50.43086003,-2.573763909,50.735,7.02539026,7.113568795,-2.7109375,-6.188328012,-2.663348761,45.33862875 +180.56,50.43086066,-2.573762908,50.7619,7.014961718,7.114678942,-2.6784375,-6.290383369,-2.598369732,45.34615386 +180.57,50.43086129,-2.573761906,50.7886,7.025390339,7.11490092,-2.645,-6.392169264,-2.531124941,45.35367892 +180.58,50.43086192,-2.573760905,50.8148,7.042771342,7.114900854,-2.61125,-6.49366444,-2.461672945,45.36120403 +180.59,50.43086256,-2.573759904,50.8408,7.042771371,7.116011,-2.5765625,-6.594847641,-2.390074306,45.36872909 +180.6,50.43086319,-2.573758902,50.8664,7.025390427,7.117121145,-2.539375,-6.695697781,-2.316391532,45.3762542 +180.61,50.43086382,-2.5737579,50.8916,7.011485669,7.117121078,-2.5,-6.796193834,-2.240688796,45.38377926 +180.62,50.43086445,-2.573756899,50.9164,7.008009488,7.117565095,-2.46,-6.896314771,-2.163032159,45.39130437 +180.63,50.43086508,-2.573755897,50.9408,7.008009516,7.119563408,-2.42,-6.996039679,-2.083489345,45.39882942 +180.64,50.43086571,-2.573754895,50.9648,7.011485752,7.121783763,-2.38,-7.095347704,-2.002129682,45.40635454 +180.65,50.43086634,-2.573753892,50.9884,7.025390567,7.123115949,-2.3396875,-7.194218217,-1.919024159,45.41387959 +180.66,50.43086697,-2.57375289,51.0116,7.042771572,7.12400405,-2.2978125,-7.292630422,-1.834245198,45.42140471 +180.67,50.43086761,-2.573751887,51.0344,7.042771591,7.124448064,-2.253125,-7.390563864,-1.747866711,45.42892976 +180.68,50.43086824,-2.573750884,51.0567,7.025390625,7.124225952,-2.2065625,-7.487998087,-1.659964099,45.43645487 +180.69,50.43086887,-2.573749882,51.0785,7.011485867,7.124447923,-2.16,-7.584912695,-1.570613967,45.44397993 +180.7,50.4308695,-2.573748879,51.0999,7.008009709,7.125780106,-2.1134375,-7.681287519,-1.479894236,45.45150504 +180.71,50.43087013,-2.573747876,51.1208,7.008009739,7.127556373,-2.06625,-7.777102334,-1.387884032,45.4590301 +180.72,50.43087076,-2.573746873,51.1412,7.008009765,7.129110597,-2.018125,-7.872337259,-1.294663513,45.46655516 +180.73,50.43087139,-2.573745869,51.1612,7.00800979,7.130220736,-1.968125,-7.96697224,-1.200314094,45.47408027 +180.74,50.43087202,-2.573744866,51.1806,7.008009807,7.131108832,-1.9165625,-8.060987681,-1.104917939,45.48160532 +180.75,50.43087265,-2.573743862,51.1995,7.00800982,7.131552843,-1.8653125,-8.154363874,-1.008558298,45.48913044 +180.76,50.43087328,-2.573742858,51.2179,7.008009832,7.131552769,-1.8146875,-8.247081279,-0.911319224,45.49665549 +180.77,50.43087391,-2.573741855,51.2358,7.00800985,7.132440863,-1.763125,-8.339120589,-0.813285401,45.50418061 +180.78,50.43087454,-2.573740851,51.2532,7.008009881,7.133995084,-1.7096875,-8.430462552,-0.71454237,45.51170566 +180.79,50.43087517,-2.573739846,51.27,7.008009912,7.134661135,-1.655,-8.521088146,-0.615176305,45.51923078 +180.8,50.4308758,-2.573738843,51.2863,7.00800993,7.135105143,-1.6,-8.610978349,-0.515273779,45.52675583 +180.81,50.43087643,-2.573737838,51.302,7.008009946,7.136437319,-1.5446875,-8.700114481,-0.414921883,45.53428094 +180.82,50.43087706,-2.573736834,51.3172,7.008009957,7.138213579,-1.488125,-8.788477866,-0.314208221,45.541806 +180.83,50.43087769,-2.573735829,51.3318,7.008009961,7.139545753,-1.43,-8.87605011,-0.213220571,45.54933111 +180.84,50.43087832,-2.573734824,51.3458,7.008009977,7.139545674,-1.371875,-8.96281288,-0.112046939,45.55685617 +180.85,50.43087895,-2.573733819,51.3592,7.008010006,7.138879468,-1.3146875,-9.04874807,-0.010775617,45.56438128 +180.86,50.43087958,-2.573732815,51.3721,7.004533831,7.139989599,-1.2565625,-9.133837745,0.090505044,45.57190634 +180.87,50.43088021,-2.57373181,51.3844,6.990629064,7.143098109,-1.1965625,-9.218064088,0.191706865,45.57943145 +180.88,50.43088084,-2.573730804,51.396,6.973248101,7.14531845,-1.136875,-9.301409566,0.292741441,45.58695651 +180.89,50.43088146,-2.573729798,51.4071,6.973248109,7.145318368,-1.078125,-9.383856703,0.393520821,45.59448162 +180.9,50.43088209,-2.573728793,51.4176,6.990629092,7.144652158,-1.0178125,-9.465388368,0.493956999,45.60200668 +180.91,50.43088272,-2.573727787,51.4275,7.004533878,7.144652074,-0.955,-9.545987487,0.593962428,45.60953179 +180.92,50.43088335,-2.573726782,51.4367,7.008010083,7.145540159,-0.891875,-9.625637272,0.693449903,45.61705684 +180.93,50.43088398,-2.573725776,51.4453,7.008010104,7.14709437,-0.8303125,-9.704320993,0.792332735,45.62458196 +180.94,50.43088461,-2.57372477,51.4533,7.004533929,7.148870621,-0.7696875,-9.782022321,0.890524638,45.63210701 +180.95,50.43088524,-2.573723764,51.4607,6.990629154,7.150202788,-0.708125,-9.858724983,0.987939953,45.63963213 +180.96,50.43088587,-2.573722757,51.4675,6.973248181,7.150424743,-0.645,-9.934412937,1.08449377,45.64715718 +180.97,50.43088649,-2.573721751,51.4736,6.973248182,7.150424656,-0.5815625,-10.00907037,1.180101919,45.6546823 +180.98,50.43088712,-2.573720745,51.4791,6.990629155,7.15175682,-0.518125,-10.08268181,1.274680979,45.66220735 +180.99,50.43088775,-2.573719738,51.484,7.00105775,7.15375511,-0.4534375,-10.15523173,1.368148501,45.66973246 +181,50.43088838,-2.573718731,51.4882,6.990629188,7.154865231,-0.3884375,-10.22670506,1.460422953,45.67725752 +181.01,50.43088901,-2.573717724,51.4917,6.973248222,7.155309225,-0.325,-10.29708686,1.551423949,45.68478263 +181.02,50.43088963,-2.573716717,51.4947,6.97324822,7.156197303,-0.2615625,-10.36636244,1.641072019,45.69230769 +181.03,50.43089026,-2.57371571,51.497,6.9906292,7.157307422,-0.1965625,-10.43451731,1.729289128,45.6998328 +181.04,50.43089089,-2.573714702,51.4986,7.001057792,7.157529371,-0.131875,-10.50153728,1.815998211,45.70735786 +181.05,50.43089152,-2.573713695,51.4996,6.990629202,7.157529277,-0.0684375,-10.56740829,1.901123754,45.71488297 +181.06,50.43089215,-2.573712688,51.5,6.973248215,7.158861436,-0.0046875,-10.63211665,1.984591444,45.72240803 +181.07,50.43089277,-2.57371168,51.4997,6.973248207,7.160859721,0.06,-10.69564879,2.066328571,45.72993308 +181.08,50.4308934,-2.573710672,51.4988,6.987152988,7.162191879,0.125,-10.75799147,2.146263804,45.7374582 +181.09,50.43089403,-2.573709664,51.4972,6.987152998,7.163301992,0.19,-10.81913168,2.22432747,45.74498325 +181.1,50.43089466,-2.573708656,51.495,6.973248224,7.164412105,0.2546875,-10.87905665,2.300451502,45.75250836 +181.11,50.43089528,-2.573707647,51.4921,6.969772025,7.16463405,0.3184375,-10.93775382,2.374569552,45.76003342 +181.12,50.43089591,-2.573706639,51.4886,6.97324822,7.164633951,0.3815625,-10.99521095,2.446616875,45.76755853 +181.13,50.43089654,-2.573705631,51.4845,6.969772027,7.165744063,0.445,-11.0514161,2.516530732,45.77508359 +181.14,50.43089716,-2.573704622,51.4797,6.969772014,7.166854174,0.5084375,-11.10635748,2.584250161,45.7826087 +181.15,50.43089779,-2.573703613,51.4743,6.973248185,7.167076116,0.5715625,-11.16002363,2.649716032,45.79013376 +181.16,50.43089842,-2.573702605,51.4683,6.969771981,7.168186225,0.6353125,-11.21240332,2.712871336,45.79765887 +181.17,50.43089904,-2.573701596,51.4616,6.969771988,7.170406543,0.6996875,-11.26348566,2.773661012,45.80518393 +181.18,50.43089967,-2.573700586,51.4543,6.973248183,7.171516651,0.763125,-11.31325994,2.832031947,45.81270904 +181.19,50.4309003,-2.573699577,51.4463,6.969771981,7.171516548,0.825,-11.36171572,2.887933377,45.8202341 +181.2,50.43090092,-2.573698568,51.4378,6.969771975,7.171960528,0.8865625,-11.40884299,2.941316427,45.82775921 +181.21,50.43090155,-2.573697558,51.4286,6.973248159,7.172848592,0.9484375,-11.45463189,2.992134632,45.83528426 +181.22,50.43090218,-2.573696549,51.4188,6.969771954,7.173958697,1.0096875,-11.49907278,3.040343645,45.84280938 +181.23,50.4309028,-2.573695539,51.4084,6.969771943,7.175290843,1.07,-11.5421564,3.085901468,45.85033443 +181.24,50.43090343,-2.573694529,51.3974,6.973248116,7.176178905,1.13,-11.5838738,3.128768279,45.85785955 +181.25,50.43090406,-2.573693519,51.3858,6.966295704,7.176622881,1.1896875,-11.62421622,3.16890678,45.8653846 +181.26,50.43090468,-2.573692509,51.3736,6.955867113,7.17751094,1.2484375,-11.66317529,3.206281963,45.87290972 +181.27,50.43090531,-2.573691499,51.3608,6.952390915,7.178843084,1.3065625,-11.70074287,3.240861226,45.88043477 +181.28,50.43090593,-2.573690488,51.3475,6.952390901,7.179953185,1.365,-11.736911,3.272614375,45.88795988 +181.29,50.43090656,-2.573689478,51.3335,6.955867085,7.181063285,1.4234375,-11.77167229,3.301513794,45.89548494 +181.3,50.43090718,-2.573688467,51.319,6.966295663,7.182395427,1.48125,-11.80501935,3.327534214,45.90301005 +181.31,50.43090781,-2.573687456,51.3039,6.973248031,7.183283484,1.538125,-11.83694531,3.350653003,45.91053511 +181.32,50.43090844,-2.573686445,51.2882,6.966295603,7.183505414,1.593125,-11.86744345,3.370849937,45.91806022 +181.33,50.43090906,-2.573685434,51.272,6.955866996,7.183727343,1.646875,-11.89650736,3.388107484,45.92558528 +181.34,50.43090969,-2.573684423,51.2553,6.952390796,7.184615398,1.7015625,-11.92413109,3.402410516,45.93311039 +181.35,50.43091031,-2.573683412,51.238,6.952390785,7.185947536,1.7565625,-11.95030879,3.4137466,45.94063545 +181.36,50.43091094,-2.5736824,51.2201,6.95239077,7.187057631,1.8096875,-11.97503501,3.422105882,45.94816056 +181.37,50.43091156,-2.573681389,51.2018,6.95239076,7.188167726,1.86125,-11.99830455,3.427480971,45.95568562 +181.38,50.43091219,-2.573680377,51.1829,6.95239074,7.189499863,1.911875,-12.02011258,3.429867283,45.96321073 +181.39,50.43091281,-2.573679365,51.1635,6.952390711,7.190387915,1.9615625,-12.04045459,3.429262698,45.97073578 +181.4,50.43091344,-2.573678353,51.1437,6.952390688,7.190831883,2.0115625,-12.05932627,3.425667789,45.9782609 +181.41,50.43091406,-2.573677341,51.1233,6.948914471,7.191719933,2.0615625,-12.07672373,3.419085593,45.98578595 +181.42,50.43091469,-2.573676329,51.1024,6.938485851,7.193052067,2.109375,-12.09264325,3.409521896,45.99331101 +181.43,50.43091531,-2.573675316,51.0811,6.931533428,7.193940117,2.155,-12.10708162,3.396985064,46.00083612 +181.44,50.43091593,-2.573674304,51.0593,6.938485805,7.19416204,2.2,-12.12003573,3.381485982,46.00836118 +181.45,50.43091656,-2.573673291,51.0371,6.94891438,7.194383962,2.245,-12.13150291,3.363038231,46.01588629 +181.46,50.43091718,-2.573672279,51.0144,6.948914356,7.195272011,2.29,-12.1414808,3.341657852,46.02341135 +181.47,50.43091781,-2.573671266,50.9913,6.938485747,7.196826184,2.334375,-12.14996728,3.317363525,46.03093646 +181.48,50.43091843,-2.573670253,50.9677,6.931533339,7.198602399,2.3765625,-12.15696051,3.290176391,46.03846152 +181.49,50.43091905,-2.57366924,50.9437,6.938485703,7.199934529,2.4165625,-12.16245919,3.260120114,46.04598663 +181.5,50.43091968,-2.573668226,50.9194,6.948914246,7.20015645,2.4565625,-12.16646204,3.227221049,46.05351168 +181.51,50.4309203,-2.573667213,50.8946,6.948914209,7.200156327,2.4965625,-12.16896828,3.19150773,46.0610368 +181.52,50.43092093,-2.5736662,50.8694,6.938485605,7.201488456,2.534375,-12.16997737,3.153011441,46.06856185 +181.53,50.43092155,-2.573665186,50.8439,6.931533197,7.20348671,2.57,-12.1694891,3.111765642,46.07608697 +181.54,50.43092217,-2.573664172,50.818,6.935009365,7.204596797,2.605,-12.16750357,3.067806314,46.08361202 +181.55,50.4309228,-2.573663158,50.7918,6.93500934,7.204818714,2.64,-12.16402119,3.021171847,46.09113714 +181.56,50.43092342,-2.573662144,50.7652,6.931533125,7.205040631,2.6746875,-12.1590427,2.971902862,46.09866219 +181.57,50.43092404,-2.57366113,50.7383,6.935009292,7.205928675,2.7078125,-12.15256914,2.920042333,46.1061873 +181.58,50.43092467,-2.573660116,50.711,6.935009254,7.207260802,2.738125,-12.14460187,2.865635464,46.11371236 +181.59,50.43092529,-2.573659101,50.6835,6.931533027,7.208148844,2.7665625,-12.13514251,2.808729754,46.12123747 +181.6,50.43092591,-2.573658087,50.6557,6.935009193,7.208592802,2.7953125,-12.12419311,2.749374764,46.12876253 +181.61,50.43092654,-2.573657072,50.6276,6.931532957,7.209480843,2.824375,-12.11175586,2.687622289,46.13628764 +181.62,50.43092716,-2.573656058,50.5992,6.917628137,7.210812969,2.8515625,-12.09783345,2.623526131,46.1438127 +181.63,50.43092778,-2.573655042,50.5705,6.917628117,7.211923052,2.87625,-12.08242873,2.557142267,46.15133781 +181.64,50.4309284,-2.573654028,50.5417,6.931532886,7.212811093,2.8996875,-12.06554498,2.488528508,46.15886287 +181.65,50.43092903,-2.573653012,50.5125,6.931532857,7.213477091,2.921875,-12.04718564,2.417744787,46.16638798 +181.66,50.43092965,-2.573651997,50.4832,6.917628036,7.213921046,2.9428125,-12.0273546,2.344852695,46.17391304 +181.67,50.43093027,-2.573650982,50.4537,6.917628004,7.214587044,2.9634375,-12.00605598,2.269915831,46.18143815 +181.68,50.43093089,-2.573649966,50.4239,6.931532763,7.215475085,2.9828125,-11.9832942,2.192999628,46.1889632 +181.69,50.43093152,-2.573648951,50.394,6.931532729,7.216585166,2.9996875,-11.95907413,2.114171063,46.19648832 +181.7,50.43093214,-2.573647935,50.3639,6.917627898,7.217917289,3.0153125,-11.93340069,2.033498892,46.20401337 +181.71,50.43093276,-2.573646919,50.3337,6.917627855,7.21902737,3.03125,-11.90627927,1.951053474,46.21153849 +181.72,50.43093338,-2.573645903,50.3033,6.931532613,7.220137451,3.04625,-11.87771561,1.866906772,46.21906354 +181.73,50.43093401,-2.573644887,50.2727,6.931532591,7.221469573,3.058125,-11.8477156,1.781132068,46.22658866 +181.74,50.43093463,-2.57364387,50.2421,6.914151583,7.222579653,3.068125,-11.8162856,1.69380419,46.23411371 +181.75,50.43093525,-2.573642854,50.2114,6.900246771,7.223689734,3.0784375,-11.78343202,1.604999284,46.24163882 +181.76,50.43093587,-2.573641837,50.1805,6.900246747,7.225021856,3.0878125,-11.74916187,1.514794757,46.24916388 +181.77,50.43093649,-2.57364082,50.1496,6.914151495,7.225909894,3.0946875,-11.71348218,1.423269333,46.25668894 +181.78,50.43093711,-2.573639803,50.1186,6.93153243,7.226131806,3.1,-11.67640053,1.330502825,46.26421405 +181.79,50.43093774,-2.573638786,50.0876,6.931532397,7.226131676,3.1046875,-11.63792458,1.236576077,46.2717391 +181.8,50.43093836,-2.573637769,50.0565,6.914151395,7.226131547,3.108125,-11.59806236,1.141571023,46.27926422 +181.81,50.43093898,-2.573636752,50.0254,6.900246572,7.226353459,3.109375,-11.55682223,1.045570512,46.28678927 +181.82,50.4309396,-2.573635735,49.9943,6.896770324,7.227463539,3.1084375,-11.51421279,0.948658254,46.29431439 +181.83,50.43094022,-2.573634718,49.9632,6.896770292,7.229461786,3.1065625,-11.47024292,0.850918701,46.30183944 +181.84,50.43094084,-2.5736337,49.9322,6.896770281,7.23101595,3.105,-11.42492185,0.752437168,46.30936456 +181.85,50.43094146,-2.573632682,49.9011,6.896770263,7.231903987,3.1028125,-11.37825902,0.653299541,46.31688961 +181.86,50.43094208,-2.573631665,49.8701,6.900246421,7.233236109,3.0978125,-11.33026418,0.553592165,46.32441472 +181.87,50.4309427,-2.573630646,49.8391,6.914151157,7.234346189,3.0903125,-11.28094735,0.453402072,46.33193978 +181.88,50.43094332,-2.573629628,49.8083,6.9315321,7.23434606,3.0828125,-11.23031879,0.352816581,46.33946489 +181.89,50.43094395,-2.57362861,49.7775,6.931532076,7.234567972,3.075,-11.17838911,0.251923469,46.34698995 +181.9,50.43094457,-2.573627592,49.7467,6.914151068,7.235678051,3.0646875,-11.12516918,0.150810628,46.35451506 +181.91,50.43094519,-2.573626573,49.7162,6.900246245,7.236788131,3.053125,-11.07067006,0.04956635,46.36204012 +181.92,50.43094581,-2.573625555,49.6857,6.896770009,7.237898211,3.0415625,-11.01490322,-0.051721244,46.36956523 +181.93,50.43094643,-2.573624536,49.6553,6.896769977,7.239230333,3.0278125,-10.95788017,-0.152963688,46.37709029 +181.94,50.43094705,-2.573623517,49.6251,6.896769952,7.240118372,3.01125,-10.89961294,-0.254072748,46.3846154 +181.95,50.43094767,-2.573622498,49.5951,6.896769924,7.240562328,2.9934375,-10.84011362,-0.354960246,46.39214046 +181.96,50.43094829,-2.573621479,49.5652,6.896769891,7.241450367,2.975,-10.77939465,-0.455538174,46.39966557 +181.97,50.43094891,-2.57362046,49.5356,6.896769861,7.242782489,2.95625,-10.7174688,-0.555718927,46.40719062 +181.98,50.43094953,-2.57361944,49.5061,6.896769839,7.24389257,2.9365625,-10.65434884,-0.655415074,46.41471574 +181.99,50.43095015,-2.573618421,49.4768,6.893293613,7.24478061,2.914375,-10.59004814,-0.754539694,46.42224079 +182,50.43095077,-2.573617401,49.4478,6.879388795,7.245224566,2.89,-10.52457998,-0.85300633,46.42976591 +182.01,50.43095139,-2.573616381,49.419,6.86200779,7.24522444,2.865,-10.45795805,-0.950729095,46.43729096 +182.02,50.430952,-2.573615362,49.3905,6.862007771,7.246334522,2.84,-10.39019634,-1.047622847,46.44481608 +182.03,50.43095262,-2.573614342,49.3622,6.87938872,7.248776855,2.8146875,-10.32130893,-1.143603075,46.45234113 +182.04,50.43095324,-2.573613321,49.3342,6.893293454,7.250553063,2.7878125,-10.25131022,-1.238586071,46.45986624 +182.05,50.43095386,-2.573612301,49.3064,6.896769597,7.250774978,2.758125,-10.18021487,-1.332488983,46.4673913 +182.06,50.43095448,-2.57361128,49.279,6.896769568,7.250108727,2.7265625,-10.10803771,-1.425229937,46.47491641 +182.07,50.4309551,-2.57361026,49.2519,6.896769562,7.249886561,2.695,-10.03479377,-1.516728031,46.48244147 +182.08,50.43095572,-2.57360924,49.2251,6.896769549,7.251218687,2.6628125,-9.960498387,-1.606903567,46.48996658 +182.09,50.43095634,-2.573608219,49.1986,6.896769517,7.253216938,2.628125,-9.8851671,-1.695677877,46.49749164 +182.1,50.43095696,-2.573607198,49.1725,6.893293284,7.254327023,2.5915625,-9.808815603,-1.782973497,46.50501675 +182.11,50.43095758,-2.573606177,49.1468,6.879388478,7.254770982,2.5553125,-9.731459827,-1.868714339,46.51254181 +182.12,50.4309582,-2.573605156,49.1214,6.862007489,7.255881068,2.5196875,-9.653115927,-1.952825632,46.52006686 +182.13,50.43095881,-2.573604135,49.0964,6.862007469,7.257879321,2.4828125,-9.573800291,-2.035234037,46.52759198 +182.14,50.43095943,-2.573603113,49.0717,6.87938841,7.259211449,2.443125,-9.493529476,-2.115867706,46.53511703 +182.15,50.43096005,-2.573602091,49.0475,6.889816958,7.259211327,2.4015625,-9.412320272,-2.194656278,46.54264214 +182.16,50.43096067,-2.57360107,49.0237,6.879388347,7.259433247,2.36,-9.33018958,-2.271531057,46.5501672 +182.17,50.43096129,-2.573600048,49.0003,6.862007351,7.260543335,2.318125,-9.247154588,-2.346425063,46.55769231 +182.18,50.4309619,-2.573599026,48.9773,6.862007323,7.261431381,2.2746875,-9.163232658,-2.41927298,46.56521737 +182.19,50.43096252,-2.573598004,48.9548,6.879388265,7.261875345,2.23,-9.078441264,-2.490011209,46.57274248 +182.2,50.43096314,-2.573596982,48.9327,6.889816826,7.262763392,2.185,-8.992798168,-2.558578156,46.58026754 +182.21,50.43096376,-2.57359596,48.9111,6.879388229,7.264095523,2.139375,-8.90632119,-2.624913949,46.58779265 +182.22,50.43096438,-2.573594937,48.8899,6.862007247,7.265205614,2.0915625,-8.819028491,-2.688960776,46.59531771 +182.23,50.43096499,-2.573593915,48.8692,6.862007232,7.266315705,2.0415625,-8.730938178,-2.750662773,46.60284282 +182.24,50.43096561,-2.573592892,48.8491,6.875911983,7.267647837,1.991875,-8.6420687,-2.809966197,46.61036788 +182.25,50.43096623,-2.573591869,48.8294,6.875911951,7.268535887,1.9434375,-8.552438678,-2.866819252,46.61789299 +182.26,50.43096685,-2.573590846,48.8102,6.862007153,7.268757812,1.894375,-8.462066732,-2.921172434,46.62541804 +182.27,50.43096746,-2.573589823,48.7915,6.862007145,7.268979738,1.843125,-8.370971771,-2.972978247,46.63294316 +182.28,50.43096808,-2.5735888,48.7733,6.875911913,7.270089831,1.79,-8.279172817,-3.022191655,46.64046821 +182.29,50.4309687,-2.573587777,48.7557,6.875911892,7.272088093,1.7365625,-8.186689064,-3.068769628,46.64799333 +182.3,50.43096932,-2.573586753,48.7386,6.862007079,7.273420229,1.683125,-8.09353982,-3.112671603,46.65551838 +182.31,50.43096993,-2.573585729,48.722,6.858530846,7.273420115,1.628125,-7.999744566,-3.153859247,46.6630435 +182.32,50.43097055,-2.573584706,48.706,6.862007024,7.273642044,1.5715625,-7.905322783,-3.192296693,46.67056855 +182.33,50.43097117,-2.573583682,48.6906,6.858530835,7.274974183,1.5153125,-7.810294295,-3.227950425,46.67809366 +182.34,50.43097178,-2.573582658,48.6757,6.858530836,7.276750405,1.4596875,-7.714678926,-3.260789329,46.68561872 +182.35,50.4309724,-2.573581634,48.6614,6.862007011,7.278082544,1.403125,-7.618496616,-3.290784758,46.69314383 +182.36,50.43097302,-2.573580609,48.6476,6.858530791,7.278304475,1.345,-7.521767475,-3.317910585,46.70066889 +182.37,50.43097363,-2.573579585,48.6345,6.858530778,7.278082324,1.2865625,-7.424511728,-3.342143205,46.708194 +182.38,50.43097425,-2.573578561,48.6219,6.862006971,7.278526299,1.2284375,-7.326749601,-3.36346136,46.71571906 +182.39,50.43097487,-2.573577536,48.6099,6.855054579,7.279414358,1.1696875,-7.228501548,-3.381846545,46.72324417 +182.4,50.43097548,-2.573576512,48.5985,6.844625984,7.280524459,1.1096875,-7.129788139,-3.397282715,46.73076923 +182.41,50.4309761,-2.573575487,48.5877,6.844625964,7.281856602,1.0484375,-7.030629943,-3.40975635,46.73829434 +182.42,50.43097671,-2.573574462,48.5775,6.855054526,7.282966704,0.9865625,-6.931047644,-3.419256678,46.7458194 +182.43,50.43097733,-2.573573437,48.568,6.862006905,7.284298849,0.925,-6.831062154,-3.425775391,46.75334451 +182.44,50.43097795,-2.573572412,48.559,6.855054519,7.286297118,0.8634375,-6.730694215,-3.429306701,46.76086956 +182.45,50.43097856,-2.573571386,48.5507,6.844625932,7.287629264,0.80125,-6.629964797,-3.429847688,46.76839462 +182.46,50.43097918,-2.57357036,48.543,6.841149714,7.287407119,0.7384375,-6.528895042,-3.427397721,46.77591973 +182.47,50.43097979,-2.573569335,48.5359,6.841149685,7.286962934,0.675,-6.427505978,-3.421959033,46.78344479 +182.48,50.43098041,-2.573568309,48.5295,6.841149679,7.287850999,0.611875,-6.325818803,-3.413536382,46.7909699 +182.49,50.43098102,-2.573567284,48.5237,6.841149696,7.289849273,0.55,-6.223854776,-3.402137043,46.79849496 +182.5,50.43098164,-2.573566257,48.5185,6.841149709,7.291181422,0.488125,-6.121635094,-3.387770985,46.80602007 +182.51,50.43098225,-2.573565231,48.5139,6.841149709,7.291181322,0.4246875,-6.019181245,-3.370450758,46.81354513 +182.52,50.43098287,-2.573564205,48.51,6.844625898,7.291625306,0.36,-5.916514485,-3.350191486,46.82107024 +182.53,50.43098348,-2.573563179,48.5067,6.855054469,7.293401541,0.295,-5.813656356,-3.327010759,46.8285953 +182.54,50.4309841,-2.573562152,48.5041,6.85853065,7.294733694,0.23,-5.710628346,-3.300928804,46.83612041 +182.55,50.43098472,-2.573561125,48.5021,6.841149677,7.294733597,0.165,-5.607451883,-3.271968423,46.84364546 +182.56,50.43098533,-2.573560099,48.5008,6.823768716,7.294955543,0.1,-5.504148566,-3.240154827,46.85117058 +182.57,50.43098594,-2.573559072,48.5001,6.827244919,7.296065656,0.0353125,-5.400739997,-3.205515746,46.85869563 +182.58,50.43098656,-2.573558045,48.5001,6.837673503,7.297175769,-0.0284375,-5.297247662,-3.168081434,46.86622075 +182.59,50.43098717,-2.573557018,48.5007,6.84114969,7.298285883,-0.0915625,-5.193693333,-3.127884492,46.8737458 +182.6,50.43098779,-2.573555991,48.5019,6.841149681,7.29961804,-0.1553125,-5.090098496,-3.084960041,46.88127092 +182.61,50.4309884,-2.573554963,48.5038,6.841149681,7.300728156,-0.22,-4.986484865,-3.039345381,46.88879597 +182.62,50.43098902,-2.573553936,48.5063,6.841149687,7.301838272,-0.2846875,-4.882874042,-2.99108039,46.89632108 +182.63,50.43098963,-2.573552908,48.5095,6.837673494,7.303170431,-0.3484375,-4.779287742,-2.940207181,46.90384614 +182.64,50.43099025,-2.57355188,48.5133,6.827244916,7.303836465,-0.4115625,-4.67574745,-2.886770043,46.91137125 +182.65,50.43099086,-2.573550852,48.5177,6.820292535,7.303392293,-0.4753125,-4.572274939,-2.830815558,46.91889631 +182.66,50.43099147,-2.573549824,48.5228,6.823768733,7.303170163,-0.54,-4.468891695,-2.772392598,46.92642142 +182.67,50.43099209,-2.573548797,48.5285,6.823768743,7.304502325,-0.6046875,-4.365619433,-2.711552044,46.93394648 +182.68,50.4309927,-2.573547768,48.5349,6.820292567,7.306500612,-0.668125,-4.262479582,-2.648347007,46.94147159 +182.69,50.43099331,-2.57354674,48.5419,6.827244973,7.307610733,-0.73,-4.159493798,-2.582832549,46.94899665 +182.7,50.43099393,-2.573545711,48.5495,6.837673567,7.30805473,-0.791875,-4.05668357,-2.515065851,46.95652176 +182.71,50.43099454,-2.573544683,48.5577,6.837673576,7.308942812,-0.8546875,-3.954070266,-2.445105928,46.96404682 +182.72,50.43099516,-2.573543654,48.5666,6.827245001,7.310274977,-0.9165625,-3.851675432,-2.373013857,46.97157193 +182.73,50.43099577,-2.573542625,48.5761,6.820292614,7.311163059,-0.9765625,-3.749520437,-2.298852549,46.97909698 +182.74,50.43099638,-2.573541596,48.5861,6.823768809,7.31160706,-1.036875,-3.64762654,-2.222686519,46.9866221 +182.75,50.430997,-2.573540567,48.5968,6.820292627,7.312717186,-1.0984375,-3.54601511,-2.144582288,46.99414715 +182.76,50.43099761,-2.573539538,48.6081,6.806387873,7.314715479,-1.1596875,-3.444707291,-2.064607979,47.00167227 +182.77,50.43099822,-2.573538508,48.62,6.806387896,7.316047647,-1.2196875,-3.343724282,-1.982833323,47.00919732 +182.78,50.43099883,-2.573537478,48.6325,6.82029269,7.316047566,-1.2784375,-3.243087167,-1.899329537,47.01672244 +182.79,50.43099945,-2.573536449,48.6456,6.823768894,7.316269528,-1.3365625,-3.142816975,-1.814169559,47.02424749 +182.8,50.43100006,-2.573535419,48.6592,6.820292697,7.317379658,-1.3946875,-3.042934618,-1.727427588,47.03177255 +182.81,50.43100067,-2.573534389,48.6735,6.823768886,7.318267746,-1.451875,-2.943460951,-1.639179253,47.03929766 +182.82,50.43100129,-2.573533359,48.6883,6.820292708,7.318711752,-1.5078125,-2.844416831,-1.549501561,47.04682272 +182.83,50.4310019,-2.573532329,48.7036,6.802911775,7.319599841,-1.56375,-2.745822827,-1.458472662,47.05434783 +182.84,50.43100251,-2.573531299,48.7196,6.792483227,7.320932014,-1.6196875,-2.647699564,-1.366171969,47.06187289 +182.85,50.43100312,-2.573530268,48.736,6.802911833,7.321820105,-1.6746875,-2.550067613,-1.272679924,47.069398 +182.86,50.43100373,-2.573529238,48.7531,6.820292824,7.322264113,-1.7284375,-2.452947256,-1.178078118,47.07692305 +182.87,50.43100435,-2.573528207,48.7706,6.820292841,7.323374246,-1.78125,-2.356358776,-1.082448998,47.08444817 +182.88,50.43100496,-2.573527177,48.7887,6.806388075,7.325372546,-1.8334375,-2.260322455,-0.98587593,47.09197322 +182.89,50.43100557,-2.573526145,48.8073,6.806388084,7.326704722,-1.885,-2.164858233,-0.888443197,47.09949834 +182.9,50.43100618,-2.573525114,48.8264,6.820292884,7.32670465,-1.9365625,-2.069986162,-0.79023571,47.10702339 +182.91,50.4310068,-2.573524083,48.846,6.820292916,7.32692662,-1.9878125,-1.975725896,-0.691339183,47.1145485 +182.92,50.43100741,-2.573523052,48.8662,6.802911975,7.328036756,-2.0365625,-1.882097258,-0.591839734,47.12207356 +182.93,50.43100802,-2.57352202,48.8868,6.789007221,7.329146893,-2.083125,-1.789119787,-0.491824221,47.12959867 +182.94,50.43100863,-2.573520989,48.9078,6.78553105,7.33025703,-2.1303125,-1.696812791,-0.39137985,47.13712373 +182.95,50.43100924,-2.573519957,48.9294,6.789007266,7.331367168,-2.178125,-1.605195694,-0.29059411,47.14464884 +182.96,50.43100985,-2.573518925,48.9514,6.80291206,7.331367099,-2.224375,-1.514287517,-0.189555065,47.1521739 +182.97,50.43101046,-2.573517893,48.9739,6.820293046,7.330700906,-2.2684375,-1.424107284,-0.088350665,47.15969901 +182.98,50.43101108,-2.573516862,48.9968,6.820293071,7.331589003,-2.31125,-1.334673843,0.012930741,47.16722407 +182.99,50.43101169,-2.57351583,49.0201,6.802912135,7.334031392,-2.3534375,-1.246005874,0.114200916,47.17474918 +183,50.4310123,-2.573514797,49.0439,6.789007392,7.335807657,-2.395,-1.158121883,0.215371455,47.18227424 +183.01,50.43101291,-2.573513765,49.068,6.785531226,7.336251674,-2.43625,-1.071040205,0.316354235,47.18979935 +183.02,50.43101352,-2.573512732,49.0926,6.785531252,7.33647365,-2.4765625,-0.984779003,0.417061136,47.19732441 +183.03,50.43101413,-2.5735117,49.1176,6.78553128,7.33736175,-2.5146875,-0.899356381,0.517404323,47.20484952 +183.04,50.43101474,-2.573510667,49.1429,6.785531303,7.338693934,-2.5515625,-0.814790102,0.617296363,47.21237457 +183.05,50.43101535,-2.573509634,49.1686,6.785531313,7.339582035,-2.588125,-0.731097871,0.71665011,47.21989969 +183.06,50.43101596,-2.573508601,49.1947,6.78553132,7.340026053,-2.623125,-0.648297104,0.815378931,47.22742474 +183.07,50.43101657,-2.573507568,49.2211,6.785531349,7.341136197,-2.6565625,-0.566405163,0.913396712,47.23494986 +183.08,50.43101718,-2.573506535,49.2478,6.7855314,7.343134507,-2.69,-0.485439122,1.010617967,47.24247491 +183.09,50.43101779,-2.573505501,49.2749,6.785531447,7.344466693,-2.7228125,-0.405415883,1.106958013,47.25000002 +183.1,50.4310184,-2.573504467,49.3023,6.785531481,7.34446663,-2.753125,-0.326352176,1.202332739,47.25752508 +183.11,50.43101901,-2.573503434,49.33,6.785531512,7.344688609,-2.7815625,-0.248264503,1.29665901,47.26505019 +183.12,50.43101962,-2.5735024,49.3579,6.785531542,7.345798754,-2.8096875,-0.171169136,1.389854549,47.27257525 +183.13,50.43102023,-2.573501366,49.3862,6.785531571,7.3469089,-2.8365625,-0.095082232,1.481838167,47.28010036 +183.14,50.43102084,-2.573500332,49.4147,6.785531593,7.348019045,-2.8615625,-0.020019661,1.572529594,47.28762542 +183.15,50.43102145,-2.573499298,49.4434,6.785531613,7.349351233,-2.8865625,0.054002876,1.661849704,47.29515047 +183.16,50.43102206,-2.573498263,49.4724,6.785531645,7.350239338,-2.91125,0.126970026,1.749720688,47.30267559 +183.17,50.43102267,-2.573497229,49.5017,6.785531688,7.350461319,-2.933125,0.198866431,1.836065886,47.31020064 +183.18,50.43102328,-2.573496194,49.5311,6.785531728,7.3506833,-2.953125,0.269677082,1.920810011,47.31772576 +183.19,50.43102389,-2.57349516,49.5607,6.785531763,7.351571405,-2.973125,0.339387253,2.003879208,47.32525081 +183.2,50.4310245,-2.573494125,49.5906,6.785531795,7.352903593,-2.9915625,0.40798239,2.085200942,47.33277593 +183.21,50.43102511,-2.57349309,49.6206,6.785531828,7.353791699,-3.0078125,0.475448113,2.164704336,47.34030098 +183.22,50.43102572,-2.573492055,49.6507,6.785531861,7.354235722,-3.0234375,0.541770385,2.242320064,47.34782609 +183.23,50.43102633,-2.57349102,49.6811,6.782055699,7.35534587,-3.038125,0.606935338,2.317980516,47.35535115 +183.24,50.43102694,-2.573489985,49.7115,6.76815095,7.357344184,-3.05125,0.670929338,2.39161963,47.36287626 +183.25,50.43102755,-2.573488949,49.7421,6.750769999,7.358676375,-3.0634375,0.733738977,2.463173178,47.37040132 +183.26,50.43102815,-2.573487913,49.7728,6.750770021,7.358676316,-3.074375,0.795351249,2.532578879,47.37792643 +183.27,50.43102876,-2.573486878,49.8036,6.76815103,7.358898298,-3.083125,0.855753262,2.599776056,47.38545149 +183.28,50.43102937,-2.573485842,49.8345,6.782055855,7.360008447,-3.09,0.914932353,2.664706212,47.3929766 +183.29,50.43102998,-2.573484806,49.8654,6.785532092,7.360896554,-3.09625,0.972876205,2.727312737,47.40050166 +183.3,50.43103059,-2.57348377,49.8964,6.782055933,7.361118537,-3.1015625,1.029572671,2.787540972,47.40802677 +183.31,50.4310312,-2.573482734,49.9275,6.768151186,7.361562561,-3.1046875,1.085009947,2.845338434,47.41555183 +183.32,50.43103181,-2.573481698,49.9585,6.750770244,7.363338834,-3.1065625,1.139176403,2.900654759,47.42307694 +183.33,50.43103241,-2.573480662,49.9896,6.750770278,7.36555919,-3.1084375,1.192060809,2.953441647,47.43060199 +183.34,50.43103302,-2.573479624,50.0207,6.768151287,7.366003215,-3.109375,1.243652106,3.003653032,47.43812711 +183.35,50.43103363,-2.573478588,50.0518,6.778579907,7.365781115,-3.108125,1.293939466,3.051245256,47.44565216 +183.36,50.43103424,-2.573477552,50.0829,6.76815135,7.367335346,-3.1046875,1.34291246,3.096176721,47.45317728 +183.37,50.43103485,-2.573476514,50.1139,6.75077039,7.369111619,-3.1,1.390560777,3.138408294,47.46070233 +183.38,50.43103545,-2.573475477,50.1449,6.750770402,7.369111561,-3.0946875,1.436874502,3.177903134,47.46822744 +183.39,50.43103606,-2.57347444,50.1758,6.764675216,7.368667419,-3.088125,1.481843954,3.214626749,47.4757525 +183.4,50.43103667,-2.573473403,50.2067,6.764675271,7.369555526,-3.0796875,1.525459793,3.248547169,47.48327761 +183.41,50.43103728,-2.573472366,50.2374,6.750770541,7.371775881,-3.07,1.567712852,3.279634827,47.49080267 +183.42,50.43103788,-2.573471328,50.2681,6.747294384,7.373774195,-3.0596875,1.608594365,3.307862624,47.49832778 +183.43,50.43103849,-2.57347029,50.2986,6.750770612,7.374218219,-3.0478125,1.648095737,3.333205866,47.50585284 +183.44,50.4310391,-2.573469252,50.3291,6.74729445,7.37421816,-3.0334375,1.686208718,3.355642549,47.51337795 +183.45,50.4310397,-2.573468215,50.3593,6.750770678,7.375328309,-3.018125,1.7229254,3.375153022,47.52090301 +183.46,50.43104031,-2.573467176,50.3894,6.764675492,7.376660497,-3.003125,1.75823805,3.391720326,47.52842812 +183.47,50.43104092,-2.573466138,50.4194,6.764675524,7.377326561,-2.98625,1.792139389,3.405329965,47.53595318 +183.48,50.43104153,-2.5734651,50.4492,6.750770775,7.377992626,-2.9665625,1.8246222,3.415970192,47.54347829 +183.49,50.43104213,-2.573464061,50.4787,6.747294612,7.378880731,-2.9465625,1.855679836,3.423631554,47.55100335 +183.5,50.43104274,-2.573463023,50.5081,6.750770837,7.379768837,-2.9265625,1.885305707,3.42830752,47.5585284 +183.51,50.43104335,-2.573461984,50.5373,6.743818468,7.3804349,-2.904375,1.913493684,3.429993907,47.56605351 +183.52,50.43104395,-2.573460945,50.5662,6.733389902,7.380878922,-2.8796875,1.940237921,3.428689282,47.57357857 +183.53,50.43104456,-2.573459907,50.5949,6.733389933,7.381544986,-2.8534375,1.96553269,3.424394849,47.58110368 +183.54,50.43104516,-2.573458867,50.6233,6.743818562,7.38243309,-2.8265625,1.989372834,3.417114217,47.58862874 +183.55,50.43104577,-2.573457829,50.6514,6.750770992,7.383543235,-2.8,2.011753367,3.40685386,47.59615385 +183.56,50.43104638,-2.573456789,50.6793,6.747294829,7.384875422,-2.7728125,2.032669536,3.393622661,47.60367891 +183.57,50.43104698,-2.57345575,50.7069,6.747294859,7.385763525,-2.743125,2.052117041,3.377432191,47.61120402 +183.58,50.43104759,-2.57345471,50.7342,6.750771084,7.386207545,-2.7115625,2.070091816,3.358296547,47.61872908 +183.59,50.4310482,-2.573453671,50.7611,6.743818722,7.387095647,-2.6796875,2.086590078,3.3362324,47.62625419 +183.6,50.4310488,-2.573452631,50.7878,6.733390164,7.388649874,-2.6465625,2.101608448,3.311259004,47.63377925 +183.61,50.43104941,-2.573451591,50.8141,6.729913997,7.390426141,-2.61125,2.115143659,3.283398186,47.64130436 +183.62,50.43105001,-2.573450551,50.84,6.729914025,7.391758325,-2.575,2.127193019,3.252674126,47.64882941 +183.63,50.43105062,-2.57344951,50.8656,6.729914053,7.391980302,-2.5384375,2.137753891,3.219113754,47.65635453 +183.64,50.43105122,-2.57344847,50.8908,6.72991408,7.391980237,-2.50125,2.146824214,3.182746232,47.66387958 +183.65,50.43105183,-2.57344743,50.9156,6.729914107,7.393090379,-2.463125,2.154401982,3.143603302,47.6714047 +183.66,50.43105243,-2.573446389,50.9401,6.729914133,7.394200519,-2.423125,2.160485591,3.101719113,47.67892975 +183.67,50.43105304,-2.573445348,50.9641,6.72991416,7.394200453,-2.3815625,2.165073894,3.057130163,47.68645487 +183.68,50.43105364,-2.573444308,50.9877,6.729914185,7.394422427,-2.34,2.168165861,3.009875411,47.69397992 +183.69,50.43105425,-2.573443267,51.0109,6.72991421,7.395754608,-2.2978125,2.169760803,2.95999594,47.70150503 +183.7,50.43105485,-2.573442226,51.0337,6.729914233,7.397530872,-2.253125,2.169858493,2.907535294,47.70903009 +183.71,50.43105546,-2.573441185,51.056,6.729914248,7.399085093,-2.206875,2.168458814,2.85253931,47.7165552 +183.72,50.43105606,-2.573440143,51.0778,6.729914261,7.399973189,-2.1615625,2.165562054,2.795055829,47.72408026 +183.73,50.43105667,-2.573439102,51.0992,6.729914284,7.400195161,-2.1165625,2.1611689,2.735134986,47.73160537 +183.74,50.43105727,-2.57343806,51.1202,6.729914318,7.400417133,-2.069375,2.155280269,2.672829092,47.73913043 +183.75,50.43105788,-2.573437019,51.1406,6.729914349,7.401305228,-2.02,2.147897307,2.608192463,47.74665554 +183.76,50.43105848,-2.573435977,51.1606,6.729914373,7.402637405,-1.97,2.13902156,2.54128142,47.7541806 +183.77,50.43105909,-2.573434935,51.18,6.729914395,7.403747539,-1.9196875,2.128654978,2.472154406,47.76170571 +183.78,50.43105969,-2.573433893,51.199,6.726438219,7.404857674,-1.8684375,2.116799621,2.400871581,47.76923077 +183.79,50.4310603,-2.573432851,51.2174,6.716009652,7.405967808,-1.81625,2.10345807,2.327495168,47.77675588 +183.8,50.4310609,-2.573431808,51.2353,6.70905728,7.406189776,-1.7634375,2.088633016,2.252089166,47.78428093 +183.81,50.4310615,-2.573430766,51.2527,6.716009691,7.406189701,-1.7096875,2.072327611,2.174719295,47.79180605 +183.82,50.43106211,-2.573429724,51.2695,6.726438297,7.407299833,-1.655,2.054545179,2.09545299,47.7993311 +183.83,50.43106271,-2.573428681,51.2858,6.726438314,7.408632007,-1.6,2.035289557,2.014359466,47.80685616 +183.84,50.43106332,-2.573427638,51.3015,6.716009744,7.409520097,-1.545,2.014564699,1.931509425,47.81438127 +183.85,50.43106392,-2.573426596,51.3167,6.709057369,7.410852268,-1.4896875,1.992374961,1.846975003,47.82190633 +183.86,50.43106452,-2.573425552,51.3313,6.712533581,7.411962397,-1.433125,1.968724925,1.760830053,47.82943144 +183.87,50.43106513,-2.573424509,51.3454,6.712533596,7.411962319,-1.375,1.943619518,1.673149577,47.8369565 +183.88,50.43106573,-2.573423466,51.3588,6.709057415,7.412406323,-1.3165625,1.91706407,1.584010121,47.84448161 +183.89,50.43106633,-2.573422423,51.3717,6.712533626,7.414404616,-1.2584375,1.889064081,1.493489379,47.85200667 +183.9,50.43106694,-2.573421379,51.384,6.712533639,7.416402908,-1.1996875,1.859625395,1.401666303,47.85953178 +183.91,50.43106754,-2.573420335,51.3957,6.709057456,7.416624869,-1.14,1.8287542,1.308620994,47.86705683 +183.92,50.43106814,-2.573419291,51.4068,6.712533665,7.415736622,-1.0796875,1.796456856,1.214434467,47.87458195 +183.93,50.43106875,-2.573418248,51.4173,6.70905748,7.415958581,-1.0184375,1.76274018,1.119189,47.882107 +183.94,50.43106935,-2.573417204,51.4272,6.695152708,7.41795687,-0.9565625,1.727611164,1.022967556,47.88963212 +183.95,50.43106995,-2.57341616,51.4364,6.695152718,7.420177201,-0.895,1.691077197,0.925854075,47.89715717 +183.96,50.43107055,-2.573415115,51.4451,6.709057512,7.421287323,-0.8334375,1.653145902,0.827933181,47.90468229 +183.97,50.43107116,-2.573414071,51.4531,6.709057521,7.42150928,-0.77125,1.613825183,0.729290361,47.91220734 +183.98,50.43107176,-2.573413026,51.4605,6.695152745,7.421731236,-0.7084375,1.573123236,0.630011615,47.91973245 +183.99,50.43107236,-2.573411982,51.4673,6.695152753,7.422619315,-0.645,1.531048538,0.530183459,47.92725751 +184,50.43107296,-2.573410937,51.4734,6.709057544,7.423951475,-0.581875,1.487609972,0.429892984,47.93478262 +184.01,50.43107357,-2.573409892,51.4789,6.709057551,7.425061593,-0.52,1.442816533,0.329227622,47.94230768 +184.02,50.43107417,-2.573408847,51.4838,6.691676577,7.426171712,-0.4578125,1.396677559,0.228275209,47.94983279 +184.03,50.43107477,-2.573407802,51.4881,6.681247994,7.42728183,-0.393125,1.349202792,0.127123693,47.95735785 +184.04,50.43107537,-2.573406756,51.4917,6.691676586,7.427503781,-0.326875,1.300402029,0.025861367,47.96488296 +184.05,50.43107597,-2.573405711,51.4946,6.70905757,7.42750369,-0.261875,1.250285525,-0.075423534,47.97240802 +184.06,50.43107658,-2.573404666,51.4969,6.709057573,7.428613804,-0.1984375,1.198863709,-0.176642716,47.97993313 +184.07,50.43107718,-2.57340362,51.4986,6.691676596,7.42994596,-0.1346875,1.146147352,-0.277707773,47.98745819 +184.08,50.43107778,-2.573402574,51.4996,6.677771814,7.430834033,-0.07,1.092147455,-0.378530755,47.9949833 +184.09,50.43107838,-2.573401529,51.5,6.674295619,7.432166188,-0.0053125,1.036875247,-0.479023599,48.00250835 +184.1,50.43107898,-2.573400482,51.4997,6.677771815,7.4332763,0.0584375,0.980342361,-0.579098699,48.01003347 +184.11,50.43107958,-2.573399436,51.4988,6.691676599,7.433276204,0.121875,0.922560542,-0.678668852,48.01755852 +184.12,50.43108018,-2.57339839,51.4973,6.709057578,7.433498149,0.1865625,0.863541878,-0.777647197,48.02508364 +184.13,50.43108079,-2.573397344,51.4951,6.709057576,7.434608258,0.251875,0.803298689,-0.875947446,48.03260869 +184.14,50.43108139,-2.573396297,51.4922,6.691676594,7.435718367,0.31625,0.74184358,-0.973483827,48.04013381 +184.15,50.43108199,-2.573395251,51.4888,6.677771807,7.436828476,0.38,0.679189327,-1.070171315,48.04765886 +184.16,50.43108259,-2.573394204,51.4846,6.674295607,7.438160624,0.4434375,0.615349052,-1.165925568,48.05518397 +184.17,50.43108319,-2.573393157,51.4799,6.674295603,7.43904869,0.5065625,0.550336104,-1.260663166,48.06270903 +184.18,50.43108379,-2.57339211,51.4745,6.674295598,7.439492673,0.5703125,0.484164005,-1.354301429,48.07023409 +184.19,50.43108439,-2.573391063,51.4685,6.674295593,7.440380737,0.6346875,0.41684662,-1.446758712,48.0777592 +184.2,50.43108499,-2.573390016,51.4618,6.674295586,7.441712882,0.698125,0.348397988,-1.537954456,48.08528425 +184.21,50.43108559,-2.573388968,51.4545,6.674295579,7.442600944,0.76,0.278832432,-1.62780902,48.09280937 +184.22,50.43108619,-2.573387921,51.4466,6.674295572,7.442822882,0.821875,0.208164448,-1.716244139,48.10033442 +184.23,50.43108679,-2.573386873,51.4381,6.674295563,7.44304482,0.885,0.136408818,-1.803182635,48.10785954 +184.24,50.43108739,-2.573385826,51.4289,6.674295555,7.444154921,0.9478125,0.063580554,-1.888548763,48.11538459 +184.25,50.43108799,-2.573384778,51.4191,6.674295545,7.446375228,1.008125,-0.010305276,-1.972268038,48.12290971 +184.26,50.43108859,-2.57338373,51.4087,6.674295535,7.448373494,1.066875,-0.08523303,-2.054267466,48.13043476 +184.27,50.43108919,-2.573382681,51.3978,6.674295524,7.448817469,1.126875,-0.161187237,-2.134475484,48.13795987 +184.28,50.43108979,-2.573381633,51.3862,6.674295513,7.44859532,1.188125,-0.23815197,-2.212822306,48.14548493 +184.29,50.43109039,-2.573380585,51.374,6.674295501,7.449039294,1.248125,-0.316111129,-2.289239463,48.15301004 +184.3,50.43109099,-2.573379536,51.3612,6.674295488,7.44992735,1.3065625,-0.395048498,-2.363660378,48.1605351 +184.31,50.43109159,-2.573378488,51.3479,6.674295475,7.451037447,1.365,-0.47494752,-2.436020135,48.16806021 +184.32,50.43109219,-2.573377439,51.3339,6.674295461,7.452369583,1.423125,-0.555791521,-2.506255651,48.17558527 +184.33,50.43109279,-2.57337639,51.3194,6.674295446,7.453257637,1.4796875,-0.637563657,-2.574305676,48.18311038 +184.34,50.43109339,-2.573375341,51.3043,6.674295431,7.453479567,1.535,-0.720246852,-2.640110853,48.19063544 +184.35,50.43109399,-2.573374292,51.2887,6.674295415,7.453701496,1.59,-0.803823805,-2.703613828,48.19816055 +184.36,50.43109459,-2.573373243,51.2725,6.674295399,7.454811588,1.645,-0.888277039,-2.764759254,48.20568561 +184.37,50.43109519,-2.573372194,51.2558,6.670819186,7.456809845,1.6996875,-0.973589022,-2.82349373,48.21321072 +184.38,50.43109579,-2.573371144,51.2385,6.656914386,7.458141978,1.7534375,-1.059741821,-2.879766035,48.22073577 +184.39,50.43109639,-2.573370094,51.2207,6.639533388,7.458141864,1.8065625,-1.146717502,-2.933527181,48.22826089 +184.4,50.43109698,-2.573369045,51.2024,6.63953337,7.45836379,1.8596875,-1.234497902,-2.984730299,48.23578594 +184.41,50.43109758,-2.573367995,51.1835,6.65691433,7.45947388,1.9115625,-1.323064687,-3.033330642,48.24331106 +184.42,50.43109818,-2.573366945,51.1641,6.670819094,7.460361929,1.96125,-1.412399349,-3.079285868,48.25083611 +184.43,50.43109878,-2.573365895,51.1443,6.67429527,7.460805893,2.01,-1.502483212,-3.122555869,48.25836123 +184.44,50.43109938,-2.573364845,51.1239,6.670819053,7.461693939,2.0584375,-1.593297481,-3.163103004,48.26588628 +184.45,50.43109998,-2.573363795,51.1031,6.656914249,7.463026068,2.10625,-1.684823248,-3.200891862,48.27341139 +184.46,50.43110058,-2.573362744,51.0818,6.639533249,7.464136155,2.1534375,-1.777041264,-3.2358895,48.28093645 +184.47,50.43110117,-2.573361694,51.06,6.639533226,7.465246242,2.1996875,-1.869932448,-3.268065434,48.28846156 +184.48,50.43110177,-2.573360643,51.0378,6.656914183,7.466578369,2.245,-1.963477261,-3.297391477,48.29598662 +184.49,50.43110237,-2.573359592,51.0151,6.667342749,7.467466413,2.2896875,-2.057656225,-3.323842245,48.30351173 +184.5,50.43110297,-2.573358541,50.992,6.656914148,7.467688333,2.333125,-2.152449628,-3.347394478,48.31103679 +184.51,50.43110357,-2.57335749,50.9684,6.639533156,7.467910253,2.375,-2.247837705,-3.368027777,48.3185619 +184.52,50.43110416,-2.573356439,50.9445,6.639533132,7.469020336,2.41625,-2.343800572,-3.385724094,48.32608696 +184.53,50.43110476,-2.573355388,50.9201,6.653437881,7.471018584,2.4565625,-2.440318121,-3.400468017,48.33361201 +184.54,50.43110536,-2.573354336,50.8953,6.653437856,7.472350708,2.4946875,-2.537370238,-3.412246711,48.34113713 +184.55,50.43110596,-2.573353284,50.8702,6.639533057,7.472350585,2.5315625,-2.6349367,-3.421049864,48.34866218 +184.56,50.43110655,-2.573352233,50.8447,6.636056835,7.472572502,2.5684375,-2.732996994,-3.426869797,48.35618729 +184.57,50.43110715,-2.573351181,50.8188,6.639532993,7.473682583,2.6046875,-2.831530781,-3.429701412,48.36371235 +184.58,50.43110775,-2.573350129,50.7926,6.636056762,7.474570623,2.6396875,-2.930517376,-3.429542302,48.37123746 +184.59,50.43110834,-2.573349077,50.766,6.639532929,7.47501458,2.6734375,-3.029936153,-3.426392581,48.37876252 +184.6,50.43110894,-2.573348025,50.7391,6.653437684,7.47590262,2.70625,-3.129766371,-3.420255,48.38628763 +184.61,50.43110954,-2.573346973,50.7119,6.653437656,7.477234741,2.738125,-3.229987175,-3.411134944,48.39381269 +184.62,50.43111014,-2.57334592,50.6843,6.639532846,7.47834482,2.768125,-3.330577651,-3.399040263,48.4013378 +184.63,50.43111073,-2.573344868,50.6565,6.636056622,7.479232858,2.79625,-3.431516714,-3.383981615,48.40886286 +184.64,50.43111133,-2.573343815,50.6284,6.639532789,7.479898854,2.8234375,-3.532783338,-3.365972061,48.41638797 +184.65,50.43111193,-2.573342762,50.6,6.636056564,7.48056485,2.8496875,-3.634356379,-3.34502736,48.42391303 +184.66,50.43111252,-2.57334171,50.5714,6.636056535,7.481896969,2.8746875,-3.736214638,-3.321165673,48.43143814 +184.67,50.43111312,-2.573340656,50.5425,6.639532701,7.483007046,2.898125,-3.838336802,-3.294407971,48.43896319 +184.68,50.43111372,-2.573339603,50.5134,6.632580281,7.483006919,2.92,-3.940701614,-3.264777459,48.44648831 +184.69,50.43111431,-2.57333855,50.4841,6.622151665,7.483450873,2.9415625,-4.043287587,-3.232299976,48.45401336 +184.7,50.43111491,-2.573337497,50.4546,6.622151634,7.485227073,2.963125,-4.146073351,-3.197003943,48.46153848 +184.71,50.4311155,-2.573336443,50.4248,6.632580193,7.486559191,2.9828125,-4.249037476,-3.158920011,48.46906353 +184.72,50.4311161,-2.573335389,50.3949,6.639532562,7.486559062,2.9996875,-4.35215842,-3.11808147,48.47658865 +184.73,50.4311167,-2.573334336,50.3648,6.632580152,7.487003014,3.015,-4.455414639,-3.074523958,48.4841137 +184.74,50.43111729,-2.573333282,50.3346,6.622151535,7.489001254,3.03,-4.558784648,-3.028285347,48.49163881 +184.75,50.43111789,-2.573332228,50.3042,6.618675297,7.490999495,3.0446875,-4.662246731,-2.979406089,48.49916387 +184.76,50.43111848,-2.573331173,50.2737,6.618675258,7.491221407,3.0578125,-4.765779403,-2.927928753,48.50668898 +184.77,50.43111908,-2.573330119,50.243,6.618675224,7.490333113,3.0684375,-4.869360947,-2.873898145,48.51421404 +184.78,50.43111967,-2.573329065,50.2123,6.618675195,7.490555024,3.0778125,-4.972969822,-2.817361535,48.52173915 +184.79,50.43112027,-2.573328011,50.1815,6.618675173,7.492553263,3.086875,-5.076584312,-2.758368081,48.52926421 +184.8,50.43112086,-2.573326956,50.1505,6.618675152,7.494773543,3.094375,-5.180182759,-2.696969294,48.53678932 +184.81,50.43112146,-2.573325901,50.1196,6.618675121,7.495883618,3.0996875,-5.283743677,-2.633218744,48.54431438 +184.82,50.43112205,-2.573324846,50.0885,6.618675078,7.496105529,3.1034375,-5.387245237,-2.567172008,48.55183949 +184.83,50.43112265,-2.573323791,50.0575,6.618675038,7.496105399,3.10625,-5.49066601,-2.498886611,48.55936455 +184.84,50.43112324,-2.573322736,50.0264,6.618675004,7.49632731,3.1084375,-5.593984281,-2.428422142,48.56688966 +184.85,50.43112384,-2.573321681,49.9953,6.618674975,7.497437384,3.109375,-5.697178506,-2.355840077,48.57441471 +184.86,50.43112443,-2.573320626,49.9642,6.618674952,7.499435623,3.1084375,-5.800227142,-2.281203673,48.58193983 +184.87,50.43112503,-2.57331957,49.9331,6.618674931,7.500767738,3.10625,-5.903108647,-2.204578074,48.58946488 +184.88,50.43112562,-2.573318514,49.9021,6.6186749,7.500767607,3.103125,-6.005801535,-2.126029972,48.59698994 +184.89,50.43112622,-2.573317459,49.871,6.618674857,7.500989519,3.098125,-6.108284375,-2.045628007,48.60451505 +184.9,50.43112681,-2.573316403,49.8401,6.618674817,7.502099594,3.09125,-6.210535799,-1.963442196,48.61204011 +184.91,50.43112741,-2.573315347,49.8092,6.618674783,7.502987628,3.0834375,-6.312534376,-1.879544216,48.61956522 +184.92,50.431128,-2.573314291,49.7784,6.615198557,7.503431579,3.0746875,-6.414258907,-1.794007289,48.62709028 +184.93,50.4311286,-2.573313235,49.7477,6.604769941,7.504319613,3.0646875,-6.515688021,-1.706905901,48.63461539 +184.94,50.43112919,-2.573312179,49.7171,6.597817519,7.505651729,3.053125,-6.616800633,-1.618316141,48.64214045 +184.95,50.43112978,-2.573311122,49.6866,6.601293684,7.506761805,3.04,-6.717575602,-1.528315128,48.64966556 +184.96,50.43113038,-2.573310066,49.6563,6.601293653,7.507871881,3.02625,-6.817991898,-1.436981416,48.65719061 +184.97,50.43113097,-2.573309009,49.6261,6.597817429,7.509203997,3.0115625,-6.918028496,-1.344394645,48.66471573 +184.98,50.43113156,-2.573307952,49.596,6.604769798,7.510092031,2.9946875,-7.017664539,-1.250635545,48.67224078 +184.99,50.43113216,-2.573306895,49.5662,6.615198364,7.510313943,2.9765625,-7.116879228,-1.15578582,48.6797659 +185,50.43113275,-2.573305838,49.5365,6.615198334,7.510535856,2.958125,-7.215651824,-1.059928319,48.68729095 +185.01,50.43113335,-2.573304781,49.507,6.60476971,7.511645932,2.9378125,-7.313961756,-0.963146465,48.69481607 +185.02,50.43113394,-2.573303724,49.4777,6.59781729,7.513644172,2.915,-7.411788398,-0.86552477,48.70234112 +185.03,50.43113453,-2.573302666,49.4487,6.601293465,7.51497629,2.8915625,-7.50911141,-0.767148318,48.70986623 +185.04,50.43113513,-2.573301608,49.4199,6.597817241,7.514976162,2.868125,-7.605910395,-0.668102937,48.71739129 +185.05,50.43113572,-2.573300551,49.3913,6.583912421,7.515198076,2.8428125,-7.702165127,-0.568474916,48.7249164 +185.06,50.43113631,-2.573299493,49.363,6.583912384,7.516308153,2.815,-7.797855611,-0.468351172,48.73244146 +185.07,50.4311369,-2.573298435,49.335,6.597817133,7.517418231,2.7865625,-7.892961792,-0.367819023,48.73996657 +185.08,50.4311375,-2.573297377,49.3073,6.597817107,7.518528309,2.758125,-7.987463789,-0.266966132,48.74749163 +185.09,50.43113809,-2.573296319,49.2798,6.583912309,7.519638388,2.728125,-8.081341892,-0.165880449,48.75501674 +185.1,50.43113868,-2.57329526,49.2527,6.583912292,7.519860303,2.69625,-8.174576507,-0.064650151,48.7625418 +185.11,50.43113927,-2.573294202,49.2259,6.597817045,7.519860178,2.6634375,-8.267148152,0.036636583,48.77006691 +185.12,50.43113987,-2.573293144,49.1994,6.597817007,7.521192299,2.6296875,-8.359037519,0.137891289,48.77759197 +185.13,50.43114046,-2.573292085,49.1733,6.583912193,7.522968501,2.5946875,-8.450225356,0.239025845,48.78511708 +185.14,50.43114105,-2.573291026,49.1475,6.583912164,7.523412459,2.558125,-8.540692699,0.339951903,48.79264213 +185.15,50.43114164,-2.573289967,49.1221,6.597816918,7.523412335,2.52,-8.630420583,0.440581569,48.80016725 +185.16,50.43114224,-2.573288909,49.0971,6.597816893,7.524744457,2.4815625,-8.719390271,0.54082701,48.8076923 +185.17,50.43114283,-2.573287849,49.0725,6.580435897,7.526742703,2.443125,-8.807583258,0.640600849,48.81521742 +185.18,50.43114342,-2.57328679,49.0482,6.570007297,7.527630744,2.403125,-8.894981094,0.739816054,48.82274247 +185.19,50.43114401,-2.57328573,49.0244,6.580435868,7.52718654,2.36125,-8.981565445,0.838386109,48.83026759 +185.2,50.4311446,-2.573284671,49.001,6.59781682,7.526964378,2.3184375,-9.067318377,0.936225127,48.83779264 +185.21,50.4311452,-2.573283612,48.978,6.597816795,7.528296503,2.275,-9.152221841,1.033247737,48.8453177 +185.22,50.43114579,-2.573282552,48.9555,6.580435801,7.53029475,2.23125,-9.236258191,1.129369314,48.85284281 +185.23,50.43114638,-2.573281492,48.9334,6.566530998,7.531404834,2.1865625,-9.319409837,1.224506091,48.86036787 +185.24,50.43114697,-2.573280432,48.9117,6.563054771,7.531848797,2.1396875,-9.401659476,1.318575104,48.86789298 +185.25,50.43114756,-2.573279372,48.8906,6.563054741,7.532736842,2.091875,-9.482989861,1.411494248,48.87541804 +185.26,50.43114815,-2.573278312,48.8699,6.566530913,7.534068969,2.045,-9.563384033,1.503182564,48.88294315 +185.27,50.43114874,-2.573277251,48.8497,6.580435673,7.534957015,1.9978125,-9.642825146,1.593560067,48.8904682 +185.28,50.43114933,-2.573276191,48.8299,6.597816635,7.53540098,1.9478125,-9.721296701,1.682548033,48.89799332 +185.29,50.43114993,-2.57327513,48.8107,6.597816627,7.536289026,1.895,-9.79878231,1.770068711,48.90551837 +185.3,50.43115052,-2.57327407,48.792,6.580435636,7.537399115,1.841875,-9.875265701,1.856045899,48.91304349 +185.31,50.43115111,-2.573273008,48.7739,6.566530828,7.537843081,1.79,-9.950731004,1.940404595,48.92056854 +185.32,50.4311517,-2.573271948,48.7562,6.563054607,7.538509089,1.738125,-10.0251624,2.023071175,48.92809365 +185.33,50.43115229,-2.573270887,48.7391,6.563054588,7.540063261,1.6846875,-10.09854432,2.103973675,48.93561871 +185.34,50.43115288,-2.573269825,48.7225,6.563054574,7.540951311,1.63,-10.1708615,2.183041449,48.94314382 +185.35,50.43115347,-2.573268764,48.7065,6.563054567,7.541173239,1.5746875,-10.24209884,2.260205572,48.95066888 +185.36,50.43115406,-2.573267703,48.691,6.563054563,7.542283332,1.5184375,-10.31224136,2.335398777,48.95819399 +185.37,50.43115465,-2.573266641,48.6761,6.56305455,7.543393425,1.4615625,-10.38127452,2.40855546,48.96571905 +185.38,50.43115524,-2.573265579,48.6618,6.563054534,7.543393315,1.405,-10.44918389,2.479611853,48.97324416 +185.39,50.43115583,-2.573264518,48.648,6.563054523,7.543615245,1.348125,-10.51595524,2.548506017,48.98076922 +185.4,50.43115642,-2.573263456,48.6348,6.563054508,7.54494738,1.2896875,-10.58157473,2.615177792,48.98829433 +185.41,50.43115701,-2.573262394,48.6222,6.563054484,7.546945639,1.23,-10.64602847,2.679569138,48.99581939 +185.42,50.4311576,-2.573261332,48.6102,6.563054466,7.54916594,1.17,-10.70930318,2.741623848,49.0033445 +185.43,50.43115819,-2.573260269,48.5988,6.563054462,7.550498078,1.1096875,-10.77138556,2.801287834,49.01086955 +185.44,50.43115878,-2.573259206,48.588,6.563054462,7.55027593,1.0484375,-10.83226267,2.858509014,49.01839467 +185.45,50.43115937,-2.573258144,48.5778,6.563054452,7.549609701,0.986875,-10.89192173,2.913237599,49.02591972 +185.46,50.43115996,-2.573257081,48.5683,6.563054432,7.549609596,0.9265625,-10.95035042,2.965425747,49.03344484 +185.47,50.43116055,-2.573256019,48.5593,6.55957822,7.550719696,0.8665625,-11.00753642,3.015028021,49.04096989 +185.48,50.43116114,-2.573254956,48.5509,6.545673432,7.55271796,0.804375,-11.06346781,3.062001106,49.04849501 +185.49,50.43116173,-2.573253893,48.5432,6.528292455,7.554050102,0.7403125,-11.11813291,3.106304094,49.05602006 +185.5,50.43116231,-2.573252829,48.5361,6.528292457,7.554050001,0.676875,-11.17152032,3.147898366,49.06354517 +185.51,50.4311629,-2.573251767,48.5297,6.545673435,7.55427194,0.615,-11.22361891,3.186747597,49.07107023 +185.52,50.43116349,-2.573250703,48.5238,6.559578209,7.555604084,0.553125,-11.27441775,3.222817983,49.07859534 +185.53,50.43116408,-2.57324964,48.5186,6.563054397,7.55738031,0.4896875,-11.32390629,3.256077954,49.0861204 +185.54,50.43116467,-2.573248576,48.514,6.563054395,7.558934496,0.425,-11.37207417,3.286498633,49.09364551 +185.55,50.43116526,-2.573247512,48.5101,6.559578195,7.559822561,0.36,-11.41891129,3.314053433,49.10117057 +185.56,50.43116585,-2.573246448,48.5068,6.545673406,7.560044504,0.2953125,-11.46440792,3.338718292,49.10869562 +185.57,50.43116644,-2.573245384,48.5042,6.528292432,7.560266448,0.2315625,-11.50855455,3.360471781,49.11622074 +185.58,50.43116702,-2.57324432,48.5022,6.528292439,7.561154515,0.168125,-11.55134195,3.379294877,49.12374579 +185.59,50.43116761,-2.573243256,48.5008,6.54567341,7.562264624,0.1034375,-11.59276118,3.395171136,49.13127091 +185.6,50.4311682,-2.573242191,48.5001,6.556101982,7.56248657,0.0384375,-11.6328036,3.408086808,49.13879596 +185.61,50.43116879,-2.573241127,48.5001,6.545673391,7.562486476,-0.025,-11.67146083,3.418030548,49.14632107 +185.62,50.43116938,-2.573240063,48.5006,6.528292418,7.563818628,-0.0884375,-11.7087248,3.424993704,49.15384613 +185.63,50.43116996,-2.573238998,48.5018,6.528292422,7.565816903,-0.15375,-11.74458778,3.428970261,49.16137124 +185.64,50.43117055,-2.573237933,48.5037,6.545673406,7.566927015,-0.2196875,-11.77904219,3.429956665,49.1688963 +185.65,50.43117114,-2.573236868,48.5062,6.556102005,7.567148965,-0.2846875,-11.81208089,3.427952115,49.17642141 +185.66,50.43117173,-2.573235803,48.5094,6.545673435,7.567370916,-0.3484375,-11.84369699,3.422958329,49.18394647 +185.67,50.43117232,-2.573234738,48.5132,6.528292467,7.568481031,-0.4115625,-11.8738839,3.414979663,49.19147158 +185.68,50.4311729,-2.573233673,48.5176,6.524816271,7.57070135,-0.475,-11.90263526,3.404023105,49.19899664 +185.69,50.43117349,-2.573232607,48.5227,6.528292467,7.572699629,-0.5384375,-11.92994507,3.390098168,49.20652175 +185.7,50.43117408,-2.573231541,48.5284,6.524816282,7.572921583,-0.6015625,-11.95580769,3.373217055,49.21404681 +185.71,50.43117466,-2.573230475,48.5347,6.528292481,7.572033334,-0.665,-11.98021764,3.353394434,49.22157192 +185.72,50.43117525,-2.57322941,48.5417,6.542197255,7.572033248,-0.728125,-12.00316993,3.330647552,49.22909698 +185.73,50.43117584,-2.573228344,48.5493,6.542197255,7.573143367,-0.79,-12.02465963,3.304996346,49.23662209 +185.74,50.43117643,-2.573227278,48.5575,6.528292484,7.574253487,-0.8515625,-12.04468233,3.276463105,49.24414714 +185.75,50.43117701,-2.573226212,48.5663,6.524816302,7.575363607,-0.9134375,-12.06323384,3.245072753,49.25167226 +185.76,50.4311776,-2.573225146,48.5758,6.528292515,7.576695769,-0.975,-12.08031033,3.210852676,49.25919731 +185.77,50.43117819,-2.573224079,48.5858,6.524816343,7.577805891,-1.0365625,-12.09590814,3.17383267,49.26672243 +185.78,50.43117877,-2.573223013,48.5965,6.524816357,7.578916014,-1.098125,-12.1100241,3.134045048,49.27424748 +185.79,50.43117936,-2.573221946,48.6078,6.528292561,7.580248177,-1.158125,-12.12265518,3.091524475,49.28177259 +185.8,50.43117995,-2.573220879,48.6197,6.521340189,7.581136261,-1.2165625,-12.13379881,3.046308021,49.28929765 +185.81,50.43118053,-2.573219812,48.6321,6.510911626,7.581358223,-1.275,-12.14345263,2.998435163,49.29682276 +185.82,50.43118112,-2.573218745,48.6452,6.51091164,7.581358145,-1.3334375,-12.15161459,2.947947612,49.30434782 +185.83,50.4311817,-2.573217678,48.6588,6.521340229,7.581580109,-1.3915625,-12.15828307,2.894889428,49.31187293 +185.84,50.43118229,-2.573216611,48.673,6.52829262,7.582690235,-1.45,-12.16345665,2.83930685,49.31939799 +185.85,50.43118288,-2.573215544,48.6878,6.521340238,7.584688525,-1.5078125,-12.16713418,2.781248349,49.3269231 +185.86,50.43118346,-2.573214476,48.7032,6.510911671,7.586020694,-1.563125,-12.16931503,2.720764575,49.33444816 +185.87,50.43118405,-2.573213408,48.7191,6.507435502,7.586020619,-1.616875,-12.16999857,2.65790824,49.34197327 +185.88,50.43118463,-2.573212341,48.7355,6.50743553,7.586242586,-1.6715625,-12.1691848,2.592734176,49.34949833 +185.89,50.43118522,-2.573211273,48.7525,6.507435548,7.587352717,-1.7265625,-12.16687383,2.525299221,49.35702344 +185.9,50.4311858,-2.573210205,48.7701,6.507435558,7.588462847,-1.7796875,-12.16306612,2.45566216,49.3645485 +185.91,50.43118639,-2.573209137,48.7881,6.507435579,7.589572979,-1.8315625,-12.15776254,2.383883669,49.37207355 +185.92,50.43118697,-2.573208069,48.8067,6.507435617,7.590905152,-1.8834375,-12.15096411,2.310026487,49.37959866 +185.93,50.43118756,-2.573207,48.8258,6.507435648,7.591793244,-1.9346875,-12.14267232,2.234154842,49.38712372 +185.94,50.43118814,-2.573205932,48.8454,6.507435658,7.592015214,-1.985,-12.1328889,2.156335027,49.39464883 +185.95,50.43118873,-2.573204863,48.8655,6.507435659,7.592237185,-2.0346875,-12.12161584,2.076634879,49.40217389 +185.96,50.43118931,-2.573203795,48.8861,6.507435669,7.593125279,-2.083125,-12.10885549,1.99512384,49.409699 +185.97,50.4311899,-2.573202726,48.9072,6.507435692,7.594457454,-2.13,-12.09461062,1.911873015,49.41722406 +185.98,50.43119048,-2.573201657,48.9287,6.507435723,7.59556759,-2.1765625,-12.07888407,1.826955055,49.42474917 +185.99,50.43119107,-2.573200588,48.9507,6.507435757,7.596677725,-2.223125,-12.06167918,1.740443929,49.43227423 +186,50.43119165,-2.573199519,48.9732,6.507435781,7.597787862,-2.2678125,-12.04299961,1.652415094,49.43979934 +186.01,50.43119224,-2.573198449,48.9961,6.507435796,7.598009837,-2.31,-12.02284914,1.562945328,49.4473244 +186.02,50.43119282,-2.57319738,49.0194,6.507435823,7.59800977,-2.351875,-12.00123207,1.472112724,49.45484951 +186.03,50.43119341,-2.573196311,49.0431,6.507435865,7.599341948,-2.3946875,-11.97815288,1.379996352,49.46237456 +186.04,50.43119399,-2.573195241,49.0673,6.503959707,7.601340249,-2.43625,-11.95361636,1.286676596,49.46989968 +186.05,50.43119458,-2.573194171,49.0919,6.493531137,7.602450389,-2.4746875,-11.92762768,1.192234874,49.47742473 +186.06,50.43119516,-2.573193101,49.1168,6.486578754,7.602672366,-2.511875,-11.90019229,1.096753462,49.48494985 +186.07,50.43119574,-2.573192031,49.1421,6.490054966,7.602894343,-2.55,-11.87131584,1.00031567,49.4924749 +186.08,50.43119633,-2.573190961,49.1678,6.490055,7.603782443,-2.5878125,-11.84100443,0.903005607,49.50000002 +186.09,50.43119691,-2.573189891,49.1939,6.486578843,7.605114624,-2.623125,-11.80926434,0.804908127,49.50752507 +186.1,50.43119749,-2.57318882,49.2203,6.49353126,7.606224766,-2.65625,-11.77610223,0.706108775,49.51505018 +186.11,50.43119808,-2.57318775,49.247,6.503959862,7.607334907,-2.6884375,-11.74152503,0.606693607,49.52257524 +186.12,50.43119866,-2.573186679,49.2741,6.503959885,7.608445049,-2.72,-11.70553996,0.506749428,49.53010035 +186.13,50.43119925,-2.573185608,49.3014,6.493531345,7.608444988,-2.75125,-11.66815452,0.406363383,49.53762541 +186.14,50.43119983,-2.573184537,49.3291,6.486579006,7.607778806,-2.7815625,-11.62937651,0.305622964,49.54515052 +186.15,50.43120041,-2.573183467,49.3571,6.49005523,7.608666908,-2.8096875,-11.589214,0.204616063,49.55267558 +186.16,50.431201,-2.573182396,49.3853,6.486579045,7.611109295,-2.8365625,-11.54767548,0.103430685,49.56020069 +186.17,50.43120158,-2.573181324,49.4138,6.472674286,7.612885561,-2.863125,-11.50476953,0.002155123,49.56772575 +186.18,50.43120216,-2.573180253,49.4426,6.472674322,7.613329583,-2.8878125,-11.46050516,-0.099122272,49.57525086 +186.19,50.43120274,-2.573179181,49.4716,6.486579132,7.613329524,-2.9096875,-11.41489159,-0.200313264,49.58277592 +186.2,50.43120333,-2.57317811,49.5008,6.490055346,7.613329465,-2.9303125,-11.36793833,-0.30132962,49.59030103 +186.21,50.43120391,-2.573177038,49.5302,6.486579178,7.613551447,-2.9515625,-11.31965523,-0.402083159,49.59782608 +186.22,50.43120449,-2.573175967,49.5598,6.490055419,7.614661592,-2.9728125,-11.27005233,-0.502486106,49.6053512 +186.23,50.43120508,-2.573174895,49.5897,6.486579277,7.616881941,-2.99125,-11.21914004,-0.602450855,49.61287625 +186.24,50.43120566,-2.573173823,49.6197,6.469198333,7.61910229,-3.0065625,-11.16692898,-0.701890259,49.62040137 +186.25,50.43120624,-2.57317275,49.6498,6.458769757,7.620212435,-3.021875,-11.11342996,-0.800717571,49.62792642 +186.26,50.43120682,-2.573171678,49.6801,6.469198358,7.620434419,-3.038125,-11.05865428,-0.898846735,49.63545148 +186.27,50.4312074,-2.573170605,49.7106,6.48657937,7.620434361,-3.0528125,-11.00261333,-0.996192035,49.64297659 +186.28,50.43120799,-2.573169533,49.7412,6.486579412,7.620434304,-3.064375,-10.94531881,-1.092668617,49.65050165 +186.29,50.43120857,-2.57316846,49.7719,6.469198468,7.620656288,-3.0734375,-10.8867827,-1.188192427,49.65802676 +186.3,50.43120915,-2.573167388,49.8027,6.458769906,7.621544394,-3.0815625,-10.82701718,-1.2826801,49.66555182 +186.31,50.43120973,-2.573166315,49.8335,6.469198526,7.623098622,-3.0896875,-10.76603476,-1.376049245,49.67307693 +186.32,50.43121031,-2.573165242,49.8645,6.486579552,7.62487489,-3.0965625,-10.70384816,-1.468218445,49.68060198 +186.33,50.4312109,-2.573164169,49.8955,6.486579595,7.626429118,-3.10125,-10.64047043,-1.55910737,49.6881271 +186.34,50.43121148,-2.573163095,49.9265,6.46919864,7.627317224,-3.105,-10.57591476,-1.648636667,49.69565215 +186.35,50.43121206,-2.573162022,49.9576,6.455293873,7.627539208,-3.108125,-10.51019461,-1.736728412,49.70317727 +186.36,50.43121264,-2.573160948,49.9887,6.451817708,7.627761192,-3.1096875,-10.44332373,-1.823305658,49.71070232 +186.37,50.43121322,-2.573159875,50.0198,6.451817749,7.628649299,-3.1096875,-10.37531605,-1.908292946,49.71822744 +186.38,50.4312138,-2.573158801,50.0509,6.455293976,7.629981487,-3.108125,-10.30618583,-1.991616193,49.72575249 +186.39,50.43121438,-2.573157727,50.082,6.469198781,7.630869593,-3.1046875,-10.2359475,-2.07320269,49.7332776 +186.4,50.43121496,-2.573156653,50.113,6.486579792,7.631313617,-3.1,-10.16461569,-2.152981391,49.74080266 +186.41,50.43121555,-2.573155579,50.144,6.486579842,7.632201723,-3.0946875,-10.09220534,-2.230882623,49.74832777 +186.42,50.43121613,-2.573154505,50.1749,6.469198908,7.633311869,-3.088125,-10.01873153,-2.306838435,49.75585283 +186.43,50.43121671,-2.57315343,50.2058,6.45529415,7.633533854,-3.0796875,-9.944209598,-2.380782706,49.76337794 +186.44,50.43121729,-2.573152356,50.2365,6.451817975,7.633533797,-3.0696875,-9.868655201,-2.452650923,49.770903 +186.45,50.43121787,-2.573151282,50.2672,6.451818007,7.634865984,-3.0584375,-9.792083975,-2.522380345,49.77842811 +186.46,50.43121845,-2.573150207,50.2977,6.451818036,7.636864292,-3.04625,-9.714512022,-2.589910239,49.78595317 +186.47,50.43121903,-2.573149132,50.3281,6.451818059,7.637974438,-3.0334375,-9.635955497,-2.655181706,49.79347828 +186.48,50.43121961,-2.573148057,50.3584,6.45181809,7.638418463,-3.0196875,-9.556430789,-2.718137792,49.80100334 +186.49,50.43122019,-2.573146982,50.3885,6.451818132,7.639084528,-3.004375,-9.475954569,-2.77872361,49.80852845 +186.5,50.43122077,-2.573145907,50.4185,6.451818172,7.639528551,-2.9865625,-9.394543569,-2.836886389,49.8160535 +186.51,50.43122135,-2.573144831,50.4483,6.451818205,7.639528492,-2.9665625,-9.312214862,-2.892575309,49.82357862 +186.52,50.43122193,-2.573143757,50.4778,6.451818235,7.640416597,-2.9465625,-9.228985581,-2.945741896,49.83110367 +186.53,50.43122251,-2.573142681,50.5072,6.451818264,7.641970823,-2.9265625,-9.144873084,-2.996339742,49.83862879 +186.54,50.43122309,-2.573141605,50.5364,6.451818285,7.642636887,-2.904375,-9.059895078,-3.044324728,49.84615384 +186.55,50.43122367,-2.57314053,50.5653,6.451818304,7.643080909,-2.88,-8.974069152,-3.089654971,49.85367896 +186.56,50.43122425,-2.573139454,50.594,6.451818333,7.644413093,-2.855,-8.887413296,-3.132291053,49.86120401 +186.57,50.43122483,-2.573138378,50.6224,6.451818372,7.646189358,-2.8296875,-8.799945616,-3.17219573,49.86872912 +186.58,50.43122541,-2.573137302,50.6506,6.448342207,7.647743583,-2.8028125,-8.71168439,-3.209334166,49.87625418 +186.59,50.43122599,-2.573136225,50.6785,6.434437454,7.648631685,-2.773125,-8.622647952,-3.243674048,49.88377924 +186.6,50.43122657,-2.573135149,50.7061,6.417056515,7.648853665,-2.741875,-8.532855038,-3.275185409,49.89130435 +186.61,50.43122714,-2.573134072,50.7333,6.417056552,7.649075646,-2.7115625,-8.442324325,-3.30384069,49.8988294 +186.62,50.43122772,-2.573132996,50.7603,6.434437547,7.649741707,-2.68125,-8.351074723,-3.329615024,49.90635452 +186.63,50.4312283,-2.573131919,50.787,6.44834234,7.650407768,-2.6478125,-8.259125253,-3.352485895,49.91387957 +186.64,50.43122888,-2.573130842,50.8133,6.451818561,7.651073827,-2.6115625,-8.166495224,-3.372433364,49.92140469 +186.65,50.43122946,-2.573129766,50.8392,6.451818596,7.652628049,-2.5753125,-8.073203829,-3.389439954,49.92892974 +186.66,50.43123004,-2.573128688,50.8648,6.448342429,7.654626351,-2.5396875,-7.979270722,-3.403490942,49.93645486 +186.67,50.43123062,-2.573127611,50.89,6.434437672,7.65551445,-2.503125,-7.884715382,-3.414574066,49.94397991 +186.68,50.4312312,-2.573126533,50.9149,6.41705673,7.655070305,-2.4646875,-7.789557635,-3.422679585,49.95150502 +186.69,50.43123177,-2.573125456,50.9393,6.417056764,7.654848201,-2.4246875,-7.693817304,-3.42780051,49.95903008 +186.7,50.43123235,-2.573124379,50.9634,6.434437757,7.65618038,-2.3834375,-7.597514386,-3.429932314,49.96655519 +186.71,50.43123293,-2.573123301,50.987,6.444866351,7.657956639,-2.34125,-7.500669049,-3.429073164,49.97408025 +186.72,50.43123351,-2.573122223,51.0102,6.434437786,7.658400655,-2.2984375,-7.40330146,-3.425223804,49.98160536 +186.73,50.43123409,-2.573121145,51.033,6.417056839,7.658400588,-2.2546875,-7.305431961,-3.418387616,49.98913042 +186.74,50.43123466,-2.573120068,51.0553,6.417056867,7.659510725,-2.2096875,-7.207081005,-3.408570557,49.99665553 +186.75,50.43123524,-2.573118989,51.0772,6.434437875,7.660842902,-2.1634375,-7.108269105,-3.395781165,50.00418059 +186.76,50.43123582,-2.573117911,51.0986,6.444866498,7.661508956,-2.1165625,-7.009017001,-3.380030555,50.0117057 +186.77,50.4312364,-2.573116833,51.1195,6.43443793,7.662175009,-2.0696875,-6.909345263,-3.361332593,50.01923076 +186.78,50.43123698,-2.573115754,51.14,6.417056952,7.663063103,-2.0215625,-6.809274804,-3.339703436,50.02675587 +186.79,50.43123755,-2.573114676,51.16,6.413580768,7.664173236,-1.97125,-6.708826536,-3.315161992,50.03428092 +186.8,50.43123813,-2.573113597,51.1794,6.417056991,7.665505409,-1.9203125,-6.608021373,-3.287729747,50.04180604 +186.81,50.43123871,-2.573112518,51.1984,6.413580817,7.666393501,-1.87,-6.506880399,-3.257430478,50.04933109 +186.82,50.43123928,-2.573111439,51.2168,6.417057032,7.666837511,-1.819375,-6.4054247,-3.224290771,50.05685621 +186.83,50.43123986,-2.57311036,51.2348,6.430961846,7.667725601,-1.7665625,-6.303675531,-3.188339388,50.06438126 +186.84,50.43124044,-2.573109281,51.2522,6.430961873,7.669057771,-1.7115625,-6.201654093,-3.149607671,50.07190638 +186.85,50.43124102,-2.573108201,51.269,6.417057098,7.66994586,-1.656875,-6.0993817,-3.108129537,50.07943143 +186.86,50.43124159,-2.573107122,51.2853,6.413580908,7.670167828,-1.603125,-5.996879722,-3.063941027,50.08695654 +186.87,50.43124217,-2.573106042,51.3011,6.41705712,7.670389795,-1.548125,-5.894169589,-3.017080699,50.0944816 +186.88,50.43124275,-2.573104963,51.3163,6.413580938,7.671277882,-1.49125,-5.791272672,-2.967589464,50.10200671 +186.89,50.43124332,-2.573103883,51.3309,6.413580944,7.672610049,-1.4334375,-5.68821057,-2.915510408,50.10953177 +186.9,50.4312439,-2.573102803,51.345,6.417057157,7.673498134,-1.375,-5.585004657,-2.860889024,50.11705688 +186.91,50.43124448,-2.573101723,51.3584,6.410104797,7.673942138,-1.316875,-5.481676646,-2.803772867,50.12458194 +186.92,50.43124505,-2.573100643,51.3713,6.399676236,7.675052264,-1.26,-5.378248024,-2.744211841,50.13210705 +186.93,50.43124563,-2.573099563,51.3836,6.399676247,7.67705055,-1.2028125,-5.27474039,-2.682257743,50.13963211 +186.94,50.4312462,-2.573098482,51.3954,6.410104839,7.678382714,-1.143125,-5.171175404,-2.617964716,50.14715716 +186.95,50.43124678,-2.573097401,51.4065,6.417057234,7.678382634,-1.0815625,-5.067574665,-2.551388797,50.15468228 +186.96,50.43124736,-2.573096321,51.417,6.410104848,7.678604594,-1.02,-4.963959774,-2.482588025,50.16220733 +186.97,50.43124793,-2.57309524,51.4269,6.399676275,7.679714715,-0.9584375,-4.860352447,-2.411622389,50.16973244 +186.98,50.43124851,-2.573094159,51.4362,6.396200098,7.680602795,-0.8965625,-4.756774282,-2.338553769,50.1772575 +186.99,50.43124908,-2.573093078,51.4448,6.396200116,7.681046793,-0.835,-4.653246939,-2.263445877,50.18478261 +187,50.43124966,-2.573091997,51.4529,6.399676323,7.681934872,-0.7734375,-4.549791961,-2.186364261,50.19230767 +187.01,50.43125023,-2.573090916,51.4603,6.410104906,7.683267031,-0.71125,-4.446431062,-2.107376127,50.19983278 +187.02,50.43125081,-2.573089834,51.4671,6.417057288,7.684155107,-0.6484375,-4.343185729,-2.026550289,50.20735784 +187.03,50.43125139,-2.573088753,51.4733,6.4101049,7.684377062,-0.5846875,-4.240077562,-1.943957277,50.21488295 +187.04,50.43125196,-2.573087671,51.4788,6.399676327,7.684599016,-0.5203125,-4.137128104,-1.859669112,50.22240801 +187.05,50.43125254,-2.57308659,51.4837,6.396200141,7.685487091,-0.4565625,-4.034358842,-1.773759304,50.22993312 +187.06,50.43125311,-2.573085508,51.4879,6.396200153,7.686819246,-0.3934375,-3.931791203,-1.68630274,50.23745818 +187.07,50.43125369,-2.573084426,51.4916,6.39620017,7.687707319,-0.3296875,-3.829446675,-1.59737568,50.24498329 +187.08,50.43125426,-2.573083344,51.4945,6.392723978,7.68792927,-0.265,-3.727346627,-1.507055701,50.25250834 +187.09,50.43125484,-2.573082262,51.4969,6.382295379,7.68815122,-0.2003125,-3.625512317,-1.41542153,50.26003346 +187.1,50.43125541,-2.57308118,51.4985,6.375342982,7.689261331,-0.1365625,-3.523965116,-1.322553093,50.26755851 +187.11,50.43125598,-2.573080098,51.4996,6.382295372,7.691481645,-0.0734375,-3.422726109,-1.228531349,50.27508363 +187.12,50.43125656,-2.573079015,51.5,6.392723955,7.693479916,-0.009375,-3.321816496,-1.133438346,50.28260868 +187.13,50.43125713,-2.573077932,51.4998,6.39620016,7.693701863,0.05625,-3.221257361,-1.03735699,50.2901338 +187.14,50.43125771,-2.573076849,51.4989,6.39620018,7.693035648,0.121875,-3.121069732,-0.940370992,50.29765885 +187.15,50.43125828,-2.573075767,51.4973,6.392723985,7.693923715,0.18625,-3.021274407,-0.842564976,50.30518396 +187.16,50.43125886,-2.573074684,51.4952,6.382295382,7.696144024,0.25,-2.921892413,-0.744024257,50.31270902 +187.17,50.43125943,-2.5730736,51.4923,6.375342981,7.697254129,0.31375,-2.822944321,-0.64483472,50.32023413 +187.18,50.43126,-2.573072517,51.4889,6.38229537,7.697254031,0.3778125,-2.724450928,-0.545082883,50.32775919 +187.19,50.43126058,-2.573071434,51.4848,6.392723962,7.697698014,0.4421875,-2.626432746,-0.444855777,50.3352843 +187.2,50.43126115,-2.57307035,51.48,6.392723971,7.698586077,0.50625,-2.52891023,-0.344240664,50.34280936 +187.21,50.43126173,-2.573069267,51.4747,6.382295378,7.69969618,0.57,-2.431903777,-0.243325435,50.35033447 +187.22,50.4312623,-2.573068183,51.4686,6.375342967,7.701028323,0.6334375,-2.33543367,-0.142197983,50.35785953 +187.23,50.43126287,-2.573067099,51.462,6.37881915,7.701916384,0.69625,-2.239520019,-0.040946543,50.36538464 +187.24,50.43126345,-2.573066015,51.4547,6.378819141,7.702138323,0.7584375,-2.144182822,0.060340592,50.3729097 +187.25,50.43126402,-2.573064931,51.4468,6.375342938,7.702360261,0.82,-2.049442073,0.16157513,50.38043481 +187.26,50.43126459,-2.573063847,51.4383,6.378819137,7.703248319,0.8815625,-1.955317483,0.262668777,50.38795986 +187.27,50.43126517,-2.573062763,51.4292,6.375342944,7.704580456,0.9434375,-1.861828704,0.363533356,50.39548498 +187.28,50.43126574,-2.573061678,51.4194,6.361438148,7.705690553,1.005,-1.768995332,0.464080917,50.40301003 +187.29,50.43126631,-2.573060594,51.4091,6.36143813,7.70657861,1.06625,-1.676836732,0.564223798,50.41053509 +187.3,50.43126688,-2.573059509,51.3981,6.375342895,7.707244626,1.126875,-1.585372099,0.663874681,50.4180602 +187.31,50.43126746,-2.573058424,51.3865,6.375342879,7.70791064,1.18625,-1.494620569,0.762946647,50.42558526 +187.32,50.43126803,-2.57305734,51.3744,6.361438088,7.709242775,1.245,-1.404601107,0.861353294,50.43311037 +187.33,50.4312686,-2.573056254,51.3616,6.361438085,7.710352869,1.3034375,-1.315332449,0.959008851,50.44063543 +187.34,50.43126917,-2.573055169,51.3483,6.375342865,7.710352759,1.3615625,-1.226833331,1.055828176,50.44816054 +187.35,50.43126975,-2.573054084,51.3344,6.375342854,7.710574689,1.42,-1.139122202,1.151726757,50.4556856 +187.36,50.43127032,-2.573052999,51.3199,6.361438045,7.711684781,1.478125,-1.052217338,1.246621001,50.46321071 +187.37,50.43127089,-2.573051913,51.3048,6.36143802,7.712572832,1.5346875,-0.966136961,1.340428173,50.47073576 +187.38,50.43127146,-2.573050828,51.2892,6.375342789,7.713016801,1.59,-0.880898947,1.43306651,50.47826088 +187.39,50.43127204,-2.573049742,51.273,6.375342775,7.71412689,1.645,-0.796521171,1.524455169,50.48578593 +187.4,50.43127261,-2.573048657,51.2563,6.357961786,7.71612514,1.6996875,-0.713021282,1.614514509,50.49331105 +187.41,50.43127318,-2.57304757,51.239,6.344056999,7.717457269,1.753125,-0.630416638,1.703165919,50.5008361 +187.42,50.43127375,-2.573046484,51.2212,6.344056982,7.717457155,1.805,-0.548724545,1.790332166,50.50836122 +187.43,50.43127432,-2.573045398,51.2029,6.357961734,7.71767908,1.8565625,-0.467962019,1.875937217,50.51588627 +187.44,50.43127489,-2.573044312,51.1841,6.375342689,7.718789166,1.9084375,-0.388145961,1.959906417,50.52341138 +187.45,50.43127547,-2.573043225,51.1647,6.375342671,7.719899252,1.9596875,-0.309292988,2.042166597,50.53093644 +187.46,50.43127604,-2.573042139,51.1449,6.357961679,7.721009337,2.0096875,-0.231419659,2.122645911,50.53846155 +187.47,50.43127661,-2.573041052,51.1245,6.344056888,7.722119421,2.058125,-0.154542187,2.201274284,50.54598661 +187.48,50.43127718,-2.573039965,51.1037,6.340580672,7.722119303,2.105,-0.078676616,2.277983077,50.55351172 +187.49,50.43127775,-2.573038878,51.0824,6.340580639,7.721453063,2.1515625,-0.003838817,2.352705483,50.56103678 +187.5,50.43127832,-2.573037792,51.0607,6.340580613,7.722341106,2.198125,0.069955626,2.425376241,50.56856189 +187.51,50.43127889,-2.573036705,51.0384,6.344056794,7.72478343,2.2434375,0.142691243,2.495932097,50.57608695 +187.52,50.43127946,-2.573035617,51.0158,6.357961565,7.726559632,2.2878125,0.214352908,2.564311401,50.58361206 +187.53,50.43128003,-2.57303453,50.9927,6.375342524,7.727003592,2.331875,0.284925609,2.630454623,50.59113712 +187.54,50.43128061,-2.573033442,50.9691,6.37534249,7.72722551,2.374375,0.354394622,2.694304066,50.59866223 +187.55,50.43128118,-2.573032355,50.9452,6.357961476,7.728113549,2.4146875,0.42274545,2.755803981,50.60618728 +187.56,50.43128175,-2.573031267,50.9208,6.344056672,7.729445669,2.4534375,0.48996377,2.814900853,50.6137124 +187.57,50.43128232,-2.573030179,50.8961,6.340580461,7.730333708,2.4915625,0.556035601,2.871543059,50.62123745 +187.58,50.43128289,-2.573029091,50.871,6.340580445,7.730555625,2.53,0.620947136,2.925681269,50.62876257 +187.59,50.43128346,-2.573028003,50.8455,6.340580425,7.730777542,2.568125,0.684684794,2.977268211,50.63628762 +187.6,50.43128403,-2.573026915,50.8196,6.340580395,7.731665579,2.6046875,0.747235284,3.02625891,50.64381274 +187.61,50.4312846,-2.573025827,50.7934,6.340580361,7.732997696,2.6396875,0.808585542,3.07261068,50.65133779 +187.62,50.43128517,-2.573024738,50.7668,6.340580326,7.733885731,2.673125,0.868722734,3.116283128,50.6588629 +187.63,50.43128574,-2.57302365,50.7399,6.340580296,7.734107647,2.7046875,0.927634312,3.157238093,50.66638796 +187.64,50.43128631,-2.573022561,50.7127,6.340580274,7.734329562,2.735,0.985308015,3.195439883,50.67391302 +187.65,50.43128688,-2.573021473,50.6852,6.33710406,7.735217597,2.765,1.041731752,3.230855206,50.68143813 +187.66,50.43128745,-2.573020384,50.6574,6.323199259,7.736771752,2.7946875,1.096893722,3.263453239,50.68896318 +187.67,50.43128802,-2.573019295,50.6293,6.305818258,7.738547948,2.823125,1.150782466,3.293205447,50.6964883 +187.68,50.43128858,-2.573018206,50.6009,6.305818226,7.740102103,2.8496875,1.203386695,3.320085934,50.70401335 +187.69,50.43128915,-2.573017116,50.5723,6.323199168,7.740990137,2.8746875,1.254695409,3.344071208,50.71153847 +187.7,50.43128972,-2.573016027,50.5434,6.337103916,7.74121205,2.898125,1.304697952,3.36514047,50.71906352 +187.71,50.43129029,-2.573014937,50.5143,6.340580087,7.741211922,2.92,1.35338378,3.383275272,50.72658864 +187.72,50.43129086,-2.573013848,50.485,6.340580072,7.741433834,2.9415625,1.40074281,3.3984598,50.73411369 +187.73,50.43129143,-2.573012758,50.4555,6.340580043,7.742321866,2.963125,1.446765129,3.410680818,50.7416388 +187.74,50.431292,-2.573011669,50.4257,6.340580001,7.743653979,2.9828125,1.491441169,3.419927669,50.74916386 +187.75,50.43129257,-2.573010578,50.3958,6.337103774,7.74476405,2.9996875,1.534761477,3.426192275,50.75668897 +187.76,50.43129314,-2.573009489,50.3657,6.323198976,7.745652081,3.015,1.576717113,3.429469192,50.76421403 +187.77,50.43129371,-2.573008398,50.3355,6.305817981,7.746318073,3.0296875,1.617299313,3.429755614,50.77173914 +187.78,50.43129427,-2.573007308,50.3051,6.305817944,7.746984064,3.0434375,1.656499538,3.427051196,50.7792642 +187.79,50.43129484,-2.573006218,50.2746,6.323198877,7.748316177,3.05625,1.694309653,3.421358344,50.78678931 +187.8,50.43129541,-2.573005127,50.244,6.337103624,7.749426248,3.068125,1.730721752,3.412681987,50.79431437 +187.81,50.43129598,-2.573004036,50.2132,6.337103601,7.749426118,3.078125,1.765728212,3.401029745,50.80183948 +187.82,50.43129655,-2.573002946,50.1824,6.323198798,7.749648028,3.08625,1.799321759,3.386411758,50.80936454 +187.83,50.43129712,-2.573001855,50.1515,6.305817796,7.750758099,3.0934375,1.831495345,3.368840746,50.81688965 +187.84,50.43129768,-2.573000764,50.1205,6.305817761,7.75186817,3.0996875,1.862242265,3.348332123,50.8244147 +187.85,50.43129825,-2.572999673,50.0895,6.319722506,7.752978241,3.1046875,1.891556047,3.32490365,50.83193982 +187.86,50.43129882,-2.572998582,50.0584,6.319722474,7.754310352,3.108125,1.919430673,3.298575838,50.83946487 +187.87,50.43129939,-2.57299749,50.0273,6.305817662,7.755198382,3.1096875,1.945860242,3.269371549,50.84698999 +187.88,50.43129995,-2.572996399,49.9962,6.305817634,7.755420291,3.1096875,1.970839253,3.237316394,50.85451504 +187.89,50.43130052,-2.572995307,49.9651,6.319722392,7.755642201,3.108125,1.994362494,3.202438218,50.86204016 +187.9,50.43130109,-2.572994216,49.934,6.319722364,7.756530232,3.105,2.016425093,3.164767504,50.86956521 +187.91,50.43130166,-2.572993124,49.903,6.305817542,7.757862343,3.1015625,2.037022353,3.124337023,50.87709032 +187.92,50.43130222,-2.572992032,49.872,6.302341305,7.758972413,3.098125,2.056150034,3.081182129,50.88461538 +187.93,50.43130279,-2.57299094,49.841,6.305817475,7.760082484,3.0928125,2.073804124,3.035340349,50.89214049 +187.94,50.43130336,-2.572989848,49.8101,6.302341265,7.761192555,3.0846875,2.089980957,2.986851732,50.89966555 +187.95,50.43130392,-2.572988755,49.7793,6.302341248,7.761414465,3.075,2.104677152,2.935758508,50.90719066 +187.96,50.43130449,-2.572987663,49.7486,6.305817414,7.761414335,3.0646875,2.117889559,2.88210525,50.91471572 +187.97,50.43130506,-2.572986571,49.718,6.302341176,7.762746446,3.053125,2.129615541,2.82593877,50.92224083 +187.98,50.43130562,-2.572985478,49.6875,6.302341133,7.764744678,3.04,2.139852578,2.767308056,50.92976589 +187.99,50.43130619,-2.572984385,49.6572,6.305817301,7.765854749,3.02625,2.14859855,2.706264216,50.93729094 +188,50.43130676,-2.572983292,49.627,6.30234109,7.76607666,3.0115625,2.155851623,2.64286042,50.94481606 +188.01,50.43130732,-2.572982199,49.5969,6.302341061,7.766076531,2.9946875,2.161610307,2.577152016,50.95234111 +188.02,50.43130789,-2.572981106,49.5671,6.305817214,7.766298442,2.9765625,2.165873399,2.509196357,50.95986622 +188.03,50.43130846,-2.572980013,49.5374,6.298864793,7.767186473,2.958125,2.168639926,2.439052571,50.96739128 +188.04,50.43130902,-2.57297892,49.5079,6.288436192,7.768518586,2.9378125,2.169909429,2.366781967,50.97491639 +188.05,50.43130959,-2.572977826,49.4786,6.288436175,7.769406619,2.915,2.169681563,2.292447454,50.98244145 +188.06,50.43131015,-2.572976733,49.4496,6.298864725,7.769628531,2.8915625,2.167956387,2.216113891,50.98996656 +188.07,50.43131072,-2.572975639,49.4208,6.305817072,7.770072483,2.868125,2.164734302,2.137847799,50.99749162 +188.08,50.43131129,-2.572974546,49.3922,6.29886465,7.771626637,2.843125,2.160015937,2.057717531,51.00501673 +188.09,50.43131185,-2.572973452,49.3639,6.288436045,7.773402831,2.81625,2.153802325,1.975792875,51.01254179 +188.1,50.43131242,-2.572972357,49.3359,6.284959834,7.774068825,2.7884375,2.146094724,1.892145334,51.0200669 +188.11,50.43131298,-2.572971264,49.3081,6.284959818,7.774512778,2.7596875,2.136894741,1.806847789,51.02759196 +188.12,50.43131355,-2.572970169,49.2807,6.284959791,7.775622853,2.7296875,2.126204265,1.719974668,51.03511707 +188.13,50.43131411,-2.572969075,49.2535,6.284959754,7.776510888,2.698125,2.114025646,1.631601657,51.04264213 +188.14,50.43131468,-2.57296798,49.2267,6.28495972,7.776954843,2.6646875,2.10036129,1.541805935,51.05016724 +188.15,50.43131524,-2.572966886,49.2002,6.284959694,7.777842879,2.63,2.085214177,1.450665654,51.05769229 +188.16,50.43131581,-2.572965791,49.1741,6.284959676,7.779174996,2.5946875,2.068587343,1.358260453,51.06521741 +188.17,50.43131637,-2.572964696,49.1483,6.284959655,7.780063032,2.5584375,2.050484398,1.264670776,51.07274246 +188.18,50.43131694,-2.572963601,49.1229,6.284959626,7.780284948,2.52125,2.030909008,1.169978271,51.08026758 +188.19,50.4313175,-2.572962506,49.0979,6.284959593,7.780506865,2.4834375,2.0098653,1.074265556,51.08779263 +188.2,50.43131807,-2.572961411,49.0732,6.284959563,7.781394903,2.4446875,1.987357684,0.977616056,51.09531774 +188.21,50.43131863,-2.572960316,49.049,6.284959544,7.782727022,2.4046875,1.963390859,0.880114109,51.1028428 +188.22,50.4313192,-2.57295922,49.0251,6.284959537,7.783615061,2.3634375,1.937969753,0.781844628,51.11036791 +188.23,50.43131976,-2.572958125,49.0017,6.281483326,7.783836979,2.32125,1.911099809,0.682893385,51.11789297 +188.24,50.43132033,-2.572957029,48.9787,6.271054711,7.784280939,2.278125,1.882786584,0.583346666,51.12541808 +188.25,50.43132089,-2.572955934,48.9561,6.264102293,7.78605714,2.233125,1.853035922,0.483291218,51.13294314 +188.26,50.43132145,-2.572954838,48.934,6.267578473,7.788499461,2.1865625,1.821854127,0.38281436,51.14046825 +188.27,50.43132202,-2.572953741,48.9124,6.267578464,7.789387502,2.14,1.789247614,0.282003696,51.14799331 +188.28,50.43132258,-2.572952645,48.8912,6.264102247,7.788499224,2.0934375,1.755223318,0.180947119,51.15551842 +188.29,50.43132314,-2.572951549,48.8705,6.271054599,7.787832986,2.04625,1.719788284,0.079732749,51.16304348 +188.3,50.43132371,-2.572950453,48.8503,6.281483152,7.788721029,1.998125,1.682949848,-0.021551177,51.17056859 +188.31,50.43132427,-2.572949357,48.8305,6.281483145,7.790719273,1.948125,1.644715859,-0.122816311,51.17809365 +188.32,50.43132484,-2.57294826,48.8113,6.27105456,7.792273437,1.8965625,1.605094109,-0.223974301,51.1856187 +188.33,50.4313254,-2.572947163,48.7926,6.264102155,7.793161482,1.845,1.56409302,-0.324937028,51.19314381 +188.34,50.43132596,-2.572946067,48.7744,6.267578321,7.794271568,1.793125,1.521721072,-0.42561637,51.20066887 +188.35,50.43132653,-2.572944969,48.7567,6.264102101,7.794715534,1.7396875,1.477987203,-0.525924606,51.20819398 +188.36,50.43132709,-2.572943872,48.7396,6.250197306,7.794271341,1.685,1.432900467,-0.625774191,51.21571904 +188.37,50.43132765,-2.572942776,48.723,6.250197297,7.794937349,1.63,1.386470259,-0.72507809,51.22324415 +188.38,50.43132821,-2.572941678,48.707,6.264102065,7.796713557,1.575,1.338706377,-0.82374973,51.23076921 +188.39,50.43132878,-2.572940581,48.6915,6.267578241,7.797823645,1.52,1.289618676,-0.921703053,51.23829432 +188.4,50.43132934,-2.572939483,48.6766,6.264102028,7.798267614,1.4646875,1.239217527,-1.018852631,51.24581938 +188.41,50.4313299,-2.572938386,48.6622,6.267578215,7.799155664,1.408125,1.187513358,-1.115113723,51.25334449 +188.42,50.43133047,-2.572937288,48.6484,6.264102019,7.800487795,1.3496875,1.134517053,-1.210402448,51.26086955 +188.43,50.43133103,-2.57293619,48.6352,6.250197228,7.801375847,1.29,1.080239558,-1.304635728,51.26839466 +188.44,50.43133159,-2.572935092,48.6226,6.250197203,7.801597779,1.23,1.024692331,-1.397731286,51.27591971 +188.45,50.43133215,-2.572933994,48.6106,6.264101957,7.801819712,1.1703125,0.967886946,-1.489607991,51.28344483 +188.46,50.43133272,-2.572932896,48.5992,6.264101949,7.802929806,1.1115625,0.909835206,-1.5801858,51.29096988 +188.47,50.43133328,-2.572931798,48.5884,6.246720981,7.80492806,1.0528125,0.850549258,-1.669385588,51.298495 +188.48,50.43133384,-2.572930699,48.5781,6.236292395,7.806260195,0.9915625,0.790041534,-1.75712972,51.30602005 +188.49,50.4313344,-2.5729296,48.5685,6.246720961,7.806260091,0.9284375,0.72832464,-1.843341534,51.31354516 +188.5,50.43133496,-2.572928502,48.5596,6.264101919,7.806482028,0.866875,0.665411411,-1.927945971,51.32107022 +188.51,50.43133553,-2.572927403,48.5512,6.264101918,7.807592125,0.8065625,0.601315081,-2.010869236,51.32859533 +188.52,50.43133609,-2.572926304,48.5434,6.246720949,7.808480183,0.744375,0.536049,-2.092038964,51.33612039 +188.53,50.43133665,-2.572925205,48.5363,6.232816165,7.808702122,0.68,0.469626748,-2.171384394,51.3436455 +188.54,50.43133721,-2.572924106,48.5298,6.229339953,7.808924062,0.6153125,0.402062247,-2.248836313,51.35117056 +188.55,50.43133777,-2.572923007,48.524,6.229339941,7.809812122,0.551875,0.333369592,-2.324327284,51.35869567 +188.56,50.43133833,-2.572921908,48.5188,6.232816138,7.811144263,0.49,0.263563107,-2.39779136,51.36622073 +188.57,50.43133889,-2.572920808,48.5142,6.246720921,7.812254366,0.4278125,0.192657402,-2.46916454,51.37374584 +188.58,50.43133945,-2.572919709,48.5102,6.264101884,7.813364469,0.3634375,0.120667318,-2.538384603,51.3812709 +188.59,50.43134002,-2.572918609,48.5069,6.264101866,7.814696612,0.298125,0.047607808,-2.6053911,51.38879601 +188.6,50.43134058,-2.572917509,48.5043,6.246720889,7.815584676,0.23375,-0.026505772,-2.670125705,51.39632107 +188.61,50.43134114,-2.572916409,48.5022,6.232816123,7.815806621,0.17,-0.101658068,-2.732531867,51.40384618 +188.62,50.4313417,-2.572915309,48.5009,6.229339941,7.816028567,0.10625,-0.177833323,-2.79255527,51.41137123 +188.63,50.43134226,-2.572914209,48.5001,6.229339941,7.816916633,0.041875,-0.25501555,-2.850143487,51.41889635 +188.64,50.43134282,-2.572913109,48.5,6.229339932,7.818248781,-0.0234375,-0.333188766,-2.905246385,51.4264214 +188.65,50.43134338,-2.572912008,48.5006,6.229339934,7.819358889,-0.088125,-0.412336583,-2.957815836,51.43394652 +188.66,50.43134394,-2.572910908,48.5018,6.229339944,7.820246958,-0.151875,-0.4924425,-3.007806002,51.44147157 +188.67,50.4313445,-2.572909807,48.5036,6.229339947,7.820690947,-0.2165625,-0.573489729,-3.05517334,51.44899663 +188.68,50.43134506,-2.572908706,48.5061,6.229339939,7.820468818,-0.2815625,-0.655461369,-3.099876538,51.45652174 +188.69,50.43134562,-2.572907606,48.5093,6.229339936,7.820690769,-0.345,-0.738340344,-3.141876579,51.4640468 +188.7,50.43134618,-2.572906505,48.513,6.229339946,7.822022922,-0.4084375,-0.822109237,-3.181136851,51.47157191 +188.71,50.43134674,-2.572905404,48.5174,6.229339962,7.823799156,-0.4734375,-0.906750688,-3.217623147,51.47909697 +188.72,50.4313473,-2.572904303,48.5225,6.229339968,7.825353349,-0.5378125,-0.992246992,-3.251303611,51.48662208 +188.73,50.43134786,-2.572903201,48.5282,6.229339963,7.826241423,-0.6,-1.078580215,-3.282148909,51.49414713 +188.74,50.43134842,-2.5729021,48.5345,6.229339963,7.826463377,-0.661875,-1.165732367,-3.31013211,51.50167225 +188.75,50.43134898,-2.572900998,48.5414,6.229339977,7.826685333,-0.725,-1.253685285,-3.335228808,51.5091973 +188.76,50.43134954,-2.572899897,48.549,6.229339996,7.827573411,-0.7884375,-1.342420576,-3.357417171,51.51672242 +188.77,50.4313501,-2.572898795,48.5572,6.229340005,7.828905568,-0.85125,-1.431919678,-3.376677778,51.52424747 +188.78,50.43135066,-2.572897693,48.566,6.229340001,7.830015686,-0.9134375,-1.522163968,-3.392993897,51.53177259 +188.79,50.43135122,-2.572896591,48.5755,6.225863803,7.831125805,-0.9746875,-1.61313454,-3.406351319,51.53929764 +188.8,50.43135178,-2.572895489,48.5855,6.211959039,7.832235924,-1.035,-1.704812371,-3.416738299,51.54682275 +188.81,50.43135234,-2.572894386,48.5962,6.1945781,7.832457885,-1.095,-1.797178439,-3.424145841,51.55434781 +188.82,50.43135289,-2.572893284,48.6074,6.194578124,7.832457807,-1.155,-1.89021332,-3.428567471,51.56187292 +188.83,50.43135345,-2.572892182,48.6193,6.211959105,7.83356793,-1.215,-1.983897649,-3.42999935,51.56939798 +188.84,50.43135401,-2.572891079,48.6317,6.22586389,7.834678052,-1.2746875,-2.078211888,-3.42844016,51.57692309 +188.85,50.43135457,-2.572889976,48.6448,6.229340086,7.834677975,-1.3334375,-2.17313627,-3.423891391,51.58444815 +188.86,50.43135513,-2.572888874,48.6584,6.225863892,7.834899939,-1.39125,-2.268651027,-3.416356938,51.59197326 +188.87,50.43135569,-2.572887771,48.6726,6.211959133,7.836010064,-1.4484375,-2.364736164,-3.405843335,51.59949832 +188.88,50.43135625,-2.572886668,48.6874,6.194578192,7.83712019,-1.5046875,-2.461371627,-3.392359804,51.60702343 +188.89,50.4313568,-2.572885565,48.7027,6.194578217,7.838230317,-1.56,-2.558537305,-3.375918093,51.61454849 +188.9,50.43135736,-2.572884462,48.7186,6.211959197,7.839562483,-1.615,-2.6562128,-3.356532524,51.6220736 +188.91,50.43135792,-2.572883358,48.735,6.222387778,7.840450571,-1.67,-2.754377831,-3.334220001,51.62959865 +188.92,50.43135848,-2.572882255,48.752,6.211959202,7.840672539,-1.725,-2.853011771,-3.308999946,51.63712377 +188.93,50.43135904,-2.572881151,48.7695,6.194578264,7.841116548,-1.779375,-2.952094107,-3.280894475,51.64464882 +188.94,50.43135959,-2.572880048,48.7876,6.194578302,7.842892797,-1.8315625,-3.051604099,-3.249927997,51.65217394 +188.95,50.43136015,-2.572878944,48.8062,6.208483091,7.845335167,-1.8815625,-3.151521006,-3.216127498,51.65969899 +188.96,50.43136071,-2.572877839,48.8252,6.208483092,7.846223258,-1.931875,-3.251823972,-3.179522485,51.66722411 +188.97,50.43136127,-2.572876735,48.8448,6.194578342,7.84533503,-1.983125,-3.352491969,-3.140144929,51.67474916 +188.98,50.43136182,-2.572875631,48.8649,6.194578382,7.844668843,-2.033125,-3.453504084,-3.098029093,51.68227427 +188.99,50.43136238,-2.572874527,48.8855,6.208483179,7.845334896,-2.0815625,-3.554839119,-3.053211704,51.68979933 +189,50.43136294,-2.572873423,48.9065,6.208483185,7.846667069,-2.1296875,-3.656475987,-3.005731895,51.69732444 +189.01,50.4313635,-2.572872318,48.9281,6.194578425,7.847777202,-2.1765625,-3.758393434,-2.955631033,51.7048495 +189.02,50.43136405,-2.572871214,48.9501,6.191102261,7.848887336,-2.22125,-3.860570143,-2.902952835,51.71237455 +189.03,50.43136461,-2.572870109,48.9725,6.194578478,7.850219511,-2.265,-3.962984802,-2.847743252,51.71989967 +189.04,50.43136517,-2.572869004,48.9954,6.191102295,7.851107607,-2.3084375,-4.065616039,-2.790050356,51.72742472 +189.05,50.43136572,-2.572867899,49.0187,6.191102312,7.851551623,-2.35125,-4.168442425,-2.729924451,51.73494984 +189.06,50.43136628,-2.572866794,49.0424,6.194578537,7.85243972,-2.393125,-4.271442475,-2.667418079,51.74247489 +189.07,50.43136684,-2.572865689,49.0666,6.191102377,7.853771896,-2.4334375,-4.374594645,-2.60258567,51.75000001 +189.08,50.43136739,-2.572864583,49.0911,6.191102402,7.854659994,-2.4728125,-4.47787745,-2.535483717,51.75752506 +189.09,50.43136795,-2.572863478,49.116,6.194578613,7.854881972,-2.511875,-4.581269288,-2.466170836,51.76505017 +189.1,50.43136851,-2.572862372,49.1414,6.187626248,7.855103951,-2.5496875,-4.684748617,-2.394707414,51.77257523 +189.11,50.43136906,-2.572861267,49.167,6.177197698,7.85599205,-2.58625,-4.788293722,-2.321155733,51.78010034 +189.12,50.43136962,-2.572860161,49.1931,6.177197723,7.857324229,-2.6215625,-4.891883059,-2.245579965,51.7876254 +189.13,50.43137017,-2.572859055,49.2195,6.187626323,7.858212329,-2.6546875,-4.99549497,-2.168046055,51.79515051 +189.14,50.43137073,-2.572857949,49.2462,6.194578733,7.85843431,-2.686875,-5.099107799,-2.088621557,51.80267557 +189.15,50.43137129,-2.572856843,49.2732,6.187626377,7.858656291,-2.7196875,-5.202699943,-2.007375798,51.81020068 +189.16,50.43137184,-2.572855737,49.3006,6.17719783,7.859766431,-2.75125,-5.306249803,-1.924379538,51.81772574 +189.17,50.4313724,-2.572854631,49.3283,6.173721667,7.861764731,-2.7796875,-5.409735664,-1.8397052,51.82525085 +189.18,50.43137295,-2.572853524,49.3562,6.173721699,7.863096913,-2.806875,-5.513135982,-1.753426579,51.83277591 +189.19,50.43137351,-2.572852417,49.3844,6.173721733,7.863096856,-2.835,-5.6164291,-1.665618964,51.84030102 +189.2,50.43137406,-2.572851311,49.4129,6.173721755,7.863318839,-2.8628125,-5.719593474,-1.5763589,51.84782607 +189.21,50.43137462,-2.572850204,49.4417,6.173721766,7.864428982,-2.8878125,-5.822607619,-1.485724253,51.85535119 +189.22,50.43137517,-2.572849097,49.4707,6.173721786,7.865317085,-2.9096875,-5.925449933,-1.393794035,51.86287624 +189.23,50.43137573,-2.57284799,49.4999,6.173721821,7.865761109,-2.9303125,-6.028099047,-1.300648401,51.87040136 +189.24,50.43137628,-2.572846883,49.5293,6.173721861,7.866649213,-2.9515625,-6.130533358,-1.206368539,51.87792641 +189.25,50.43137684,-2.572845776,49.5589,6.17372189,7.867981396,-2.9728125,-6.232731668,-1.111036727,51.88545153 +189.26,50.43137739,-2.572844668,49.5888,6.173721911,7.86909154,-2.99125,-6.334672491,-1.014736101,51.89297658 +189.27,50.43137795,-2.572843561,49.6188,6.173721941,7.870201684,-3.0065625,-6.43633457,-0.917550599,51.90050169 +189.28,50.4313785,-2.572842453,49.6489,6.173721979,7.871311828,-3.0215625,-6.537696705,-0.819564961,51.90802675 +189.29,50.43137906,-2.572841345,49.6792,6.173722009,7.871311773,-3.0365625,-6.638737698,-0.720864673,51.91555186 +189.3,50.43137961,-2.572840237,49.7097,6.173722028,7.870423559,-3.0496875,-6.739436463,-0.621535793,51.92307692 +189.31,50.43138017,-2.57283913,49.7402,6.173722052,7.870645545,-3.0615625,-6.839772029,-0.521664894,51.93060203 +189.32,50.43138072,-2.572838022,49.7709,6.170245896,7.872643849,-3.073125,-6.939723314,-0.421339068,51.93812709 +189.33,50.43138128,-2.572836914,49.8017,6.159817358,7.874864193,-3.0828125,-7.039269517,-0.320645861,51.9456522 +189.34,50.43138183,-2.572835805,49.8326,6.152865005,7.875974339,-3.09,-7.138389897,-0.21967305,51.95317726 +189.35,50.43138238,-2.572834697,49.8635,6.156341224,7.876196324,-3.0965625,-7.237063658,-0.1185087,51.96070237 +189.36,50.43138294,-2.572833588,49.8945,6.15634125,7.87641831,-3.1028125,-7.335270228,-0.017240988,51.96822743 +189.37,50.43138349,-2.57283248,49.9256,6.152865081,7.877306417,-3.10625,-7.432989097,0.084041736,51.97575248 +189.38,50.43138404,-2.572831371,49.9567,6.159817493,7.878638602,-3.1065625,-7.530199924,0.185251235,51.98327759 +189.39,50.4313846,-2.572830262,49.9877,6.17024611,7.879748748,-3.106875,-7.626882312,0.286299161,51.99080265 +189.4,50.43138515,-2.572829153,50.0188,6.170246149,7.880858893,-3.1084375,-7.723016093,0.387097391,51.99832776 +189.41,50.43138571,-2.572828044,50.0499,6.159817596,7.881969038,-3.1090625,-7.81858127,0.487558092,52.00585282 +189.42,50.43138626,-2.572826934,50.081,6.152865231,7.881968984,-3.1065625,-7.913557791,0.587593658,52.01337793 +189.43,50.43138681,-2.572825825,50.1121,6.156341455,7.881080771,-3.10125,-8.007925831,0.687116828,52.02090299 +189.44,50.43138737,-2.572824716,50.143,6.152865292,7.881302757,-3.095,-8.101665737,0.786040799,52.0284281 +189.45,50.43138792,-2.572823607,50.174,6.138960545,7.883301062,-3.088125,-8.194757857,0.884279341,52.03595316 +189.46,50.43138847,-2.572822497,50.2048,6.138960574,7.885521407,-3.0796875,-8.287182824,0.981746795,52.04347827 +189.47,50.43138902,-2.572821387,50.2356,6.152865377,7.886631552,-3.07,-8.378921274,1.078358137,52.05100333 +189.48,50.43138958,-2.572820277,50.2662,6.152865409,7.886853538,-3.0596875,-8.469954126,1.17402914,52.05852844 +189.49,50.43139013,-2.572819167,50.2968,6.138960673,7.887075523,-3.048125,-8.560262302,1.268676324,52.06605349 +189.5,50.43139068,-2.572818057,50.3272,6.138960709,7.887963628,-3.0346875,-8.64982695,1.362217242,52.07357861 +189.51,50.43139123,-2.572816947,50.3575,6.152865515,7.889295813,-3.02,-8.738629392,1.454570304,52.08110366 +189.52,50.43139179,-2.572815836,50.3876,6.15286554,7.890183918,-3.004375,-8.826651064,1.545654951,52.08862878 +189.53,50.43139234,-2.572814726,50.4176,6.138960782,7.890405903,-2.9865625,-8.913873576,1.635391773,52.09615383 +189.54,50.43139289,-2.572813615,50.4474,6.138960803,7.890627887,-2.9665625,-9.000278762,1.723702503,52.10367895 +189.55,50.43139344,-2.572812505,50.4769,6.152865617,7.891515991,-2.9465625,-9.085848519,1.810510078,52.111204 +189.56,50.431394,-2.572811394,50.5063,6.152865661,7.892848174,-2.9265625,-9.17056497,1.895738925,52.11872911 +189.57,50.43139455,-2.572810283,50.5355,6.135484716,7.893736277,-2.9046875,-9.254410525,1.979314674,52.12625417 +189.58,50.4313951,-2.572809172,50.5644,6.121579948,7.894180301,-2.88125,-9.337367538,2.061164388,52.13377928 +189.59,50.43139565,-2.572808061,50.5931,6.12157997,7.895068404,-2.8565625,-9.419418761,2.141216734,52.14130434 +189.6,50.4313962,-2.57280695,50.6216,6.135484787,7.896400586,-2.8296875,-9.500547064,2.219401924,52.14882945 +189.61,50.43139675,-2.572805838,50.6497,6.152865794,7.897288688,-2.8015625,-9.580735486,2.295651778,52.15635451 +189.62,50.43139731,-2.572804727,50.6776,6.152865814,7.897510669,-2.7734375,-9.659967242,2.369899774,52.16387962 +189.63,50.43139786,-2.572803615,50.7052,6.135484869,7.897732651,-2.7446875,-9.738225828,2.442081169,52.17140468 +189.64,50.43139841,-2.572802504,50.7325,6.121580126,7.898620753,-2.7146875,-9.815494916,2.512133052,52.17892979 +189.65,50.43139896,-2.572801392,50.7595,6.118103953,7.899952934,-2.6828125,-9.891758349,2.579994345,52.18645485 +189.66,50.43139951,-2.57280028,50.7862,6.118103964,7.900841036,-2.648125,-9.967000255,2.645605805,52.19397996 +189.67,50.43140006,-2.572799168,50.8125,6.118103989,7.901285056,-2.611875,-10.04120476,2.70891025,52.20150501 +189.68,50.43140061,-2.572798056,50.8384,6.121580226,7.902173155,-2.5765625,-10.11435658,2.769852505,52.20903013 +189.69,50.43140116,-2.572796944,50.864,6.135485039,7.903505332,-2.5415625,-10.18644028,2.828379399,52.21655518 +189.7,50.43140171,-2.572795831,50.8893,6.15286603,7.90461547,-2.5046875,-10.25744081,2.884439938,52.22408024 +189.71,50.43140227,-2.572794719,50.9141,6.152866048,7.905503569,-2.46625,-10.32734344,2.937985136,52.23160535 +189.72,50.43140282,-2.572793606,50.9386,6.135485099,7.906169626,-2.4265625,-10.39613355,2.98896841,52.23913041 +189.73,50.43140337,-2.572792493,50.9627,6.121580339,7.906613644,-2.3846875,-10.46379672,3.037345242,52.24665552 +189.74,50.43140392,-2.572791381,50.9863,6.11810416,7.907279701,-2.3415625,-10.53031884,3.08307352,52.25418058 +189.75,50.43140447,-2.572790267,51.0095,6.11810419,7.908167797,-2.2984375,-10.59568605,3.12611325,52.26170569 +189.76,50.43140502,-2.572789155,51.0323,6.118104225,7.909277932,-2.255,-10.65988465,3.166426961,52.26923075 +189.77,50.43140557,-2.572788041,51.0546,6.118104243,7.910610106,-2.21125,-10.72290124,3.203979532,52.27675586 +189.78,50.43140612,-2.572786928,51.0765,6.118104249,7.911498201,-2.1665625,-10.7847227,3.238738189,52.28428091 +189.79,50.43140667,-2.572785814,51.098,6.11810427,7.911942216,-2.1196875,-10.84533608,3.270672564,52.29180603 +189.8,50.43140722,-2.572784701,51.1189,6.118104306,7.912608269,-2.0715625,-10.90472871,3.299754928,52.29933108 +189.81,50.43140777,-2.572783587,51.1394,6.118104333,7.913052282,-2.023125,-10.96288828,3.32595984,52.3068562 +189.82,50.43140832,-2.572782473,51.1594,6.114628153,7.912830175,-1.973125,-11.01980253,3.34926444,52.31438125 +189.83,50.43140887,-2.57278136,51.1789,6.10072339,7.913052147,-1.9215625,-11.07545965,3.369648445,52.32190637 +189.84,50.43140942,-2.572780246,51.1978,6.083342428,7.914384318,-1.87,-11.12984795,3.387094036,52.32943142 +189.85,50.43140996,-2.572779132,51.2163,6.083342434,7.916160568,-1.8184375,-11.18295615,3.401586087,52.33695653 +189.86,50.43141051,-2.572778018,51.2342,6.100723425,7.917714777,-1.76625,-11.23477308,3.413111877,52.34448159 +189.87,50.43141106,-2.572776903,51.2516,6.114628233,7.918602866,-1.7134375,-11.28528796,3.421661382,52.3520067 +189.88,50.43141161,-2.572775789,51.2685,6.118104446,7.918824834,-1.6596875,-11.33449026,3.427227151,52.35953176 +189.89,50.43141216,-2.572774674,51.2848,6.118104455,7.919046803,-1.605,-11.3823697,3.429804315,52.36705687 +189.9,50.43141271,-2.57277356,51.3006,6.118104478,7.91993489,-1.5496875,-11.42891622,3.429390697,52.37458193 +189.91,50.43141326,-2.572772445,51.3158,6.11462831,7.921267055,-1.493125,-11.47412019,3.425986526,52.38210704 +189.92,50.43141381,-2.57277133,51.3305,6.10072354,7.922155141,-1.4353125,-11.51797208,3.419594895,52.3896321 +189.93,50.43141436,-2.572770215,51.3445,6.083342571,7.922377107,-1.378125,-11.5604628,3.410221305,52.39715721 +189.94,50.4314149,-2.5727691,51.358,6.083342589,7.922599071,-1.3215625,-11.60158347,3.397873893,52.40468227 +189.95,50.43141545,-2.572767985,51.371,6.100723576,7.923709194,-1.2628125,-11.64132543,3.382563544,52.41220738 +189.96,50.431416,-2.57276687,51.3833,6.114628358,7.925707475,-1.201875,-11.67968048,3.364303551,52.41973243 +189.97,50.43141655,-2.572765754,51.395,6.11462837,7.927039637,-1.141875,-11.71664056,3.343109842,52.42725755 +189.98,50.4314171,-2.572764638,51.4061,6.100723612,7.927039559,-1.083125,-11.75219792,3.319000867,52.4347826 +189.99,50.43141765,-2.572763523,51.4167,6.083342646,7.927039481,-1.023125,-11.78634517,3.29199771,52.44230772 +190,50.43141819,-2.572762407,51.4266,6.083342643,7.927261441,-0.96125,-11.81907521,3.262123862,52.44983277 +190.01,50.43141874,-2.572761291,51.4359,6.09724743,7.927261361,-0.89875,-11.85038117,3.229405394,52.45735789 +190.02,50.43141929,-2.572760176,51.4446,6.097247448,7.928371479,-0.8365625,-11.88025651,3.193870838,52.46488294 +190.03,50.43141984,-2.57275906,51.4526,6.083342678,7.930813834,-0.775,-11.90869498,3.155551134,52.47240805 +190.04,50.43142038,-2.572757943,51.4601,6.083342681,7.93259007,-0.713125,-11.93569069,3.1144798,52.47993311 +190.05,50.43142093,-2.572756827,51.4669,6.097247471,7.933034066,-0.6496875,-11.96123796,3.070692589,52.48745817 +190.06,50.43142148,-2.57275571,51.4731,6.097247486,7.933033982,-0.5853125,-11.98533146,3.02422766,52.49498328 +190.07,50.43142203,-2.572754594,51.4786,6.083342712,7.933255937,-0.521875,-12.00796616,2.975125578,52.50250833 +190.08,50.43142257,-2.572753477,51.4835,6.079866517,7.93414401,-0.4596875,-12.02913735,2.923429143,52.51003345 +190.09,50.43142312,-2.572752361,51.4878,6.08334272,7.935476163,-0.3965625,-12.04884057,2.869183447,52.5175585 +190.1,50.43142367,-2.572751243,51.4915,6.079866527,7.936586275,-0.3315625,-12.06707174,2.812435759,52.52508362 +190.11,50.43142421,-2.572750127,51.4944,6.079866518,7.937474345,-0.266875,-12.08382703,2.753235583,52.53260867 +190.12,50.43142476,-2.572749009,51.4968,6.08334271,7.937918335,-0.2034375,-12.09910301,2.691634541,52.54013379 +190.13,50.43142531,-2.572747892,51.4985,6.079866525,7.937696206,-0.1396875,-12.11289639,2.627686378,52.54765884 +190.14,50.43142585,-2.572746775,51.4996,6.079866535,7.938140196,-0.075,-12.12520433,2.561446784,52.55518395 +190.15,50.4314264,-2.572745658,51.5,6.083342735,7.939916423,-0.01,-12.13602423,2.492973629,52.56270901 +190.16,50.43142695,-2.57274454,51.4998,6.079866539,7.941470609,0.055,-12.14535394,2.422326501,52.57023412 +190.17,50.43142749,-2.572743422,51.4989,6.079866536,7.942358675,0.12,-12.15319137,2.349567106,52.57775918 +190.18,50.43142804,-2.572742305,51.4974,6.083342725,7.943690819,0.1846875,-12.15953499,2.274758872,52.58528429 +190.19,50.43142859,-2.572741186,51.4952,6.076390329,7.944800923,0.2484375,-12.16438341,2.197967,52.59280935 +190.2,50.43142913,-2.572740068,51.4924,6.065961747,7.944578789,0.3115625,-12.16773562,2.11925847,52.60033446 +190.21,50.43142968,-2.57273895,51.489,6.065961749,7.944134614,0.3753125,-12.16959097,2.038701922,52.60785952 +190.22,50.43143022,-2.572737832,51.4849,6.076390327,7.944800637,0.44,-12.16994907,1.9563676,52.61538463 +190.23,50.43143077,-2.572736714,51.4802,6.083342712,7.946132777,0.5046875,-12.16880974,1.872327239,52.62290969 +190.24,50.43143132,-2.572735595,51.4748,6.076390312,7.947242877,0.568125,-12.16617339,1.786654235,52.6304348 +190.25,50.43143186,-2.572734477,51.4688,6.065961716,7.948352977,0.63,-12.16204041,1.699423244,52.63795985 +190.26,50.43143241,-2.572733358,51.4622,6.062485519,7.949685116,0.691875,-12.15641173,1.610710298,52.64548497 +190.27,50.43143295,-2.572732239,51.455,6.062485519,7.950573174,0.755,-12.14928855,1.520592803,52.65301002 +190.28,50.4314335,-2.57273112,51.4471,6.062485515,7.950795112,0.8184375,-12.14067235,1.429149369,52.66053514 +190.29,50.43143404,-2.572730001,51.4386,6.062485507,7.951017049,0.88125,-12.13056486,1.336459638,52.66806019 +190.3,50.43143459,-2.572728882,51.4295,6.062485499,7.951905105,0.9434375,-12.11896826,1.24260451,52.67558531 +190.31,50.43143513,-2.572727763,51.4197,6.062485488,7.95323724,1.0046875,-12.10588499,1.147665804,52.68311036 +190.32,50.43143568,-2.572726643,51.4094,6.062485472,7.954125294,1.0646875,-12.09131771,1.051726313,52.69063547 +190.33,50.43143622,-2.572725524,51.3984,6.06248546,7.954347229,1.12375,-12.07526951,0.954869746,52.69816053 +190.34,50.43143677,-2.572724404,51.3869,6.062485459,7.954569163,1.183125,-12.0577437,0.857180499,52.70568564 +190.35,50.43143731,-2.572723285,51.3748,6.062485452,7.955457215,1.2434375,-12.03874402,0.758743772,52.7132107 +190.36,50.43143786,-2.572722165,51.362,6.062485436,7.956789345,1.303125,-12.01827436,0.659645393,52.72073581 +190.37,50.4314384,-2.572721045,51.3487,6.05900923,7.957677396,1.36125,-11.99633907,0.559971821,52.72826087 +190.38,50.43143895,-2.572719925,51.3348,6.048580629,7.958121366,1.4184375,-11.97294263,0.459809918,52.73578598 +190.39,50.43143949,-2.572718805,51.3203,6.041628213,7.959009416,1.475,-11.94809001,0.359247059,52.74331104 +190.4,50.43144003,-2.572717685,51.3053,6.048580591,7.960341544,1.5315625,-11.92178638,0.258370963,52.75083609 +190.41,50.43144058,-2.572716564,51.2897,6.059009176,7.961451631,1.588125,-11.89403717,0.157269524,52.75836121 +190.42,50.43144112,-2.572715444,51.2735,6.059009161,7.962339677,1.643125,-11.86484824,0.056030975,52.76588626 +190.43,50.43144167,-2.572714323,51.2568,6.048580556,7.962783645,1.6965625,-11.83422571,-0.045256447,52.77341137 +190.44,50.43144221,-2.572713202,51.2396,6.041628152,7.962561493,1.75,-11.80217594,-0.146504449,52.78093643 +190.45,50.43144275,-2.572712082,51.2218,6.04510433,7.963005459,1.8034375,-11.76870558,-0.247624624,52.78846154 +190.46,50.4314433,-2.572710961,51.2035,6.045104311,7.965003701,1.85625,-11.73382173,-0.348528909,52.7959866 +190.47,50.43144384,-2.57270984,51.1847,6.041628102,7.967001942,1.908125,-11.69753156,-0.44912924,52.80351171 +190.48,50.43144438,-2.572708718,51.1653,6.045104276,7.967223867,1.958125,-11.65984268,-0.549337954,52.81103677 +190.49,50.43144493,-2.572707597,51.1455,6.045104249,7.966335592,2.0065625,-11.620763,-0.649067618,52.81856188 +190.5,50.43144547,-2.572706476,51.1252,6.041628036,7.966557515,2.0553125,-11.58030067,-0.748231314,52.82608694 +190.51,50.43144601,-2.572705355,51.1044,6.04510422,7.968333715,2.1046875,-11.53846409,-0.846742526,52.83361205 +190.52,50.43144656,-2.572704233,51.0831,6.045104202,7.969887874,2.1528125,-11.4952621,-0.944515368,52.84113711 +190.53,50.4314471,-2.572703111,51.0613,6.041627986,7.970775914,2.198125,-11.45070363,-1.041464582,52.84866222 +190.54,50.43144764,-2.57270199,51.0391,6.045104162,7.972108032,2.2415625,-11.40479796,-1.137505601,52.85618728 +190.55,50.43144819,-2.572700867,51.0165,6.041627943,7.973218111,2.2853125,-11.35755479,-1.232554716,52.86371239 +190.56,50.43144873,-2.572699745,50.9934,6.027723131,7.972995952,2.3296875,-11.30898389,-1.326529019,52.87123744 +190.57,50.43144927,-2.572698623,50.9699,6.027723107,7.972551752,2.3728125,-11.25909548,-1.419346577,52.87876256 +190.58,50.43144981,-2.572697501,50.9459,6.041627877,7.973439789,2.4134375,-11.20789993,-1.510926432,52.88628761 +190.59,50.43145036,-2.572696379,50.9216,6.041627859,7.975438023,2.453125,-11.15540794,-1.601188714,52.89381273 +190.6,50.4314509,-2.572695256,50.8969,6.024246853,7.976770138,2.493125,-11.10163041,-1.690054754,52.90133778 +190.61,50.43145144,-2.572694133,50.8717,6.013818246,7.976770017,2.53125,-11.04657868,-1.77744709,52.90886289 +190.62,50.43145198,-2.572693011,50.8462,6.024246819,7.976991934,2.5665625,-10.9902642,-1.863289403,52.91638795 +190.63,50.43145252,-2.572691888,50.8204,6.041627772,7.978102008,2.601875,-10.93269873,-1.947506922,52.92391306 +190.64,50.43145307,-2.572690765,50.7942,6.041627741,7.979212081,2.638125,-10.8738943,-2.030026195,52.93143812 +190.65,50.43145361,-2.572689642,50.7676,6.024246733,7.980322154,2.6728125,-10.81386322,-2.110775257,52.93896323 +190.66,50.43145415,-2.572688519,50.7407,6.010341918,7.981432227,2.7046875,-10.75261792,-2.189683692,52.94648829 +190.67,50.43145469,-2.572687395,50.7135,6.010341891,7.981654142,2.735,-10.69017125,-2.266682688,52.9540134 +190.68,50.43145523,-2.572686272,50.686,6.024246658,7.981654017,2.7646875,-10.62653633,-2.341705094,52.96153846 +190.69,50.43145577,-2.572685149,50.6582,6.041627615,7.982986128,2.793125,-10.56172632,-2.414685479,52.96906357 +190.7,50.43145632,-2.572684025,50.6301,6.041627585,7.984762317,2.82,-10.49575487,-2.485560243,52.97658863 +190.71,50.43145686,-2.572682901,50.6018,6.024246584,7.98498423,2.8465625,-10.42863567,-2.554267566,52.98411374 +190.72,50.4314574,-2.572681777,50.5732,6.010341784,7.984317985,2.873125,-10.36038276,-2.620747515,52.99163879 +190.73,50.43145794,-2.572680654,50.5443,6.006865559,7.985206016,2.898125,-10.29101041,-2.684942165,52.99916391 +190.74,50.43145848,-2.57267953,50.5152,6.006865526,7.987426284,2.92125,-10.22053311,-2.74679548,53.00668896 +190.75,50.43145902,-2.572678405,50.4859,6.006865496,7.988536354,2.943125,-10.14896558,-2.806253545,53.01421402 +190.76,50.43145956,-2.572677281,50.4563,6.006865469,7.988536226,2.963125,-10.07632272,-2.863264507,53.02173913 +190.77,50.4314601,-2.572676157,50.4266,6.006865442,7.988980177,2.98125,-10.00261972,-2.917778691,53.02926419 +190.78,50.43146064,-2.572675032,50.3967,6.006865416,7.989868206,2.9984375,-9.927872051,-2.969748484,53.0367893 +190.79,50.43146118,-2.572673908,50.3666,6.006865395,7.990978275,3.0146875,-9.852095231,-3.01912868,53.04431436 +190.8,50.43146172,-2.572672783,50.3364,6.006865369,7.992310383,3.0296875,-9.775305078,-3.065876077,53.05183947 +190.81,50.43146226,-2.572671658,50.306,6.006865333,7.993198412,3.043125,-9.697517692,-3.109950053,53.05936453 +190.82,50.4314628,-2.572670533,50.2755,6.0068653,7.993420323,3.055,-9.618749288,-3.151312048,53.06688964 +190.83,50.43146334,-2.572669408,50.2449,6.006865276,7.993642233,3.0665625,-9.539016309,-3.189926081,53.0744147 +190.84,50.43146388,-2.572668283,50.2142,6.006865243,7.994530262,3.078125,-9.458335429,-3.22575846,53.08193981 +190.85,50.43146442,-2.572667158,50.1833,6.006865206,7.995862369,3.0878125,-9.376723493,-3.258777903,53.08946486 +190.86,50.43146496,-2.572666032,50.1524,6.00686518,7.996972435,3.094375,-9.294197517,-3.288955647,53.09698998 +190.87,50.4314655,-2.572664907,50.1214,6.006865158,7.997860463,3.0984375,-9.210774747,-3.316265394,53.10451503 +190.88,50.43146604,-2.572663781,50.0904,6.006865133,7.998304413,3.1015625,-9.126472659,-3.340683309,53.11204015 +190.89,50.43146658,-2.572662655,50.0594,6.006865111,7.998082244,3.105,-9.041308728,-3.362188076,53.1195652 +190.9,50.43146712,-2.57266153,50.0283,6.006865085,7.998526193,3.108125,-8.955300888,-3.380760961,53.12709031 +190.91,50.43146766,-2.572660404,49.9972,6.006865047,8.000524417,3.1096875,-8.868467014,-3.396385807,53.13461537 +190.92,50.4314682,-2.572659278,49.9661,6.006865014,8.002522643,3.1096875,-8.78082527,-3.409048919,53.14214048 +190.93,50.43146874,-2.572658151,49.935,6.00686499,8.002966592,3.1078125,-8.692393932,-3.418739297,53.14966554 +190.94,50.43146928,-2.572657025,49.9039,6.006864959,8.002744423,3.103125,-8.603191508,-3.425448518,53.15719065 +190.95,50.43146982,-2.572655899,49.8729,6.00686493,8.003188371,3.0965625,-8.513236562,-3.429170624,53.16471571 +190.96,50.43147036,-2.572654772,49.842,6.003388717,8.004076399,3.0903125,-8.422547942,-3.42990252,53.17224082 +190.97,50.4314709,-2.572653646,49.8111,5.989483908,8.005186466,3.0846875,-8.331144558,-3.427643462,53.17976588 +190.98,50.43147144,-2.572652519,49.7803,5.972102892,8.006518574,3.0778125,-8.239045546,-3.422395398,53.18729099 +190.99,50.43147197,-2.572651392,49.7495,5.972102865,8.007406602,3.0678125,-8.146270043,-3.414163026,53.19481605 +191,50.43147251,-2.572650265,49.7189,5.98948382,8.007628513,3.0546875,-8.052837528,-3.40295345,53.20234116 +191.01,50.43147305,-2.572649138,49.6884,6.003388564,8.007628383,3.0403125,-7.958767427,-3.388776412,53.20986622 +191.02,50.43147359,-2.572648011,49.6581,6.003388528,8.007850293,3.02625,-7.864079448,-3.371644286,53.21739133 +191.03,50.43147413,-2.572646884,49.6279,5.98948373,8.008960362,3.0115625,-7.768793358,-3.351572085,53.22491638 +191.04,50.43147467,-2.572645757,49.5978,5.972102744,8.011180628,2.9946875,-7.672929039,-3.328577283,53.2324415 +191.05,50.4314752,-2.572644629,49.568,5.972102716,8.013178854,2.9765625,-7.576506487,-3.302679877,53.23996655 +191.06,50.43147574,-2.572643501,49.5383,5.986007452,8.013400766,2.9584375,-7.479545871,-3.273902499,53.24749167 +191.07,50.43147628,-2.572642373,49.5088,5.986007412,8.01251248,2.939375,-7.382067473,-3.242270187,53.25501672 +191.08,50.43147682,-2.572641246,49.4795,5.972102607,8.012512352,2.9178125,-7.284091575,-3.207810614,53.26254178 +191.09,50.43147735,-2.572640118,49.4504,5.972102586,8.013844461,2.8934375,-7.185638633,-3.170553747,53.27006689 +191.1,50.43147789,-2.57263899,49.4216,5.986007345,8.015620649,2.868125,-7.08672933,-3.13053213,53.27759195 +191.11,50.43147843,-2.572637862,49.3931,5.986007325,8.017174798,2.843125,-6.987384178,-3.087780654,53.28511706 +191.12,50.43147897,-2.572636733,49.3647,5.972102521,8.01806283,2.8165625,-6.887624032,-3.042336564,53.29264212 +191.13,50.4314795,-2.572635605,49.3367,5.972102486,8.018284743,2.7878125,-6.787469634,-2.994239565,53.30016723 +191.14,50.43148004,-2.572634476,49.309,5.986007239,8.018284617,2.75875,-6.686942012,-2.943531482,53.30769228 +191.15,50.43148058,-2.572633348,49.2815,5.986007225,8.018506531,2.7296875,-6.586062021,-2.890256606,53.3152174 +191.16,50.43148112,-2.572632219,49.2544,5.97210242,8.019394564,2.699375,-6.48485086,-2.834461403,53.32274245 +191.17,50.43148165,-2.572631091,49.2275,5.968626189,8.020726675,2.6665625,-6.383329556,-2.776194517,53.33026757 +191.18,50.43148219,-2.572629961,49.201,5.972102362,8.021836748,2.63125,-6.281519368,-2.715506713,53.33779262 +191.19,50.43148273,-2.572628833,49.1749,5.968626152,8.022724782,2.5953125,-6.179441608,-2.652450989,53.34531774 +191.2,50.43148326,-2.572627703,49.1491,5.968626126,8.023390777,2.5596875,-6.077117477,-2.587082234,53.35284279 +191.21,50.4314838,-2.572626574,49.1237,5.972102291,8.024056773,2.523125,-5.974568402,-2.519457515,53.3603679 +191.22,50.43148434,-2.572625445,49.0986,5.965149879,8.025388887,2.485,-5.871815813,-2.449635847,53.36789296 +191.23,50.43148487,-2.572624315,49.074,5.954721278,8.026498961,2.44625,-5.768881194,-2.37767802,53.37541807 +191.24,50.43148541,-2.572623185,49.0497,5.954721258,8.02649884,2.4065625,-5.665785976,-2.303646831,53.38294313 +191.25,50.43148594,-2.572622056,49.0258,5.965149812,8.026720758,2.3646875,-5.562551701,-2.227606794,53.39046824 +191.26,50.43148648,-2.572620926,49.0024,5.972102178,8.027830835,2.3215625,-5.45919997,-2.149624316,53.3979933 +191.27,50.43148702,-2.572619796,48.9794,5.965149781,8.028718873,2.2784375,-5.355752325,-2.069767292,53.40551841 +191.28,50.43148755,-2.572618666,48.9568,5.954721182,8.029162832,2.2346875,-5.252230426,-1.988105394,53.41304347 +191.29,50.43148809,-2.572617536,48.9347,5.951244959,8.030050871,2.1896875,-5.148655814,-1.90470984,53.42056858 +191.3,50.43148862,-2.572616406,48.913,5.95124493,8.031382989,2.143125,-5.045050147,-1.819653338,53.42809364 +191.31,50.43148916,-2.572615275,48.8918,5.954721106,8.032271029,2.095,-4.941435085,-1.733010145,53.43561875 +191.32,50.43148969,-2.572614145,48.8711,5.965149678,8.032492952,2.0465625,-4.837832226,-1.644855661,53.4431438 +191.33,50.43149023,-2.572613014,48.8509,5.972102051,8.032714875,1.998125,-4.734263286,-1.555266891,53.45066892 +191.34,50.43149077,-2.572611884,48.8311,5.965149635,8.033602916,1.9484375,-4.630749809,-1.464321873,53.45819397 +191.35,50.4314913,-2.572610753,48.8119,5.954721031,8.034935037,1.8978125,-4.527313452,-1.372099962,53.46571909 +191.36,50.43149184,-2.572609622,48.7932,5.95124483,8.03582308,1.846875,-4.423975815,-1.278681542,53.47324414 +191.37,50.43149237,-2.572608491,48.7749,5.951244814,8.036267045,1.7946875,-4.3207585,-1.18414809,53.48076926 +191.38,50.43149291,-2.57260736,48.7573,5.951244787,8.03715509,1.7415625,-4.217682991,-1.088582053,53.48829431 +191.39,50.43149344,-2.572606229,48.7401,5.947768579,8.038487213,1.6884375,-4.11477089,-0.992066739,53.49581942 +191.4,50.43149398,-2.572605097,48.7235,5.937339991,8.039597298,1.634375,-4.012043626,-0.894686374,53.50334448 +191.41,50.43149451,-2.572603966,48.7074,5.930387591,8.040485344,1.5784375,-3.909522683,-0.796525812,53.51086959 +191.42,50.43149504,-2.572602834,48.6919,5.937339962,8.040929312,1.5215625,-3.807229491,-0.697670654,53.51839465 +191.43,50.43149558,-2.572601702,48.677,5.947768522,8.040707164,1.465,-3.705185421,-0.598207128,53.5259197 +191.44,50.43149611,-2.572600571,48.6626,5.951244702,8.040929095,1.408125,-3.603411673,-0.498221925,53.53344482 +191.45,50.43149665,-2.572599439,48.6488,5.951244701,8.042261223,1.3496875,-3.501929675,-0.397802305,53.54096987 +191.46,50.43149718,-2.572598307,48.6356,5.947768494,8.04403743,1.2903125,-3.400760512,-0.29703576,53.54849499 +191.47,50.43149772,-2.572597175,48.623,5.937339888,8.045369558,1.2315625,-3.299925268,-0.196010237,53.55602004 +191.48,50.43149825,-2.572596042,48.611,5.930387492,8.045591492,1.1734375,-3.199445144,-0.094813743,53.56354516 +191.49,50.43149878,-2.57259491,48.5995,5.937339887,8.045591387,1.1146875,-3.099340995,0.00646537,53.57107021 +191.5,50.43149932,-2.572593778,48.5887,5.947768461,8.046701479,1.0546875,-2.999633791,0.107738927,53.57859532 +191.51,50.43149985,-2.572592645,48.5784,5.947768437,8.047811572,0.9934375,-2.90034433,0.20891846,53.58612038 +191.52,50.43150039,-2.572591512,48.5688,5.93733984,8.047811469,0.93125,-2.801493354,0.309915851,53.59364549 +191.53,50.43150092,-2.57259038,48.5598,5.930387456,8.048033406,0.86875,-2.703101489,0.410642977,53.60117055 +191.54,50.43150145,-2.572589247,48.5514,5.933863652,8.0491435,0.8065625,-2.605189304,0.511012005,53.60869566 +191.55,50.43150199,-2.572588114,48.5437,5.930387449,8.050253596,0.7446875,-2.507777312,0.610935443,53.61622072 +191.56,50.43150252,-2.572586981,48.5365,5.916482658,8.051363694,0.681875,-2.410885737,0.710326145,53.62374583 +191.57,50.43150305,-2.572585848,48.53,5.916482641,8.052695831,0.618125,-2.314534862,0.809097423,53.63127089 +191.58,50.43150358,-2.572584714,48.5242,5.930387412,8.053583891,0.5553125,-2.218744799,0.90716316,53.638796 +191.59,50.43150412,-2.572583581,48.5189,5.933863614,8.053805833,0.493125,-2.1235356,1.004437815,53.64632106 +191.6,50.43150465,-2.572582447,48.5143,5.930387415,8.054027775,0.4296875,-2.02892709,1.100836589,53.65384617 +191.61,50.43150518,-2.572581314,48.5103,5.933863596,8.054915836,0.365,-1.934939036,1.196275429,53.66137122 +191.62,50.43150572,-2.57258018,48.507,5.930387401,8.056247976,0.3,-1.841591148,1.290671085,53.66889634 +191.63,50.43150625,-2.572579046,48.5043,5.913006437,8.057136039,0.2353125,-1.748902791,1.383941281,53.67642139 +191.64,50.43150678,-2.572577912,48.5023,5.902577856,8.057580025,0.1715625,-1.656893389,1.476004655,53.68394651 +191.65,50.43150731,-2.572576778,48.5009,5.913006435,8.05846809,0.108125,-1.565582194,1.566780879,53.69147156 +191.66,50.43150784,-2.572575644,48.5001,5.930387397,8.059800235,0.043125,-1.47498817,1.656190886,53.69899668 +191.67,50.43150838,-2.572574509,48.5,5.930387395,8.0606883,-0.023125,-1.38513034,1.744156695,53.70652173 +191.68,50.43150891,-2.572573375,48.5006,5.916482631,8.06091025,-0.088125,-1.296027439,1.830601531,53.71404684 +191.69,50.43150944,-2.57257224,48.5018,5.916482639,8.0611322,-0.1515625,-1.20769803,1.915450106,53.7215719 +191.7,50.43150997,-2.572571106,48.5036,5.930387411,8.062020269,-0.215,-1.120160622,1.998628337,53.72909701 +191.71,50.43151051,-2.572569971,48.5061,5.930387407,8.063352416,-0.2784375,-1.033433433,2.080063745,53.73662207 +191.72,50.43151104,-2.572568836,48.5092,5.913006444,8.064240486,-0.3415625,-0.947534683,2.159685341,53.74414718 +191.73,50.43151157,-2.572567701,48.5129,5.899101681,8.06446244,-0.4053125,-0.862482193,2.237423624,53.75167224 +191.74,50.4315121,-2.572566566,48.5173,5.895625493,8.064684394,-0.47,-0.778293779,2.313210814,53.75919735 +191.75,50.43151263,-2.572565431,48.5223,5.895625493,8.065572467,-0.5346875,-0.694986977,2.386980906,53.76672241 +191.76,50.43151316,-2.572564296,48.528,5.899101687,8.06690462,-0.5984375,-0.612579259,2.4586695,53.77424752 +191.77,50.43151369,-2.57256316,48.5343,5.913006461,8.068014733,-0.6615625,-0.531087816,2.528214086,53.78177258 +191.78,50.43151422,-2.572562025,48.5412,5.930387439,8.069124847,-0.725,-0.450529606,2.595553988,53.78929763 +191.79,50.43151476,-2.572560889,48.5488,5.93038746,8.070234962,-0.788125,-0.370921475,2.660630591,53.79682274 +191.8,50.43151529,-2.572559753,48.557,5.913006501,8.070456921,-0.8496875,-0.292280153,2.72338706,53.8043478 +191.81,50.43151582,-2.572558617,48.5658,5.899101723,8.070456842,-0.91,-0.214621911,2.783768733,53.81187291 +191.82,50.43151635,-2.572557482,48.5752,5.895625528,8.071566959,-0.9703125,-0.137963023,2.841722841,53.81939797 +191.83,50.43151688,-2.572556345,48.5852,5.895625538,8.072677077,-1.0315625,-0.062319588,2.897198964,53.82692308 +191.84,50.43151741,-2.572555209,48.5958,5.895625557,8.072677,-1.093125,0.012292752,2.950148744,53.83444814 +191.85,50.43151794,-2.572554073,48.6071,5.895625582,8.073121003,-1.1534375,0.085858299,3.000525886,53.84197325 +191.86,50.43151847,-2.572552937,48.6189,5.8956256,8.074897241,-1.213125,0.158361753,3.048286502,53.84949831 +191.87,50.431519,-2.5725518,48.6313,5.895625603,8.076229402,-1.2734375,0.229787932,3.093389052,53.85702342 +191.88,50.43151953,-2.572550663,48.6444,5.895625598,8.076229327,-1.3328125,0.300121939,3.135794059,53.86454848 +191.89,50.43152006,-2.572549527,48.658,5.895625607,8.076451293,-1.3896875,0.369349107,3.175464626,53.87207359 +191.9,50.43152059,-2.57254839,48.6722,5.895625634,8.077561417,-1.4453125,0.437454938,3.212366087,53.87959864 +191.91,50.43152112,-2.572547253,48.6869,5.895625657,8.078449503,-1.5015625,0.504425225,3.246466415,53.88712376 +191.92,50.43152165,-2.572546116,48.7022,5.895625669,8.078893511,-1.5584375,0.570245986,3.277735701,53.89464881 +191.93,50.43152218,-2.572544979,48.7181,5.895625678,8.079781596,-1.6146875,0.634903471,3.306146788,53.90217393 +191.94,50.43152271,-2.572543842,48.7345,5.895625682,8.08111376,-1.6696875,0.698384158,3.331674865,53.90969898 +191.95,50.43152324,-2.572542704,48.7515,5.895625696,8.082223887,-1.7234375,0.760674812,3.354297645,53.9172241 +191.96,50.43152377,-2.572541567,48.769,5.895625728,8.083334015,-1.7765625,0.821762483,3.373995418,53.92474915 +191.97,50.4315243,-2.572540429,48.787,5.895625761,8.084444144,-1.8296875,0.881634281,3.390751054,53.93227426 +191.98,50.43152483,-2.572539291,48.8056,5.892149584,8.084444077,-1.8815625,0.940277829,3.404549883,53.93979932 +191.99,50.43152536,-2.572538153,48.8247,5.878244807,8.083555855,-1.9315625,0.997680809,3.415379931,53.94732443 +192,50.43152589,-2.572537016,48.8442,5.860863836,8.083777828,-1.9815625,1.053831246,3.423231687,53.95484949 +192.01,50.43152641,-2.572535878,48.8643,5.860863858,8.085776116,-2.0315625,1.108717394,3.428098333,53.9623746 +192.02,50.43152694,-2.57253474,48.8849,5.878244863,8.087996443,-2.0796875,1.162327852,3.42997563,53.96989966 +192.03,50.43152747,-2.572533601,48.9059,5.892149668,8.089106576,-2.1265625,1.214651332,3.428861914,53.97742477 +192.04,50.431528,-2.572532463,48.9274,5.895625886,8.089328552,-2.1734375,1.265677005,3.424758219,53.98494983 +192.05,50.43152853,-2.572531324,48.9494,5.892149703,8.089550528,-2.2196875,1.315394157,3.417668095,53.99247494 +192.06,50.43152906,-2.572530186,48.9718,5.878244931,8.090216583,-2.2646875,1.363792475,3.407597674,54 +192.07,50.43152959,-2.572529047,48.9947,5.860863983,8.0906606,-2.308125,1.41086176,3.39455578,54.00752511 +192.08,50.43153011,-2.572527908,49.018,5.860864023,8.090438501,-2.35,1.456592157,3.378553813,54.01505016 +192.09,50.43153064,-2.57252677,49.0417,5.878245029,8.09088252,-2.3915625,1.50097427,3.359605641,54.02257528 +192.1,50.43153117,-2.572525631,49.0658,5.888673632,8.092880812,-2.433125,1.543998702,3.337727878,54.03010033 +192.11,50.4315317,-2.572524492,49.0904,5.878245063,8.094879105,-2.473125,1.585656458,3.312939603,54.03762545 +192.12,50.43153223,-2.572523352,49.1153,5.860864105,8.095323124,-2.51125,1.625938943,3.285262361,54.0451505 +192.13,50.43153275,-2.572522213,49.1406,5.860864118,8.095323067,-2.5484375,1.664837678,3.254720273,54.05267556 +192.14,50.43153328,-2.572521074,49.1663,5.87476892,8.096433205,-2.5846875,1.702344527,3.221340096,54.06020067 +192.15,50.43153381,-2.572519934,49.1923,5.87476896,8.097543343,-2.6196875,1.738451697,3.185150821,54.06772573 +192.16,50.43153434,-2.572518794,49.2187,5.86086422,8.097543286,-2.6534375,1.773151625,3.146184076,54.07525084 +192.17,50.43153486,-2.572517655,49.2454,5.860864248,8.097765269,-2.68625,1.806437036,3.10447378,54.0827759 +192.18,50.43153539,-2.572516515,49.2724,5.874769047,8.098875409,-2.7184375,1.838301052,3.060056373,54.09030101 +192.19,50.43153592,-2.572515375,49.2998,5.874769066,8.099985549,-2.7496875,1.868736971,3.012970529,54.09782606 +192.2,50.43153645,-2.572514235,49.3274,5.860864305,8.101095689,-2.7796875,1.897738433,2.96325733,54.10535118 +192.21,50.43153697,-2.572513095,49.3554,5.857388125,8.102427869,-2.808125,1.925299365,2.910960092,54.11287623 +192.22,50.4315375,-2.572511954,49.3836,5.860864344,8.103315971,-2.8346875,1.951414036,2.856124536,54.12040135 +192.23,50.43153803,-2.572510814,49.4121,5.857388191,8.103537957,-2.86,1.976077004,2.798798332,54.1279264 +192.24,50.43153855,-2.572509673,49.4408,5.857388234,8.103759942,-2.8846875,1.99928317,2.739031558,54.13545152 +192.25,50.43153908,-2.572508533,49.4698,5.860864458,8.104648045,-2.908125,2.021027549,2.676876294,54.14297657 +192.26,50.43153961,-2.572507392,49.499,5.857388281,8.105980227,-2.93,2.041305728,2.612386743,54.15050168 +192.27,50.43154013,-2.572506251,49.5284,5.857388296,8.106868331,-2.95125,2.060113354,2.545619169,54.15802674 +192.28,50.43154066,-2.57250511,49.558,5.860864512,8.107312356,-2.9715625,2.077446646,2.476631785,54.16555185 +192.29,50.43154119,-2.572503969,49.5879,5.853912156,8.108200461,-2.9896875,2.09330182,2.40548475,54.17307691 +192.3,50.43154171,-2.572502828,49.6178,5.843483609,8.109310604,-3.0065625,2.107675727,2.332240118,54.18060202 +192.31,50.43154224,-2.572501686,49.648,5.84348364,8.109532592,-3.023125,2.120565215,2.256961657,54.18812708 +192.32,50.43154276,-2.572500545,49.6783,5.853912252,8.10953254,-3.0378125,2.131967705,2.179715143,54.19565219 +192.33,50.43154329,-2.572499404,49.7088,5.860864675,8.110642684,-3.05,2.141880792,2.100567899,54.20317725 +192.34,50.43154382,-2.572498262,49.7393,5.853912318,8.111752828,-3.0615625,2.150302355,2.019588909,54.21070236 +192.35,50.43154434,-2.57249712,49.77,5.843483752,8.111752778,-3.073125,2.157230675,1.936848819,54.21822742 +192.36,50.43154487,-2.572495979,49.8008,5.840007567,8.112196805,-3.0828125,2.16266432,1.852419763,54.22575253 +192.37,50.43154539,-2.572494837,49.8317,5.840007592,8.114195106,-3.0896875,2.166602144,1.766375311,54.23327758 +192.38,50.43154592,-2.572493695,49.8626,5.840007634,8.116193407,-3.095,2.169043288,1.678790633,54.2408027 +192.39,50.43154644,-2.572492552,49.8936,5.840007672,8.116637434,-3.1,2.169987236,1.589741991,54.24832775 +192.4,50.43154697,-2.57249141,49.9246,5.840007701,8.116415344,-3.1046875,2.169433874,1.499307077,54.25585287 +192.41,50.43154749,-2.572490268,49.9557,5.840007734,8.116859373,-3.108125,2.167383258,1.407564732,54.26337792 +192.42,50.43154802,-2.572489125,49.9868,5.84000777,8.11774748,-3.1096875,2.163835847,1.314594995,54.27090304 +192.43,50.43154854,-2.572487983,50.0179,5.840007796,8.118857625,-3.1096875,2.158792329,1.220478885,54.27842809 +192.44,50.43154907,-2.57248684,50.049,5.84000781,8.120189808,-3.108125,2.152253791,1.125298506,54.2859532 +192.45,50.43154959,-2.572485697,50.0801,5.840007824,8.121077913,-3.1046875,2.144221611,1.029136879,54.29347826 +192.46,50.43155012,-2.572484554,50.1111,5.840007855,8.121299902,-3.1,2.134697448,0.932077829,54.30100332 +192.47,50.43155064,-2.572483411,50.1421,5.836531699,8.121299852,-3.095,2.123683251,0.834205923,54.30852843 +192.48,50.43155117,-2.572482268,50.173,5.826103148,8.121299802,-3.089375,2.111181427,0.735606648,54.31605348 +192.49,50.43155169,-2.572481125,50.2039,5.819150792,8.12152179,-3.0815625,2.097194495,0.636365888,54.3235786 +192.5,50.43155221,-2.572479982,50.2347,5.826103219,8.122631934,-3.07125,2.08172538,0.53657022,54.33110365 +192.51,50.43155274,-2.572478839,50.2653,5.836531836,8.124630235,-3.06,2.064777403,0.436306616,54.33862877 +192.52,50.43155326,-2.572477695,50.2959,5.836531865,8.126184458,-3.048125,2.046354002,0.335662626,54.34615382 +192.53,50.43155379,-2.572476551,50.3263,5.826103302,8.126850524,-3.0346875,2.026459017,0.234725854,54.35367894 +192.54,50.43155431,-2.572475408,50.3566,5.819150923,8.12729455,-3.02,2.005096686,0.133584422,54.36120399 +192.55,50.43155483,-2.572474263,50.3867,5.822627131,8.127516538,-3.0046875,1.98227148,0.032326508,54.3687291 +192.56,50.43155536,-2.57247312,50.4167,5.822627161,8.128182604,-2.9878125,1.957988039,-0.068959596,54.37625416 +192.57,50.43155588,-2.572471976,50.4465,5.819151004,8.129958865,-2.968125,1.93225152,-0.170185539,54.38377927 +192.58,50.4315564,-2.572470831,50.4761,5.822627234,8.131513086,-2.946875,1.905067308,-0.271263144,54.39130433 +192.59,50.43155693,-2.572469687,50.5054,5.822627268,8.131957111,-2.9265625,1.876441076,-0.372104174,54.39882944 +192.6,50.43155745,-2.572468542,50.5346,5.819151106,8.131957059,-2.90625,1.846378783,-0.472620681,54.4063545 +192.61,50.43155797,-2.572467398,50.5636,5.822627329,8.131957006,-2.8828125,1.814886731,-0.572725117,54.41387961 +192.62,50.4315585,-2.572466253,50.5923,5.822627349,8.132178992,-2.8565625,1.781971394,-0.672330105,54.42140467 +192.63,50.43155902,-2.572465109,50.6207,5.819151173,8.133067095,-2.83,1.74763982,-0.771348786,54.42892978 +192.64,50.43155954,-2.572463964,50.6489,5.822627391,8.134399275,-2.803125,1.711899057,-0.869694872,54.43645484 +192.65,50.43156007,-2.572462819,50.6768,5.819151217,8.135287377,-2.7746875,1.674756552,-0.967282533,54.44397995 +192.66,50.43156059,-2.572461674,50.7044,5.805246459,8.1357314,-2.745,1.636220155,-1.064026743,54.451505 +192.67,50.43156111,-2.572460529,50.7317,5.805246489,8.13684154,-2.7146875,1.596297889,-1.159843106,54.45903012 +192.68,50.43156163,-2.572459384,50.7587,5.819151302,8.138839837,-2.683125,1.554998059,-1.254648083,54.46655517 +192.69,50.43156216,-2.572458238,50.7854,5.819151333,8.140172015,-2.6496875,1.512329262,-1.34835894,54.47408029 +192.7,50.43156268,-2.572457092,50.8117,5.805246581,8.13994992,-2.6146875,1.468300492,-1.44089403,54.48160534 +192.71,50.4315632,-2.572455947,50.8377,5.805246605,8.139283747,-2.5784375,1.42292086,-1.532172681,54.48913046 +192.72,50.43156372,-2.572454801,50.8633,5.819151406,8.139505729,-2.5415625,1.376199933,-1.622115195,54.49665551 +192.73,50.43156425,-2.572453656,50.8885,5.819151425,8.141059944,-2.5046875,1.328147395,-1.710643248,54.50418062 +192.74,50.43156477,-2.57245251,50.9134,5.801770473,8.142614159,-2.4665625,1.278773273,-1.797679548,54.51170568 +192.75,50.43156529,-2.572451363,50.9379,5.787865718,8.142614101,-2.42625,1.228087937,-1.883148292,54.51923079 +192.76,50.43156581,-2.572450218,50.9619,5.787865739,8.142614043,-2.385,1.176101986,-1.966974825,54.52675585 +192.77,50.43156633,-2.572449072,50.9856,5.801770529,8.144168256,-2.3434375,1.122826193,-2.049086209,54.53428096 +192.78,50.43156685,-2.572447925,51.0088,5.819151516,8.145944508,-2.30125,1.06827173,-2.129410709,54.54180602 +192.79,50.43156738,-2.572446779,51.0316,5.819151541,8.147054642,-2.258125,1.012449942,-2.207878368,54.54933113 +192.8,50.4315679,-2.572445632,51.054,5.8017706,8.147498659,-2.213125,0.955372574,-2.284420716,54.55685619 +192.81,50.43156842,-2.572444485,51.0759,5.787865845,8.147276558,-2.1665625,0.897051544,-2.358971005,54.56438124 +192.82,50.43156894,-2.572443339,51.0973,5.784389664,8.147720574,-2.12,0.837498941,-2.431464204,54.57190636 +192.83,50.43156946,-2.572442192,51.1183,5.784389679,8.149718862,-2.073125,0.776727256,-2.501837172,54.57943141 +192.84,50.43156998,-2.572441045,51.1388,5.784389703,8.15171715,-2.0246875,0.71474915,-2.570028489,54.58695652 +192.85,50.4315705,-2.572439897,51.1588,5.784389728,8.151939126,-1.9746875,0.651577631,-2.635978739,54.59448158 +192.86,50.43157102,-2.57243875,51.1783,5.787865945,8.151050906,-1.9234375,0.587225819,-2.699630339,54.60200669 +192.87,50.43157154,-2.572437603,51.1973,5.801770747,8.151272879,-1.8715625,0.521707236,-2.760927828,54.60953175 +192.88,50.43157206,-2.572436456,51.2157,5.819151743,8.153049124,-1.82,0.455035461,-2.819817747,54.61705686 +192.89,50.43157259,-2.572435308,51.2337,5.819151753,8.154381292,-1.768125,0.38722453,-2.876248705,54.62458192 +192.9,50.43157311,-2.57243416,51.2511,5.801770784,8.154381224,-1.7146875,0.318288483,-2.930171596,54.63210703 +192.91,50.43157363,-2.572433013,51.268,5.787866018,8.154603195,-1.6603125,0.248241814,-2.981539325,54.63963209 +192.92,50.43157415,-2.572431865,51.2843,5.784389835,8.155713321,-1.60625,0.177099135,-3.030307086,54.6471572 +192.93,50.43157467,-2.572430717,51.3001,5.784389838,8.156601408,-1.5515625,0.104875283,-3.076432366,54.65468226 +192.94,50.43157519,-2.572429569,51.3154,5.784389846,8.157045416,-1.4946875,0.03158533,-3.119874943,54.66220737 +192.95,50.43157571,-2.572428421,51.33,5.784389867,8.157933501,-1.436875,-0.042755428,-3.160596944,54.66973242 +192.96,50.43157623,-2.572427273,51.3441,5.780913697,8.159265664,-1.38,-0.118131407,-3.198562904,54.67725754 +192.97,50.43157675,-2.572426124,51.3576,5.767008934,8.160375787,-1.323125,-0.194526964,-3.233739647,54.68478259 +192.98,50.43157727,-2.572424976,51.3706,5.749627965,8.16126387,-1.2646875,-0.271925999,-3.266096522,54.69230771 +192.99,50.43157778,-2.572423827,51.3829,5.74962797,8.161707875,-1.205,-0.350312469,-3.295605281,54.69983276 +193,50.4315783,-2.572422678,51.3947,5.767008958,8.161485762,-1.145,-0.429669989,-3.322240255,54.70735788 +193.01,50.43157882,-2.57242153,51.4058,5.780913758,8.161707726,-1.0846875,-0.509981941,-3.345978183,54.71488293 +193.02,50.43157934,-2.572420381,51.4164,5.784389971,8.163039884,-1.0234375,-0.591231596,-3.366798324,54.72240804 +193.03,50.43157986,-2.572419232,51.4263,5.784389982,8.164816119,-0.9615625,-0.673401938,-3.384682628,54.7299331 +193.04,50.43158038,-2.572418083,51.4356,5.784389991,8.166148275,-0.9003125,-0.756475833,-3.399615398,54.73745821 +193.05,50.4315809,-2.572416933,51.4443,5.784389998,8.166370235,-0.8396875,-0.84043598,-3.411583684,54.74498327 +193.06,50.43158142,-2.572415784,51.4524,5.780913802,8.166370156,-0.778125,-0.925264731,-3.420577002,54.75250838 +193.07,50.43158194,-2.572414635,51.4599,5.76700902,8.16748027,-0.715,-1.010944495,-3.426587558,54.76003344 +193.08,50.43158246,-2.572413485,51.4667,5.74962805,8.168590385,-0.6515625,-1.097457284,-3.429610025,54.76755855 +193.09,50.43158297,-2.572412335,51.4729,5.749628063,8.168590304,-0.5884375,-1.184785104,-3.429641824,54.77508361 +193.1,50.43158349,-2.572411186,51.4785,5.767009052,8.168812262,-0.525,-1.27290968,-3.426682956,54.78260872 +193.11,50.43158401,-2.572410036,51.4834,5.780913842,8.169922373,-0.4615625,-1.361812562,-3.420735998,54.79013378 +193.12,50.43158453,-2.572408886,51.4877,5.780913844,8.171032484,-0.398125,-1.451475243,-3.411806049,54.79765889 +193.13,50.43158505,-2.572407736,51.4914,5.767009056,8.172142594,-0.3334375,-1.541879045,-3.39990096,54.80518394 +193.14,50.43158557,-2.572406586,51.4944,5.749628074,8.173474742,-0.268125,-1.633005003,-3.385031101,54.81270906 +193.15,50.43158608,-2.572405435,51.4967,5.749628078,8.174362812,-0.20375,-1.724834095,-3.367209478,54.82023411 +193.16,50.4315866,-2.572404285,51.4985,5.763532866,8.174584764,-0.14,-1.817347183,-3.346451618,54.82775917 +193.17,50.43158712,-2.572403134,51.4995,5.763532863,8.174806715,-0.07625,-1.910524903,-3.32277557,54.83528428 +193.18,50.43158764,-2.572401984,51.5,5.749628074,8.175472743,-0.011875,-2.004347831,-3.296201959,54.84280934 +193.19,50.43158815,-2.572400833,51.4998,5.74962807,8.175916732,0.0534375,-2.098796371,-3.266754106,54.85033445 +193.2,50.43158867,-2.572399682,51.4989,5.763532857,8.175916642,0.118125,-2.193850814,-3.234457564,54.85785951 +193.21,50.43158919,-2.572398532,51.4974,5.763532867,8.177026745,0.1815625,-2.289491278,-3.199340465,54.86538462 +193.22,50.43158971,-2.572397381,51.4953,5.74962809,8.179247042,0.2453125,-2.385697767,-3.161433577,54.87290968 +193.23,50.43159022,-2.572396229,51.4925,5.74962809,8.180357144,0.31,-2.482450228,-3.120769845,54.88043479 +193.24,50.43159074,-2.572395078,51.4891,5.76353287,8.180579089,0.3746875,-2.579728435,-3.077384736,54.88795985 +193.25,50.43159126,-2.572393927,51.485,5.76353286,8.181689189,0.4384375,-2.677512105,-3.031316122,54.89548496 +193.26,50.43159178,-2.572392775,51.4803,5.749628067,8.182799288,0.5015625,-2.775780784,-2.98260411,54.90301001 +193.27,50.43159229,-2.572391623,51.475,5.746151871,8.182799192,0.565,-2.87451396,-2.93129127,54.91053513 +193.28,50.43159281,-2.572390472,51.469,5.749628069,8.183021135,0.6284375,-2.973691064,-2.877422294,54.91806018 +193.29,50.43159333,-2.57238932,51.4624,5.742675673,8.184131232,0.69125,-3.073291297,-2.821044164,54.9255853 +193.3,50.43159384,-2.572388168,51.4552,5.732247078,8.185019289,0.7534375,-3.173293918,-2.762206039,54.93311035 +193.31,50.43159436,-2.572387016,51.4473,5.732247069,8.185241228,0.8153125,-3.273678014,-2.700959257,54.94063546 +193.32,50.43159487,-2.572385864,51.4389,5.742675645,8.185463168,0.878125,-3.374422616,-2.63735716,54.94816052 +193.33,50.43159539,-2.572384712,51.4298,5.749628025,8.186351223,0.9415625,-3.475506695,-2.571455268,54.95568563 +193.34,50.43159591,-2.57238356,51.42,5.742675629,8.187683355,1.0028125,-3.576909166,-2.503310991,54.96321069 +193.35,50.43159642,-2.572382407,51.4097,5.732247038,8.188793447,1.061875,-3.678608831,-2.432983802,54.9707358 +193.36,50.43159694,-2.572381255,51.3988,5.732247031,8.189903538,1.121875,-3.780584433,-2.360535065,54.97826086 +193.37,50.43159745,-2.572380102,51.3873,5.742675609,8.191235667,1.183125,-3.882814714,-2.286027863,54.98578597 +193.38,50.43159797,-2.572378949,51.3751,5.749627989,8.191901679,1.243125,-3.985278246,-2.209527226,54.99331103 +193.39,50.43159849,-2.572377796,51.3624,5.742675579,8.191457496,1.30125,-4.087953773,-2.131099846,55.00083614 +193.4,50.431599,-2.572376643,51.3491,5.732246975,8.191235352,1.35875,-4.190819693,-2.050814078,55.0083612 +193.41,50.43159952,-2.572375491,51.3352,5.728770771,8.192345439,1.41625,-4.293854693,-1.968739993,55.01588631 +193.42,50.43160003,-2.572374337,51.3208,5.728770765,8.193677565,1.4734375,-4.397037058,-1.884949156,55.02341137 +193.43,50.43160055,-2.572373184,51.3057,5.728770754,8.194565612,1.53,-4.500345417,-1.799514617,55.03093648 +193.44,50.43160106,-2.572372031,51.2902,5.728770741,8.195897736,1.58625,-4.603758111,-1.712510861,55.03846153 +193.45,50.43160158,-2.572370877,51.274,5.728770727,8.197007821,1.641875,-4.70725354,-1.624013805,55.04598665 +193.46,50.43160209,-2.572369723,51.2573,5.728770712,8.19700771,1.69625,-4.810810104,-1.534100513,55.0535117 +193.47,50.43160261,-2.57236857,51.2401,5.728770695,8.197229638,1.75,-4.914406202,-1.442849535,55.06103682 +193.48,50.43160312,-2.572367416,51.2223,5.728770673,8.19833972,1.803125,-5.018020176,-1.350340343,55.06856187 +193.49,50.43160364,-2.572366262,51.204,5.728770653,8.199227764,1.8546875,-5.121630368,-1.256653607,55.07608698 +193.5,50.43160415,-2.572365108,51.1852,5.728770641,8.199449689,1.905,-5.225215122,-1.16187109,55.08361204 +193.51,50.43160467,-2.572363954,51.1659,5.728770631,8.199671615,1.955,-5.328752893,-1.066075354,55.0911371 +193.52,50.43160518,-2.5723628,51.1461,5.725294419,8.200559656,2.005,-5.432222023,-0.969350051,55.09866221 +193.53,50.4316057,-2.572361646,51.1258,5.714865813,8.201891774,2.0546875,-5.535600855,-0.871779407,55.10618727 +193.54,50.43160621,-2.572360491,51.105,5.707913401,8.203001852,2.103125,-5.638867846,-0.773448562,55.11371238 +193.55,50.43160672,-2.572359337,51.0837,5.714865768,8.20411193,2.1496875,-5.742001395,-0.674443288,55.12123743 +193.56,50.43160724,-2.572358182,51.062,5.725294333,8.205222007,2.195,-5.844980016,-0.574849874,55.12876255 +193.57,50.43160775,-2.572357027,51.0398,5.725294318,8.205443928,2.24,-5.947782167,-0.474755178,55.1362876 +193.58,50.43160827,-2.572355872,51.0172,5.714865716,8.20544381,2.2846875,-6.05038636,-0.374246521,55.14381272 +193.59,50.43160878,-2.572354718,50.9941,5.707913306,8.206553886,2.3284375,-6.152771225,-0.273411449,55.15133777 +193.6,50.43160929,-2.572353562,50.9706,5.711389482,8.207663962,2.37125,-6.254915333,-0.172338027,55.15886289 +193.61,50.43160981,-2.572352407,50.9467,5.711389461,8.207663842,2.413125,-6.356797371,-0.071114261,55.16638794 +193.62,50.43161032,-2.572351252,50.9223,5.707913243,8.208107799,2.453125,-6.45839608,0.030171442,55.17391305 +193.63,50.43161083,-2.572350097,50.8976,5.71138942,8.209883989,2.49125,-6.559690206,0.131430903,55.18143811 +193.64,50.43161135,-2.572348941,50.8725,5.711389405,8.211216101,2.5284375,-6.660658605,0.232575716,55.18896322 +193.65,50.43161186,-2.572347785,50.847,5.707913189,8.211215979,2.565,-6.761280192,0.333517759,55.19648828 +193.66,50.43161237,-2.57234663,50.8212,5.711389353,8.211437896,2.60125,-6.861533941,0.434168911,55.20401339 +193.67,50.43161289,-2.572345474,50.795,5.70791313,8.212547968,2.6365625,-6.961398995,0.534441509,55.21153845 +193.68,50.4316134,-2.572344318,50.7684,5.694008329,8.213436,2.6696875,-7.060854384,0.634248065,55.21906356 +193.69,50.43161391,-2.572343162,50.7416,5.694008308,8.213879955,2.7015625,-7.159879367,0.733501543,55.22658862 +193.7,50.43161442,-2.572342006,50.7144,5.707913063,8.214767987,2.7334375,-7.258453318,0.832115372,55.23411373 +193.71,50.43161494,-2.57234085,50.6869,5.707913037,8.216100095,2.7646875,-7.356555667,0.930003607,55.24163879 +193.72,50.43161545,-2.572339693,50.6591,5.694008229,8.216988125,2.7946875,-7.454165846,1.02708082,55.2491639 +193.73,50.43161596,-2.572338537,50.631,5.694008205,8.217210039,2.8228125,-7.551263456,1.123262443,55.25668895 +193.74,50.43161647,-2.57233738,50.6026,5.707912961,8.217431952,2.848125,-7.647828331,1.218464595,55.26421407 +193.75,50.43161699,-2.572336224,50.574,5.707912929,8.218319982,2.8715625,-7.743840186,1.312604196,55.27173912 +193.76,50.4316175,-2.572335067,50.5452,5.690531921,8.219652089,2.8953125,-7.839279084,1.405599143,55.27926424 +193.77,50.43161801,-2.57233391,50.5161,5.680103312,8.220540118,2.9196875,-7.934125028,1.497368475,55.28678929 +193.78,50.43161852,-2.572332753,50.4868,5.69053188,8.22076203,2.9428125,-8.028358193,1.587831979,55.2943144 +193.79,50.43161903,-2.572331596,50.4572,5.707912836,8.220983942,2.9628125,-8.121958928,1.676910931,55.30183946 +193.8,50.43161955,-2.572330439,50.4275,5.70791281,8.22187197,2.98,-8.214907636,1.764527579,55.30936457 +193.81,50.43162006,-2.572329282,50.3976,5.690531805,8.223204075,2.996875,-8.30718501,1.85060555,55.31688963 +193.82,50.43162057,-2.572328124,50.3676,5.676626995,8.224092103,3.0146875,-8.398771741,1.935069785,55.32441474 +193.83,50.43162108,-2.572326967,50.3373,5.673150773,8.224314015,3.03125,-8.489648634,2.017846544,55.3319398 +193.84,50.43162159,-2.572325809,50.3069,5.673150747,8.224535926,3.044375,-8.579796782,2.098863751,55.33946485 +193.85,50.4316221,-2.572324652,50.2764,5.676626914,8.225423953,3.055,-8.669197335,2.178050701,55.34698997 +193.86,50.43162261,-2.572323494,50.2458,5.690531663,8.226756057,3.065,-8.757831614,2.25533841,55.35451502 +193.87,50.43162312,-2.572322336,50.2151,5.70791261,8.227866123,3.075,-8.845681113,2.330659384,55.36204014 +193.88,50.43162364,-2.572321178,50.1843,5.707912587,8.228976188,3.0846875,-8.932727497,2.403947963,55.36956519 +193.89,50.43162415,-2.57232002,50.1534,5.690531591,8.230086252,3.093125,-9.018952545,2.475140318,55.37709031 +193.9,50.43162466,-2.572318861,50.1224,5.676626792,8.230308162,3.0996875,-9.104338326,2.544174284,55.38461536 +193.91,50.43162517,-2.572317703,50.0914,5.673150581,8.230308033,3.1046875,-9.188866961,2.6109897,55.39214047 +193.92,50.43162568,-2.572316545,50.0603,5.673150553,8.231418099,3.108125,-9.272520805,2.675528296,55.39966553 +193.93,50.43162619,-2.572315386,50.0292,5.673150515,8.232528164,3.1096875,-9.355282438,2.737733808,55.40719064 +193.94,50.4316267,-2.572314227,49.9981,5.673150479,8.232528036,3.1096875,-9.437134444,2.79755192,55.4147157 +193.95,50.43162721,-2.572313069,49.967,5.67315045,8.232749946,3.108125,-9.518059862,2.854930549,55.42224081 +193.96,50.43162772,-2.57231191,49.9359,5.673150423,8.23408205,3.105,-9.598041734,2.909819677,55.42976587 +193.97,50.43162823,-2.572310751,49.9049,5.673150396,8.23585823,3.1015625,-9.677063328,2.962171346,55.43729098 +193.98,50.43162874,-2.572309592,49.8739,5.673150366,8.237190334,3.098125,-9.755108201,3.011940007,55.44481604 +193.99,50.43162925,-2.572308432,49.8429,5.673150333,8.237412244,3.0928125,-9.832160024,3.059082173,55.45234115 +194,50.43162976,-2.572307273,49.812,5.673150301,8.237190077,3.0846875,-9.908202753,3.103556818,55.45986621 +194.01,50.43163027,-2.572306114,49.7812,5.673150279,8.237634026,3.075,-9.983220461,3.14532504,55.46739132 +194.02,50.43163078,-2.572304954,49.7505,5.673150258,8.238522052,3.065,-10.05719745,3.184350571,55.47491637 +194.03,50.43163129,-2.572303795,49.7199,5.673150234,8.239632118,3.0546875,-10.1301183,3.220599261,55.48244149 +194.04,50.4316318,-2.572302635,49.6894,5.669674014,8.240742183,3.043125,-10.20196784,3.254039542,55.48996654 +194.05,50.43163231,-2.572301475,49.659,5.655769215,8.240964094,3.029375,-10.27273094,3.284642249,55.49749166 +194.06,50.43163282,-2.572300315,49.6288,5.638388223,8.240963967,3.013125,-10.34239298,3.312380683,55.50501671 +194.07,50.43163332,-2.572299156,49.5987,5.638388197,8.242074034,2.995,-10.4109393,3.337230722,55.51254183 +194.08,50.43163383,-2.572297995,49.5689,5.655769137,8.243184101,2.9765625,-10.47835558,3.359170594,55.52006688 +194.09,50.43163434,-2.572296835,49.5392,5.669673883,8.243183974,2.9584375,-10.54462783,3.378181276,55.52759199 +194.1,50.43163485,-2.572295675,49.5097,5.67315005,8.243627925,2.939375,-10.60974213,3.394246096,55.53511705 +194.11,50.43163536,-2.572294515,49.4804,5.673150025,8.245404107,2.918125,-10.67368491,3.407351073,55.54264216 +194.12,50.43163587,-2.572293354,49.4513,5.669673804,8.246958251,2.8946875,-10.73644281,3.417484806,55.55016722 +194.13,50.43163638,-2.572292193,49.4225,5.655768996,8.24784628,2.8696875,-10.79800271,3.42463847,55.55769233 +194.14,50.43163689,-2.572291033,49.3939,5.638387989,8.248956348,2.8434375,-10.85835179,3.428805764,55.56521739 +194.15,50.43163739,-2.572289871,49.3656,5.63838796,8.249400301,2.8165625,-10.91747742,3.429983078,55.5727425 +194.16,50.4316379,-2.57228871,49.3376,5.655768915,8.248956099,2.7896875,-10.97536724,3.42816938,55.58026756 +194.17,50.43163841,-2.57228755,49.3098,5.666197486,8.249400052,2.7615625,-11.03200922,3.423366332,55.58779267 +194.18,50.43163892,-2.572286388,49.2823,5.655768888,8.250510121,2.73125,-11.08739149,3.415578002,55.59531773 +194.19,50.43163943,-2.572285227,49.2552,5.638387899,8.251176113,2.6996875,-11.14150249,3.404811266,55.60284278 +194.2,50.43163993,-2.572284066,49.2283,5.638387876,8.251842107,2.6665625,-11.19433091,3.391075462,55.61036789 +194.21,50.43164044,-2.572282904,49.2018,5.652292622,8.252730139,2.6315625,-11.24586572,3.374382623,55.61789295 +194.22,50.43164095,-2.572281743,49.1757,5.652292591,8.25384021,2.5965625,-11.29609612,3.354747245,55.62541806 +194.23,50.43164146,-2.572280581,49.1499,5.638387786,8.25517232,2.5615625,-11.34501171,3.332186516,55.63294312 +194.24,50.43164196,-2.572279419,49.1244,5.638387764,8.255838314,2.5246875,-11.39260221,3.306720032,55.64046823 +194.25,50.43164247,-2.572278257,49.0994,5.652292522,8.255394116,2.4865625,-11.43885773,3.278370023,55.64799329 +194.26,50.43164298,-2.572277095,49.0747,5.652292501,8.255171958,2.448125,-11.48376851,3.247161241,55.6555184 +194.27,50.43164349,-2.572275934,49.0504,5.6383877,8.256282031,2.4078125,-11.52732528,3.213120902,55.66304346 +194.28,50.43164399,-2.572274771,49.0265,5.634911487,8.257614143,2.365,-11.56951892,3.176278684,55.67056857 +194.29,50.4316445,-2.572273609,49.0031,5.63838767,8.258502178,2.321875,-11.61034056,3.136666674,55.67809363 +194.3,50.43164501,-2.572272447,48.9801,5.634911467,8.260056331,2.2796875,-11.64978177,3.094319478,55.68561874 +194.31,50.43164551,-2.572271284,48.9575,5.634911447,8.261832522,2.23625,-11.68783419,3.049273995,55.69314379 +194.32,50.43164602,-2.572270121,48.9353,5.638387612,8.262054444,2.19,-11.72448996,3.001569471,55.70066891 +194.33,50.43164653,-2.572268958,48.9137,5.634911389,8.261166174,2.143125,-11.75974142,2.951247505,55.70819396 +194.34,50.43164703,-2.572267796,48.8925,5.634911367,8.261166058,2.096875,-11.79358123,2.898352041,55.71571908 +194.35,50.43164754,-2.572266633,48.8717,5.638387537,8.262498174,2.049375,-11.82600222,2.842929203,55.72324413 +194.36,50.43164805,-2.57226547,48.8515,5.631435126,8.264274368,2,-11.85699774,2.785027235,55.73076925 +194.37,50.43164855,-2.572264307,48.8317,5.621006531,8.265606486,1.95,-11.88656122,2.724696727,55.7382943 +194.38,50.43164906,-2.572263143,48.8125,5.621006529,8.265828412,1.8996875,-11.91468657,2.661990163,55.74581941 +194.39,50.43164956,-2.57226198,48.7937,5.631435111,8.265828299,1.8484375,-11.94136784,2.596962375,55.75334447 +194.4,50.43165007,-2.572260817,48.7755,5.638387485,8.266938379,1.79625,-11.96659953,2.529669972,55.76086958 +194.41,50.43165058,-2.572259653,48.7578,5.63143507,8.268048461,1.7434375,-11.9903763,2.460171681,55.76839464 +194.42,50.43165108,-2.572258489,48.7406,5.621006462,8.268048352,1.6896875,-12.01269324,2.388528064,55.77591975 +194.43,50.43165159,-2.572257326,48.724,5.61753025,8.268492319,1.6346875,-12.03354569,2.314801631,55.78344481 +194.44,50.43165209,-2.572256162,48.7079,5.617530237,8.270268519,1.5784375,-12.05292925,2.239056668,55.79096992 +194.45,50.4316526,-2.572254998,48.6924,5.617530223,8.271600641,1.521875,-12.07083986,2.161359179,55.79849498 +194.46,50.4316531,-2.572253833,48.6775,5.617530213,8.271600534,1.4665625,-12.08727389,2.081776946,55.80602009 +194.47,50.43165361,-2.57225267,48.6631,5.61753021,8.271822466,1.41125,-12.10222775,2.00037941,55.81354515 +194.48,50.43165411,-2.572251505,48.6492,5.617530209,8.272932552,1.353125,-12.11569844,1.917237505,55.82107026 +194.49,50.43165462,-2.572250341,48.636,5.617530198,8.273820601,1.293125,-12.12768312,1.832423708,55.82859531 +194.5,50.43165512,-2.572249176,48.6234,5.617530176,8.274264574,1.23375,-12.1381793,1.746012047,55.83612043 +194.51,50.43165563,-2.572248012,48.6113,5.617530157,8.275152624,1.175,-12.14718471,1.658077808,55.84364548 +194.52,50.43165613,-2.572246847,48.5999,5.617530145,8.276484753,1.11625,-12.15469756,1.568697767,55.8511706 +194.53,50.43165664,-2.572245682,48.589,5.617530136,8.277372805,1.0565625,-12.16071619,1.477949732,55.85869565 +194.54,50.43165714,-2.572244517,48.5787,5.614053935,8.277594742,0.9946875,-12.16523947,1.385912943,55.86622071 +194.55,50.43165765,-2.572243352,48.5691,5.603625352,8.277594641,0.931875,-12.16826635,1.292667557,55.87374582 +194.56,50.43165815,-2.572242187,48.5601,5.596672966,8.27781658,0.8703125,-12.1697962,1.198294991,55.88127088 +194.57,50.43165865,-2.572241022,48.5517,5.603625348,8.278704636,0.8096875,-12.16982874,1.102877464,55.88879599 +194.58,50.43165916,-2.572239857,48.5439,5.614053915,8.280036769,0.748125,-12.16836398,1.006498228,55.89632105 +194.59,50.43165966,-2.572238691,48.5367,5.614053901,8.280924825,0.6846875,-12.16540219,0.909241336,55.90384616 +194.6,50.43166017,-2.572237526,48.5302,5.603625309,8.281146766,0.6203125,-12.160944,0.811191584,55.91137121 +194.61,50.43166067,-2.57223636,48.5243,5.596672915,8.281368709,0.5565625,-12.15499028,0.712434401,55.91889633 +194.62,50.43166117,-2.572235195,48.5191,5.600149108,8.282256769,0.4934375,-12.14754241,0.613056017,55.92642138 +194.63,50.43166168,-2.572234029,48.5144,5.600149113,8.283588906,0.43,-12.13860186,0.513143007,55.9339465 +194.64,50.43166218,-2.572232863,48.5105,5.596672926,8.284699006,0.3665625,-12.12817047,0.412782516,55.94147155 +194.65,50.43166268,-2.572231697,48.5071,5.600149118,8.285809105,0.3034375,-12.11625049,0.312062093,55.94899667 +194.66,50.43166319,-2.572230531,48.5044,5.600149106,8.287141244,0.239375,-12.10284431,0.211069573,55.95652172 +194.67,50.43166369,-2.572229364,48.5023,5.596672901,8.288251346,0.17375,-12.08795485,0.109892961,55.96404683 +194.68,50.43166419,-2.572228198,48.5009,5.600149095,8.289139411,0.1084375,-12.0715851,0.008620494,55.97157189 +194.69,50.4316647,-2.572227031,48.5002,5.596672909,8.289583399,0.045,-12.05373861,-0.092659422,55.979097 +194.7,50.4316652,-2.572225864,48.5,5.582768141,8.289361273,-0.0184375,-12.03441899,-0.193858551,55.98662206 +194.71,50.4316657,-2.572224698,48.5005,5.582768142,8.289583224,-0.08375,-12.01363037,-0.294888657,55.99414717 +194.72,50.4316662,-2.572223531,48.5017,5.596672911,8.290471291,-0.1496875,-11.99137703,-0.39566162,56.00167223 +194.73,50.43166671,-2.572222364,48.5035,5.596672905,8.290693244,-0.2146875,-11.96766357,-0.496089548,56.00919734 +194.74,50.43166721,-2.572221197,48.506,5.582768126,8.29069316,-0.2784375,-11.94249508,-0.596084893,56.0167224 +194.75,50.43166771,-2.572220031,48.5091,5.582768132,8.291803269,-0.3415625,-11.91587672,-0.69556045,56.02424751 +194.76,50.43166821,-2.572218863,48.5128,5.596672923,8.293135416,-0.405,-11.88781405,-0.794429417,56.03177257 +194.77,50.43166872,-2.572217696,48.5172,5.596672938,8.294023488,-0.4684375,-11.85831291,-0.892605678,56.03929768 +194.78,50.43166922,-2.572216529,48.5222,5.582768164,8.295355636,-0.5315625,-11.82737955,-0.990003518,56.04682273 +194.79,50.43166972,-2.572215361,48.5278,5.582768159,8.296465748,-0.595,-11.79502038,-1.08653814,56.05434785 +194.8,50.43167022,-2.572214193,48.5341,5.596672935,8.296465668,-0.6584375,-11.76124217,-1.182125205,56.0618729 +194.81,50.43167073,-2.572213026,48.541,5.596672939,8.296687628,-0.7215625,-11.7260519,-1.276681519,56.06939802 +194.82,50.43167123,-2.572211858,48.5485,5.579291975,8.297797743,-0.785,-11.68945703,-1.370124461,56.07692307 +194.83,50.43167173,-2.57221069,48.5567,5.565387212,8.298907858,-0.848125,-11.65146512,-1.462372728,56.08444819 +194.84,50.43167223,-2.572209522,48.5655,5.561911037,8.300017974,-0.9096875,-11.61208418,-1.553345706,56.09197324 +194.85,50.43167273,-2.572208354,48.5749,5.56538724,8.301128091,-0.97,-11.57132236,-1.642964155,56.09949835 +194.86,50.43167323,-2.572207185,48.5849,5.579292017,8.301350054,-1.03,-11.52918819,-1.73114998,56.10702341 +194.87,50.43167373,-2.572206017,48.5955,5.596672992,8.301127942,-1.0903125,-11.48569055,-1.817826119,56.11454852 +194.88,50.43167424,-2.572204849,48.6067,5.596673002,8.301571945,-1.1515625,-11.44083838,-1.902917169,56.12207358 +194.89,50.43167474,-2.57220368,48.6185,5.579292048,8.302460026,-1.213125,-11.39464114,-1.98634882,56.12959863 +194.9,50.43167524,-2.572202512,48.631,5.565387291,8.303570146,-1.2728125,-11.34710851,-2.068048304,56.13712375 +194.91,50.43167574,-2.572201343,48.644,5.561911108,8.304902306,-1.3296875,-11.29825033,-2.147944461,56.1446488 +194.92,50.43167624,-2.572200174,48.6576,5.56191111,8.305790391,-1.3853125,-11.24807682,-2.225967562,56.15217392 +194.93,50.43167674,-2.572199005,48.6717,5.561911114,8.30601236,-1.441875,-11.19659851,-2.302049654,56.15969897 +194.94,50.43167724,-2.572197836,48.6864,5.561911127,8.30623433,-1.5,-11.14382612,-2.376124216,56.16722409 +194.95,50.43167774,-2.572196667,48.7017,5.56191115,8.307122416,-1.558125,-11.08977064,-2.448126848,56.17474914 +194.96,50.43167824,-2.572195498,48.7176,5.561911175,8.308454579,-1.6146875,-11.03444343,-2.517994639,56.18227425 +194.97,50.43167874,-2.572194328,48.734,5.56191119,8.309342667,-1.6696875,-10.977856,-2.585666684,56.18979931 +194.98,50.43167924,-2.572193159,48.751,5.561911194,8.30956464,-1.723125,-10.92002015,-2.651084026,56.19732442 +194.99,50.43167974,-2.572191989,48.7685,5.561911203,8.309786613,-1.775,-10.86094797,-2.71418954,56.20484948 +195,50.43168024,-2.57219082,48.7865,5.561911226,8.310674702,-1.8265625,-10.80065184,-2.77492828,56.21237459 +195.01,50.43168074,-2.57218965,48.805,5.561911254,8.312006869,-1.8784375,-10.73914431,-2.833247248,56.21989965 +195.02,50.43168124,-2.57218848,48.8241,5.561911271,8.31289496,-1.9296875,-10.6764382,-2.889095564,56.22742476 +195.03,50.43168174,-2.57218731,48.8436,5.561911277,8.313116936,-1.98,-10.6125467,-2.942424528,56.23494982 +195.04,50.43168224,-2.57218614,48.8637,5.561911286,8.313338914,-2.03,-10.54748305,-2.993187672,56.24247493 +195.05,50.43168274,-2.57218497,48.8842,5.561911305,8.314227006,-2.079375,-10.48126087,-3.041340706,56.24999999 +195.06,50.43168324,-2.5721838,48.9053,5.561911333,8.315337138,-2.1265625,-10.41389404,-3.086841634,56.2575251 +195.07,50.43168374,-2.572182629,48.9268,5.561911363,8.315781155,-2.1715625,-10.34539654,-3.129650806,56.26505015 +195.08,50.43168424,-2.572181459,48.9487,5.558435187,8.316447211,-2.216875,-10.27578274,-3.169730923,56.27257527 +195.09,50.43168474,-2.572180289,48.9711,5.544530416,8.318001421,-2.263125,-10.2050672,-3.207046919,56.28010032 +195.1,50.43168524,-2.572179117,48.994,5.527149457,8.318889517,-2.3078125,-10.13326459,-3.241566366,56.28762544 +195.11,50.43168573,-2.572177947,49.0173,5.527149491,8.318889461,-2.3496875,-10.06038997,-3.273259068,56.29515049 +195.12,50.43168623,-2.572176776,49.041,5.544530503,8.319333481,-2.39,-9.986458589,-3.302097466,56.30267561 +195.13,50.43168673,-2.572175605,49.0651,5.5584353,8.320221579,-2.43,-9.911485801,-3.328056407,56.31020066 +195.14,50.43168723,-2.572174434,49.0896,5.561911499,8.321331714,-2.47,-9.835487362,-3.351113203,56.31772577 +195.15,50.43168773,-2.572173263,49.1145,5.558435318,8.322663889,-2.5096875,-9.758479084,-3.371247799,56.32525083 +195.16,50.43168823,-2.572172091,49.1398,5.544530566,8.323551988,-2.548125,-9.680477011,-3.388442607,56.33277594 +195.17,50.43168873,-2.57217092,49.1655,5.527149625,8.323773973,-2.5846875,-9.601497529,-3.40268267,56.340301 +195.18,50.43168922,-2.572169748,49.1915,5.527149648,8.323995958,-2.6196875,-9.521557082,-3.4139555,56.34782611 +195.19,50.43168972,-2.572168577,49.2179,5.544530636,8.32466202,-2.653125,-9.440672344,-3.422251299,56.35535117 +195.2,50.43169022,-2.572167405,49.2446,5.554959238,8.325328082,-2.685,-9.358860216,-3.427562904,56.36287628 +195.21,50.43169072,-2.572166233,49.2716,5.544530683,8.325994145,-2.7165625,-9.27613783,-3.429885561,56.37040134 +195.22,50.43169122,-2.572165062,49.2989,5.527149743,8.327326324,-2.748125,-9.192522432,-3.429217377,56.37792645 +195.23,50.43169171,-2.572163889,49.3266,5.527149768,8.328436464,-2.778125,-9.10803144,-3.425558813,56.38545151 +195.24,50.43169221,-2.572162717,49.3545,5.541054562,8.328436413,-2.80625,-9.022682558,-3.418913132,56.39297656 +195.25,50.43169271,-2.572161545,49.3827,5.54105458,8.3286584,-2.8334375,-8.936493606,-3.409286066,56.40050167 +195.26,50.43169321,-2.572160373,49.4112,5.527149831,8.329768542,-2.8596875,-8.849482573,-3.396686094,56.40802673 +195.27,50.4316937,-2.5721592,49.4399,5.527149868,8.330878684,-2.8846875,-8.761667566,-3.381124159,56.41555184 +195.28,50.4316942,-2.572158028,49.4689,5.541054674,8.331988827,-2.908125,-8.673067035,-3.362613841,56.4230769 +195.29,50.4316947,-2.572156855,49.4981,5.541054689,8.333098969,-2.9296875,-8.583699427,-3.341171239,56.43060201 +195.3,50.4316952,-2.572155682,49.5275,5.527149927,8.33309892,-2.95,-8.493583422,-3.31681509,56.43812707 +195.31,50.43169569,-2.572154509,49.5571,5.523673765,8.332432757,-2.97,-8.402737812,-3.28956665,56.44565218 +195.32,50.43169619,-2.572153337,49.5869,5.527149997,8.333320862,-2.9896875,-8.311181563,-3.259449639,56.45317724 +195.33,50.43169669,-2.572152164,49.6169,5.523673829,8.335541197,-3.0078125,-8.218933811,-3.226490356,56.46070235 +195.34,50.43169718,-2.57215099,49.6471,5.523673846,8.336429302,-3.023125,-8.126013865,-3.190717564,56.46822741 +195.35,50.43169768,-2.572149817,49.6774,5.527150071,8.335763139,-3.0365625,-8.032441033,-3.152162375,56.47575252 +195.36,50.43169818,-2.572148644,49.7078,5.520197722,8.33598513,-3.05,-7.938234969,-3.11085842,56.48327757 +195.37,50.43169867,-2.572147471,49.7384,5.509769167,8.337983428,-3.0628125,-7.843415266,-3.066841797,56.49080269 +195.38,50.43169917,-2.572146297,49.7691,5.509769179,8.339981727,-3.073125,-7.748001808,-3.020150836,56.49832774 +195.39,50.43169966,-2.572145123,49.7999,5.520197779,8.340203718,-3.08125,-7.652014418,-2.970826275,56.50585286 +195.4,50.43170016,-2.572143949,49.8307,5.527150202,8.339315517,-3.0884375,-7.555473149,-2.918911085,56.51337791 +195.41,50.43170066,-2.572142776,49.8617,5.520197849,8.339537508,-3.095,-7.458398285,-2.864450529,56.52090303 +195.42,50.43170115,-2.572141602,49.8926,5.50976929,8.341535807,-3.10125,-7.360809936,-2.807492165,56.52842808 +195.43,50.43170165,-2.572140428,49.9237,5.506293113,8.343534105,-3.1065625,-7.262728614,-2.748085666,56.53595319 +195.44,50.43170214,-2.572139253,49.9548,5.50629314,8.343978136,-3.109375,-7.164174717,-2.686282714,56.54347825 +195.45,50.43170264,-2.572138079,49.9859,5.506293176,8.343756051,-3.1096875,-7.065168928,-2.622137339,56.55100336 +195.46,50.43170313,-2.572136905,50.017,5.506293203,8.344200082,-3.1084375,-6.965731759,-2.555705403,56.55852842 +195.47,50.43170363,-2.57213573,50.0481,5.509769415,8.345088188,-3.1065625,-6.865884123,-2.487044891,56.56605353 +195.48,50.43170412,-2.572134556,50.0791,5.520198025,8.346198333,-3.1046875,-6.765646818,-2.41621562,56.57357859 +195.49,50.43170462,-2.572133381,50.1102,5.523674261,8.347530516,-3.1015625,-6.665040815,-2.343279353,56.5811037 +195.5,50.43170512,-2.572132206,50.1412,5.506293326,8.348196584,-3.0959375,-6.564087027,-2.268299689,56.58862876 +195.51,50.43170561,-2.572131031,50.1721,5.488912373,8.347752461,-3.0884375,-6.462806652,-2.191342061,56.59615387 +195.52,50.4317061,-2.572129856,50.203,5.492388587,8.347530376,-3.0796875,-6.361220777,-2.112473561,56.60367893 +195.53,50.4317066,-2.572128682,50.2337,5.502817201,8.348640521,-3.07,-6.2593506,-2.031762944,56.61120404 +195.54,50.43170709,-2.572127506,50.2644,5.506293421,8.349972705,-3.06,-6.157217435,-1.949280628,56.61872909 +195.55,50.43170759,-2.572126331,50.2949,5.506293437,8.350860811,-3.049375,-6.054842597,-1.86509846,56.62625421 +195.56,50.43170808,-2.572125156,50.3254,5.506293457,8.352192993,-3.0365625,-5.952247456,-1.779289894,56.63377926 +195.57,50.43170858,-2.57212398,50.3557,5.50629349,8.353303136,-3.02125,-5.849453499,-1.691929816,56.64130432 +195.58,50.43170907,-2.572122804,50.3858,5.502817332,8.353303088,-3.005,-5.746482097,-1.603094314,56.64882943 +195.59,50.43170957,-2.572121629,50.4158,5.492388771,8.353525079,-2.988125,-5.643354851,-1.51286091,56.65635449 +195.6,50.43171006,-2.572120453,50.4456,5.485436397,8.354635224,-2.969375,-5.540093188,-1.42130827,56.6638796 +195.61,50.43171055,-2.572119277,50.4752,5.492388816,8.355523329,-2.9484375,-5.436718768,-1.328516208,56.67140466 +195.62,50.43171105,-2.572118101,50.5046,5.502817445,8.355745318,-2.9265625,-5.333253132,-1.234565626,56.67892977 +195.63,50.43171154,-2.572116925,50.5337,5.502817475,8.355967307,-2.9046875,-5.22971794,-1.13953857,56.68645483 +195.64,50.43171204,-2.572115749,50.5627,5.4923889,8.357077449,-2.8815625,-5.126134733,-1.043517719,56.69397994 +195.65,50.43171253,-2.572114573,50.5914,5.485436527,8.359075745,-2.85625,-5.022525171,-0.946587011,56.701505 +195.66,50.43171302,-2.572113396,50.6198,5.488912754,8.360407925,-2.8303125,-4.918910968,-0.848830786,56.70903011 +195.67,50.43171352,-2.572112219,50.648,5.488912779,8.360407875,-2.8046875,-4.815313609,-0.750334413,56.71655516 +195.68,50.43171401,-2.572111043,50.6759,5.485436598,8.360407825,-2.7778125,-4.711754868,-0.651183723,56.72408028 +195.69,50.4317145,-2.572109866,50.7036,5.488912819,8.360629813,-2.748125,-4.608256345,-0.551465174,56.73160533 +195.7,50.431715,-2.572108689,50.7309,5.485436655,8.360629761,-2.71625,-4.50483964,-0.451265742,56.73913045 +195.71,50.43171549,-2.572107513,50.7579,5.471531895,8.361739901,-2.6834375,-4.401526297,-0.350672802,56.7466555 +195.72,50.43171598,-2.572106336,50.7846,5.471531912,8.363960233,-2.6496875,-4.298337973,-0.249774075,56.75418061 +195.73,50.43171647,-2.572105158,50.8109,5.485436726,8.364848333,-2.615,-4.195296155,-0.148657567,56.76170567 +195.74,50.43171697,-2.572103981,50.8369,5.485436762,8.364182165,-2.5796875,-4.092422385,-0.047411398,56.76923078 +195.75,50.43171746,-2.572102804,50.8625,5.471531998,8.36440415,-2.543125,-3.989738149,0.053876081,56.77675584 +195.76,50.43171795,-2.572101627,50.8878,5.471532011,8.366180403,-2.505,-3.887264934,0.155116635,56.78428095 +195.77,50.43171844,-2.572100449,50.9126,5.485436817,8.367512579,-2.4665625,-3.785024053,0.256221856,56.79180601 +195.78,50.43171894,-2.572099271,50.9371,5.485436837,8.367512524,-2.428125,-3.683036936,0.357103738,56.79933112 +195.79,50.43171943,-2.572098094,50.9612,5.471532065,8.367734507,-2.3878125,-3.581324838,0.45767416,56.80685618 +195.8,50.43171992,-2.572096916,50.9849,5.471532086,8.368844642,-2.345,-3.479909016,0.55784546,56.81438129 +195.81,50.43172041,-2.572095738,51.0081,5.485436901,8.369732739,-2.3015625,-3.37881067,0.657530376,56.82190635 +195.82,50.43172091,-2.57209456,51.0309,5.485436928,8.370176758,-2.2584375,-3.278050828,0.756641876,56.82943146 +195.83,50.4317214,-2.572093382,51.0533,5.468055963,8.371064854,-2.2146875,-3.177650632,0.855093558,56.83695652 +195.84,50.43172189,-2.572092204,51.0752,5.454151193,8.372174987,-2.1696875,-3.077630994,0.952799592,56.84448163 +195.85,50.43172238,-2.572091025,51.0967,5.450675018,8.372396967,-2.123125,-2.978012827,1.049674838,56.85200668 +195.86,50.43172287,-2.572089847,51.1177,5.454151232,8.372396909,-2.0746875,-2.878816931,1.145634669,56.8595318 +195.87,50.43172336,-2.572088669,51.1382,5.468056033,8.373729079,-2.025,-2.780064045,1.240595548,56.86705685 +195.88,50.43172385,-2.57208749,51.1582,5.485437034,8.375727362,-1.975,-2.681774739,1.334474568,56.87458197 +195.89,50.43172435,-2.572086311,51.1777,5.485437049,8.376837492,-1.925,-2.583969526,1.427189911,56.88210702 +195.9,50.43172484,-2.572085132,51.1967,5.468056078,8.377059468,-1.8746875,-2.486668917,1.518660732,56.88963213 +195.91,50.43172533,-2.572083953,51.2152,5.454151316,8.377059406,-1.823125,-2.389893194,1.608807276,56.89715719 +195.92,50.43172582,-2.572082774,51.2332,5.450675149,8.377059343,-1.77,-2.293662526,1.697550876,56.90468225 +195.93,50.43172631,-2.572081595,51.2506,5.450675162,8.377281318,-1.7165625,-2.197997023,1.784814239,56.91220736 +195.94,50.4317268,-2.572080416,51.2675,5.450675168,8.378169407,-1.663125,-2.10291674,1.870521162,56.91973242 +195.95,50.43172729,-2.572079237,51.2839,5.450675182,8.379501571,-1.608125,-2.008441442,1.954596989,56.92725753 +195.96,50.43172778,-2.572078057,51.2997,5.450675194,8.380611696,-1.5515625,-1.914590898,2.036968381,56.93478258 +195.97,50.43172827,-2.572076878,51.3149,5.450675199,8.381499783,-1.495,-1.821384702,2.117563489,56.9423077 +195.98,50.43172876,-2.572075698,51.3296,5.450675212,8.38216583,-1.4384375,-1.728842335,2.196312069,56.94983275 +195.99,50.43172925,-2.572074518,51.3437,5.450675235,8.382609838,-1.3815625,-1.636983049,2.273145423,56.95735787 +196,50.43172974,-2.572073339,51.3572,5.450675256,8.383275885,-1.3246875,-1.545826151,2.347996572,56.96488292 +196.01,50.43173023,-2.572072158,51.3702,5.45067527,8.384163969,-1.2665625,-1.455390607,2.420800199,56.97240803 +196.02,50.43173072,-2.572070979,51.3826,5.450675279,8.385052051,-1.20625,-1.365695268,2.491492935,56.97993309 +196.03,50.43173121,-2.572069798,51.3943,5.450675283,8.385718094,-1.1453125,-1.276758925,2.560012957,56.9874582 +196.04,50.4317317,-2.572068618,51.4055,5.450675288,8.386384137,-1.085,-1.188600144,2.626300679,56.99498326 +196.05,50.43173219,-2.572067438,51.416,5.4506753,8.387716294,-1.025,-1.101237315,2.690298174,57.00250837 +196.06,50.43173268,-2.572066257,51.426,5.450675307,8.388826412,-0.965,-1.014688717,2.751949693,57.01003343 +196.07,50.43173317,-2.572065076,51.4353,5.450675306,8.388826337,-0.904375,-0.928972398,2.811201494,57.01755854 +196.08,50.43173366,-2.572063896,51.4441,5.450675317,8.388826262,-0.841875,-0.844106233,2.868001894,57.0250836 +196.09,50.43173415,-2.572062715,51.4522,5.450675339,8.389270262,-0.778125,-0.760107984,2.922301333,57.03260871 +196.1,50.43173464,-2.572061534,51.4596,5.450675353,8.3899363,-0.7153125,-0.676995185,2.974052486,57.04013377 +196.11,50.43173513,-2.572060354,51.4665,5.447199156,8.391268452,-0.6534375,-0.594785195,3.023210259,57.04765888 +196.12,50.43173562,-2.572059172,51.4727,5.433294372,8.392600604,-0.59125,-0.513495147,3.069731682,57.05518394 +196.13,50.43173611,-2.572057991,51.4783,5.415913395,8.393266639,-0.528125,-0.433142113,3.113576303,57.06270905 +196.14,50.43173659,-2.57205681,51.4833,5.415913404,8.393710635,-0.4634375,-0.353742768,3.154705792,57.0702341 +196.15,50.43173708,-2.572055628,51.4876,5.433294397,8.393710554,-0.3984375,-0.275313726,3.193084396,57.07775922 +196.16,50.43173757,-2.572054447,51.4912,5.44719918,8.393710473,-0.335,-0.197871376,3.228678539,57.08528427 +196.17,50.43173806,-2.572053266,51.4943,5.447199167,8.394820582,-0.2715625,-0.121431873,3.261457226,57.09280939 +196.18,50.43173855,-2.572052084,51.4967,5.433294382,8.395930691,-0.2065625,-0.046011261,3.291391864,57.10033444 +196.19,50.43173904,-2.572050902,51.4984,5.415913411,8.395930606,-0.141875,0.028374818,3.318456385,57.10785955 +196.2,50.43173952,-2.572049721,51.4995,5.415913417,8.396374597,-0.0784375,0.10171078,3.342627182,57.11538461 +196.21,50.43174001,-2.572048539,51.5,5.433294404,8.398372855,-0.0146875,0.173981327,3.363883114,57.12290972 +196.22,50.4317405,-2.572047357,51.4998,5.443723,8.400593151,0.05,0.245171333,3.382205732,57.13043478 +196.23,50.43174099,-2.572046174,51.499,5.433294406,8.401703254,0.115,0.315266016,3.397578992,57.13795989 +196.24,50.43174148,-2.572044992,51.4975,5.415913414,8.401703166,0.18,0.384250593,3.409989487,57.14548495 +196.25,50.43174196,-2.572043809,51.4954,5.415913413,8.401036963,0.2446875,0.452110797,3.419426445,57.15301006 +196.26,50.43174245,-2.572042627,51.4926,5.429818197,8.400814835,0.3084375,0.518832363,3.425881617,57.16053512 +196.27,50.43174294,-2.572041445,51.4892,5.429818192,8.401924935,0.3715625,0.584401367,3.429349387,57.16806017 +196.28,50.43174343,-2.572040262,51.4852,5.415913406,8.403257072,0.4353125,0.648804172,3.429826661,57.17558529 +196.29,50.43174391,-2.572039079,51.4805,5.412437208,8.404145132,0.5,0.712027314,3.427313095,57.18311034 +196.3,50.4317444,-2.572037897,51.4752,5.415913405,8.405477268,0.5646875,0.774057559,3.421810924,57.19063546 +196.31,50.43174489,-2.572036713,51.4692,5.41243721,8.406587365,0.628125,0.834881956,3.413324789,57.19816051 +196.32,50.43174537,-2.57203553,51.4626,5.412437201,8.406365232,0.69,0.894487787,3.401862252,57.20568562 +196.33,50.43174586,-2.572034347,51.4554,5.415913383,8.405921061,0.751875,0.952862675,3.387433227,57.21321068 +196.34,50.43174635,-2.572033164,51.4476,5.41243718,8.406587079,0.815,1.00999436,3.37005026,57.22073579 +196.35,50.43174683,-2.572031981,51.4391,5.412437173,8.40791921,0.878125,1.065870923,3.349728593,57.22826085 +196.36,50.43174732,-2.572030797,51.43,5.415913363,8.409029303,0.9396875,1.120480733,3.32648593,57.23578596 +196.37,50.43174781,-2.572029614,51.4203,5.412437167,8.409917356,1,1.17381239,3.300342496,57.24331102 +196.38,50.43174829,-2.57202843,51.41,5.412437163,8.410583371,1.06,1.225854662,3.271321152,57.25083613 +196.39,50.43174878,-2.572027246,51.3991,5.415913344,8.411027347,1.12,1.276596778,3.239447109,57.25836119 +196.4,50.43174927,-2.572026063,51.3876,5.408960938,8.41169336,1.18,1.326028082,3.204748269,57.2658863 +196.41,50.43174975,-2.572024878,51.3755,5.398532339,8.41258141,1.2396875,1.374138316,3.167254828,57.27341136 +196.42,50.43175024,-2.572023695,51.3628,5.398532333,8.41346946,1.2984375,1.420917341,3.126999501,57.28093647 +196.43,50.43175072,-2.57202251,51.3495,5.408960918,8.414135471,1.3565625,1.466355473,3.084017353,57.28846152 +196.44,50.43175121,-2.572021326,51.3357,5.415913295,8.414579443,1.415,1.5104432,3.038345913,57.29598664 +196.45,50.4317517,-2.572020142,51.3212,5.408960882,8.415245453,1.473125,1.553171298,2.990025002,57.30351169 +196.46,50.43175218,-2.572018957,51.3062,5.39853228,8.4161335,1.5296875,1.59453083,2.939096732,57.31103681 +196.47,50.43175267,-2.572017773,51.2906,5.395056071,8.417243584,1.585,1.6345132,2.885605564,57.31856186 +196.48,50.43175315,-2.572016588,51.2745,5.395056058,8.418353666,1.6396875,1.673109986,2.829598022,57.32608698 +196.49,50.43175364,-2.572015403,51.2578,5.395056056,8.418575596,1.6934375,1.710313224,2.771123096,57.33361203 +196.5,50.43175412,-2.572014218,51.2406,5.395056053,8.418575488,1.7465625,1.746115122,2.71023172,57.34113714 +196.51,50.43175461,-2.572013034,51.2229,5.395056034,8.419685569,1.8,1.780508117,2.64697695,57.3486622 +196.52,50.43175509,-2.572011848,51.2046,5.395056005,8.421017688,1.853125,1.813485161,2.581413962,57.35618731 +196.53,50.43175558,-2.572010663,51.1858,5.395055985,8.421683691,1.9046875,1.845039265,2.513599938,57.36371237 +196.54,50.43175606,-2.572009478,51.1665,5.395055978,8.422349694,1.955,1.875163839,2.443594064,57.37123748 +196.55,50.43175655,-2.572008292,51.1467,5.395055966,8.423015696,2.0046875,1.903852638,2.371457303,57.37876254 +196.56,50.43175703,-2.572007107,51.1264,5.391579747,8.423237622,2.053125,1.931099703,2.297252622,57.38628765 +196.57,50.43175752,-2.572005921,51.1056,5.381151137,8.42323751,2.1,1.956899248,2.221044651,57.39381271 +196.58,50.431758,-2.572004736,51.0844,5.374198727,8.423237395,2.1465625,1.981245943,2.142899969,57.40133782 +196.59,50.43175848,-2.57200355,51.0627,5.381151106,8.423681356,2.1934375,2.00413469,2.062886585,57.40886288 +196.6,50.43175897,-2.572002365,51.0405,5.391579685,8.425457546,2.2396875,2.025560734,1.9810744,57.41638799 +196.61,50.43175945,-2.572001179,51.0179,5.391579669,8.427899849,2.2846875,2.045519546,1.897534632,57.42391304 +196.62,50.43175994,-2.571999992,50.9948,5.381151054,8.428787886,2.328125,2.064007004,1.812340162,57.4314381 +196.63,50.43176042,-2.571998806,50.9713,5.374198636,8.428121654,2.3696875,2.081019267,1.725565361,57.43896321 +196.64,50.4317609,-2.57199762,50.9474,5.381151011,8.428121537,2.41,2.096552725,1.637285857,57.44648827 +196.65,50.43176139,-2.571996434,50.9231,5.391579586,8.42923161,2.45,2.110604172,1.547578543,57.45401338 +196.66,50.43176187,-2.571995247,50.8984,5.391579561,8.430341681,2.4896875,2.123170626,1.456521798,57.46153844 +196.67,50.43176236,-2.571994061,50.8733,5.381150943,8.431451752,2.528125,2.13424951,1.364194863,57.46906355 +196.68,50.43176284,-2.571992874,50.8478,5.37419853,8.432561823,2.565,2.143838531,1.270678411,57.47658861 +196.69,50.43176332,-2.571991687,50.822,5.377674704,8.432561703,2.60125,2.151935628,1.176053858,57.48411372 +196.7,50.43176381,-2.5719905,50.7958,5.374198487,8.431895469,2.6365625,2.158539139,1.080403768,57.49163878 +196.71,50.43176429,-2.571989314,50.7692,5.360293692,8.4327835,2.6696875,2.16364763,0.983811563,57.49916389 +196.72,50.43176477,-2.571988127,50.7424,5.360293681,8.435225798,2.7015625,2.167260129,0.886361469,57.50668894 +196.73,50.43176525,-2.571986939,50.7152,5.374198438,8.437001981,2.7334375,2.169375833,0.788138398,57.51421406 +196.74,50.43176574,-2.571985752,50.6877,5.374198402,8.437223897,2.764375,2.169994341,0.68922812,57.52173911 +196.75,50.43176622,-2.571984564,50.6599,5.360293591,8.43655766,2.793125,2.169115481,0.589716811,57.52926423 +196.76,50.4317667,-2.571983377,50.6318,5.360293579,8.436113461,2.82,2.166739368,0.489691271,57.53678928 +196.77,50.43176718,-2.57198219,50.6035,5.37419835,8.436779452,2.84625,2.162866631,0.389238706,57.5443144 +196.78,50.43176767,-2.571981002,50.5749,5.374198322,8.438333595,2.8715625,2.157498017,0.288446721,57.55183945 +196.79,50.43176815,-2.571979815,50.546,5.360293501,8.4396657,2.895,2.15063467,0.18740315,57.55936456 +196.8,50.43176863,-2.571978626,50.517,5.360293473,8.439887613,2.918125,2.142277966,0.086196229,57.56688962 +196.81,50.43176911,-2.571977439,50.4877,5.374198241,8.439887488,2.9415625,2.132429738,-0.015085864,57.57441473 +196.82,50.4317696,-2.571976251,50.4581,5.374198221,8.441219591,2.9625,2.121091935,-0.116354837,57.58193979 +196.83,50.43177008,-2.571975063,50.4284,5.356817213,8.442995771,2.98,2.108267019,-0.217522338,57.5894649 +196.84,50.43177056,-2.571973874,50.3985,5.342912409,8.443439723,2.9965625,2.093957628,-0.318500134,57.59698996 +196.85,50.43177104,-2.571972686,50.3685,5.342912393,8.443439597,3.013125,2.078166739,-0.419200216,57.60451507 +196.86,50.43177152,-2.571971498,50.3382,5.356817147,8.4447717,3.0284375,2.060897676,-0.519534695,57.61204013 +196.87,50.431772,-2.571970309,50.3079,5.374198088,8.446547878,3.0428125,2.04215405,-0.619416193,57.61956524 +196.88,50.43177249,-2.57196912,50.2774,5.374198058,8.44676979,3.0565625,2.021939755,-0.718757506,57.6270903 +196.89,50.43177297,-2.571967931,50.2467,5.356817065,8.445881512,3.0678125,2.000258975,-0.817472118,57.63461541 +196.9,50.43177345,-2.571966743,50.216,5.342912268,8.445881385,3.0765625,1.97711635,-0.915473799,57.64214046 +196.91,50.43177393,-2.571965554,50.1852,5.339436042,8.447213487,3.085,1.952516579,-1.012677234,57.64966558 +196.92,50.43177441,-2.571964365,50.1543,5.339436004,8.448989665,3.093125,1.926464875,-1.10899757,57.65719063 +196.93,50.43177489,-2.571963176,50.1233,5.339435974,8.450321767,3.099375,1.898966683,-1.204350868,57.66471575 +196.94,50.43177537,-2.571961986,50.0923,5.339435959,8.450543678,3.103125,1.87002773,-1.298653934,57.6722408 +196.95,50.43177585,-2.571960797,50.0612,5.339435945,8.450321514,3.105,1.839654092,-1.39182455,57.67976586 +196.96,50.43177633,-2.571959608,50.0302,5.339435915,8.450765463,3.1065625,1.807852069,-1.483781525,57.68729097 +196.97,50.43177681,-2.571958418,49.9991,5.339435876,8.451653488,3.1084375,1.774628252,-1.574444534,57.69481603 +196.98,50.43177729,-2.571957229,49.968,5.339435846,8.452763552,3.109375,1.739989688,-1.663734677,57.70234114 +196.99,50.43177777,-2.571956039,49.9369,5.339435831,8.454095653,3.108125,1.703943595,-1.751573978,57.7098662 +197,50.43177825,-2.571954849,49.9058,5.339435817,8.454983678,3.1046875,1.666497423,-1.837885887,57.71739131 +197.01,50.43177873,-2.571953659,49.8748,5.339435791,8.455205589,3.0996875,1.62765902,-1.922595176,57.72491636 +197.02,50.43177921,-2.571952469,49.8438,5.339435766,8.455427501,3.093125,1.587436523,-2.005627876,57.73244148 +197.03,50.43177969,-2.571951279,49.8129,5.33943574,8.456315527,3.0846875,1.545838355,-2.086911679,57.73996653 +197.04,50.43178017,-2.571950089,49.7821,5.339435704,8.45742559,3.075,1.502873167,-2.166375654,57.74749165 +197.05,50.43178065,-2.571948898,49.7514,5.339435667,8.457647501,3.065,1.458549954,-2.243950473,57.7550167 +197.06,50.43178113,-2.571947708,49.7208,5.339435647,8.457647376,3.0546875,1.412877941,-2.319568583,57.76254182 +197.07,50.43178161,-2.571946518,49.6903,5.339435635,8.458979478,3.043125,1.365866639,-2.393163981,57.77006687 +197.08,50.43178209,-2.571945327,49.6599,5.339435614,8.460755655,3.029375,1.317525961,-2.464672494,57.77759198 +197.09,50.43178257,-2.571944136,49.6297,5.339435578,8.460977568,3.013125,1.267865933,-2.534031785,57.78511704 +197.1,50.43178305,-2.571942945,49.5996,5.339435543,8.460311329,2.995,1.216896925,-2.60118135,57.79264215 +197.11,50.43178353,-2.571941755,49.5698,5.339435522,8.461199355,2.9765625,1.164629595,-2.66606269,57.80016721 +197.12,50.43178401,-2.571940564,49.5401,5.335959316,8.463419609,2.9584375,1.111074886,-2.728619139,57.80769232 +197.13,50.43178449,-2.571939372,49.5106,5.322054517,8.464307637,2.939375,1.056243971,-2.788796208,57.81521738 +197.14,50.43178497,-2.571938181,49.4813,5.304673512,8.4636414,2.918125,1.000148252,-2.846541416,57.82274249 +197.15,50.43178544,-2.57193699,49.4522,5.304673479,8.463863314,2.8946875,0.942799474,-2.901804398,57.83026755 +197.16,50.43178592,-2.571935799,49.4234,5.322054425,8.465639494,2.87,0.884209669,-2.954536913,57.83779266 +197.17,50.4317864,-2.571934607,49.3948,5.335959185,8.466971597,2.845,0.824390984,-3.004693065,57.84531772 +197.18,50.43178688,-2.571933415,49.3665,5.339435366,8.466971474,2.819375,0.76335591,-3.052229082,57.85284283 +197.19,50.43178736,-2.571932224,49.3384,5.335959152,8.46719339,2.7915625,0.701117281,-3.097103537,57.86036788 +197.2,50.43178784,-2.571931032,49.3106,5.322054351,8.468303458,2.7615625,0.637688046,-3.139277242,57.867893 +197.21,50.43178832,-2.57192984,49.2832,5.304673355,8.469191488,2.7315625,0.573081439,-3.178713411,57.87541805 +197.22,50.43178879,-2.571928648,49.256,5.304673326,8.469635442,2.70125,0.507310984,-3.215377782,57.88294317 +197.23,50.43178927,-2.571927456,49.2291,5.318578071,8.470523473,2.668125,0.440390373,-3.249238213,57.89046822 +197.24,50.43178975,-2.571926264,49.2026,5.318578045,8.471633542,2.633125,0.372333644,-3.28026531,57.89799334 +197.25,50.43179023,-2.571925071,49.1765,5.304673254,8.47185546,2.5984375,0.303154949,-3.308431973,57.90551839 +197.26,50.4317907,-2.571923879,49.1506,5.304673244,8.471855341,2.563125,0.232868784,-3.333713563,57.9130435 +197.27,50.43179118,-2.571922687,49.1252,5.318578004,8.472965411,2.52625,0.161489759,-3.356088196,57.92056856 +197.28,50.43179166,-2.571921494,49.1001,5.318577984,8.474075481,2.488125,0.089032829,-3.375536217,57.92809367 +197.29,50.43179214,-2.571920301,49.0754,5.304673185,8.474075364,2.448125,0.015513119,-3.392040724,57.93561873 +197.3,50.43179261,-2.571919109,49.0511,5.301196966,8.474297284,2.4065625,-0.059054015,-3.405587337,57.94314378 +197.31,50.43179309,-2.571917916,49.0273,5.304673133,8.475629394,2.365,-0.134652989,-3.416164195,57.9506689 +197.32,50.43179357,-2.571916723,49.0038,5.301196912,8.477183543,2.3234375,-0.211267988,-3.423762132,57.95819395 +197.33,50.43179404,-2.57191553,48.9808,5.301196895,8.477849542,2.28125,-0.288883143,-3.428374499,57.96571907 +197.34,50.43179452,-2.571914336,48.9582,5.304673081,8.477627389,2.238125,-0.367482066,-3.429997287,57.97324412 +197.35,50.431795,-2.571913144,48.936,5.301196872,8.477849312,2.193125,-0.447048486,-3.428629064,57.98076924 +197.36,50.43179547,-2.57191195,48.9143,5.301196857,8.478959387,2.14625,-0.527565729,-3.424270975,57.98829429 +197.37,50.43179595,-2.571910757,48.8931,5.304673037,8.479847425,2.0984375,-0.609016951,-3.416926917,57.9958194 +197.38,50.43179643,-2.571909563,48.8723,5.301196823,8.480291389,2.05,-0.691385192,-3.406603249,58.00334446 +197.39,50.4317969,-2.57190837,48.8521,5.301196806,8.481179428,2.00125,-0.774653263,-3.393308966,58.01086957 +197.4,50.43179738,-2.571907176,48.8323,5.304672985,8.482511544,1.951875,-0.858803689,-3.377055643,58.01839463 +197.41,50.43179786,-2.571905982,48.813,5.297720569,8.483399584,1.90125,-0.943818995,-3.357857547,58.02591974 +197.42,50.43179833,-2.571904788,48.7943,5.287291958,8.483843549,1.85,-1.029681361,-3.335731292,58.0334448 +197.43,50.43179881,-2.571903594,48.776,5.283815753,8.484731592,1.798125,-1.116372912,-3.310696245,58.04096991 +197.44,50.43179928,-2.5719024,48.7583,5.283815752,8.485841673,1.7446875,-1.203875485,-3.282774178,58.04849497 +197.45,50.43179976,-2.571901205,48.7411,5.287291939,8.486063603,1.69,-1.292170802,-3.251989556,58.05602008 +197.46,50.43180023,-2.571900011,48.7245,5.297720508,8.486063496,1.635,-1.381240472,-3.218369081,58.06354514 +197.47,50.43180071,-2.571898817,48.7084,5.304672885,8.487173578,1.58,-1.471065873,-3.1819422,58.07107025 +197.48,50.43180119,-2.571897622,48.6929,5.297720485,8.488283662,1.5246875,-1.56162827,-3.142740542,58.0785953 +197.49,50.43180166,-2.571896427,48.6779,5.287291884,8.488283557,1.4684375,-1.652908697,-3.100798427,58.08612042 +197.5,50.43180214,-2.571895233,48.6635,5.283815671,8.48850549,1.4115625,-1.744888133,-3.056152353,58.09364547 +197.51,50.43180261,-2.571894038,48.6497,5.28381566,8.489615576,1.3546875,-1.837547326,-3.00884128,58.10117059 +197.52,50.43180309,-2.571892843,48.6364,5.283815656,8.490725662,1.2965625,-1.930866967,-2.958906461,58.10869564 +197.53,50.43180356,-2.571891648,48.6237,5.280339456,8.491835749,1.2365625,-2.024827577,-2.906391441,58.11622076 +197.54,50.43180404,-2.571890453,48.6117,5.269910859,8.492945837,1.1765625,-2.119409559,-2.851341943,58.12374581 +197.55,50.43180451,-2.571889257,48.6002,5.262958461,8.493167776,1.116875,-2.214593032,-2.793806094,58.13127092 +197.56,50.43180498,-2.571888062,48.5893,5.269910844,8.492945639,1.05625,-2.310358229,-2.733833971,58.13879598 +197.57,50.43180546,-2.571886867,48.5791,5.280339418,8.493389616,0.9953125,-2.406685154,-2.671477943,58.14632109 +197.58,50.43180593,-2.571885671,48.5694,5.283815606,8.494055631,0.935,-2.503553639,-2.606792326,58.15384615 +197.59,50.43180641,-2.571884476,48.5604,5.283815598,8.49449961,0.874375,-2.600943458,-2.539833498,58.16137126 +197.6,50.43180688,-2.57188328,48.5519,5.280339388,8.495387665,0.811875,-2.698834329,-2.47065996,58.16889632 +197.61,50.43180736,-2.571882085,48.5441,5.269910793,8.496719797,0.748125,-2.797205739,-2.399331928,58.17642143 +197.62,50.43180783,-2.571880888,48.537,5.262958405,8.497829891,0.6853125,-2.896037177,-2.325911684,58.18394649 +197.63,50.4318083,-2.571879693,48.5304,5.269910792,8.498717948,0.623125,-2.995308017,-2.250463169,58.1914716 +197.64,50.43180878,-2.571878496,48.5245,5.280339367,8.499161931,0.5596875,-3.094997459,-2.173052274,58.19899666 +197.65,50.43180925,-2.5718773,48.5192,5.280339363,8.498939802,0.4953125,-3.195084821,-2.093746378,58.20652171 +197.66,50.43180973,-2.571876104,48.5146,5.269910782,8.499161749,0.4315625,-3.295549074,-2.012614752,58.21404682 +197.67,50.4318102,-2.571874908,48.5106,5.262958394,8.500271848,0.3684375,-3.396369249,-1.929728099,58.22157188 +197.68,50.43181067,-2.571873711,48.5072,5.266434584,8.501381947,0.3046875,-3.497524374,-1.845158669,58.22909699 +197.69,50.43181115,-2.571872515,48.5045,5.262958388,8.502492047,0.24,-3.598993194,-1.758980202,58.23662205 +197.7,50.43181162,-2.571871318,48.5024,5.249053609,8.503824187,0.1753125,-3.700754681,-1.671267926,58.24414716 +197.71,50.43181209,-2.571870121,48.501,5.249053606,8.504712251,0.1115625,-3.802787464,-1.582098276,58.25167222 +197.72,50.43181256,-2.571868924,48.5002,5.262958385,8.504934203,0.048125,-3.905070285,-1.491549,58.25919733 +197.73,50.43181304,-2.571867727,48.5,5.266434583,8.504934118,-0.016875,-4.007581717,-1.399699052,58.26672239 +197.74,50.43181351,-2.57186653,48.5005,5.262958386,8.505156072,-0.083125,-4.110300444,-1.30662859,58.2742475 +197.75,50.43181398,-2.571865333,48.5017,5.266434583,8.506044139,-0.148125,-4.213204982,-1.212418687,58.28177256 +197.76,50.43181446,-2.571864136,48.5035,5.262958392,8.507376283,-0.2115625,-4.316273844,-1.117151562,58.28929767 +197.77,50.43181493,-2.571862938,48.5059,5.245577416,8.508264353,-0.275,-4.41948543,-1.020910294,58.29682272 +197.78,50.4318154,-2.571861741,48.509,5.235148828,8.508486311,-0.3384375,-4.522818311,-0.923778707,58.30434784 +197.79,50.43181587,-2.571860543,48.5127,5.245577416,8.508708269,-0.4015625,-4.62625083,-0.825841656,58.31187289 +197.8,50.43181634,-2.571859346,48.517,5.2629584,8.509596341,-0.4653125,-4.729761385,-0.727184397,58.31939801 +197.81,50.43181682,-2.571858148,48.522,5.262958409,8.510928489,-0.53,-4.833328377,-0.627893046,58.32692306 +197.82,50.43181729,-2.57185695,48.5276,5.245577438,8.511816563,-0.5946875,-4.936930204,-0.528054119,58.33444818 +197.83,50.43181776,-2.571855752,48.5339,5.235148859,8.512038524,-0.658125,-5.040545152,-0.427754763,58.34197323 +197.84,50.43181823,-2.571854554,48.5408,5.245577452,8.512260487,-0.72,-5.144151678,-0.327082411,58.34949834 +197.85,50.4318187,-2.571853356,48.5483,5.262958431,8.513148563,-0.781875,-5.247728123,-0.226124784,58.3570234 +197.86,50.43181918,-2.571852158,48.5564,5.262958438,8.514258678,-0.845,-5.351252773,-0.124970002,58.36454851 +197.87,50.43181965,-2.571850959,48.5652,5.245577473,8.514480643,-0.908125,-5.454704085,-0.023706243,58.37207357 +197.88,50.43182012,-2.571849761,48.5746,5.2316727,8.514480571,-0.9696875,-5.558060457,0.077578142,58.37959868 +197.89,50.43182059,-2.571848563,48.5846,5.228196514,8.515812726,-1.03,-5.66130029,0.178794918,58.38712374 +197.9,50.43182106,-2.571847364,48.5952,5.228196525,8.517588957,-1.09,-5.764401982,0.279855792,58.39464885 +197.91,50.43182153,-2.571846165,48.6064,5.228196535,8.518032963,-1.15,-5.867344049,0.380672643,58.40217391 +197.92,50.431822,-2.571844966,48.6182,5.231672746,8.518032895,-1.2096875,-5.970105003,0.481157523,58.40969902 +197.93,50.43182247,-2.571843768,48.6306,5.245577541,8.519143016,-1.2684375,-6.07266336,0.581222769,58.41722408 +197.94,50.43182294,-2.571842568,48.6436,5.262958513,8.520253137,-1.3265625,-6.17499769,0.680781233,58.42474919 +197.95,50.43182342,-2.571841369,48.6571,5.262958514,8.520031032,-1.385,-6.277086623,0.779746056,58.43227424 +197.96,50.43182389,-2.57184017,48.6713,5.245577556,8.519586891,-1.443125,-6.378908901,0.878030949,58.43979936 +197.97,50.43182436,-2.571838971,48.686,5.231672795,8.52025294,-1.4996875,-6.480443153,0.975550142,58.44732441 +197.98,50.43182483,-2.571837772,48.7013,5.228196622,8.521585101,-1.555,-6.581668294,1.072218665,58.45484953 +197.99,50.4318253,-2.571836572,48.7171,5.228196642,8.522695226,-1.61,-6.682563067,1.167952177,58.46237458 +198,50.43182577,-2.571835373,48.7335,5.228196649,8.523805352,-1.665,-6.783106504,1.2626672,58.46989964 +198.01,50.43182624,-2.571834173,48.7504,5.228196657,8.525137517,-1.7196875,-6.883277517,1.356281227,58.47742475 +198.02,50.43182671,-2.571832973,48.7679,5.228196672,8.526025606,-1.7734375,-6.983055252,1.448712498,58.48494981 +198.03,50.43182718,-2.571831773,48.7859,5.228196685,8.526247584,-1.82625,-7.082418854,1.539880453,58.49247492 +198.04,50.43182765,-2.571830573,48.8044,5.2281967,8.526469561,-1.8784375,-7.18134758,1.629705683,58.49999998 +198.05,50.43182812,-2.571829373,48.8235,5.228196719,8.527357653,-1.9296875,-7.279820748,1.718109747,58.50752509 +198.06,50.43182859,-2.571828173,48.843,5.224720538,8.528467784,-1.9796875,-7.377817845,1.805015585,58.51505015 +198.07,50.43182906,-2.571826972,48.8631,5.210815775,8.528689764,-2.0284375,-7.475318302,1.890347392,58.52257526 +198.08,50.43182953,-2.571825772,48.8836,5.193434819,8.528689707,-2.07625,-7.572301836,1.974030858,58.53010031 +198.09,50.43182999,-2.571824572,48.9046,5.193434834,8.52979984,-2.1234375,-7.668748223,2.055992871,58.53762543 +198.1,50.43183046,-2.571823371,48.9261,5.21081583,8.530909973,-2.17,-7.764637237,2.1361621,58.54515048 +198.11,50.43183093,-2.57182217,48.948,5.224720637,8.530909917,-2.21625,-7.85994888,2.214468528,58.5526756 +198.12,50.4318314,-2.57182097,48.9704,5.228196853,8.531131901,-2.2615625,-7.954663273,2.290843917,58.56020065 +198.13,50.43183187,-2.571819769,48.9933,5.228196868,8.532242036,-2.3046875,-8.048760647,2.365221631,58.56772576 +198.14,50.43183234,-2.571818568,49.0165,5.224720688,8.533352171,-2.346875,-8.142221294,2.437536812,58.57525082 +198.15,50.43183281,-2.571817367,49.0402,5.210815923,8.534462306,-2.39,-8.235025731,2.507726491,58.58277593 +198.16,50.43183328,-2.571816166,49.0643,5.193434967,8.535572442,-2.4325,-8.327154595,2.575729362,58.59030099 +198.17,50.43183374,-2.571814964,49.0889,5.19343499,8.535794429,-2.4715625,-8.418588632,2.641486181,58.5978261 +198.18,50.43183421,-2.571813763,49.1138,5.210815984,8.535572341,-2.508125,-8.509308707,2.704939538,58.60535116 +198.19,50.43183468,-2.571812562,49.139,5.224720786,8.536016366,-2.5453125,-8.599295911,2.766034199,58.61287627 +198.2,50.43183515,-2.57181136,49.1647,5.22472081,8.536904466,-2.583125,-8.688531452,2.824716823,58.62040133 +198.21,50.43183562,-2.571810159,49.1907,5.21081605,8.538014605,-2.619375,-8.776996708,2.880936244,58.62792644 +198.22,50.43183609,-2.571808957,49.2171,5.193435103,8.539346782,-2.653125,-8.864673174,2.934643417,58.6354515 +198.23,50.43183655,-2.571807755,49.2438,5.193435132,8.540234884,-2.6846875,-8.951542571,2.985791589,58.64297661 +198.24,50.43183702,-2.571806553,49.2708,5.207339929,8.540456874,-2.7153125,-9.03758668,3.034336068,58.65050166 +198.25,50.43183749,-2.571805351,49.2981,5.207339945,8.540678864,-2.7465625,-9.122787681,3.080234571,58.65802678 +198.26,50.43183796,-2.571804149,49.3257,5.193435187,8.541566967,-2.7778125,-9.207127642,3.123447105,58.66555183 +198.27,50.43183842,-2.571802947,49.3537,5.193435208,8.542677109,-2.8065625,-9.290588971,3.163935913,58.67307695 +198.28,50.43183889,-2.571801744,49.3819,5.207340012,8.5428991,-2.8328125,-9.37315431,3.201665699,58.680602 +198.29,50.43183936,-2.571800542,49.4103,5.207340038,8.542677016,-2.8584375,-9.454806353,3.236603577,58.68812712 +198.3,50.43183983,-2.57179934,49.4391,5.193435281,8.543121046,-2.883125,-9.535528085,3.268719122,58.69565217 +198.31,50.43184029,-2.571798137,49.468,5.189959116,8.544009152,-2.90625,-9.615302603,3.297984316,58.70317728 +198.32,50.43184076,-2.571796935,49.4972,5.193435342,8.545119295,-2.9284375,-9.694113292,3.324373607,58.71070234 +198.33,50.43184123,-2.571795732,49.5266,5.189959164,8.546451476,-2.9496875,-9.771943649,3.347863959,58.7182274 +198.34,50.43184169,-2.571794529,49.5562,5.189959182,8.547339582,-2.97,-9.848777462,3.36843492,58.72575251 +198.35,50.43184216,-2.571793326,49.586,5.193435402,8.547783613,-2.9896875,-9.924598685,3.386068613,58.73327757 +198.36,50.43184263,-2.571792123,49.616,5.18995923,8.54867172,-3.0078125,-9.99939145,3.400749568,58.74080268 +198.37,50.43184309,-2.57179092,49.6462,5.189959257,8.549781864,-3.023125,-10.07314017,3.412465008,58.74832773 +198.38,50.43184356,-2.571789716,49.6765,5.193435486,8.550003859,-3.03625,-10.14582944,3.421204734,58.75585285 +198.39,50.43184403,-2.571788513,49.7069,5.186483123,8.550003816,-3.0484375,-10.21744406,3.426961127,58.7633779 +198.4,50.43184449,-2.57178731,49.7375,5.176054557,8.551113961,-3.06,-10.28796903,3.4297292,58.77090302 +198.41,50.43184496,-2.571786106,49.7681,5.172578382,8.552224106,-3.07125,-10.35738975,3.429506434,58.77842807 +198.42,50.43184542,-2.571784902,49.7989,5.172578403,8.552224063,-3.0815625,-10.42569159,3.426293115,58.78595318 +198.43,50.43184589,-2.571783699,49.8298,5.176054624,8.552446058,-3.0896875,-10.4928604,3.420091993,58.79347824 +198.44,50.43184635,-2.571782495,49.8607,5.186483241,8.553556204,-3.09625,-10.55888204,3.410908568,58.80100335 +198.45,50.43184682,-2.571781291,49.8917,5.193435662,8.554444312,-3.1015625,-10.62374281,3.39875069,58.80852841 +198.46,50.43184729,-2.571780087,49.9228,5.186483303,8.554666307,-3.1046875,-10.68742914,3.383629131,58.81605352 +198.47,50.43184775,-2.571778883,49.9538,5.176054747,8.554888302,-3.1065625,-10.74992772,3.365556953,58.82357858 +198.48,50.43184822,-2.571777679,49.9849,5.17257857,8.555998449,-3.1084375,-10.81122549,3.344549971,58.83110369 +198.49,50.43184868,-2.571776475,50.016,5.172578585,8.557996746,-3.109375,-10.87130968,3.320626463,58.83862875 +198.5,50.43184915,-2.57177527,50.0471,5.172578608,8.559328929,-3.108125,-10.93016769,3.293807339,58.84615386 +198.51,50.43184961,-2.571774065,50.0782,5.172578638,8.559106848,-3.105,-10.98778731,3.264115979,58.85367892 +198.52,50.43185008,-2.571772861,50.1092,5.172578668,8.558440693,-3.10125,-11.04415644,3.231578221,58.86120403 +198.53,50.43185054,-2.571771656,50.1402,5.172578698,8.558440651,-3.0965625,-11.09926329,3.196222543,58.86872909 +198.54,50.43185101,-2.571770452,50.1712,5.172578721,8.559328759,-3.0896875,-11.1530964,3.158079654,58.8762542 +198.55,50.43185147,-2.571769247,50.202,5.169102542,8.560660943,-3.08125,-11.20564454,3.1171829,58.88377925 +198.56,50.43185194,-2.571768042,50.2328,5.15867398,8.561549051,-3.071875,-11.2568967,3.073567921,58.89130437 +198.57,50.4318524,-2.571766837,50.2635,5.151721623,8.561993084,-3.0609375,-11.30684218,3.027272759,58.89882942 +198.58,50.43185286,-2.571765632,50.294,5.158674042,8.562881192,-3.0484375,-11.35547054,2.978337751,58.90635454 +198.59,50.43185333,-2.571764427,50.3245,5.16910265,8.564213374,-3.035,-11.4027717,2.926805584,58.91387959 +198.6,50.43185379,-2.571763221,50.3547,5.16910267,8.565101481,-3.02125,-11.44873563,2.872721175,58.9214047 +198.61,50.43185426,-2.571762016,50.3849,5.158674105,8.565323476,-3.0065625,-11.49335289,2.816131738,58.92892976 +198.62,50.43185472,-2.57176081,50.4149,5.151721747,8.56554547,-2.989375,-11.53661407,2.757086604,58.93645487 +198.63,50.43185518,-2.571759605,50.4447,5.158674177,8.566433577,-2.97,-11.57851017,2.695637224,58.94397993 +198.64,50.43185565,-2.571758399,50.4743,5.169102784,8.567765759,-2.9496875,-11.61903244,2.631837228,58.95150504 +198.65,50.43185611,-2.571757193,50.5037,5.169102793,8.568653865,-2.928125,-11.65817245,2.565742192,58.9590301 +198.66,50.43185658,-2.571755987,50.5329,5.158674227,8.568875857,-2.905,-11.69592195,2.497409813,58.96655521 +198.67,50.43185704,-2.571754781,50.5618,5.151721868,8.56909785,-2.8815625,-11.73227308,2.426899678,58.97408027 +198.68,50.4318575,-2.571753575,50.5905,5.15519809,8.569985956,-2.858125,-11.76721823,2.354273267,58.98160532 +198.69,50.43185797,-2.571752369,50.619,5.151721917,8.571318135,-2.8328125,-11.80075019,2.279593833,58.98913044 +198.7,50.43185843,-2.571751162,50.6472,5.137817165,8.57220624,-2.805,-11.83286189,2.20292658,58.99665549 +198.71,50.43185889,-2.571749956,50.6751,5.13781719,8.572428233,-2.7765625,-11.86354659,2.124338371,59.00418061 +198.72,50.43185935,-2.571748749,50.7027,5.151721984,8.572650224,-2.7478125,-11.89279798,2.043897675,59.01170566 +198.73,50.43185982,-2.571747543,50.7301,5.151721997,8.573538327,-2.7165625,-11.92060987,1.961674679,59.01923077 +198.74,50.43186028,-2.571746336,50.7571,5.137817238,8.574648467,-2.683125,-11.94697652,1.877741117,59.02675583 +198.75,50.43186074,-2.571745129,50.7837,5.137817264,8.574870457,-2.65,-11.97189234,1.7921701,59.03428094 +198.76,50.4318612,-2.571743922,50.8101,5.151722075,8.574870409,-2.6165625,-11.99535215,1.705036283,59.041806 +198.77,50.43186167,-2.571742716,50.8361,5.151722094,8.575980548,-2.58125,-12.0173511,1.61641564,59.04933111 +198.78,50.43186213,-2.571741508,50.8617,5.137817321,8.577090687,-2.545,-12.03788459,1.526385464,59.05685617 +198.79,50.43186259,-2.571740301,50.887,5.137817342,8.577090639,-2.508125,-12.05694827,1.43502425,59.06438128 +198.8,50.43186305,-2.571739094,50.9119,5.151722156,8.577312627,-2.4696875,-12.07453824,1.342411695,59.07190634 +198.81,50.43186352,-2.571737887,50.9364,5.151722179,8.578422763,-2.4296875,-12.09065073,1.248628531,59.07943145 +198.82,50.43186398,-2.571736679,50.9605,5.134341218,8.579532899,-2.3884375,-12.10528247,1.153756518,59.08695651 +198.83,50.43186444,-2.571735472,50.9842,5.120436461,8.580643035,-2.34625,-12.11843031,1.057878448,59.09448162 +198.84,50.4318649,-2.571734264,51.0074,5.120436483,8.581975209,-2.3034375,-12.1300916,0.961077859,59.10200667 +198.85,50.43186536,-2.571733056,51.0303,5.134341273,8.582641269,-2.2596875,-12.14026389,0.863439204,59.10953179 +198.86,50.43186582,-2.571731848,51.0526,5.151722264,8.582197141,-2.2146875,-12.14894495,0.765047626,59.11705684 +198.87,50.43186629,-2.57173064,51.0746,5.151722284,8.581975049,-2.1684375,-12.15613311,0.665988952,59.12458196 +198.88,50.43186675,-2.571729433,51.096,5.134341325,8.583085182,-2.1215625,-12.16182676,0.566349472,59.13210701 +198.89,50.43186721,-2.571728224,51.117,5.120436561,8.584195315,-2.075,-12.16602476,0.466216159,59.13963213 +198.9,50.43186767,-2.571727016,51.1375,5.116960382,8.584195259,-2.0278125,-12.16872626,0.365676275,59.14715718 +198.91,50.43186813,-2.571725808,51.1576,5.116960396,8.584639278,-1.978125,-12.16993067,0.264817483,59.15468229 +198.92,50.43186859,-2.5717246,51.1771,5.116960417,8.58663756,-1.9265625,-12.16963766,0.163727847,59.16220735 +198.93,50.43186905,-2.571723391,51.1961,5.116960437,8.58863584,-1.8753125,-12.16784746,0.062495372,59.16973246 +198.94,50.43186951,-2.571722182,51.2146,5.116960446,8.588857819,-1.8246875,-12.16456028,-0.038791535,59.17725752 +198.95,50.43186997,-2.571720973,51.2326,5.116960452,8.58796961,-1.773125,-12.15977689,-0.140044693,59.18478263 +198.96,50.43187043,-2.571719765,51.2501,5.11696047,8.58796955,-1.7196875,-12.15349824,-0.241175698,59.19230769 +198.97,50.43187089,-2.571718556,51.267,5.116960491,8.589079678,-1.665,-12.14572573,-0.342096369,59.1998328 +198.98,50.43187135,-2.571717347,51.2834,5.1169605,8.589967767,-1.61,-12.13646089,-0.442718759,59.20735786 +198.99,50.43187181,-2.571716138,51.2992,5.116960516,8.59041178,-1.5546875,-12.12570572,-0.542955032,59.21488297 +199,50.43187227,-2.571714929,51.3145,5.116960539,8.591299868,-1.498125,-12.11346242,-0.642717928,59.22240803 +199.01,50.43187273,-2.57171372,51.3292,5.116960549,8.59263203,-1.44,-12.09973355,-0.741920299,59.22993314 +199.02,50.43187319,-2.57171251,51.3433,5.116960552,8.593520115,-1.381875,-12.08452203,-0.840475743,59.23745819 +199.03,50.43187365,-2.571711301,51.3568,5.116960563,8.593742088,-1.325,-12.06783097,-0.93829826,59.24498325 +199.04,50.43187411,-2.571710091,51.3698,5.116960574,8.59396406,-1.268125,-12.04966385,-1.035302536,59.25250836 +199.05,50.43187457,-2.571708882,51.3822,5.116960582,8.594852144,-1.209375,-12.03002458,-1.131404059,59.26003342 +199.06,50.43187503,-2.571707672,51.394,5.116960597,8.595962264,-1.1484375,-12.0089171,-1.226519006,59.26755853 +199.07,50.43187549,-2.571706462,51.4052,5.116960613,8.595962195,-1.086875,-11.98634594,-1.320564356,59.27508359 +199.08,50.43187595,-2.571705252,51.4157,5.116960622,8.595296014,-1.0265625,-11.96231575,-1.413458175,59.2826087 +199.09,50.43187641,-2.571704043,51.4257,5.116960623,8.596184095,-0.9665625,-11.93683162,-1.505119448,59.29013376 +199.1,50.43187687,-2.571702833,51.4351,5.116960625,8.598626437,-0.9046875,-11.90989876,-1.595468188,59.29765887 +199.11,50.43187733,-2.571701622,51.4438,5.113484431,8.600402665,-0.841875,-11.88152291,-1.684425673,59.30518393 +199.12,50.43187779,-2.571700412,51.4519,5.09957965,8.600846668,-0.78,-11.85170991,-1.77191438,59.31270904 +199.13,50.43187825,-2.571699201,51.4594,5.082198683,8.600846595,-0.718125,-11.82046601,-1.857857878,59.32023409 +199.14,50.4318787,-2.571697991,51.4663,5.082198702,8.600846522,-0.655,-11.78779773,-1.942181337,59.32775921 +199.15,50.43187916,-2.57169678,51.4725,5.099579688,8.601068485,-0.591875,-11.75371196,-2.024811133,59.33528426 +199.16,50.43187962,-2.57169557,51.4781,5.11348447,8.601956559,-0.5296875,-11.71821573,-2.105675302,59.34280938 +199.17,50.43188008,-2.571694359,51.4831,5.113484474,8.603288708,-0.4665625,-11.68131651,-2.184703314,59.35033443 +199.18,50.43188054,-2.571693148,51.4875,5.099579692,8.604176781,-0.4015625,-11.64302196,-2.261826183,59.35785955 +199.19,50.431881,-2.571691937,51.4911,5.082198711,8.604620778,-0.336875,-11.6033401,-2.336976702,59.3653846 +199.2,50.43188145,-2.571690726,51.4942,5.082198718,8.60550885,-0.2734375,-11.5622792,-2.410089383,59.37290971 +199.21,50.43188191,-2.571689515,51.4966,5.099579709,8.606618958,-0.2096875,-11.51984789,-2.481100454,59.38043477 +199.22,50.43188237,-2.571688303,51.4984,5.110008303,8.606618877,-0.145,-11.47605495,-2.549947922,59.38795988 +199.23,50.43188283,-2.571687092,51.4995,5.099579715,8.605730645,-0.08,-11.4309096,-2.616571799,59.39548494 +199.24,50.43188329,-2.571685881,51.5,5.082198733,8.605952601,-0.015,-11.38442124,-2.680913985,59.40301005 +199.25,50.43188374,-2.57168467,51.4998,5.078722537,8.607950855,0.05,-11.33659954,-2.742918389,59.41053511 +199.26,50.4318842,-2.571683458,51.499,5.082198731,8.609949108,0.1146875,-11.2874546,-2.802530923,59.41806022 +199.27,50.43188466,-2.571682246,51.4975,5.078722527,8.610171061,0.1784375,-11.23699656,-2.859699621,59.42558528 +199.28,50.43188511,-2.571681034,51.4954,5.082198715,8.609504863,0.2415625,-11.18523595,-2.914374577,59.43311039 +199.29,50.43188557,-2.571679823,51.4927,5.096103495,8.610170889,0.3053125,-11.13218367,-2.966508178,59.44063545 +199.3,50.43188603,-2.571678611,51.4893,5.096103491,8.611725065,0.37,-11.07785083,-3.016054933,59.44816056 +199.31,50.43188649,-2.571677398,51.4853,5.082198713,8.612391088,0.4346875,-11.0222486,-3.062971639,59.45568561 +199.32,50.43188694,-2.571676187,51.4806,5.078722533,8.612835074,0.4984375,-10.96538878,-3.107217446,59.46321073 +199.33,50.4318874,-2.571674974,51.4753,5.082198726,8.614167209,0.5615625,-10.90728313,-3.148753677,59.47073578 +199.34,50.43188786,-2.571673762,51.4694,5.078722507,8.61572138,0.625,-10.84794384,-3.187544123,59.4782609 +199.35,50.43188831,-2.571672549,51.4628,5.078722498,8.616387401,0.688125,-10.78738323,-3.223554979,59.48578595 +199.36,50.43188877,-2.571671336,51.4556,5.082198694,8.615943234,0.75,-10.72561408,-3.256754904,59.49331107 +199.37,50.43188923,-2.571670124,51.4478,5.07524629,8.615277028,0.811875,-10.66264917,-3.287114849,59.50083612 +199.38,50.43188968,-2.571668911,51.4394,5.064817697,8.615498972,0.8746875,-10.59850167,-3.314608343,59.50836118 +199.39,50.43189014,-2.571667699,51.4303,5.061341505,8.617275177,0.9365625,-10.533185,-3.339211495,59.51588629 +199.4,50.43189059,-2.571666486,51.4206,5.061341495,8.619717493,0.9965625,-10.46671279,-3.360902817,59.52341135 +199.41,50.43189105,-2.571665272,51.4104,5.064817675,8.620605546,1.056875,-10.39909895,-3.379663403,59.53093646 +199.42,50.4318915,-2.571664059,51.3995,5.075246258,8.619939337,1.1184375,-10.3303576,-3.395476809,59.53846151 +199.43,50.43189196,-2.571662846,51.388,5.082198649,8.619939239,1.1796875,-10.26050304,-3.408329341,59.54598663 +199.44,50.43189242,-2.571661633,51.3759,5.075246249,8.621049327,1.2396875,-10.18954984,-3.418209769,59.55351168 +199.45,50.43189287,-2.571660419,51.3632,5.06481765,8.621937377,1.298125,-10.11751294,-3.425109442,59.5610368 +199.46,50.43189333,-2.571659206,51.3499,5.061341444,8.622159314,1.355,-10.04440731,-3.4290224,59.56856185 +199.47,50.43189378,-2.571657992,51.3361,5.061341433,8.62238125,1.411875,-9.970248181,-3.429945148,59.57608697 +199.48,50.43189424,-2.571656779,51.3217,5.06134142,8.623269298,1.47,-9.895051137,-3.427877,59.58361202 +199.49,50.43189469,-2.571655565,51.3067,5.061341402,8.62460142,1.528125,-9.818831765,-3.422819616,59.59113713 +199.5,50.43189515,-2.571654351,51.2911,5.061341388,8.625489466,1.584375,-9.74160605,-3.414777523,59.59866219 +199.51,50.4318956,-2.571653137,51.275,5.061341384,8.625711399,1.6384375,-9.663390149,-3.403757711,59.6061873 +199.52,50.43189606,-2.571651923,51.2583,5.061341373,8.625711294,1.6915625,-9.584200334,-3.389769749,59.61371236 +199.53,50.43189651,-2.571650709,51.2412,5.061341349,8.625933226,1.745,-9.504053164,-3.37282584,59.62123747 +199.54,50.43189697,-2.571649495,51.2234,5.061341338,8.626821269,1.7984375,-9.422965427,-3.352940824,59.62876253 +199.55,50.43189742,-2.571648281,51.2052,5.057865145,8.628153386,1.85125,-9.340953967,-3.330131947,59.63628764 +199.56,50.43189788,-2.571647066,51.1864,5.047436541,8.629041428,1.9034375,-9.258035916,-3.304419205,59.6438127 +199.57,50.43189833,-2.571645852,51.1671,5.040484116,8.629485395,1.954375,-9.174228692,-3.275824887,59.65133781 +199.58,50.43189878,-2.571644637,51.1473,5.047436489,8.630373435,2.0034375,-9.089549712,-3.244374031,59.65886287 +199.59,50.43189924,-2.571643423,51.127,5.057865067,8.63170555,2.0515625,-9.004016682,-3.21009408,59.66638798 +199.6,50.43189969,-2.571642207,51.1063,5.057865046,8.632593589,2.0996875,-8.917647477,-3.17301483,59.67391303 +199.61,50.43190015,-2.571640993,51.085,5.047436446,8.632815515,2.146875,-8.830460088,-3.133168652,59.68143815 +199.62,50.4319006,-2.571639777,51.0633,5.040484054,8.63303744,2.1928125,-8.742472793,-3.090590325,59.6889632 +199.63,50.43190105,-2.571638563,51.0412,5.043960233,8.63370344,2.2384375,-8.653703926,-3.045316976,59.69648832 +199.64,50.43190151,-2.571637347,51.0185,5.043960198,8.63436944,2.283125,-8.564171994,-2.997388025,59.70401337 +199.65,50.43190196,-2.571636132,50.9955,5.040483984,8.634813401,2.32625,-8.47389579,-2.946845355,59.71153849 +199.66,50.43190241,-2.571634917,50.972,5.043960179,8.6354794,2.3684375,-8.382894049,-2.89373297,59.71906354 +199.67,50.43190287,-2.571633701,50.9481,5.043960161,8.636367434,2.4096875,-8.291185851,-2.838097164,59.72658865 +199.68,50.43190332,-2.571632486,50.9238,5.040483928,8.637477506,2.4496875,-8.198790333,-2.779986524,59.73411371 +199.69,50.43190377,-2.57163127,50.8991,5.043960103,8.638587577,2.4884375,-8.105726804,-2.719451699,59.74163882 +199.7,50.43190423,-2.571630054,50.874,5.040483899,8.638587461,2.52625,-8.012014687,-2.656545517,59.74916388 +199.71,50.43190468,-2.571628838,50.8486,5.026579092,8.637921232,2.5634375,-7.917673519,-2.591322752,59.75668893 +199.72,50.43190513,-2.571627623,50.8227,5.026579065,8.638587227,2.5996875,-7.822723068,-2.523840298,59.76421405 +199.73,50.43190558,-2.571626407,50.7966,5.040483838,8.640141371,2.6346875,-7.7271831,-2.454156999,59.7717391 +199.74,50.43190604,-2.57162519,50.77,5.040483827,8.640807365,2.6684375,-7.631073612,-2.382333703,59.77926422 +199.75,50.43190649,-2.571623975,50.7432,5.026579013,8.641251321,2.7009375,-7.534414658,-2.308432919,59.78678927 +199.76,50.43190694,-2.571622758,50.716,5.026578983,8.642583426,2.731875,-7.437226406,-2.232519163,59.79431439 +199.77,50.43190739,-2.571621542,50.6885,5.040483755,8.644137568,2.76125,-7.339529138,-2.15465861,59.80183944 +199.78,50.43190785,-2.571620325,50.6608,5.040483742,8.644803561,2.79,-7.241343366,-2.074919214,59.80936455 +199.79,50.4319083,-2.571619108,50.6327,5.023102731,8.644359366,2.8184375,-7.142689487,-1.993370418,59.81688961 +199.8,50.43190875,-2.571617892,50.6044,5.009197916,8.643693134,2.84625,-7.043588129,-1.910083382,59.82441472 +199.81,50.4319092,-2.571616675,50.5758,5.009197903,8.643693013,2.8728125,-6.944059974,-1.8251307,59.83193978 +199.82,50.43190965,-2.571615459,50.5469,5.023102673,8.644803078,2.8965625,-6.844125878,-1.738586514,59.83946489 +199.83,50.4319101,-2.571614242,50.5178,5.040483622,8.64702333,2.918125,-6.743806584,-1.650526224,59.84698995 +199.84,50.43191056,-2.571613025,50.4886,5.040483588,8.649021544,2.94,-6.643123174,-1.561026664,59.85451506 +199.85,50.43191101,-2.571611807,50.459,5.023102588,8.649243459,2.96125,-6.54209662,-1.470165871,59.86204012 +199.86,50.43191146,-2.57161059,50.4293,5.009197788,8.648355188,2.979375,-6.440748006,-1.378023028,59.86956523 +199.87,50.43191191,-2.571609373,50.3994,5.005721571,8.648355066,2.9953125,-6.339098532,-1.284678577,59.87709029 +199.88,50.43191236,-2.571608156,50.3694,5.00572155,8.649465129,3.0115625,-6.237169341,-1.190213879,59.8846154 +199.89,50.43191281,-2.571606938,50.3392,5.005721533,8.650575193,3.028125,-6.13498186,-1.094711269,59.89214045 +199.9,50.43191326,-2.571605721,50.3088,5.009197708,8.651685256,3.043125,-6.032557289,-0.998254053,59.89966557 +199.91,50.43191371,-2.571604503,50.2783,5.023102456,8.653017357,3.05625,-5.929917113,-0.900926343,59.90719062 +199.92,50.43191416,-2.571603285,50.2477,5.040483401,8.653905383,3.068125,-5.827082763,-0.80281305,59.91471574 +199.93,50.43191462,-2.571602067,50.2169,5.040483379,8.654127296,3.0778125,-5.724075666,-0.70399966,59.92224079 +199.94,50.43191507,-2.571600849,50.1861,5.023102383,8.654127172,3.085,-5.620917308,-0.604572346,59.92976591 +199.95,50.43191552,-2.571599631,50.1552,5.009197578,8.654349086,3.0915625,-5.517629346,-0.504617853,59.93729096 +199.96,50.43191597,-2.571598413,50.1243,5.005721358,8.655237112,3.098125,-5.414233268,-0.404223329,59.94481607 +199.97,50.43191642,-2.571597195,50.0932,5.005721334,8.656347174,3.103125,-5.310750673,-0.303476321,59.95234113 +199.98,50.43191687,-2.571595976,50.0622,5.005721313,8.656569086,3.10625,-5.207203162,-0.202464721,59.95986624 +199.99,50.43191732,-2.571594758,50.0311,5.005721295,8.656568962,3.1084375,-5.103612393,-0.101276536,59.9673913 +200,50.43191777,-2.57159354,50,5.005721276,8.657679024,3.109375,-5.000000023,0,59.97491641 +200.01,50.43191822,-2.571592321,49.9689,5.002245052,8.659011123,3.1084375,-4.896387596,0.101276536,59.98244147 +200.02,50.43191867,-2.571591102,49.9378,4.988340238,8.659677111,3.10625,-4.792796826,0.202464721,59.98996658 +200.03,50.43191912,-2.571589884,49.9068,4.970959234,8.6603431,3.103125,-4.689249315,0.303476321,59.99749164 +200.04,50.43191956,-2.571588664,49.8757,4.97095921,8.661231127,3.098125,-4.58576672,0.404223329,60.00501675 +200.05,50.43192001,-2.571587446,49.8448,4.988340164,8.662119153,3.0915625,-4.482370642,0.504617853,60.01254181 +200.06,50.43192046,-2.571586226,49.8139,5.002244923,8.662563103,3.085,-4.379082681,0.604572346,60.02006686 +200.07,50.43192091,-2.571585007,49.7831,5.005721095,8.662340942,3.0778125,-4.275924323,0.70399966,60.02759197 +200.08,50.43192136,-2.571583788,49.7523,5.005721071,8.662562855,3.068125,-4.172917226,0.80281305,60.03511703 +200.09,50.43192181,-2.571582569,49.7217,5.005721047,8.663672917,3.05625,-4.070082875,0.900926343,60.04264214 +200.1,50.43192226,-2.571581349,49.6912,5.005721024,8.66478298,3.043125,-3.9674427,0.998254053,60.0501672 +200.11,50.43192271,-2.57158013,49.6608,5.002244805,8.665671007,3.028125,-3.865018129,1.094711269,60.05769231 +200.12,50.43192316,-2.57157891,49.6306,4.98834,8.666114959,3.0115625,-3.762830648,1.190213879,60.06521737 +200.13,50.43192361,-2.57157769,49.6006,4.970959001,8.665892798,2.9953125,-3.660901513,1.284678577,60.07274248 +200.14,50.43192405,-2.571576471,49.5707,4.970958985,8.666114714,2.979375,-3.559251982,1.378023028,60.08026754 +200.15,50.4319245,-2.571575251,49.541,4.988339944,8.667224778,2.96125,-3.457903369,1.470165871,60.08779265 +200.16,50.43192495,-2.571574031,49.5114,4.998768503,8.668334843,2.94,-3.356876815,1.561026664,60.09531771 +200.17,50.4319254,-2.571572811,49.4822,4.988339888,8.669444907,2.918125,-3.256193405,1.650526224,60.10284282 +200.18,50.43192585,-2.571571591,49.4531,4.970958888,8.670554972,2.8965625,-3.155874167,1.738586514,60.11036787 +200.19,50.43192629,-2.57157037,49.4242,4.970958873,8.670776888,2.8728125,-3.055940015,1.8251307,60.11789299 +200.2,50.43192674,-2.57156915,49.3956,4.98833983,8.670776768,2.84625,-2.95641186,1.910083382,60.12541804 +200.21,50.43192719,-2.57156793,49.3673,4.998768383,8.671886834,2.8184375,-2.857310559,1.993370418,60.13294316 +200.22,50.43192764,-2.571566709,49.3392,4.988339767,8.6729969,2.79,-2.758656623,2.074919214,60.14046821 +200.23,50.43192809,-2.571565488,49.3115,4.970958778,8.672996781,2.76125,-2.660470851,2.15465861,60.14799333 +200.24,50.43192853,-2.571564268,49.284,4.96748257,8.673218699,2.731875,-2.56277364,2.232519163,60.15551838 +200.25,50.43192898,-2.571563047,49.2568,4.970958736,8.674328766,2.7009375,-2.465585387,2.308432919,60.16304349 +200.26,50.43192943,-2.571561826,49.23,4.967482511,8.675438835,2.6684375,-2.368926433,2.382333703,60.17056855 +200.27,50.43192987,-2.571560605,49.2034,4.970958697,8.676548903,2.6346875,-2.272816889,2.454156999,60.17809366 +200.28,50.43193032,-2.571559384,49.1773,4.984863476,8.677658972,2.5996875,-2.177276921,2.523840298,60.18561872 +200.29,50.43193077,-2.571558162,49.1514,4.984863456,8.677880893,2.5634375,-2.08232647,2.591322752,60.19314383 +200.3,50.43193122,-2.571556941,49.126,4.970958638,8.677658739,2.52625,-1.987985302,2.656545517,60.20066889 +200.31,50.43193166,-2.57155572,49.1009,4.967482412,8.678102698,2.4884375,-1.894273184,2.719451699,60.208194 +200.32,50.43193211,-2.571554498,49.0762,4.9709586,8.678768694,2.4496875,-1.801209655,2.779986524,60.21571906 +200.33,50.43193256,-2.571553277,49.0519,4.964006211,8.678990617,2.4096875,-1.708814137,2.838097164,60.22324417 +200.34,50.431933,-2.571552055,49.028,4.953577614,8.67921254,2.3684375,-1.61710594,2.89373297,60.23076923 +200.35,50.43193345,-2.571550834,49.0045,4.95357758,8.680100576,2.32625,-1.526104256,2.946845355,60.23829434 +200.36,50.43193389,-2.571549612,48.9815,4.964006126,8.681432686,2.283125,-1.435827995,2.997388025,60.24581939 +200.37,50.43193434,-2.57154839,48.9588,4.970958499,8.682320722,2.2384375,-1.346296063,3.045316976,60.25334451 +200.38,50.43193479,-2.571547168,48.9367,4.964006112,8.682542647,2.1928125,-1.257527196,3.090590325,60.26086956 +200.39,50.43193523,-2.571545946,48.915,4.953577517,8.682764574,2.146875,-1.169539901,3.133168652,60.26839468 +200.4,50.43193568,-2.571544724,48.8937,4.95010129,8.683652613,2.0996875,-1.082352512,3.17301483,60.27591973 +200.41,50.43193612,-2.571543502,48.873,4.950101263,8.684984726,2.0515625,-0.995983307,3.21009408,60.28344479 +200.42,50.43193657,-2.571542279,48.8527,4.953577454,8.686094802,2.0034375,-0.910450276,3.244374031,60.2909699 +200.43,50.43193701,-2.571541057,48.8329,4.964006042,8.686982843,1.954375,-0.825771297,3.275824887,60.29849496 +200.44,50.43193746,-2.571539834,48.8136,4.970958417,8.68742681,1.9034375,-0.741964073,3.304419205,60.30602007 +200.45,50.43193791,-2.571538611,48.7948,4.964005995,8.687204666,1.85125,-0.659046079,3.330131947,60.31354513 +200.46,50.43193835,-2.571537389,48.7766,4.953577385,8.687426597,1.7984375,-0.577034619,3.352940824,60.32107024 +200.47,50.4319388,-2.571536166,48.7588,4.950101186,8.688536676,1.745,-0.495946824,3.37282584,60.32859529 +200.48,50.43193924,-2.571534943,48.7417,4.946624989,8.689646757,1.6915625,-0.415799655,3.389769749,60.33612041 +200.49,50.43193969,-2.57153372,48.725,4.936196389,8.690756839,1.6384375,-0.33660984,3.403757711,60.34364546 +200.5,50.43194013,-2.571532497,48.7089,4.92924398,8.691866922,1.584375,-0.258393939,3.414777523,60.35117058 +200.51,50.43194057,-2.571531273,48.6933,4.936196359,8.692088858,1.528125,-0.181168223,3.422819616,60.35869563 +200.52,50.43194102,-2.57153005,48.6783,4.946624939,8.691866719,1.47,-0.104948909,3.427877,60.36622075 +200.53,50.43194146,-2.571528827,48.6639,4.950101128,8.692310691,1.411875,-0.029751808,3.429945148,60.3737458 +200.54,50.43194191,-2.571527603,48.6501,4.950101115,8.693198739,1.355,0.044407323,3.4290224,60.38127091 +200.55,50.43194235,-2.57152638,48.6368,4.946624912,8.694308826,1.298125,0.117512956,3.425109442,60.38879597 +200.56,50.4319428,-2.571525156,48.6241,4.936196327,8.695640951,1.2396875,0.189549851,3.418209769,60.39632108 +200.57,50.43194324,-2.571523932,48.612,4.929243926,8.696306964,1.1796875,0.260502996,3.408329341,60.40384614 +200.58,50.43194368,-2.571522708,48.6005,4.936196289,8.695862793,1.1184375,0.330357553,3.395476809,60.41137125 +200.59,50.43194413,-2.571521484,48.5896,4.946624855,8.695640659,1.056875,0.399098966,3.379663403,60.41889631 +200.6,50.43194457,-2.571520261,48.5794,4.946624859,8.696750749,0.9965625,0.466712799,3.360902817,60.42642142 +200.61,50.43194502,-2.571519036,48.5697,4.936196282,8.69786084,0.9365625,0.533185013,3.339211495,60.43394648 +200.62,50.43194546,-2.571517812,48.5606,4.929243879,8.697860747,0.8746875,0.598501686,3.314608343,60.44147159 +200.63,50.4319459,-2.571516588,48.5522,4.932720048,8.698082692,0.811875,0.662649124,3.287114849,60.44899665 +200.64,50.43194635,-2.571515364,48.5444,4.932720042,8.699192786,0.75,0.725614034,3.256754904,60.45652176 +200.65,50.43194679,-2.571514139,48.5372,4.929243864,8.700302881,0.688125,0.787383239,3.223554979,60.46404681 +200.66,50.43194723,-2.571512915,48.5306,4.932720072,8.701412977,0.625,0.847943847,3.187544123,60.47157193 +200.67,50.43194768,-2.57151169,48.5247,4.929243875,8.70274511,0.5615625,0.907283138,3.148753677,60.47909698 +200.68,50.43194812,-2.571510465,48.5194,4.915339081,8.703633169,0.4984375,0.965388793,3.107217446,60.4866221 +200.69,50.43194856,-2.57150924,48.5147,4.915339058,8.703855119,0.4346875,1.022248609,3.062971639,60.49414715 +200.7,50.431949,-2.571508015,48.5107,4.929243824,8.703855033,0.37,1.077850783,3.016054933,60.50167227 +200.71,50.43194945,-2.57150679,48.5073,4.929243832,8.703854947,0.3053125,1.132183683,2.966508178,60.50919732 +200.72,50.43194989,-2.571505565,48.5046,4.915339069,8.704076898,0.2415625,1.185235965,2.914374577,60.51672243 +200.73,50.43195033,-2.57150434,48.5025,4.91533907,8.704964963,0.1784375,1.236996514,2.859699621,60.52424749 +200.74,50.43195077,-2.571503115,48.501,4.929243837,8.706297103,0.1146875,1.287454558,2.802530923,60.5317726 +200.75,50.43195122,-2.571501889,48.5002,4.929243828,8.707185169,0.05,1.336599554,2.742918389,60.53929766 +200.76,50.43195166,-2.571500664,48.5,4.911862852,8.707407125,-0.015,1.384421247,2.680913985,60.54682272 +200.77,50.4319521,-2.571499438,48.5005,4.901434268,8.707629081,-0.08,1.43090961,2.616571799,60.55434783 +200.78,50.43195254,-2.571498213,48.5016,4.911862856,8.70851715,-0.145,1.47605496,2.549947922,60.56187288 +200.79,50.43195298,-2.571496987,48.5034,4.929243841,8.709849295,-0.2096875,1.519847901,2.481100454,60.569398 +200.8,50.43195343,-2.571495761,48.5058,4.929243857,8.710737366,-0.2734375,1.562279207,2.410089383,60.57692305 +200.81,50.43195387,-2.571494535,48.5089,4.911862889,8.711181362,-0.336875,1.603340113,2.336976702,60.58444817 +200.82,50.43195431,-2.571493309,48.5125,4.897958098,8.712069434,-0.4015625,1.643021967,2.261826183,60.59197322 +200.83,50.43195475,-2.571492083,48.5169,4.894481884,8.713179545,-0.4665625,1.681316518,2.184703314,60.59949833 +200.84,50.43195519,-2.571490856,48.5219,4.894481888,8.713401508,-0.5296875,1.718215744,2.105675302,60.60702339 +200.85,50.43195563,-2.57148963,48.5275,4.894481915,8.713179398,-0.591875,1.75371197,2.024811133,60.6145485 +200.86,50.43195607,-2.571488404,48.5337,4.897958133,8.7136234,-0.655,1.787797744,1.942181337,60.62207356 +200.87,50.43195651,-2.571487177,48.5406,4.911862921,8.714511477,-0.718125,1.820466022,1.857857878,60.62959867 +200.88,50.43195695,-2.571485951,48.5481,4.929243892,8.715399554,-0.78,1.851709926,1.77191438,60.63712373 +200.89,50.4319574,-2.571484724,48.5562,4.929243886,8.715843559,-0.841875,1.881522868,1.684425673,60.64464884 +200.9,50.43195784,-2.571483497,48.5649,4.911862909,8.715621452,-0.9046875,1.909898775,1.595468188,60.6521739 +200.91,50.43195828,-2.571482271,48.5743,4.897958137,8.716065457,-0.9665625,1.93683163,1.505119448,60.65969901 +200.92,50.43195872,-2.571481044,48.5843,4.894481957,8.717841687,-1.0265625,1.962315761,1.413458175,60.66722407 +200.93,50.43195916,-2.571479817,48.5948,4.89448197,8.719173843,-1.086875,1.986345955,1.320564356,60.67474918 +200.94,50.4319596,-2.571478589,48.606,4.894481977,8.719173778,-1.1484375,2.008917112,1.226519006,60.68227424 +200.95,50.43196004,-2.571477363,48.6178,4.894481988,8.71939575,-1.209375,2.030024533,1.131404059,60.68979935 +200.96,50.43196048,-2.571476135,48.6302,4.894482009,8.720727909,-1.268125,2.049663865,1.035302536,60.6973244 +200.97,50.43196092,-2.571474908,48.6432,4.894482024,8.722282105,-1.325,2.067830981,0.93829826,60.70484952 +200.98,50.43196136,-2.57147368,48.6567,4.894482019,8.722948154,-1.381875,2.084521987,0.840475743,60.71237457 +200.99,50.4319618,-2.571472452,48.6708,4.894482008,8.722504018,-1.44,2.099733558,0.741920299,60.71989969 +201,50.43196224,-2.571471225,48.6855,4.891005825,8.721837846,-1.498125,2.113462429,0.642717928,60.72742474 +201.01,50.43196268,-2.571469997,48.7008,4.877101079,8.721837786,-1.5546875,2.125705735,0.542955032,60.73494985 +201.02,50.43196312,-2.57146877,48.7166,4.859720134,8.722947913,-1.61,2.136460897,0.442718759,60.74247491 +201.03,50.43196355,-2.571467542,48.733,4.859720149,8.724946189,-1.665,2.14572574,0.342096369,60.75000002 +201.04,50.43196399,-2.571466314,48.7499,4.877101129,8.726278354,-1.7196875,2.153498256,0.241175698,60.75752508 +201.05,50.43196443,-2.571465085,48.7674,4.891005912,8.726278296,-1.773125,2.159776899,0.140044693,60.76505019 +201.06,50.43196487,-2.571463858,48.7854,4.894482119,8.726500276,-1.8246875,2.164560295,0.038791535,60.77257525 +201.07,50.43196531,-2.571462629,48.8039,4.894482136,8.727610406,-1.8753125,2.167847411,-0.062495372,60.78010036 +201.08,50.43196575,-2.571461401,48.8229,4.894482146,8.7284985,-1.9265625,2.169637675,-0.163727847,60.78762542 +201.09,50.43196619,-2.571460172,48.8424,4.89100596,8.72894252,-1.978125,2.169930628,-0.264817483,60.79515047 +201.1,50.43196663,-2.571458944,48.8625,4.877101195,8.729830614,-2.0278125,2.168726271,-0.365676275,60.80267559 +201.11,50.43196707,-2.571457715,48.883,4.859720244,8.731162784,-2.075,2.166024775,-0.466216159,60.81020064 +201.12,50.4319675,-2.571456486,48.904,4.859720274,8.732050881,-2.1215625,2.16182677,-0.566349472,60.81772576 +201.13,50.43196794,-2.571455257,48.9254,4.877101275,8.732272868,-2.1684375,2.156133117,-0.665988952,60.82525081 +201.14,50.43196838,-2.571454028,48.9474,4.887529878,8.732272817,-2.2146875,2.14894496,-0.765047626,60.83277592 +201.15,50.43196882,-2.571452799,48.9697,4.877101301,8.732272766,-2.2596875,2.140263847,-0.863439204,60.84030098 +201.16,50.43196926,-2.57145157,48.9926,4.85972033,8.732494754,-2.3034375,2.130091612,-0.961077859,60.84782609 +201.17,50.43196969,-2.571450341,49.0158,4.859720339,8.733382853,-2.34625,2.118430317,-1.057878448,60.85535115 +201.18,50.43197013,-2.571449112,49.0395,4.877101334,8.734492989,-2.3884375,2.105282482,-1.153756518,60.86287626 +201.19,50.43197057,-2.571447882,49.0636,4.887529945,8.734714978,-2.4296875,2.090650744,-1.248628531,60.87040132 +201.2,50.43197101,-2.571446653,49.0881,4.877101382,8.734714932,-2.4696875,2.074538197,-1.342411695,60.87792643 +201.21,50.43197145,-2.571445424,49.113,4.859720423,8.736047108,-2.508125,2.056948278,-1.43502425,60.88545149 +201.22,50.43197188,-2.571444194,49.1383,4.85624425,8.738045395,-2.545,2.037884597,-1.526385464,60.8929766 +201.23,50.43197232,-2.571442964,49.1639,4.859720476,8.739155535,-2.58125,2.017351108,-1.61641564,60.90050166 +201.24,50.43197276,-2.571441734,49.1899,4.85624431,8.739377528,-2.6165625,1.995352164,-1.705036283,60.90802677 +201.25,50.43197319,-2.571440504,49.2163,4.856244331,8.739377484,-2.65,1.97189235,-1.7921701,60.91555182 +201.26,50.43197363,-2.571439274,49.2429,4.859720538,8.739377439,-2.683125,1.946976478,-1.877741117,60.92307694 +201.27,50.43197407,-2.571438044,49.2699,4.85624435,8.739377395,-2.7165625,1.920609877,-1.961674679,60.93060199 +201.28,50.4319745,-2.571436814,49.2973,4.856244362,8.73959939,-2.7478125,1.89279799,-2.043897675,60.93812711 +201.29,50.43197494,-2.571435584,49.3249,4.859720579,8.740487495,-2.7765625,1.863546604,-2.124338371,60.94565216 +201.3,50.43197538,-2.571434354,49.3528,4.856244414,8.741819675,-2.805,1.832861906,-2.20292658,60.95317727 +201.31,50.43197581,-2.571433123,49.381,4.856244447,8.742929818,-2.8328125,1.8007502,-2.279593833,60.96070233 +201.32,50.43197625,-2.571431893,49.4095,4.859720665,8.743817924,-2.858125,1.767218246,-2.354273267,60.96822744 +201.33,50.43197669,-2.571430662,49.4382,4.852768287,8.744483995,-2.8815625,1.732273035,-2.426899678,60.9757525 +201.34,50.43197712,-2.571429431,49.4671,4.842339723,8.744928029,-2.905,1.695921899,-2.497409813,60.98327761 +201.35,50.43197756,-2.571428201,49.4963,4.842339757,8.745594099,-2.928125,1.65817246,-2.565742192,60.99080267 +201.36,50.43197799,-2.571426969,49.5257,4.852768375,8.746482207,-2.9496875,1.619032453,-2.631837228,60.99832778 +201.37,50.43197843,-2.571425739,49.5553,4.859720789,8.747370315,-2.97,1.578510185,-2.695637224,61.00585284 +201.38,50.43197887,-2.571424507,49.5851,4.852768412,8.747814349,-2.989375,1.536614078,-2.757086604,61.01337795 +201.39,50.4319793,-2.571423276,49.6151,4.842339835,8.747592274,-3.0065625,1.4933529,-2.816131738,61.02090301 +201.4,50.43197974,-2.571422045,49.6453,4.838863654,8.747814271,-3.02125,1.448735645,-2.872721175,61.02842812 +201.41,50.43198017,-2.571420814,49.6755,4.838863677,8.748924417,-3.035,1.402771653,-2.926805584,61.03595318 +201.42,50.43198061,-2.571419582,49.706,4.83886371,8.750034564,-3.0484375,1.355470549,-2.978337751,61.04347829 +201.43,50.43198104,-2.571418351,49.7365,4.838863744,8.751144711,-3.0609375,1.306842189,-3.027272759,61.05100334 +201.44,50.43198148,-2.571417119,49.7672,4.838863768,8.752476895,-3.071875,1.256896713,-3.073567921,61.0585284 +201.45,50.43198191,-2.571415887,49.798,4.838863783,8.753142968,-3.08125,1.20564455,-3.1171829,61.06605351 +201.46,50.43198235,-2.571414655,49.8288,4.838863807,8.752476819,-3.0896875,1.153096413,-3.158079654,61.07357857 +201.47,50.43198278,-2.571413423,49.8598,4.838863842,8.751588633,-3.0965625,1.099263304,-3.196222543,61.08110368 +201.48,50.43198322,-2.571412192,49.8908,4.838863874,8.752476743,-3.10125,1.044156395,-3.231578221,61.08862874 +201.49,50.43198365,-2.57141096,49.9218,4.835387702,8.754697076,-3.105,0.987787318,-3.264115979,61.09615385 +201.5,50.43198409,-2.571409727,49.9529,4.82495913,8.755585186,-3.108125,0.930167702,-3.293807339,61.10367891 +201.51,50.43198452,-2.571408495,49.984,4.818006752,8.754919037,-3.109375,0.871309696,-3.320626463,61.11120402 +201.52,50.43198495,-2.571407263,50.0151,4.824959167,8.754919,-3.1084375,0.811225503,-3.344549971,61.11872908 +201.53,50.43198539,-2.571406031,50.0462,4.83538779,8.756029148,-3.1065625,0.749927728,-3.365556953,61.12625419 +201.54,50.43198582,-2.571404798,50.0772,4.835387822,8.757139296,-3.1046875,0.687429148,-3.383629131,61.13377924 +201.55,50.43198626,-2.571403566,50.1083,4.824959259,8.758249443,-3.1015625,0.623742826,-3.39875069,61.14130436 +201.56,50.43198669,-2.571402333,50.1393,4.818006882,8.759581627,-3.09625,0.558882056,-3.410908568,61.14882941 +201.57,50.43198712,-2.5714011,50.1702,4.824959284,8.760469738,-3.0896875,0.492860415,-3.420091993,61.15635453 +201.58,50.43198756,-2.571399867,50.2011,4.835387887,8.760691737,-3.0815625,0.425691599,-3.426293115,61.16387958 +201.59,50.43198799,-2.571398634,50.2319,4.83538791,8.760691698,-3.07125,0.357389759,-3.429506434,61.1714047 +201.6,50.43198843,-2.571397401,50.2625,4.821483159,8.76069166,-3.06,0.287969046,-3.4297292,61.17892975 +201.61,50.43198886,-2.571396168,50.2931,4.804102214,8.76091366,-3.0484375,0.217444015,-3.426961127,61.18645486 +201.62,50.43198929,-2.571394935,50.3235,4.804102238,8.76180177,-3.03625,0.145829447,-3.421204734,61.19397992 +201.63,50.43198972,-2.571393702,50.3538,4.818007036,8.763133954,-3.023125,0.073140182,-3.412465008,61.20150503 +201.64,50.43199016,-2.571392468,50.384,4.821483255,8.764244099,-3.0078125,-0.000608538,-3.400749568,61.20903009 +201.65,50.43199059,-2.571391235,50.414,4.818007093,8.765132208,-2.9896875,-0.075401303,-3.386068613,61.2165552 +201.66,50.43199102,-2.571390001,50.4438,4.821483321,8.765576243,-2.97,-0.151222527,-3.36843492,61.22408026 +201.67,50.43199146,-2.571388767,50.4734,4.81800715,8.765354167,-2.9496875,-0.228056339,-3.347863959,61.23160537 +201.68,50.43199189,-2.571387534,50.5028,4.804102386,8.765576165,-2.9284375,-0.305886754,-3.324373607,61.23913043 +201.69,50.43199232,-2.5713863,50.532,4.8041024,8.76668631,-2.90625,-0.384697385,-3.297984316,61.24665554 +201.7,50.43199275,-2.571385066,50.5609,4.818007195,8.767574418,-2.883125,-0.464471961,-3.268719122,61.2541806 +201.71,50.43199319,-2.571383832,50.5897,4.818007217,8.768018451,-2.8584375,-0.545193635,-3.236603577,61.26170571 +201.72,50.43199362,-2.571382598,50.6181,4.800626269,8.768906558,-2.8328125,-0.626845679,-3.201665699,61.26923076 +201.73,50.43199405,-2.571381364,50.6463,4.790197712,8.770016701,-2.8065625,-0.709411017,-3.163935913,61.27675588 +201.74,50.43199448,-2.571380129,50.6743,4.800626324,8.770238697,-2.7778125,-0.792872404,-3.123447105,61.28428093 +201.75,50.43199491,-2.571378895,50.7019,4.818007323,8.770238655,-2.7465625,-0.877212365,-3.080234571,61.29180605 +201.76,50.43199535,-2.571377661,50.7292,4.818007335,8.771570835,-2.7153125,-0.962413309,-3.034336068,61.2993311 +201.77,50.43199578,-2.571376426,50.7562,4.800626364,8.773347088,-2.6846875,-1.048457475,-2.985791589,61.30685622 +201.78,50.43199621,-2.571375191,50.7829,4.7867216,8.773569082,-2.653125,-1.135326815,-2.934643417,61.31438127 +201.79,50.43199664,-2.571373956,50.8093,4.783245435,8.772680891,-2.619375,-1.22300328,-2.880936244,61.32190633 +201.8,50.43199707,-2.571372722,50.8353,4.78672166,8.772680847,-2.583125,-1.311468537,-2.824716823,61.32943144 +201.81,50.4319975,-2.571371487,50.861,4.800626467,8.773790988,-2.5453125,-1.400704078,-2.766034199,61.3369565 +201.82,50.43199793,-2.571370252,50.8862,4.818007465,8.774901127,-2.508125,-1.490691282,-2.704939538,61.34448161 +201.83,50.43199837,-2.571369017,50.9111,4.818007475,8.776011266,-2.4715625,-1.581411414,-2.641486181,61.35200666 +201.84,50.4319988,-2.571367782,50.9357,4.800626502,8.777343441,-2.4325,-1.672845394,-2.575729362,61.35953178 +201.85,50.43199923,-2.571366546,50.9598,4.786721735,8.778231543,-2.39,-1.764974257,-2.507726491,61.36705683 +201.86,50.43199966,-2.571365311,50.9835,4.783245568,8.778231496,-2.346875,-1.857778695,-2.437536812,61.37458195 +201.87,50.43200009,-2.571364075,51.0067,4.783245595,8.777565338,-2.3046875,-1.951239341,-2.365221631,61.382107 +201.88,50.43200052,-2.57136284,51.0296,4.783245614,8.777343253,-2.2615625,-2.045336716,-2.290843917,61.38963212 +201.89,50.43200095,-2.571361605,51.052,4.783245629,8.778675425,-2.21625,-2.140051108,-2.214468528,61.39715717 +201.9,50.43200138,-2.571360369,51.0739,4.783245637,8.780673708,-2.17,-2.235362752,-2.1361621,61.40468228 +201.91,50.43200181,-2.571359133,51.0954,4.783245643,8.781783844,-2.1234375,-2.331251823,-2.055992871,61.41220734 +201.92,50.43200224,-2.571357897,51.1164,4.783245659,8.78200583,-2.07625,-2.427698152,-1.974030858,61.41973245 +201.93,50.43200267,-2.571356661,51.1369,4.783245686,8.782227815,-2.0284375,-2.524681687,-1.890347392,61.42725751 +201.94,50.4320031,-2.571355425,51.157,4.78324571,8.783115911,-1.9796875,-2.622182201,-1.805015585,61.43478262 +201.95,50.43200353,-2.571354189,51.1765,4.783245727,8.784226043,-1.9296875,-2.720179241,-1.718109747,61.44230768 +201.96,50.43200396,-2.571352952,51.1956,4.78324574,8.784448027,-1.8784375,-2.818652409,-1.629705683,61.44983279 +201.97,50.43200439,-2.571351716,51.2141,4.783245745,8.784225936,-1.82625,-2.917581135,-1.539880453,61.45735785 +201.98,50.43200482,-2.57135048,51.2321,4.783245748,8.784669955,-1.7734375,-3.016944736,-1.448712498,61.46488296 +201.99,50.43200525,-2.571349243,51.2496,4.783245761,8.785558047,-1.7196875,-3.116722472,-1.356281227,61.47240802 +202,50.43200568,-2.571348007,51.2665,4.779769589,8.786446138,-1.665,-3.216893485,-1.2626672,61.47993313 +202.01,50.43200611,-2.57134677,51.2829,4.765864825,8.786890155,-1.61,-3.317436921,-1.167952177,61.48745818 +202.02,50.43200654,-2.571345533,51.2987,4.748483857,8.786668062,-1.555,-3.418331752,-1.072218665,61.4949833 +202.03,50.43200696,-2.571344297,51.314,4.748483869,8.787112078,-1.4996875,-3.519556836,-0.975550142,61.50250835 +202.04,50.43200739,-2.57134306,51.3287,4.76586486,8.789110351,-1.443125,-3.621091145,-0.878030949,61.51003347 +202.05,50.43200782,-2.571341823,51.3429,4.779769648,8.791108623,-1.385,-3.722913366,-0.779746056,61.51755852 +202.06,50.43200825,-2.571340585,51.3564,4.783245844,8.791552636,-1.3265625,-3.825002298,-0.680781233,61.52508364 +202.07,50.43200868,-2.571339348,51.3694,4.779769658,8.791330537,-1.2684375,-3.927336686,-0.581222769,61.53260869 +202.08,50.43200911,-2.571338111,51.3818,4.765864892,8.791774549,-1.2096875,-4.029894985,-0.481157523,61.5401338 +202.09,50.43200954,-2.571336873,51.3936,4.748483928,8.792440597,-1.15,-4.13265594,-0.380672643,61.54765886 +202.1,50.43200996,-2.571335636,51.4048,4.748483939,8.79266257,-1.09,-4.235598006,-0.279855792,61.55518397 +202.11,50.43201039,-2.571334398,51.4154,4.765864927,8.792884543,-1.03,-4.338699756,-0.178794918,61.56270903 +202.12,50.43201082,-2.571333161,51.4254,4.776293516,8.793772625,-0.9696875,-4.441939532,-0.077578142,61.57023414 +202.13,50.43201125,-2.571331923,51.4348,4.765864923,8.795104779,-0.908125,-4.545295904,0.023706243,61.5777592 +202.14,50.43201168,-2.571330685,51.4436,4.748483947,8.795992859,-0.845,-4.648747215,0.124970002,61.58528425 +202.15,50.4320121,-2.571329447,51.4517,4.748483964,8.796214829,-0.781875,-4.752271923,0.226124784,61.59280937 +202.16,50.43201253,-2.571328209,51.4592,4.762388765,8.79621476,-0.72,-4.855848311,0.327082411,61.60033442 +202.17,50.43201296,-2.571326971,51.4661,4.762388773,8.796214691,-0.658125,-4.959454836,0.427754763,61.60785954 +202.18,50.43201339,-2.571325733,51.4724,4.748483992,8.796436657,-0.5946875,-5.063069785,0.528054119,61.61538459 +202.19,50.43201381,-2.571324495,51.478,4.748483994,8.797324733,-0.53,-5.166671612,0.627893046,61.6229097 +202.2,50.43201424,-2.571323257,51.483,4.762388776,8.798656882,-0.4653125,-5.270238604,0.727184397,61.63043476 +202.21,50.43201467,-2.571322018,51.4873,4.762388768,8.799766993,-0.4015625,-5.373749159,0.825841656,61.63795987 +202.22,50.4320151,-2.57132078,51.491,4.748483985,8.800877104,-0.3384375,-5.477181677,0.923778707,61.64548493 +202.23,50.43201552,-2.571319541,51.4941,4.745007802,8.801987214,-0.275,-5.580514558,1.020910294,61.65301004 +202.24,50.43201595,-2.571318302,51.4965,4.74848401,8.802209174,-0.2115625,-5.683726144,1.117151562,61.6605351 +202.25,50.43201638,-2.571317063,51.4983,4.74153162,8.80198706,-0.148125,-5.786795006,1.212418687,61.66806021 +202.26,50.4320168,-2.571315825,51.4995,4.731103032,8.802431058,-0.083125,-5.889699544,1.30662859,61.67558527 +202.27,50.43201723,-2.571314585,51.5,4.73110303,8.803319128,-0.016875,-5.992418272,1.399699052,61.68311038 +202.28,50.43201765,-2.571313347,51.4998,4.741531612,8.804207196,0.048125,-6.094929703,1.491549,61.69063544 +202.29,50.43201808,-2.571312107,51.499,4.748483993,8.804873226,0.1115625,-6.197212525,1.582098276,61.69816055 +202.3,50.43201851,-2.571310868,51.4976,4.745007796,8.805317218,0.1753125,-6.299245307,1.671267926,61.7056856 +202.31,50.43201893,-2.571309629,51.4955,4.745007806,8.805983247,0.24,-6.401006794,1.758980202,61.71321072 +202.32,50.43201936,-2.571308389,51.4928,4.74848401,8.806649275,0.3046875,-6.502475672,1.845158669,61.72073577 +202.33,50.43201979,-2.57130715,51.4894,4.741531617,8.806871228,0.3684375,-6.60363074,1.929728099,61.72826089 +202.34,50.43202021,-2.57130591,51.4854,4.731103024,8.80709318,0.4315625,-6.704450972,2.012614752,61.73578594 +202.35,50.43202064,-2.571304671,51.4808,4.727626827,8.807981243,0.4953125,-6.804915225,2.093746378,61.74331106 +202.36,50.43202106,-2.571303431,51.4755,4.72762683,8.809313378,0.5596875,-6.90500253,2.173052274,61.75083611 +202.37,50.43202149,-2.571302191,51.4696,4.727626828,8.810201439,0.623125,-7.004691972,2.250463169,61.75836122 +202.38,50.43202191,-2.571300951,51.463,4.727626813,8.810423388,0.6853125,-7.103962812,2.325911684,61.76588628 +202.39,50.43202234,-2.571299711,51.4559,4.727626797,8.810423299,0.748125,-7.20279425,2.399331928,61.77341139 +202.4,50.43202276,-2.571298471,51.4481,4.727626793,8.810645246,0.811875,-7.30116566,2.47065996,61.78093645 +202.41,50.43202319,-2.571297231,51.4396,4.727626794,8.811533303,0.874375,-7.399056531,2.539833498,61.78846156 +202.42,50.43202361,-2.571295991,51.4306,4.72762679,8.812865433,0.935,-7.49644635,2.606792326,61.79598662 +202.43,50.43202404,-2.57129475,51.4209,4.727626783,8.813753489,0.9953125,-7.593314834,2.671477943,61.80351173 +202.44,50.43202446,-2.57129351,51.4107,4.727626774,8.813975432,1.05625,-7.689641759,2.733833971,61.81103679 +202.45,50.43202489,-2.571292269,51.3998,4.727626757,8.814197375,1.116875,-7.785406957,2.793806094,61.8185619 +202.46,50.43202531,-2.571291029,51.3883,4.724150541,8.815085427,1.1765625,-7.880590487,2.851341943,61.82608696 +202.47,50.43202574,-2.571289788,51.3763,4.713721943,8.816417554,1.2365625,-7.975172412,2.906391441,61.83361207 +202.48,50.43202616,-2.571288547,51.3636,4.706769552,8.817305605,1.2965625,-8.069133021,2.958906461,61.84113712 +202.49,50.43202658,-2.571287306,51.3503,4.713721945,8.817527545,1.3546875,-8.162452663,3.00884128,61.84866218 +202.5,50.43202701,-2.571286065,51.3365,4.724150526,8.817527446,1.4115625,-8.255111856,3.056152353,61.85618729 +202.51,50.43202743,-2.571284824,51.3221,4.724150516,8.817527348,1.4684375,-8.347091291,3.100798427,61.86371235 +202.52,50.43202786,-2.571283583,51.3071,4.713721916,8.817749285,1.5246875,-8.438371776,3.142740542,61.87123746 +202.53,50.43202828,-2.571282342,51.2916,4.706769514,8.818859369,1.58,-8.528934115,3.1819422,61.87876252 +202.54,50.4320287,-2.571281101,51.2755,4.710245706,8.8208576,1.635,-8.618759516,3.218369081,61.88628763 +202.55,50.43202913,-2.571279859,51.2589,4.710245696,8.822189719,1.69,-8.707829186,3.251989556,61.89381269 +202.56,50.43202955,-2.571278617,51.2417,4.706769476,8.821967581,1.7446875,-8.796124561,3.282774178,61.9013378 +202.57,50.43202997,-2.571277376,51.224,4.710245649,8.821523404,1.798125,-8.883627076,3.310696245,61.90886286 +202.58,50.4320304,-2.571276134,51.2057,4.710245638,8.82218941,1.85,-8.970318627,3.335731292,61.91638797 +202.59,50.43203082,-2.571274893,51.187,4.706769435,8.823299489,1.90125,-9.056180994,3.357857547,61.92391302 +202.6,50.43203124,-2.57127365,51.1677,4.710245619,8.823743458,1.951875,-9.1411963,3.377055643,61.93143814 +202.61,50.43203167,-2.571272409,51.1479,4.710245605,8.824409463,2.00125,-9.225346726,3.393308966,61.93896319 +202.62,50.43203209,-2.571271167,51.1277,4.706769392,8.825963614,2.05,-9.308614797,3.406603249,61.94648831 +202.63,50.43203251,-2.571269924,51.1069,4.710245564,8.826629617,2.0984375,-9.390983037,3.416926917,61.95401336 +202.64,50.43203294,-2.571268682,51.0857,4.706769342,8.825963399,2.14625,-9.472434259,3.424270975,61.96153848 +202.65,50.43203336,-2.57126744,51.064,4.689388346,8.826185327,2.193125,-9.552951502,3.428629064,61.96906353 +202.66,50.43203378,-2.571266198,51.0418,4.678959761,8.827961512,2.238125,-9.632517922,3.429997287,61.97658864 +202.67,50.4320342,-2.571264955,51.0192,4.689388354,8.829071587,2.28125,-9.711116903,3.428374499,61.9841137 +202.68,50.43203462,-2.571263712,50.9962,4.706769321,8.828183329,2.3234375,-9.788732,3.423762132,61.99163881 +202.69,50.43203505,-2.57126247,50.9727,4.706769293,8.827295071,2.365,-9.865347,3.416164195,61.99916387 +202.7,50.43203547,-2.571261228,50.9489,4.689388286,8.828405144,2.4065625,-9.940946031,3.405587337,62.00668898 +202.71,50.43203589,-2.571259985,50.9246,4.678959677,8.8306254,2.448125,-10.01551311,3.392040724,62.01421404 +202.72,50.43203631,-2.571258742,50.8999,4.689388248,8.832401582,2.488125,-10.08903282,3.375536217,62.02173915 +202.73,50.43203673,-2.571257499,50.8748,4.706769209,8.833067579,2.52625,-10.16148975,3.356088196,62.02926421 +202.74,50.43203716,-2.571256255,50.8494,4.706769182,8.832845428,2.563125,-10.23286877,3.333713563,62.03678932 +202.75,50.43203758,-2.571255013,50.8235,4.689388171,8.832845314,2.5984375,-10.30315494,3.308431973,62.04431438 +202.76,50.432038,-2.571253769,50.7974,4.675483369,8.833289274,2.633125,-10.37233363,3.28026531,62.05183949 +202.77,50.43203842,-2.571252526,50.7709,4.672007174,8.833733232,2.668125,-10.44039042,3.249238213,62.05936454 +202.78,50.43203884,-2.571251283,50.744,4.672007174,8.834399227,2.70125,-10.50731097,3.215377782,62.06688966 +202.79,50.43203926,-2.571250039,50.7168,4.672007157,8.835287258,2.7315625,-10.57308149,3.178713411,62.07441471 +202.8,50.43203968,-2.571248796,50.6894,4.672007126,8.836397326,2.7615625,-10.63768803,3.139277242,62.08193983 +202.81,50.4320401,-2.571247552,50.6616,4.675483293,8.837507393,2.7915625,-10.70111727,3.097103537,62.08946488 +202.82,50.43204052,-2.571246308,50.6335,4.689388055,8.837729312,2.819375,-10.76335596,3.052229082,62.09698994 +202.83,50.43204094,-2.571245064,50.6052,4.706769013,8.837729195,2.845,-10.82439097,3.004693065,62.10451505 +202.84,50.43204137,-2.571243821,50.5766,4.706768984,8.83883926,2.87,-10.88420966,2.954536913,62.11204011 +202.85,50.43204179,-2.571242576,50.5478,4.689387971,8.839949326,2.8946875,-10.94279946,2.901804398,62.11956522 +202.86,50.43204221,-2.571241332,50.5187,4.675483168,8.839949208,2.918125,-11.00014824,2.846541416,62.12709028 +202.87,50.43204263,-2.571240088,50.4894,4.672006971,8.840171126,2.939375,-11.05624396,2.788796208,62.13461539 +202.88,50.43204305,-2.571238844,50.4599,4.67200697,8.841281191,2.9584375,-11.11107487,2.728619139,62.14214044 +202.89,50.43204347,-2.571237599,50.4302,4.67200695,8.842169218,2.9765625,-11.16462958,2.66606269,62.14966556 +202.9,50.43204389,-2.571236355,50.4004,4.672006918,8.842391135,2.995,-11.21689691,2.60118135,62.15719061 +202.91,50.43204431,-2.57123511,50.3703,4.672006887,8.842613051,3.013125,-11.26786592,2.534031785,62.16471573 +202.92,50.43204473,-2.571233866,50.3401,4.668530667,8.843501078,3.029375,-11.31752595,2.464672494,62.17224078 +202.93,50.43204515,-2.571232621,50.3097,4.654625862,8.844833179,3.043125,-11.36586663,2.393163981,62.1797659 +202.94,50.43204557,-2.571231376,50.2792,4.637244858,8.845721205,3.0546875,-11.41287793,2.319568583,62.18729095 +202.95,50.43204598,-2.571230131,50.2486,4.637244829,8.845943122,3.065,-11.45854994,2.243950473,62.19481606 +202.96,50.4320464,-2.571228886,50.2179,4.654625784,8.845943002,3.075,-11.50287316,2.166375654,62.20234112 +202.97,50.43204682,-2.571227641,50.1871,4.668530557,8.845942882,3.0846875,-11.54583834,2.086911679,62.20986623 +202.98,50.43204724,-2.571226396,50.1562,4.672006742,8.846164798,3.093125,-11.58743657,2.005627876,62.21739129 +202.99,50.43204766,-2.571225151,50.1252,4.672006717,8.847052823,3.0996875,-11.62765901,1.922595176,62.2249164 +203,50.43204808,-2.571223906,50.0942,4.672006688,8.848384922,3.1046875,-11.66649741,1.837885887,62.23244146 +203.01,50.4320485,-2.57122266,50.0631,4.668530468,8.849272948,3.108125,-11.70394358,1.751573978,62.23996657 +203.02,50.43204892,-2.571221415,50.032,4.654625662,8.849494864,3.109375,-11.73998968,1.663734677,62.24749163 +203.03,50.43204934,-2.571220169,50.0009,4.637244663,8.84971678,3.1084375,-11.77462824,1.574444534,62.25501674 +203.04,50.43204975,-2.571218924,49.9698,4.637244649,8.850604805,3.1065625,-11.80785206,1.483781525,62.2625418 +203.05,50.43205017,-2.571217678,49.9388,4.654625617,8.851936905,3.105,-11.83965408,1.39182455,62.27006691 +203.06,50.43205059,-2.571216432,49.9077,4.668530378,8.852824931,3.103125,-11.87002778,1.298653934,62.27759196 +203.07,50.43205101,-2.571215186,49.8767,4.668530342,8.853046846,3.099375,-11.89896673,1.204350868,62.28511708 +203.08,50.43205143,-2.57121394,49.8457,4.654625519,8.853046724,3.093125,-11.92646492,1.10899757,62.29264213 +203.09,50.43205185,-2.571212694,49.8148,4.637244505,8.85326864,3.085,-11.95251657,1.012677234,62.30016725 +203.1,50.43205226,-2.571211448,49.784,4.637244483,8.854156667,3.0765625,-11.97711634,0.915473799,62.3076923 +203.11,50.43205268,-2.571210202,49.7533,4.651149257,8.85526673,3.0678125,-12.00025896,0.817472118,62.31521742 +203.12,50.4320531,-2.571208955,49.7226,4.651149253,8.855488646,3.0565625,-12.02193974,0.718757506,62.32274247 +203.13,50.43205352,-2.571207709,49.6921,4.637244462,8.855488526,3.0428125,-12.04215404,0.619416193,62.33026758 +203.14,50.43205393,-2.571206463,49.6618,4.63724444,8.856820626,3.0284375,-12.06089766,0.519534695,62.33779264 +203.15,50.43205435,-2.571205216,49.6315,4.651149189,8.8585968,3.013125,-12.07816673,0.419200216,62.34531775 +203.16,50.43205477,-2.571203969,49.6015,4.651149159,8.859040753,2.9965625,-12.09395762,0.318500134,62.35284281 +203.17,50.43205519,-2.571202722,49.5716,4.637244353,8.859040634,2.98,-12.10826701,0.217522338,62.36036787 +203.18,50.4320556,-2.571201476,49.5419,4.633768139,8.860150698,2.9625,-12.12109192,0.116354837,62.36789298 +203.19,50.43205602,-2.571200228,49.5123,4.637244322,8.861260763,2.9415625,-12.13242973,0.015085864,62.37541803 +203.2,50.43205644,-2.571198981,49.483,4.633768114,8.861038608,2.918125,-12.14227795,-0.086196229,62.38294315 +203.21,50.43205685,-2.571197734,49.454,4.633768085,8.86037238,2.895,-12.15063466,-0.18740315,62.3904682 +203.22,50.43205727,-2.571196487,49.4251,4.637244237,8.860372262,2.8715625,-12.15749801,-0.288446721,62.39799332 +203.23,50.43205769,-2.57119524,49.3965,4.630291817,8.861482328,2.84625,-12.16286668,-0.389238706,62.40551837 +203.24,50.4320581,-2.571193993,49.3682,4.619863222,8.863480541,2.82,-12.16673941,-0.489691271,62.41304348 +203.25,50.43205852,-2.571192745,49.3401,4.619863219,8.864812644,2.793125,-12.16911547,-0.589716811,62.42056854 +203.26,50.43205893,-2.571191497,49.3123,4.630291799,8.864812528,2.764375,-12.16999433,-0.68922812,62.42809365 +203.27,50.43205935,-2.57119025,49.2848,4.63724417,8.865034449,2.7334375,-12.16937588,-0.788138398,62.43561871 +203.28,50.43205977,-2.571189002,49.2576,4.630291749,8.86592248,2.7015625,-12.16726017,-0.886361469,62.44314382 +203.29,50.43206018,-2.571187754,49.2308,4.619863135,8.865922364,2.6696875,-12.16364768,-0.983811563,62.45066888 +203.3,50.4320606,-2.571186506,49.2042,4.61638692,8.86525614,2.6365625,-12.15853913,-1.080403768,62.45819399 +203.31,50.43206101,-2.571185259,49.178,4.616386911,8.866144173,2.60125,-12.15193562,-1.176053858,62.46571905 +203.32,50.43206143,-2.571184011,49.1522,4.616386903,8.868364426,2.565,-12.14383852,-1.270678411,62.47324416 +203.33,50.43206184,-2.571182762,49.1267,4.616386885,8.869474496,2.528125,-12.1342495,-1.364194863,62.48076922 +203.34,50.43206226,-2.571181514,49.1016,4.616386856,8.869474384,2.4896875,-12.12317061,-1.456521798,62.48829433 +203.35,50.43206267,-2.571180266,49.0769,4.616386828,8.869918345,2.45,-12.11060416,-1.547578543,62.49581939 +203.36,50.43206309,-2.571179017,49.0526,4.616386802,8.870584344,2.41,-12.09655271,-1.637285857,62.5033445 +203.37,50.4320635,-2.571177769,49.0287,4.616386782,8.87080627,2.3696875,-12.08101926,-1.725565361,62.51086955 +203.38,50.43206392,-2.57117652,49.0052,4.616386777,8.871028196,2.328125,-12.06400705,-1.812340162,62.51839467 +203.39,50.43206433,-2.571175272,48.9821,4.616386771,8.871916232,2.2846875,-12.04551954,-1.897534632,62.52591972 +203.4,50.43206475,-2.571174023,48.9595,4.616386753,8.873248343,2.2396875,-12.02556072,-1.9810744,62.53344484 +203.41,50.43206516,-2.571172774,48.9373,4.616386731,8.874136382,2.1934375,-12.00413468,-2.062886585,62.54096989 +203.42,50.43206558,-2.571171525,48.9156,4.616386716,8.874358311,2.1465625,-11.98124593,-2.142899969,62.548495 +203.43,50.43206599,-2.571170276,48.8944,4.616386709,8.874358203,2.1,-11.95689924,-2.221044651,62.55602006 +203.44,50.43206641,-2.571169027,48.8736,4.616386706,8.874580133,2.053125,-11.93109969,-2.297252622,62.56354517 +203.45,50.43206682,-2.571167778,48.8533,4.612910496,8.875468174,2.0046875,-11.90385268,-2.371457303,62.57107023 +203.46,50.43206724,-2.571166529,48.8335,4.602481886,8.876800288,1.955,-11.87516383,-2.443594064,62.57859534 +203.47,50.43206765,-2.571165279,48.8142,4.595529473,8.877688331,1.9046875,-11.84503925,-2.513599938,62.5861204 +203.48,50.43206806,-2.57116403,48.7954,4.599005655,8.877910265,1.853125,-11.81348515,-2.581413962,62.59364551 +203.49,50.43206848,-2.57116278,48.7771,4.599005651,8.878132198,1.8,-11.78050816,-2.64697695,62.60117057 +203.5,50.43206889,-2.571161531,48.7594,4.595529454,8.878798205,1.7465625,-11.74611511,-2.71023172,62.60869568 +203.51,50.4320693,-2.571160281,48.7422,4.599005635,8.879242177,1.6934375,-11.71031327,-2.771123096,62.61622074 +203.52,50.43206972,-2.571159031,48.7255,4.599005604,8.879242078,1.6396875,-11.67311003,-2.829598022,62.62374579 +203.53,50.43207013,-2.571157782,48.7094,4.595529379,8.880130124,1.585,-11.63451319,-2.885605564,62.6312709 +203.54,50.43207054,-2.571156532,48.6938,4.59900557,8.881462244,1.5296875,-11.59453082,-2.939096732,62.63879596 +203.55,50.43207096,-2.571155281,48.6788,4.599005582,8.881462145,1.473125,-11.55317129,-2.990025002,62.64632107 +203.56,50.43207137,-2.571154032,48.6643,4.595529386,8.881462048,1.415,-11.51044319,-3.038345913,62.65384613 +203.57,50.43207178,-2.571152782,48.6505,4.599005562,8.883016208,1.3565625,-11.46635546,-3.084017353,62.66137124 +203.58,50.4320722,-2.571151531,48.6372,4.595529351,8.884570368,1.2984375,-11.42091733,-3.126999501,62.6688963 +203.59,50.43207261,-2.571150281,48.6245,4.581624569,8.885014346,1.2396875,-11.37413831,-3.167254828,62.67642141 +203.6,50.43207302,-2.57114903,48.6124,4.581624571,8.885014252,1.18,-11.32602807,-3.204748269,62.68394647 +203.61,50.43207343,-2.57114778,48.6009,4.595529344,8.885014158,1.12,-11.27659677,-3.239447109,62.69147158 +203.62,50.43207385,-2.571146529,48.59,4.595529325,8.885236103,1.06,-11.22585465,-3.271321152,62.69899664 +203.63,50.43207426,-2.571145279,48.5797,4.578148336,8.886124158,1,-11.17381238,-3.300342496,62.70652175 +203.64,50.43207467,-2.571144028,48.57,4.567719751,8.887456287,0.9396875,-11.12048072,-3.32648593,62.71404681 +203.65,50.43207508,-2.571142777,48.5609,4.578148341,8.888344344,0.878125,-11.06587097,-3.349728593,62.72157192 +203.66,50.43207549,-2.571141526,48.5524,4.59552931,8.888788328,0.815,-11.00999435,-3.37005026,62.72909697 +203.67,50.43207591,-2.571140275,48.5446,4.595529294,8.889676385,0.751875,-10.95286266,-3.387433227,62.73662209 +203.68,50.43207632,-2.571139024,48.5374,4.578148308,8.89078648,0.69,-10.89448778,-3.401862252,62.74414714 +203.69,50.43207673,-2.571137772,48.5308,4.56424353,8.89100843,0.628125,-10.83488194,-3.413324789,62.75167226 +203.7,50.43207714,-2.571136521,48.5248,4.564243535,8.890786309,0.5646875,-10.77405755,-3.421810924,62.75919731 +203.71,50.43207755,-2.57113527,48.5195,4.578148302,8.891230298,0.5,-10.7120273,-3.427313095,62.76672242 +203.72,50.43207796,-2.571134018,48.5148,4.595529252,8.891896324,0.4353125,-10.64880416,-3.429826661,62.77424748 +203.73,50.43207838,-2.571132767,48.5108,4.595529243,8.892118277,0.3715625,-10.58440136,-3.429349387,62.78177259 +203.74,50.43207879,-2.571131515,48.5074,4.578148284,8.892340231,0.3084375,-10.51883235,-3.425881617,62.78929765 +203.75,50.4320792,-2.571130264,48.5046,4.564243522,8.893228296,0.2446875,-10.45211079,-3.419426445,62.79682276 +203.76,50.43207961,-2.571129012,48.5025,4.560767328,8.894560436,0.18,-10.38425058,-3.409989487,62.80434782 +203.77,50.43208002,-2.57112776,48.501,4.560767318,8.895448504,0.115,-10.315266,-3.397578992,62.81187293 +203.78,50.43208043,-2.571126508,48.5002,4.560767318,8.895670462,0.05,-10.24517138,-3.382205732,62.81939799 +203.79,50.43208084,-2.571125256,48.5,4.560767327,8.895892421,-0.0146875,-10.17398132,-3.363883114,62.8269231 +203.8,50.43208125,-2.571124004,48.5005,4.560767328,8.896780491,-0.0784375,-10.10171083,-3.342627182,62.83444816 +203.81,50.43208166,-2.571122752,48.5016,4.560767318,8.898112634,-0.141875,-10.02837486,-3.318456385,62.84197327 +203.82,50.43208207,-2.571121499,48.5033,4.560767313,8.899000706,-0.2065625,-9.953988785,-3.291391864,62.84949833 +203.83,50.43208248,-2.571120247,48.5057,4.560767321,8.899222669,-0.2715625,-9.878568116,-3.261457226,62.85702344 +203.84,50.43208289,-2.571118994,48.5088,4.560767335,8.899444634,-0.335,-9.802128613,-3.228678539,62.86454849 +203.85,50.4320833,-2.571117742,48.5124,4.560767338,8.900110671,-0.3984375,-9.724686262,-3.193084396,62.87207361 +203.86,50.43208371,-2.571116489,48.5167,4.560767333,8.900554673,-0.4634375,-9.646257278,-3.154705792,62.87959866 +203.87,50.43208412,-2.571115236,48.5217,4.560767336,8.900332566,-0.528125,-9.566857933,-3.113576303,62.88712372 +203.88,50.43208453,-2.571113984,48.5273,4.56076735,8.900554533,-0.59125,-9.486504842,-3.069731682,62.89464883 +203.89,50.43208494,-2.571112731,48.5335,4.560767354,8.901886684,-0.6534375,-9.405214793,-3.023210259,62.90217389 +203.9,50.43208535,-2.571111478,48.5404,4.560767351,8.903662909,-0.7153125,-9.323004803,-2.974052486,62.909699 +203.91,50.43208576,-2.571110225,48.5478,4.560767356,8.904995061,-0.778125,-9.239892004,-2.922301333,62.91722406 +203.92,50.43208617,-2.571108971,48.5559,4.560767371,8.904994996,-0.841875,-9.155893756,-2.868001894,62.92474917 +203.93,50.43208658,-2.571107718,48.5647,4.557291183,8.904106785,-0.904375,-9.071027591,-2.811201494,62.93227423 +203.94,50.43208699,-2.571106465,48.574,4.543386401,8.904328758,-0.965,-8.985311271,-2.751949693,62.93979934 +203.95,50.4320874,-2.571105212,48.584,4.526005433,8.906104987,-1.025,-8.898762673,-2.690298174,62.94732439 +203.96,50.4320878,-2.571103958,48.5945,4.526005448,8.907437145,-1.085,-8.811399845,-2.626300679,62.95484951 +203.97,50.43208821,-2.571102704,48.6057,4.543386422,8.907215047,-1.1453125,-8.723241063,-2.560012957,62.96237456 +203.98,50.43208862,-2.571101451,48.6174,4.557291189,8.906770914,-1.20625,-8.634304721,-2.491492935,62.96989968 +203.99,50.43208903,-2.571100197,48.6298,4.557291192,8.907659,-1.2665625,-8.544609381,-2.420800199,62.97742473 +204,50.43208944,-2.571098944,48.6428,4.543386439,8.909435233,-1.3246875,-8.454173837,-2.347996572,62.98494985 +204.01,50.43208985,-2.571097689,48.6563,4.526005493,8.910101285,-1.3815625,-8.36301694,-2.273145423,62.9924749 +204.02,50.43209025,-2.571096435,48.6704,4.526005506,8.909657155,-1.4384375,-8.271157653,-2.196312069,63.00000001 +204.03,50.43209066,-2.571095182,48.6851,4.543386483,8.910101172,-1.495,-8.178615286,-2.117563489,63.00752507 +204.04,50.43209107,-2.571093927,48.7003,4.553815079,8.911211298,-1.5515625,-8.085409091,-2.036968381,63.01505018 +204.05,50.43209148,-2.571092673,48.7161,4.543386515,8.911877353,-1.608125,-7.991558546,-1.954596989,63.02257524 +204.06,50.43209189,-2.571091419,48.7325,4.526005551,8.912543409,-1.663125,-7.897083249,-1.870521162,63.03010035 +204.07,50.43209229,-2.571090164,48.7494,4.526005555,8.913431502,-1.7165625,-7.802002966,-1.784814239,63.03762541 +204.08,50.4320927,-2.57108891,48.7668,4.539910348,8.914319596,-1.77,-7.706337463,-1.697550876,63.04515052 +204.09,50.43209311,-2.571087655,48.7848,4.53991037,8.914763617,-1.823125,-7.610106795,-1.608807276,63.05267558 +204.1,50.43209352,-2.5710864,48.8033,4.526005603,8.91454153,-1.8746875,-7.513331072,-1.518660732,63.06020069 +204.11,50.43209392,-2.571085146,48.8223,4.526005608,8.914763517,-1.925,-7.416030463,-1.427189911,63.06772575 +204.12,50.43209433,-2.571083891,48.8418,4.539910402,8.91587365,-1.975,-7.318225249,-1.334474568,63.07525086 +204.13,50.43209474,-2.571082636,48.8618,4.539910426,8.916761746,-2.025,-7.219935944,-1.240595548,63.08277591 +204.14,50.43209515,-2.571081381,48.8823,4.522529467,8.916983734,-2.0746875,-7.121183058,-1.145634669,63.09030103 +204.15,50.43209555,-2.571080126,48.9033,4.508624699,8.917205724,-2.123125,-7.021987161,-1.049674838,63.09782608 +204.16,50.43209596,-2.571078871,48.9248,4.508624717,8.918093823,-2.1696875,-6.922368995,-0.952799592,63.1053512 +204.17,50.43209636,-2.571077616,48.9467,4.519053316,8.919425997,-2.2146875,-6.822349357,-0.855093558,63.11287625 +204.18,50.43209677,-2.57107636,48.9691,4.526005714,8.920314098,-2.2584375,-6.72194916,-0.756641876,63.12040137 +204.19,50.43209718,-2.571075105,48.9919,4.522529535,8.92053609,-2.3015625,-6.621189375,-0.657530376,63.12792642 +204.2,50.43209758,-2.571073849,49.0151,4.522529561,8.920536045,-2.345,-6.520090973,-0.55784546,63.13545148 +204.21,50.43209799,-2.571072594,49.0388,4.526005773,8.920536001,-2.3878125,-6.418675151,-0.45767416,63.14297659 +204.22,50.4320984,-2.571071338,49.0629,4.519053391,8.920757995,-2.428125,-6.316963053,-0.357103738,63.15050165 +204.23,50.4320988,-2.571070083,49.0874,4.508624823,8.921646099,-2.4665625,-6.214975935,-0.256221856,63.15802676 +204.24,50.43209921,-2.571068827,49.1122,4.505148655,8.922978277,-2.505,-6.112735054,-0.155116635,63.16555181 +204.25,50.43209961,-2.571067571,49.1375,4.505148675,8.924088418,-2.543125,-6.010261839,-0.053876081,63.17307693 +204.26,50.43210002,-2.571066315,49.1631,4.508624887,8.92519856,-2.5796875,-5.907577604,0.047411398,63.18060198 +204.27,50.43210042,-2.571065059,49.1891,4.519053494,8.926308702,-2.615,-5.804703834,0.148657567,63.1881271 +204.28,50.43210083,-2.571063802,49.2154,4.526005901,8.926530699,-2.6496875,-5.701662072,0.249774075,63.19565215 +204.29,50.43210124,-2.571062546,49.2421,4.51905352,8.926308623,-2.6834375,-5.598473691,0.350672802,63.20317727 +204.3,50.43210164,-2.57106129,49.2691,4.508624954,8.926752656,-2.71625,-5.495160405,0.451265742,63.21070232 +204.31,50.43210205,-2.571060033,49.2964,4.505148787,8.927418728,-2.748125,-5.391743643,0.551465174,63.21822743 +204.32,50.43210245,-2.571058777,49.3241,4.505148807,8.927640727,-2.7778125,-5.28824512,0.651183723,63.22575249 +204.33,50.43210286,-2.57105752,49.352,4.505148818,8.927862727,-2.8046875,-5.184686379,0.750334413,63.2332776 +204.34,50.43210326,-2.571056264,49.3802,4.501672643,8.928750836,-2.8303125,-5.081089078,0.848830786,63.24080266 +204.35,50.43210367,-2.571055007,49.4086,4.491244085,8.930083018,-2.85625,-4.977474817,0.946587011,63.24832777 +204.36,50.43210407,-2.57105375,49.4373,4.484291717,8.930971128,-2.8815625,-4.873865255,1.043517719,63.25585283 +204.37,50.43210447,-2.571052493,49.4663,4.491244127,8.931193128,-2.9046875,-4.770282106,1.13953857,63.26337794 +204.38,50.43210488,-2.571051236,49.4954,4.501672736,8.931193093,-2.9265625,-4.666746856,1.234565626,63.270903 +204.39,50.43210528,-2.571049979,49.5248,4.505148953,8.931415095,-2.9484375,-4.563281221,1.328516208,63.27842811 +204.4,50.43210569,-2.571048722,49.5544,4.505148972,8.932303206,-2.969375,-4.4599068,1.42130827,63.28595317 +204.41,50.43210609,-2.571047465,49.5842,4.5016728,8.933413353,-2.988125,-4.356645195,1.51286091,63.29347828 +204.42,50.4321065,-2.571046207,49.6142,4.49124423,8.933635355,-3.005,-4.253517892,1.603094314,63.30100333 +204.43,50.4321069,-2.57104495,49.6443,4.484291845,8.933635322,-3.02125,-4.15054649,1.691929816,63.30852845 +204.44,50.4321073,-2.571043693,49.6746,4.48776806,8.93474547,-3.0365625,-4.047752533,1.779289894,63.3160535 +204.45,50.43210771,-2.571042435,49.7051,4.4877681,8.935855619,-3.049375,-3.945157392,1.86509846,63.32357862 +204.46,50.43210811,-2.571041177,49.7356,4.484291932,8.935855586,-3.06,-3.842782554,1.949280628,63.33110367 +204.47,50.43210851,-2.57103992,49.7663,4.487768143,8.936077589,-3.07,-3.740649389,2.031762944,63.33862879 +204.48,50.43210892,-2.571038662,49.797,4.48776817,8.937187738,-3.0796875,-3.638779269,2.112473561,63.34615384 +204.49,50.43210932,-2.571037404,49.8279,4.484291998,8.938075851,-3.0884375,-3.537193336,2.191342061,63.35367895 +204.5,50.43210972,-2.571036146,49.8588,4.487768209,8.938297855,-3.0959375,-3.435912962,2.268299689,63.36120401 +204.51,50.43211013,-2.571034888,49.8898,4.487768236,8.938519858,-3.1015625,-3.334959174,2.343279353,63.36872912 +204.52,50.43211053,-2.57103363,49.9209,4.484292065,8.939407972,-3.1046875,-3.234353171,2.41621562,63.37625418 +204.53,50.43211093,-2.571032372,49.9519,4.487768274,8.940740158,-3.1065625,-3.134115866,2.487044891,63.38377929 +204.54,50.43211134,-2.571031113,49.983,4.484292098,8.941628271,-3.1084375,-3.03426823,2.555705403,63.39130435 +204.55,50.43211174,-2.571029855,50.0141,4.466911141,8.941850275,-3.1096875,-2.934831118,2.622137339,63.3988294 +204.56,50.43211214,-2.571028596,50.0452,4.456482578,8.942072279,-3.109375,-2.835825272,2.686282714,63.40635452 +204.57,50.43211254,-2.571027338,50.0763,4.466911196,8.942960393,-3.1065625,-2.737271374,2.748085666,63.41387957 +204.58,50.43211294,-2.571026079,50.1074,4.484292191,8.944292579,-3.10125,-2.639190052,2.807492165,63.42140469 +204.59,50.43211335,-2.57102482,50.1383,4.484292198,8.944958656,-3.095,-2.541601761,2.864450529,63.42892974 +204.6,50.43211375,-2.571023561,50.1693,4.466911249,8.94451455,-3.0884375,-2.444526839,2.918911085,63.43645485 +204.61,50.43211415,-2.571022302,50.2001,4.456482701,8.944070445,-3.08125,-2.347985628,2.970826275,63.44397991 +204.62,50.43211455,-2.571021044,50.2309,4.466911306,8.944514485,-3.073125,-2.251998238,3.020150836,63.45150502 +204.63,50.43211495,-2.571019784,50.2616,4.484292301,8.945402598,-3.0628125,-2.156584722,3.066841797,63.45903008 +204.64,50.43211536,-2.571018526,50.2922,4.484292329,8.946512747,-3.05,-2.06176502,3.11085842,63.46655519 +204.65,50.43211576,-2.571017266,50.3226,4.466911369,8.947844932,-3.0365625,-1.967558955,3.152162375,63.47408025 +204.66,50.43211616,-2.571016007,50.3529,4.453006602,8.948733044,-3.023125,-1.873986124,3.190717564,63.48160536 +204.67,50.43211656,-2.571014747,50.3831,4.449530434,8.948955047,-3.0078125,-1.781066178,3.226490356,63.48913042 +204.68,50.43211696,-2.571013488,50.4131,4.449530453,8.948955014,-2.9896875,-1.688818426,3.259449639,63.49665553 +204.69,50.43211736,-2.571012228,50.4429,4.453006666,8.949177017,-2.97,-1.597262234,3.28956665,63.50418059 +204.7,50.43211776,-2.571010969,50.4725,4.466911478,8.949843092,-2.95,-1.506416624,3.31681509,63.5117057 +204.71,50.43211816,-2.571009709,50.5019,4.484292477,8.95028713,-2.9296875,-1.416300562,3.341171239,63.51923075 +204.72,50.43211857,-2.571008449,50.5311,4.484292496,8.950287095,-2.908125,-1.326932954,3.362613841,63.52675587 +204.73,50.43211897,-2.57100719,50.5601,4.466911549,8.951397242,-2.8846875,-1.238332422,3.381124159,63.53428092 +204.74,50.43211937,-2.57100593,50.5888,4.453006785,8.95361757,-2.8596875,-1.150517473,3.396686094,63.54180604 +204.75,50.43211977,-2.571004669,50.6173,4.449530596,8.954505681,-2.8334375,-1.063506383,3.409286066,63.54933109 +204.76,50.43212017,-2.571003409,50.6455,4.44953062,8.953839536,-2.80625,-0.977317431,3.418913132,63.55685621 +204.77,50.43212057,-2.571002149,50.6734,4.449530649,8.953839499,-2.778125,-0.891968549,3.425558813,63.56438126 +204.78,50.43212097,-2.571000889,50.7011,4.449530664,8.954949643,-2.748125,-0.807477557,3.429217377,63.57190637 +204.79,50.43212137,-2.570999628,50.7284,4.449530679,8.955837752,-2.7165625,-0.723862159,3.429885561,63.57943143 +204.8,50.43212177,-2.570998368,50.7554,4.449530696,8.956059751,-2.685,-0.641139773,3.427562904,63.58695654 +204.81,50.43212217,-2.570997107,50.7821,4.449530713,8.95628175,-2.653125,-0.559327645,3.422251299,63.5944816 +204.82,50.43212257,-2.570995847,50.8085,4.449530733,8.957169857,-2.6196875,-0.478442906,3.4139555,63.60200671 +204.83,50.43212297,-2.570994586,50.8345,4.449530752,8.95828,-2.5846875,-0.39850246,3.40268267,63.60953177 +204.84,50.43212337,-2.570993325,50.8602,4.446054572,8.958501996,-2.548125,-0.319522978,3.388442607,63.61705688 +204.85,50.43212377,-2.570992064,50.8855,4.432149809,8.958501956,-2.5096875,-0.241520962,3.371247799,63.62458194 +204.86,50.43212417,-2.570990804,50.9104,4.414768852,8.959612098,-2.47,-0.164512627,3.351113203,63.63210705 +204.87,50.43212456,-2.570989542,50.9349,4.414768869,8.96072224,-2.43,-0.088514187,3.328056407,63.63963211 +204.88,50.43212496,-2.570988281,50.959,4.432149861,8.960500162,-2.39,-0.013541399,3.302097466,63.64715722 +204.89,50.43212536,-2.57098702,50.9827,4.446054659,8.960056047,-2.3496875,0.060389981,3.273259068,63.65468227 +204.9,50.43212576,-2.570985759,51.006,4.449530874,8.96094415,-2.3078125,0.133264597,3.241566366,63.66220733 +204.91,50.43212616,-2.570984498,51.0289,4.44953089,8.962942434,-2.263125,0.205067153,3.207046919,63.66973244 +204.92,50.43212656,-2.570983236,51.0513,4.446054707,8.964274608,-2.216875,0.27578275,3.169730923,63.6772575 +204.93,50.43212696,-2.570981974,51.0732,4.43214994,8.964274564,-2.1715625,0.345396549,3.129650806,63.68478261 +204.94,50.43212736,-2.570980713,51.0947,4.414768973,8.964496555,-2.1265625,0.413893997,3.086841634,63.69230767 +204.95,50.43212775,-2.570979451,51.1158,4.414768986,8.965606691,-2.079375,0.481260885,3.041340706,63.69983278 +204.96,50.43212815,-2.570978189,51.1363,4.432149985,8.96649479,-2.03,0.54748306,2.993187672,63.70735784 +204.97,50.43212855,-2.570976927,51.1564,4.442578588,8.966494742,-1.98,0.612546715,2.942424528,63.71488295 +204.98,50.43212895,-2.570975665,51.1759,4.43215001,8.965828585,-1.9296875,0.676438213,2.889095564,63.72240801 +204.99,50.43212935,-2.570974403,51.195,4.414769046,8.965606501,-1.8784375,0.739144318,2.833247248,63.72993312 +205,50.43212974,-2.570973142,51.2135,4.414769066,8.966938671,-1.8265625,0.800651853,2.77492828,63.73745817 +205.01,50.43213014,-2.570971879,51.2315,4.432150061,8.968936948,-1.775,0.860947983,2.71418954,63.74498329 +205.02,50.43213054,-2.570970617,51.249,4.442578656,8.970047079,-1.723125,0.920020161,2.651084026,63.75250834 +205.03,50.43213094,-2.570969354,51.266,4.432150074,8.970269064,-1.6696875,0.977856011,2.585666684,63.76003346 +205.04,50.43213134,-2.570968092,51.2824,4.414769106,8.970269012,-1.6146875,1.034443443,2.517994639,63.76755851 +205.05,50.43213173,-2.570966829,51.2983,4.411292921,8.970490996,-1.558125,1.089770654,2.448126848,63.77508363 +205.06,50.43213213,-2.570965567,51.3136,4.414769126,8.971157051,-1.5,1.143826128,2.376124216,63.78260868 +205.07,50.43213253,-2.570964304,51.3283,4.411292944,8.97160107,-1.441875,1.19659852,2.302049654,63.79013379 +205.08,50.43213292,-2.570963041,51.3424,4.411292961,8.971601014,-1.3853125,1.24807683,2.225967562,63.79765885 +205.09,50.43213332,-2.570961779,51.356,4.414769167,8.972489104,-1.3296875,1.298250343,2.147944461,63.80518396 +205.1,50.43213372,-2.570960516,51.369,4.411292973,8.974043302,-1.2728125,1.347108517,2.068048304,63.81270902 +205.11,50.43213411,-2.570959252,51.3815,4.411292978,8.974709353,-1.213125,1.394641153,1.98634882,63.82023413 +205.12,50.43213451,-2.57095799,51.3933,4.414769187,8.974931331,-1.1515625,1.440838396,1.902917169,63.82775919 +205.13,50.43213491,-2.570956726,51.4045,4.411293005,8.975153308,-1.0903125,1.485690506,1.817826119,63.8352843 +205.14,50.4321353,-2.570955463,51.4151,4.411293013,8.974931212,-1.03,1.529188202,1.73114998,63.84280936 +205.15,50.4321357,-2.5709542,51.4251,4.41476921,8.975375224,-0.97,1.571322372,1.642964155,63.85033447 +205.16,50.4321361,-2.570952937,51.4345,4.407816819,8.977373489,-0.9096875,1.612084194,1.553345706,63.85785953 +205.17,50.43213649,-2.570951673,51.4433,4.397388238,8.979371753,-0.848125,1.65146513,1.462372728,63.86538464 +205.18,50.43213689,-2.570950409,51.4515,4.397388244,8.979593726,-0.785,1.689457045,1.370124461,63.87290969 +205.19,50.43213728,-2.570949145,51.459,4.407816837,8.978705517,-0.7215625,1.726051916,1.276681519,63.88043481 +205.2,50.43213768,-2.570947882,51.4659,4.414769242,8.978705452,-0.6584375,1.761242125,1.182125205,63.88795986 +205.21,50.43213808,-2.570946618,51.4722,4.407816869,8.979815567,-0.595,1.795020393,1.08653814,63.89548498 +205.22,50.43213847,-2.570945354,51.4778,4.397388292,8.980703645,-0.5315625,1.82737956,0.990003518,63.90301003 +205.23,50.43213887,-2.57094409,51.4828,4.393912086,8.980925614,-0.4684375,1.858312921,0.892605678,63.91053515 +205.24,50.43213926,-2.570942826,51.4872,4.393912072,8.981147582,-0.405,1.887814002,0.794429417,63.9180602 +205.25,50.43213966,-2.570941562,51.4909,4.393912081,8.982035658,-0.3415625,1.915876673,0.69556045,63.92558526 +205.26,50.43214005,-2.570940298,51.494,4.393912099,8.983145769,-0.2784375,1.942495089,0.596084893,63.93311037 +205.27,50.43214045,-2.570939033,51.4965,4.393912099,8.983367734,-0.2146875,1.967663578,0.496089548,63.94063543 +205.28,50.43214084,-2.570937769,51.4983,4.393912087,8.983367662,-0.1496875,1.991376983,0.39566162,63.94816054 +205.29,50.43214124,-2.570936505,51.4995,4.393912082,8.984477771,-0.08375,2.013630377,0.294888657,63.95568559 +205.3,50.43214163,-2.57093524,51.5,4.39043589,8.985587878,-0.0184375,2.034419005,0.193858551,63.96321071 +205.31,50.43214203,-2.570933975,51.4998,4.380007307,8.985587803,0.045,2.053738626,0.092659422,63.97073576 +205.32,50.43214242,-2.570932711,51.4991,4.373054916,8.985809764,0.1084375,2.071585115,-0.008620494,63.97826088 +205.33,50.43214281,-2.570931446,51.4977,4.380007308,8.986919869,0.17375,2.087954863,-0.109892961,63.98578593 +205.34,50.43214321,-2.570930181,51.4956,4.390435895,8.987807937,0.239375,2.102844318,-0.211069573,63.99331105 +205.35,50.4321436,-2.570928916,51.4929,4.390435887,8.988029895,0.3034375,2.116250441,-0.312062093,64.0008361 +205.36,50.432144,-2.570927651,51.4895,4.38000729,8.988029815,0.3665625,2.128170485,-0.412782516,64.00836121 +205.37,50.43214439,-2.570926386,51.4856,4.373054899,8.988251772,0.43,2.138601812,-0.513143007,64.01588627 +205.38,50.43214478,-2.570925121,51.4809,4.376531099,8.989139836,0.4934375,2.147542417,-0.613056017,64.02341138 +205.39,50.43214518,-2.570923856,51.4757,4.376531096,8.990471971,0.5565625,2.154990295,-0.712434401,64.03093644 +205.4,50.43214557,-2.57092259,51.4698,4.373054889,8.991360034,0.6203125,2.160943957,-0.811191584,64.03846155 +205.41,50.43214596,-2.570921325,51.4633,4.376531077,8.991581987,0.6846875,2.165402199,-0.909241336,64.04598661 +205.42,50.43214636,-2.570920059,51.4561,4.376531077,8.991803939,0.748125,2.16836399,-1.006498228,64.05351172 +205.43,50.43214675,-2.570918794,51.4483,4.373054882,8.992691999,0.8096875,2.169828756,-1.102877464,64.06103678 +205.44,50.43214714,-2.570917528,51.4399,4.376531075,8.99402413,0.8703125,2.169796212,-1.198294991,64.06856189 +205.45,50.43214754,-2.570916262,51.4309,4.376531069,8.994912187,0.931875,2.1682663,-1.292667557,64.07608695 +205.46,50.43214793,-2.570914996,51.4213,4.373054864,8.995134135,0.9946875,2.165239479,-1.385912943,64.08361206 +205.47,50.43214832,-2.57091373,51.411,4.37653105,8.995134046,1.0565625,2.160716206,-1.477949732,64.09113711 +205.48,50.43214872,-2.570912464,51.4001,4.37305485,8.995133957,1.11625,2.154697571,-1.568697767,64.09866223 +205.49,50.43214911,-2.570911198,51.3887,4.359150072,8.995133867,1.175,2.147184719,-1.658077808,64.10618728 +205.5,50.4321495,-2.570909932,51.3766,4.359150071,8.995355812,1.23375,2.138179312,-1.746012047,64.1137124 +205.51,50.43214989,-2.570908666,51.364,4.37305484,8.996243865,1.293125,2.127683127,-1.832423708,64.12123745 +205.52,50.43215029,-2.5709074,51.3508,4.373054822,8.997575989,1.353125,2.115698454,-1.917237505,64.12876257 +205.53,50.43215068,-2.570906133,51.3369,4.355673826,8.99846404,1.41125,2.102227758,-2.00037941,64.13628762 +205.54,50.43215107,-2.570904867,51.3225,4.34524522,8.998685982,1.4665625,2.087273846,-2.081776946,64.14381273 +205.55,50.43215146,-2.5709036,51.3076,4.355673795,8.998907923,1.521875,2.070839869,-2.161359179,64.15133779 +205.56,50.43215185,-2.570902334,51.2921,4.373054772,8.999795972,1.5784375,2.052929209,-2.239056668,64.1588629 +205.57,50.43215225,-2.570901067,51.276,4.373054768,9.001128092,1.6346875,2.033545645,-2.314801631,64.16638796 +205.58,50.43215264,-2.5708998,51.2594,4.355673776,9.00201614,1.6896875,2.012693247,-2.388528064,64.17391301 +205.59,50.43215303,-2.570898533,51.2422,4.341768979,9.002238078,1.7434375,1.990376312,-2.460171681,64.18143813 +205.6,50.43215342,-2.570897266,51.2245,4.338292771,9.002460015,1.79625,1.966599538,-2.529669972,64.18896318 +205.61,50.43215381,-2.570895999,51.2063,4.341768955,9.00334806,1.8484375,1.941367851,-2.596962375,64.1964883 +205.62,50.4321542,-2.570894732,51.1875,4.355673726,9.004458141,1.8996875,1.914686582,-2.661990163,64.20401335 +205.63,50.43215459,-2.570893464,51.1683,4.373054689,9.00445804,1.95,1.88656123,-2.724696727,64.21153847 +205.64,50.43215499,-2.570892197,51.1485,4.373054672,9.003569792,2,1.856997753,-2.785027235,64.21906352 +205.65,50.43215538,-2.57089093,51.1283,4.355673682,9.003791726,2.049375,1.826002226,-2.842929203,64.22658863 +205.66,50.43215577,-2.570889663,51.1075,4.341768898,9.005789949,2.096875,1.793581238,-2.898352041,64.23411369 +205.67,50.43215616,-2.570888395,51.0863,4.338292701,9.00778817,2.143125,1.759741434,-2.951247505,64.2416388 +205.68,50.43215655,-2.570887127,51.0647,4.338292686,9.008010102,2.19,1.724489976,-3.001569471,64.24916386 +205.69,50.43215694,-2.570885859,51.0425,4.338292661,9.007121852,2.23625,1.687834199,-3.049273995,64.25668897 +205.7,50.43215733,-2.570884592,51.0199,4.338292637,9.007121747,2.2796875,1.649781723,-3.094319478,64.26421403 +205.71,50.43215772,-2.570883324,50.9969,4.338292617,9.008231821,2.321875,1.610340569,-3.136666674,64.27173914 +205.72,50.43215811,-2.570882056,50.9735,4.338292595,9.009119859,2.365,1.56951893,-3.176278684,64.2792642 +205.73,50.4321585,-2.570880788,50.9496,4.338292574,9.009563824,2.4078125,1.527325287,-3.213120902,64.28678931 +205.74,50.43215889,-2.57087952,50.9253,4.338292562,9.010451861,2.448125,1.483768519,-3.247161241,64.29431437 +205.75,50.43215928,-2.570878252,50.9006,4.338292552,9.011561933,2.4865625,1.438857738,-3.278370023,64.30183948 +205.76,50.43215967,-2.570876983,50.8756,4.338292538,9.01178386,2.5246875,1.392602225,-3.306720032,64.30936453 +205.77,50.43216006,-2.570875715,50.8501,4.338292521,9.011561713,2.5615625,1.34501172,-3.332186516,64.31688965 +205.78,50.43216045,-2.570874447,50.8243,4.338292504,9.012005675,2.5965625,1.296096136,-3.354747245,64.3244147 +205.79,50.43216084,-2.570873178,50.7982,4.338292486,9.012893709,2.6315625,1.245865728,-3.374382623,64.33193982 +205.8,50.43216123,-2.57087191,50.7717,4.338292468,9.014003779,2.6665625,1.194330925,-3.391075462,64.33946487 +205.81,50.43216162,-2.570870641,50.7448,4.334816254,9.015335884,2.6996875,1.141502497,-3.404811266,64.34698999 +205.82,50.43216201,-2.570869372,50.7177,4.320911453,9.016223917,2.73125,1.087391504,-3.415578002,64.35451504 +205.83,50.4321624,-2.570868103,50.6902,4.303530463,9.016445841,2.7615625,1.032009231,-3.423366332,64.36204015 +205.84,50.43216278,-2.570866834,50.6624,4.303530455,9.016445729,2.7896875,0.975367254,-3.42816938,64.36956521 +205.85,50.43216317,-2.570865565,50.6344,4.320911417,9.016445615,2.8165625,0.917477432,-3.429983078,64.37709032 +205.86,50.43216356,-2.570864296,50.6061,4.33481617,9.016445501,2.8434375,0.858351797,-3.428805764,64.38461538 +205.87,50.43216395,-2.570863027,50.5775,4.338292332,9.016667423,2.8696875,0.798002726,-3.42463847,64.39214049 +205.88,50.43216434,-2.570861758,50.5487,4.334816112,9.017555453,2.8946875,0.736442765,-3.417484806,64.39966555 +205.89,50.43216473,-2.570860489,50.5196,4.320911319,9.018887555,2.918125,0.673684864,-3.407351073,64.40719066 +205.9,50.43216512,-2.570859219,50.4903,4.303530328,9.019775585,2.939375,0.609742087,-3.394246096,64.41471572 +205.91,50.4321655,-2.57085795,50.4608,4.303530299,9.019997506,2.9584375,0.54462784,-3.378181276,64.42224083 +205.92,50.43216589,-2.57085668,50.4311,4.320911249,9.020219427,2.9765625,0.478355588,-3.359170594,64.42976589 +205.93,50.43216628,-2.570855411,50.4013,4.331339819,9.020885419,2.995,0.410939254,-3.337230722,64.43729094 +205.94,50.43216667,-2.570854141,50.3712,4.320911218,9.021551412,3.013125,0.342392989,-3.312380683,64.44481605 +205.95,50.43216706,-2.570852871,50.341,4.30353022,9.022217404,3.029375,0.272730947,-3.284642249,64.45234111 +205.96,50.43216744,-2.570851602,50.3106,4.303530199,9.023327468,3.043125,0.201967795,-3.254039542,64.45986622 +205.97,50.43216783,-2.570850331,50.2801,4.317434965,9.023771424,3.0546875,0.130118314,-3.220599261,64.46739128 +205.98,50.43216822,-2.570849061,50.2495,4.317434954,9.023327234,3.065,0.05719746,-3.184350571,64.47491639 +205.99,50.43216861,-2.570847792,50.2188,4.30353016,9.023771189,3.075,-0.016779585,-3.14532504,64.48244145 +206,50.43216899,-2.570846521,50.188,4.300053944,9.024881253,3.0846875,-0.091797235,-3.103556818,64.48996656 +206.01,50.43216938,-2.570845251,50.1571,4.303530108,9.025547245,3.0928125,-0.167839965,-3.059082173,64.49749162 +206.02,50.43216977,-2.570843981,50.1261,4.300053883,9.026213236,3.098125,-0.244891787,-3.011940007,64.50501673 +206.03,50.43217015,-2.57084271,50.0951,4.30005386,9.026879227,3.1015625,-0.32293666,-2.962171346,64.51254179 +206.04,50.43217054,-2.57084144,50.0641,4.303530035,9.027101146,3.105,-0.401958255,-2.909819677,64.5200669 +206.05,50.43217093,-2.570840169,50.033,4.300053819,9.027323064,3.108125,-0.481940126,-2.854930549,64.52759196 +206.06,50.43217131,-2.570838899,50.0019,4.300053798,9.028211091,3.1096875,-0.562865545,-2.79755192,64.53511707 +206.07,50.4321717,-2.570837628,49.9708,4.303529973,9.02954319,3.1096875,-0.644717608,-2.737733808,64.54264212 +206.08,50.43217209,-2.570836357,49.9397,4.296577561,9.030431218,3.108125,-0.727479184,-2.675528296,64.55016724 +206.09,50.43217247,-2.570835086,49.9086,4.286148955,9.030653137,3.1046875,-0.811133027,-2.6109897,64.55769229 +206.1,50.43217286,-2.570833815,49.8776,4.286148943,9.03065302,3.0996875,-0.895661663,-2.544174284,64.56521741 +206.11,50.43217324,-2.570832544,49.8466,4.296577521,9.030874938,3.093125,-0.981047443,-2.475140318,64.57274246 +206.12,50.43217363,-2.570831273,49.8157,4.303529892,9.031762965,3.0846875,-1.067272492,-2.403947963,64.58026757 +206.13,50.43217402,-2.570830002,49.7849,4.296577469,9.032873029,3.075,-1.154318876,-2.330659384,64.58779263 +206.14,50.4321744,-2.57082873,49.7542,4.286148853,9.033094949,3.065,-1.242168432,-2.25533841,64.59531774 +206.15,50.43217479,-2.570827459,49.7236,4.282672634,9.033094833,3.055,-1.330802711,-2.178050701,64.6028428 +206.16,50.43217517,-2.570826188,49.6931,4.282672614,9.034204897,3.044375,-1.420203206,-2.098863751,64.61036791 +206.17,50.43217556,-2.570824916,49.6627,4.282672594,9.035314961,3.03125,-1.510351355,-2.017846544,64.61789297 +206.18,50.43217594,-2.570823644,49.6324,4.282672574,9.035314844,3.0146875,-1.601228305,-1.935069785,64.62541808 +206.19,50.43217633,-2.570822373,49.6024,4.282672554,9.035536764,2.996875,-1.692814978,-1.85060555,64.63294314 +206.2,50.43217671,-2.570821101,49.5725,4.282672534,9.03664683,2.98,-1.785092352,-1.764527579,64.64046825 +206.21,50.4321771,-2.570819829,49.5428,4.282672515,9.037534859,2.9628125,-1.878041118,-1.676910931,64.64799331 +206.22,50.43217748,-2.570818557,49.5132,4.282672495,9.03775678,2.9428125,-1.971641853,-1.587831979,64.65551842 +206.23,50.43217787,-2.570817285,49.4839,4.282672478,9.037756665,2.9196875,-2.065875018,-1.497368475,64.66304348 +206.24,50.43217825,-2.570816013,49.4548,4.28267247,9.037756551,2.8953125,-2.160720904,-1.405599143,64.67056859 +206.25,50.43217864,-2.570814741,49.426,4.282672468,9.037978473,2.8715625,-2.256159802,-1.312604196,64.67809364 +206.26,50.43217902,-2.570813469,49.3974,4.282672454,9.03908854,2.848125,-2.352171658,-1.218464595,64.68561876 +206.27,50.43217941,-2.570812197,49.369,4.282672419,9.041086751,2.8228125,-2.448736532,-1.123262443,64.69314381 +206.28,50.43217979,-2.570810924,49.3409,4.27919619,9.042418854,2.7946875,-2.5458342,-1.02708082,64.70066887 +206.29,50.43218018,-2.570809651,49.3131,4.268767581,9.042196705,2.7646875,-2.643444321,-0.930003607,64.70819398 +206.3,50.43218056,-2.570808379,49.2856,4.261815172,9.041530484,2.7334375,-2.741546671,-0.832115372,64.71571904 +206.31,50.43218094,-2.570807106,49.2584,4.265291349,9.041530373,2.7015625,-2.840120622,-0.733501543,64.72324415 +206.32,50.43218133,-2.570805834,49.2316,4.265291331,9.042418407,2.6696875,-2.939145605,-0.634248065,64.73076921 +206.33,50.43218171,-2.570804561,49.205,4.261815121,9.043750514,2.6365625,-3.038601051,-0.534441509,64.73829432 +206.34,50.43218209,-2.570803288,49.1788,4.265291308,9.044638548,2.60125,-3.138466048,-0.434168911,64.74581938 +206.35,50.43218248,-2.570802015,49.153,4.265291302,9.044860474,2.565,-3.238719797,-0.333517759,64.75334449 +206.36,50.43218286,-2.570800742,49.1275,4.26181509,9.044860364,2.5284375,-3.339341441,-0.232575716,64.76086954 +206.37,50.43218324,-2.570799469,49.1024,4.26529126,9.045082291,2.49125,-3.44030984,-0.131430903,64.76839466 +206.38,50.43218363,-2.570798196,49.0777,4.265291241,9.045970328,2.453125,-3.541603966,-0.030171442,64.77591971 +206.39,50.43218401,-2.570796923,49.0533,4.261815032,9.047302437,2.413125,-3.643202618,0.071114261,64.78344483 +206.4,50.43218439,-2.570795649,49.0294,4.265291207,9.04841251,2.37125,-3.745084655,0.172338027,64.79096988 +206.41,50.43218478,-2.570794376,49.0059,4.26181499,9.049300547,2.3284375,-3.847228763,0.273411449,64.798495 +206.42,50.43218516,-2.570793102,48.9828,4.247910191,9.049744514,2.2846875,-3.949613629,0.374246521,64.80602005 +206.43,50.43218554,-2.570791828,48.9602,4.247910179,9.049522373,2.24,-4.052217822,0.474755178,64.81354516 +206.44,50.43218592,-2.570790555,48.938,4.261814954,9.049744305,2.195,-4.155019972,0.574849874,64.82107022 +206.45,50.43218631,-2.570789281,48.9163,4.261814951,9.050854382,2.1496875,-4.257998593,0.674443288,64.82859533 +206.46,50.43218669,-2.570788007,48.895,4.247910156,9.051742422,2.103125,-4.361132142,0.773448562,64.83612039 +206.47,50.43218707,-2.570786733,48.8742,4.247910131,9.051964356,2.0546875,-4.464399133,0.871779407,64.8436455 +206.48,50.43218745,-2.570785459,48.8539,4.261814892,9.051964255,2.005,-4.567778023,0.969350051,64.85117056 +206.49,50.43218784,-2.570784185,48.8341,4.261814884,9.051964154,1.955,-4.671247096,1.066075354,64.85869567 +206.5,50.43218822,-2.570782911,48.8148,4.2444339,9.052186089,1.905,-4.774784867,1.16187109,64.86622073 +206.51,50.4321886,-2.570781637,48.796,4.230529102,9.053074134,1.8546875,-4.878369677,1.256653607,64.87374584 +206.52,50.43218898,-2.570780363,48.7777,4.227052889,9.054184215,1.803125,-4.98197987,1.350340343,64.8812709 +206.53,50.43218936,-2.570779088,48.7599,4.23052907,9.054406154,1.75,-5.085593787,1.442849535,64.88879601 +206.54,50.43218974,-2.570777814,48.7427,4.244433842,9.054406057,1.69625,-5.189189885,1.534100513,64.89632106 +206.55,50.43219012,-2.57077654,48.726,4.261814816,9.055738176,1.641875,-5.292746449,1.624013805,64.90384618 +206.56,50.43219051,-2.570775265,48.7098,4.261814816,9.057736405,1.58625,-5.396241878,1.712510861,64.91137123 +206.57,50.43219089,-2.57077399,48.6943,4.244433833,9.058846489,1.53,-5.499654572,1.799514617,64.91889635 +206.58,50.43219127,-2.570772715,48.6792,4.230529038,9.058846395,1.4734375,-5.60296293,1.884949156,64.9264214 +206.59,50.43219165,-2.57077144,48.6648,4.227052829,9.058180194,1.41625,-5.706145353,1.968739993,64.93394651 +206.6,50.43219203,-2.570770165,48.6509,4.227052813,9.057958066,1.35875,-5.809180296,2.050814078,64.94147157 +206.61,50.43219241,-2.570768891,48.6376,4.227052798,9.059068155,1.30125,-5.912046216,2.131099846,64.94899668 +206.62,50.43219279,-2.570767615,48.6249,4.227052788,9.060178244,1.243125,-6.014721743,2.209527226,64.95652174 +206.63,50.43219317,-2.57076634,48.6127,4.227052782,9.060178155,1.183125,-6.117185332,2.286027863,64.9640468 +206.64,50.43219355,-2.570765065,48.6012,4.227052786,9.060400101,1.121875,-6.219415613,2.360535065,64.97157191 +206.65,50.43219393,-2.57076379,48.5903,4.227052797,9.061510193,1.061875,-6.321391215,2.432983802,64.97909696 +206.66,50.43219431,-2.570762514,48.58,4.227052795,9.06239825,1.0028125,-6.423090879,2.503310991,64.98662208 +206.67,50.43219469,-2.570761239,48.5702,4.227052773,9.0626202,0.9415625,-6.524493294,2.571455268,64.99414713 +206.68,50.43219507,-2.570759963,48.5611,4.227052752,9.06284215,0.878125,-6.62557743,2.63735716,65.00167225 +206.69,50.43219545,-2.570758688,48.5527,4.227052742,9.063508174,0.8153125,-6.726322032,2.700959257,65.0091973 +206.7,50.43219583,-2.570757412,48.5448,4.227052737,9.063952162,0.7534375,-6.826706128,2.762206039,65.01672242 +206.71,50.43219621,-2.570756136,48.5376,4.227052735,9.063730043,0.69125,-6.926708692,2.821044164,65.02424747 +206.72,50.43219659,-2.570754861,48.531,4.227052739,9.063951997,0.6284375,-7.026308925,2.877422294,65.03177258 +206.73,50.43219697,-2.570753585,48.525,4.227052749,9.065284132,0.565,-7.125486028,2.93129127,65.03929764 +206.74,50.43219735,-2.570752309,48.5197,4.227052752,9.06706034,0.5015625,-7.224219204,2.98260411,65.04682275 +206.75,50.43219773,-2.570751033,48.515,4.227052743,9.068392476,0.4384375,-7.322487883,3.031316122,65.05434781 +206.76,50.43219811,-2.570749756,48.5109,4.227052727,9.068614434,0.3746875,-7.420271553,3.077384736,65.06187292 +206.77,50.43219849,-2.57074848,48.5075,4.223576521,9.06839232,0.31,-7.51754976,3.120769845,65.06939798 +206.78,50.43219887,-2.570747204,48.5047,4.20967174,9.068836315,0.2453125,-7.614302221,3.161433577,65.07692309 +206.79,50.43219925,-2.570745927,48.5026,4.19229077,9.069724384,0.1815625,-7.710508768,3.199340465,65.08444815 +206.8,50.43219962,-2.570744651,48.5011,4.192290774,9.070612454,0.118125,-7.806149175,3.234457564,65.09197326 +206.81,50.4322,-2.570743374,48.5002,4.209671746,9.071056453,0.0534375,-7.901203618,3.266754106,65.09949832 +206.82,50.43220038,-2.570742097,48.5,4.223576529,9.070834344,-0.011875,-7.995652158,3.296201959,65.10702343 +206.83,50.43220076,-2.570740821,48.5005,4.22357654,9.071056308,-0.07625,-8.089475085,3.32277557,65.11454848 +206.84,50.43220114,-2.570739544,48.5015,4.209671768,9.071944381,-0.14,-8.182652805,3.346451618,65.1220736 +206.85,50.43220152,-2.570738267,48.5033,4.192290788,9.072166347,-0.20375,-8.275165894,3.367209478,65.12959865 +206.86,50.43220189,-2.57073699,48.5056,4.192290776,9.072166278,-0.268125,-8.366994986,3.385031101,65.13712377 +206.87,50.43220227,-2.570735714,48.5086,4.20619555,9.07327639,-0.3334375,-8.458120944,3.39990096,65.14464882 +206.88,50.43220265,-2.570734436,48.5123,4.206195552,9.074608539,-0.398125,-8.548524746,3.411806049,65.15217394 +206.89,50.43220303,-2.570733159,48.5166,4.192290784,9.07527458,-0.4615625,-8.638187427,3.420735998,65.15969899 +206.9,50.4322034,-2.570731882,48.5215,4.192290801,9.075718587,-0.525,-8.727090366,3.426682956,65.1672241 +206.91,50.43220378,-2.570730604,48.5271,4.206195594,9.075718522,-0.5884375,-8.815214884,3.429641824,65.17474916 +206.92,50.43220416,-2.570729327,48.5333,4.206195598,9.075718459,-0.6515625,-8.902542705,3.429610025,65.18227427 +206.93,50.43220454,-2.57072805,48.5401,4.192290814,9.076828577,-0.715,-8.989055493,3.426587558,65.18979933 +206.94,50.43220491,-2.570726772,48.5476,4.188814611,9.077938696,-0.778125,-9.074735258,3.420577002,65.19732444 +206.95,50.43220529,-2.570725494,48.5557,4.192290803,9.077938635,-0.8396875,-9.159564066,3.411583684,65.2048495 +206.96,50.43220567,-2.570724217,48.5644,4.188814613,9.07816061,-0.9003125,-9.243524155,3.399615398,65.21237455 +206.97,50.43220604,-2.570722939,48.5737,4.188814629,9.079270731,-0.9615625,-9.326598051,3.384682628,65.21989967 +206.98,50.43220642,-2.570721661,48.5836,4.192290844,9.080158817,-1.0234375,-9.408768392,3.366798324,65.22742472 +206.99,50.4322068,-2.570720383,48.5942,4.188814663,9.080380796,-1.0846875,-9.490018047,3.345978183,65.23494984 +207,50.43220717,-2.570719105,48.6053,4.188814664,9.080602775,-1.145,-9.57033,3.322240255,65.24247489 +207.01,50.43220755,-2.570717827,48.6171,4.192290856,9.081490863,-1.205,-9.649687519,3.295605281,65.25 +207.02,50.43220793,-2.570716549,48.6294,4.188814667,9.082600989,-1.2646875,-9.72807399,3.266096522,65.25752506 +207.03,50.4322083,-2.57071527,48.6424,4.188814678,9.082822971,-1.323125,-9.805473082,3.233739647,65.26505017 +207.04,50.43220868,-2.570713992,48.6559,4.19229088,9.082600882,-1.38,-9.881868582,3.198562904,65.27257523 +207.05,50.43220906,-2.570712714,48.67,4.185338501,9.083044902,-1.436875,-9.95724456,3.160596944,65.28010034 +207.06,50.43220943,-2.570711435,48.6846,4.174909937,9.083932994,-1.4946875,-10.03158532,3.119874943,65.2876254 +207.07,50.43220981,-2.570710157,48.6999,4.171433759,9.085043124,-1.5515625,-10.10487527,3.076432366,65.29515051 +207.08,50.43221018,-2.570708878,48.7157,4.171433762,9.086375291,-1.60625,-10.17709912,3.030307086,65.30267557 +207.09,50.43221056,-2.570707599,48.732,4.171433762,9.087041349,-1.6603125,-10.24824186,2.981539325,65.31020068 +207.1,50.43221093,-2.57070632,48.7489,4.171433771,9.086375193,-1.7146875,-10.31828853,2.930171596,65.31772574 +207.11,50.43221131,-2.570705041,48.7663,4.171433785,9.085487003,-1.768125,-10.38722452,2.876248705,65.32525085 +207.12,50.43221168,-2.570703763,48.7843,4.171433797,9.086375101,-1.82,-10.45503551,2.819817747,65.3327759 +207.13,50.43221206,-2.570702484,48.8027,4.171433819,9.088595414,-1.8715625,-10.52170722,2.760927828,65.34030102 +207.14,50.43221243,-2.570701204,48.8217,4.171433845,9.089483513,-1.9234375,-10.58722587,2.699630339,65.34782607 +207.15,50.43221281,-2.570699925,48.8412,4.171433855,9.088817361,-1.9746875,-10.65157762,2.635978739,65.35535119 +207.16,50.43221318,-2.570698646,48.8612,4.171433858,9.088817318,-2.0246875,-10.7147492,2.570028489,65.36287624 +207.17,50.43221356,-2.570697367,48.8817,4.171433865,9.089927455,-2.073125,-10.77672724,2.501837172,65.37040136 +207.18,50.43221393,-2.570696087,48.9027,4.171433872,9.091037592,-2.12,-10.83749893,2.431464204,65.37792641 +207.19,50.43221431,-2.570694808,48.9241,4.17143388,9.091925694,-2.1665625,-10.89705153,2.358971005,65.38545152 +207.2,50.43221468,-2.570693528,48.946,4.167957701,9.092369725,-2.213125,-10.95537262,2.284420716,65.39297658 +207.21,50.43221506,-2.570692248,48.9684,4.157529146,9.09214765,-2.258125,-11.01244999,2.207878368,65.40050169 +207.22,50.43221543,-2.570690969,48.9912,4.150576786,9.092369647,-2.30125,-11.06827172,2.129410709,65.40802675 +207.23,50.4322158,-2.570689689,49.0144,4.15752919,9.093479787,-2.3434375,-11.12282618,2.049086209,65.41555186 +207.24,50.43221618,-2.570688409,49.0381,4.16795778,9.094367893,-2.385,-11.17610197,1.966974825,65.42307692 +207.25,50.43221655,-2.570687129,49.0621,4.167957789,9.094811927,-2.42625,-11.22808798,1.883148292,65.43060203 +207.26,50.43221693,-2.570685849,49.0866,4.157529215,9.095700034,-2.4665625,-11.27877332,1.797679548,65.43812709 +207.27,50.4322173,-2.570684569,49.1115,4.150576843,9.096810177,-2.5046875,-11.32814738,1.710643248,65.4456522 +207.28,50.43221767,-2.570683288,49.1367,4.154053066,9.096810142,-2.5415625,-11.37619992,1.622115195,65.45317726 +207.29,50.43221805,-2.570682008,49.1623,4.154053092,9.095921963,-2.5784375,-11.42292091,1.532172681,65.46070237 +207.3,50.43221842,-2.570680728,49.1883,4.150576914,9.095921928,-2.6146875,-11.46830048,1.44089403,65.46822742 +207.31,50.43221879,-2.570679448,49.2146,4.154053118,9.097032074,-2.6496875,-11.51232925,1.34835894,65.47575248 +207.32,50.43221917,-2.570678167,49.2413,4.154053122,9.09814222,-2.683125,-11.55499805,1.254648083,65.48327759 +207.33,50.43221954,-2.570676887,49.2683,4.150576936,9.09903033,-2.7146875,-11.59629788,1.159843106,65.49080265 +207.34,50.43221991,-2.570675606,49.2956,4.154053152,9.099696405,-2.745,-11.6362202,1.064026743,65.49832776 +207.35,50.43222029,-2.570674325,49.3232,4.150576992,9.10036248,-2.7746875,-11.6747566,0.967282533,65.50585282 +207.36,50.43222066,-2.570673045,49.3511,4.13667225,9.101472627,-2.803125,-11.71189905,0.869694872,65.51337793 +207.37,50.43222103,-2.570671763,49.3793,4.136672269,9.101694632,-2.83,-11.74763981,0.771348786,65.52090299 +207.38,50.4322214,-2.570670482,49.4077,4.15057705,9.100584422,-2.8565625,-11.78197144,0.672330105,65.5284281 +207.39,50.43222178,-2.570669202,49.4364,4.150577058,9.100806427,-2.8828125,-11.81488672,0.572725117,65.53595316 +207.4,50.43222215,-2.570667921,49.4654,4.133196101,9.10280472,-2.90625,-11.84637877,0.472620681,65.54347827 +207.41,50.43222252,-2.570666639,49.4946,4.122767538,9.103692834,-2.9265625,-11.87644106,0.372104174,65.55100332 +207.42,50.43222289,-2.570665358,49.5239,4.133196149,9.103026697,-2.946875,-11.90506735,0.271263144,65.55852844 +207.43,50.43222326,-2.570664077,49.5535,4.150577146,9.103248703,-2.968125,-11.93225157,0.170185539,65.56605349 +207.44,50.43222364,-2.570662796,49.5833,4.150577164,9.105246997,-2.9878125,-11.95798803,0.068959596,65.57357861 +207.45,50.43222401,-2.570661514,49.6133,4.133196207,9.107245292,-3.0046875,-11.98227147,-0.032326508,65.58110366 +207.46,50.43222438,-2.570660232,49.6434,4.119291442,9.107467299,-3.02,-12.00509673,-0.133584422,65.58862878 +207.47,50.43222475,-2.57065895,49.6737,4.11581526,9.106579128,-3.0346875,-12.02645906,-0.234725854,65.59615383 +207.48,50.43222512,-2.570657669,49.7041,4.115815286,9.1065791,-3.048125,-12.04635399,-0.335662626,65.60367894 +207.49,50.43222549,-2.570656387,49.7347,4.119291515,9.107689252,-3.06,-12.06477739,-0.436306616,65.611204 +207.5,50.43222586,-2.570655105,49.7653,4.133196316,9.108577368,-3.07125,-12.08172543,-0.53657022,65.61872911 +207.51,50.43222623,-2.570653823,49.7961,4.150577304,9.108799377,-3.0815625,-12.09719448,-0.636365888,65.62625417 +207.52,50.43222661,-2.570652541,49.827,4.150577318,9.109021384,-3.089375,-12.11118142,-0.735606648,65.63377928 +207.53,50.43222698,-2.570651259,49.8579,4.133196357,9.1099095,-3.095,-12.12368324,-0.834205923,65.64130434 +207.54,50.43222735,-2.570649977,49.8889,4.119291603,9.111019653,-3.1,-12.13469744,-0.932077829,65.64882945 +207.55,50.43222772,-2.570648694,49.9199,4.115815441,9.111019626,-3.1046875,-12.1442216,-1.029136879,65.65635451 +207.56,50.43222809,-2.570647412,49.951,4.115815459,9.110131456,-3.108125,-12.15225378,-1.125298506,65.66387962 +207.57,50.43222846,-2.57064613,49.9821,4.115815468,9.110353464,-3.1096875,-12.15879232,-1.220478885,65.67140468 +207.58,50.43222883,-2.570644848,50.0132,4.115815482,9.112129725,-3.1096875,-12.16383584,-1.314594995,65.67892979 +207.59,50.4322292,-2.570643565,50.0443,4.115815498,9.113461914,-3.108125,-12.16738325,-1.407564732,65.68645484 +207.6,50.43222957,-2.570642282,50.0754,4.115815523,9.113461887,-3.1046875,-12.16943386,-1.499307077,65.69397996 +207.61,50.43222994,-2.570641,50.1064,4.115815561,9.113683896,-3.1,-12.16998728,-1.589741991,65.70150501 +207.62,50.43223031,-2.570639717,50.1374,4.115815592,9.114794049,-3.095,-12.16904328,-1.678790633,65.70903013 +207.63,50.43223068,-2.570638434,50.1683,4.115815603,9.115682165,-3.0896875,-12.16660213,-1.766375311,65.71655518 +207.64,50.43223105,-2.570637151,50.1992,4.11581561,9.11612621,-3.0828125,-12.16266431,-1.852419763,65.7240803 +207.65,50.43223142,-2.570635868,50.23,4.115815624,9.117014326,-3.073125,-12.15723072,-1.936848819,65.73160535 +207.66,50.43223179,-2.570634585,50.2607,4.115815642,9.118124478,-3.0615625,-12.15030234,-2.019588909,65.73913041 +207.67,50.43223216,-2.570633301,50.2912,4.112339474,9.118124451,-3.05,-12.14188078,-2.100567899,65.74665552 +207.68,50.43223253,-2.570632018,50.3217,4.098434723,9.11723628,-3.0378125,-12.13196775,-2.179715143,65.75418058 +207.69,50.4322329,-2.570630735,50.352,4.08105376,9.117236252,-3.023125,-12.12056526,-2.256961657,65.76170569 +207.7,50.43223326,-2.570629452,50.3822,4.081053771,9.118346404,-3.0065625,-12.10767572,-2.332240118,65.76923074 +207.71,50.43223363,-2.570628168,50.4121,4.098434771,9.119456555,-2.9896875,-12.09330187,-2.40548475,65.77675586 +207.72,50.432234,-2.570626885,50.442,4.112339575,9.120566706,-2.9715625,-12.07744663,-2.476631785,65.78428091 +207.73,50.43223437,-2.570625601,50.4716,4.115815791,9.121898892,-2.95125,-12.06011334,-2.545619169,65.79180603 +207.74,50.43223474,-2.570624317,50.501,4.112339622,9.122564971,-2.93,-12.04130572,-2.612386743,65.79933108 +207.75,50.43223511,-2.570623033,50.5302,4.098434859,9.121898835,-2.908125,-12.02102754,-2.676876294,65.8068562 +207.76,50.43223548,-2.570621749,50.5592,4.081053884,9.121010662,-2.8846875,-11.99928316,-2.739031558,65.81438125 +207.77,50.43223584,-2.570620466,50.5879,4.081053894,9.121898775,-2.86,-11.97607705,-2.798798332,65.82190636 +207.78,50.43223621,-2.570619182,50.6164,4.098434896,9.124119104,-2.8346875,-11.95141402,-2.856124536,65.82943142 +207.79,50.43223658,-2.570617897,50.6446,4.108863509,9.125007217,-2.808125,-11.92529935,-2.910960092,65.83695653 +207.8,50.43223695,-2.570616613,50.6726,4.098434952,9.124119043,-2.7796875,-11.89773842,-2.96325733,65.84448159 +207.81,50.43223732,-2.570615329,50.7002,4.081053997,9.123452904,-2.7496875,-11.86873696,-3.012970529,65.8520067 +207.82,50.43223768,-2.570614045,50.7276,4.081054004,9.12411898,-2.7184375,-11.83830104,-3.060056373,65.85953176 +207.83,50.43223805,-2.570612761,50.7546,4.094958789,9.125451163,-2.68625,-11.80643702,-3.10447378,65.86705687 +207.84,50.43223842,-2.570611476,50.7813,4.094958807,9.126339273,-2.6534375,-11.77315161,-3.146184076,65.87458193 +207.85,50.43223879,-2.570610192,50.8077,4.081054056,9.126783312,-2.6196875,-11.73845169,-3.185150821,65.88210704 +207.86,50.43223915,-2.570608907,50.8337,4.077577888,9.127671423,-2.5846875,-11.70234452,-3.221340096,65.8896321 +207.87,50.43223952,-2.570607623,50.8594,4.081054092,9.128781568,-2.5484375,-11.66483767,-3.254720273,65.89715721 +207.88,50.43223989,-2.570606337,50.8847,4.077577899,9.12900357,-2.51125,-11.62593893,-3.285262361,65.90468226 +207.89,50.43224025,-2.570605053,50.9096,4.081054105,9.128781498,-2.473125,-11.5856565,-3.312939603,65.91220738 +207.9,50.43224062,-2.570603768,50.9342,4.094958904,9.129225534,-2.433125,-11.54399869,-3.337727878,65.91973243 +207.91,50.43224099,-2.570602483,50.9583,4.094958931,9.130113641,-2.3915625,-11.50097426,-3.359605641,65.92725755 +207.92,50.43224136,-2.570601198,50.982,4.077577984,9.131223784,-2.35,-11.4565922,-3.378553813,65.9347826 +207.93,50.43224172,-2.570599913,51.0053,4.063673214,9.132333926,-2.308125,-11.41086175,-3.39455578,65.94230772 +207.94,50.43224209,-2.570598627,51.0282,4.063673209,9.132555924,-2.2646875,-11.36379246,-3.407597674,65.94983277 +207.95,50.43224245,-2.570597342,51.0506,4.074101806,9.13233385,-2.2196875,-11.3153942,-3.417668095,65.95735788 +207.96,50.43224282,-2.570596057,51.0726,4.081054229,9.132777882,-2.1734375,-11.26567705,-3.424758219,65.96488294 +207.97,50.43224319,-2.570594771,51.0941,4.074101861,9.13344395,-2.1265625,-11.21465138,-3.428861914,65.97240805 +207.98,50.43224355,-2.570593486,51.1151,4.063673276,9.133665946,-2.0796875,-11.16232784,-3.42997563,65.97993311 +207.99,50.43224392,-2.5705922,51.1357,4.063673279,9.133887941,-2.0315625,-11.10871738,-3.428098333,65.98745822 +208,50.43224428,-2.570590915,51.1558,4.074101881,9.134776042,-1.9815625,-11.05383123,-3.423231687,65.99498328 +208.01,50.43224465,-2.570589629,51.1753,4.081054287,9.136108215,-1.9315625,-10.9976808,-3.415379931,66.00250833 +208.02,50.43224502,-2.570588343,51.1944,4.074101906,9.136996314,-1.8815625,-10.94027782,-3.404549883,66.01003345 +208.03,50.43224538,-2.570587057,51.213,4.06367334,9.137218306,-1.8296875,-10.88163427,-3.390751054,66.0175585 +208.04,50.43224575,-2.570585771,51.231,4.060197164,9.137218262,-1.7765625,-10.82176247,-3.373995418,66.02508362 +208.05,50.43224611,-2.570584485,51.2485,4.060197164,9.137440253,-1.7234375,-10.76067486,-3.354297645,66.03260867 +208.06,50.43224648,-2.570583199,51.2655,4.06019716,9.13832835,-1.6696875,-10.69838415,-3.331674865,66.04013378 +208.07,50.43224684,-2.570581913,51.2819,4.060197177,9.139438482,-1.6146875,-10.63490346,-3.306146788,66.04765884 +208.08,50.43224721,-2.570580626,51.2978,4.060197207,9.139660471,-1.5584375,-10.57024597,-3.277735701,66.05518395 +208.09,50.43224757,-2.57057934,51.3131,4.060197217,9.139438386,-1.5015625,-10.50442521,-3.246466415,66.06270901 +208.1,50.43224794,-2.570578054,51.3278,4.060197207,9.139882409,-1.4453125,-10.43745493,-3.212366087,66.07023412 +208.11,50.4322483,-2.570576767,51.342,4.056721013,9.140548466,-1.3896875,-10.3693491,-3.175464626,66.07775918 +208.12,50.43224867,-2.570575481,51.3556,4.046292448,9.140770451,-1.3328125,-10.30012193,-3.135794059,66.08528429 +208.13,50.43224903,-2.570574194,51.3687,4.039340074,9.140992436,-1.2734375,-10.22978792,-3.093389052,66.09280935 +208.14,50.43224939,-2.570572908,51.3811,4.046292467,9.141880527,-1.213125,-10.15836174,-3.048286502,66.10033446 +208.15,50.43224976,-2.570571621,51.3929,4.056721053,9.143212688,-1.1534375,-10.08585829,-3.000525886,66.10785952 +208.16,50.43225012,-2.570570334,51.4042,4.056721061,9.144100778,-1.093125,-10.01229274,-2.950148744,66.11538463 +208.17,50.43225049,-2.570569047,51.4148,4.046292478,9.144544795,-1.0315625,-9.937680458,-2.897198964,66.12290968 +208.18,50.43225085,-2.57056776,51.4248,4.039340091,9.145432883,-0.9703125,-9.862036965,-2.841722841,66.1304348 +208.19,50.43225121,-2.570566473,51.4342,4.042816305,9.146543005,-0.91,-9.785378077,-2.783768733,66.13795985 +208.2,50.43225158,-2.570565185,51.443,4.04281632,9.146542947,-0.8496875,-9.707719893,-2.72338706,66.14548497 +208.21,50.43225194,-2.570563898,51.4512,4.039340117,9.145654745,-0.788125,-9.629078514,-2.660630591,66.15301002 +208.22,50.4322523,-2.570562611,51.4588,4.042816304,9.145654687,-0.725,-9.549470383,-2.595553988,66.16053514 +208.23,50.43225267,-2.570561324,51.4657,4.042816315,9.146764806,-0.6615625,-9.46891223,-2.528214086,66.16806019 +208.24,50.43225303,-2.570560036,51.472,4.039340145,9.147874923,-0.5984375,-9.38742073,-2.4586695,66.1755853 +208.25,50.43225339,-2.570558749,51.4777,4.042816352,9.14898504,-0.5346875,-9.305013012,-2.386980906,66.18311036 +208.26,50.43225376,-2.570557461,51.4827,4.039340141,9.150095156,-0.47,-9.221706266,-2.313210814,66.19063547 +208.27,50.43225412,-2.570556173,51.4871,4.025435339,9.150095093,-0.4053125,-9.137517796,-2.237423624,66.19816053 +208.28,50.43225448,-2.570554885,51.4908,4.025435349,9.149206885,-0.3415625,-9.052465305,-2.159685341,66.20568564 +208.29,50.43225484,-2.570553598,51.4939,4.039340157,9.149206819,-0.2784375,-8.966566556,-2.080063745,66.2132107 +208.3,50.43225521,-2.57055231,51.4964,4.039340159,9.150316932,-0.215,-8.879839367,-1.998628337,66.22073581 +208.31,50.43225557,-2.570551022,51.4982,4.025435354,9.151427044,-0.1515625,-8.792301958,-1.915450106,66.22826087 +208.32,50.43225593,-2.570549734,51.4994,4.025435348,9.152537155,-0.088125,-8.70397255,-1.830601531,66.23578598 +208.33,50.43225629,-2.570548446,51.5,4.039340153,9.153647265,-0.023125,-8.614869649,-1.744156695,66.24331104 +208.34,50.43225666,-2.570547157,51.4999,4.039340171,9.15386923,0.043125,-8.525011818,-1.656190886,66.25083615 +208.35,50.43225702,-2.570545869,51.4991,4.021959181,9.153647124,0.108125,-8.434417852,-1.566780879,66.2583612 +208.36,50.43225738,-2.570544581,51.4977,4.008054371,9.154091124,0.1715625,-8.343106599,-1.476004655,66.26588626 +208.37,50.43225774,-2.570543292,51.4957,4.008054364,9.154979195,0.2353125,-8.251097198,-1.383941281,66.27341137 +208.38,50.4322581,-2.570542004,51.493,4.021959167,9.155867264,0.3,-8.158408898,-1.290671085,66.28093643 +208.39,50.43225846,-2.570540715,51.4897,4.039340166,9.156311261,0.365,-8.065060953,-1.196275429,66.28846154 +208.4,50.43225883,-2.570539426,51.4857,4.039340157,9.15608915,0.4296875,-7.971072899,-1.100836589,66.2959866 +208.41,50.43225919,-2.570538138,51.4811,4.021959149,9.156311109,0.493125,-7.876464389,-1.004437815,66.30351171 +208.42,50.43225955,-2.570536849,51.4758,4.008054352,9.15742121,0.5553125,-7.78125519,-0.90716316,66.31103677 +208.43,50.43225991,-2.57053556,51.47,4.00457817,9.158309275,0.618125,-7.685465184,-0.809097423,66.31856188 +208.44,50.43226027,-2.570534271,51.4635,4.004578184,9.158531233,0.681875,-7.589114309,-0.710326145,66.32608694 +208.45,50.43226063,-2.570532982,51.4563,4.004578173,9.158531153,0.7446875,-7.492222734,-0.610935443,66.33361205 +208.46,50.43226099,-2.570531693,51.4486,4.004578146,9.158753109,0.8065625,-7.394810684,-0.511012005,66.34113711 +208.47,50.43226135,-2.570530404,51.4402,4.004578135,9.15964117,0.86875,-7.296898499,-0.410642977,66.34866222 +208.48,50.43226171,-2.570529115,51.4312,4.008054341,9.160751266,0.93125,-7.198506692,-0.309915851,66.35618727 +208.49,50.43226207,-2.570527825,51.4216,4.021959133,9.160973218,0.9934375,-7.099655716,-0.20891846,66.36371239 +208.5,50.43226243,-2.570526536,51.4113,4.039340102,9.160973134,1.0546875,-7.000366255,-0.107738927,66.37123744 +208.51,50.4322628,-2.570525247,51.4005,4.039340084,9.162305263,1.1146875,-6.900658994,-0.00646537,66.37876256 +208.52,50.43226316,-2.570523957,51.389,4.021959098,9.164081463,1.1734375,-6.800554902,0.094813743,66.38628761 +208.53,50.43226352,-2.570522667,51.377,4.00805432,9.164303411,1.2315625,-6.70007472,0.196010237,66.39381272 +208.54,50.43226388,-2.570521377,51.3644,4.00110193,9.163415181,1.2903125,-6.599239534,0.29703576,66.40133778 +208.55,50.43226424,-2.570520088,51.3512,3.987197126,9.163415092,1.3496875,-6.498070314,0.397802305,66.40886289 +208.56,50.4322646,-2.570518798,51.3374,3.969816113,9.164525182,1.408125,-6.396588315,0.498221925,66.41638795 +208.57,50.43226495,-2.570517508,51.323,3.969816097,9.165413236,1.465,-6.294814624,0.598207128,66.42391306 +208.58,50.43226531,-2.570516218,51.3081,3.987197089,9.165635181,1.5215625,-6.192770497,0.697670654,66.43143812 +208.59,50.43226567,-2.570514928,51.2926,4.001101884,9.165857125,1.5784375,-6.090477306,0.796525812,66.43896323 +208.6,50.43226603,-2.570513638,51.2765,4.004578064,9.166745176,1.634375,-5.987956363,0.894686374,66.44648829 +208.61,50.43226639,-2.570512348,51.2599,4.004578032,9.167855261,1.6884375,-5.885229156,0.992066739,66.4540134 +208.62,50.43226675,-2.570511057,51.2427,4.004578014,9.168077202,1.7415625,-5.782316997,1.088582053,66.46153846 +208.63,50.43226711,-2.570509767,51.2251,4.004578021,9.167855072,1.7946875,-5.679241546,1.18414809,66.46906357 +208.64,50.43226747,-2.570508477,51.2068,4.001101833,9.168299048,1.846875,-5.576024174,1.278681542,66.47658862 +208.65,50.43226783,-2.570507186,51.1881,3.987197036,9.169187095,1.8978125,-5.472686537,1.372099962,66.48411374 +208.66,50.43226819,-2.570505896,51.1689,3.969816024,9.170297176,1.9484375,-5.36925018,1.464321873,66.49163879 +208.67,50.43226854,-2.570504605,51.1491,3.969816,9.171629293,1.998125,-5.265736702,1.555266891,66.49916391 +208.68,50.4322689,-2.570503314,51.1289,3.987196979,9.172517338,2.0465625,-5.162167763,1.644855661,66.50668896 +208.69,50.43226926,-2.570502023,51.1082,4.001101764,9.172739275,2.095,-5.058564904,1.733010145,66.51421402 +208.7,50.43226962,-2.570500732,51.087,4.001101751,9.172739175,2.143125,-4.954949841,1.819653338,66.52173913 +208.71,50.43226998,-2.570499441,51.0653,3.987196952,9.172739075,2.1896875,-4.851344232,1.90470984,66.52926419 +208.72,50.43227034,-2.57049815,51.0432,3.969815956,9.172738974,2.2346875,-4.74776962,1.988105394,66.5367893 +208.73,50.43227069,-2.570496859,51.0206,3.969815931,9.172738872,2.2784375,-4.644247663,2.069767292,66.54431436 +208.74,50.43227105,-2.570495568,50.9976,3.983720691,9.172960806,2.3215625,-4.540800019,2.149624316,66.55183947 +208.75,50.43227141,-2.570494277,50.9742,3.983720681,9.173848846,2.3646875,-4.437448287,2.227606794,66.55936453 +208.76,50.43227177,-2.570492986,50.9503,3.969815897,9.175180957,2.4065625,-4.334214012,2.303646831,66.56688964 +208.77,50.43227212,-2.570491694,50.926,3.969815893,9.176291032,2.44625,-4.231118794,2.37767802,66.57441469 +208.78,50.43227248,-2.570490403,50.9014,3.983720654,9.17717907,2.485,-4.128184176,2.449635847,66.58193981 +208.79,50.43227284,-2.570489111,50.8763,3.983720617,9.177623036,2.523125,-4.025431587,2.519457515,66.58946486 +208.8,50.4322732,-2.570487819,50.8509,3.969815809,9.177400894,2.5596875,-3.922882512,2.587082234,66.59698998 +208.81,50.43227355,-2.570486528,50.8251,3.966339614,9.177622824,2.5953125,-3.820558438,2.652450989,66.60451503 +208.82,50.43227391,-2.570485236,50.799,3.969815815,9.178732897,2.63125,-3.718480621,2.715506713,66.61204014 +208.83,50.43227427,-2.570483944,50.7725,3.966339602,9.179620932,2.6665625,-3.616670432,2.776194517,66.6195652 +208.84,50.43227462,-2.570482652,50.7456,3.966339568,9.17984286,2.699375,-3.515149186,2.834461403,66.62709031 +208.85,50.43227498,-2.57048136,50.7185,3.969815737,9.179842752,2.7296875,-3.413937968,2.890256606,66.63461537 +208.86,50.43227534,-2.570480068,50.691,3.966339532,9.179842644,2.75875,-3.313058034,2.943531482,66.64214048 +208.87,50.43227569,-2.570478776,50.6633,3.966339526,9.18006457,2.7878125,-3.212530354,2.994239565,66.64966554 +208.88,50.43227605,-2.570477484,50.6353,3.969815705,9.180952604,2.8165625,-3.112375956,3.042336564,66.65719065 +208.89,50.43227641,-2.570476192,50.6069,3.962863298,9.182062673,2.843125,-3.012615811,3.087780654,66.66471571 +208.9,50.43227676,-2.570474899,50.5784,3.952434698,9.182284599,2.868125,-2.913270659,3.13053213,66.67224082 +208.91,50.43227712,-2.570473607,50.5496,3.948958476,9.182284488,2.8934375,-2.814361356,3.170553747,66.67976588 +208.92,50.43227747,-2.570472315,50.5205,3.948958436,9.183394556,2.9178125,-2.715908471,3.207810614,66.68729099 +208.93,50.43227783,-2.570471022,50.4912,3.948958411,9.184504624,2.939375,-2.617932573,3.242270187,66.69481605 +208.94,50.43227818,-2.570469729,50.4617,3.948958411,9.184504513,2.9584375,-2.520454118,3.273902499,66.70234116 +208.95,50.43227854,-2.570468437,50.432,3.952434609,9.184726437,2.9765625,-2.423493501,3.302679877,66.70986621 +208.96,50.43227889,-2.570467144,50.4022,3.962863181,9.185836504,2.9946875,-2.32707095,3.328577283,66.71739133 +208.97,50.43227925,-2.570465851,50.3721,3.969815542,9.186724534,3.0115625,-2.231206631,3.351572085,66.72491638 +208.98,50.43227961,-2.570464558,50.3419,3.962863115,9.186946457,3.02625,-2.135920541,3.371644286,66.7324415 +208.99,50.43227996,-2.570463265,50.3116,3.952434504,9.186946344,3.0403125,-2.041232562,3.388776412,66.73996655 +209,50.43228032,-2.570461972,50.2811,3.9489583,9.186946232,3.0546875,-1.94716246,3.40295345,66.74749166 +209.01,50.43228067,-2.570460679,50.2505,3.945482099,9.187168155,3.0678125,-1.853729946,3.414163026,66.75501672 +209.02,50.43228103,-2.570459386,50.2197,3.935053499,9.188056184,3.0778125,-1.7609545,3.422395398,66.76254183 +209.03,50.43228138,-2.570458093,50.1889,3.928101092,9.189388286,3.0846875,-1.66885543,3.427643462,66.77006689 +209.04,50.43228173,-2.570456799,50.158,3.935053463,9.190498351,3.0903125,-1.577452046,3.42990252,66.77759195 +209.05,50.43228209,-2.570455506,50.1271,3.945482023,9.191608416,3.0965625,-1.486763427,3.429170624,66.78511706 +209.06,50.43228244,-2.570454212,50.0961,3.948958198,9.192718481,3.103125,-1.396808538,3.425448518,66.79264211 +209.07,50.4322828,-2.570452918,50.065,3.948958179,9.192718368,3.1078125,-1.307606056,3.418739297,66.80016723 +209.08,50.43228315,-2.570451624,50.0339,3.945481953,9.191830112,3.1096875,-1.219174719,3.409048919,66.80769228 +209.09,50.43228351,-2.570450331,50.0028,3.935053336,9.191607963,3.1096875,-1.131532975,3.396385807,66.8152174 +209.1,50.43228386,-2.570449037,49.9717,3.928100929,9.192051921,3.108125,-1.044699101,3.380760961,66.82274245 +209.11,50.43228421,-2.570447743,49.9406,3.931577122,9.192717915,3.105,-0.95869126,3.362188076,66.83026757 +209.12,50.43228457,-2.57044645,49.9096,3.931577116,9.194050015,3.1015625,-0.873527329,3.340683309,66.83779262 +209.13,50.43228492,-2.570445155,49.8786,3.928100901,9.19516008,3.0984375,-0.789225241,3.316265394,66.84531773 +209.14,50.43228527,-2.570443861,49.8476,3.931577067,9.194937931,3.094375,-0.705802472,3.288955647,66.85284279 +209.15,50.43228563,-2.570442567,49.8167,3.93157704,9.194493747,3.0878125,-0.623276496,3.258777903,66.8603679 +209.16,50.43228598,-2.570441273,49.7858,3.928100823,9.195159741,3.078125,-0.541664559,3.22575846,66.86789296 +209.17,50.43228633,-2.570439979,49.7551,3.931577,9.196491842,3.0665625,-0.460983679,3.189926081,66.87541807 +209.18,50.43228669,-2.570438684,49.7245,3.928100788,9.197379872,3.055,-0.381250701,3.151312048,66.88294313 +209.19,50.43228704,-2.57043739,49.694,3.914195995,9.197601795,3.043125,-0.302482296,3.109950053,66.89046824 +209.2,50.43228739,-2.570436095,49.6636,3.914195988,9.197823719,3.0296875,-0.22469491,3.065876077,66.8979933 +209.21,50.43228774,-2.570434801,49.6334,3.928100752,9.198711749,3.0146875,-0.147904815,3.01912868,66.90551841 +209.22,50.4322881,-2.570433506,49.6033,3.928100725,9.200043852,2.9984375,-0.072127938,2.969748484,66.91304347 +209.23,50.43228845,-2.570432211,49.5734,3.914195922,9.200931883,2.98125,0.002619735,2.917778691,66.92056858 +209.24,50.4322888,-2.570430916,49.5437,3.914195904,9.201153807,2.963125,0.076322734,2.863264507,66.92809363 +209.25,50.43228915,-2.570429621,49.5141,3.928100657,9.200931661,2.943125,0.148965532,2.806253545,66.93561875 +209.26,50.43228951,-2.570428326,49.4848,3.928100631,9.200265443,2.92125,0.220533117,2.74679548,66.9431438 +209.27,50.43228986,-2.570427031,49.4557,3.910719646,9.200043297,2.898125,0.291010421,2.684942165,66.95066892 +209.28,50.43229021,-2.570425737,49.4268,3.90029106,9.201153365,2.873125,0.360382776,2.620747515,66.95819397 +209.29,50.43229056,-2.570424441,49.3982,3.910719631,9.202485469,2.8465625,0.428635685,2.554267566,66.96571909 +209.3,50.43229091,-2.570423146,49.3699,3.928100583,9.203151467,2.82,0.495754884,2.485560243,66.97324414 +209.31,50.43229127,-2.570421851,49.3418,3.928100566,9.203817465,2.793125,0.561726333,2.414685479,66.98076925 +209.32,50.43229162,-2.570420555,49.314,3.91071958,9.204705499,2.7646875,0.626536339,2.341705094,66.98829431 +209.33,50.43229197,-2.57041926,49.2865,3.896814782,9.205593533,2.735,0.690171266,2.266682688,66.99581942 +209.34,50.43229232,-2.570417964,49.2593,3.893338559,9.206037497,2.7046875,0.752617936,2.189683692,67.00334448 +209.35,50.43229267,-2.570416668,49.2324,3.893338534,9.205815355,2.6728125,0.813863171,2.110775257,67.01086959 +209.36,50.43229302,-2.570415373,49.2058,3.893338515,9.206037285,2.638125,0.873894309,2.030026195,67.01839465 +209.37,50.43229337,-2.570414077,49.1796,3.8933385,9.207147357,2.601875,0.932698743,1.947506922,67.02591976 +209.38,50.43229372,-2.570412781,49.1538,3.893338486,9.208035394,2.5665625,0.990264214,1.863289403,67.03344482 +209.39,50.43229407,-2.570411485,49.1283,3.896814675,9.208257324,2.53125,1.046578689,1.77744709,67.04096987 +209.4,50.43229442,-2.570410189,49.1031,3.910719453,9.20825722,2.493125,1.101630422,1.690054754,67.04849499 +209.41,50.43229477,-2.570408893,49.0784,3.928100415,9.208257116,2.453125,1.155407897,1.601188714,67.05602004 +209.42,50.43229513,-2.570407597,49.0541,3.928100391,9.208257013,2.4134375,1.207899941,1.510926432,67.06354515 +209.43,50.43229548,-2.570406301,49.0301,3.9107194,9.208478946,2.3728125,1.259095496,1.419346577,67.07107021 +209.44,50.43229583,-2.570405005,49.0066,3.896814613,9.209589021,2.3296875,1.308983905,1.326529019,67.07859532 +209.45,50.43229618,-2.570403709,48.9835,3.893338404,9.211587239,2.2853125,1.357554798,1.232554716,67.08612038 +209.46,50.43229653,-2.570402412,48.9609,3.893338379,9.212919352,2.2415625,1.404797976,1.137505601,67.09364549 +209.47,50.43229688,-2.570401115,48.9387,3.893338357,9.212697217,2.198125,1.450703583,1.041464582,67.10117055 +209.48,50.43229723,-2.570399819,48.9169,3.889862146,9.212031011,2.1528125,1.49526211,0.944515368,67.10869566 +209.49,50.43229758,-2.570398522,48.8956,3.875957353,9.212030912,2.1046875,1.538464102,0.846742526,67.11622072 +209.5,50.43229793,-2.570397226,48.8748,3.858576366,9.212918957,2.0553125,1.580300678,0.748231314,67.12374583 +209.51,50.43229827,-2.570395929,48.8545,3.858576362,9.214251073,2.0065625,1.620763015,0.649067618,67.13127089 +209.52,50.43229862,-2.570394632,48.8347,3.875957338,9.215139119,1.958125,1.65984269,0.549337954,67.138796 +209.53,50.43229897,-2.570393335,48.8153,3.88986211,9.215361059,1.908125,1.697531567,0.44912924,67.14632105 +209.54,50.43229932,-2.570392038,48.7965,3.893338292,9.215582999,1.85625,1.733821682,0.348528909,67.15384617 +209.55,50.43229967,-2.570390741,48.7782,3.893338283,9.216471047,1.8034375,1.768705587,0.247624624,67.16137122 +209.56,50.43230002,-2.570389444,48.7604,3.89333827,9.217581131,1.75,1.802175948,0.146504449,67.16889634 +209.57,50.43230037,-2.570388146,48.7432,3.889862056,9.217581039,1.6965625,1.834225718,0.045256447,67.17642139 +209.58,50.43230072,-2.570386849,48.7265,3.875957265,9.216692805,1.643125,1.864848249,-0.056030975,67.18394651 +209.59,50.43230107,-2.570385552,48.7103,3.858576288,9.216914749,1.588125,1.894037183,-0.157269524,67.19147156 +209.6,50.43230141,-2.570384255,48.6947,3.858576279,9.218690943,1.5315625,1.921786331,-0.258370963,67.19899667 +209.61,50.43230176,-2.570382957,48.6797,3.875957237,9.219801032,1.475,1.948090021,-0.359247059,67.20652173 +209.62,50.43230211,-2.570381659,48.6652,3.886385814,9.218912801,1.4184375,1.972942639,-0.459809918,67.21404684 +209.63,50.43230246,-2.570380362,48.6513,3.875957229,9.218246606,1.36125,1.996339084,-0.559971821,67.2215719 +209.64,50.43230281,-2.570379065,48.638,3.858576243,9.220022803,1.303125,2.018274372,-0.659645393,67.22909701 +209.65,50.43230315,-2.570377767,48.6252,3.858576218,9.222243072,1.2434375,2.038744034,-0.758743772,67.23662207 +209.66,50.4323035,-2.570376468,48.6131,3.875957176,9.222242988,1.183125,2.057743716,-0.857180499,67.24414718 +209.67,50.43230385,-2.570375171,48.6016,3.886385763,9.221354761,1.12375,2.075269521,-0.954869746,67.25167224 +209.68,50.4323042,-2.570373873,48.5906,3.875957185,9.221576713,1.0646875,2.091317725,-1.051726313,67.25919735 +209.69,50.43230455,-2.570372575,48.5803,3.85857621,9.222464773,1.0046875,2.105885005,-1.147665804,67.26672241 +209.7,50.43230489,-2.570371277,48.5705,3.855100013,9.223574868,0.9434375,2.118968267,-1.24260451,67.27424752 +209.71,50.43230524,-2.570369979,48.5614,3.858576201,9.224684964,0.88125,2.130564875,-1.336459638,67.28177257 +209.72,50.43230559,-2.57036868,48.5529,3.855099992,9.22490692,0.8184375,2.140672309,-1.429149369,67.28929769 +209.73,50.43230593,-2.570367382,48.545,3.855099987,9.224906842,0.755,2.149288563,-1.520592803,67.29682274 +209.74,50.43230628,-2.570366084,48.5378,3.858576187,9.226238977,0.691875,2.156411746,-1.610710298,67.3043478 +209.75,50.43230663,-2.570364785,48.5312,3.855099988,9.228015184,0.63,2.162040426,-1.699423244,67.31187291 +209.76,50.43230697,-2.570363486,48.5252,3.855099976,9.228237144,0.568125,2.166173343,-1.786654235,67.31939797 +209.77,50.43230732,-2.570362187,48.5198,3.858576168,9.227348927,0.5046875,2.168809751,-1.872327239,67.32692308 +209.78,50.43230767,-2.570360889,48.5151,3.855099979,9.227348853,0.44,2.169949077,-1.9563676,67.33444814 +209.79,50.43230801,-2.57035959,48.511,3.855099979,9.228236921,0.3753125,2.169590979,-2.038701922,67.34197325 +209.8,50.43230836,-2.570358291,48.5076,3.85857617,9.228236848,0.3115625,2.167735627,-2.11925847,67.34949831 +209.81,50.43230871,-2.570356992,48.5048,3.851623781,9.22757067,0.2484375,2.164383423,-2.197967,67.35702342 +209.82,50.43230905,-2.570355694,48.5026,3.841195192,9.228458741,0.1846875,2.159534996,-2.274758872,67.36454847 +209.83,50.4323094,-2.570354395,48.5011,3.841195183,9.230679026,0.12,2.15319138,-2.349567106,67.37207359 +209.84,50.43230974,-2.570353095,48.5002,3.851623768,9.231789135,0.055,2.145353947,-2.422326501,67.37959864 +209.85,50.43231009,-2.570351796,48.5,3.858576167,9.231789068,-0.01,2.136024246,-2.492973629,67.38712376 +209.86,50.43231044,-2.570350497,48.5004,3.851623779,9.232233072,-0.075,2.125204339,-2.561446784,67.39464881 +209.87,50.43231078,-2.570349197,48.5015,3.841195193,9.232899113,-0.1396875,2.112896347,-2.627686378,67.40217393 +209.88,50.43231113,-2.570347898,48.5032,3.837719001,9.233121084,-0.2034375,2.099103018,-2.691634541,67.40969898 +209.89,50.43231147,-2.570346598,48.5056,3.837719001,9.233343055,-0.266875,2.083827046,-2.753235583,67.41722409 +209.9,50.43231182,-2.570345299,48.5085,3.837718994,9.234009099,-0.3315625,2.067071755,-2.812435759,67.42474915 +209.91,50.43231216,-2.570343999,48.5122,3.837718996,9.234453108,-0.3965625,2.048840582,-2.869183447,67.43227426 +209.92,50.43231251,-2.570342699,48.5165,3.837719008,9.234231011,-0.4596875,2.029137365,-2.923429143,67.43979932 +209.93,50.43231285,-2.5703414,48.5214,3.837719013,9.234452986,-0.521875,2.007966174,-2.975125578,67.44732443 +209.94,50.4323132,-2.5703401,48.5269,3.837719014,9.235563104,-0.5853125,1.985331476,-3.02422766,67.45484949 +209.95,50.43231354,-2.5703388,48.5331,3.834242826,9.236451188,-0.6496875,1.96123797,-3.070692589,67.4623746 +209.96,50.43231389,-2.5703375,48.5399,3.823814242,9.236673166,-0.713125,1.935690699,-3.1144798,67.46989966 +209.97,50.43231423,-2.5703362,48.5474,3.816861848,9.23667311,-0.775,1.90869499,-3.155551134,67.47742477 +209.98,50.43231457,-2.5703349,48.5554,3.823814243,9.23689509,-0.8365625,1.880256517,-3.193870838,67.48494983 +209.99,50.43231492,-2.5703336,48.5641,3.834242843,9.237783178,-0.89875,1.85038118,-3.229405394,67.49247494 +210,50.43231526,-2.5703323,48.5734,3.834242851,9.239115337,-0.96125,1.819075224,-3.262123862,67.49999999 +210.01,50.43231561,-2.570330999,48.5833,3.823814269,9.240003425,-1.023125,1.786345182,-3.29199771,67.50752511 +210.02,50.43231595,-2.570329699,48.5939,3.816861888,9.240225409,-1.083125,1.752197929,-3.319000867,67.51505016 +210.03,50.43231629,-2.570328398,48.605,3.820338088,9.240225358,-1.141875,1.716640512,-3.343109842,67.52257528 +210.04,50.43231664,-2.570327098,48.6167,3.820338086,9.240225308,-1.201875,1.679680494,-3.364303551,67.53010033 +210.05,50.43231698,-2.570325797,48.629,3.816861899,9.240447295,-1.2628125,1.641325439,-3.382563544,67.53762545 +210.06,50.43231732,-2.570324497,48.642,3.820338111,9.241335389,-1.3215625,1.601583424,-3.397873893,67.5451505 +210.07,50.43231767,-2.570323196,48.6555,3.820338121,9.242667553,-1.378125,1.560462816,-3.410221305,67.55267556 +210.08,50.43231801,-2.570321895,48.6695,3.816861932,9.243555649,-1.4353125,1.517972094,-3.419594895,67.56020067 +210.09,50.43231835,-2.570320594,48.6842,3.820338139,9.243777639,-1.493125,1.474120197,-3.425986526,67.56772573 +210.1,50.4323187,-2.570319293,48.6994,3.820338146,9.243777594,-1.5496875,1.428916233,-3.429390697,67.57525084 +210.11,50.43231904,-2.570317992,48.7152,3.816861951,9.243999585,-1.605,1.382369715,-3.429804315,67.58277589 +210.12,50.43231938,-2.570316691,48.7315,3.820338157,9.244887683,-1.6596875,1.334490267,-3.427227151,67.59030101 +210.13,50.43231973,-2.57031539,48.7484,3.816861981,9.245997817,-1.7134375,1.285287975,-3.421661382,67.59782606 +210.14,50.43232007,-2.570314088,48.7658,3.799481017,9.246219812,-1.76625,1.234773094,-3.413111877,67.60535118 +210.15,50.43232041,-2.570312787,48.7837,3.78905244,9.245997736,-1.8184375,1.182956109,-3.401586087,67.61287623 +210.16,50.43232075,-2.570311486,48.8022,3.799481039,9.246441767,-1.87,1.129847963,-3.387094036,67.62040135 +210.17,50.43232109,-2.570310184,48.8211,3.816862027,9.24732987,-1.9215625,1.0754596,-3.369648445,67.6279264 +210.18,50.43232144,-2.570308883,48.8406,3.816862037,9.248217973,-1.973125,1.019802538,-3.34926444,67.63545151 +210.19,50.43232178,-2.570307581,48.8606,3.799481075,9.248662006,-2.023125,0.962888233,-3.32595984,67.64297657 +210.2,50.43232212,-2.570306279,48.8811,3.789052499,9.248439933,-2.0715625,0.90472872,-3.299754928,67.65050168 +210.21,50.43232246,-2.570304978,48.902,3.799481089,9.248661932,-2.1196875,0.845336087,-3.270672564,67.65802674 +210.22,50.4323228,-2.570303676,48.9235,3.816862079,9.249772073,-2.1665625,0.784722652,-3.238738189,67.66555185 +210.23,50.43232315,-2.570302374,48.9454,3.816862101,9.25066018,-2.21125,0.722901251,-3.203979532,67.67307691 +210.24,50.43232349,-2.570301072,48.9677,3.79948114,9.250882181,-2.255,0.659884603,-3.166426961,67.68060202 +210.25,50.43232383,-2.57029977,48.9905,3.78557637,9.250882147,-2.2984375,0.595686,-3.12611325,67.68812708 +210.26,50.43232417,-2.570298468,49.0137,3.782100191,9.251104149,-2.3415625,0.530318849,-3.08307352,67.69565219 +210.27,50.43232451,-2.570297166,49.0373,3.782100205,9.251992258,-2.3846875,0.46379673,-3.037345242,67.70317725 +210.28,50.43232485,-2.570295864,49.0614,3.782100217,9.253102405,-2.4265625,0.396133566,-2.98896841,67.71070236 +210.29,50.43232519,-2.570294561,49.0859,3.782100234,9.25332441,-2.46625,0.327343451,-2.937985136,67.71822741 +210.3,50.43232553,-2.570293259,49.1107,3.785576442,9.25332438,-2.5046875,0.257440824,-2.884439938,67.72575253 +210.31,50.43232587,-2.570291957,49.136,3.799481231,9.254656562,-2.5415625,0.186440237,-2.828379399,67.73327758 +210.32,50.43232621,-2.570290654,49.1616,3.816862224,9.256432814,-2.5765625,0.114356532,-2.769852505,67.7408027 +210.33,50.43232656,-2.570289351,49.1875,3.816862248,9.25665482,-2.611875,0.041204775,-2.70891025,67.74832775 +210.34,50.4323269,-2.570288048,49.2138,3.799481289,9.25576665,-2.648125,-0.032999791,-2.645605805,67.75585287 +210.35,50.43232724,-2.570286746,49.2405,3.78557652,9.255766622,-2.6828125,-0.10824164,-2.579994345,67.76337792 +210.36,50.43232758,-2.570285443,49.2675,3.782100343,9.256876772,-2.7146875,-0.184505072,-2.512133052,67.77090303 +210.37,50.43232792,-2.57028414,49.2948,3.78210036,9.257542852,-2.7446875,-0.261774161,-2.442081169,67.77842809 +210.38,50.43232826,-2.570282837,49.3224,3.782100374,9.257098755,-2.7734375,-0.340032747,-2.369899774,67.7859532 +210.39,50.4323286,-2.570281534,49.3503,3.778624198,9.256876693,-2.8015625,-0.419264559,-2.295651778,67.79347826 +210.4,50.43232894,-2.570280232,49.3784,3.764719434,9.257986845,-2.8296875,-0.499452925,-2.219401924,67.80100337 +210.41,50.43232928,-2.570278928,49.4069,3.74733848,9.259319032,-2.8565625,-0.580581228,-2.141216734,67.80852843 +210.42,50.43232961,-2.570277625,49.4356,3.74733851,9.259985115,-2.88125,-0.662632451,-2.061164388,67.81605348 +210.43,50.43232995,-2.570276322,49.4645,3.764719506,9.260651197,-2.9046875,-0.745589463,-1.979314674,67.8235786 +210.44,50.43233029,-2.570275018,49.4937,3.778624293,9.261317279,-2.9265625,-0.829435018,-1.895738925,67.83110365 +210.45,50.43233063,-2.570273715,49.5231,3.782100499,9.26153929,-2.9465625,-0.914151469,-1.810510078,67.83862877 +210.46,50.43233097,-2.570272411,49.5526,3.782100513,9.261761302,-2.9665625,-0.999721226,-1.723702503,67.84615382 +210.47,50.43233131,-2.570271108,49.5824,3.782100522,9.262427385,-2.9865625,-1.086126413,-1.635391773,67.85367893 +210.48,50.43233165,-2.570269804,49.6124,3.78210054,9.262871433,-3.004375,-1.173348924,-1.545654951,67.86120399 +210.49,50.43233199,-2.5702685,49.6425,3.778624371,9.262649375,-3.02,-1.261370597,-1.454570304,67.8687291 +210.5,50.43233233,-2.570267197,49.6728,3.764719608,9.262871388,-3.0346875,-1.350173039,-1.362217242,67.87625416 +210.51,50.43233267,-2.570265893,49.7032,3.747338645,9.263981544,-3.048125,-1.439737687,-1.268676324,67.88377927 +210.52,50.432333,-2.570264589,49.7338,3.747338666,9.264869664,-3.0596875,-1.530045862,-1.17402914,67.89130433 +210.53,50.43233334,-2.570263285,49.7644,3.764719663,9.265313713,-3.07,-1.621078714,-1.078358137,67.89882944 +210.54,50.43233368,-2.570261981,49.7952,3.775148267,9.266201832,-3.0796875,-1.712817164,-0.981746795,67.9063545 +210.55,50.43233402,-2.570260677,49.826,3.7647197,9.267311987,-3.088125,-1.805242132,-0.884279341,67.91387961 +210.56,50.43233436,-2.570259372,49.857,3.747338739,9.267311967,-3.095,-1.898334309,-0.786040799,67.92140467 +210.57,50.43233469,-2.570258068,49.8879,3.747338755,9.266423805,-3.10125,-1.992074158,-0.687116828,67.92892978 +210.58,50.43233503,-2.570256764,49.919,3.761243562,9.266423784,-3.1065625,-2.086442255,-0.587593658,67.93645483 +210.59,50.43233537,-2.57025546,49.9501,3.761243589,9.267533939,-3.1090625,-2.181418718,-0.487558092,67.94397995 +210.6,50.43233571,-2.570254155,49.9812,3.747338833,9.268644095,-3.1084375,-2.276983896,-0.387097391,67.951505 +210.61,50.43233604,-2.570252851,50.0123,3.747338854,9.269532215,-3.106875,-2.373117677,-0.286299161,67.95903012 +210.62,50.43233638,-2.570251546,50.0433,3.761243645,9.269976265,-3.1065625,-2.469800065,-0.185251235,67.96655517 +210.63,50.43233672,-2.570250241,50.0744,3.761243652,9.269754209,-3.10625,-2.567010892,-0.084041736,67.97408029 +210.64,50.43233706,-2.570248937,50.1055,3.747338887,9.269976225,-3.1028125,-2.664729761,0.017240988,67.98160534 +210.65,50.43233739,-2.570247632,50.1365,3.743862709,9.271086381,-3.0965625,-2.762936388,0.1185087,67.98913045 +210.66,50.43233773,-2.570246327,50.1674,3.747338921,9.271974501,-3.09,-2.861610149,0.21967305,67.99665551 +210.67,50.43233807,-2.570245022,50.1983,3.743862746,9.272196515,-3.0828125,-2.960730472,0.320645861,68.00418062 +210.68,50.4323384,-2.570243717,50.2291,3.743862762,9.272418529,-3.073125,-3.060276675,0.421339068,68.01170568 +210.69,50.43233874,-2.570242412,50.2598,3.747338967,9.273306649,-3.0615625,-3.160228016,0.521664894,68.01923079 +210.7,50.43233908,-2.570241107,50.2903,3.740386596,9.274416804,-3.0496875,-3.260563526,0.621535793,68.02675585 +210.71,50.43233941,-2.570239801,50.3208,3.729958045,9.274638819,-3.0365625,-3.361262291,0.720864673,68.03428096 +210.72,50.43233975,-2.570238496,50.3511,3.729958083,9.274416762,-3.0215625,-3.462303284,0.819564961,68.04180602 +210.73,50.43234008,-2.570237191,50.3812,3.74038669,9.27486081,-3.0065625,-3.563665419,0.917550599,68.04933113 +210.74,50.43234042,-2.570235885,50.4112,3.74733908,9.27574893,-2.99125,-3.665327555,1.014736101,68.05685619 +210.75,50.43234076,-2.57023458,50.4411,3.740386685,9.276637049,-2.9728125,-3.767268378,1.111036727,68.0643813 +210.76,50.43234109,-2.570233274,50.4707,3.729958112,9.277081098,-2.9515625,-3.869466631,1.206368539,68.07190635 +210.77,50.43234143,-2.570231968,50.5001,3.726481942,9.276859039,-2.9303125,-3.971900999,1.300648401,68.07943141 +210.78,50.43234176,-2.570230663,50.5293,3.726481962,9.27708105,-2.9096875,-4.074550055,1.393794035,68.08695652 +210.79,50.4323421,-2.570229357,50.5583,3.726481976,9.278191204,-2.8878125,-4.17739237,1.485724253,68.09448158 +210.8,50.43234243,-2.570228051,50.5871,3.726481996,9.279079322,-2.8628125,-4.280406514,1.5763589,68.10200669 +210.81,50.43234277,-2.570226745,50.6156,3.726482015,9.279301334,-2.835,-4.383570889,1.665618964,68.10953175 +210.82,50.4323431,-2.570225439,50.6438,3.726482038,9.279301309,-2.806875,-4.486864064,1.753426579,68.11705686 +210.83,50.43234344,-2.570224133,50.6717,3.726482068,9.279301284,-2.7796875,-4.590264325,1.8397052,68.12458192 +210.84,50.43234377,-2.570222827,50.6994,3.726482084,9.279523293,-2.75125,-4.693750185,1.924379538,68.13210703 +210.85,50.43234411,-2.570221521,50.7268,3.726482087,9.280411409,-2.7196875,-4.797300045,2.007375798,68.13963209 +210.86,50.43234444,-2.570220215,50.7538,3.726482097,9.281743595,-2.686875,-4.90089219,2.088621557,68.1471572 +210.87,50.43234478,-2.570218908,50.7805,3.72648211,9.28263171,-2.6546875,-5.004505018,2.168046055,68.15468225 +210.88,50.43234511,-2.570217602,50.8069,3.726482124,9.282631683,-2.6215625,-5.10811693,2.245579965,68.16220737 +210.89,50.43234545,-2.570216295,50.833,3.726482141,9.281965549,-2.58625,-5.211706267,2.321155733,68.16973242 +210.9,50.43234578,-2.570214989,50.8586,3.723005962,9.281743485,-2.5496875,-5.315251429,2.394707414,68.17725754 +210.91,50.43234612,-2.570213683,50.884,3.712577395,9.283075669,-2.511875,-5.4187307,2.466170836,68.18478259 +210.92,50.43234645,-2.570212376,50.9089,3.705625032,9.285073958,-2.4728125,-5.522122539,2.535483717,68.19230771 +210.93,50.43234678,-2.570211069,50.9334,3.70910125,9.28596207,-2.4334375,-5.625405343,2.60258567,68.19983276 +210.94,50.43234712,-2.570209762,50.9576,3.709101253,9.28551797,-2.393125,-5.728557513,2.667418079,68.20735787 +210.95,50.43234745,-2.570208455,50.9813,3.705625053,9.285295904,-2.35125,-5.831557563,2.729924451,68.21488293 +210.96,50.43234778,-2.570207149,51.0046,3.70910125,9.286406048,-2.3084375,-5.93438395,2.790050356,68.22240804 +210.97,50.43234812,-2.570205841,51.0275,3.709101263,9.287516192,-2.265,-6.037015187,2.847743252,68.2299331 +210.98,50.43234845,-2.570204534,51.0499,3.705625089,9.28751616,-2.22125,-6.139429846,2.902952835,68.23745821 +210.99,50.43234878,-2.570203227,51.0719,3.709101303,9.287738163,-2.1765625,-6.241606612,2.955631033,68.24498327 +211,50.43234912,-2.57020192,51.0935,3.709101322,9.28862627,-2.1296875,-6.343524001,3.005731895,68.25250838 +211.01,50.43234945,-2.570200612,51.1145,3.705625153,9.288848271,-2.0815625,-6.44516087,3.053211704,68.26003344 +211.02,50.43234978,-2.570199305,51.1351,3.709101369,9.2886262,-2.033125,-6.546495904,3.098029093,68.26755855 +211.03,50.43235012,-2.570197998,51.1552,3.705625173,9.289070235,-1.983125,-6.64750802,3.140144929,68.27508361 +211.04,50.43235045,-2.57019669,51.1748,3.691720383,9.289958339,-1.931875,-6.748176017,3.179522485,68.28260872 +211.05,50.43235078,-2.570195383,51.1938,3.691720388,9.291068479,-1.8815625,-6.848478983,3.216127498,68.29013377 +211.06,50.43235111,-2.570194075,51.2124,3.705625187,9.292178617,-1.8315625,-6.948395889,3.249927997,68.29765889 +211.07,50.43235145,-2.570192767,51.2305,3.7056252,9.292178578,-1.779375,-7.047905881,3.280894475,68.30518394 +211.08,50.43235178,-2.570191459,51.248,3.688244234,9.291290397,-1.725,-7.146988218,3.308999946,68.31270906 +211.09,50.43235211,-2.570190152,51.265,3.677815667,9.291290357,-1.67,-7.245622157,3.334220001,68.32023411 +211.1,50.43235244,-2.570188844,51.2814,3.688244267,9.292622529,-1.615,-7.343787188,3.356532524,68.32775923 +211.11,50.43235277,-2.570187536,51.2973,3.705625246,9.29439877,-1.56,-7.441462684,3.375918093,68.33528428 +211.12,50.43235311,-2.570186228,51.3126,3.705625249,9.295730939,-1.5046875,-7.538628362,3.392359804,68.34280934 +211.13,50.43235344,-2.570184919,51.3274,3.688244272,9.295730894,-1.4484375,-7.635263825,3.405843335,68.35033445 +211.14,50.43235377,-2.570183611,51.3416,3.674339494,9.294620673,-1.39125,-7.731348962,3.416356938,68.35785951 +211.15,50.4323541,-2.570182303,51.3552,3.674339513,9.293954523,-1.3334375,-7.826863719,3.423891391,68.36538462 +211.16,50.43235443,-2.570180995,51.3683,3.688244319,9.294842619,-1.2746875,-7.921788101,3.42844016,68.37290968 +211.17,50.43235476,-2.570179687,51.3807,3.705625307,9.29684089,-1.215,-8.016102339,3.42999935,68.38043479 +211.18,50.4323551,-2.570178378,51.3926,3.705625305,9.298173054,-1.155,-8.109786669,3.428567471,68.38795984 +211.19,50.43235543,-2.570177069,51.4038,3.68824432,9.298173005,-1.095,-8.20282155,3.424145841,68.39548496 +211.2,50.43235576,-2.570175761,51.4145,3.674339535,9.298172955,-1.035,-8.295187618,3.416738299,68.40301001 +211.21,50.43235609,-2.570174452,51.4245,3.670863351,9.29839494,-0.9746875,-8.386865449,3.406351319,68.41053513 +211.22,50.43235642,-2.570173143,51.434,3.670863372,9.298172854,-0.9134375,-8.47783602,3.392993897,68.41806018 +211.23,50.43235675,-2.570171835,51.4428,3.670863388,9.298394837,-0.85125,-8.568080311,3.376677778,68.42558529 +211.24,50.43235708,-2.570170526,51.451,3.670863387,9.299504961,-0.7884375,-8.657579412,3.357417171,68.43311035 +211.25,50.43235741,-2.570169217,51.4586,3.670863376,9.300393049,-0.725,-8.746314704,3.335228808,68.44063546 +211.26,50.43235774,-2.570167908,51.4655,3.670863373,9.30061503,-0.661875,-8.834267622,3.31013211,68.44816052 +211.27,50.43235807,-2.570166599,51.4718,3.670863377,9.300837011,-0.6,-8.921419773,3.282148909,68.45568563 +211.28,50.4323584,-2.57016529,51.4775,3.670863387,9.301725096,-0.5378125,-9.007753054,3.251303611,68.46321069 +211.29,50.43235873,-2.570163981,51.4826,3.670863404,9.302835215,-0.4734375,-9.093249301,3.217623147,68.4707358 +211.3,50.43235906,-2.570162671,51.487,3.670863406,9.303057191,-0.4084375,-9.177890751,3.181136851,68.47826086 +211.31,50.43235939,-2.570161362,51.4907,3.670863395,9.302835096,-0.345,-9.261659702,3.141876579,68.48578597 +211.32,50.43235972,-2.570160053,51.4939,3.670863391,9.303279106,-0.2815625,-9.34453862,3.099876538,68.49331103 +211.33,50.43236005,-2.570158743,51.4964,3.670863392,9.304167187,-0.2165625,-9.426510259,3.05517334,68.50083614 +211.34,50.43236038,-2.570157434,51.4982,3.6708634,9.305277302,-0.151875,-9.507557546,3.007806002,68.5083612 +211.35,50.43236071,-2.570156124,51.4994,3.670863417,9.306609451,-0.088125,-9.587663406,2.957815836,68.51588631 +211.36,50.43236104,-2.570154814,51.5,3.667387227,9.307275493,-0.0234375,-9.666811222,2.905246385,68.52341136 +211.37,50.43236137,-2.570153504,51.4999,3.653482429,9.306609322,0.041875,-9.744984438,2.850143487,68.53093648 +211.38,50.4323617,-2.570152194,51.4991,3.63610143,9.30549908,0.10625,-9.822166723,2.79255527,68.53846153 +211.39,50.43236202,-2.570150885,51.4978,3.636101425,9.305499014,0.17,-9.89834192,2.732531867,68.54598665 +211.4,50.43236235,-2.570149575,51.4957,3.653482419,9.306831159,0.23375,-9.973494216,2.670125705,68.5535117 +211.41,50.43236268,-2.570148265,51.4931,3.667387215,9.308607372,0.298125,-10.04760785,2.6053911,68.56103681 +211.42,50.43236301,-2.570146955,51.4898,3.670863408,9.309939514,0.3634375,-10.12066731,2.538384603,68.56856187 +211.43,50.43236334,-2.570145644,51.4858,3.667387201,9.309939444,0.4278125,-10.19265745,2.46916454,68.57608698 +211.44,50.43236367,-2.570144334,51.4812,3.653482402,9.309051232,0.49,-10.2635631,2.39779136,68.58361204 +211.45,50.432364,-2.570143024,51.476,3.636101413,9.309051161,0.551875,-10.33336958,2.324327284,68.5911371 +211.46,50.43236432,-2.570141714,51.4702,3.636101423,9.310161265,0.6153125,-10.40206224,2.248836313,68.59866221 +211.47,50.43236465,-2.570140403,51.4637,3.650006225,9.311271367,0.68,-10.46962674,2.171384394,68.60618726 +211.48,50.43236498,-2.570139093,51.4566,3.650006221,9.312159432,0.744375,-10.53604899,2.092038964,68.61371238 +211.49,50.43236531,-2.570137782,51.4488,3.636101412,9.312603427,0.8065625,-10.60131507,2.010869236,68.62123743 +211.5,50.43236563,-2.570136471,51.4404,3.636101396,9.312381317,0.866875,-10.66541146,1.927945971,68.62876255 +211.51,50.43236596,-2.570135161,51.4315,3.650006189,9.312603275,0.9284375,-10.72832463,1.843341534,68.6362876 +211.52,50.43236629,-2.57013385,51.4219,3.650006202,9.313713373,0.9915625,-10.79004152,1.75712972,68.64381272 +211.53,50.43236662,-2.570132539,51.4116,3.636101409,9.314601434,1.0528125,-10.8505493,1.669385588,68.65133777 +211.54,50.43236694,-2.570131228,51.4008,3.636101386,9.31482339,1.1115625,-10.90983519,1.5801858,68.65886288 +211.55,50.43236727,-2.570129917,51.3894,3.650006155,9.314823309,1.1703125,-10.96788693,1.489607991,68.66638794 +211.56,50.4323676,-2.570128606,51.3774,3.650006157,9.314823227,1.23,-11.02469232,1.397731286,68.67391305 +211.57,50.43236793,-2.570127295,51.3648,3.636101375,9.315045179,1.29,-11.0802396,1.304635728,68.68143811 +211.58,50.43236825,-2.570125984,51.3516,3.632625168,9.315711202,1.3496875,-11.13451704,1.210402448,68.68896322 +211.59,50.43236858,-2.570124673,51.3378,3.636101348,9.316155189,1.408125,-11.18751335,1.115113723,68.69648828 +211.6,50.43236891,-2.570123361,51.3234,3.629148941,9.315933068,1.4646875,-11.23921752,1.018852631,68.70401339 +211.61,50.43236923,-2.570122051,51.3085,3.618720347,9.316155017,1.52,-11.28961872,0.921703053,68.71153845 +211.62,50.43236956,-2.570120739,51.293,3.618720353,9.317487142,1.575,-11.33870637,0.82374973,68.71906356 +211.63,50.43236988,-2.570119428,51.277,3.629148941,9.319263337,1.63,-11.38647025,0.72507809,68.72658862 +211.64,50.43237021,-2.570118116,51.2604,3.636101314,9.320817496,1.685,-11.43290046,0.625774191,68.73411373 +211.65,50.43237054,-2.570116804,51.2433,3.629148898,9.321483513,1.7396875,-11.47798719,0.525924606,68.74163878 +211.66,50.43237086,-2.570115492,51.2256,3.618720301,9.320817317,1.793125,-11.52172112,0.42561637,68.7491639 +211.67,50.43237119,-2.57011418,51.2074,3.615244109,9.319707051,1.845,-11.56409301,0.324937028,68.75668895 +211.68,50.43237151,-2.570112869,51.1887,3.615244106,9.319706959,1.8965625,-11.6050941,0.223974301,68.76421407 +211.69,50.43237184,-2.570111557,51.1695,3.61872028,9.320817043,1.948125,-11.64471585,0.122816311,68.77173912 +211.7,50.43237216,-2.570110245,51.1497,3.629148846,9.321705092,1.998125,-11.68294989,0.021551177,68.77926424 +211.71,50.43237249,-2.570108933,51.1295,3.63610123,9.322149069,2.04625,-11.71978827,-0.079732749,68.78678929 +211.72,50.43237282,-2.570107621,51.1088,3.629148839,9.323037116,2.0934375,-11.75522331,-0.180947119,68.7943144 +211.73,50.43237314,-2.570106309,51.0876,3.618720237,9.324147196,2.14,-11.78924766,-0.282003696,68.80183946 +211.74,50.43237347,-2.570104996,51.066,3.615244015,9.324369136,2.1865625,-11.82185412,-0.38281436,68.80936457 +211.75,50.43237379,-2.570103684,51.0439,3.611767804,9.324147005,2.233125,-11.85303591,-0.483291218,68.81688963 +211.76,50.43237412,-2.570102372,51.0213,3.601339215,9.324590979,2.278125,-11.88278657,-0.583346666,68.82441474 +211.77,50.43237444,-2.570101059,50.9983,3.59438682,9.325256988,2.32125,-11.9110998,-0.682893385,68.8319398 +211.78,50.43237476,-2.570099747,50.9749,3.601339194,9.325478925,2.3634375,-11.9379698,-0.781844628,68.83946491 +211.79,50.43237509,-2.570098434,50.951,3.611767757,9.325700862,2.4046875,-11.96339085,-0.880114109,68.84698997 +211.8,50.43237541,-2.570097122,50.9268,3.615243942,9.326588903,2.4446875,-11.98735767,-0.977616056,68.85451502 +211.81,50.43237574,-2.570095809,50.9021,3.615243937,9.32769898,2.4834375,-12.00986529,-1.074265556,68.86204014 +211.82,50.43237606,-2.570094496,50.8771,3.611767724,9.327920915,2.52125,-12.030909,-1.169978271,68.86956519 +211.83,50.43237639,-2.570093183,50.8517,3.601339114,9.327698779,2.5584375,-12.05048439,-1.264670776,68.8770903 +211.84,50.43237671,-2.570091871,50.8259,3.594386707,9.328142748,2.5946875,-12.06858739,-1.358260453,68.88461536 +211.85,50.43237703,-2.570090557,50.7998,3.597862895,9.329030787,2.63,-12.08521417,-1.450665654,68.89214047 +211.86,50.43237736,-2.570089245,50.7733,3.597862885,9.329918825,2.6646875,-12.10036134,-1.541805935,68.89966553 +211.87,50.43237768,-2.570087931,50.7465,3.594386669,9.330362793,2.698125,-12.11402563,-1.631601657,68.90719064 +211.88,50.432378,-2.570086618,50.7193,3.597862846,9.330140655,2.7296875,-12.12620431,-1.719974668,68.9147157 +211.89,50.43237833,-2.570085305,50.6919,3.597862838,9.330362587,2.7596875,-12.13689473,-1.806847789,68.92224081 +211.9,50.43237865,-2.570083992,50.6641,3.594386635,9.331250624,2.7884375,-12.14609471,-1.892145334,68.92976587 +211.91,50.43237897,-2.570082678,50.6361,3.597862809,9.331472554,2.81625,-12.15380231,-1.975792875,68.93729098 +211.92,50.4323793,-2.570081365,50.6078,3.59786278,9.331472449,2.843125,-12.16001593,-2.057717531,68.94481604 +211.93,50.43237962,-2.570080052,50.5792,3.594386572,9.332804555,2.868125,-12.16473429,-2.137847799,68.95234115 +211.94,50.43237994,-2.570078738,50.5504,3.597862767,9.334802765,2.8915625,-12.16795638,-2.216113891,68.9598662 +211.95,50.43238027,-2.570077424,50.5214,3.594386555,9.3356908,2.915,-12.16968155,-2.292447454,68.96739132 +211.96,50.43238059,-2.57007611,50.4921,3.577005542,9.335024589,2.9378125,-12.16990942,-2.366781967,68.97491637 +211.97,50.43238091,-2.570074796,50.4626,3.566576933,9.333914307,2.958125,-12.16863991,-2.439052571,68.98244149 +211.98,50.43238123,-2.570073483,50.4329,3.577005518,9.3339142,2.9765625,-12.16587339,-2.509196357,68.98996654 +211.99,50.43238155,-2.570072169,50.4031,3.594386489,9.335024269,2.9946875,-12.1616103,-2.577152016,68.99749166 +212,50.43238188,-2.570070855,50.373,3.594386464,9.335912302,3.0115625,-12.15585167,-2.64286042,69.00501671 +212.01,50.4323822,-2.570069541,50.3428,3.577005459,9.336356265,3.02625,-12.14859854,-2.706264216,69.01254182 +212.02,50.43238252,-2.570068227,50.3125,3.566576859,9.337244299,3.04,-12.13985257,-2.767308056,69.02006688 +212.03,50.43238284,-2.570066913,50.282,3.577005432,9.338354367,3.053125,-12.12961553,-2.82593877,69.02759199 +212.04,50.43238316,-2.570065598,50.2514,3.594386387,9.338576293,3.0646875,-12.1178896,-2.88210525,69.03511705 +212.05,50.43238349,-2.570064284,50.2207,3.594386368,9.338354149,3.075,-12.10467714,-2.935758508,69.04264216 +212.06,50.43238381,-2.57006297,50.1899,3.577005384,9.338798111,3.0846875,-12.08998095,-2.986851732,69.05016722 +212.07,50.43238413,-2.570061655,50.159,3.563100589,9.339686144,3.0928125,-12.07380411,-3.035340349,69.05769233 +212.08,50.43238445,-2.570060341,50.128,3.559624369,9.340574176,3.098125,-12.05615002,-3.081182129,69.06521739 +212.09,50.43238477,-2.570059026,50.097,3.559624352,9.341018138,3.1015625,-12.03702234,-3.124337023,69.0727425 +212.1,50.43238509,-2.570057711,50.066,3.559624341,9.340795995,3.105,-12.01642508,-3.164767504,69.08026756 +212.11,50.43238541,-2.570056397,50.0349,3.563100513,9.341017922,3.108125,-11.99436254,-3.202438218,69.08779267 +212.12,50.43238573,-2.570055082,50.0038,3.577005267,9.342127989,3.1096875,-11.9708393,-3.237316394,69.09531772 +212.13,50.43238605,-2.570053767,49.9727,3.594386234,9.34301602,3.1096875,-11.94586023,-3.269371549,69.10284284 +212.14,50.43238638,-2.570052452,49.9416,3.594386232,9.343237946,3.108125,-11.91943066,-3.298575838,69.11036789 +212.15,50.4323867,-2.570051137,49.9105,3.577005237,9.343237837,3.1046875,-11.89155609,-3.32490365,69.11789295 +212.16,50.43238702,-2.570049822,49.8795,3.563100428,9.343237729,3.0996875,-11.86224225,-3.348332123,69.12541806 +212.17,50.43238734,-2.570048507,49.8485,3.559624212,9.343237621,3.0934375,-11.83149533,-3.368840746,69.13294312 +212.18,50.43238766,-2.570047192,49.8176,3.559624198,9.343459548,3.08625,-11.79932175,-3.386411758,69.14046823 +212.19,50.43238798,-2.570045877,49.7868,3.559624178,9.34434758,3.078125,-11.7657282,-3.401029745,69.14799329 +212.2,50.4323883,-2.570044562,49.756,3.559624161,9.345679683,3.068125,-11.73072174,-3.412681987,69.1555184 +212.21,50.43238862,-2.570043246,49.7254,3.559624147,9.346567716,3.05625,-11.69430964,-3.421358344,69.16304346 +212.22,50.43238894,-2.570041931,49.6949,3.556147932,9.346789643,3.0434375,-11.65649953,-3.427051196,69.17056857 +212.23,50.43238926,-2.570040615,49.6645,3.542243134,9.346789536,3.0296875,-11.6172993,-3.429755614,69.17809362 +212.24,50.43238958,-2.5700393,49.6343,3.524862148,9.346789429,3.015,-11.57671716,-3.429469192,69.18561874 +212.25,50.43238989,-2.570037984,49.6042,3.524862129,9.347011358,2.9996875,-11.53476147,-3.426192275,69.19314379 +212.26,50.43239021,-2.570036669,49.5743,3.542243076,9.347899392,2.9828125,-11.49144116,-3.419927669,69.20066891 +212.27,50.43239053,-2.570035353,49.5445,3.556147838,9.349231496,2.963125,-11.44676517,-3.410680818,69.20819396 +212.28,50.43239085,-2.570034037,49.515,3.559624031,9.35011953,2.9415625,-11.40074286,-3.3984598,69.21571908 +212.29,50.43239117,-2.570032721,49.4857,3.559624021,9.35034146,2.92,-11.35338383,-3.383275272,69.22324413 +212.3,50.43239149,-2.570031405,49.4566,3.559623998,9.350341354,2.898125,-11.30469794,-3.36514047,69.23076924 +212.31,50.43239181,-2.570030089,49.4277,3.556147787,9.350341248,2.8746875,-11.25469546,-3.344071208,69.2382943 +212.32,50.43239213,-2.570028773,49.3991,3.542242995,9.350341143,2.8496875,-11.20338668,-3.320085934,69.24581941 +212.33,50.43239245,-2.570027457,49.3707,3.524861997,9.350563075,2.823125,-11.15078251,-3.293205447,69.25334447 +212.34,50.43239276,-2.570026141,49.3426,3.524861975,9.351451112,2.7946875,-11.09689377,-3.263453239,69.26086958 +212.35,50.43239308,-2.570024825,49.3148,3.542242944,9.352783219,2.765,-11.04173174,-3.230855206,69.26839464 +212.36,50.4323934,-2.570023508,49.2873,3.552671523,9.353671255,2.735,-10.985308,-3.195439883,69.27591975 +212.37,50.43239372,-2.570022192,49.2601,3.542242921,9.353893188,2.7046875,-10.92763436,-3.157238093,69.28344481 +212.38,50.43239404,-2.570020875,49.2332,3.524861931,9.354115121,2.673125,-10.86872272,-3.116283128,69.29096992 +212.39,50.43239435,-2.570019559,49.2066,3.524861912,9.354781126,2.6396875,-10.80858553,-3.07261068,69.29849498 +212.4,50.43239467,-2.570018242,49.1804,3.538766664,9.355225095,2.6046875,-10.74723527,-3.02625891,69.30602009 +212.41,50.43239499,-2.570016925,49.1545,3.538766646,9.355002959,2.568125,-10.68468478,-2.977268211,69.31354514 +212.42,50.43239531,-2.570015609,49.129,3.524861863,9.355224894,2.53,-10.62094712,-2.925681269,69.32107026 +212.43,50.43239562,-2.570014292,49.1039,3.524861858,9.356112935,2.4915625,-10.55603559,-2.871543059,69.32859531 +212.44,50.43239594,-2.570012975,49.0792,3.538766624,9.356334872,2.4534375,-10.48996376,-2.814900853,69.33612043 +212.45,50.43239626,-2.570011658,49.0548,3.538766606,9.356334774,2.4146875,-10.42274544,-2.755803981,69.34364548 +212.46,50.43239658,-2.570010342,49.0309,3.524861807,9.357444851,2.374375,-10.35439461,-2.694304066,69.3511706 +212.47,50.43239689,-2.570009024,49.0073,3.521385601,9.358554929,2.331875,-10.2849256,-2.630454623,69.35869565 +212.48,50.43239721,-2.570007707,48.9842,3.524861793,9.358554833,2.2878125,-10.2143529,-2.564311401,69.36622076 +212.49,50.43239753,-2.57000639,48.9616,3.521385587,9.358776772,2.2434375,-10.14269123,-2.495932097,69.37374582 +212.5,50.43239784,-2.570005073,48.9393,3.521385573,9.359886852,2.198125,-10.06995561,-2.425376241,69.38127088 +212.51,50.43239816,-2.570003755,48.9176,3.524861756,9.360774898,2.1515625,-9.996161171,-2.352705483,69.38879599 +212.52,50.43239848,-2.570002438,48.8963,3.521385541,9.360996839,2.105,-9.921323372,-2.277983077,69.39632104 +212.53,50.43239879,-2.57000112,48.8755,3.521385516,9.360996746,2.058125,-9.845457801,-2.201274284,69.40384616 +212.54,50.43239911,-2.569999803,48.8551,3.524861705,9.360996654,2.0096875,-9.76858033,-2.122645911,69.41137121 +212.55,50.43239943,-2.569998485,48.8353,3.517909321,9.361218598,1.9596875,-9.690707,-2.042166597,69.41889633 +212.56,50.43239974,-2.569997168,48.8159,3.507480736,9.361884613,1.9084375,-9.611854027,-1.959906417,69.42642138 +212.57,50.43240006,-2.56999585,48.7971,3.50400453,9.362328593,1.8565625,-9.53203797,-1.875937217,69.4339465 +212.58,50.43240037,-2.569994532,48.7788,3.504004509,9.362328504,1.805,-9.451275501,-1.790332166,69.44147155 +212.59,50.43240069,-2.569993215,48.761,3.504004482,9.363216555,1.753125,-9.36958335,-1.703165919,69.44899666 +212.6,50.432401,-2.569991897,48.7437,3.504004468,9.364770713,1.6996875,-9.286978707,-1.614514509,69.45652172 +212.61,50.43240132,-2.569990578,48.727,3.504004475,9.365214697,1.645,-9.203478817,-1.524455169,69.46404683 +212.62,50.43240163,-2.569989261,48.7108,3.504004481,9.364770541,1.59,-9.119101042,-1.43306651,69.47157189 +212.63,50.43240195,-2.569987942,48.6952,3.504004475,9.364770456,1.5346875,-9.033863085,-1.340428173,69.479097 +212.64,50.43240226,-2.569986625,48.6801,3.504004458,9.365658512,1.478125,-8.94778265,-1.246621001,69.48662206 +212.65,50.43240258,-2.569985306,48.6656,3.504004437,9.366990638,1.42,-8.860877787,-1.151726757,69.49414717 +212.66,50.43240289,-2.569983988,48.6517,3.504004423,9.367656661,1.3615625,-8.773166658,-1.055828176,69.50167223 +212.67,50.43240321,-2.569982669,48.6384,3.504004423,9.367212509,1.3034375,-8.684667539,-0.959008851,69.50919734 +212.68,50.43240352,-2.569981351,48.6256,3.504004429,9.366990393,1.245,-8.595398939,-0.861353294,69.5167224 +212.69,50.43240384,-2.569980033,48.6135,3.504004429,9.368100488,1.18625,-8.505379419,-0.762946647,69.52424751 +212.7,50.43240415,-2.569978714,48.6019,3.504004416,9.369210584,1.126875,-8.414627947,-0.663874681,69.53177256 +212.71,50.43240447,-2.569977395,48.5909,3.5040044,9.369210506,1.06625,-8.323163313,-0.564223798,69.53929768 +212.72,50.43240478,-2.569976077,48.5806,3.500528197,9.369210429,1.005,-8.231004656,-0.464080917,69.54682273 +212.73,50.4324051,-2.569974758,48.5708,3.490099608,9.369432387,0.9434375,-8.138171284,-0.363533356,69.55434785 +212.74,50.43240541,-2.569973439,48.5617,3.483147211,9.369210277,0.8815625,-8.044682563,-0.262668777,69.5618729 +212.75,50.43240572,-2.569972121,48.5532,3.486623404,9.369654273,0.82,-7.950557973,-0.16157513,69.56939802 +212.76,50.43240604,-2.569970802,48.5453,3.486623411,9.371652515,0.7584375,-7.855817167,-0.060340592,69.57692307 +212.77,50.43240635,-2.569969483,48.538,3.48314722,9.373650756,0.69625,-7.760480027,0.040946543,69.58444818 +212.78,50.43240666,-2.569968163,48.5314,3.486623412,9.373872719,0.6334375,-7.664566319,0.142197983,69.59197324 +212.79,50.43240698,-2.569966844,48.5253,3.486623402,9.372984509,0.57,-7.568096212,0.243325435,69.59949835 +212.8,50.43240729,-2.569965525,48.52,3.4831472,9.372984439,0.50625,-7.471089759,0.344240664,69.60702341 +212.81,50.4324076,-2.569964206,48.5152,3.486623393,9.373872511,0.4421875,-7.373567243,0.444855777,69.61454852 +212.82,50.43240792,-2.569962886,48.5111,3.486623384,9.374094478,0.3778125,-7.275549061,0.545082883,69.62207358 +212.83,50.43240823,-2.569961567,48.5077,3.483147181,9.373872376,0.31375,-7.177055668,0.64483472,69.62959863 +212.84,50.43240854,-2.569960248,48.5048,3.486623381,9.37431638,0.25,-7.078107633,0.744024257,69.63712375 +212.85,50.43240886,-2.569958928,48.5027,3.483147192,9.375204455,0.18625,-6.978725582,0.842564976,69.6446488 +212.86,50.43240917,-2.569957609,48.5011,3.46924241,9.376092531,0.121875,-6.878930314,0.940370992,69.65217392 +212.87,50.43240948,-2.569956289,48.5002,3.469242412,9.376536537,0.05625,-6.778742628,1.03735699,69.65969897 +212.88,50.43240979,-2.569954969,48.5,3.483147193,9.376536475,-0.009375,-6.678183493,1.133438346,69.66722408 +212.89,50.43241011,-2.56995365,48.5004,3.483147191,9.377424554,-0.0734375,-6.577273879,1.228531349,69.67474914 +212.9,50.43241042,-2.56995233,48.5015,3.46576622,9.378756703,-0.1365625,-6.47603493,1.322553093,69.68227425 +212.91,50.43241073,-2.569951009,48.5031,3.455337643,9.378534609,-0.2003125,-6.374487672,1.41542153,69.68979931 +212.92,50.43241104,-2.56994969,48.5055,3.465766227,9.377646411,-0.265,-6.272653362,1.507055701,69.69732442 +212.93,50.43241135,-2.56994837,48.5084,3.483147192,9.377868389,-0.3296875,-6.170553314,1.59737568,69.70484948 +212.94,50.43241167,-2.56994705,48.5121,3.483147185,9.378756473,-0.3934375,-6.068208785,1.68630274,69.71237459 +212.95,50.43241198,-2.56994573,48.5163,3.465766218,9.379866592,-0.4565625,-5.965641204,1.773759304,69.71989965 +212.96,50.43241229,-2.56994441,48.5212,3.451861447,9.381198747,-0.5203125,-5.862871941,1.859669112,69.72742476 +212.97,50.4324126,-2.569943089,48.5267,3.448385255,9.382086834,-0.5846875,-5.759922484,1.943957277,69.73494982 +212.98,50.43241291,-2.569941769,48.5329,3.448385263,9.382308817,-0.6484375,-5.656814317,2.026550289,69.74247493 +212.99,50.43241322,-2.569940448,48.5397,3.451861469,9.382308766,-0.71125,-5.553568984,2.107376127,69.74999998 +213,50.43241353,-2.569939128,48.5471,3.465766254,9.382308715,-0.7734375,-5.450208028,2.186364261,69.7575251 +213.01,50.43241384,-2.569937807,48.5552,3.483147225,9.3825307,-0.835,-5.346753049,2.263445877,69.76505015 +213.02,50.43241416,-2.569936487,48.5638,3.483147219,9.383196755,-0.8965625,-5.243225706,2.338553769,69.77257527 +213.03,50.43241447,-2.569935166,48.5731,3.465766246,9.383862813,-0.9584375,-5.139647542,2.411622389,69.78010032 +213.04,50.43241478,-2.569933845,48.583,3.451861475,9.384306836,-1.02,-5.036040214,2.482588025,69.78762544 +213.05,50.43241509,-2.569932525,48.5935,3.448385291,9.384750859,-1.0815625,-4.932425323,2.551388797,69.79515049 +213.06,50.4324154,-2.569931203,48.6046,3.448385303,9.384750814,-1.143125,-4.828824584,2.617964716,69.8026756 +213.07,50.43241571,-2.569929883,48.6164,3.448385317,9.384528735,-1.2028125,-4.725259598,2.682257743,69.81020066 +213.08,50.43241602,-2.569928562,48.6287,3.448385323,9.385194797,-1.26,-4.621751965,2.744211841,69.81772577 +213.09,50.43241633,-2.569927241,48.6416,3.448385324,9.386748999,-1.316875,-4.518323343,2.803772867,69.82525083 +213.1,50.43241664,-2.56992592,48.655,3.448385327,9.388081167,-1.375,-4.414995332,2.860889024,69.83277594 +213.11,50.43241695,-2.569924598,48.6691,3.448385339,9.388081126,-1.4334375,-4.311789475,2.915510408,69.840301 +213.12,50.43241726,-2.569923277,48.6837,3.448385352,9.387192947,-1.49125,-4.208727317,2.967589464,69.84782611 +213.13,50.43241757,-2.569921956,48.6989,3.448385353,9.387192908,-1.548125,-4.1058304,3.017080699,69.85535117 +213.14,50.43241788,-2.569920635,48.7147,3.448385351,9.388303044,-1.603125,-4.003120266,3.063941027,69.86287628 +213.15,50.43241819,-2.569919313,48.731,3.444909165,9.389413182,-1.656875,-3.900618289,3.108129537,69.87040134 +213.16,50.4324185,-2.569917992,48.7478,3.431004404,9.390301285,-1.7115625,-3.798345895,3.149607671,69.87792645 +213.17,50.43241881,-2.56991667,48.7652,3.413623446,9.39074532,-1.7665625,-3.696324457,3.188339388,69.8854515 +213.18,50.43241911,-2.569915348,48.7832,3.413623456,9.39052325,-1.819375,-3.594575289,3.224290771,69.89297656 +213.19,50.43241942,-2.569914027,48.8016,3.431004436,9.390745251,-1.87,-3.493119647,3.257430478,69.90050167 +213.2,50.43241973,-2.569912705,48.8206,3.444909223,9.391855393,-1.9203125,-3.391978616,3.287729747,69.90802673 +213.21,50.43242004,-2.569911383,48.84,3.448385433,9.3927435,-1.97125,-3.291173452,3.315161992,69.91555184 +213.22,50.43242035,-2.569910061,48.86,3.444909256,9.392965503,-2.0215625,-3.190725185,3.339703436,69.9230769 +213.23,50.43242066,-2.569908739,48.8805,3.431004488,9.392965472,-2.0696875,-3.090654725,3.361332593,69.93060201 +213.24,50.43242097,-2.569907417,48.9014,3.413623522,9.392965442,-2.1165625,-2.990983045,3.380030555,69.93812707 +213.25,50.43242127,-2.569906095,48.9228,3.413623529,9.392965412,-2.1634375,-2.891730884,3.395781165,69.94565218 +213.26,50.43242158,-2.569904773,48.9447,3.431004505,9.393187419,-2.2096875,-2.792918983,3.408570557,69.95317724 +213.27,50.43242189,-2.569903451,48.967,3.44490929,9.39407553,-2.2546875,-2.694568028,3.418387616,69.96070235 +213.28,50.4324222,-2.569902129,48.9898,3.444909311,9.395185677,-2.2984375,-2.596698586,3.425223804,69.9682274 +213.29,50.43242251,-2.569900806,49.013,3.431004556,9.395407685,-2.34125,-2.499330997,3.429073164,69.97575252 +213.3,50.43242282,-2.569899484,49.0366,3.413623593,9.395407659,-2.3834375,-2.402485603,3.429932314,69.98327757 +213.31,50.43242312,-2.569898162,49.0607,3.4136236,9.396517808,-2.4246875,-2.306182742,3.42780051,69.99080269 +213.32,50.43242343,-2.569896839,49.0851,3.427528391,9.397627957,-2.4646875,-2.210442411,3.422679585,69.99832774 +213.33,50.43242374,-2.569895516,49.11,3.427528409,9.397627932,-2.503125,-2.115284606,3.414574066,70.00585286 +213.34,50.43242405,-2.569894194,49.1352,3.413623647,9.397627908,-2.5396875,-2.020729324,3.403490942,70.01337791 +213.35,50.43242435,-2.569892871,49.1608,3.410147467,9.397849921,-2.5753125,-1.92679616,3.389439954,70.02090302 +213.36,50.43242466,-2.569891548,49.1867,3.413623677,9.397627864,-2.6115625,-1.833504822,3.372433364,70.02842808 +213.37,50.43242497,-2.569890226,49.213,3.410147493,9.397849877,-2.6478125,-1.740874736,3.352485895,70.03595319 +213.38,50.43242527,-2.569888903,49.2397,3.410147501,9.39896003,-2.68125,-1.648925323,3.329615024,70.04347825 +213.39,50.43242558,-2.56988758,49.2667,3.413623707,9.400070183,-2.7115625,-1.557675663,3.30384069,70.05100336 +213.4,50.43242589,-2.569886257,49.2939,3.410147531,9.401180336,-2.741875,-1.467144951,3.275185409,70.05852842 +213.41,50.43242619,-2.569884934,49.3215,3.410147552,9.402290491,-2.773125,-1.377352037,3.243674048,70.06605353 +213.42,50.4324265,-2.56988361,49.3494,3.413623765,9.402290471,-2.8028125,-1.288315656,3.209334166,70.07357859 +213.43,50.43242681,-2.569882287,49.3776,3.406671389,9.401402312,-2.8296875,-1.200054372,3.17219573,70.0811037 +213.44,50.43242711,-2.569880964,49.406,3.396242813,9.401402294,-2.855,-1.112586693,3.132291053,70.08862876 +213.45,50.43242742,-2.569879641,49.4347,3.396242815,9.40251245,-2.88,-1.025930837,3.089654971,70.09615387 +213.46,50.43242772,-2.569878317,49.4636,3.406671409,9.403400572,-2.904375,-0.940104968,3.044324728,70.10367892 +213.47,50.43242803,-2.569876994,49.4928,3.413623825,9.403622589,-2.9265625,-0.855126904,2.996339742,70.11120404 +213.48,50.43242834,-2.56987567,49.5222,3.406671463,9.403844606,-2.9465625,-0.771014465,2.945741896,70.11872909 +213.49,50.43242864,-2.569874347,49.5517,3.396242896,9.404732728,-2.9665625,-0.687785184,2.892575309,70.12625421 +213.5,50.43242895,-2.569873023,49.5815,3.392766716,9.406064921,-2.9865625,-0.60545642,2.836886389,70.13377926 +213.51,50.43242925,-2.569871699,49.6115,3.392766732,9.40673101,-3.004375,-0.524045419,2.77872361,70.14130438 +213.52,50.43242956,-2.569870375,49.6416,3.392766749,9.406064889,-3.0196875,-0.4435692,2.718137792,70.14882943 +213.53,50.43242986,-2.569869051,49.6719,3.392766763,9.404954699,-3.0334375,-0.364044491,2.655181706,70.15635449 +213.54,50.43243017,-2.569867728,49.7023,3.392766772,9.405176718,-3.04625,-0.285487967,2.589910239,70.1638796 +213.55,50.43243047,-2.569866404,49.7328,3.392766784,9.407175016,-3.0584375,-0.207916013,2.522380345,70.17140466 +213.56,50.43243078,-2.56986508,49.7635,3.392766805,9.409173315,-3.0696875,-0.131344845,2.452650923,70.17892977 +213.57,50.43243108,-2.569863755,49.7942,3.392766829,9.409395336,-3.0796875,-0.05579039,2.380782706,70.18645483 +213.58,50.43243139,-2.569862431,49.8251,3.392766847,9.408507181,-3.088125,0.018731537,2.306838435,70.19397994 +213.59,50.43243169,-2.569861107,49.856,3.392766864,9.408507165,-3.0946875,0.092205353,2.230882623,70.20150499 +213.6,50.432432,-2.569859783,49.887,3.392766881,9.40939529,-3.1,0.164615702,2.152981391,70.20903011 +213.61,50.4324323,-2.569858458,49.918,3.389290701,9.409617311,-3.1046875,0.235947515,2.07320269,70.21655516 +213.62,50.43243261,-2.569857134,49.9491,3.378862128,9.409395261,-3.108125,0.306185838,1.991616193,70.22408028 +213.63,50.43243291,-2.56985581,49.9802,3.371909746,9.409839316,-3.1096875,0.375316061,1.908292946,70.23160533 +213.64,50.43243321,-2.569854485,50.0113,3.375385957,9.410505407,-3.1096875,0.443323745,1.823305658,70.23913044 +213.65,50.43243352,-2.569853161,50.0424,3.375385984,9.410949463,-3.108125,0.510194623,1.736728412,70.2466555 +213.66,50.43243382,-2.569851836,50.0735,3.371909814,9.411837588,-3.105,0.575914716,1.648636667,70.25418061 +213.67,50.43243412,-2.569850512,50.1045,3.378862214,9.412947747,-3.10125,0.640470443,1.55910737,70.26170567 +213.68,50.43243443,-2.569849186,50.1355,3.389290807,9.413169767,-3.0965625,0.70384817,1.468218445,70.26923078 +213.69,50.43243473,-2.569847862,50.1665,3.389290826,9.412947717,-3.0896875,0.766034775,1.376049245,70.27675584 +213.7,50.43243504,-2.569846537,50.1973,3.375386065,9.413391773,-3.0815625,0.827017136,1.2826801,70.28428095 +213.71,50.43243534,-2.569845212,50.2281,3.358005103,9.414279898,-3.0734375,0.88678265,1.188192427,70.29180601 +213.72,50.43243564,-2.569843887,50.2588,3.358005119,9.415390059,-3.064375,0.945318826,1.092668617,70.29933112 +213.73,50.43243594,-2.569842562,50.2894,3.37190992,9.416500218,-3.0528125,1.002613345,0.996192035,70.30685618 +213.74,50.43243625,-2.569841236,50.3199,3.375386133,9.416500203,-3.038125,1.05865429,0.898846735,70.31438129 +213.75,50.43243655,-2.569839911,50.3502,3.371909953,9.415612047,-3.021875,1.113429972,0.800717571,70.32190635 +213.76,50.43243685,-2.569838586,50.3803,3.375386165,9.415612031,-3.0065625,1.166928932,0.701890259,70.32943146 +213.77,50.43243716,-2.569837261,50.4103,3.371909985,9.41672219,-2.99125,1.219140055,0.602450855,70.33695651 +213.78,50.43243746,-2.569835935,50.4402,3.354529019,9.417610313,-2.9728125,1.27005234,0.502486106,70.34448163 +213.79,50.43243776,-2.56983461,50.4698,3.344100447,9.417832332,-2.9515625,1.319655244,0.402083159,70.35200668 +213.8,50.43243806,-2.569833284,50.4992,3.354529051,9.418054351,-2.9303125,1.36793834,0.30132962,70.3595318 +213.81,50.43243836,-2.569831959,50.5284,3.371910048,9.418720438,-2.9096875,1.414891601,0.200313264,70.36705685 +213.82,50.43243867,-2.569830633,50.5574,3.371910063,9.419164491,-2.8878125,1.460505172,0.099122272,70.37458196 +213.83,50.43243897,-2.569829307,50.5862,3.354529097,9.418942438,-2.863125,1.504769542,-0.002155123,70.38210702 +213.84,50.43243927,-2.569827982,50.6147,3.340624327,9.419164455,-2.8365625,1.547675487,-0.103430685,70.38963213 +213.85,50.43243957,-2.569826656,50.6429,3.340624338,9.420274612,-2.8096875,1.58921401,-0.204616063,70.39715719 +213.86,50.43243987,-2.56982533,50.6709,3.354529125,9.421162733,-2.7815625,1.629376518,-0.305622964,70.4046823 +213.87,50.43244017,-2.569824004,50.6986,3.371910113,9.421384749,-2.75125,1.668154531,-0.406363383,70.41220736 +213.88,50.43244048,-2.569822678,50.7259,3.371910136,9.421384729,-2.72,1.70553997,-0.506749428,70.41973241 +213.89,50.43244078,-2.569821352,50.753,3.354529184,9.421606744,-2.6884375,1.741525043,-0.606693607,70.42725753 +213.9,50.43244108,-2.569820026,50.7797,3.340624423,9.422494863,-2.65625,1.776102243,-0.706108775,70.43478258 +213.91,50.43244138,-2.5698187,50.8061,3.337148245,9.423605017,-2.623125,1.809264353,-0.804908127,70.4423077 +213.92,50.43244168,-2.569817373,50.8322,3.337148255,9.42382703,-2.5878125,1.841004439,-0.903005607,70.44983275 +213.93,50.43244198,-2.569816047,50.8579,3.337148264,9.423604973,-2.55,1.871315854,-1.00031567,70.45735786 +213.94,50.43244228,-2.569814721,50.8832,3.337148282,9.424049021,-2.511875,1.900192297,-1.096753462,70.46488292 +213.95,50.43244258,-2.569813394,50.9081,3.3371483,9.424937138,-2.4746875,1.927627693,-1.192234874,70.47240803 +213.96,50.43244288,-2.569812068,50.9327,3.337148308,9.42604729,-2.43625,1.953616371,-1.286676596,70.47993309 +213.97,50.43244318,-2.569810741,50.9569,3.337148314,9.42715744,-2.3946875,1.978152888,-1.379996352,70.4874582 +213.98,50.43244348,-2.569809414,50.9806,3.337148325,9.427157415,-2.351875,2.001232086,-1.472112724,70.49498326 +213.99,50.43244378,-2.569808087,51.0039,3.337148337,9.42626925,-2.31,2.022849154,-1.562945328,70.50250837 +214,50.43244408,-2.569806761,51.0268,3.337148349,9.426269225,-2.2678125,2.042999564,-1.652415094,70.51003343 +214.01,50.43244438,-2.569805434,51.0493,3.337148361,9.427379373,-2.223125,2.061679191,-1.740443929,70.51755854 +214.02,50.43244468,-2.569804107,51.0713,3.337148373,9.428267486,-2.1765625,2.078884082,-1.826955055,70.5250836 +214.03,50.43244498,-2.56980278,51.0928,3.337148384,9.428489492,-2.13,2.09461057,-1.911873015,70.53260871 +214.04,50.43244528,-2.569801453,51.1139,3.337148396,9.428489464,-2.083125,2.108855504,-1.99512384,70.54013377 +214.05,50.43244558,-2.569800126,51.1345,3.337148407,9.428489435,-2.0346875,2.121615847,-2.076634879,70.54765888 +214.06,50.43244588,-2.569798799,51.1546,3.337148417,9.42871144,-1.985,2.132888907,-2.156335027,70.55518393 +214.07,50.43244618,-2.569797472,51.1742,3.337148428,9.429599548,-1.9346875,2.142672333,-2.234154842,70.56270905 +214.08,50.43244648,-2.569796145,51.1933,3.337148438,9.430709691,-1.8834375,2.150964121,-2.310026487,70.5702341 +214.09,50.43244678,-2.569794817,51.2119,3.333672251,9.430931694,-1.8315625,2.157762552,-2.383883669,70.57775922 +214.1,50.43244708,-2.56979349,51.2299,3.319767474,9.430709627,-1.7796875,2.163066135,-2.45566216,70.58528427 +214.11,50.43244738,-2.569792163,51.2475,3.3023865,9.431153663,-1.7265625,2.166873841,-2.525299221,70.59280938 +214.12,50.43244767,-2.569790835,51.2645,3.302386509,9.432041768,-1.6715625,2.169184809,-2.592734176,70.60033444 +214.13,50.43244797,-2.569789508,51.2809,3.319767501,9.433151908,-1.616875,2.169998581,-2.65790824,70.60785955 +214.14,50.43244827,-2.56978818,51.2968,3.333672296,9.434262047,-1.563125,2.169314985,-2.720764575,70.61538461 +214.15,50.43244857,-2.569786852,51.3122,3.333672305,9.43426201,-1.5078125,2.167134193,-2.781248349,70.62290972 +214.16,50.43244887,-2.569785524,51.327,3.319767525,9.433373833,-1.45,2.163456663,-2.83930685,70.63043478 +214.17,50.43244917,-2.569784197,51.3412,3.302386549,9.433373794,-1.3915625,2.158283084,-2.894889428,70.63795989 +214.18,50.43244946,-2.569782869,51.3548,3.302386557,9.43448393,-1.3334375,2.1516146,-2.947947612,70.64548495 +214.19,50.43244976,-2.569781541,51.3679,3.316291351,9.43537203,-1.275,2.143452587,-2.998435163,70.65301006 +214.2,50.43245006,-2.569780213,51.3803,3.316291359,9.435594023,-1.2165625,2.133798764,-3.046308021,70.66053512 +214.21,50.43245036,-2.569778885,51.3922,3.302386585,9.435816017,-1.158125,2.122655193,-3.091524475,70.66806017 +214.22,50.43245065,-2.569777557,51.4035,3.302386596,9.436704114,-1.098125,2.110024052,-3.134045048,70.67558529 +214.23,50.43245095,-2.569776229,51.4142,3.316291384,9.437814245,-1.0365625,2.095908148,-3.17383267,70.68311034 +214.24,50.43245125,-2.5697749,51.4242,3.316291385,9.438036235,-0.975,2.080310346,-3.210852676,70.69063545 +214.25,50.43245155,-2.569773572,51.4337,3.302386607,9.437814155,-0.9134375,2.063233855,-3.245072753,70.69816051 +214.26,50.43245184,-2.569772244,51.4425,3.29891042,9.438258179,-0.8515625,2.044682341,-3.276463105,70.70568562 +214.27,50.43245214,-2.569770915,51.4507,3.302386617,9.438924237,-0.79,2.024659643,-3.304996346,70.71321068 +214.28,50.43245244,-2.569769587,51.4583,3.298910417,9.439146224,-0.728125,2.003169887,-3.330647552,70.72073579 +214.29,50.43245273,-2.569768258,51.4653,3.298910419,9.43936821,-0.665,1.980217656,-3.353394434,70.72826085 +214.3,50.43245303,-2.56976693,51.4716,3.302386619,9.440034265,-0.6015625,1.955807706,-3.373217055,70.73578596 +214.31,50.43245333,-2.569765601,51.4773,3.298910425,9.440478285,-0.5384375,1.929945078,-3.390098168,70.74331102 +214.32,50.43245362,-2.569764272,51.4824,3.298910428,9.440256198,-0.475,1.902635274,-3.404023105,70.75083613 +214.33,50.43245392,-2.569762944,51.4868,3.30238663,9.44047818,-0.4115625,1.873883908,-3.414979663,70.75836119 +214.34,50.43245422,-2.569761615,51.4906,3.295434245,9.441588301,-0.3484375,1.843696997,-3.422958329,70.7658863 +214.35,50.43245451,-2.569760286,51.4938,3.285005661,9.442698421,-0.2846875,1.812080899,-3.427952115,70.77341135 +214.36,50.43245481,-2.569758957,51.4963,3.285005658,9.443586506,-0.2196875,1.779042204,-3.429956665,70.78093647 +214.37,50.4324551,-2.569757628,51.4982,3.295434243,9.444030519,-0.15375,1.744587731,-3.428970261,70.78846152 +214.38,50.4324554,-2.569756298,51.4994,3.302386635,9.443808427,-0.0884375,1.708724813,-3.424993704,70.79598664 +214.39,50.4324557,-2.56975497,51.4999,3.295434242,9.44380837,-0.025,1.671460784,-3.418030548,70.80351169 +214.4,50.43245599,-2.56975364,51.4999,3.285005651,9.44425238,0.0384375,1.632803551,-3.408086808,70.81103681 +214.41,50.43245629,-2.569752311,51.4992,3.281529454,9.44469639,0.1034375,1.592761135,-3.395171136,70.81856186 +214.42,50.43245658,-2.569750982,51.4978,3.281529456,9.445140399,0.168125,1.551341958,-3.379294877,70.82608697 +214.43,50.43245688,-2.569749652,51.4958,3.281529464,9.445140338,0.2315625,1.508554559,-3.360471781,70.83361203 +214.44,50.43245717,-2.569748323,51.4932,3.281529474,9.445140275,0.2953125,1.464407932,-3.338718292,70.84113714 +214.45,50.43245747,-2.569746994,51.4899,3.281529472,9.446250385,0.36,1.418911301,-3.314053433,70.8486622 +214.46,50.43245776,-2.569745664,51.486,3.281529459,9.447360495,0.425,1.372074179,-3.286498633,70.85618731 +214.47,50.43245806,-2.569744334,51.4814,3.281529448,9.44736043,0.4896875,1.323906304,-3.256077954,70.86371237 +214.48,50.43245835,-2.569743005,51.4762,3.278053247,9.447582399,0.553125,1.274417762,-3.222817983,70.87123748 +214.49,50.43245865,-2.569741675,51.4703,3.267624656,9.448692505,0.615,1.223618923,-3.186747597,70.87876254 +214.5,50.43245894,-2.569740345,51.4639,3.260672266,9.449580576,0.676875,1.171520329,-3.147898366,70.88628765 +214.51,50.43245923,-2.569739015,51.4568,3.26762466,9.449802542,0.7403125,1.118132924,-3.106304094,70.89381271 +214.52,50.43245953,-2.569737685,51.4491,3.278053242,9.449802472,0.804375,1.063467766,-3.062001106,70.90133782 +214.53,50.43245982,-2.569736355,51.4407,3.278053232,9.449802401,0.8665625,1.007536371,-3.015028021,70.90886287 +214.54,50.43246012,-2.569735025,51.4317,3.267624637,9.450024364,0.9265625,0.95035037,-2.965425747,70.91638799 +214.55,50.43246041,-2.569733695,51.4222,3.260672245,9.450912431,0.986875,0.891921738,-2.913237599,70.92391304 +214.56,50.4324607,-2.569732365,51.412,3.26762464,9.452022532,1.0484375,0.832262622,-2.858509014,70.9314381 +214.57,50.432461,-2.569731034,51.4012,3.278053227,9.452244493,1.1096875,0.77138557,-2.801287834,70.93896321 +214.58,50.43246129,-2.569729704,51.3898,3.27805322,9.452022382,1.17,0.709303187,-2.741623848,70.94648827 +214.59,50.43246159,-2.569728374,51.3778,3.264148422,9.452466375,1.23,0.646028478,-2.679569138,70.95401338 +214.6,50.43246188,-2.569727043,51.3652,3.246767432,9.453132403,1.2896875,0.581574679,-2.615177792,70.96153844 +214.61,50.43246217,-2.569725713,51.352,3.246767428,9.45335436,1.348125,0.515955255,-2.548506017,70.96906355 +214.62,50.43246246,-2.569724382,51.3382,3.260672203,9.453354281,1.405,0.4491839,-2.479611853,70.97658861 +214.63,50.43246276,-2.569723052,51.3239,3.264148386,9.453354201,1.4615625,0.381274536,-2.40855546,70.98411372 +214.64,50.43246305,-2.569721721,51.309,3.26067218,9.453576156,1.5184375,0.312241372,-2.335398777,70.99163877 +214.65,50.43246334,-2.569720391,51.2935,3.264148369,9.454464214,1.5746875,0.24209879,-2.260205572,70.99916389 +214.66,50.43246364,-2.56971906,51.2775,3.260672166,9.455796341,1.63,0.170861515,-2.183041449,71.00668894 +214.67,50.43246393,-2.569717729,51.2609,3.246767378,9.456684397,1.6846875,0.098544329,-2.103973675,71.01421406 +214.68,50.43246422,-2.569716398,51.2438,3.246767374,9.456906348,1.738125,0.025162416,-2.023071175,71.02173911 +214.69,50.43246451,-2.569715067,51.2261,3.260672149,9.456906264,1.79,-0.049268985,-1.940404595,71.02926423 +214.7,50.43246481,-2.569713736,51.208,3.26067214,9.457128214,1.841875,-0.124734287,-1.856045899,71.03678928 +214.71,50.4324651,-2.569712405,51.1893,3.243291152,9.458016267,1.895,-0.201217678,-1.770068711,71.04431439 +214.72,50.43246539,-2.569711074,51.1701,3.229386358,9.459126355,1.9478125,-0.278703287,-1.682548033,71.05183945 +214.73,50.43246568,-2.569709742,51.1503,3.229386346,9.459126268,1.9978125,-0.357174842,-1.593560067,71.05936456 +214.74,50.43246597,-2.569708411,51.1301,3.243291116,9.458238041,2.045,-0.436616013,-1.503182564,71.06688962 +214.75,50.43246626,-2.56970708,51.1094,3.260672082,9.458459987,2.091875,-0.517010128,-1.411494248,71.07441473 +214.76,50.43246656,-2.569705749,51.0883,3.260672071,9.460236175,2.1396875,-0.598340513,-1.318575104,71.08193979 +214.77,50.43246685,-2.569704417,51.0666,3.243291084,9.461568294,2.1865625,-0.680590151,-1.224506091,71.0894649 +214.78,50.43246714,-2.569703085,51.0445,3.229386293,9.461346168,2.23125,-0.763741797,-1.129369314,71.09698996 +214.79,50.43246743,-2.569701754,51.022,3.225910087,9.460679973,2.275,-0.847778147,-1.033247737,71.10451507 +214.8,50.43246772,-2.569700422,50.999,3.225910074,9.460679881,2.3184375,-0.932681612,-0.936225127,71.11204013 +214.81,50.43246801,-2.569699091,50.9756,3.225910058,9.461567928,2.36125,-1.018434543,-0.838386109,71.11956524 +214.82,50.4324683,-2.569697759,50.9518,3.225910046,9.462900043,2.403125,-1.105018951,-0.739816054,71.12709029 +214.83,50.43246859,-2.569696427,50.9275,3.229386232,9.463788088,2.443125,-1.19241673,-0.640600849,71.13461541 +214.84,50.43246888,-2.569695095,50.9029,3.243291002,9.464010028,2.4815625,-1.280609717,-0.54082701,71.14214046 +214.85,50.43246917,-2.569693763,50.8779,3.260671965,9.464009933,2.52,-1.369579406,-0.440581569,71.14966558 +214.86,50.43246947,-2.569692431,50.8525,3.260671952,9.464009837,2.558125,-1.459307347,-0.339951903,71.15719063 +214.87,50.43246976,-2.569691099,50.8267,3.243290964,9.464009741,2.5946875,-1.549774632,-0.239025845,71.16471575 +214.88,50.43247005,-2.569689767,50.8006,3.229386169,9.464009644,2.6296875,-1.64096247,-0.137891289,71.1722408 +214.89,50.43247034,-2.569688435,50.7741,3.225909959,9.464231582,2.6634375,-1.732851837,-0.036636583,71.17976591 +214.9,50.43247063,-2.569687103,50.7473,3.222433756,9.465119624,2.69625,-1.825423482,0.064650151,71.18729097 +214.91,50.43247092,-2.569685771,50.7202,3.208528964,9.466451735,2.728125,-1.918658096,0.165880449,71.19481603 +214.92,50.43247121,-2.569684438,50.6927,3.191147961,9.467339775,2.758125,-2.0125362,0.266966132,71.20234114 +214.93,50.43247149,-2.569683106,50.665,3.191147941,9.467561711,2.7865625,-2.107038197,0.367819023,71.20986619 +214.94,50.43247178,-2.569681773,50.637,3.208528909,9.467561613,2.815,-2.202144378,0.468351172,71.21739131 +214.95,50.43247207,-2.569680441,50.6087,3.222433676,9.467561514,2.8428125,-2.297834861,0.568474916,71.22491636 +214.96,50.43247236,-2.569679108,50.5801,3.225909853,9.467783448,2.868125,-2.394089651,0.668102937,71.23244148 +214.97,50.43247265,-2.569677776,50.5513,3.225909846,9.468449451,2.8915625,-2.490888636,0.767148318,71.23996653 +214.98,50.43247294,-2.569676443,50.5223,3.225909842,9.469115455,2.915,-2.588211591,0.86552477,71.24749165 +214.99,50.43247323,-2.56967511,50.493,3.225909827,9.469559423,2.9378125,-2.686038233,0.963146465,71.2550167 +215,50.43247352,-2.569673778,50.4635,3.222433608,9.470225426,2.958125,-2.784348165,1.059928319,71.26254181 +215.01,50.43247381,-2.569672444,50.4338,3.208528806,9.470891428,2.9765625,-2.88312076,1.15578582,71.27006687 +215.02,50.4324741,-2.569671112,50.404,3.191147812,9.471113361,2.9946875,-2.98233545,1.250635545,71.27759198 +215.03,50.43247438,-2.569669778,50.3739,3.191147797,9.471335294,3.0115625,-3.081971493,1.344394645,71.28511704 +215.04,50.43247467,-2.569668446,50.3437,3.208528769,9.472001296,3.02625,-3.18200809,1.436981416,71.29264215 +215.05,50.43247496,-2.569667112,50.3134,3.222433546,9.472667298,3.04,-3.282424387,1.528315128,71.30016721 +215.06,50.43247525,-2.569665779,50.2829,3.222433524,9.473111265,3.053125,-3.383199355,1.618316141,71.30769232 +215.07,50.43247554,-2.569664446,50.2523,3.208528717,9.473555231,3.0646875,-3.484311968,1.706905901,71.31521738 +215.08,50.43247583,-2.569663112,50.2216,3.191147721,9.473333093,3.0746875,-3.585741082,1.794007289,71.32274249 +215.09,50.43247611,-2.569661779,50.1908,3.191147701,9.472444851,3.0834375,-3.687465613,1.879544216,71.33026755 +215.1,50.4324764,-2.569660446,50.1599,3.205052464,9.472444748,3.09125,-3.78946419,1.963442196,71.33779266 +215.11,50.43247669,-2.569659113,50.129,3.205052449,9.473554818,3.098125,-3.891715613,2.045628007,71.34531771 +215.12,50.43247698,-2.569657779,50.0979,3.191147658,9.474664889,3.103125,-3.994198454,2.126029972,71.35284283 +215.13,50.43247726,-2.569656446,50.0669,3.187671457,9.47577496,3.10625,-4.096891398,2.204578074,71.36036788 +215.14,50.43247755,-2.569655112,50.0358,3.19114764,9.477107064,3.1084375,-4.199772903,2.281203673,71.367893 +215.15,50.43247784,-2.569653778,50.0047,3.187671424,9.4779951,3.109375,-4.302821483,2.355840077,71.37541805 +215.16,50.43247812,-2.569652444,49.9736,3.191147601,9.478217031,3.1084375,-4.406015708,2.428422142,71.38294317 +215.17,50.43247841,-2.56965111,49.9425,3.205052367,9.477994893,3.10625,-4.509333979,2.498886611,71.39046822 +215.18,50.4324787,-2.569649776,49.9115,3.205052358,9.47710665,3.1034375,-4.612754751,2.567172008,71.39799333 +215.19,50.43247899,-2.569648442,49.8804,3.18767137,9.476218408,3.0996875,-4.716256369,2.633218744,71.40551839 +215.2,50.43247927,-2.569647109,49.8495,3.173766564,9.477106444,3.094375,-4.81981723,2.696969294,71.4130435 +215.21,50.43247956,-2.569645775,49.8185,3.173766542,9.479326688,3.086875,-4.923415734,2.758368081,71.42056856 +215.22,50.43247984,-2.56964444,49.7877,3.184195114,9.480214724,3.0778125,-5.027030224,2.817361535,71.42809367 +215.23,50.43248013,-2.569643106,49.757,3.191147489,9.479548516,3.0684375,-5.130639041,2.873898145,71.43561873 +215.24,50.43248042,-2.569641772,49.7263,3.187671278,9.479548414,3.0578125,-5.234220586,2.927928753,71.44314384 +215.25,50.4324807,-2.569640438,49.6958,3.187671265,9.480658485,3.0446875,-5.337753257,2.979406089,71.4506689 +215.26,50.43248099,-2.569639103,49.6654,3.191147446,9.481546522,3.03,-5.44121534,3.028285347,71.45819395 +215.27,50.43248128,-2.569637769,49.6352,3.184195046,9.48154642,3.015,-5.544585349,3.074523958,71.46571907 +215.28,50.43248156,-2.569636434,49.6051,3.17376645,9.480880214,2.9996875,-5.647841568,3.11808147,71.47324412 +215.29,50.43248185,-2.5696351,49.5752,3.170290233,9.480658078,2.9828125,-5.750962512,3.158920011,71.48076923 +215.3,50.43248213,-2.569633766,49.5454,3.170290212,9.481990185,2.963125,-5.853926638,3.197003943,71.48829429 +215.31,50.43248242,-2.569632431,49.5159,3.170290199,9.483988396,2.9415625,-5.956712401,3.232299976,71.4958194 +215.32,50.4324827,-2.569631096,49.4866,3.170290189,9.484876434,2.92,-6.059298432,3.264777459,71.50334446 +215.33,50.43248299,-2.569629761,49.4575,3.170290182,9.484210231,2.898125,-6.161663186,3.294407971,71.51086957 +215.34,50.43248327,-2.569628426,49.4286,3.170290172,9.483099957,2.8746875,-6.26378535,3.321165673,71.51839463 +215.35,50.43248356,-2.569627092,49.4,3.170290151,9.483099858,2.8496875,-6.36564361,3.34502736,71.52591974 +215.36,50.43248384,-2.569625757,49.3716,3.170290128,9.484431966,2.8234375,-6.467216651,3.365972061,71.5334448 +215.37,50.43248413,-2.569624422,49.3435,3.170290119,9.486208145,2.79625,-6.568483274,3.383981615,71.54096991 +215.38,50.43248441,-2.569623087,49.3157,3.170290112,9.487540255,2.768125,-6.669422338,3.399040263,71.54849497 +215.39,50.4324847,-2.569621751,49.2881,3.170290092,9.487540157,2.738125,-6.770012814,3.411134944,71.55602008 +215.4,50.43248498,-2.569620416,49.2609,3.166813876,9.486651921,2.70625,-6.870233617,3.420255,71.56354513 +215.41,50.43248527,-2.569619081,49.234,3.156385276,9.486651824,2.6734375,-6.970063835,3.426392581,71.57107025 +215.42,50.43248555,-2.569617746,49.2074,3.14943287,9.487539866,2.6396875,-7.069482612,3.429542302,71.5785953 +215.43,50.43248583,-2.56961641,49.1812,3.152909055,9.487761805,2.6046875,-7.168469265,3.429701412,71.58612042 +215.44,50.43248612,-2.569615075,49.1553,3.152909051,9.487761711,2.5684375,-7.267002994,3.426869797,71.59364547 +215.45,50.4324864,-2.56961374,49.1298,3.149432845,9.48887179,2.5315625,-7.365063346,3.421049864,71.60117059 +215.46,50.43248668,-2.569612404,49.1047,3.152909026,9.489981869,2.4946875,-7.46262975,3.412246711,71.60869564 +215.47,50.43248697,-2.569611068,49.0799,3.152909016,9.489981775,2.4565625,-7.559681868,3.400468017,71.61622075 +215.48,50.43248725,-2.569609733,49.0555,3.149432809,9.489981682,2.41625,-7.656199416,3.385724094,71.62374581 +215.49,50.43248753,-2.569608397,49.0316,3.15290899,9.490425659,2.375,-7.752162284,3.368027777,71.63127092 +215.5,50.43248782,-2.569607061,49.008,3.152908981,9.490869637,2.333125,-7.84755036,3.347394478,71.63879598 +215.51,50.4324881,-2.569605726,48.9849,3.149432772,9.491313616,2.2896875,-7.942343821,3.323842245,71.64632109 +215.52,50.43248838,-2.569604389,48.9622,3.152908948,9.491313526,2.245,-8.036522727,3.297391477,71.65384615 +215.53,50.43248867,-2.569603054,48.94,3.152908935,9.491313436,2.1996875,-8.130067541,3.268065434,71.66137126 +215.54,50.43248895,-2.569601718,48.9182,3.149432731,9.492645554,2.1534375,-8.222958725,3.2358895,71.66889632 +215.55,50.43248923,-2.569600382,48.8969,3.152908916,9.494421743,2.10625,-8.315176797,3.200891862,71.67642143 +215.56,50.43248952,-2.569599045,48.8761,3.149432719,9.49464369,2.0584375,-8.406702508,3.163103004,71.68394649 +215.57,50.4324898,-2.569597709,48.8557,3.132051746,9.493755464,2.01,-8.497516777,3.122555869,71.6914716 +215.58,50.43249008,-2.569596373,48.8359,3.121623145,9.493755378,1.96125,-8.587600696,3.079285868,71.69899665 +215.59,50.43249036,-2.569595037,48.8165,3.132051707,9.494643432,1.9115625,-8.676935302,3.033330642,71.70652177 +215.6,50.43249064,-2.5695937,48.7976,3.149432672,9.494865382,1.8596875,-8.765502087,2.984730299,71.71404682 +215.61,50.43249093,-2.569592364,48.7793,3.149432672,9.494643264,1.8065625,-8.853282487,2.933527181,71.72157188 +215.62,50.43249121,-2.569591028,48.7615,3.132051689,9.49508725,1.7534375,-8.940258167,2.879766035,71.72909699 +215.63,50.43249149,-2.569589691,48.7442,3.118146899,9.495975307,1.6996875,-9.026410966,2.82349373,71.73662205 +215.64,50.43249177,-2.569588355,48.7275,3.1181469,9.496863364,1.645,-9.11172295,2.764759254,71.74414716 +215.65,50.43249205,-2.569587018,48.7113,3.132051676,9.497307353,1.59,-9.196176184,2.703613828,71.75167222 +215.66,50.43249233,-2.569585681,48.6957,3.149432631,9.497085239,1.535,-9.279753136,2.640110853,71.75919733 +215.67,50.43249262,-2.569584345,48.6806,3.149432618,9.497307195,1.4796875,-9.362436332,2.574305676,71.76672239 +215.68,50.4324929,-2.569583008,48.6661,3.132051641,9.498417289,1.423125,-9.444208467,2.506255651,71.7742475 +215.69,50.43249318,-2.569581671,48.6521,3.118146853,9.49930535,1.365,-9.525052526,2.436020135,71.78177255 +215.7,50.43249346,-2.569580334,48.6388,3.114670644,9.499527309,1.3065625,-9.604951548,2.363660378,71.78929767 +215.71,50.43249374,-2.569578997,48.626,3.114670643,9.499527233,1.248125,-9.68388886,2.289239463,71.79682272 +215.72,50.43249402,-2.56957766,48.6138,3.114670644,9.499527159,1.188125,-9.761848018,2.212822306,71.80434784 +215.73,50.4324943,-2.569576323,48.6022,3.114670634,9.499749122,1.126875,-9.838812751,2.134475484,71.81187289 +215.74,50.43249458,-2.569574986,48.5913,3.114670631,9.500637188,1.066875,-9.914766959,2.054267466,71.81939801 +215.75,50.43249486,-2.569573649,48.5809,3.114670637,9.501747289,1.008125,-9.98969477,1.972268038,71.82692306 +215.76,50.43249514,-2.569572311,48.5711,3.114670628,9.501969253,0.9478125,-10.06358054,1.888548763,71.83444817 +215.77,50.43249542,-2.569570974,48.5619,3.114670608,9.501747148,0.885,-10.13640886,1.803182635,71.84197323 +215.78,50.4324957,-2.569569637,48.5534,3.114670604,9.502191148,0.821875,-10.20816449,1.716244139,71.84949834 +215.79,50.43249598,-2.569568299,48.5455,3.114670616,9.503079219,0.76,-10.27883248,1.62780902,71.8570234 +215.8,50.43249626,-2.569566962,48.5382,3.114670617,9.503967291,0.698125,-10.34839803,1.537954456,71.86454851 +215.81,50.43249654,-2.569565624,48.5315,3.1146706,9.504411294,0.6346875,-10.41684661,1.446758712,71.87207357 +215.82,50.43249682,-2.569564286,48.5255,3.114670591,9.504189195,0.5703125,-10.48416399,1.354301429,71.87959868 +215.83,50.4324971,-2.569562949,48.5201,3.114670597,9.50418913,0.5065625,-10.55033609,1.260663166,71.88712374 +215.84,50.43249738,-2.569561611,48.5154,3.114670602,9.504411101,0.4434375,-10.61534904,1.165925568,71.89464885 +215.85,50.43249766,-2.569560273,48.5112,3.114670595,9.504189005,0.38,-10.67918932,1.070171315,71.90217391 +215.86,50.43249794,-2.569558936,48.5078,3.11467059,9.504633013,0.31625,-10.74184357,0.973483827,71.90969902 +215.87,50.43249822,-2.569557598,48.5049,3.114670591,9.506409228,0.251875,-10.80329868,0.875947446,71.91722407 +215.88,50.4324985,-2.56955626,48.5027,3.111194394,9.507519342,0.1865625,-10.86354187,0.777647197,71.92474919 +215.89,50.43249878,-2.569554921,48.5012,3.097289611,9.50685318,0.121875,-10.92256053,0.678668852,71.93227424 +215.9,50.43249906,-2.569553584,48.5003,3.079908639,9.506631089,0.0584375,-10.98034235,0.579098699,71.93979936 +215.91,50.43249933,-2.569552246,48.5,3.079908643,9.50796324,-0.0053125,-11.03687524,0.479023599,71.94732441 +215.92,50.43249961,-2.569550907,48.5004,3.097289613,9.508629289,-0.07,-11.09214744,0.378530755,71.95484953 +215.93,50.43249989,-2.569549569,48.5014,3.111194386,9.507963131,-0.1346875,-11.14614734,0.277707773,71.96237458 +215.94,50.43250017,-2.569548231,48.5031,3.111194393,9.507963077,-0.1984375,-11.1988637,0.176642716,71.96989964 +215.95,50.43250045,-2.569546893,48.5054,3.097289627,9.509073198,-0.261875,-11.25028551,0.075423534,71.97742475 +215.96,50.43250073,-2.569545554,48.5083,3.07990865,9.510183319,-0.326875,-11.30040202,-0.025861367,71.98494981 +215.97,50.432501,-2.569544216,48.5119,3.079908643,9.511071407,-0.393125,-11.34920278,-0.127123693,71.99247492 +215.98,50.43250128,-2.569542877,48.5162,3.093813428,9.511515427,-0.4578125,-11.39667761,-0.228275209,71.99999998 +215.99,50.43250156,-2.569541538,48.5211,3.093813438,9.511293344,-0.52,-11.44281652,-0.329227622,72.00752509 +216,50.43250184,-2.5695402,48.5266,3.07990866,9.511515331,-0.581875,-11.48760996,-0.429892984,72.01505014 +216.01,50.43250211,-2.569538861,48.5327,3.079908656,9.512625457,-0.645,-11.53104853,-0.530183459,72.02257526 +216.02,50.43250239,-2.569537522,48.5395,3.093813436,9.513291515,-0.7084375,-11.57312322,-0.630011615,72.03010031 +216.03,50.43250267,-2.569536183,48.5469,3.093813444,9.512625367,-0.77125,-11.61382517,-0.729290361,72.03762543 +216.04,50.43250295,-2.569534844,48.5549,3.079908672,9.511515151,-0.8334375,-11.65314589,-0.827933181,72.04515048 +216.05,50.43250322,-2.569533506,48.5636,3.076432474,9.511737142,-0.895,-11.69107724,-0.925854075,72.05267559 +216.06,50.4325035,-2.569532167,48.5728,3.079908665,9.513735412,-0.9565625,-11.72761121,-1.022967556,72.06020065 +216.07,50.43250378,-2.569530828,48.5827,3.076432481,9.515733682,-1.0184375,-11.76274017,-1.119189,72.06772576 +216.08,50.43250405,-2.569529488,48.5932,3.076432502,9.515955677,-1.0796875,-11.79645684,-1.214434467,72.07525082 +216.09,50.43250433,-2.569528149,48.6043,3.079908707,9.514845465,-1.14,-11.82875419,-1.308620994,72.08277593 +216.1,50.43250461,-2.56952681,48.616,3.076432511,9.514179324,-1.1996875,-11.85962538,-1.401666303,72.09030099 +216.11,50.43250488,-2.569525471,48.6283,3.076432508,9.51484539,-1.2584375,-11.88906407,-1.493489379,72.0978261 +216.12,50.43250516,-2.569524132,48.6412,3.079908708,9.516177561,-1.3165625,-11.91706406,-1.584010121,72.10535116 +216.13,50.43250544,-2.569522792,48.6546,3.072956333,9.517065664,-1.375,-11.94361956,-1.673149577,72.11287627 +216.14,50.43250571,-2.569521453,48.6687,3.062527756,9.517287663,-1.433125,-11.96872491,-1.760830053,72.12040133 +216.15,50.43250599,-2.569520113,48.6833,3.06252775,9.517509664,-1.4896875,-11.99237495,-1.846975003,72.12792644 +216.16,50.43250626,-2.569518774,48.6985,3.072956337,9.518175735,-1.545,-12.01456469,-1.931509425,72.13545149 +216.17,50.43250654,-2.569517434,48.7142,3.079908746,9.518619773,-1.6,-12.03528955,-2.014359466,72.14297661 +216.18,50.43250682,-2.569516094,48.7305,3.072956377,9.518397707,-1.655,-12.05454522,-2.09545299,72.15050166 +216.19,50.43250709,-2.569514755,48.7473,3.062527797,9.518397677,-1.7096875,-12.0723276,-2.174719295,72.15802678 +216.2,50.43250737,-2.569513415,48.7647,3.059051596,9.518841716,-1.7634375,-12.088633,-2.252089166,72.16555183 +216.21,50.43250764,-2.569512075,48.7826,3.059051605,9.519507792,-1.81625,-12.10345806,-2.327495168,72.17307695 +216.22,50.43250792,-2.569510736,48.801,3.059051627,9.520839971,-1.8684375,-12.11679967,-2.400871581,72.180602 +216.23,50.43250819,-2.569509395,48.82,3.059051639,9.521950116,-1.9196875,-12.12865497,-2.472154406,72.18812711 +216.24,50.43250847,-2.569508055,48.8394,3.059051635,9.521728055,-1.97,-12.13902155,-2.54128142,72.19565217 +216.25,50.43250874,-2.569506715,48.8594,3.055575438,9.521061927,-2.02,-12.1478973,-2.608192463,72.20317728 +216.26,50.43250902,-2.569505375,48.8798,3.045146869,9.521061902,-2.069375,-12.15528026,-2.672829092,72.21070234 +216.27,50.43250929,-2.569504035,48.9008,3.038194503,9.521950017,-2.1165625,-12.16116895,-2.735134986,72.21822745 +216.28,50.43250956,-2.569502695,48.9222,3.045146909,9.523060167,-2.1615625,-12.1655621,-2.795055829,72.22575251 +216.29,50.43250984,-2.569501354,48.944,3.055575499,9.523282179,-2.206875,-12.1684588,-2.85253931,72.23327756 +216.3,50.43251011,-2.569500014,48.9663,3.059051697,9.523060121,-2.253125,-12.16985848,-2.907535294,72.24080268 +216.31,50.43251039,-2.569498674,48.9891,3.059051706,9.523504169,-2.2978125,-12.16976079,-2.95999594,72.24832773 +216.32,50.43251066,-2.569497333,49.0123,3.055575532,9.524170252,-2.34,-12.16816585,-3.009875411,72.25585285 +216.33,50.43251094,-2.569495993,49.0359,3.045146966,9.524392267,-2.3815625,-12.16507388,-3.057130163,72.2633779 +216.34,50.43251121,-2.569494652,49.0599,3.038194576,9.524614283,-2.423125,-12.16048564,-3.101719113,72.27090301 +216.35,50.43251148,-2.569493312,49.0844,3.041670765,9.525280368,-2.463125,-12.15440197,-3.143603302,72.27842807 +216.36,50.43251176,-2.569491971,49.1092,3.041670777,9.525946453,-2.50125,-12.1468242,-3.182746232,72.28595318 +216.37,50.43251203,-2.56949063,49.1344,3.038194612,9.526390505,-2.5384375,-12.13775394,-3.219113754,72.29347824 +216.38,50.4325123,-2.56948929,49.16,3.041670833,9.526834558,-2.575,-12.12719301,-3.252674126,72.30100335 +216.39,50.43251258,-2.569487948,49.1859,3.041670843,9.526834541,-2.61125,-12.11514365,-3.283398186,72.30852841 +216.4,50.43251285,-2.569486608,49.2122,3.038194651,9.526834525,-2.6465625,-12.10160844,-3.311259004,72.31605352 +216.41,50.43251312,-2.569485267,49.2389,3.041670851,9.527944682,-2.6796875,-12.08659012,-3.3362324,72.32357858 +216.42,50.4325134,-2.569483926,49.2658,3.038194666,9.529054841,-2.7115625,-12.0700918,-3.358296547,72.33110369 +216.43,50.43251367,-2.569482584,49.2931,3.024289908,9.529054827,-2.743125,-12.05211709,-3.377432191,72.33862875 +216.44,50.43251394,-2.569481244,49.3207,3.02428993,9.529054814,-2.7728125,-12.03266958,-3.393622661,72.34615386 +216.45,50.43251421,-2.569479902,49.3486,3.038194715,9.529498869,-2.8,-12.01175336,-3.40685386,72.35367892 +216.46,50.43251449,-2.569478561,49.3767,3.038194711,9.529942925,-2.8265625,-11.98937288,-3.417114217,72.36120403 +216.47,50.43251476,-2.56947722,49.4051,3.024289941,9.530609016,-2.8534375,-11.96553274,-3.424394849,72.36872908 +216.48,50.43251503,-2.569475878,49.4338,3.024289973,9.531275108,-2.8796875,-11.94023791,-3.428689282,72.3762542 +216.49,50.4325153,-2.569474537,49.4627,3.038194783,9.531497131,-2.904375,-11.91349373,-3.429993907,72.38377925 +216.5,50.43251558,-2.569473195,49.4919,3.038194797,9.531497119,-2.9265625,-11.88530575,-3.42830752,72.39130437 +216.51,50.43251585,-2.569471854,49.5213,3.02081383,9.531497108,-2.9465625,-11.85567982,-3.423631554,72.39882942 +216.52,50.43251612,-2.569470512,49.5508,3.006909054,9.531719132,-2.9665625,-11.82462225,-3.415970192,72.40635453 +216.53,50.43251639,-2.569469171,49.5806,3.00343286,9.532385227,-2.98625,-11.79213938,-3.405329965,72.41387959 +216.54,50.43251666,-2.569467829,49.6106,3.00690907,9.532829286,-3.003125,-11.7582381,-3.391720326,72.4214047 +216.55,50.43251693,-2.569466487,49.6407,3.020813881,9.532607242,-3.018125,-11.72292539,-3.375153022,72.42892976 +216.56,50.4325172,-2.569465146,49.6709,3.038194881,9.532829267,-3.0334375,-11.68620871,-3.355642549,72.43645487 +216.57,50.43251748,-2.569463804,49.7014,3.038194896,9.53393943,-3.0478125,-11.64809573,-3.333205866,72.44397993 +216.58,50.43251775,-2.569462462,49.7319,3.020813924,9.534827559,-3.0596875,-11.60859435,-3.307862624,72.45150504 +216.59,50.43251802,-2.56946112,49.7626,3.006909142,9.53527162,-3.07,-11.5677129,-3.279634827,72.4590301 +216.6,50.43251829,-2.569459778,49.7933,3.003432961,9.535937715,-3.0796875,-11.52545978,-3.248547169,72.46655521 +216.61,50.43251856,-2.569458436,49.8242,3.003432989,9.536381775,-3.088125,-11.481844,-3.214626749,72.47408027 +216.62,50.43251883,-2.569457093,49.8551,3.00343301,9.536159733,-3.0946875,-11.43687449,-3.177903134,72.48160538 +216.63,50.4325191,-2.569455752,49.8861,3.003433027,9.536381759,-3.1,-11.39056077,-3.138408294,72.48913044 +216.64,50.43251937,-2.569454409,49.9171,3.003433042,9.537491924,-3.1046875,-11.34291245,-3.096176721,72.49665549 +216.65,50.43251964,-2.569453067,49.9482,3.003433045,9.538380054,-3.108125,-11.29393945,-3.051245256,72.5041806 +216.66,50.43251991,-2.569451724,49.9793,3.003433049,9.53860208,-3.109375,-11.24365209,-3.003653032,72.51170566 +216.67,50.43252018,-2.569450382,50.0104,3.003433066,9.538380037,-3.1084375,-11.19206085,-2.953441647,72.51923077 +216.68,50.43252045,-2.569449039,50.0415,3.00343309,9.537713926,-3.1065625,-11.13917645,-2.900654759,72.52675583 +216.69,50.43252072,-2.569447697,50.0725,3.003433113,9.537491884,-3.1046875,-11.08500994,-2.845338434,72.53428094 +216.7,50.43252099,-2.569446355,50.1036,3.003433133,9.538602049,-3.1015625,-11.02957266,-2.787540972,72.541806 +216.71,50.43252126,-2.569445012,50.1346,3.003433141,9.539712214,-3.09625,-10.97287619,-2.727312737,72.54933111 +216.72,50.43252153,-2.569443669,50.1655,3.00343314,9.539712206,-3.09,-10.91493234,-2.664706212,72.55685617 +216.73,50.4325218,-2.569442327,50.1964,3.003433144,9.539934232,-3.083125,-10.85575325,-2.599776056,72.56438128 +216.74,50.43252207,-2.569440984,50.2272,3.003433165,9.541044396,-3.074375,-10.79535129,-2.532578879,72.57190634 +216.75,50.43252234,-2.569439641,50.2579,3.003433195,9.541932525,-3.0634375,-10.73373902,-2.463173178,72.57943145 +216.76,50.43252261,-2.569438298,50.2885,2.99995702,9.542154551,-3.05125,-10.67092933,-2.39161963,72.5869565 +216.77,50.43252288,-2.569436955,50.3189,2.986052254,9.542154543,-3.038125,-10.60693533,-2.317980516,72.59448162 +216.78,50.43252315,-2.569435612,50.3493,2.968671294,9.542154534,-3.0234375,-10.54177037,-2.242320064,72.60200667 +216.79,50.43252341,-2.569434269,50.3794,2.968671299,9.542154525,-3.0078125,-10.47544816,-2.164704336,72.60953179 +216.8,50.43252368,-2.569432926,50.4094,2.986052273,9.54237655,-2.9915625,-10.40798238,-2.085200942,72.61705684 +216.81,50.43252395,-2.569431583,50.4393,2.999957063,9.543486714,-2.973125,-10.3393873,-2.003879208,72.62458196 +216.82,50.43252422,-2.56943024,50.4689,2.999957088,9.545485015,-2.953125,-10.26967707,-1.920810011,72.63210701 +216.83,50.43252449,-2.569428896,50.4983,2.986052332,9.546595177,-2.933125,-10.19886642,-1.836065886,72.63963212 +216.84,50.43252476,-2.569427552,50.5276,2.968671371,9.545707028,-2.91125,-10.12697001,-1.749720688,72.64715718 +216.85,50.43252502,-2.569426209,50.5566,2.968671382,9.544596845,-2.8865625,-10.05400287,-1.661849704,72.65468229 +216.86,50.43252529,-2.569424866,50.5853,2.986052376,9.544818869,-2.8615625,-9.979980328,-1.572529594,72.66220735 +216.87,50.43252556,-2.569423522,50.6138,2.996480972,9.545706996,-2.8365625,-9.904917757,-1.481838167,72.66973246 +216.88,50.43252583,-2.569422179,50.6421,2.986052382,9.546595122,-2.8096875,-9.828830853,-1.389854549,72.67725752 +216.89,50.4325261,-2.569420835,50.67,2.968671413,9.547039179,-2.7815625,-9.751735485,-1.29665901,72.68478263 +216.9,50.43252636,-2.569419491,50.6977,2.965195243,9.546817132,-2.753125,-9.673647812,-1.202332739,72.69230769 +216.91,50.43252663,-2.569418148,50.7251,2.968671459,9.547039153,-2.7228125,-9.594584105,-1.106958013,72.6998328 +216.92,50.4325269,-2.569416804,50.7522,2.96519528,9.548149313,-2.69,-9.514560866,-1.010617967,72.70735786 +216.93,50.43252716,-2.56941546,50.7789,2.968671498,9.549037437,-2.6565625,-9.433594825,-0.913396712,72.71488297 +216.94,50.43252743,-2.569414116,50.8053,2.982576297,9.549259457,-2.623125,-9.351702884,-0.815378931,72.72240802 +216.95,50.4325277,-2.569412772,50.8314,2.982576295,9.549259442,-2.588125,-9.268902118,-0.71665011,72.72993314 +216.96,50.43252797,-2.569411428,50.8571,2.968671504,9.549259427,-2.5515625,-9.185209886,-0.617296363,72.73745819 +216.97,50.43252823,-2.569410084,50.8824,2.965195308,9.549259411,-2.5146875,-9.100643607,-0.517404323,72.74498331 +216.98,50.4325285,-2.56940874,50.9074,2.968671525,9.549481429,-2.4765625,-9.015220986,-0.417061136,72.75250836 +216.99,50.43252877,-2.569407396,50.932,2.961719166,9.550369551,-2.43625,-8.928959783,-0.316354235,72.76003342 +217,50.43252903,-2.569406052,50.9561,2.951290596,9.55170174,-2.395,-8.841878105,-0.215371455,72.76755853 +217.01,50.4325293,-2.569404707,50.9799,2.951290601,9.55258986,-2.3534375,-8.753994115,-0.114200916,72.77508359 +217.02,50.43252956,-2.569403363,51.0032,2.9617192,9.552589841,-2.31125,-8.665326146,-0.012930741,72.7826087 +217.03,50.43252983,-2.569402018,51.0261,2.968671606,9.551923718,-2.2684375,-8.575892705,0.088350665,72.79013376 +217.04,50.4325301,-2.569400674,51.0486,2.961719221,9.551701663,-2.224375,-8.485712471,0.189555065,72.79765887 +217.05,50.43253036,-2.56939933,51.0706,2.951290641,9.55303385,-2.178125,-8.394804295,0.29059411,72.80518392 +217.06,50.43253063,-2.569397985,51.0922,2.947814455,9.554810105,-2.1303125,-8.303187197,0.39137985,72.81270904 +217.07,50.43253089,-2.56939664,51.1132,2.947814453,9.555032118,-2.083125,-8.210880259,0.491824221,72.82023409 +217.08,50.43253116,-2.569395295,51.1338,2.947814452,9.554143957,-2.0365625,-8.11790273,0.591839734,72.82775921 +217.09,50.43253142,-2.569393951,51.154,2.947814464,9.554143934,-1.9878125,-8.024274093,0.691339183,72.83528426 +217.1,50.43253169,-2.569392606,51.1736,2.947814482,9.555032048,-1.9365625,-7.930013884,0.79023571,72.84280938 +217.11,50.43253195,-2.569391261,51.1927,2.9478145,9.555254058,-1.885,-7.835141756,0.888443197,72.85033443 +217.12,50.43253222,-2.569389916,51.2113,2.947814513,9.555254032,-1.8334375,-7.739677533,0.98587593,72.85785954 +217.13,50.43253248,-2.569388572,51.2294,2.947814519,9.556364178,-1.78125,-7.643641213,1.082448998,72.8653846 +217.14,50.43253275,-2.569387226,51.2469,2.947814527,9.557474323,-1.7284375,-7.54705279,1.178078118,72.87290971 +217.15,50.43253301,-2.569385881,51.264,2.947814538,9.557252261,-1.6746875,-7.449932433,1.272679924,72.88043477 +217.16,50.43253328,-2.569384536,51.2804,2.947814543,9.556808163,-1.6196875,-7.352300424,1.366171969,72.88795988 +217.17,50.43253354,-2.569383191,51.2964,2.947814548,9.557474236,-1.56375,-7.254177162,1.458472662,72.89548494 +217.18,50.43253381,-2.569381846,51.3117,2.947814549,9.558584379,-1.5078125,-7.155583158,1.549501561,72.90301005 +217.19,50.43253407,-2.5693805,51.3265,2.944338346,9.558584348,-1.451875,-7.056539038,1.639179253,72.91053511 +217.2,50.43253434,-2.569379155,51.3408,2.933909762,9.557696178,-1.3946875,-6.957065371,1.727427588,72.91806022 +217.21,50.4325346,-2.56937781,51.3544,2.926957388,9.55791818,-1.3365625,-6.857183014,1.814169559,72.92558528 +217.22,50.43253486,-2.569376465,51.3675,2.930433598,9.559694422,-1.2784375,-6.756912821,1.899329537,72.93311039 +217.23,50.43253513,-2.569375119,51.38,2.930433608,9.561026595,-1.2196875,-6.656275707,1.982833323,72.94063544 +217.24,50.43253539,-2.569373773,51.3919,2.926957426,9.56102656,-1.1596875,-6.555292697,2.064607979,72.94816056 +217.25,50.43253565,-2.569372428,51.4032,2.930433628,9.561026524,-1.0984375,-6.453984936,2.144582288,72.95568561 +217.26,50.43253592,-2.569371082,51.4139,2.930433624,9.561248521,-1.036875,-6.352373449,2.222686519,72.96321073 +217.27,50.43253618,-2.569369736,51.4239,2.92695743,9.561026449,-0.9765625,-6.250479551,2.298852549,72.97073578 +217.28,50.43253644,-2.569368391,51.4334,2.930433633,9.561248445,-0.9165625,-6.148324557,2.373013857,72.9782609 +217.29,50.43253671,-2.569367045,51.4423,2.930433635,9.562358576,-0.8546875,-6.045929722,2.445105928,72.98578595 +217.3,50.43253697,-2.569365699,51.4505,2.926957442,9.563246673,-0.791875,-5.943316476,2.515065851,72.99331106 +217.31,50.43253723,-2.569364353,51.4581,2.930433645,9.563468666,-0.73,-5.84050619,2.582832549,73.00083612 +217.32,50.4325375,-2.569363007,51.4651,2.926957449,9.563468624,-0.668125,-5.737520407,2.648347007,73.00836118 +217.33,50.43253776,-2.569361661,51.4715,2.913052663,9.563468581,-0.6046875,-5.634380555,2.711552044,73.01588629 +217.34,50.43253802,-2.569360315,51.4772,2.913052659,9.563690571,-0.54,-5.531108293,2.772392598,73.02341134 +217.35,50.43253828,-2.569358969,51.4823,2.926957436,9.564578663,-0.4753125,-5.427725049,2.830815558,73.03093646 +217.36,50.43253855,-2.569357623,51.4867,2.92695744,9.565688789,-0.4115625,-5.324252538,2.886770043,73.03846151 +217.37,50.43253881,-2.569356276,51.4905,2.909576477,9.565688743,-0.3484375,-5.220712304,2.940207181,73.04598663 +217.38,50.43253907,-2.56935493,51.4937,2.899147897,9.564800557,-0.2846875,-5.117125946,2.99108039,73.05351168 +217.39,50.43253933,-2.569353584,51.4962,2.909576482,9.564800508,-0.22,-5.013515123,3.039345381,73.0610368 +217.4,50.43253959,-2.569352238,51.4981,2.926957466,9.56591063,-0.1553125,-4.909901493,3.084960041,73.06856185 +217.41,50.43253986,-2.569350891,51.4993,2.926957469,9.567020751,-0.0915625,-4.806306656,3.127884492,73.07608696 +217.42,50.43254012,-2.569349545,51.4999,2.909576482,9.567908837,-0.0284375,-4.702752326,3.168081434,73.08361202 +217.43,50.43254038,-2.569348198,51.4999,2.895671695,9.568352854,0.0353125,-4.599260048,3.205515746,73.09113713 +217.44,50.43254064,-2.569346851,51.4992,2.8921955,9.568130766,0.1,-4.495851422,3.240154827,73.09866219 +217.45,50.4325409,-2.569345505,51.4979,2.895671694,9.568352746,0.165,-4.392548106,3.271968423,73.1061873 +217.46,50.43254116,-2.569344158,51.4959,2.909576483,9.569462862,0.23,-4.289371642,3.300928804,73.11371236 +217.47,50.43254142,-2.569342811,51.4933,2.926957475,9.570350943,0.295,-4.186343632,3.327010759,73.12123747 +217.48,50.43254169,-2.569341464,51.49,2.926957474,9.57057292,0.36,-4.083485504,3.350191486,73.12876253 +217.49,50.43254195,-2.569340117,51.4861,2.909576479,9.570572861,0.4246875,-3.980818744,3.370450758,73.13628764 +217.5,50.43254221,-2.56933877,51.4815,2.895671688,9.570572801,0.488125,-3.878364894,3.387770985,73.1438127 +217.51,50.43254247,-2.569337423,51.4763,2.892195491,9.570572741,0.55,-3.77614527,3.402137043,73.15133781 +217.52,50.43254273,-2.569336076,51.4705,2.892195486,9.57057268,0.611875,-3.674181185,3.413536382,73.15886286 +217.53,50.43254299,-2.569334729,51.4641,2.892195485,9.570572618,0.675,-3.572494011,3.421959033,73.16638798 +217.54,50.43254325,-2.569333382,51.457,2.892195491,9.570572555,0.7384375,-3.471104947,3.427397721,73.17391303 +217.55,50.43254351,-2.569332035,51.4493,2.892195488,9.570794525,0.80125,-3.370035192,3.429847688,73.18143815 +217.56,50.43254377,-2.569330688,51.441,2.892195475,9.571904633,0.8634375,-3.269305831,3.429306701,73.1889632 +217.57,50.43254403,-2.569329341,51.432,2.892195469,9.573902877,0.925,-3.168937892,3.425775391,73.19648832 +217.58,50.43254429,-2.569327993,51.4225,2.892195467,9.575012983,0.9865625,-3.068952345,3.419256678,73.20401337 +217.59,50.43254455,-2.569326645,51.4123,2.89219546,9.574124777,1.0484375,-2.969370045,3.40975635,73.21153848 +217.6,50.43254481,-2.569325298,51.4015,2.892195453,9.573014537,1.1096875,-2.870211849,3.397282715,73.21906354 +217.61,50.43254507,-2.569323951,51.3901,2.892195442,9.573236501,1.1696875,-2.77149844,3.381846545,73.22658865 +217.62,50.43254533,-2.569322603,51.3781,2.888719229,9.574124568,1.2284375,-2.673250388,3.36346136,73.23411371 +217.63,50.43254559,-2.569321256,51.3655,2.874814447,9.575234669,1.2865625,-2.575488318,3.342143205,73.24163882 +217.64,50.43254585,-2.569319908,51.3524,2.857433486,9.576566804,1.345,-2.478232514,3.317910585,73.24916388 +217.65,50.4325461,-2.56931856,51.3386,2.85743348,9.57745487,1.403125,-2.381503373,3.290784758,73.25668899 +217.66,50.43254636,-2.569317212,51.3243,2.874814429,9.577676831,1.4596875,-2.285321062,3.260789329,73.26421405 +217.67,50.43254662,-2.569315864,51.3094,2.888719198,9.577454722,1.5153125,-2.189705693,3.227950425,73.2717391 +217.68,50.43254688,-2.569314516,51.294,2.892195399,9.576788543,1.5715625,-2.094677205,3.192296693,73.27926422 +217.69,50.43254714,-2.569313168,51.278,2.888719202,9.576566433,1.628125,-2.000255422,3.153859247,73.28678927 +217.7,50.4325474,-2.569311821,51.2614,2.874814412,9.577676527,1.683125,-1.906460169,3.112671603,73.29431438 +217.71,50.43254766,-2.569310472,51.2443,2.857433429,9.578786622,1.7365625,-1.813310925,3.068769628,73.30183944 +217.72,50.43254791,-2.569309124,51.2267,2.857433421,9.578564509,1.79,-1.720827171,3.022191655,73.30936455 +217.73,50.43254817,-2.569307776,51.2085,2.874814388,9.578120361,1.843125,-1.629028217,2.972978247,73.31688961 +217.74,50.43254843,-2.569306428,51.1898,2.885242968,9.578786384,1.894375,-1.537933314,2.921172434,73.32441472 +217.75,50.43254869,-2.56930508,51.1706,2.874814372,9.580118509,1.9434375,-1.447561368,2.866819252,73.33193978 +217.76,50.43254895,-2.569303731,51.1509,2.857433377,9.581006565,1.991875,-1.357931288,2.809966197,73.33946489 +217.77,50.4325492,-2.569302383,51.1308,2.85743337,9.581228518,2.0415625,-1.26906181,2.750662773,73.34698995 +217.78,50.43254946,-2.569301034,51.1101,2.871338157,9.581228435,2.0915625,-1.180971555,2.688960776,73.35451506 +217.79,50.43254972,-2.569299686,51.0889,2.871338147,9.581228351,2.139375,-1.093678799,2.624913949,73.36204012 +217.8,50.43254998,-2.569298337,51.0673,2.857433342,9.581228266,2.185,-1.007201821,2.558578156,73.36956523 +217.81,50.43255023,-2.569296989,51.0452,2.853957134,9.581228182,2.23,-0.921558725,2.490011209,73.37709028 +217.82,50.43255049,-2.56929564,51.0227,2.857433323,9.581450131,2.2746875,-0.836767331,2.41927298,73.3846154 +217.83,50.43255075,-2.569294292,50.9997,2.853957114,9.582338182,2.318125,-0.752845401,2.346425063,73.39214045 +217.84,50.432551,-2.569292943,50.9763,2.853957108,9.583670302,2.36,-0.669810409,2.271531057,73.39966557 +217.85,50.43255126,-2.569291594,50.9525,2.857433309,9.584558352,2.4015625,-0.587679716,2.194656278,73.40719062 +217.86,50.43255152,-2.569290245,50.9283,2.853957104,9.584780297,2.443125,-0.506470512,2.115867706,73.41471574 +217.87,50.43255177,-2.569288896,50.9036,2.853957075,9.584780209,2.4828125,-0.426199698,2.035234037,73.42224079 +217.88,50.43255203,-2.569287547,50.8786,2.857433259,9.58478012,2.5196875,-0.346884062,1.952825632,73.4297659 +217.89,50.43255229,-2.569286198,50.8532,2.853957071,9.58478003,2.5553125,-0.268540219,1.868714339,73.43729096 +217.9,50.43255254,-2.569284849,50.8275,2.853957059,9.585001974,2.5915625,-0.191184442,1.782973497,73.44481607 +217.91,50.4325528,-2.5692835,50.8014,2.857433225,9.585667986,2.628125,-0.114832889,1.695677877,73.45234113 +217.92,50.43255306,-2.569282151,50.7749,2.850480822,9.586111963,2.6628125,-0.039501601,1.606903567,73.45986624 +217.93,50.43255331,-2.569280801,50.7481,2.840052238,9.586111871,2.695,0.034793779,1.516728031,73.4673913 +217.94,50.43255357,-2.569279453,50.721,2.836576028,9.586999917,2.7265625,0.108037724,1.425229937,73.47491641 +217.95,50.43255382,-2.569278103,50.6936,2.836576,9.58833203,2.758125,0.180214879,1.332488983,73.48244147 +217.96,50.43255408,-2.569276753,50.6658,2.836575984,9.588109902,2.7878125,0.251310232,1.238586071,73.48996658 +217.97,50.43255433,-2.569275404,50.6378,2.836575973,9.587443706,2.8146875,0.321308945,1.143603075,73.49749164 +217.98,50.43255459,-2.569274055,50.6095,2.836575959,9.588331749,2.84,0.390196348,1.047622847,73.50501675 +217.99,50.43255484,-2.569272705,50.581,2.836575948,9.589441827,2.865,0.457958061,0.950729095,73.5125418 +218,50.4325551,-2.569271355,50.5522,2.836575945,9.589441732,2.89,0.524579932,0.85300633,73.52006692 +218.01,50.43255535,-2.569270006,50.5232,2.836575932,9.589663671,2.914375,0.590048095,0.754539694,73.52759197 +218.02,50.43255561,-2.569268656,50.4939,2.83657591,9.590551713,2.9365625,0.654348856,0.655415074,73.53511703 +218.03,50.43255586,-2.569267306,50.4644,2.836575897,9.590551618,2.95625,0.717468752,0.555718927,73.54264214 +218.04,50.43255612,-2.569265956,50.4348,2.836575893,9.589663385,2.975,0.779394661,0.455538174,73.5501672 +218.05,50.43255637,-2.569264607,50.4049,2.83657588,9.589663289,2.9934375,0.840113634,0.354960246,73.55769231 +218.06,50.43255663,-2.569263257,50.3749,2.836575858,9.590995398,3.01125,0.899612894,0.254072748,73.56521737 +218.07,50.43255688,-2.569261907,50.3447,2.833099646,9.592549541,3.0278125,0.957880181,0.152963688,73.57274248 +218.08,50.43255714,-2.569260557,50.3143,2.822671046,9.592993512,3.0415625,1.014903175,0.051721244,73.58026754 +218.09,50.43255739,-2.569259206,50.2838,2.815718638,9.592105278,3.053125,1.070670074,-0.04956635,73.58779265 +218.1,50.43255764,-2.569257857,50.2533,2.819194823,9.591883147,3.0646875,1.12516919,-0.150810628,73.5953177 +218.11,50.4325579,-2.569256507,50.2225,2.819194818,9.593215256,3.075,1.178389119,-0.251923469,73.60284282 +218.12,50.43255815,-2.569255156,50.1917,2.815718609,9.594103296,3.0828125,1.230318805,-0.352816581,73.61036787 +218.13,50.4325584,-2.569253806,50.1609,2.822670978,9.594103198,3.0903125,1.280947361,-0.453402072,73.61789299 +218.14,50.43255866,-2.569252456,50.1299,2.833099553,9.594547169,3.0978125,1.330264188,-0.553592165,73.62541804 +218.15,50.43255891,-2.569251105,50.0989,2.833099551,9.595213174,3.1028125,1.378259029,-0.653299541,73.63294316 +218.16,50.43255917,-2.569249755,50.0678,2.819194762,9.595435111,3.105,1.424921858,-0.752437168,73.64046821 +218.17,50.43255942,-2.569248404,50.0368,2.80181377,9.595435013,3.1065625,1.470242934,-0.850918701,73.64799332 +218.18,50.43255967,-2.569247054,50.0057,2.801813756,9.595434915,3.1084375,1.514212804,-0.948658254,73.65551838 +218.19,50.43255992,-2.569245703,49.9746,2.815718525,9.595656852,3.109375,1.556822243,-1.045570512,73.66304349 +218.2,50.43256018,-2.569244353,49.9435,2.815718502,9.596322857,3.108125,1.59806237,-1.141571023,73.67056855 +218.21,50.43256043,-2.569243002,49.9124,2.801813694,9.596766828,3.1046875,1.637924533,-1.236576077,73.67809366 +218.22,50.43256068,-2.569241651,49.8814,2.80181368,9.596544696,3.1,1.676400482,-1.330502825,73.68561872 +218.23,50.43256093,-2.569240301,49.8504,2.815718459,9.596988667,3.0946875,1.713482196,-1.423269333,73.69314383 +218.24,50.43256119,-2.56923895,49.8195,2.815718446,9.598986878,3.0878125,1.749161825,-1.514794757,73.70066889 +218.25,50.43256144,-2.569237599,49.7886,2.80181364,9.600985089,3.0784375,1.783432035,-1.604999284,73.708194 +218.26,50.43256169,-2.569236247,49.7579,2.801813626,9.601207026,3.068125,1.81628555,-1.69380419,73.71571906 +218.27,50.43256194,-2.569234896,49.7273,2.815718405,9.600096758,3.058125,1.847715608,-1.781132068,73.72324417 +218.28,50.4325622,-2.569233545,49.6967,2.815718392,9.599208524,3.04625,1.877715621,-1.866906772,73.73076922 +218.29,50.43256245,-2.569232194,49.6663,2.798337391,9.598986393,3.03125,1.906279286,-1.951053474,73.73829434 +218.3,50.4325627,-2.569230843,49.6361,2.784432596,9.598986297,3.0153125,1.933400644,-2.033498892,73.74581939 +218.31,50.43256295,-2.569229492,49.606,2.780956405,9.599208236,2.9996875,1.959074081,-2.114171063,73.75334451 +218.32,50.4325632,-2.569228141,49.5761,2.784432599,9.600096277,2.9828125,1.98329421,-2.192999628,73.76086956 +218.33,50.43256345,-2.56922679,49.5463,2.79833736,9.601428387,2.9634375,2.00605599,-2.269915831,73.76839468 +218.34,50.4325637,-2.569225438,49.5168,2.815718315,9.602316429,2.9428125,2.027354607,-2.344852695,73.77591973 +218.35,50.43256396,-2.569224087,49.4875,2.815718303,9.602538368,2.921875,2.04718565,-2.417744787,73.78344484 +218.36,50.43256421,-2.569222735,49.4583,2.798337309,9.602538273,2.8996875,2.065544937,-2.488528508,73.7909699 +218.37,50.43256446,-2.569221384,49.4295,2.784432504,9.602538179,2.87625,2.082428743,-2.557142267,73.79849496 +218.38,50.43256471,-2.569220032,49.4008,2.780956296,9.602760119,2.8515625,2.097833458,-2.623526131,73.80602007 +218.39,50.43256496,-2.569218681,49.3724,2.780956293,9.603648164,2.824375,2.111755874,-2.687622289,73.81354512 +218.4,50.43256521,-2.569217329,49.3443,2.780956281,9.604758243,2.7953125,2.124193069,-2.749374764,73.82107024 +218.41,50.43256546,-2.569215977,49.3165,2.78095626,9.604980185,2.7665625,2.135142522,-2.808729754,73.82859529 +218.42,50.43256571,-2.569214625,49.289,2.780956248,9.604758057,2.738125,2.144601883,-2.865635464,73.83612041 +218.43,50.43256596,-2.569213274,49.2617,2.780956247,9.60498,2.7078125,2.152569147,-2.920042333,73.84364546 +218.44,50.43256621,-2.569211921,49.2348,2.780956244,9.604979909,2.6746875,2.159042711,-2.971902862,73.85117058 +218.45,50.43256646,-2.56921057,49.2082,2.780956235,9.604757785,2.64,2.164021199,-3.021171847,73.85869563 +218.46,50.43256671,-2.569209218,49.182,2.780956224,9.605201763,2.605,2.167503579,-3.067806314,73.86622074 +218.47,50.43256696,-2.569207866,49.1561,2.78095621,9.606089811,2.57,2.169489107,-3.111765642,73.8737458 +218.48,50.43256721,-2.569206514,49.1306,2.780956191,9.607199894,2.534375,2.169977381,-3.153011441,73.88127091 +218.49,50.43256746,-2.569205162,49.1054,2.780956169,9.608309976,2.4965625,2.168968288,-3.19150773,73.88879597 +218.5,50.43256771,-2.569203809,49.0806,2.780956158,9.608531922,2.4565625,2.166462056,-3.227221049,73.89632108 +218.51,50.43256796,-2.569202457,49.0563,2.777479961,9.608309801,2.4165625,2.162459201,-3.260120114,73.90384614 +218.52,50.43256821,-2.569201105,49.0323,2.763575168,9.608753783,2.3765625,2.156960525,-3.290176391,73.91137125 +218.53,50.43256846,-2.569199752,49.0087,2.746194174,9.6094198,2.334375,2.149967232,-3.317363525,73.91889631 +218.54,50.4325687,-2.5691984,48.9856,2.746194173,9.609641749,2.29,2.14148081,-3.341657852,73.92642142 +218.55,50.43256895,-2.569197047,48.9629,2.763575163,9.609641665,2.245,2.131502922,-3.363038231,73.93394648 +218.56,50.4325692,-2.569195695,48.9407,2.777479942,9.609419547,2.2,2.120035744,-3.381485982,73.94147159 +218.57,50.43256945,-2.569194342,48.9189,2.78095611,9.608753362,2.155,2.107081627,-3.396985064,73.94899664 +218.58,50.4325697,-2.56919299,48.8976,2.777479886,9.608531245,2.109375,2.092643262,-3.409521896,73.95652176 +218.59,50.43256995,-2.569191638,48.8767,2.763575093,9.609863368,2.0615625,2.076723687,-3.419085593,73.96404681 +218.6,50.4325702,-2.569190285,48.8563,2.746194116,9.611861595,2.0115625,2.059326282,-3.425667789,73.97157193 +218.61,50.43257044,-2.569188932,48.8365,2.746194107,9.612971687,1.9615625,2.0404546,-3.429262698,73.97909698 +218.62,50.43257069,-2.569187579,48.8171,2.763575067,9.613193641,1.911875,2.020112592,-3.429867283,73.9866221 +218.63,50.43257094,-2.569186226,48.7982,2.774003648,9.613193562,1.86125,1.998304558,-3.427480971,73.99414715 +218.64,50.43257119,-2.569184873,48.7799,2.763575071,9.613193484,1.8096875,1.975034966,-3.422105882,74.00167226 +218.65,50.43257144,-2.56918352,48.762,2.746194098,9.613193408,1.7565625,1.950308801,-3.4137466,74.00919732 +218.66,50.43257168,-2.569182167,48.7447,2.746194081,9.613193332,1.7015625,1.924131104,-3.402410516,74.01672243 +218.67,50.43257193,-2.569180814,48.728,2.760098845,9.613193257,1.646875,1.896507376,-3.388107484,74.02424749 +218.68,50.43257218,-2.569179461,48.7118,2.760098838,9.613193182,1.593125,1.867443404,-3.370849937,74.0317726 +218.69,50.43257243,-2.569178108,48.6961,2.746194048,9.613415143,1.538125,1.836945319,-3.350653003,74.03929766 +218.7,50.43257267,-2.569176755,48.681,2.742717839,9.614303207,1.48125,1.805019366,-3.327534214,74.04682271 +218.71,50.43257292,-2.569175402,48.6665,2.746194037,9.615413306,1.4234375,1.771672306,-3.301513794,74.05434783 +218.72,50.43257317,-2.569174048,48.6525,2.742717858,9.615635269,1.365,1.736911014,-3.272614375,74.06187288 +218.73,50.43257341,-2.569172695,48.6392,2.742717859,9.615635199,1.3065625,1.700742824,-3.240861226,74.069398 +218.74,50.43257366,-2.569171342,48.6264,2.746194031,9.6167453,1.2484375,1.663175299,-3.206281963,74.07692305 +218.75,50.43257391,-2.569169988,48.6142,2.742717811,9.617855403,1.1896875,1.624216231,-3.16890678,74.08444816 +218.76,50.43257415,-2.569168634,48.6026,2.742717804,9.617633302,1.13,1.583873815,-3.128768279,74.09197322 +218.77,50.4325744,-2.569167281,48.5916,2.746194004,9.616967133,1.07,1.542156414,-3.085901468,74.09949833 +218.78,50.43257465,-2.569165927,48.5812,2.739241611,9.616967067,1.0096875,1.499072738,-3.040343645,74.10702339 +218.79,50.43257489,-2.569164574,48.5714,2.728813021,9.617855139,0.9484375,1.454631897,-2.992134632,74.1145485 +218.8,50.43257514,-2.56916322,48.5622,2.728813028,9.619187281,0.8865625,1.408843,-2.941316427,74.12207356 +218.81,50.43257538,-2.569161866,48.5537,2.739241621,9.620075355,0.825,1.361715732,-2.887933377,74.12959867 +218.82,50.43257563,-2.569160512,48.5457,2.746194004,9.620297327,0.763125,1.313259946,-2.832031947,74.13712373 +218.83,50.43257588,-2.569159158,48.5384,2.739241595,9.620075232,0.6996875,1.26348567,-2.773661012,74.14464884 +218.84,50.43257612,-2.569157804,48.5317,2.728812993,9.619187036,0.6353125,1.212403332,-2.712871336,74.1521739 +218.85,50.43257637,-2.56915645,48.5257,2.725336798,9.61829884,0.5715625,1.160023645,-2.649716032,74.15969901 +218.86,50.43257661,-2.569155097,48.5203,2.725336813,9.619186919,0.5084375,1.106357495,-2.584250161,74.16722407 +218.87,50.43257686,-2.569153743,48.5155,2.725336822,9.621407204,0.445,1.051416114,-2.516530732,74.17474918 +218.88,50.4325771,-2.569152388,48.5114,2.725336812,9.622295285,0.3815625,0.99521096,-2.446616875,74.18227423 +218.89,50.43257735,-2.569151034,48.5079,2.725336799,9.621629127,0.3184375,0.937753835,-2.374569552,74.18979935 +218.9,50.43257759,-2.56914968,48.505,2.725336801,9.621629073,0.2546875,0.879056601,-2.300451502,74.1973244 +218.91,50.43257784,-2.569148326,48.5028,2.725336804,9.622517157,0.19,0.81913169,-2.22432747,74.20484952 +218.92,50.43257808,-2.569146971,48.5012,2.721860604,9.622739139,0.125,0.757991478,-2.146263804,74.21237457 +218.93,50.43257833,-2.569145617,48.5003,2.711432016,9.622517054,0.06,0.6956488,-2.066328571,74.21989968 +218.94,50.43257857,-2.569144263,48.5,2.704479636,9.622961073,-0.0046875,0.632116662,-1.984591444,74.22742474 +218.95,50.43257881,-2.569142908,48.5004,2.711432036,9.623627126,-0.0684375,0.567408298,-1.901123754,74.23494985 +218.96,50.43257906,-2.569141554,48.5014,2.721860611,9.623849113,-0.131875,0.501537288,-1.815998211,74.24247491 +218.97,50.4325793,-2.569140199,48.503,2.721860594,9.6240711,-0.1965625,0.434517326,-1.729289128,74.25000002 +218.98,50.43257955,-2.569138845,48.5053,2.711432009,9.624959191,-0.2615625,0.36636245,-1.641072019,74.25752508 +218.99,50.43257979,-2.56913749,48.5083,2.70447964,9.626069316,-0.325,0.297086867,-1.551423949,74.26505019 +219,50.43258003,-2.569136135,48.5118,2.71143205,9.626069272,-0.3884375,0.226705076,-1.460422953,74.27257525 +219.01,50.43258028,-2.56913478,48.516,2.721860631,9.625181092,-0.4534375,0.155231742,-1.368148501,74.28010036 +219.02,50.43258052,-2.569133426,48.5209,2.721860611,9.625403085,-0.518125,0.082681763,-1.274680979,74.28762542 +219.03,50.43258077,-2.569132071,48.5264,2.707955824,9.627401351,-0.5815625,0.00907038,-1.180101919,74.29515053 +219.04,50.43258101,-2.569130716,48.5325,2.690574861,9.629399619,-0.645,-0.065587109,-1.08449377,74.30267559 +219.05,50.43258125,-2.56912936,48.5393,2.690574879,9.629621613,-0.708125,-0.141275063,-0.987939953,74.31020064 +219.06,50.43258149,-2.569128005,48.5467,2.704479668,9.628511404,-0.7696875,-0.217977668,-0.890524638,74.31772575 +219.07,50.43258174,-2.56912665,48.5547,2.707955856,9.62762323,-0.8303125,-0.295678995,-0.792332735,74.32525081 +219.08,50.43258198,-2.569125295,48.5633,2.704479653,9.62740116,-0.891875,-0.374362717,-0.693449903,74.33277592 +219.09,50.43258222,-2.56912394,48.5725,2.707955853,9.627401124,-0.955,-0.454012502,-0.593962428,74.34030098 +219.1,50.43258247,-2.569122585,48.5824,2.704479662,9.627623124,-1.0178125,-0.534611621,-0.493956999,74.34782609 +219.11,50.43258271,-2.56912123,48.5929,2.68709869,9.628733262,-1.078125,-0.616143286,-0.393520821,74.35535115 +219.12,50.43258295,-2.569119875,48.604,2.67667012,9.630731537,-1.136875,-0.698590423,-0.292741441,74.36287626 +219.13,50.43258319,-2.569118519,48.6156,2.687098722,9.631841677,-1.1965625,-0.7819359,-0.191706865,74.37040132 +219.14,50.43258343,-2.569117163,48.6279,2.704479699,9.630953509,-1.2565625,-0.8661623,-0.090505044,74.37792643 +219.15,50.43258368,-2.569115808,48.6408,2.704479692,9.630065343,-1.3146875,-0.951251919,0.010775617,74.38545149 +219.16,50.43258392,-2.569114453,48.6542,2.687098716,9.63095345,-1.371875,-1.037187108,0.112046939,74.3929766 +219.17,50.43258416,-2.569113097,48.6682,2.676670147,9.632063593,-1.43,-1.123949878,0.213220571,74.40050165 +219.18,50.4325844,-2.569111741,48.6828,2.687098751,9.632063566,-1.488125,-1.211522123,0.314208221,74.40802677 +219.19,50.43258464,-2.569110386,48.698,2.70447973,9.632285574,-1.5446875,-1.299885507,0.414921883,74.41555182 +219.2,50.43258489,-2.56910903,48.7137,2.704479721,9.633173685,-1.6,-1.38902164,0.515273779,74.42307694 +219.21,50.43258513,-2.569107674,48.73,2.68709874,9.63317366,-1.655,-1.4789119,0.615176305,74.43060199 +219.22,50.43258537,-2.569106318,48.7468,2.673193974,9.632507534,-1.7096875,-1.569537436,0.71454237,74.4381271 +219.23,50.43258561,-2.569104963,48.7642,2.669717808,9.633173614,-1.763125,-1.6608794,0.813285401,74.44565216 +219.24,50.43258585,-2.569103607,48.7821,2.669717823,9.634505798,-1.8146875,-1.752918709,0.911319224,74.45317727 +219.25,50.43258609,-2.56910225,48.8005,2.669717813,9.634505777,-1.8653125,-1.845636172,1.008558298,74.46070233 +219.26,50.43258633,-2.569100895,48.8194,2.669717803,9.634505757,-1.9165625,-1.939012307,1.104917939,74.46822744 +219.27,50.43258657,-2.569099539,48.8388,2.669717818,9.635837942,-1.968125,-2.033027749,1.200314094,74.4757525 +219.28,50.43258681,-2.569098182,48.8588,2.669717848,9.636504026,-2.018125,-2.127662787,1.294663513,74.48327761 +219.29,50.43258705,-2.569096826,48.8792,2.669717866,9.635615871,-2.06625,-2.222897654,1.387884032,74.49080267 +219.3,50.43258729,-2.56909547,48.9001,2.669717866,9.634949751,-2.1134375,-2.31871247,1.479894236,74.49832778 +219.31,50.43258753,-2.569094114,48.9215,2.669717866,9.635615838,-2.16,-2.415087294,1.570613967,74.50585284 +219.32,50.43258777,-2.569092758,48.9433,2.669717873,9.636948026,-2.2065625,-2.512001902,1.659964099,74.51337795 +219.33,50.43258801,-2.569091401,48.9656,2.669717883,9.637836148,-2.253125,-2.609436125,1.747866711,74.52090301 +219.34,50.43258825,-2.569090045,48.9884,2.669717892,9.638058168,-2.2978125,-2.707369566,1.834245198,74.52842812 +219.35,50.43258849,-2.569088688,49.0116,2.669717902,9.638058154,-2.3396875,-2.805781829,1.919024159,74.53595317 +219.36,50.43258873,-2.569087332,49.0352,2.669717912,9.638058141,-2.38,-2.904652285,2.002129682,74.54347829 +219.37,50.43258897,-2.569085975,49.0592,2.669717922,9.638280163,-2.42,-3.003960309,2.083489345,74.55100334 +219.38,50.43258921,-2.569084619,49.0836,2.669717933,9.639168287,-2.46,-3.103685218,2.163032159,74.55852846 +219.39,50.43258945,-2.569083262,49.1084,2.669717943,9.640278447,-2.5,-3.203806155,2.240688796,74.56605351 +219.4,50.43258969,-2.569081905,49.1336,2.669717954,9.640278436,-2.539375,-3.304302207,2.316391532,74.57357857 +219.41,50.43258993,-2.569080548,49.1592,2.669717965,9.639390289,-2.5765625,-3.405152348,2.390074306,74.58110368 +219.42,50.43259017,-2.569079192,49.1852,2.66624178,9.63939028,-2.61125,-3.506335548,2.461672945,74.58862874 +219.43,50.43259041,-2.569077835,49.2114,2.652337008,9.640500441,-2.645,-3.607830725,2.531124941,74.59615385 +219.44,50.43259065,-2.569076478,49.2381,2.634956043,9.641388569,-2.6784375,-3.70961662,2.598369732,74.60367891 +219.45,50.43259088,-2.569075121,49.265,2.634956064,9.641610596,-2.7109375,-3.811671977,2.663348761,74.61120402 +219.46,50.43259112,-2.569073764,49.2923,2.652337062,9.641610589,-2.741875,-3.913975539,2.726005248,74.61872907 +219.47,50.43259136,-2.569072407,49.3199,2.666241848,9.641832617,-2.77125,-4.016505878,2.786284648,74.62625419 +219.48,50.4325916,-2.56907105,49.3477,2.666241838,9.642720747,-2.7996875,-4.119241623,2.844134363,74.63377924 +219.49,50.43259184,-2.569069693,49.3759,2.65233706,9.643830911,-2.826875,-4.222161287,2.899503973,74.64130436 +219.5,50.43259208,-2.569068335,49.4043,2.634956111,9.64405294,-2.8528125,-4.325243384,2.952345177,74.64882941 +219.51,50.43259231,-2.569066978,49.4329,2.63495614,9.6438309,-2.8784375,-4.428466429,3.002611853,74.65635453 +219.52,50.43259255,-2.569065621,49.4619,2.648860929,9.64405293,-2.9028125,-4.531808821,3.050260227,74.66387958 +219.53,50.43259279,-2.569064263,49.491,2.648860921,9.644052925,-2.9246875,-4.63524896,3.095248701,74.67140469 +219.54,50.43259303,-2.569062906,49.5204,2.63495615,9.644052921,-2.945,-4.738765302,3.137538086,74.67892975 +219.55,50.43259326,-2.569061549,49.5499,2.634956182,9.645163089,-2.965,-4.84233619,3.177091539,74.68645486 +219.56,50.4325935,-2.569060191,49.5797,2.648860985,9.646273256,-2.9846875,-4.945939965,3.213874456,74.69397992 +219.57,50.43259374,-2.569058833,49.6096,2.648860982,9.646051219,-3.0028125,-5.049555085,3.247854864,74.70150503 +219.58,50.43259398,-2.569057476,49.6398,2.6349562,9.645385114,-3.0184375,-5.153159835,3.279003084,74.70903009 +219.59,50.43259421,-2.569056118,49.67,2.631480026,9.645385111,-3.0328125,-5.256732613,3.307291958,74.7165552 +219.6,50.43259445,-2.569054761,49.7004,2.634956245,9.646273246,-3.046875,-5.360251763,3.33269685,74.72408026 +219.61,50.43259469,-2.569053403,49.731,2.63148006,9.647605449,-3.059375,-5.463695683,3.355195585,74.73160537 +219.62,50.43259492,-2.569052045,49.7616,2.631480066,9.648493584,-3.0696875,-5.567042774,3.37476851,74.73913043 +219.63,50.43259516,-2.569050687,49.7924,2.634956272,9.648715615,-3.0784375,-5.670271434,3.391398553,74.74665554 +219.64,50.4325954,-2.569049329,49.8232,2.631480089,9.648715614,-3.0865625,-5.77336012,3.405071332,74.75418059 +219.65,50.43259563,-2.569047971,49.8541,2.631480104,9.648493579,-3.0946875,-5.87628729,3.415774756,74.76170571 +219.66,50.43259587,-2.569046613,49.8851,2.634956322,9.647827475,-3.10125,-5.979031457,3.423499602,74.76923076 +219.67,50.43259611,-2.569045255,49.9162,2.628003954,9.647605439,-3.1046875,-6.081571192,3.428239109,74.77675588 +219.68,50.43259634,-2.569043898,49.9472,2.617575376,9.648715609,-3.1065625,-6.183885011,3.429989151,74.78428093 +219.69,50.43259658,-2.569042539,49.9783,2.614099176,9.649825779,-3.1084375,-6.285951655,3.428748182,74.79180605 +219.7,50.43259681,-2.569041181,50.0094,2.614099177,9.649825778,-3.109375,-6.387749697,3.42451729,74.7993311 +219.71,50.43259705,-2.569039823,50.0405,2.617575395,9.65004781,-3.1084375,-6.489257936,3.417300199,74.80685621 +219.72,50.43259728,-2.569038465,50.0716,2.628004008,9.65115798,-3.10625,-6.590455174,3.407103154,74.81438127 +219.73,50.43259752,-2.569037106,50.1026,2.634956413,9.652046117,-3.103125,-6.691320212,3.393935037,74.82190638 +219.74,50.43259776,-2.569035748,50.1337,2.628004033,9.65226815,-3.098125,-6.791832078,3.377807421,74.82943144 +219.75,50.43259799,-2.569034389,50.1646,2.617575458,9.652268148,-3.09125,-6.891969745,3.358734229,74.83695649 +219.76,50.43259823,-2.569033031,50.1955,2.614099263,9.652268147,-3.083125,-6.991712301,3.336732192,74.84448161 +219.77,50.43259846,-2.569031672,50.2263,2.610623071,9.652268146,-3.073125,-7.091038946,3.311820502,74.85200666 +219.78,50.4325987,-2.569030314,50.257,2.600194506,9.652268144,-3.0615625,-7.189928883,3.284020877,74.85953178 +219.79,50.43259893,-2.569028955,50.2875,2.593242144,9.652490177,-3.05,-7.288361428,3.253357493,74.86705683 +219.8,50.43259916,-2.569027597,50.318,2.600194549,9.653378312,-3.038125,-7.386316126,3.219857109,74.87458195 +219.81,50.4325994,-2.569026238,50.3483,2.610623132,9.654488481,-3.0246875,-7.483772466,3.183549003,74.882107 +219.82,50.43259963,-2.569024879,50.3785,2.61409933,9.654488479,-3.0096875,-7.580710107,3.144464802,74.88963211 +219.83,50.43259987,-2.56902352,50.4085,2.614099351,9.653600341,-2.993125,-7.677108823,3.102638539,74.89715717 +219.84,50.4326001,-2.569022162,50.4384,2.61062318,9.653600338,-2.9746875,-7.77294839,3.058106769,74.90468228 +219.85,50.43260034,-2.569020803,50.468,2.60019461,9.654710506,-2.9546875,-7.868208926,3.010908282,74.91220734 +219.86,50.43260057,-2.569019444,50.4975,2.593242232,9.655598638,-2.9334375,-7.962870435,2.961084216,74.91973245 +219.87,50.4326008,-2.569018085,50.5267,2.596718429,9.656042703,-2.91125,-8.056913206,2.908678058,74.92725751 +219.88,50.43260104,-2.569016726,50.5557,2.596718421,9.656930836,-2.888125,-8.150317588,2.853735474,74.93478262 +219.89,50.43260127,-2.569015367,50.5845,2.593242237,9.658041003,-2.863125,-8.243064043,2.796304419,74.94230768 +219.9,50.4326015,-2.569014007,50.613,2.596718465,9.658040998,-2.8365625,-8.335133204,2.736434913,74.94983279 +219.91,50.43260174,-2.569012648,50.6412,2.596718483,9.656930823,-2.81,-8.426505935,2.67417921,74.95735785 +219.92,50.43260197,-2.569011289,50.6692,2.593242282,9.656264716,-2.783125,-8.517163041,2.609591568,74.96488296 +219.93,50.4326022,-2.56900993,50.6969,2.596718479,9.657152847,-2.754375,-8.607085616,2.542728368,74.97240801 +219.94,50.43260244,-2.569008571,50.7243,2.596718499,9.659151148,-2.723125,-8.696254923,2.47364782,74.97993313 +219.95,50.43260267,-2.569007211,50.7514,2.593242327,9.660261312,-2.69,-8.784652341,2.402410259,74.98745818 +219.96,50.4326029,-2.569005851,50.7781,2.596718541,9.659373169,-2.6565625,-8.872259307,2.329077734,74.9949833 +219.97,50.43260314,-2.569004492,50.8045,2.59324236,9.658485024,-2.6234375,-8.959057658,2.253714189,75.00250835 +219.98,50.43260337,-2.569003133,50.8306,2.57933758,9.659373152,-2.589375,-9.04502923,2.176385399,75.01003347 +219.99,50.4326036,-2.569001773,50.8563,2.579337573,9.660483315,-2.553125,-9.130155976,2.0971588,75.01755852 +220,50.43260383,-2.569000413,50.8817,2.593242359,9.660483306,-2.515,-9.214420249,2.016103435,75.02508363 +220.01,50.43260407,-2.568999054,50.9066,2.593242378,9.660705331,-2.4765625,-9.297804401,1.933289949,75.03260869 +220.02,50.4326043,-2.568997694,50.9312,2.575861418,9.661593457,-2.438125,-9.380290957,1.848790649,75.0401338 +220.03,50.43260453,-2.568996334,50.9554,2.561956648,9.661593446,-2.3978125,-9.461862787,1.76267916,75.04765886 +220.04,50.43260476,-2.568994974,50.9792,2.56195666,9.660705299,-2.355,-9.542502815,1.675030598,75.05518397 +220.05,50.43260499,-2.568993615,51.0025,2.575861447,9.660705287,-2.3115625,-9.622194197,1.585921394,75.06270903 +220.06,50.43260522,-2.568992255,51.0254,2.593242427,9.661815446,-2.2684375,-9.700920259,1.495429242,75.07023414 +220.07,50.43260546,-2.568990895,51.0479,2.593242438,9.662703569,-2.2246875,-9.778664616,1.403633038,75.0777592 +220.08,50.43260569,-2.568989535,51.0699,2.575861475,9.662925589,-2.1796875,-9.855411052,1.310612824,75.08528425 +220.09,50.43260592,-2.568988175,51.0915,2.561956703,9.663147608,-2.1334375,-9.931143468,1.216449789,75.09280937 +220.1,50.43260615,-2.568986815,51.1126,2.55848052,9.66403573,-2.08625,-10.00584605,1.121225922,75.10033442 +220.11,50.43260638,-2.568985455,51.1332,2.558480528,9.665145885,-2.038125,-10.07950327,1.025024418,75.10785953 +220.12,50.43260661,-2.568984094,51.1534,2.558480532,9.665367903,-1.988125,-10.15209966,0.927928984,75.11538459 +220.13,50.43260684,-2.568982734,51.173,2.56195673,9.665145852,-1.9365625,-10.22362009,0.83002442,75.1229097 +220.14,50.43260707,-2.568981374,51.1921,2.575861512,9.665589902,-1.8853125,-10.29404966,0.731396095,75.13043476 +220.15,50.4326073,-2.568980013,51.2107,2.593242494,9.666255985,-1.835,-10.36337366,0.632129954,75.13795987 +220.16,50.43260754,-2.568978653,51.2288,2.593242513,9.666477999,-1.784375,-10.43157758,0.53231257,75.14548493 +220.17,50.43260777,-2.568977292,51.2464,2.575861554,9.666477978,-1.7315625,-10.49864716,0.432031033,75.15301004 +220.18,50.432608,-2.568975932,51.2635,2.561956776,9.666477957,-1.6765625,-10.56456842,0.331372776,75.1605351 +220.19,50.43260823,-2.568974571,51.2799,2.558480575,9.666477935,-1.6215625,-10.62932761,0.23042552,75.16806021 +220.2,50.43260846,-2.568973211,51.2959,2.558480572,9.666477912,-1.5665625,-10.69291114,0.129277327,75.17558527 +220.21,50.43260869,-2.56897185,51.3113,2.558480578,9.666699923,-1.5096875,-10.75530584,0.028016433,75.18311038 +220.22,50.43260892,-2.56897049,51.3261,2.555004397,9.667588035,-1.451875,-10.81649859,-0.073268926,75.19063543 +220.23,50.43260915,-2.568969129,51.3403,2.541099626,9.668920215,-1.395,-10.87647662,-0.1744904,75.19816055 +220.24,50.43260938,-2.568967768,51.354,2.52371865,9.669586291,-1.338125,-10.93522748,-0.275559697,75.2056856 +220.25,50.4326096,-2.568966407,51.3671,2.523718651,9.668920162,-1.2796875,-10.99273881,-0.376388695,75.21321072 +220.26,50.43260983,-2.568965046,51.3796,2.541099633,9.667809964,-1.22,-11.04899862,-0.476889446,75.22073577 +220.27,50.43261006,-2.568963686,51.3915,2.555004414,9.667809936,-1.16,-11.10399518,-0.576974401,75.22826089 +220.28,50.43261029,-2.568962325,51.4028,2.558480614,9.669142111,-1.1,-11.15771696,-0.676556185,75.23578594 +220.29,50.43261052,-2.568960964,51.4135,2.558480631,9.670696319,-1.04,-11.21015286,-0.775548051,75.24331105 +220.3,50.43261075,-2.568959603,51.4236,2.558480644,9.67136239,-0.98,-11.2612918,-0.873863598,75.25083611 +220.31,50.43261098,-2.568958241,51.4331,2.558480648,9.671140323,-0.9196875,-11.31112315,-0.971417111,75.25836122 +220.32,50.43261121,-2.568956881,51.442,2.555004455,9.67114029,-0.858125,-11.35963651,-1.068123563,75.26588628 +220.33,50.43261144,-2.568955519,51.4503,2.541099662,9.671584324,-0.795,-11.40682177,-1.163898558,75.27341139 +220.34,50.43261167,-2.568954158,51.4579,2.523718667,9.672028358,-0.7315625,-11.45266899,-1.258658616,75.28093645 +220.35,50.43261189,-2.568952797,51.4649,2.523718673,9.67247239,-0.6684375,-11.49716873,-1.352321172,75.28846156 +220.36,50.43261212,-2.568951435,51.4713,2.541099671,9.672472353,-0.605,-11.54031154,-1.44480441,75.29598662 +220.37,50.43261235,-2.568950074,51.477,2.55152827,9.672250281,-0.5415625,-11.58208852,-1.536027771,75.30351173 +220.38,50.43261258,-2.568948713,51.4821,2.541099686,9.67269431,-0.4784375,-11.62249093,-1.625911728,75.31103679 +220.39,50.43261281,-2.568947351,51.4866,2.523718704,9.673360373,-0.415,-11.66151033,-1.714377844,75.3185619 +220.4,50.43261303,-2.56894599,51.4904,2.523718701,9.673582366,-0.3515625,-11.69913853,-1.801348998,75.32608695 +220.41,50.43261326,-2.568944628,51.4936,2.537623485,9.67380436,-0.288125,-11.73536768,-1.886749332,75.33361207 +220.42,50.43261349,-2.568943267,51.4962,2.537623482,9.674692453,-0.223125,-11.77019028,-1.970504417,75.34113712 +220.43,50.43261372,-2.568941905,51.4981,2.523718695,9.67580258,-0.156875,-11.80359899,-2.052541144,75.34866218 +220.44,50.43261394,-2.568940543,51.4993,2.520242503,9.675802536,-0.091875,-11.83558688,-2.132788066,75.35618729 +220.45,50.43261417,-2.568939181,51.4999,2.523718705,9.674914355,-0.0284375,-11.86614719,-2.211175167,75.36371235 +220.46,50.4326144,-2.56893782,51.4999,2.520242513,9.674914308,0.0353125,-11.89527361,-2.287634093,75.37123746 +220.47,50.43261462,-2.568936458,51.4992,2.520242512,9.676024431,0.1,-11.92296008,-2.362098152,75.37876252 +220.48,50.43261485,-2.568935096,51.4979,2.523718705,9.67691252,0.1646875,-11.94920075,-2.434502484,75.38628763 +220.49,50.43261508,-2.568933734,51.4959,2.5202425,9.677134504,0.2284375,-11.97399017,-2.504783837,75.39381269 +220.5,50.4326153,-2.568932372,51.4933,2.520242488,9.677134454,0.2915625,-11.99732318,-2.572880959,75.4013378 +220.51,50.43261553,-2.56893101,51.4901,2.523718682,9.677134404,0.3553125,-12.01919487,-2.638734551,75.40886285 +220.52,50.43261576,-2.568929648,51.4862,2.520242497,9.677134352,0.42,-12.03960071,-2.702287087,75.41638797 +220.53,50.43261598,-2.568928286,51.4817,2.520242504,9.677356333,0.4846875,-12.05853639,-2.763483162,75.42391302 +220.54,50.43261621,-2.568926924,51.4765,2.523718699,9.678244414,0.5484375,-12.07599802,-2.822269491,75.43143814 +220.55,50.43261644,-2.568925562,51.4707,2.516766307,9.67935453,0.6115625,-12.09198189,-2.878594738,75.43896319 +220.56,50.43261666,-2.568924199,51.4643,2.506337719,9.679576508,0.675,-12.10648471,-2.932409856,75.44648831 +220.57,50.43261689,-2.568922837,51.4572,2.506337707,9.679354418,0.738125,-12.1195034,-2.983667806,75.45401336 +220.58,50.43261711,-2.568921475,51.4495,2.516766277,9.679798429,0.7996875,-12.13103532,-3.032323955,75.46153847 +220.59,50.43261734,-2.568920112,51.4412,2.523718663,9.680464472,0.8603125,-12.14107795,-3.078335904,75.46906353 +220.6,50.43261757,-2.56891875,51.4323,2.516766279,9.680686446,0.921875,-12.14962929,-3.121663488,75.47658864 +220.61,50.43261779,-2.568917387,51.4228,2.506337694,9.680908419,0.9846875,-12.15668756,-3.162268949,75.4841137 +220.62,50.43261802,-2.568916025,51.4126,2.502861493,9.68157446,1.0465625,-12.16225121,-3.200116822,75.49163881 +220.63,50.43261824,-2.568914662,51.4018,2.502861493,9.682018467,1.1065625,-12.16631909,-3.235174162,75.49916387 +220.64,50.43261847,-2.568913299,51.3905,2.502861493,9.68179637,1.1665625,-12.16889041,-3.267410372,75.50668898 +220.65,50.43261869,-2.568911937,51.3785,2.499385283,9.681796306,1.2265625,-12.16996459,-3.296797377,75.51421404 +220.66,50.43261892,-2.568910574,51.3659,2.48895667,9.682018276,1.2846875,-12.16954146,-3.323309567,75.52173915 +220.67,50.43261914,-2.568909211,51.3528,2.482004267,9.681796176,1.341875,-12.16762102,-3.346923678,75.52926421 +220.68,50.43261936,-2.568907849,51.3391,2.488956671,9.682240177,1.4,-12.16420373,-3.367619315,75.53678932 +220.69,50.43261959,-2.568906486,51.3248,2.499385271,9.684016382,1.458125,-12.15929027,-3.385378314,75.54431437 +220.7,50.43261981,-2.568905123,51.3099,2.502861465,9.685126484,1.515,-12.15288168,-3.400185147,75.55183949 +220.71,50.43262004,-2.568903759,51.2945,2.502861452,9.684238279,1.5715625,-12.14497928,-3.412027039,75.55936454 +220.72,50.43262026,-2.568902397,51.2785,2.499385245,9.683350072,1.628125,-12.13558478,-3.420893561,75.56688966 +220.73,50.43262049,-2.568901034,51.2619,2.488956648,9.684460172,1.6828125,-12.12470013,-3.426777035,75.57441471 +220.74,50.43262071,-2.568899671,51.2448,2.482004239,9.686236373,1.735,-12.1123275,-3.429672306,75.58193983 +220.75,50.43262093,-2.568898307,51.2272,2.485480416,9.686458335,1.786875,-12.0984696,-3.429576851,75.58946488 +220.76,50.43262116,-2.568896944,51.2091,2.485480413,9.685570126,1.8396875,-12.08312929,-3.426490728,75.59698999 +220.77,50.43262138,-2.568895581,51.1904,2.482004227,9.685570052,1.8915625,-12.06630977,-3.420416688,75.60451505 +220.78,50.4326216,-2.568894218,51.1712,2.485480427,9.686458113,1.9415625,-12.04801448,-3.411360002,75.61204011 +220.79,50.43262183,-2.568892854,51.1516,2.485480422,9.686680072,1.9915625,-12.02824732,-3.399328518,75.61956522 +220.8,50.43262205,-2.568891491,51.1314,2.482004215,9.686457962,2.0415625,-12.00701247,-3.38433278,75.62709027 +220.81,50.43262227,-2.568890128,51.1107,2.485480397,9.686901953,2.0896875,-11.98431424,-3.366385851,75.63461539 +220.82,50.4326225,-2.568888764,51.0896,2.485480382,9.687567978,2.1365625,-11.96015742,-3.345503431,75.64214044 +220.83,50.43262272,-2.568887401,51.068,2.482004173,9.687789933,2.1834375,-11.93454706,-3.321703623,75.64966556 +220.84,50.43262294,-2.568886037,51.0459,2.485480357,9.688011888,2.2296875,-11.9074885,-3.295007285,75.65719061 +220.85,50.43262317,-2.568884674,51.0234,2.482004152,9.688677911,2.2746875,-11.8789874,-3.265437621,75.66471573 +220.86,50.43262339,-2.56888331,51.0004,2.464623164,9.689121899,2.318125,-11.84904973,-3.233020471,75.67224078 +220.87,50.43262361,-2.568881946,50.977,2.454194569,9.688899785,2.3596875,-11.81768172,-3.197784025,75.67976589 +220.88,50.43262383,-2.568880583,50.9532,2.464623157,9.689121737,2.4,-11.78488997,-3.159759108,75.68729095 +220.89,50.43262405,-2.568879219,50.929,2.482004137,9.690231825,2.44,-11.75068124,-3.118978837,75.69481606 +220.9,50.43262428,-2.568877855,50.9044,2.482004128,9.691119878,2.4796875,-11.71506269,-3.075478735,75.70234112 +220.91,50.4326245,-2.568876491,50.8794,2.464623126,9.691341829,2.5184375,-11.67804182,-3.02929679,75.70986623 +220.92,50.43262472,-2.568875127,50.854,2.454194514,9.691341746,2.55625,-11.63962632,-2.98047328,75.71739129 +220.93,50.43262494,-2.568873763,50.8283,2.464623087,9.691341662,2.593125,-11.5998242,-2.929050719,75.7249164 +220.94,50.43262516,-2.568872399,50.8021,2.482004066,9.691341577,2.628125,-11.55864378,-2.875074026,75.73244146 +220.95,50.43262539,-2.568871035,50.7757,2.482004069,9.691563525,2.66125,-11.5160937,-2.818590185,75.73996657 +220.96,50.43262561,-2.568869671,50.7489,2.464623085,9.692451575,2.6934375,-11.47218284,-2.75964847,75.74749163 +220.97,50.43262583,-2.568868307,50.7218,2.450718289,9.693561659,2.7246875,-11.42692032,-2.698300332,75.75501674 +220.98,50.43262605,-2.568866942,50.6944,2.447242075,9.693561572,2.755,-11.38031565,-2.634599285,75.76254179 +220.99,50.43262627,-2.568865578,50.6667,2.44724206,9.692451315,2.7846875,-11.33237851,-2.568600735,75.77006691 +221,50.43262649,-2.568864214,50.6387,2.447242054,9.691785126,2.813125,-11.28311892,-2.500362379,75.77759196 +221.01,50.43262671,-2.56886285,50.6104,2.447242048,9.69245114,2.84,-11.23254714,-2.429943688,75.78511708 +221.02,50.43262693,-2.568861486,50.5819,2.44724203,9.693783256,2.86625,-11.18067383,-2.357406028,75.79264213 +221.03,50.43262715,-2.568860121,50.5531,2.447242008,9.694671304,2.8915625,-11.12750977,-2.282812653,75.80016725 +221.04,50.43262737,-2.568858757,50.524,2.447241995,9.694893249,2.914375,-11.07306606,-2.20622865,75.8076923 +221.05,50.43262759,-2.568857392,50.4948,2.447241988,9.69489316,2.935,-11.01735405,-2.12772077,75.81521741 +221.06,50.43262781,-2.568856028,50.4653,2.447241981,9.69489307,2.955,-10.96038537,-2.04735748,75.82274247 +221.07,50.43262803,-2.568854663,50.4357,2.447241977,9.695115014,2.9746875,-10.902172,-1.965208912,75.83026758 +221.08,50.43262825,-2.568853299,50.4058,2.447241972,9.69600306,2.9934375,-10.84272597,-1.881346626,75.83779264 +221.09,50.43262847,-2.568851934,50.3758,2.447241963,9.697335173,3.0109375,-10.78205982,-1.795843791,75.84531775 +221.1,50.43262869,-2.568850569,50.3456,2.447241951,9.698001185,3.0265625,-10.72018611,-1.70877489,75.85284281 +221.11,50.43262891,-2.568849204,50.3152,2.44724194,9.697557026,3.0396875,-10.65711784,-1.620215955,75.86036792 +221.12,50.43262913,-2.568847839,50.2848,2.447241926,9.697334901,3.0515625,-10.59286818,-1.53024422,75.86789298 +221.13,50.43262935,-2.568846475,50.2542,2.447241903,9.698222945,3.0634375,-10.5274505,-1.43893801,75.87541803 +221.14,50.43262957,-2.568845109,50.2235,2.447241874,9.698666921,3.0746875,-10.46087847,-1.346377079,75.88294315 +221.15,50.43262979,-2.568843744,50.1927,2.447241858,9.698000727,3.0846875,-10.39316598,-1.252642043,75.8904682 +221.16,50.43263001,-2.56884238,50.1618,2.447241861,9.697778601,3.0928125,-10.32432722,-1.15781472,75.89799331 +221.17,50.43263023,-2.568841014,50.1308,2.447241865,9.698444612,3.098125,-10.25437658,-1.061977732,75.90551837 +221.18,50.43263045,-2.56883965,50.0998,2.443765661,9.699332656,3.1015625,-10.18332861,-0.965214728,75.91304348 +221.19,50.43263067,-2.568838284,50.0688,2.429860865,9.699776632,3.105,-10.11119815,-0.867609993,75.92056854 +221.2,50.43263089,-2.568836919,50.0377,2.412479873,9.699554507,3.108125,-10.03800027,-0.769248724,75.92809365 +221.21,50.4326311,-2.568835554,50.0066,2.412479861,9.699776449,3.1096875,-9.963750324,-0.670216636,75.93561871 +221.22,50.43263132,-2.568834189,49.9755,2.429860825,9.700664493,3.1096875,-9.888463727,-0.570600131,75.94314382 +221.23,50.43263154,-2.568832823,49.9444,2.440289386,9.700886435,3.108125,-9.812156234,-0.470486012,75.95066888 +221.24,50.43263176,-2.568831458,49.9133,2.429860771,9.700886344,3.1046875,-9.734843773,-0.369961656,75.95819399 +221.25,50.43263198,-2.568830093,49.8823,2.412479783,9.701996422,3.0996875,-9.656542501,-0.269114724,75.96571905 +221.26,50.43263219,-2.568828727,49.8513,2.412479789,9.702884466,3.0934375,-9.577268805,-0.168033051,75.97324416 +221.27,50.43263241,-2.568827361,49.8204,2.429860769,9.701996239,3.08625,-9.497039187,-0.066804874,75.98076922 +221.28,50.43263263,-2.568825996,49.7896,2.440289347,9.701108012,3.078125,-9.415870376,0.034481517,75.98829433 +221.29,50.43263285,-2.568824631,49.7588,2.429860748,9.702218091,3.068125,-9.333779447,0.135737884,75.99581938 +221.3,50.43263307,-2.568823265,49.7282,2.412479756,9.704216306,3.0565625,-9.250783416,0.236875879,76.0033445 +221.31,50.43263328,-2.568821899,49.6977,2.409003549,9.705326384,3.045,-9.166899645,0.337807322,76.01086955 +221.32,50.4326335,-2.568820533,49.6673,2.412479733,9.705326294,3.0328125,-9.082145722,0.438444207,76.01839467 +221.33,50.43263372,-2.568819167,49.637,2.409003526,9.704438067,3.018125,-8.996539239,0.538698701,76.02591972 +221.34,50.43263393,-2.568817801,49.6069,2.409003515,9.703327807,3.00125,-8.910098185,0.638483483,76.03344483 +221.35,50.43263415,-2.568816436,49.577,2.4124797,9.703327718,2.9834375,-8.822840494,0.737711465,76.04096989 +221.36,50.43263437,-2.56881507,49.5472,2.40900349,9.704437798,2.9646875,-8.734784501,0.836296188,76.048495 +221.37,50.43263458,-2.568813704,49.5177,2.40900347,9.705325845,2.9446875,-8.645948541,0.93415165,76.05602006 +221.38,50.4326348,-2.568812338,49.4883,2.412479644,9.70554779,2.923125,-8.556351177,1.031192537,76.06354517 +221.39,50.43263502,-2.568810972,49.4592,2.409003437,9.705769735,2.8996875,-8.466011088,1.127334168,76.07107023 +221.4,50.43263523,-2.568809606,49.4303,2.409003438,9.706435749,2.875,-8.374947182,1.222492717,76.07859534 +221.41,50.43263545,-2.56880824,49.4017,2.412479632,9.706879729,2.85,-8.28317848,1.316585279,76.0861204 +221.42,50.43263567,-2.568806873,49.3733,2.405527232,9.706657608,2.8246875,-8.190724119,1.409529805,76.09364551 +221.43,50.43263588,-2.568805508,49.3452,2.395098634,9.706657521,2.798125,-8.097603409,1.501245107,76.10117057 +221.44,50.4326361,-2.568804141,49.3173,2.395098623,9.707101503,2.7696875,-8.003835771,1.591651373,76.10869568 +221.45,50.43263631,-2.568802775,49.2898,2.4055272,9.707545485,2.7396875,-7.90944086,1.680669648,76.11622073 +221.46,50.43263653,-2.568801409,49.2625,2.412479582,9.708211501,2.708125,-7.814438327,1.768222355,76.12374579 +221.47,50.43263675,-2.568800042,49.2356,2.405527178,9.708877518,2.6746875,-7.718848054,1.854233175,76.1312709 +221.48,50.43263696,-2.568798676,49.209,2.395098574,9.709099467,2.6403125,-7.622689979,1.938627051,76.13879596 +221.49,50.43263718,-2.568797309,49.1828,2.391622362,9.709099383,2.60625,-7.525984215,2.021330472,76.14632107 +221.5,50.43263739,-2.568795943,49.1569,2.391622348,9.709099299,2.5715625,-7.42875087,2.102271188,76.15384613 +221.51,50.43263761,-2.568794576,49.1313,2.391622334,9.70932125,2.5346875,-7.331010344,2.181378726,76.16137124 +221.52,50.43263782,-2.56879321,49.1062,2.391622327,9.710209304,2.4965625,-7.232783033,2.258584044,76.1688963 +221.53,50.43263804,-2.568791843,49.0814,2.391622329,9.711541426,2.4584375,-7.134089448,2.333819877,76.17642141 +221.54,50.43263825,-2.568790476,49.057,2.388146133,9.712207447,2.419375,-7.03495016,2.407020564,76.18394647 +221.55,50.43263847,-2.568789109,49.033,2.37771754,9.711541265,2.378125,-6.935385851,2.478122334,76.19147158 +221.56,50.43263868,-2.568787742,49.0094,2.37076514,9.710431016,2.335,-6.835417436,2.54706308,76.19899664 +221.57,50.43263889,-2.568786376,48.9863,2.377717522,9.710430937,2.2915625,-6.735065654,2.613782812,76.20652175 +221.58,50.43263911,-2.568785009,48.9636,2.388146101,9.711541028,2.248125,-6.634351591,2.678223261,76.2140468 +221.59,50.43263932,-2.568783642,48.9413,2.388146095,9.712429086,2.203125,-6.53329616,2.740328219,76.22157192 +221.6,50.43263954,-2.568782275,48.9195,2.377717507,9.712651043,2.1565625,-6.43192056,2.800043656,76.22909697 +221.61,50.43263975,-2.568780908,48.8982,2.370765112,9.712650966,2.1096875,-6.330245933,2.85731732,76.23662209 +221.62,50.43263996,-2.568779541,48.8773,2.377717491,9.712872925,2.0615625,-6.228293422,2.912099419,76.24414714 +221.63,50.43264018,-2.568778174,48.8569,2.388146063,9.713760986,2.0115625,-6.126084455,2.964342111,76.25167225 +221.64,50.43264039,-2.568776807,48.8371,2.388146052,9.714871082,1.961875,-6.023640346,3.013999848,76.25919731 +221.65,50.43264061,-2.568775439,48.8177,2.377717449,9.715093042,1.913125,-5.92098241,3.061029312,76.26672242 +221.66,50.43264082,-2.568774072,48.7988,2.37076504,9.714870936,1.8628125,-5.818132188,3.105389538,76.27424748 +221.67,50.43264103,-2.568772705,48.7804,2.374241229,9.715092899,1.81,-5.715111053,3.147041851,76.28177259 +221.68,50.43264125,-2.568771337,48.7626,2.370765038,9.714870794,1.7565625,-5.611940606,3.185949868,76.28929765 +221.69,50.43264146,-2.56876997,48.7453,2.356860259,9.713982589,1.7034375,-5.508642389,3.22207967,76.29682276 +221.7,50.43264167,-2.568768603,48.7285,2.356860255,9.714204554,1.6496875,-5.405237888,3.255399801,76.30434782 +221.71,50.43264188,-2.568767236,48.7123,2.37076503,9.715980757,1.595,-5.301748819,3.285881156,76.31187293 +221.72,50.4326421,-2.568765868,48.6966,2.370765025,9.717312892,1.5396875,-5.198196667,3.313497149,76.31939799 +221.73,50.43264231,-2.5687645,48.6815,2.356860238,9.717312825,1.483125,-5.094603204,3.338223773,76.3269231 +221.74,50.43264252,-2.568763133,48.6669,2.356860232,9.71731276,1.425,-4.990989918,3.36003937,76.33444816 +221.75,50.43264273,-2.568761765,48.653,2.370765009,9.717534729,1.366875,-4.887378522,3.378924975,76.34197327 +221.76,50.43264295,-2.568760397,48.6396,2.370765004,9.717312632,1.31,-4.783790675,3.394864146,76.34949832 +221.77,50.43264316,-2.56875903,48.6268,2.353384022,9.717312569,1.2528125,-4.680247977,3.4078429,76.35702344 +221.78,50.43264337,-2.568757662,48.6145,2.342955432,9.717534541,1.193125,-4.576772028,3.417850009,76.36454849 +221.79,50.43264358,-2.568756294,48.6029,2.353384014,9.717312446,1.1315625,-4.473384487,3.424876649,76.37207361 +221.8,50.43264379,-2.568754927,48.5919,2.370764989,9.717534419,1.0703125,-4.370106896,3.428916746,76.37959866 +221.81,50.43264401,-2.568753559,48.5815,2.370764992,9.71864453,1.01,-4.266960914,3.429966806,76.38712372 +221.82,50.43264422,-2.568752191,48.5717,2.353384016,9.719532607,0.9496875,-4.163967969,3.428025912,76.39464883 +221.83,50.43264443,-2.568750823,48.5625,2.339479224,9.719754584,0.8884375,-4.061149604,3.423095667,76.40217389 +221.84,50.43264464,-2.568749455,48.5539,2.336003011,9.719976561,0.8265625,-3.958527362,3.415180484,76.409699 +221.85,50.43264485,-2.568748087,48.546,2.336002994,9.720864641,0.7646875,-3.856122558,3.404287181,76.41722406 +221.86,50.43264506,-2.568746719,48.5386,2.336002992,9.721974756,0.701875,-3.753956678,3.39042527,76.42474917 +221.87,50.43264527,-2.56874535,48.5319,2.339479196,9.721974703,0.638125,-3.652050977,3.373606896,76.43227422 +221.88,50.43264548,-2.568743982,48.5259,2.353383984,9.720864481,0.575,-3.550426828,3.35384667,76.43979934 +221.89,50.43264569,-2.568742614,48.5204,2.370764961,9.720198328,0.5115625,-3.449105373,3.331161839,76.44732439 +221.9,50.43264591,-2.568741246,48.5156,2.370764959,9.720864379,0.4465625,-3.34810781,3.305572226,76.45484951 +221.91,50.43264612,-2.568739878,48.5115,2.353383983,9.722196532,0.3821875,-3.247455226,3.277100062,76.46237456 +221.92,50.43264633,-2.568738509,48.508,2.339479207,9.723306653,0.3196875,-3.147168647,3.245770214,76.46989968 +221.93,50.43264654,-2.568737141,48.5051,2.336003016,9.724194741,0.2565625,-3.047268986,3.211610012,76.47742473 +221.94,50.43264675,-2.568735772,48.5028,2.33600301,9.724638763,0.1915625,-2.947777157,3.17464925,76.48494984 +221.95,50.43264696,-2.568734403,48.5013,2.336003003,9.724194649,0.126875,-2.8487139,3.134920127,76.4924749 +221.96,50.43264717,-2.568733035,48.5003,2.336003001,9.723528503,0.0634375,-2.750099899,3.092457365,76.50000001 +221.97,50.43264738,-2.568731666,48.5,2.332526805,9.723306426,-0.000625,-2.651955724,3.047297863,76.50752507 +221.98,50.43264759,-2.568730298,48.5003,2.318622027,9.723306384,-0.06625,-2.554301943,2.999481097,76.51505018 +221.99,50.4326478,-2.568728929,48.5013,2.301241057,9.723528376,-0.131875,-2.457158954,2.949048779,76.52257524 +222,50.432648,-2.568727561,48.503,2.301241062,9.724416472,-0.19625,-2.360546983,2.896044797,76.53010035 +222.01,50.43264821,-2.568726192,48.5052,2.318622035,9.725748636,-0.26,-2.264486197,2.840515447,76.53762541 +222.02,50.43264842,-2.568724823,48.5082,2.332526811,9.726414699,-0.3234375,-2.168996707,2.782509085,76.54515052 +222.03,50.43264863,-2.568723454,48.5117,2.336003006,9.725970594,-0.3865625,-2.074098452,2.722076362,76.55267558 +222.04,50.43264884,-2.568722085,48.5159,2.336003007,9.72552649,-0.4503125,-1.9798112,2.659269931,76.56020069 +222.05,50.43264905,-2.568720717,48.5207,2.336003007,9.725748488,-0.515,-1.886154659,2.594144626,76.56772574 +222.06,50.43264926,-2.568719347,48.5262,2.336003,9.725970487,-0.5796875,-1.793148483,2.526757112,76.57525086 +222.07,50.43264947,-2.568717979,48.5323,2.332526798,9.726636554,-0.643125,-1.70081198,2.457166288,76.58277591 +222.08,50.43264968,-2.56871661,48.5391,2.318622026,9.728190759,-0.705,-1.609164458,2.385432774,76.59030103 +222.09,50.43264989,-2.56871524,48.5464,2.301241068,9.72885683,-0.766875,-1.518225055,2.31161908,76.59782608 +222.1,50.43265009,-2.568713871,48.5544,2.301241075,9.728190698,-0.83,-1.428012793,2.235789663,76.6053512 +222.11,50.4326503,-2.568712502,48.563,2.315145855,9.728190668,-0.8928125,-1.338546522,2.158010585,76.61287625 +222.12,50.43265051,-2.568711133,48.5723,2.315145859,9.729078774,-0.9534375,-1.249844863,2.078349742,76.62040136 +222.13,50.43265072,-2.568709763,48.5821,2.301241087,9.72930078,-1.0134375,-1.16192638,1.996876461,76.62792642 +222.14,50.43265092,-2.568708394,48.5925,2.301241096,9.72907872,-1.075,-1.074809408,1.913661962,76.63545153 +222.15,50.43265113,-2.568707025,48.6036,2.318622072,9.729300729,-1.1365625,-0.988512224,1.828778665,76.64297659 +222.16,50.43265134,-2.568705655,48.6153,2.329050656,9.729300704,-1.19625,-0.903052761,1.742300656,76.65050164 +222.17,50.43265155,-2.568704286,48.6275,2.318622072,9.72930068,-1.255,-0.818448839,1.654303334,76.65802676 +222.18,50.43265176,-2.568702917,48.6404,2.3012411,9.730410826,-1.3134375,-0.734718277,1.564863419,76.66555181 +222.19,50.43265196,-2.568701547,48.6538,2.297764912,9.731298938,-1.37125,-0.651878377,1.474058947,76.67307693 +222.2,50.43265217,-2.568700177,48.6678,2.301241119,9.730410782,-1.4284375,-0.569946558,1.381969103,76.68060198 +222.21,50.43265238,-2.568698808,48.6824,2.297764933,9.729522628,-1.485,-0.488939894,1.288674098,76.6881271 +222.22,50.43265258,-2.568697439,48.6975,2.297764934,9.730632778,-1.5415625,-0.408875345,1.194255352,76.69565215 +222.23,50.43265279,-2.568696069,48.7132,2.301241129,9.732631064,-1.598125,-0.329769583,1.098795255,76.70317726 +222.24,50.432653,-2.568694699,48.7295,2.297764939,9.733741215,-1.653125,-0.25163911,1.002376943,76.71070232 +222.25,50.4326532,-2.568693329,48.7463,2.297764952,9.733963231,-1.7065625,-0.174500255,0.905084584,76.71822743 +222.26,50.43265341,-2.568691959,48.7636,2.301241158,9.733741181,-1.76,-0.098369176,0.807002918,76.72575249 +222.27,50.43265362,-2.568690589,48.7815,2.29428877,9.732853031,-1.813125,-0.023261743,0.708217603,76.7332776 +222.28,50.43265382,-2.568689219,48.7999,2.283860183,9.731742848,-1.865,0.050806345,0.60881464,76.74080266 +222.29,50.43265403,-2.56868785,48.8188,2.28386019,9.731742835,-1.9165625,0.123819675,0.508880831,76.74832777 +222.3,50.43265423,-2.56868648,48.8382,2.29428879,9.733075025,-1.968125,0.195762948,0.408503266,76.75585283 +222.31,50.43265444,-2.56868511,48.8582,2.301241193,9.734851284,-2.0178125,0.266621154,0.307769494,76.76337794 +222.32,50.43265465,-2.56868374,48.8786,2.294288805,9.736183476,-2.065,0.336379511,0.20676729,76.770903 +222.33,50.43265485,-2.568682369,48.8995,2.283860219,9.736183466,-2.111875,0.405023407,0.105584834,76.77842811 +222.34,50.43265506,-2.568680999,48.9208,2.280384032,9.73529532,-2.1596875,0.472538519,0.004310247,76.78595316 +222.35,50.43265526,-2.568679629,48.9427,2.280384046,9.735295311,-2.2065625,0.538910752,-0.096968065,76.79347828 +222.36,50.43265547,-2.568678259,48.965,2.280384059,9.736183438,-2.25125,0.604126298,-0.198161808,76.80100333 +222.37,50.43265567,-2.568676888,48.9877,2.280384062,9.736405465,-2.295,0.66817152,-0.299182747,76.80852845 +222.38,50.43265588,-2.568675518,49.0109,2.280384064,9.736183425,-2.338125,0.731032955,-0.399942818,76.8160535 +222.39,50.43265608,-2.568674148,49.0345,2.280384073,9.736627486,-2.3796875,0.792697537,-0.50035413,76.82357862 +222.4,50.43265629,-2.568672777,49.0585,2.280384086,9.737293582,-2.42,0.853152434,-0.600329078,76.83110367 +222.41,50.43265649,-2.568671407,49.0829,2.280384092,9.737515611,-2.4596875,0.912384926,-0.699780571,76.83862878 +222.42,50.4326567,-2.568670036,49.1077,2.280384097,9.737515607,-2.4984375,0.97038275,-0.798621864,76.84615384 +222.43,50.4326569,-2.568668666,49.1329,2.280384115,9.737515603,-2.53625,1.027133704,-0.896766727,76.85367895 +222.44,50.43265711,-2.568667295,49.1584,2.280384128,9.737737634,-2.573125,1.082625927,-0.994129559,76.86120401 +222.45,50.43265731,-2.568665925,49.1844,2.276907924,9.738403733,-2.6084375,1.13684796,-1.090625564,76.86872912 +222.46,50.43265752,-2.568664554,49.2106,2.266479333,9.738847799,-2.643125,1.189788344,-1.186170459,76.87625418 +222.47,50.43265772,-2.568663183,49.2372,2.25952696,9.738625764,-2.678125,1.24143602,-1.280681051,76.88377929 +222.48,50.43265792,-2.568661813,49.2642,2.266479377,9.738847797,-2.71125,1.291780332,-1.374074833,76.89130435 +222.49,50.43265813,-2.568660442,49.2915,2.276907981,9.739957965,-2.74125,1.340810679,-1.466270446,76.89882946 +222.5,50.43265833,-2.568659071,49.319,2.276907988,9.7408461,-2.77,1.388516807,-1.557187389,76.90635452 +222.51,50.43265854,-2.5686577,49.3469,2.266479411,9.741068135,-2.7984375,1.434888745,-1.646746479,76.91387957 +222.52,50.43265874,-2.568656329,49.375,2.259527032,9.741068136,-2.82625,1.479916868,-1.734869622,76.92140468 +222.53,50.43265894,-2.568654958,49.4034,2.263003233,9.741068138,-2.853125,1.523591722,-1.821479871,76.92892974 +222.54,50.43265915,-2.568653587,49.4321,2.259527041,9.74106814,-2.878125,1.565904254,-1.906501765,76.93645485 +222.55,50.43265935,-2.568652216,49.461,2.245622268,9.741068143,-2.90125,1.606845526,-1.989861166,76.94397991 +222.56,50.43265955,-2.568650845,49.4901,2.245622285,9.741068145,-2.9234375,1.646407116,-2.071485421,76.95150502 +222.57,50.43265975,-2.568649474,49.5195,2.259527083,9.741290182,-2.9446875,1.684580601,-2.151303255,76.95903008 +222.58,50.43265996,-2.568648103,49.549,2.259527092,9.742178321,-2.9646875,1.721358189,-2.229245167,76.96655519 +222.59,50.43266016,-2.568646732,49.5788,2.245622319,9.743288494,-2.9834375,1.75673203,-2.305243091,76.97408025 +222.6,50.43266036,-2.56864536,49.6087,2.245622332,9.743510532,-3.00125,1.790694848,-2.37923085,76.98160536 +222.61,50.43266056,-2.568643989,49.6388,2.259527124,9.743288502,-3.018125,1.823239539,-2.451143872,76.98913042 +222.62,50.43266077,-2.568642618,49.6691,2.259527134,9.743510541,-3.033125,1.854359226,-2.520919474,76.99665553 +222.63,50.43266097,-2.568641246,49.6995,2.245622364,9.743510546,-3.04625,1.884047492,-2.588496752,77.00418058 +222.64,50.43266117,-2.568639875,49.73,2.24562237,9.743510551,-3.0584375,1.91229815,-2.653816863,77.0117057 +222.65,50.43266137,-2.568638504,49.7607,2.259527159,9.744620725,-3.0696875,1.939105184,-2.716822797,77.01923075 +222.66,50.43266158,-2.568637132,49.7914,2.259527169,9.7457309,-3.0796875,1.96446315,-2.777459608,77.02675587 +222.67,50.43266178,-2.56863576,49.8223,2.242146207,9.745508871,-3.088125,1.988366663,-2.835674469,77.03428092 +222.68,50.43266198,-2.568634389,49.8532,2.228241438,9.744842775,-3.0946875,2.010810737,-2.891416559,77.04180604 +222.69,50.43266218,-2.568633017,49.8842,2.224765251,9.744842781,-3.1,2.031790676,-2.944637233,77.04933109 +222.7,50.43266238,-2.568631646,49.9152,2.228241458,9.745730922,-3.1046875,2.051302123,-2.995290198,77.0568562 +222.71,50.43266258,-2.568630274,49.9463,2.242146255,9.746841098,-3.108125,2.069341012,-3.043331219,77.06438126 +222.72,50.43266278,-2.568628902,49.9774,2.259527245,9.746841104,-3.1096875,2.08590356,-3.088718414,77.07190637 +222.73,50.43266299,-2.56862753,50.0085,2.259527256,9.745952975,-3.1096875,2.100986273,-3.131412193,77.07943143 +222.74,50.43266319,-2.568626159,50.0396,2.242146288,9.745952981,-3.108125,2.114586056,-3.171375369,77.08695654 +222.75,50.43266339,-2.568624787,50.0707,2.228241512,9.747063156,-3.105,2.126700046,-3.208573049,77.0944816 +222.76,50.43266359,-2.568623415,50.1017,2.224765327,9.747951297,-3.10125,2.13732572,-3.242972748,77.10200671 +222.77,50.43266379,-2.568622043,50.1327,2.22476534,9.748173337,-3.0965625,2.146460844,-3.274544556,77.10953177 +222.78,50.43266399,-2.568620671,50.1637,2.224765349,9.748173343,-3.0896875,2.154103528,-3.303260914,77.11705688 +222.79,50.43266419,-2.568619299,50.1945,2.22476536,9.748395383,-3.0815625,2.160252225,-3.329096841,77.12458194 +222.8,50.43266439,-2.568617927,50.2253,2.224765373,9.749283524,-3.0734375,2.164905502,-3.352029649,77.13210705 +222.81,50.43266459,-2.568616555,50.256,2.224765381,9.7503937,-3.064375,2.168062556,-3.372039512,77.1396321 +222.82,50.43266479,-2.568615182,50.2866,2.224765392,9.750393705,-3.053125,2.169722587,-3.389108842,77.14715722 +222.83,50.43266499,-2.56861381,50.3171,2.224765405,9.749505575,-3.0396875,2.169885364,-3.403222855,77.15468227 +222.84,50.43266519,-2.568612438,50.3474,2.224765413,9.74950558,-3.025,2.168550774,-3.414369233,77.16220739 +222.85,50.43266539,-2.568611066,50.3776,2.224765424,9.750615755,-3.0096875,2.165719159,-3.422538179,77.16973244 +222.86,50.43266559,-2.568609693,50.4076,2.224765437,9.751503894,-2.993125,2.161391036,-3.427722645,77.1772575 +222.87,50.43266579,-2.568608321,50.4375,2.224765445,9.751725933,-2.9746875,2.155567378,-3.429918105,77.18478261 +222.88,50.43266599,-2.568606948,50.4671,2.221289261,9.751725937,-2.9546875,2.148249332,-3.429122553,77.19230767 +222.89,50.43266619,-2.568605576,50.4966,2.207384495,9.751725941,-2.9334375,2.139438502,-3.425336849,77.19983278 +222.9,50.43266639,-2.568604203,50.5258,2.190003523,9.751725944,-2.91125,2.129136663,-3.418564144,77.20735784 +222.91,50.43266658,-2.568602831,50.5548,2.190003524,9.751725949,-2.8884375,2.117345994,-3.408810397,77.21488295 +222.92,50.43266678,-2.568601458,50.5836,2.207384514,9.751725952,-2.8646875,2.104069015,-3.396084145,77.222408 +222.93,50.43266698,-2.568600086,50.6121,2.221289312,9.751725955,-2.8396875,2.089308362,-3.380396446,77.22993312 +222.94,50.43266718,-2.568598713,50.6404,2.224765516,9.751947991,-2.813125,2.073067243,-3.361760993,77.23745817 +222.95,50.43266738,-2.568597341,50.6684,2.22128933,9.752836127,-2.784375,2.055349039,-3.340194003,77.24498329 +222.96,50.43266758,-2.568595968,50.6961,2.207384555,9.754168331,-2.7534375,2.036157359,-3.315714381,77.25250834 +222.97,50.43266778,-2.568594595,50.7235,2.19000358,9.755056468,-2.7215625,2.015496272,-3.288343327,77.26003346 +222.98,50.43266797,-2.568593222,50.7505,2.19000359,9.755056469,-2.69,1.993370131,-3.25810485,77.26755851 +222.99,50.43266817,-2.568591849,50.7773,2.207384584,9.754168335,-2.6584375,1.969783464,-3.225025246,77.27508362 +223,50.43266837,-2.568590476,50.8037,2.217813183,9.753280199,-2.6259375,1.944741255,-3.189133336,77.28260868 +223.01,50.43266857,-2.568589104,50.8298,2.207384613,9.753946298,-2.5915625,1.918248775,-3.150460518,77.29013379 +223.02,50.43266877,-2.568587731,50.8556,2.190003659,9.755500534,-2.5546875,1.890311468,-3.109040368,77.29765885 +223.03,50.43266896,-2.568586357,50.8809,2.190003668,9.756166633,-2.5165625,1.860935177,-3.064909153,77.30518396 +223.04,50.43266916,-2.568584985,50.9059,2.203908443,9.756388665,-2.4784375,1.83012609,-3.018105262,77.31270902 +223.05,50.43266936,-2.568583611,50.9305,2.203908441,9.756610696,-2.439375,1.797890625,-2.968669547,77.32023413 +223.06,50.43266956,-2.568582238,50.9547,2.190003663,9.756166625,-2.3984375,1.764235543,-2.916645151,77.32775919 +223.07,50.43266975,-2.568580865,50.9785,2.186527472,9.755500519,-2.35625,1.729167775,-2.862077338,77.3352843 +223.08,50.43266995,-2.568579492,51.0018,2.190003677,9.755500514,-2.3134375,1.692694772,-2.805013779,77.34280936 +223.09,50.43267015,-2.568578119,51.0248,2.18652749,9.756388644,-2.27,1.654824038,-2.745504205,77.35033447 +223.1,50.43267034,-2.568576746,51.0472,2.186527496,9.757720841,-2.22625,1.615563537,-2.683600469,77.35785952 +223.11,50.43267054,-2.568575372,51.0693,2.190003702,9.758831004,-2.1815625,1.574921464,-2.61935666,77.36538464 +223.12,50.43267074,-2.568573999,51.0909,2.186527522,9.759719132,-2.1346875,1.532906297,-2.552828697,77.37290969 +223.13,50.43267093,-2.568572625,51.112,2.186527529,9.759941157,-2.0865625,1.48952686,-2.484074621,77.38043481 +223.14,50.43267113,-2.568571251,51.1326,2.190003724,9.758830979,-2.0384375,1.444792091,-2.413154421,77.38795986 +223.15,50.43267133,-2.568569878,51.1528,2.183051338,9.757942833,-1.9896875,1.398711445,-2.340129861,77.39548498 +223.16,50.43267152,-2.568568505,51.1724,2.172622763,9.758830958,-1.9396875,1.351294546,-2.265064712,77.40301003 +223.17,50.43267172,-2.568567131,51.1916,2.17262277,9.759941117,-1.8884375,1.302551251,-2.188024406,77.41053514 +223.18,50.43267191,-2.568565757,51.2102,2.183051358,9.759941105,-1.83625,1.252491699,-2.109076093,77.4180602 +223.19,50.43267211,-2.568564384,51.2283,2.190003755,9.759941092,-1.78375,1.201126434,-2.028288643,77.42558526 +223.2,50.43267231,-2.56856301,51.2459,2.18305137,9.760163112,-1.73125,1.148466112,-1.945732472,77.43311037 +223.21,50.4326725,-2.568561636,51.2629,2.172622783,9.759941064,-1.678125,1.094521792,-1.861479659,77.44063542 +223.22,50.4326727,-2.568560263,51.2795,2.169146594,9.760163084,-1.623125,1.039304703,-1.775603541,77.44816054 +223.23,50.43267289,-2.568558889,51.2954,2.169146609,9.761273237,-1.5665625,0.982826362,-1.688179062,77.45568559 +223.24,50.43267309,-2.568557515,51.3108,2.169146614,9.762161356,-1.5103125,0.92509863,-1.59928254,77.46321071 +223.25,50.43267328,-2.568556141,51.3256,2.16914661,9.762383372,-1.4546875,0.866133481,-1.508991325,77.47073576 +223.26,50.43267348,-2.568554767,51.3399,2.169146613,9.762383353,-1.398125,0.80594329,-1.417384311,77.47826088 +223.27,50.43267367,-2.568553393,51.3536,2.16914662,9.762383335,-1.34,0.744540549,-1.324541314,77.48578593 +223.28,50.43267387,-2.568552019,51.3667,2.169146622,9.762383315,-1.2815625,0.681938207,-1.23054329,77.49331104 +223.29,50.43267406,-2.568550645,51.3792,2.165670432,9.762383294,-1.223125,0.618149211,-1.135472231,77.5008361 +223.3,50.43267426,-2.568549271,51.3912,2.155241854,9.762605305,-1.163125,0.55318697,-1.039410987,77.50836121 +223.31,50.43267445,-2.568547897,51.4025,2.148289464,9.763493418,-1.101875,0.487064947,-0.94244338,77.51588627 +223.32,50.43267464,-2.568546523,51.4132,2.155241853,9.764603565,-1.0415625,0.419797124,-0.844653923,77.52341138 +223.33,50.43267484,-2.568545148,51.4233,2.165670447,9.76460354,-0.9815625,0.351397365,-0.746127929,77.53093644 +223.34,50.43267503,-2.568543774,51.4329,2.165670459,9.763715379,-0.92,0.281880052,-0.646951341,77.53846155 +223.35,50.43267523,-2.5685424,51.4417,2.155241872,9.763715352,-0.858125,0.211259738,-0.547210562,77.54598661 +223.36,50.43267542,-2.568541026,51.45,2.148289472,9.764825495,-0.796875,0.139551033,-0.446992623,77.55351172 +223.37,50.43267561,-2.568539651,51.4577,2.151765674,9.765713602,-0.734375,0.066769064,-0.346384844,77.56103678 +223.38,50.43267581,-2.568538277,51.4647,2.151765694,9.765935607,-0.6703125,-0.007071044,-0.245475058,77.56856189 +223.39,50.432676,-2.568536902,51.4711,2.14828951,9.766157611,-0.606875,-0.081953878,-0.144351216,77.57608694 +223.4,50.43267619,-2.568535528,51.4768,2.1517657,9.766823681,-0.5446875,-0.157863738,-0.043101495,77.58361206 +223.41,50.43267639,-2.568534153,51.482,2.151765691,9.767267717,-0.4815625,-0.234784869,0.058185812,77.59113711 +223.42,50.43267658,-2.568532778,51.4865,2.148289495,9.76704565,-0.4165625,-0.31270117,0.159422355,77.59866223 +223.43,50.43267677,-2.568531404,51.4903,2.151765692,9.767045615,-0.351875,-0.391596313,0.260519899,77.60618728 +223.44,50.43267697,-2.568530029,51.4935,2.148289487,9.767267614,-0.2884375,-0.471453853,0.361390264,77.6137124 +223.45,50.43267716,-2.568528654,51.4961,2.1343847,9.767045545,-0.2246875,-0.552257174,0.461945503,77.62123745 +223.46,50.43267735,-2.56852728,51.498,2.13438471,9.767267543,-0.16,-0.633989259,0.562097896,77.62876256 +223.47,50.43267754,-2.568525905,51.4993,2.148289498,9.768155641,-0.0953125,-0.716633207,0.66176018,77.63628762 +223.48,50.43267774,-2.56852453,51.4999,2.148289489,9.768377636,-0.0315625,-0.800171657,0.760845324,77.64381273 +223.49,50.43267793,-2.568523155,51.4999,2.134384702,9.768377596,0.031875,-0.884587191,0.859267097,77.65133779 +223.5,50.43267812,-2.568521781,51.4993,2.13438471,9.769487724,0.096875,-0.969862161,0.956939499,77.6588629 +223.51,50.43267831,-2.568520405,51.498,2.148289498,9.770597852,0.163125,-1.055978806,1.053777445,77.66638796 +223.52,50.43267851,-2.56851903,51.496,2.148289488,9.770375775,0.228125,-1.142919078,1.149696481,77.67391307 +223.53,50.4326787,-2.568517655,51.4934,2.130908503,9.769709631,0.2915625,-1.230664872,1.244613014,77.68143813 +223.54,50.43267889,-2.56851628,51.4902,2.117003725,9.769487552,0.355,-1.319197852,1.338444192,77.68896318 +223.55,50.43267908,-2.568514905,51.4863,2.113527533,9.769487507,0.4184375,-1.408499512,1.431108198,77.6964883 +223.56,50.43267927,-2.56851353,51.4818,2.117003722,9.769487461,0.4815625,-1.498551174,1.522524301,77.70401335 +223.57,50.43267946,-2.568512155,51.4767,2.130908497,9.769709448,0.5453125,-1.589334102,1.61261269,77.71153846 +223.58,50.43267965,-2.56851078,51.4709,2.14828948,9.770597534,0.6096875,-1.680829332,1.701294926,77.71906352 +223.59,50.43267985,-2.568509405,51.4645,2.148289487,9.771929687,0.673125,-1.773017668,1.788493544,77.72658863 +223.6,50.43268004,-2.568508029,51.4574,2.130908502,9.772817773,0.735,-1.865879974,1.874132629,77.73411369 +223.61,50.43268023,-2.568506654,51.4498,2.117003712,9.773039756,0.796875,-1.959396771,1.958137409,77.7416388 +223.62,50.43268042,-2.568505278,51.4415,2.113527523,9.773039704,0.86,-2.053548519,2.040434661,77.74916386 +223.63,50.43268061,-2.568503903,51.4326,2.113527532,9.772817617,0.9228125,-2.148315681,2.120952591,77.75668897 +223.64,50.4326808,-2.568502527,51.423,2.113527524,9.772151462,0.9834375,-2.243678318,2.199621072,77.76421403 +223.65,50.43268099,-2.568501152,51.4129,2.113527505,9.771929374,1.043125,-2.339616605,2.276371461,77.77173914 +223.66,50.43268118,-2.568499777,51.4022,2.113527489,9.773039487,1.10375,-2.43611049,2.351136781,77.7792642 +223.67,50.43268137,-2.568498401,51.3908,2.113527485,9.774149599,1.1646875,-2.533139747,2.423851886,77.78678931 +223.68,50.43268156,-2.568497025,51.3789,2.113527492,9.774149542,1.2246875,-2.630684265,2.49445335,77.79431436 +223.69,50.43268175,-2.56849565,51.3663,2.113527495,9.774149484,1.2834375,-2.728723531,2.562879637,77.80183948 +223.7,50.43268194,-2.568494274,51.3532,2.113527484,9.774371458,1.34125,-2.827237093,2.629070987,77.80936453 +223.71,50.43268213,-2.568492898,51.3395,2.113527468,9.774149365,1.39875,-2.926204494,2.692969819,77.81688965 +223.72,50.43268232,-2.568491523,51.3252,2.113527464,9.774371338,1.45625,-3.025604936,2.754520326,77.8244147 +223.73,50.43268251,-2.568490147,51.3104,2.113527468,9.775481445,1.5134375,-3.125417679,2.813668822,77.83193982 +223.74,50.4326827,-2.568488771,51.2949,2.113527462,9.776369517,1.5696875,-3.225621924,2.870363798,77.83946487 +223.75,50.43268289,-2.568487395,51.279,2.113527448,9.776591488,1.6246875,-3.326196758,2.92455575,77.84698998 +223.76,50.43268308,-2.568486019,51.2624,2.110051246,9.776591423,1.67875,-3.427121097,2.976197468,77.85451504 +223.77,50.43268327,-2.568484643,51.2454,2.096146467,9.776591358,1.7328125,-3.528373912,3.025243858,77.86204015 +223.78,50.43268346,-2.568483267,51.2278,2.078765494,9.776591293,1.786875,-3.629934119,3.071652236,77.86956521 +223.79,50.43268364,-2.568481891,51.2096,2.0787655,9.776591226,1.839375,-3.731780403,3.115382094,77.87709032 +223.8,50.43268383,-2.568480515,51.191,2.096146469,9.776591158,1.89,-3.833891509,3.156395215,77.88461538 +223.81,50.43268402,-2.568479139,51.1718,2.110051228,9.77659109,1.9403125,-3.936246179,3.194655962,77.89214049 +223.82,50.43268421,-2.568477763,51.1522,2.113527409,9.776813055,1.99125,-4.038822985,3.23013093,77.89966555 +223.83,50.4326844,-2.568476387,51.132,2.110051215,9.777701121,2.0415625,-4.141600556,3.262789181,77.90719066 +223.84,50.43268459,-2.568475011,51.1113,2.096146427,9.779033253,2.089375,-4.244557347,3.292602237,77.91471572 +223.85,50.43268478,-2.568473634,51.0902,2.07876543,9.779921316,2.135,-4.347671931,3.319544031,77.92224083 +223.86,50.43268496,-2.568472258,51.0686,2.078765412,9.779921245,2.1803125,-4.450922765,3.343591184,77.92976588 +223.87,50.43268515,-2.568470881,51.0466,2.092670192,9.779255071,2.22625,-4.55428819,3.36472267,77.937291 +223.88,50.43268534,-2.568469505,51.0241,2.092670196,9.77881093,2.2715625,-4.657746778,3.382920096,77.94481605 +223.89,50.43268553,-2.568468129,51.0011,2.078765408,9.779254925,2.3146875,-4.761276814,3.398167534,77.95234111 +223.9,50.43268571,-2.568466752,50.9778,2.078765394,9.779920953,2.356875,-4.864856697,3.410451692,77.95986622 +223.91,50.4326859,-2.568465376,50.954,2.092670162,9.780142911,2.3996875,-4.96846477,3.419761912,77.96739128 +223.92,50.43268609,-2.568463999,50.9298,2.092670154,9.780364868,2.44125,-5.072079489,3.426090059,77.97491639 +223.93,50.43268628,-2.568462623,50.9051,2.078765373,9.781030893,2.48,-5.175679139,3.429430632,77.98244145 +223.94,50.43268646,-2.568461246,50.8802,2.075289185,9.781474884,2.518125,-5.279242062,3.429780652,77.98996656 +223.95,50.43268665,-2.568459869,50.8548,2.078765385,9.781252773,2.5565625,-5.382746716,3.427139832,77.99749162 +223.96,50.43268684,-2.568458493,50.829,2.075289171,9.781474729,2.5928125,-5.486171442,3.421510522,78.00501673 +223.97,50.43268702,-2.568457116,50.8029,2.075289141,9.782362785,2.6265625,-5.589494583,3.412897591,78.01254179 +223.98,50.43268721,-2.568455739,50.7765,2.07876532,9.782362706,2.66,-5.692694653,3.401308603,78.0200669 +223.99,50.4326874,-2.568454362,50.7497,2.075289124,9.781474492,2.693125,-5.79575005,3.386753584,78.02759195 +224,50.43268758,-2.568452986,50.7226,2.075289124,9.781696446,2.7246875,-5.89863929,3.369245255,78.03511707 +224.01,50.43268777,-2.568451609,50.6952,2.078765311,9.783472636,2.7546875,-6.001340829,3.348798912,78.04264212 +224.02,50.43268796,-2.568450232,50.6675,2.0718129,9.784582723,2.7834375,-6.103833296,3.325432375,78.05016724 +224.03,50.43268814,-2.568448854,50.6395,2.061384291,9.783916541,2.8115625,-6.206095204,3.299166042,78.05769229 +224.04,50.43268833,-2.568447478,50.6113,2.061384282,9.783472392,2.8396875,-6.30810524,3.270022715,78.0652174 +224.05,50.43268851,-2.568446101,50.5827,2.071812873,9.784138412,2.86625,-6.40984209,3.23802795,78.07274246 +224.06,50.4326887,-2.568444723,50.5539,2.078765263,9.784582396,2.8896875,-6.511284497,3.203209534,78.08026757 +224.07,50.43268889,-2.568443347,50.5249,2.071812857,9.784804347,2.9115625,-6.612411318,3.165597834,78.08779263 +224.08,50.43268907,-2.568441969,50.4957,2.061384256,9.785026298,2.9334375,-6.713201413,3.125225738,78.09531774 +224.09,50.43268926,-2.568440592,50.4662,2.057908061,9.78480418,2.9546875,-6.813633695,3.082128426,78.1028428 +224.1,50.43268944,-2.568439215,50.4366,2.057908062,9.785026131,2.9746875,-6.913687252,3.036343426,78.11036791 +224.11,50.43268963,-2.568437838,50.4067,2.057908051,9.786136216,2.993125,-7.013341171,2.987910673,78.11789297 +224.12,50.43268981,-2.56843646,50.3767,2.057908034,9.787024267,3.0096875,-7.112574596,2.936872395,78.12541808 +224.13,50.43269,-2.568435083,50.3465,2.05790802,9.787024183,3.025,-7.211366844,2.883273167,78.13294314 +224.14,50.43269018,-2.568433705,50.3162,2.057908002,9.786357997,3.0396875,-7.309697288,2.827159686,78.14046825 +224.15,50.43269037,-2.568432328,50.2857,2.057907981,9.786135878,3.053125,-7.407545416,2.768580825,78.14799331 +224.16,50.43269055,-2.568430951,50.2551,2.054431775,9.787245961,3.0646875,-7.504890716,2.707587749,78.15551842 +224.17,50.43269074,-2.568429573,50.2244,2.044003187,9.788134011,3.0746875,-7.601712906,2.644233628,78.16304347 +224.18,50.43269092,-2.568428195,50.1936,2.037050796,9.787245792,3.083125,-7.69799176,2.578573696,78.17056859 +224.19,50.4326911,-2.568426818,50.1627,2.04400319,9.786357572,3.09,-7.793707167,2.510665191,78.17809364 +224.2,50.43269129,-2.568425441,50.1318,2.054431777,9.787467655,3.0965625,-7.888839131,2.440567357,78.18561876 +224.21,50.43269147,-2.568424063,50.1008,2.054431759,9.789243839,3.103125,-7.983367828,2.368341329,78.19314381 +224.22,50.43269166,-2.568422685,50.0697,2.044003138,9.789465787,3.1078125,-8.077273491,2.294050074,78.20066892 +224.23,50.43269184,-2.568421307,50.0386,2.037050727,9.788577567,3.1096875,-8.170536467,2.217758337,78.20819398 +224.24,50.43269202,-2.56841993,50.0075,2.040526922,9.788577482,3.1096875,-8.263137333,2.139532696,78.21571904 +224.25,50.43269221,-2.568418552,49.9764,2.040526921,9.789687564,3.108125,-8.35505678,2.05944139,78.22324415 +224.26,50.43269239,-2.568417174,49.9453,2.037050717,9.790575614,3.105,-8.4462755,1.977554147,78.23076921 +224.27,50.43269257,-2.568415796,49.9143,2.040526903,9.790797562,3.1015625,-8.536774584,1.89394253,78.23829432 +224.28,50.43269276,-2.568414418,49.8833,2.040526891,9.790797477,3.0984375,-8.626535012,1.808679306,78.24581937 +224.29,50.43269294,-2.56841304,49.8523,2.037050677,9.790797392,3.094375,-8.715538047,1.7218389,78.25334449 +224.3,50.43269312,-2.568411662,49.8214,2.040526854,9.790797306,3.088125,-8.803765182,1.633497059,78.26086954 +224.31,50.43269331,-2.568410284,49.7905,2.037050657,9.790797221,3.0796875,-8.891197969,1.54373073,78.26839466 +224.32,50.43269349,-2.568408906,49.7598,2.023145885,9.790797137,3.0696875,-8.977818072,1.452618294,78.27591971 +224.33,50.43269367,-2.568407528,49.7291,2.023145884,9.790797052,3.0584375,-9.063607501,1.360239105,78.28344483 +224.34,50.43269385,-2.56840615,49.6986,2.03705065,9.791019001,3.04625,-9.148548322,1.266673779,78.29096988 +224.35,50.43269404,-2.568404772,49.6682,2.037050631,9.791907051,3.033125,-9.232622717,1.172003906,78.29849499 +224.36,50.43269422,-2.568403394,49.6379,2.019669638,9.793017136,3.018125,-9.315813209,1.076312047,78.30602005 +224.37,50.4326944,-2.568402015,49.6078,2.009241031,9.793239087,3.00125,-9.398102382,0.979681626,78.31354516 +224.38,50.43269458,-2.568400637,49.5779,2.019669599,9.79301697,2.9834375,-9.479473103,0.882196868,78.32107022 +224.39,50.43269476,-2.568399259,49.5481,2.037050569,9.79323892,2.9646875,-9.559908299,0.783942857,78.32859533 +224.4,50.43269495,-2.56839788,49.5186,2.037050573,9.793238837,2.9446875,-9.639391239,0.68500525,78.33612039 +224.41,50.43269513,-2.568396502,49.4892,2.019669602,9.793016721,2.9234375,-9.717905307,0.585470277,78.3436455 +224.42,50.43269531,-2.568395124,49.4601,2.005764823,9.793460707,2.9009375,-9.795434117,0.485424741,78.35117056 +224.43,50.43269549,-2.568393745,49.4312,2.002288618,9.794126726,2.876875,-9.871961397,0.384955961,78.35869567 +224.44,50.43269567,-2.568392367,49.4025,2.005764791,9.794348678,2.85125,-9.947471275,0.284151486,78.36622073 +224.45,50.43269585,-2.568390988,49.3742,2.019669548,9.794570631,2.825,-10.02194794,0.183099206,78.37374584 +224.46,50.43269603,-2.56838961,49.346,2.037050505,9.795458685,2.798125,-10.09537586,0.081887243,78.38127089 +224.47,50.43269622,-2.568388231,49.3182,2.037050496,9.796568773,2.7696875,-10.16773963,-0.019396111,78.38879601 +224.48,50.4326964,-2.568386852,49.2906,2.01966952,9.796568693,2.74,-10.23902417,-0.120662505,78.39632106 +224.49,50.43269658,-2.568385473,49.2634,2.005764737,9.79568048,2.709375,-10.30921465,-0.221823762,78.40384618 +224.5,50.43269676,-2.568384095,49.2364,2.002288537,9.795680401,2.6765625,-10.37829635,-0.32279153,78.41137123 +224.51,50.43269694,-2.568382716,49.2098,2.002288537,9.796568458,2.6415625,-10.44625487,-0.423477805,78.41889634 +224.52,50.43269712,-2.568381337,49.1836,2.00228854,9.796790414,2.606875,-10.51307602,-0.523794865,78.4264214 +224.53,50.4326973,-2.568379958,49.1577,2.002288532,9.796790337,2.573125,-10.5787458,-0.623655106,78.43394651 +224.54,50.43269748,-2.56837858,49.1321,2.002288511,9.797678395,2.5378125,-10.6432506,-0.722971553,78.44147157 +224.55,50.43269766,-2.5683772,49.1069,2.002288486,9.797900353,2.4996875,-10.70657681,-0.821657517,78.44899668 +224.56,50.43269784,-2.568375821,49.0821,2.002288465,9.796568076,2.4596875,-10.76871128,-0.919626998,78.45652174 +224.57,50.43269802,-2.568374443,49.0577,2.002288457,9.796123934,2.4184375,-10.82964104,-1.016794566,78.46404679 +224.58,50.4326982,-2.568373064,49.0337,2.002288461,9.79790013,2.3765625,-10.88935339,-1.113075483,78.47157191 +224.59,50.43269838,-2.568371685,49.0102,2.002288462,9.799898359,2.335,-10.94783576,-1.208385752,78.47909696 +224.6,50.43269856,-2.568370305,48.987,2.002288459,9.80012032,2.293125,-11.00507602,-1.302642294,78.48662208 +224.61,50.43269874,-2.568368926,48.9643,2.002288461,9.799232114,2.2496875,-11.06106225,-1.395762947,78.49414713 +224.62,50.43269892,-2.568367547,48.942,1.99881227,9.799232043,2.2046875,-11.11578264,-1.487666409,78.50167225 +224.63,50.4326991,-2.568366168,48.9202,1.984907481,9.800120106,2.158125,-11.16922585,-1.578272636,78.5091973 +224.64,50.43269928,-2.568364788,48.8988,1.967526485,9.800120036,2.1103125,-11.22138071,-1.66750262,78.51672241 +224.65,50.43269945,-2.568363409,48.878,1.96752647,9.799231834,2.063125,-11.27223633,-1.755278493,78.52424747 +224.66,50.43269963,-2.56836203,48.8576,1.984907437,9.799231766,2.0165625,-11.32178199,-1.84152371,78.53177258 +224.67,50.43269981,-2.568360651,48.8376,1.998812204,9.800341866,1.9675,-11.37000751,-1.926163156,78.53929764 +224.68,50.43269999,-2.568359271,48.8182,1.998812187,9.801229934,1.915,-11.41690273,-2.009122918,78.54682275 +224.69,50.43270017,-2.568357892,48.7993,1.984907401,9.801451902,1.861875,-11.4624578,-2.09033069,78.55434781 +224.7,50.43270035,-2.568356512,48.781,1.967526438,9.801451837,1.81,-11.50666333,-2.169715654,78.56187292 +224.71,50.43270052,-2.568355133,48.7631,1.967526452,9.801451773,1.7584375,-11.54950997,-2.247208597,78.56939798 +224.72,50.4327007,-2.568353753,48.7458,1.984907427,9.801673743,1.7059375,-11.59098891,-2.322741967,78.57692309 +224.73,50.43270088,-2.568352374,48.729,1.995335997,9.802339781,1.651875,-11.63109137,-2.396249874,78.58444815 +224.74,50.43270106,-2.568350994,48.7127,1.984907397,9.802783786,1.59625,-11.66980899,-2.467668204,78.59197326 +224.75,50.43270124,-2.568349614,48.6971,1.967526412,9.802561692,1.54,-11.7071337,-2.536934676,78.59949831 +224.76,50.43270141,-2.568348235,48.6819,1.967526408,9.802783667,1.4834375,-11.74305775,-2.603988901,78.60702343 +224.77,50.43270159,-2.568346855,48.6674,1.981431187,9.803893776,1.4265625,-11.77757353,-2.668772436,78.61454848 +224.78,50.43270177,-2.568345475,48.6534,1.981431192,9.804559818,1.37,-11.81067399,-2.731228732,78.6220736 +224.79,50.43270195,-2.568344095,48.64,1.967526417,9.80389366,1.3128125,-11.84235208,-2.791303357,78.62959865 +224.8,50.43270212,-2.568342715,48.6271,1.964050218,9.802783435,1.2534375,-11.87260122,-2.848943942,78.63712377 +224.81,50.4327023,-2.568341336,48.6149,1.967526396,9.802783381,1.193125,-11.90141515,-2.904100183,78.64464882 +224.82,50.43270248,-2.568339956,48.6033,1.96405018,9.803893495,1.1334375,-11.92878775,-2.956724007,78.65217393 +224.83,50.43270265,-2.568338576,48.5922,1.964050163,9.80500361,1.073125,-11.9547134,-3.006769579,78.65969899 +224.84,50.43270283,-2.568337196,48.5818,1.967526355,9.805891691,1.0115625,-11.97918666,-3.054193124,78.6672241 +224.85,50.43270301,-2.568335816,48.572,1.964050168,9.806335706,0.9503125,-12.00220238,-3.098953446,78.67474916 +224.86,50.43270318,-2.568334435,48.5628,1.964050176,9.806113621,0.89,-12.02375579,-3.141011356,78.68227427 +224.87,50.43270336,-2.568333056,48.5542,1.96752638,9.806113572,0.8296875,-12.04384237,-3.180330298,78.68979933 +224.88,50.43270354,-2.568331675,48.5462,1.964050193,9.806335557,0.768125,-12.06245794,-3.216875953,78.69732444 +224.89,50.43270371,-2.568330295,48.5388,1.964050191,9.806113476,0.7046875,-12.07959861,-3.250616463,78.7048495 +224.9,50.43270389,-2.568328915,48.5321,1.967526373,9.806335462,0.64,-12.09526075,-3.281522322,78.71237461 +224.91,50.43270407,-2.568327535,48.526,1.960573972,9.807223551,0.5753125,-12.10944117,-3.309566716,78.71989967 +224.92,50.43270424,-2.568326154,48.5206,1.950145382,9.807223506,0.5115625,-12.12213688,-3.334725063,78.72742472 +224.93,50.43270442,-2.568324774,48.5158,1.946669185,9.806335329,0.4484375,-12.13334526,-3.356975478,78.73494983 +224.94,50.43270459,-2.568323394,48.5116,1.946669186,9.806335286,0.385,-12.14306388,-3.376298594,78.74247489 +224.95,50.43270477,-2.568322014,48.5081,1.946669194,9.807445413,0.3215625,-12.15129081,-3.39267751,78.75 +224.96,50.43270494,-2.568320633,48.5052,1.946669204,9.808333506,0.2584375,-12.15802421,-3.406097957,78.75752506 +224.97,50.43270512,-2.568319253,48.5029,1.946669204,9.8085555,0.1946875,-12.16326282,-3.416548249,78.76505017 +224.98,50.43270529,-2.568317872,48.5013,1.946669192,9.808777495,0.13,-12.16700544,-3.424019275,78.77257523 +224.99,50.43270547,-2.568316492,48.5003,1.946669183,9.809443559,0.065,-12.16925132,-3.428504503,78.78010034 +225,50.43270564,-2.568315111,48.5,1.946669181,9.809887589,-1.56E-12,-12.17,-3.42999998,78.7876254 +225.01,50.43270582,-2.56831373,48.5003,1.946669183,9.809443486,-0.065,-12.16925132,-3.428504503,78.79515051 +225.02,50.43270599,-2.56831235,48.5013,1.946669193,9.80877735,-0.13,-12.16700544,-3.424019275,78.80267557 +225.03,50.43270617,-2.568310969,48.5029,1.946669204,9.808777317,-0.1946875,-12.16326282,-3.416548249,78.81020068 +225.04,50.43270634,-2.568309589,48.5052,1.94319301,9.809665419,-0.2584375,-12.15802421,-3.406097957,78.81772573 +225.05,50.43270652,-2.568308208,48.5081,1.932764411,9.810997589,-0.3215625,-12.15129081,-3.39267751,78.82525085 +225.06,50.43270669,-2.568306827,48.5116,1.925812004,9.811885693,-0.385,-12.14306388,-3.376298594,78.8327759 +225.07,50.43270686,-2.568305446,48.5158,1.929288187,9.811885663,-0.4484375,-12.13334526,-3.356975478,78.84030102 +225.08,50.43270704,-2.568304065,48.5206,1.929288189,9.8109975,-0.5115625,-12.12213688,-3.334725063,78.84782607 +225.09,50.43270721,-2.568302684,48.526,1.925812008,9.810109338,-0.5753125,-12.10944117,-3.309566716,78.85535119 +225.1,50.43270738,-2.568301304,48.5321,1.932764419,9.810997446,-0.64,-12.09526075,-3.281522322,78.86287624 +225.11,50.43270756,-2.568299923,48.5388,1.94319302,9.812995722,-0.7046875,-12.07959861,-3.250616463,78.87040135 +225.12,50.43270773,-2.568298541,48.5462,1.943193023,9.813217731,-0.768125,-12.06245794,-3.216875953,78.87792641 +225.13,50.43270791,-2.56829716,48.5542,1.929288232,9.81210754,-0.8296875,-12.04384237,-3.180330298,78.88545152 +225.14,50.43270808,-2.56829578,48.5628,1.911907249,9.812329551,-0.89,-12.02375579,-3.141011356,78.89297658 +225.15,50.43270825,-2.568294398,48.572,1.91190725,9.813217664,-0.9503125,-12.00220238,-3.098953446,78.90050169 +225.16,50.43270842,-2.568293017,48.5818,1.925812037,9.81299561,-1.0115625,-11.97918666,-3.054193124,78.90802675 +225.17,50.4327086,-2.568291636,48.5922,1.929288244,9.812551523,-1.073125,-11.9547134,-3.006769579,78.91555186 +225.18,50.43270877,-2.568290255,48.6033,1.925812063,9.813217605,-1.1334375,-11.92878775,-2.956724007,78.92307692 +225.19,50.43270894,-2.568288874,48.6149,1.929288262,9.814327754,-1.193125,-11.90141515,-2.904100183,78.93060203 +225.2,50.43270912,-2.568287492,48.6271,1.92581206,9.814549771,-1.2534375,-11.87260122,-2.848943942,78.93812709 +225.21,50.43270929,-2.568286111,48.64,1.908431077,9.814327722,-1.3128125,-11.84235208,-2.791303357,78.9456522 +225.22,50.43270946,-2.56828473,48.6534,1.898002493,9.814771774,-1.37,-11.81067399,-2.731228732,78.95317725 +225.23,50.43270963,-2.568283348,48.6674,1.908431086,9.81543786,-1.4265625,-11.77757353,-2.668772436,78.96070237 +225.24,50.4327098,-2.568281967,48.6819,1.925812076,9.815437847,-1.4834375,-11.74305775,-2.603988901,78.96822742 +225.25,50.43270998,-2.568280585,48.6971,1.925812092,9.814771734,-1.54,-11.7071337,-2.536934676,78.97575254 +225.26,50.43271015,-2.568279204,48.7127,1.908431119,9.814549689,-1.59625,-11.66980899,-2.467668204,78.98327759 +225.27,50.43271032,-2.568277823,48.729,1.894526331,9.815659846,-1.651875,-11.63109137,-2.396249874,78.99080265 +225.28,50.43271049,-2.568276441,48.7458,1.894526328,9.816770005,-1.7059375,-11.59098891,-2.322741967,78.99832776 +225.29,50.43271066,-2.568275059,48.7631,1.908431113,9.816769996,-1.7584375,-11.54950997,-2.247208597,79.00585282 +225.3,50.43271083,-2.568273678,48.781,1.925812098,9.816992021,-1.81,-11.50666333,-2.169715654,79.01337793 +225.31,50.43271101,-2.568272296,48.7993,1.925812112,9.818102181,-1.861875,-11.4624578,-2.09033069,79.02090299 +225.32,50.43271118,-2.568270914,48.8182,1.908431151,9.818768275,-1.915,-11.41690273,-2.009122918,79.0284281 +225.33,50.43271135,-2.568269532,48.8376,1.894526375,9.818102169,-1.9675,-11.37000751,-1.926163156,79.03595315 +225.34,50.43271152,-2.56826815,48.8576,1.891050175,9.816991997,-2.0165625,-11.32178199,-1.84152371,79.04347827 +225.35,50.43271169,-2.568266769,48.878,1.891050172,9.816991993,-2.063125,-11.27223633,-1.755278493,79.05100332 +225.36,50.43271186,-2.568265387,48.8988,1.891050176,9.818102158,-2.1103125,-11.22138071,-1.66750262,79.05852844 +225.37,50.43271203,-2.568264005,48.9202,1.891050184,9.81899029,-2.158125,-11.16922585,-1.578272636,79.06605349 +225.38,50.4327122,-2.568262623,48.942,1.8910502,9.819212322,-2.2046875,-11.11578264,-1.487666409,79.07357861 +225.39,50.43271237,-2.568261241,48.9643,1.891050218,9.819212321,-2.2496875,-11.06106225,-1.395762947,79.08110366 +225.4,50.43271254,-2.568259859,48.987,1.891050224,9.819212321,-2.293125,-11.00507602,-1.302642294,79.08862877 +225.41,50.43271271,-2.568258477,49.0102,1.89105022,9.819212321,-2.335,-10.94783576,-1.208385752,79.09615383 +225.42,50.43271288,-2.568257095,49.0337,1.891050221,9.819212322,-2.3765625,-10.88935339,-1.113075483,79.10367894 +225.43,50.43271305,-2.568255713,49.0577,1.891050237,9.819212323,-2.4184375,-10.82964104,-1.016794566,79.111204 +225.44,50.43271322,-2.568254331,49.0821,1.891050264,9.819434359,-2.4596875,-10.76871128,-0.919626998,79.11872911 +225.45,50.43271339,-2.568252949,49.1069,1.891050282,9.820322497,-2.4996875,-10.70657681,-0.821657517,79.12625417 +225.46,50.43271356,-2.568251567,49.1321,1.891050279,9.821432668,-2.5378125,-10.6432506,-0.722971553,79.13377928 +225.47,50.43271373,-2.568250184,49.1577,1.891050266,9.821432672,-2.573125,-10.5787458,-0.623655106,79.14130434 +225.48,50.4327139,-2.568248802,49.1836,1.891050263,9.820544542,-2.606875,-10.51307602,-0.523794865,79.14882945 +225.49,50.43271407,-2.56824742,49.2098,1.891050271,9.820544548,-2.6415625,-10.44625487,-0.423477805,79.15635451 +225.5,50.43271424,-2.568246038,49.2364,1.887574092,9.821654721,-2.6765625,-10.37829635,-0.32279153,79.16387962 +225.51,50.43271441,-2.568244655,49.2634,1.873669328,9.822542862,-2.709375,-10.30921465,-0.221823762,79.17140467 +225.52,50.43271458,-2.568243273,49.2906,1.856288357,9.822542869,-2.74,-10.23902417,-0.120662505,79.17892979 +225.53,50.43271474,-2.56824189,49.3182,1.856288354,9.821876776,-2.7696875,-10.16773963,-0.019396111,79.18645484 +225.54,50.43271491,-2.568240508,49.346,1.873669333,9.82165475,-2.798125,-10.09537586,0.081887243,79.19397996 +225.55,50.43271508,-2.568239126,49.3742,1.887574122,9.822764927,-2.825,-10.02194794,0.183099206,79.20150501 +225.56,50.43271525,-2.568237743,49.4025,1.887574133,9.823875103,-2.85125,-9.947471275,0.284151486,79.20903013 +225.57,50.43271542,-2.56823636,49.4312,1.873669367,9.823875112,-2.876875,-9.871961397,0.384955961,79.21655518 +225.58,50.43271559,-2.568234978,49.4601,1.856288407,9.823875122,-2.9009375,-9.795434117,0.485424741,79.22408029 +225.59,50.43271575,-2.568233595,49.4892,1.856288416,9.824097166,-2.9234375,-9.717905307,0.585470277,79.23160535 +225.6,50.43271592,-2.568232212,49.5186,1.873669393,9.823875143,-2.9446875,-9.639391239,0.68500525,79.23913046 +225.61,50.43271609,-2.56823083,49.5481,1.88409798,9.823875153,-2.9646875,-9.559908299,0.783942857,79.24665552 +225.62,50.43271626,-2.568229447,49.5779,1.873669401,9.824319231,-2.9834375,-9.479473103,0.882196868,79.25418057 +225.63,50.43271643,-2.568228064,49.6078,1.856288439,9.824763309,-3.00125,-9.398102382,0.979681626,79.26170569 +225.64,50.43271659,-2.568226682,49.6379,1.852812263,9.825207388,-3.018125,-9.315813209,1.076312047,79.26923074 +225.65,50.43271676,-2.568225298,49.6682,1.856288468,9.8252074,-3.033125,-9.232622717,1.172003906,79.27675586 +225.66,50.43271693,-2.568223916,49.6986,1.85281227,9.825207413,-3.04625,-9.148548322,1.266673779,79.28428091 +225.67,50.43271709,-2.568222533,49.7291,1.852812274,9.826317594,-3.0584375,-9.063607501,1.360239105,79.29180603 +225.68,50.43271726,-2.56822115,49.7598,1.856288495,9.82720574,-3.0696875,-8.977818072,1.452618294,79.29933108 +225.69,50.43271743,-2.568219766,49.7905,1.85281233,9.826317618,-3.0796875,-8.891197969,1.54373073,79.30685619 +225.7,50.43271759,-2.568218384,49.8214,1.852812339,9.825207463,-3.088125,-8.803765182,1.633497059,79.31438125 +225.71,50.43271776,-2.568217001,49.8523,1.856288522,9.825651543,-3.094375,-8.715538047,1.7218389,79.32190636 +225.72,50.43271793,-2.568215618,49.8833,1.852812317,9.827205791,-3.0984375,-8.626535012,1.808679306,79.32943142 +225.73,50.43271809,-2.568214235,49.9143,1.852812324,9.828538006,-3.1015625,-8.536774584,1.89394253,79.33695653 +225.74,50.43271826,-2.568212851,49.9453,1.856288538,9.828538019,-3.105,-8.4462755,1.977554147,79.34448159 +225.75,50.43271843,-2.568211468,49.9764,1.849336166,9.827649899,-3.108125,-8.35505678,2.05944139,79.3520067 +225.76,50.43271859,-2.568210085,50.0075,1.838907586,9.827649912,-3.1096875,-8.263137333,2.139532696,79.35953176 +225.77,50.43271876,-2.568208702,50.0386,1.838907584,9.82853806,-3.1096875,-8.170536467,2.217758337,79.36705687 +225.78,50.43271892,-2.568207318,50.0697,1.849336173,9.828760106,-3.1078125,-8.077273491,2.294050074,79.37458193 +225.79,50.43271909,-2.568205935,50.1008,1.856288575,9.828538086,-3.103125,-7.983367828,2.368341329,79.38210704 +225.8,50.43271926,-2.568204552,50.1318,1.8493362,9.828982166,-3.0965625,-7.888839131,2.440567357,79.38963209 +225.81,50.43271942,-2.568203168,50.1627,1.838907631,9.829648281,-3.09,-7.793707167,2.510665191,79.39715721 +225.82,50.43271959,-2.568201785,50.1936,1.835431446,9.829870328,-3.083125,-7.69799176,2.578573696,79.40468226 +225.83,50.43271975,-2.568200401,50.2244,1.835431453,9.829870341,-3.0746875,-7.601712906,2.644233628,79.41220738 +225.84,50.43271992,-2.568199018,50.2551,1.835431466,9.829870353,-3.0646875,-7.504890716,2.707587749,79.41973243 +225.85,50.43272008,-2.568197634,50.2857,1.835431482,9.8300924,-3.053125,-7.407545416,2.768580825,79.42725755 +225.86,50.43272025,-2.568196251,50.3162,1.835431491,9.830758514,-3.0396875,-7.309697288,2.827159686,79.4347826 +225.87,50.43272041,-2.568194867,50.3465,1.835431491,9.831202593,-3.025,-7.211366844,2.883273167,79.44230771 +225.88,50.43272058,-2.568193483,50.3767,1.835431486,9.830980572,-3.0096875,-7.112574596,2.936872395,79.44983277 +225.89,50.43272074,-2.5681921,50.4067,1.831955289,9.831202618,-2.993125,-7.013341171,2.987910673,79.45735788 +225.9,50.43272091,-2.568190716,50.4366,1.821526709,9.832090764,-2.9746875,-6.913687252,3.036343426,79.46488294 +225.91,50.43272107,-2.568189332,50.4662,1.814574333,9.832090776,-2.9546875,-6.813633695,3.082128426,79.47240805 +225.92,50.43272123,-2.568187948,50.4957,1.821526746,9.831202653,-2.9334375,-6.713201413,3.125225738,79.47993311 +225.93,50.4327214,-2.568186565,50.5249,1.831955346,9.831202663,-2.9115625,-6.612411318,3.165597834,79.48745822 +225.94,50.43272156,-2.568185181,50.5539,1.831955352,9.832312842,-2.8896875,-6.511284497,3.203209534,79.49498328 +225.95,50.43272173,-2.568183797,50.5827,1.821526775,9.833200987,-2.86625,-6.40984209,3.23802795,79.50250833 +225.96,50.43272189,-2.568182413,50.6113,1.814574397,9.833423031,-2.8396875,-6.30810524,3.270022715,79.51003345 +225.97,50.43272205,-2.568181029,50.6395,1.818050602,9.83342304,-2.8115625,-6.206095204,3.299166042,79.5175585 +225.98,50.43272222,-2.568179645,50.6675,1.818050601,9.833423049,-2.7834375,-6.103833296,3.325432375,79.52508361 +225.99,50.43272238,-2.568178261,50.6952,1.814574399,9.833423057,-2.7546875,-6.001340829,3.348798912,79.53260867 +226,50.43272254,-2.568176877,50.7226,1.818050595,9.833423066,-2.7246875,-5.89863929,3.369245255,79.54013378 +226.01,50.43272271,-2.568175493,50.7497,1.818050602,9.833423074,-2.693125,-5.79575005,3.386753584,79.54765884 +226.02,50.43272287,-2.568174109,50.7765,1.814574422,9.833645114,-2.66,-5.692694653,3.401308603,79.55518395 +226.03,50.43272303,-2.568172725,50.8029,1.81805064,9.834533256,-2.6265625,-5.589494583,3.412897591,79.56270901 +226.04,50.4327232,-2.568171341,50.829,1.814574459,9.835643431,-2.5928125,-5.486171442,3.421510522,79.57023412 +226.05,50.43272336,-2.568169956,50.8548,1.80066968,9.835643437,-2.5565625,-5.382746716,3.427139832,79.57775918 +226.06,50.43272352,-2.568168572,50.8802,1.800669681,9.834755308,-2.518125,-5.279242062,3.429780652,79.58528429 +226.07,50.43272368,-2.568167188,50.9051,1.81457447,9.834755312,-2.48,-5.175679139,3.429430632,79.59280935 +226.08,50.43272385,-2.568165804,50.9298,1.814574479,9.83564345,-2.44125,-5.072079489,3.426090059,79.60033446 +226.09,50.43272401,-2.568164419,50.954,1.797193501,9.835865487,-2.3996875,-4.96846477,3.419761912,79.60785951 +226.1,50.43272417,-2.568163035,50.9778,1.786764906,9.835643457,-2.356875,-4.864856697,3.410451692,79.61538463 +226.11,50.43272433,-2.568161651,51.0011,1.797193494,9.836087527,-2.3146875,-4.761276814,3.398167534,79.62290968 +226.12,50.43272449,-2.568160266,51.0241,1.814574487,9.83675363,-2.2715625,-4.657746778,3.382920096,79.6304348 +226.13,50.43272466,-2.568158882,51.0466,1.814574511,9.836975664,-2.22625,-4.55428819,3.36472267,79.63795985 +226.14,50.43272482,-2.568157497,51.0686,1.797193555,9.837197698,-2.1803125,-4.450922765,3.343591184,79.64548497 +226.15,50.43272498,-2.568156113,51.0902,1.783288774,9.837863798,-2.135,-4.347671931,3.319544031,79.65301002 +226.16,50.43272514,-2.568154728,51.1113,1.779812564,9.838307864,-2.089375,-4.244557347,3.292602237,79.66053513 +226.17,50.4327253,-2.568153343,51.132,1.779812561,9.837863796,-2.0415625,-4.141600556,3.262789181,79.66806019 +226.18,50.43272546,-2.568151959,51.1522,1.78328877,9.837197694,-1.99125,-4.038822985,3.23013093,79.6755853 +226.19,50.43272562,-2.568150574,51.1718,1.797193563,9.837197691,-1.9403125,-3.936246179,3.194655962,79.68311036 +226.2,50.43272578,-2.56814919,51.191,1.814574543,9.838085821,-1.89,-3.833891509,3.156395215,79.69063547 +226.21,50.43272595,-2.568147805,51.2096,1.814574551,9.839418017,-1.839375,-3.731780403,3.115382094,79.69816053 +226.22,50.43272611,-2.56814642,51.2278,1.79719359,9.840306145,-1.786875,-3.629934119,3.071652236,79.70568564 +226.23,50.43272627,-2.568145035,51.2454,1.783288818,9.84030614,-1.7328125,-3.528373912,3.025243858,79.7132107 +226.24,50.43272643,-2.56814365,51.2624,1.779812615,9.839417998,-1.67875,-3.427121097,2.976197468,79.72073581 +226.25,50.43272659,-2.568142265,51.279,1.7798126,9.838307822,-1.6246875,-3.326196758,2.92455575,79.72826087 +226.26,50.43272675,-2.568140881,51.2949,1.779812596,9.838529847,-1.5696875,-3.225621924,2.870363798,79.73578598 +226.27,50.43272691,-2.568139496,51.3104,1.779812607,9.840306106,-1.5134375,-3.125417679,2.813668822,79.74331103 +226.28,50.43272707,-2.568138111,51.3252,1.779812624,9.841638297,-1.45625,-3.025604936,2.754520326,79.75083615 +226.29,50.43272723,-2.568136725,51.3395,1.779812637,9.841638287,-1.39875,-2.926204494,2.692969819,79.7583612 +226.3,50.43272739,-2.568135341,51.3532,1.779812641,9.841638275,-1.34125,-2.827237093,2.629070987,79.76588626 +226.31,50.43272755,-2.568133955,51.3663,1.779812638,9.841860296,-1.2834375,-2.728723531,2.562879637,79.77341137 +226.32,50.43272771,-2.56813257,51.3789,1.77633644,9.841416214,-1.2246875,-2.630684265,2.49445335,79.78093643 +226.33,50.43272787,-2.568131185,51.3908,1.762431658,9.840750099,-1.1646875,-2.533139747,2.423851886,79.78846154 +226.34,50.43272803,-2.5681298,51.4022,1.745050676,9.840750084,-1.10375,-2.43611049,2.351136781,79.7959866 +226.35,50.43272818,-2.568128415,51.4129,1.745050677,9.841638202,-1.043125,-2.339616605,2.276371461,79.80351171 +226.36,50.43272834,-2.56812703,51.423,1.762431669,9.842748352,-0.9834375,-2.243678318,2.199621072,79.81103677 +226.37,50.4327285,-2.568125644,51.4326,1.776336466,9.842970367,-0.9228125,-2.148315681,2.120952591,79.81856188 +226.38,50.43272866,-2.568124259,51.4415,1.779812666,9.842748315,-0.86,-2.053548519,2.040434661,79.82608694 +226.39,50.43272882,-2.568122874,51.4498,1.779812659,9.843192362,-0.796875,-1.959396771,1.958137409,79.83361205 +226.4,50.43272898,-2.568121488,51.4574,1.776336451,9.843858442,-0.735,-1.865879974,1.874132629,79.8411371 +226.41,50.43272914,-2.568120103,51.4645,1.762431661,9.843858419,-0.673125,-1.773017668,1.788493544,79.84866222 +226.42,50.4327293,-2.568118717,51.4709,1.745050693,9.843192295,-0.6096875,-1.680829332,1.701294926,79.85618727 +226.43,50.43272945,-2.568117332,51.4767,1.745050717,9.842748205,-0.5453125,-1.589334102,1.61261269,79.86371239 +226.44,50.43272961,-2.568115947,51.4818,1.762431704,9.843192247,-0.4815625,-1.498551174,1.522524301,79.87123744 +226.45,50.43272977,-2.568114561,51.4863,1.772860276,9.844080355,-0.4184375,-1.408499512,1.431108198,79.87876255 +226.46,50.43272993,-2.568113176,51.4902,1.762431677,9.845190496,-0.355,-1.319197852,1.338444192,79.88628761 +226.47,50.43273009,-2.56811179,51.4934,1.745050702,9.846300636,-0.2915625,-1.230664872,1.244613014,79.89381272 +226.48,50.43273024,-2.568110404,51.496,1.745050712,9.846300608,-0.228125,-1.142919078,1.149696481,79.90133778 +226.49,50.4327304,-2.568109018,51.498,1.7589555,9.84519041,-0.163125,-1.055978806,1.053777445,79.90886289 +226.5,50.43273056,-2.568107633,51.4993,1.758955494,9.844302245,-0.096875,-0.969862161,0.956939499,79.91638795 +226.51,50.43273072,-2.568106247,51.4999,1.745050702,9.844302213,-0.031875,-0.884587191,0.859267097,79.92391306 +226.52,50.43273087,-2.568104862,51.4999,1.741574507,9.845190315,0.0315625,-0.800171657,0.760845324,79.93143812 +226.53,50.43273103,-2.568103476,51.4993,1.745050704,9.846522483,0.0953125,-0.716633207,0.66176018,79.93896323 +226.54,50.43273119,-2.56810209,51.498,1.741574507,9.847410584,0.16,-0.633989259,0.562097896,79.94648829 +226.55,50.43273134,-2.568100704,51.4961,1.741574517,9.847632581,0.2246875,-0.552257174,0.461945503,79.9540134 +226.56,50.4327315,-2.568099318,51.4935,1.745050722,9.847632545,0.2884375,-0.471453853,0.361390264,79.96153846 +226.57,50.43273166,-2.568097932,51.4903,1.741574513,9.847632507,0.351875,-0.391596313,0.260519899,79.96906357 +226.58,50.43273181,-2.568096546,51.4865,1.741574495,9.847632469,0.4165625,-0.31270117,0.159422355,79.97658862 +226.59,50.43273197,-2.56809516,51.482,1.745050691,9.847632429,0.4815625,-0.234784869,0.058185812,79.98411374 +226.6,50.43273213,-2.568093774,51.4768,1.738098313,9.847632389,0.5446875,-0.157863738,-0.043101495,79.99163879 +226.61,50.43273228,-2.568092388,51.4711,1.727669732,9.847632348,0.606875,-0.081953878,-0.144351216,79.99916391 +226.62,50.43273244,-2.568091002,51.4647,1.727669719,9.847632306,0.6703125,-0.007071044,-0.245475058,80.00668896 +226.63,50.43273259,-2.568089616,51.4577,1.738098288,9.847632263,0.734375,0.066769064,-0.346384844,80.01421407 +226.64,50.43273275,-2.56808823,51.45,1.745050673,9.847854252,0.796875,0.139551033,-0.446992623,80.02173913 +226.65,50.43273291,-2.568086844,51.4417,1.738098293,9.848742341,0.858125,0.211259738,-0.547210562,80.02926419 +226.66,50.43273306,-2.568085458,51.4329,1.727669721,9.849852463,0.92,0.281880052,-0.646951341,80.0367893 +226.67,50.43273322,-2.568084071,51.4233,1.724193522,9.849852416,0.9815625,0.351397365,-0.746127929,80.04431436 +226.68,50.43273337,-2.568082685,51.4132,1.724193499,9.848964234,1.0415625,0.419797124,-0.844653923,80.05183947 +226.69,50.43273353,-2.568081299,51.4025,1.72419349,9.848964185,1.101875,0.487064947,-0.94244338,80.05936452 +226.7,50.43273368,-2.568079913,51.3912,1.724193502,9.850074303,1.163125,0.55318697,-1.039410987,80.06688964 +226.71,50.43273384,-2.568078526,51.3792,1.72419351,9.850962386,1.223125,0.618149211,-1.135472231,80.07441469 +226.72,50.43273399,-2.56807714,51.3667,1.724193498,9.851184369,1.2815625,0.681938207,-1.23054329,80.08193981 +226.73,50.43273415,-2.568075753,51.3536,1.724193483,9.851184317,1.34,0.744540549,-1.324541314,80.08946486 +226.74,50.4327343,-2.568074367,51.3399,1.724193482,9.851184263,1.398125,0.80594329,-1.417384311,80.09698997 +226.75,50.43273446,-2.56807298,51.3256,1.724193485,9.851184209,1.4546875,0.866133481,-1.508991325,80.10451503 +226.76,50.43273461,-2.568071594,51.3108,1.720717286,9.851184155,1.5103125,0.92509863,-1.59928254,80.11204014 +226.77,50.43273477,-2.568070207,51.2954,1.710288691,9.851406132,1.5665625,0.982826362,-1.688179062,80.1195652 +226.78,50.43273492,-2.568068821,51.2795,1.703336291,9.852072176,1.623125,1.039304703,-1.775603541,80.12709031 +226.79,50.43273507,-2.568067434,51.2629,1.710288674,9.852516186,1.678125,1.094521792,-1.861479659,80.13461537 +226.8,50.43273523,-2.568066047,51.2459,1.720717256,9.852294094,1.73125,1.148466112,-1.945732472,80.14214048 +226.81,50.43273538,-2.568064661,51.2283,1.720717255,9.852516069,1.78375,1.201126434,-2.028288643,80.14966554 +226.82,50.43273554,-2.568063274,51.2102,1.710288667,9.853404143,1.83625,1.252491699,-2.109076093,80.15719065 +226.83,50.43273569,-2.568061887,51.1916,1.703336268,9.853404082,1.8884375,1.302551251,-2.188024406,80.16471571 +226.84,50.43273584,-2.5680605,51.1724,1.706812453,9.852515887,1.9396875,1.351294546,-2.265064712,80.17224082 +226.85,50.432736,-2.568059114,51.1528,1.706812446,9.852515825,1.9896875,1.398711445,-2.340129861,80.17976588 +226.86,50.43273615,-2.568057727,51.1326,1.703336255,9.853625929,2.0384375,1.444792091,-2.413154421,80.18729099 +226.87,50.4327363,-2.56805634,51.112,1.706812455,9.854513999,2.0865625,1.48952686,-2.484074621,80.19481604 +226.88,50.43273646,-2.568054953,51.0909,1.703336244,9.854735969,2.1346875,1.532906297,-2.552828697,80.20234116 +226.89,50.43273661,-2.568053566,51.0693,1.689431442,9.854735904,2.1815625,1.574921464,-2.61935666,80.20986621 +226.9,50.43273676,-2.568052179,51.0472,1.689431445,9.854735839,2.22625,1.615563537,-2.683600469,80.21739133 +226.91,50.43273691,-2.568050792,51.0248,1.703336235,9.854735772,2.27,1.654824038,-2.745504205,80.22491638 +226.92,50.43273707,-2.568049405,51.0018,1.70333622,9.854735705,2.3134375,1.692694772,-2.805013779,80.23244149 +226.93,50.43273722,-2.568048018,50.9785,1.689431418,9.854957671,2.35625,1.729167775,-2.862077338,80.23996655 +226.94,50.43273737,-2.568046631,50.9547,1.68943142,9.855845736,2.3984375,1.764235543,-2.916645151,80.24749166 +226.95,50.43273752,-2.568045244,50.9305,1.70333621,9.856955835,2.439375,1.797890625,-2.968669547,80.25501672 +226.96,50.43273768,-2.568043856,50.9059,1.703336192,9.856955766,2.4784375,1.83012609,-3.018105262,80.26254183 +226.97,50.43273783,-2.568042469,50.8809,1.685955187,9.855845528,2.5165625,1.860935177,-3.064909153,80.27006689 +226.98,50.43273798,-2.568041082,50.8556,1.6720504,9.855179357,2.5546875,1.890311468,-3.109040368,80.277592 +226.99,50.43273813,-2.568039695,50.8298,1.672050413,9.855845387,2.5915625,1.918248775,-3.150460518,80.28511706 +227,50.43273828,-2.568038308,50.8037,1.685955193,9.856955483,2.6259375,1.944741255,-3.189133336,80.29264211 +227.01,50.43273843,-2.56803692,50.7773,1.703336151,9.857177444,2.6584375,1.969783464,-3.225025246,80.30016723 +227.02,50.43273859,-2.568035533,50.7505,1.703336144,9.856955337,2.69,1.993370131,-3.25810485,80.30769228 +227.03,50.43273874,-2.568034146,50.7235,1.685955172,9.857399331,2.7215625,2.015496272,-3.288343327,80.3152174 +227.04,50.43273889,-2.568032758,50.6961,1.672050379,9.858065358,2.7534375,2.036157359,-3.315714381,80.32274245 +227.05,50.43273904,-2.568031371,50.6684,1.668574157,9.858065284,2.784375,2.055349039,-3.340194003,80.33026756 +227.06,50.43273919,-2.568029983,50.6404,1.66857415,9.857399109,2.813125,2.073067243,-3.361760993,80.33779262 +227.07,50.43273934,-2.568028596,50.6121,1.66857416,9.857177001,2.8396875,2.089308362,-3.380396446,80.34531773 +227.08,50.43273949,-2.568027209,50.5836,1.668574153,9.858509127,2.8646875,2.104069015,-3.396084145,80.35284279 +227.09,50.43273964,-2.568025821,50.5548,1.668574128,9.860285319,2.8884375,2.117345994,-3.408810397,80.3603679 +227.1,50.43273979,-2.568024433,50.5258,1.66857412,9.860507277,2.91125,2.129136663,-3.418564144,80.36789296 +227.11,50.43273994,-2.568023045,50.4966,1.66857413,9.859619067,2.9334375,2.139438502,-3.425336849,80.37541807 +227.12,50.43274009,-2.568021658,50.4671,1.668574122,9.859396957,2.9546875,2.148249332,-3.429122553,80.38294313 +227.13,50.43274024,-2.56802027,50.4375,1.668574097,9.859618913,2.9746875,2.155567378,-3.429918105,80.39046824 +227.14,50.43274039,-2.568018882,50.4076,1.668574089,9.859396803,2.993125,2.161391036,-3.427722645,80.3979933 +227.15,50.43274054,-2.568017495,50.3776,1.668574099,9.859396725,3.0096875,2.165719159,-3.422538179,80.40551841 +227.16,50.43274069,-2.568016107,50.3474,1.668574091,9.859618681,3.025,2.168550774,-3.414369233,80.41304346 +227.17,50.43274084,-2.568014719,50.3171,1.668574066,9.859396569,3.0396875,2.169885364,-3.403222855,80.42056858 +227.18,50.43274099,-2.568013332,50.2866,1.668574058,9.859618524,3.053125,2.169722587,-3.389108842,80.42809363 +227.19,50.43274114,-2.568011944,50.256,1.668574067,9.860728614,3.064375,2.168062556,-3.372039512,80.43561875 +227.2,50.43274129,-2.568010556,50.2253,1.668574059,9.861616669,3.0734375,2.164905502,-3.352029649,80.4431438 +227.21,50.43274144,-2.568009168,50.1945,1.668574034,9.861838624,3.0815625,2.160252225,-3.329096841,80.45066892 +227.22,50.43274159,-2.56800778,50.1637,1.668574026,9.861838544,3.0896875,2.154103528,-3.303260914,80.45819397 +227.23,50.43274174,-2.568006392,50.1327,1.665097839,9.861838465,3.0965625,2.146460844,-3.274544556,80.46571908 +227.24,50.43274189,-2.568005004,50.1017,1.651193048,9.862060421,3.10125,2.13732572,-3.242972748,80.47324414 +227.25,50.43274204,-2.568003616,50.0707,1.633812048,9.862726443,3.105,2.126700046,-3.208573049,80.48076925 +227.26,50.43274218,-2.568002228,50.0396,1.633812042,9.863170431,3.108125,2.114586056,-3.171375369,80.48829431 +227.27,50.43274233,-2.568000839,50.0085,1.651193022,9.862948319,3.1096875,2.100986273,-3.131412193,80.49581942 +227.28,50.43274248,-2.567999452,49.9774,1.66509779,9.86294824,3.1096875,2.08590356,-3.088718414,80.50334448 +227.29,50.43274263,-2.567998063,49.9463,1.665097773,9.863170194,3.108125,2.069341012,-3.043331219,80.51086959 +227.3,50.43274278,-2.567996675,49.9152,1.651192989,9.862948082,3.1046875,2.051302123,-2.995290198,80.51839465 +227.31,50.43274293,-2.567995287,49.8842,1.63381201,9.863170037,3.1,2.031790676,-2.944637233,80.52591976 +227.32,50.43274307,-2.567993899,49.8532,1.633811995,9.864058093,3.0946875,2.010810737,-2.891416559,80.53344482 +227.33,50.43274322,-2.56799251,49.8223,1.647716769,9.864280048,3.088125,1.988366663,-2.835674469,80.54096987 +227.34,50.43274337,-2.567991122,49.7914,1.647716772,9.864057935,3.0796875,1.96446315,-2.777459608,80.54849498 +227.35,50.43274352,-2.567989734,49.7607,1.63381198,9.864501924,3.0696875,1.939105184,-2.716822797,80.55602004 +227.36,50.43274366,-2.567988345,49.73,1.633811961,9.865167947,3.0584375,1.91229815,-2.653816863,80.56354515 +227.37,50.43274381,-2.567986957,49.6995,1.64771674,9.865389903,3.04625,1.884047492,-2.588496752,80.57107021 +227.38,50.43274396,-2.567985568,49.6691,1.647716739,9.865389825,3.033125,1.854359226,-2.520919474,80.57859532 +227.39,50.43274411,-2.56798418,49.6388,1.633811938,9.865389747,3.018125,1.823239539,-2.451143872,80.58612038 +227.4,50.43274425,-2.567982791,49.6087,1.630335725,9.86538967,3.00125,1.790694848,-2.37923085,80.59364549 +227.41,50.4327444,-2.567981403,49.5788,1.633811923,9.865389594,2.9834375,1.75673203,-2.305243091,80.60117055 +227.42,50.43274455,-2.567980014,49.549,1.63033573,9.865611551,2.9646875,1.721358189,-2.229245167,80.60869566 +227.43,50.43274469,-2.567978626,49.5195,1.63033572,9.866277576,2.9446875,1.684580601,-2.151303255,80.61622072 +227.44,50.43274484,-2.567977237,49.4901,1.633811902,9.866721567,2.9234375,1.646407116,-2.071485421,80.62374583 +227.45,50.43274499,-2.567975848,49.461,1.626859503,9.866499458,2.90125,1.606845526,-1.989861166,80.63127088 +227.46,50.43274513,-2.56797446,49.4321,1.616430915,9.866721416,2.878125,1.565904254,-1.906501765,80.638796 +227.47,50.43274528,-2.567973071,49.4034,1.616430912,9.867831508,2.853125,1.523591722,-1.821479871,80.64632105 +227.48,50.43274542,-2.567971682,49.375,1.626859488,9.868497534,2.82625,1.479916868,-1.734869622,80.65384617 +227.49,50.43274557,-2.567970293,49.3469,1.633811866,9.86783136,2.7984375,1.434888745,-1.646746479,80.66137122 +227.5,50.43274572,-2.567968904,49.319,1.626859465,9.86672112,2.77,1.388516807,-1.557187389,80.66889634 +227.51,50.43274586,-2.567967516,49.2915,1.616430871,9.866721047,2.74125,1.340810679,-1.466270446,80.67642139 +227.52,50.43274601,-2.567966127,49.2642,1.61295467,9.867831142,2.71125,1.291780332,-1.374074833,80.6839465 +227.53,50.43274615,-2.567964738,49.2372,1.61295467,9.868719205,2.678125,1.24143602,-1.280681051,80.69147156 +227.54,50.4327463,-2.567963349,49.2106,1.612954665,9.868941167,2.643125,1.189788344,-1.186170459,80.69899667 +227.55,50.43274644,-2.56796196,49.1844,1.61295465,9.868941095,2.6084375,1.13684796,-1.090625564,80.70652173 +227.56,50.43274659,-2.567960571,49.1584,1.612954641,9.868941025,2.573125,1.082625927,-0.994129559,80.71404684 +227.57,50.43274673,-2.567959182,49.1329,1.612954646,9.868940956,2.53625,1.027133704,-0.896766727,80.7215719 +227.58,50.43274688,-2.567957793,49.1077,1.612954642,9.868940887,2.4984375,0.97038275,-0.798621864,80.72909701 +227.59,50.43274702,-2.567956404,49.0829,1.612954631,9.869162852,2.4596875,0.912384926,-0.699780571,80.73662207 +227.6,50.43274717,-2.567955015,49.0585,1.612954629,9.869828884,2.42,0.853152434,-0.600329078,80.74414718 +227.61,50.43274731,-2.567953626,49.0345,1.612954619,9.870272883,2.3796875,0.792697537,-0.50035413,80.75167224 +227.62,50.43274746,-2.567952236,49.0109,1.612954595,9.870050783,2.338125,0.731032955,-0.399942818,80.75919735 +227.63,50.4327476,-2.567950848,48.9877,1.609478394,9.870272751,2.295,0.66817152,-0.299182747,80.7667224 +227.64,50.43274775,-2.567949458,48.965,1.599049819,9.871382854,2.25125,0.604126298,-0.198161808,80.77424752 +227.65,50.43274789,-2.567948069,48.9427,1.592097427,9.87204889,2.2065625,0.538910752,-0.096968065,80.78177257 +227.66,50.43274803,-2.567946679,48.9208,1.595573612,9.871382726,2.1596875,0.472538519,0.004310247,80.78929769 +227.67,50.43274818,-2.56794529,48.8995,1.595573612,9.870272496,2.111875,0.405023407,0.105584834,80.79682274 +227.68,50.43274832,-2.567943901,48.8786,1.592097409,9.870272433,2.065,0.336379511,0.20676729,80.8043478 +227.69,50.43274846,-2.567942512,48.8582,1.599049783,9.871382539,2.0178125,0.266621154,0.307769494,80.81187291 +227.7,50.43274861,-2.567941122,48.8382,1.609478367,9.872270612,1.968125,0.195762948,0.408503266,80.81939797 +227.71,50.43274875,-2.567939733,48.8188,1.609478371,9.872270553,1.9165625,0.123819675,0.508880831,80.82692308 +227.72,50.4327489,-2.567938343,48.7999,1.595573585,9.871604393,1.865,0.050806345,0.60881464,80.83444814 +227.73,50.43274904,-2.567936954,48.7815,1.578192602,9.871382301,1.813125,-0.023261743,0.708217603,80.84197325 +227.74,50.43274918,-2.567935565,48.7636,1.5781926,9.872492411,1.76,-0.098369176,0.807002918,80.8494983 +227.75,50.43274932,-2.567934175,48.7463,1.592097373,9.873602521,1.7065625,-0.174500255,0.905084584,80.85702342 +227.76,50.43274947,-2.567932785,48.7295,1.592097363,9.873602465,1.653125,-0.25163911,1.002376943,80.86454847 +227.77,50.43274961,-2.567931396,48.7132,1.578192577,9.873824444,1.598125,-0.329769583,1.098795255,80.87207359 +227.78,50.43274975,-2.567930006,48.6975,1.57819258,9.874712524,1.5415625,-0.408875345,1.194255352,80.87959864 +227.79,50.43274989,-2.567928616,48.6824,1.592097362,9.874712471,1.485,-0.488939894,1.288674098,80.88712376 +227.8,50.43275004,-2.567927226,48.6678,1.592097356,9.873824285,1.4284375,-0.569946558,1.381969103,80.89464881 +227.81,50.43275018,-2.567925837,48.6538,1.574716376,9.873824234,1.37125,-0.651878377,1.474058947,80.90217392 +227.82,50.43275032,-2.567924447,48.6404,1.564287786,9.874934352,1.3134375,-0.734718277,1.564863419,80.90969898 +227.83,50.43275046,-2.567923057,48.6275,1.57471636,9.875600402,1.255,-0.818448839,1.654303334,80.91722409 +227.84,50.4327506,-2.567921667,48.6153,1.592097332,9.874934253,1.19625,-0.903052761,1.742300656,80.92474915 +227.85,50.43275075,-2.567920277,48.6036,1.592097343,9.873824038,1.1365625,-0.988512224,1.828778665,80.93227426 +227.86,50.43275089,-2.567918888,48.5925,1.574716372,9.873823992,1.075,-1.074809408,1.913661962,80.93979932 +227.87,50.43275103,-2.567917498,48.5821,1.560811585,9.874934113,1.0134375,-1.16192638,1.996876461,80.94732443 +227.88,50.43275117,-2.567916108,48.5723,1.557335383,9.875822202,0.9534375,-1.249844863,2.078349742,80.95484949 +227.89,50.43275131,-2.567914718,48.563,1.560811572,9.876044192,0.8928125,-1.338546522,2.158010585,80.9623746 +227.9,50.43275145,-2.567913328,48.5544,1.574716351,9.87604415,0.83,-1.428012793,2.235789663,80.96989966 +227.91,50.43275159,-2.567911938,48.5464,1.592097329,9.876266141,0.766875,-1.518225055,2.31161908,80.97742477 +227.92,50.43275174,-2.567910548,48.5391,1.592097322,9.877154234,0.705,-1.609164458,2.385432774,80.98494982 +227.93,50.43275188,-2.567909158,48.5323,1.574716337,9.87826436,0.643125,-1.70081198,2.457166288,80.99247494 +227.94,50.43275202,-2.567907767,48.5262,1.560811554,9.878264321,0.5796875,-1.793148483,2.526757112,80.99999999 +227.95,50.43275216,-2.567906377,48.5207,1.557335364,9.877154117,0.515,-1.886154659,2.594144626,81.00752511 +227.96,50.4327523,-2.567904987,48.5159,1.55733537,9.876265947,0.4503125,-1.9798112,2.659269931,81.01505016 +227.97,50.43275244,-2.567903597,48.5117,1.557335373,9.876265911,0.3865625,-2.074098452,2.722076362,81.02257528 +227.98,50.43275258,-2.567902207,48.5082,1.557335374,9.87715401,0.3234375,-2.168996707,2.782509085,81.03010033 +227.99,50.43275272,-2.567900817,48.5052,1.557335367,9.878264143,0.26,-2.264486197,2.840515447,81.03762544 +228,50.43275286,-2.567899426,48.503,1.55733536,9.878486144,0.19625,-2.360546983,2.896044797,81.0451505 +228.01,50.432753,-2.567898036,48.5013,1.557335364,9.878264079,0.131875,-2.457158954,2.949048779,81.05267561 +228.02,50.43275314,-2.567896646,48.5003,1.557335364,9.878486082,0.06625,-2.554301943,2.999481097,81.06020067 +228.03,50.43275328,-2.567895255,48.5,1.557335359,9.878486052,0.000625,-2.651955724,3.047297863,81.06772572 +228.04,50.43275342,-2.567893865,48.5003,1.557335364,9.87826399,-0.0634375,-2.750099899,3.092457365,81.07525084 +228.05,50.43275356,-2.567892475,48.5013,1.553859167,9.878485996,-0.126875,-2.8487139,3.134920127,81.08277589 +228.06,50.4327537,-2.567891084,48.5028,1.539954374,9.878485969,-0.1915625,-2.947777157,3.17464925,81.09030101 +228.07,50.43275384,-2.567889694,48.5051,1.522573403,9.878485944,-0.2565625,-3.047268986,3.211610012,81.09782606 +228.08,50.43275397,-2.567888304,48.508,1.522573419,9.879596086,-0.3196875,-3.147168647,3.245770214,81.10535118 +228.09,50.43275411,-2.567886913,48.5115,1.539954399,9.88070623,-0.3821875,-3.247455226,3.277100062,81.11287623 +228.1,50.43275425,-2.567885522,48.5156,1.553859173,9.880706208,-0.4465625,-3.34810781,3.305572226,81.12040134 +228.11,50.43275439,-2.567884132,48.5204,1.557335367,9.880706187,-0.5115625,-3.449105373,3.331161839,81.1279264 +228.12,50.43275453,-2.567882741,48.5259,1.553859177,9.880928199,-0.575,-3.550426828,3.35384667,81.13545151 +228.13,50.43275467,-2.56788135,48.5319,1.539954402,9.880706146,-0.638125,-3.652050977,3.373606896,81.14297657 +228.14,50.43275481,-2.56787996,48.5386,1.522573429,9.880928161,-0.701875,-3.753956678,3.39042527,81.15050168 +228.15,50.43275494,-2.567878569,48.546,1.522573424,9.881816277,-0.7646875,-3.856122558,3.404287181,81.15802674 +228.16,50.43275508,-2.567877178,48.5539,1.539954396,9.88181626,-0.8265625,-3.958527362,3.415180484,81.16555185 +228.17,50.43275522,-2.567875787,48.5625,1.550382991,9.880928112,-0.8884375,-4.061149604,3.423095667,81.17307691 +228.18,50.43275536,-2.567874397,48.5717,1.539954414,9.880928097,-0.9496875,-4.163967969,3.428025912,81.18060202 +228.19,50.4327555,-2.567873006,48.5815,1.522573437,9.882038251,-1.01,-4.266960914,3.429966806,81.18812708 +228.2,50.43275563,-2.567871615,48.5919,1.522573435,9.882926372,-1.0703125,-4.370106896,3.428916746,81.19565219 +228.21,50.43275577,-2.567870224,48.6029,1.536478213,9.88292636,-1.1315625,-4.473384487,3.424876649,81.20317724 +228.22,50.43275591,-2.567868833,48.6145,1.536478211,9.882260249,-1.193125,-4.576772028,3.417850009,81.21070236 +228.23,50.43275605,-2.567867442,48.6268,1.522573439,9.882038205,-1.2528125,-4.680247977,3.4078429,81.21822741 +228.24,50.43275618,-2.567866052,48.6396,1.519097255,9.883148363,-1.31,-4.783790675,3.394864146,81.22575253 +228.25,50.43275632,-2.56786466,48.653,1.52257345,9.884258523,-1.366875,-4.887378522,3.378924975,81.23327758 +228.26,50.43275646,-2.567863269,48.6669,1.519097251,9.884036483,-1.425,-4.990989918,3.36003937,81.2408027 +228.27,50.43275659,-2.567861878,48.6815,1.519097261,9.883370377,-1.483125,-5.094603204,3.338223773,81.24832775 +228.28,50.43275673,-2.567860487,48.6966,1.522573467,9.883148338,-1.5396875,-5.198196667,3.313497149,81.25585286 +228.29,50.43275687,-2.567859096,48.7123,1.519097273,9.883370367,-1.595,-5.301748819,3.285881156,81.26337792 +228.3,50.432757,-2.567857705,48.7285,1.519097272,9.884258497,-1.6496875,-5.405237888,3.255399801,81.27090303 +228.31,50.43275714,-2.567856314,48.7453,1.522573467,9.885368662,-1.7034375,-5.508642389,3.22207967,81.27842809 +228.32,50.43275728,-2.567854922,48.7626,1.515621083,9.88536866,-1.7565625,-5.611940606,3.185949868,81.2859532 +228.33,50.43275741,-2.567853531,48.7804,1.505192509,9.884480526,-1.81,-5.715111053,3.147041851,81.29347826 +228.34,50.43275755,-2.56785214,48.7988,1.505192516,9.884480526,-1.8628125,-5.818132188,3.105389538,81.30100337 +228.35,50.43275768,-2.567850749,48.8177,1.515621105,9.88536866,-1.913125,-5.92098241,3.061029312,81.30852843 +228.36,50.43275782,-2.567849357,48.8371,1.522573501,9.885590696,-1.961875,-6.023640346,3.013999848,81.31605354 +228.37,50.43275796,-2.567847966,48.8569,1.515621108,9.885368664,-2.0115625,-6.126084455,2.964342111,81.3235786 +228.38,50.43275809,-2.567846575,48.8773,1.505192519,9.885812734,-2.0615625,-6.228293422,2.912099419,81.33110365 +228.39,50.43275823,-2.567845183,48.8982,1.501716335,9.886478838,-2.1096875,-6.330245933,2.85731732,81.33862876 +228.4,50.43275836,-2.567843792,48.9195,1.501716347,9.886478844,-2.1565625,-6.43192056,2.800043656,81.34615382 +228.41,50.4327585,-2.5678424,48.9413,1.501716352,9.885812749,-2.203125,-6.53329616,2.740328219,81.35367893 +228.42,50.43275863,-2.567841009,48.9636,1.501716359,9.885368688,-2.248125,-6.634351591,2.678223261,81.36120399 +228.43,50.43275877,-2.567839618,48.9863,1.501716363,9.885812761,-2.2915625,-6.735065654,2.613782812,81.3687291 +228.44,50.4327589,-2.567838226,49.0094,1.501716359,9.886700902,-2.335,-6.835417436,2.54706308,81.37625416 +228.45,50.43275904,-2.567836835,49.033,1.501716363,9.887589045,-2.378125,-6.935385851,2.478122334,81.38377927 +228.46,50.43275917,-2.567835443,49.057,1.498240177,9.888033121,-2.419375,-7.03495016,2.407020564,81.39130433 +228.47,50.43275931,-2.567834051,49.0814,1.4878116,9.887589064,-2.4584375,-7.134089448,2.333819877,81.39882944 +228.48,50.43275944,-2.56783266,49.1062,1.480859219,9.886922975,-2.4965625,-7.232783033,2.258584044,81.4063545 +228.49,50.43275957,-2.567831268,49.1313,1.487811616,9.886922986,-2.5346875,-7.331010344,2.181378726,81.41387961 +228.5,50.43275971,-2.567829877,49.1569,1.498240205,9.88781113,-2.5715625,-7.42875087,2.102271188,81.42140466 +228.51,50.43275984,-2.567828485,49.1828,1.498240207,9.889143342,-2.60625,-7.525984215,2.021330472,81.42892978 +228.52,50.43275998,-2.567827093,49.209,1.487811621,9.889809455,-2.6403125,-7.622689979,1.938627051,81.43645483 +228.53,50.43276011,-2.567825701,49.2356,1.480859238,9.889143368,-2.6746875,-7.718848054,1.854233175,81.44397995 +228.54,50.43276024,-2.567824309,49.2625,1.487811645,9.888033215,-2.708125,-7.814438327,1.768222355,81.451505 +228.55,50.43276038,-2.567822918,49.2898,1.498240241,9.888033229,-2.7396875,-7.90944086,1.680669648,81.45903012 +228.56,50.43276051,-2.567821526,49.3173,1.498240245,9.88914341,-2.7696875,-8.003835771,1.591651373,81.46655517 +228.57,50.43276065,-2.567820134,49.3452,1.484335471,9.890031559,-2.798125,-8.097603409,1.501245107,81.47408028 +228.58,50.43276078,-2.567818742,49.3733,1.466954498,9.890253609,-2.8246875,-8.190724119,1.409529805,81.48160534 +228.59,50.43276091,-2.56781735,49.4017,1.4669545,9.890253626,-2.85,-8.28317848,1.316585279,81.48913045 +228.6,50.43276104,-2.567815958,49.4303,1.480859286,9.890253642,-2.875,-8.374947182,1.222492717,81.49665551 +228.61,50.43276118,-2.567814566,49.4592,1.484335484,9.890253659,-2.8996875,-8.466011088,1.127334168,81.50418062 +228.62,50.43276131,-2.567813174,49.4883,1.480859297,9.890253676,-2.923125,-8.556351177,1.031192537,81.51170568 +228.63,50.43276144,-2.567811782,49.5177,1.484335509,9.890253694,-2.9446875,-8.645948541,0.93415165,81.51923079 +228.64,50.43276158,-2.56781039,49.5472,1.480859322,9.890253712,-2.9646875,-8.734784501,0.836296188,81.52675585 +228.65,50.43276171,-2.567808998,49.577,1.463478347,9.890475763,-2.9834375,-8.822840494,0.737711465,81.53428096 +228.66,50.43276184,-2.567807606,49.6069,1.453049768,9.891363915,-3.00125,-8.910098185,0.638483483,81.54180602 +228.67,50.43276197,-2.567806214,49.637,1.463478363,9.892474102,-3.018125,-8.996539239,0.538698701,81.54933113 +228.68,50.4327621,-2.567804821,49.6673,1.480859348,9.892474121,-3.0328125,-9.082145722,0.438444207,81.55685618 +228.69,50.43276224,-2.567803429,49.6977,1.480859357,9.891363974,-3.045,-9.166899645,0.337807322,81.5643813 +228.7,50.43276237,-2.567802037,49.7282,1.463478384,9.890697893,-3.0565625,-9.250783416,0.236875879,81.57190635 +228.71,50.4327625,-2.567800645,49.7588,1.449573605,9.891364013,-3.068125,-9.333779447,0.135737884,81.57943147 +228.72,50.43276263,-2.567799253,49.7896,1.449573612,9.892696234,-3.078125,-9.415870376,0.034481517,81.58695652 +228.73,50.43276276,-2.56779786,49.8204,1.463478397,9.893584388,-3.08625,-9.497039187,-0.066804874,81.59448158 +228.74,50.43276289,-2.567796468,49.8513,1.480859378,9.893584408,-3.0934375,-9.577268805,-0.168033051,81.60200669 +228.75,50.43276303,-2.567795075,49.8823,1.480859391,9.892918328,-3.0996875,-9.656542501,-0.269114724,81.60953175 +228.76,50.43276316,-2.567793683,49.9133,1.463478424,9.892474282,-3.1046875,-9.734843773,-0.369961656,81.61705686 +228.77,50.43276329,-2.567792291,49.9444,1.449573647,9.892918369,-3.108125,-9.812156234,-0.470486012,81.62458192 +228.78,50.43276342,-2.567790898,49.9755,1.44609746,9.893806524,-3.1096875,-9.888463727,-0.570600131,81.63210703 +228.79,50.43276355,-2.567789506,50.0066,1.446097467,9.894694679,-3.1096875,-9.963750324,-0.670216636,81.63963208 +228.8,50.43276368,-2.567788113,50.0377,1.446097472,9.895138767,-3.108125,-10.03800027,-0.769248724,81.6471572 +228.81,50.43276381,-2.56778672,50.0688,1.446097484,9.894694721,-3.105,-10.11119815,-0.867609993,81.65468225 +228.82,50.43276394,-2.567785328,50.0998,1.446097497,9.894028641,-3.1015625,-10.18332861,-0.965214728,81.66220737 +228.83,50.43276407,-2.567783935,50.1308,1.446097504,9.893806629,-3.098125,-10.25437658,-1.061977732,81.66973242 +228.84,50.4327642,-2.567782543,50.1618,1.446097505,9.89380665,-3.0928125,-10.32432722,-1.15781472,81.67725754 +228.85,50.43276433,-2.56778115,50.1927,1.446097507,9.894028704,-3.0846875,-10.39316598,-1.252642043,81.68478259 +228.86,50.43276446,-2.567779758,50.2235,1.446097517,9.894916858,-3.0746875,-10.46087847,-1.346377079,81.6923077 +228.87,50.43276459,-2.567778365,50.2542,1.446097524,9.896027045,-3.0634375,-10.5274505,-1.43893801,81.69983276 +228.88,50.43276472,-2.567776972,50.2848,1.446097528,9.896027065,-3.0515625,-10.59286818,-1.53024422,81.70735787 +228.89,50.43276485,-2.567775579,50.3152,1.446097538,9.895138952,-3.0396875,-10.65711784,-1.620215955,81.71488293 +228.9,50.43276498,-2.567774187,50.3456,1.446097544,9.895138972,-3.0265625,-10.72018611,-1.70877489,81.72240804 +228.91,50.43276511,-2.567772794,50.3758,1.446097549,9.896027125,-3.0109375,-10.78205982,-1.795843791,81.7299331 +228.92,50.43276524,-2.567771401,50.4058,1.446097558,9.896027144,-2.9934375,-10.84272597,-1.881346626,81.73745821 +228.93,50.43276537,-2.567770008,50.4357,1.442621369,9.89513903,-2.9746875,-10.902172,-1.965208912,81.74498327 +228.94,50.4327655,-2.567768616,50.4653,1.428716587,9.895361082,-2.955,-10.96038537,-2.04735748,81.75250838 +228.95,50.43276563,-2.567767223,50.4948,1.411335616,9.897359402,-2.935,-11.01735405,-2.12772077,81.76003344 +228.96,50.43276575,-2.56776583,50.524,1.411335629,9.899135688,-2.914375,-11.07306606,-2.20622865,81.76755855 +228.97,50.43276588,-2.567764436,50.5531,1.428716618,9.898469606,-2.8915625,-11.12750977,-2.282812653,81.7750836 +228.98,50.43276601,-2.567763043,50.5819,1.442621404,9.896471323,-2.86625,-11.18067383,-2.357406028,81.78260872 +228.99,50.43276614,-2.567761651,50.6104,1.442621406,9.89647134,-2.84,-11.23254714,-2.429943688,81.79013377 +229,50.43276627,-2.567760258,50.6387,1.428716628,9.898469657,-2.813125,-11.28311892,-2.500362379,81.79765889 +229.01,50.4327664,-2.567758864,50.6667,1.411335652,9.899357807,-2.7846875,-11.33237851,-2.568600735,81.80518394 +229.02,50.43276652,-2.567757471,50.6944,1.411335656,9.89846969,-2.755,-11.38031565,-2.634599285,81.81270906 +229.03,50.43276665,-2.567756078,50.7218,1.428716647,9.897581573,-2.7246875,-11.42692032,-2.698300332,81.82023411 +229.04,50.43276678,-2.567754685,50.7489,1.439145243,9.897581588,-2.6934375,-11.47218284,-2.75964847,81.82775922 +229.05,50.43276691,-2.567753292,50.7757,1.428716657,9.898469736,-2.66125,-11.5160937,-2.818590185,81.83528428 +229.06,50.43276704,-2.567751899,50.8021,1.411335684,9.899579918,-2.628125,-11.55864378,-2.875074026,81.84280934 +229.07,50.43276716,-2.567750505,50.8283,1.4078595,9.899579931,-2.593125,-11.5998242,-2.929050719,81.85033445 +229.08,50.43276729,-2.567749112,50.854,1.411335703,9.898691811,-2.55625,-11.63962632,-2.98047328,81.85785951 +229.09,50.43276742,-2.567747719,50.8794,1.407859505,9.898691824,-2.5184375,-11.67804182,-3.02929679,81.86538462 +229.1,50.43276754,-2.567746326,50.9044,1.411335703,9.899802003,-2.4796875,-11.71506269,-3.075478735,81.87290967 +229.11,50.43276767,-2.567744932,50.929,1.425240497,9.900690148,-2.44,-11.75068124,-3.118978837,81.88043479 +229.12,50.4327678,-2.567743539,50.9532,1.425240503,9.900690159,-2.4,-11.78488997,-3.159759108,81.88795984 +229.13,50.43276793,-2.567742145,50.977,1.411335719,9.900024069,-2.3596875,-11.81768172,-3.197784025,81.89548496 +229.14,50.43276805,-2.567740752,51.0004,1.407859534,9.899580012,-2.318125,-11.84904973,-3.233020471,81.90301001 +229.15,50.43276818,-2.567739359,51.0234,1.411335749,9.900024088,-2.2746875,-11.8789874,-3.265437621,81.91053512 +229.16,50.43276831,-2.567737965,51.0459,1.404383365,9.900690197,-2.2296875,-11.9074885,-3.295007285,81.91806018 +229.17,50.43276843,-2.567736572,51.068,1.393954768,9.900912238,-2.1834375,-11.93454706,-3.321703623,81.92558529 +229.18,50.43276856,-2.567735178,51.0896,1.393954762,9.900912245,-2.1365625,-11.96015742,-3.345503431,81.93311035 +229.19,50.43276868,-2.567733785,51.1107,1.404383357,9.900912252,-2.0896875,-11.98431424,-3.366385851,81.94063546 +229.2,50.43276881,-2.567732391,51.1314,1.411335755,9.900912257,-2.0415625,-12.00701247,-3.38433278,81.94816052 +229.21,50.43276894,-2.567730998,51.1516,1.404383364,9.900912262,-1.9915625,-12.02824732,-3.399328518,81.95568563 +229.22,50.43276906,-2.567729604,51.1712,1.393954782,9.9011343,-1.9415625,-12.04801448,-3.411360002,81.96321069 +229.23,50.43276919,-2.567728211,51.1904,1.390478596,9.901800404,-1.8915625,-12.06630977,-3.420416688,81.9707358 +229.24,50.43276931,-2.567726817,51.2091,1.3904786,9.902244473,-1.8396875,-12.08312929,-3.426490728,81.97826086 +229.25,50.43276944,-2.567725423,51.2272,1.3904786,9.902022442,-1.786875,-12.0984696,-3.429576851,81.98578597 +229.26,50.43276956,-2.56772403,51.2448,1.390478606,9.902244476,-1.735,-12.1123275,-3.429672306,81.99331103 +229.27,50.43276969,-2.567722636,51.2619,1.390478617,9.903354643,-1.6828125,-12.12470013,-3.426777035,82.00083614 +229.28,50.43276981,-2.567721242,51.2785,1.390478616,9.904242776,-1.628125,-12.13558478,-3.420893561,82.00836119 +229.29,50.43276994,-2.567719848,51.2945,1.39047861,9.904242775,-1.5715625,-12.14497928,-3.412027039,82.01588631 +229.3,50.43277006,-2.567718454,51.3099,1.390478614,9.90335464,-1.515,-12.15288168,-3.400185147,82.02341136 +229.31,50.43277019,-2.56771706,51.3248,1.390478617,9.90224447,-1.458125,-12.15929027,-3.385378314,82.03093648 +229.32,50.43277031,-2.567715667,51.3391,1.390478618,9.902244466,-1.4,-12.16420373,-3.367619315,82.03846153 +229.33,50.43277044,-2.567714273,51.3528,1.390478625,9.903354628,-1.341875,-12.16762102,-3.346923678,82.04598664 +229.34,50.43277056,-2.567712879,51.3659,1.387002438,9.904242756,-1.2846875,-12.16954146,-3.323309567,82.0535117 +229.35,50.43277069,-2.567711485,51.3785,1.37657385,9.904464783,-1.2265625,-12.16996459,-3.296797377,82.06103681 +229.36,50.43277081,-2.567710091,51.3905,1.369621454,9.904464775,-1.1665625,-12.16889041,-3.267410372,82.06856187 +229.37,50.43277093,-2.567708697,51.4018,1.376573853,9.904464767,-1.1065625,-12.16631909,-3.235174162,82.07608698 +229.38,50.43277106,-2.567707303,51.4126,1.387002455,9.904464759,-1.0465625,-12.16225121,-3.200116822,82.08361204 +229.39,50.43277118,-2.567705909,51.4228,1.387002459,9.904464748,-0.9846875,-12.15668756,-3.162268949,82.09113715 +229.4,50.43277131,-2.567704515,51.4323,1.376573864,9.90468677,-0.921875,-12.14962929,-3.121663488,82.09866221 +229.41,50.43277143,-2.567703121,51.4412,1.369621463,9.905574891,-0.8603125,-12.14107795,-3.078335904,82.10618726 +229.42,50.43277155,-2.567701727,51.4495,1.373097657,9.906685046,-0.7996875,-12.13103532,-3.032323955,82.11371238 +229.43,50.43277168,-2.567700332,51.4572,1.369621469,9.906685032,-0.738125,-12.1195034,-2.983667806,82.12123743 +229.44,50.4327718,-2.567698938,51.4643,1.355716696,9.905574851,-0.675,-12.10648471,-2.932409856,82.12876255 +229.45,50.43277192,-2.567697544,51.4707,1.355716701,9.904686702,-0.6115625,-12.09198189,-2.878594738,82.1362876 +229.46,50.43277204,-2.56769615,51.4765,1.36962148,9.904686685,-0.5484375,-12.07599802,-2.822269491,82.14381271 +229.47,50.43277217,-2.567694756,51.4817,1.36962147,9.905796834,-0.4846875,-12.05853639,-2.763483162,82.15133777 +229.48,50.43277229,-2.567693362,51.4862,1.355716683,9.907795116,-0.42,-12.03960071,-2.702287087,82.15886288 +229.49,50.43277241,-2.567691967,51.4901,1.355716684,9.908905263,-0.3553125,-12.01919487,-2.638734551,82.16638794 +229.5,50.43277253,-2.567690572,51.4933,1.369621472,9.907795076,-0.2915625,-11.99732318,-2.572880959,82.17391305 +229.51,50.43277266,-2.567689178,51.4959,1.369621484,9.906018787,-0.2284375,-11.97399017,-2.504783837,82.18143811 +229.52,50.43277278,-2.567687784,51.4979,1.355716707,9.905796732,-0.1646875,-11.94920075,-2.434502484,82.18896322 +229.53,50.4327729,-2.56768639,51.4992,1.355716703,9.906906875,-0.1,-11.92296008,-2.362098152,82.19648828 +229.54,50.43277302,-2.567684995,51.4999,1.369621478,9.908017017,-0.0353125,-11.89527361,-2.287634093,82.20401339 +229.55,50.43277315,-2.567683601,51.4999,1.369621472,9.908905125,0.0284375,-11.86614719,-2.211175167,82.21153845 +229.56,50.43277327,-2.567682206,51.4993,1.352240491,9.909127132,0.091875,-11.83558688,-2.132788066,82.21906356 +229.57,50.43277339,-2.567680811,51.4981,1.338335711,9.908016938,0.156875,-11.80359899,-2.052541144,82.22658861 +229.58,50.43277351,-2.567679417,51.4962,1.334859521,9.907128776,0.223125,-11.77019028,-1.970504417,82.23411373 +229.59,50.43277363,-2.567678023,51.4936,1.338335715,9.90801688,0.288125,-11.73536768,-1.886749332,82.24163878 +229.6,50.43277375,-2.567676628,51.4904,1.352240493,9.909127017,0.3515625,-11.69913853,-1.801348998,82.2491639 +229.61,50.43277387,-2.567675233,51.4866,1.369621476,9.909126986,0.415,-11.66151033,-1.714377844,82.25668895 +229.62,50.432774,-2.567673839,51.4821,1.369621481,9.909126954,0.4784375,-11.62249093,-1.625911728,82.26421407 +229.63,50.43277412,-2.567672444,51.477,1.352240502,9.909348953,0.5415625,-11.58208852,-1.536027771,82.27173912 +229.64,50.43277424,-2.567671049,51.4713,1.33833571,9.909126885,0.605,-11.54031154,-1.44480441,82.27926423 +229.65,50.43277436,-2.567669655,51.4649,1.334859503,9.90912685,0.6684375,-11.49716873,-1.352321172,82.28678929 +229.66,50.43277448,-2.56766826,51.4579,1.3348595,9.909348848,0.7315625,-11.45266899,-1.258658616,82.2943144 +229.67,50.4327746,-2.567666865,51.4503,1.334859505,9.909126778,0.795,-11.40682177,-1.163898558,82.30183946 +229.68,50.43277472,-2.567665471,51.442,1.33485951,9.909348774,0.858125,-11.35963651,-1.068123563,82.30936457 +229.69,50.43277484,-2.567664076,51.4331,1.334859506,9.910458902,0.9196875,-11.31112315,-0.971417111,82.31688963 +229.7,50.43277496,-2.567662681,51.4236,1.334859495,9.911346995,0.98,-11.2612918,-0.873863598,82.32441474 +229.71,50.43277508,-2.567661286,51.4135,1.33485949,9.911568988,1.04,-11.21015286,-0.775548051,82.3319398 +229.72,50.4327752,-2.567659891,51.4028,1.334859495,9.911568946,1.1,-11.15771696,-0.676556185,82.33946491 +229.73,50.43277532,-2.567658496,51.3915,1.334859499,9.91134687,1.16,-11.10399518,-0.576974401,82.34698997 +229.74,50.43277544,-2.567657101,51.3796,1.334859494,9.910680726,1.22,-11.04899862,-0.476889446,82.35451508 +229.75,50.43277556,-2.567655706,51.3671,1.334859483,9.910458648,1.2796875,-10.99273881,-0.376388695,82.36204013 +229.76,50.43277568,-2.567654312,51.354,1.334859478,9.91156877,1.338125,-10.93522748,-0.275559697,82.36956519 +229.77,50.4327758,-2.567652916,51.3403,1.331383285,9.912456857,1.395,-10.87647662,-0.1744904,82.3770903 +229.78,50.43277592,-2.567651521,51.3261,1.317478501,9.911568677,1.451875,-10.81649859,-0.073268926,82.38461536 +229.79,50.43277604,-2.567650126,51.3113,1.300097511,9.910680497,1.5096875,-10.75530584,0.028016433,82.39214047 +229.8,50.43277615,-2.567648732,51.2959,1.300097499,9.911568582,1.5665625,-10.69291114,0.129277327,82.39966553 +229.81,50.43277627,-2.567647336,51.2799,1.317478478,9.912678699,1.6215625,-10.62932761,0.23042552,82.40719064 +229.82,50.43277639,-2.567645941,51.2635,1.331383269,9.912456615,1.6765625,-10.56456842,0.331372776,82.4147157 +229.83,50.43277651,-2.567644546,51.2464,1.334859469,9.911790463,1.7315625,-10.49864716,0.432031033,82.42224081 +229.84,50.43277663,-2.567643151,51.2288,1.331383266,9.911790411,1.784375,-10.43157758,0.53231257,82.42976587 +229.85,50.43277675,-2.567641756,51.2107,1.317478469,9.912678492,1.835,-10.36337366,0.632129954,82.43729098 +229.86,50.43277687,-2.567640361,51.1921,1.300097485,9.913788605,1.8853125,-10.29404966,0.731396095,82.44481603 +229.87,50.43277698,-2.567638965,51.173,1.30009749,9.914010584,1.9365625,-10.22362009,0.83002442,82.45234115 +229.88,50.4327771,-2.56763757,51.1534,1.317478468,9.913788495,1.988125,-10.15209966,0.927928984,82.4598662 +229.89,50.43277722,-2.567636175,51.1332,1.327907047,9.914010473,2.038125,-10.07950327,1.025024418,82.46739132 +229.9,50.43277734,-2.567634779,51.1126,1.317478451,9.914010417,2.08625,-10.00584605,1.121225922,82.47491637 +229.91,50.43277746,-2.567633384,51.0915,1.300097462,9.913788326,2.1334375,-9.931143468,1.216449789,82.48244149 +229.92,50.43277757,-2.567631989,51.0699,1.300097458,9.914010301,2.1796875,-9.855411052,1.310612824,82.48996654 +229.93,50.43277769,-2.567630593,51.0479,1.314002243,9.914010242,2.2246875,-9.778664616,1.403633038,82.49749165 +229.94,50.43277781,-2.567629198,51.0254,1.314002245,9.913788149,2.2684375,-9.700920259,1.495429242,82.50501671 +229.95,50.43277793,-2.567627803,51.0025,1.300097457,9.914232156,2.3115625,-9.622194197,1.585921394,82.51254182 +229.96,50.43277804,-2.567626407,50.9792,1.296621254,9.915120229,2.355,-9.542502815,1.675030598,82.52006688 +229.97,50.43277816,-2.567625012,50.9554,1.300097443,9.916008301,2.3978125,-9.461862787,1.76267916,82.52759199 +229.98,50.43277828,-2.567623616,50.9312,1.296621237,9.916452306,2.438125,-9.380290957,1.848790649,82.53511705 +229.99,50.43277839,-2.56762222,50.9066,1.296621226,9.916008176,2.4765625,-9.297804401,1.933289949,82.54264216 +230,50.43277851,-2.567620825,50.8817,1.300097422,9.915342014,2.515,-9.214420249,2.016103435,82.55016722 +230.01,50.43277863,-2.567619429,50.8563,1.293145032,9.91534195,2.553125,-9.130155976,2.0971588,82.55769233 +230.02,50.43277874,-2.567618034,50.8306,1.282716433,9.916230019,2.589375,-9.04502923,2.176385399,82.56521739 +230.03,50.43277886,-2.567616638,50.8045,1.282716414,9.917340121,2.6234375,-8.959057658,2.253714189,82.5727425 +230.04,50.43277897,-2.567615242,50.7781,1.293144994,9.917340056,2.6565625,-8.872259307,2.329077734,82.58026755 +230.05,50.43277909,-2.567613846,50.7514,1.300097393,9.916451857,2.69,-8.784652341,2.402410259,82.58779267 +230.06,50.43277921,-2.567612451,50.7243,1.293145006,9.916229757,2.723125,-8.696254923,2.47364782,82.59531772 +230.07,50.43277932,-2.567611055,50.6969,1.28271641,9.916451724,2.754375,-8.607085616,2.542728368,82.60284284 +230.08,50.43277944,-2.567609659,50.6692,1.279240208,9.916229624,2.783125,-8.517163041,2.609591568,82.61036789 +230.09,50.43277955,-2.567608264,50.6412,1.279240203,9.91645159,2.81,-8.426505935,2.67417921,82.61789301 +230.1,50.43277967,-2.567606868,50.613,1.279240188,9.917339655,2.8365625,-8.335133204,2.736434913,82.62541806 +230.11,50.43277978,-2.567605472,50.5845,1.279240178,9.91756162,2.863125,-8.243064043,2.796304419,82.63294312 +230.12,50.4327799,-2.567604076,50.5557,1.279240179,9.917339518,2.888125,-8.150317588,2.853735474,82.64046823 +230.13,50.43278001,-2.567602681,50.5267,1.279240177,9.917561482,2.91125,-8.056913206,2.908678058,82.64799329 +230.14,50.43278013,-2.567601284,50.4975,1.279240174,9.917561412,2.9334375,-7.962870435,2.961084216,82.6555184 +230.15,50.43278024,-2.567599889,50.468,1.27924017,9.917339309,2.9546875,-7.868208926,3.010908282,82.66304345 +230.16,50.43278036,-2.567598493,50.4384,1.27924016,9.917783306,2.9746875,-7.77294839,3.058106769,82.67056857 +230.17,50.43278047,-2.567597097,50.4085,1.279240147,9.918449336,2.993125,-7.677108823,3.102638539,82.67809362 +230.18,50.43278059,-2.567595701,50.3785,1.279240139,9.918671299,3.0096875,-7.580710107,3.144464802,82.68561874 +230.19,50.4327807,-2.567594305,50.3483,1.275763939,9.918671228,3.0246875,-7.483772466,3.183549003,82.69314379 +230.2,50.43278082,-2.567592909,50.318,1.26533535,9.918671157,3.038125,-7.386316126,3.219857109,82.70066891 +230.21,50.43278093,-2.567591513,50.2875,1.258382956,9.91889312,3.05,-7.288361428,3.253357493,82.70819396 +230.22,50.43278104,-2.567590117,50.257,1.26533534,9.919781182,3.0615625,-7.189928883,3.284020877,82.71571907 +230.23,50.43278116,-2.567588721,50.2263,1.275763921,9.920891276,3.073125,-7.091038946,3.311820502,82.72324413 +230.24,50.43278127,-2.567587324,50.1955,1.275763911,9.920891204,3.083125,-6.991712301,3.336732192,82.73076924 +230.25,50.43278139,-2.567585928,50.1646,1.265335309,9.919780965,3.09125,-6.891969745,3.358734229,82.7382943 +230.26,50.4327815,-2.567584532,50.1337,1.258382915,9.919114794,3.098125,-6.791832078,3.377807421,82.74581941 +230.27,50.43278161,-2.567583136,50.1026,1.261859114,9.919780823,3.103125,-6.691320212,3.393935037,82.75334447 +230.28,50.43278173,-2.56758174,50.0716,1.261859108,9.920890918,3.10625,-6.590455174,3.407103154,82.76086958 +230.29,50.43278184,-2.567580343,50.0405,1.258382905,9.921112879,3.1084375,-6.489257936,3.417300199,82.76839464 +230.3,50.43278195,-2.567578947,50.0094,1.261859097,9.920890773,3.109375,-6.387749697,3.42451729,82.77591975 +230.31,50.43278207,-2.567577551,49.9783,1.258382893,9.921112734,3.1084375,-6.285951655,3.428748182,82.78344481 +230.32,50.43278218,-2.567576154,49.9472,1.244478102,9.920890629,3.1065625,-6.183885011,3.429989151,82.79096992 +230.33,50.43278229,-2.567574758,49.9162,1.244478098,9.920002425,3.1046875,-6.081571192,3.428239109,82.79849497 +230.34,50.4327824,-2.567573362,49.8851,1.258382872,9.920002354,3.10125,-5.979031457,3.423499602,82.80602009 +230.35,50.43278252,-2.567571966,49.8541,1.258382862,9.921112449,3.0946875,-5.87628729,3.415774756,82.81354514 +230.36,50.43278263,-2.567570569,49.8232,1.244478076,9.92200051,3.0865625,-5.77336012,3.405071332,82.82107026 +230.37,50.43278274,-2.567569173,49.7924,1.244478074,9.922222471,3.0784375,-5.670271434,3.391398553,82.82859531 +230.38,50.43278285,-2.567567776,49.7616,1.25838285,9.9222224,3.0696875,-5.567042774,3.37476851,82.83612043 +230.39,50.43278297,-2.56756638,49.731,1.258382842,9.92222233,3.059375,-5.463695683,3.355195585,82.84364548 +230.4,50.43278308,-2.567564983,49.7004,1.241001852,9.922444292,3.046875,-5.360251763,3.33269685,82.85117059 +230.41,50.43278319,-2.567563587,49.67,1.227097055,9.923110321,3.0328125,-5.256732613,3.307291958,82.85869565 +230.42,50.4327833,-2.56756219,49.6398,1.227097053,9.923554317,3.0184375,-5.153159835,3.279003084,82.86622076 +230.43,50.43278341,-2.567560793,49.6096,1.24100184,9.923110181,3.0028125,-5.049555085,3.247854864,82.87374582 +230.44,50.43278352,-2.567559397,49.5797,1.258382814,9.922444011,2.9846875,-4.945939965,3.213874456,82.88127087 +230.45,50.43278364,-2.567558,49.5499,1.258382811,9.922443942,2.965,-4.84233619,3.177091539,82.88879599 +230.46,50.43278375,-2.567556604,49.5204,1.241001834,9.923109972,2.945,-4.738765302,3.137538086,82.89632104 +230.47,50.43278386,-2.567555207,49.491,1.227097045,9.923553969,2.9246875,-4.63524896,3.095248701,82.90384616 +230.48,50.43278397,-2.56755381,49.4619,1.223620834,9.923331867,2.9028125,-4.531808821,3.050260227,82.91137121 +230.49,50.43278408,-2.567552414,49.4329,1.223620827,9.923553833,2.8784375,-4.428466429,3.002611853,82.91889633 +230.5,50.43278419,-2.567551017,49.4043,1.223620821,9.924441899,2.8528125,-4.325243384,2.952345177,82.92642138 +230.51,50.4327843,-2.56754962,49.3759,1.223620807,9.924441832,2.826875,-4.222161287,2.899503973,82.93394649 +230.52,50.43278441,-2.567548223,49.3477,1.223620799,9.923553632,2.7996875,-4.119241623,2.844134363,82.94147155 +230.53,50.43278452,-2.567546827,49.3199,1.223620807,9.923553566,2.77125,-4.016505878,2.786284648,82.94899666 +230.54,50.43278463,-2.56754543,49.2923,1.223620809,9.924663666,2.741875,-3.913975539,2.726005248,82.95652172 +230.55,50.43278474,-2.567544033,49.265,1.223620797,9.9253297,2.7109375,-3.811671977,2.663348761,82.96404683 +230.56,50.43278485,-2.567542636,49.2381,1.223620792,9.924663536,2.6784375,-3.70961662,2.598369732,82.97157189 +230.57,50.43278496,-2.567541239,49.2114,1.223620795,9.923775339,2.645,-3.607830725,2.531124941,82.979097 +230.58,50.43278507,-2.567539843,49.1852,1.22362079,9.924663408,2.61125,-3.506335548,2.461672945,82.98662206 +230.59,50.43278518,-2.567538446,49.1592,1.223620777,9.926661644,2.5765625,-3.405152348,2.390074306,82.99414717 +230.6,50.43278529,-2.567537048,49.1336,1.223620769,9.926661581,2.539375,-3.304302207,2.316391532,83.00167223 +230.61,50.4327854,-2.567535651,49.1084,1.223620765,9.924885253,2.5,-3.203806155,2.240688796,83.00919734 +230.62,50.43278551,-2.567534255,49.0836,1.223620751,9.924885192,2.46,-3.103685218,2.163032159,83.01672239 +230.63,50.43278562,-2.567532858,49.0592,1.223620744,9.926661396,2.42,-3.003960309,2.083489345,83.02424751 +230.64,50.43278573,-2.56753146,49.0352,1.223620753,9.926883369,2.38,-2.904652285,2.002129682,83.03177256 +230.65,50.43278584,-2.567530063,49.0116,1.220144559,9.925773143,2.3396875,-2.805781829,1.919024159,83.03929768 +230.66,50.43278595,-2.567528667,48.9884,1.206239766,9.925995118,2.2978125,-2.707369566,1.834245198,83.04682273 +230.67,50.43278606,-2.567527269,48.9656,1.188858783,9.926883193,2.253125,-2.609436125,1.747866711,83.05434785 +230.68,50.43278616,-2.567525872,48.9433,1.188858788,9.926883136,2.2065625,-2.512001902,1.659964099,83.0618729 +230.69,50.43278627,-2.567524475,48.9215,1.206239762,9.92688308,2.16,-2.415087294,1.570613967,83.06939801 +230.7,50.43278638,-2.567523078,48.9001,1.220144531,9.927105057,2.1134375,-2.31871247,1.479894236,83.07692307 +230.71,50.43278649,-2.56752168,48.8792,1.220144528,9.926882968,2.06625,-2.222897654,1.387884032,83.08444818 +230.72,50.4327866,-2.567520284,48.8588,1.206239748,9.926882914,2.018125,-2.127662787,1.294663513,83.09197324 +230.73,50.43278671,-2.567518886,48.8388,1.18885876,9.927326926,1.968125,-2.033027749,1.200314094,83.09949835 +230.74,50.43278681,-2.567517489,48.8194,1.188858743,9.92777094,1.9165625,-1.939012307,1.104917939,83.10702341 +230.75,50.43278692,-2.567516092,48.8005,1.202763526,9.928436988,1.8653125,-1.845636172,1.008558298,83.11454852 +230.76,50.43278703,-2.567514694,48.7821,1.202763538,9.929103036,1.8146875,-1.752918709,0.911319224,83.12207358 +230.77,50.43278714,-2.567513297,48.7642,1.188858755,9.929102986,1.763125,-1.6608794,0.813285401,83.12959869 +230.78,50.43278724,-2.567511899,48.7468,1.188858743,9.928214804,1.7096875,-1.569537436,0.71454237,83.13712375 +230.79,50.43278735,-2.567510502,48.73,1.202763522,9.92710459,1.655,-1.4789119,0.615176305,83.1446488 +230.8,50.43278746,-2.567509105,48.7137,1.202763527,9.927326575,1.6,-1.38902164,0.515273779,83.15217391 +230.81,50.43278757,-2.567507708,48.698,1.188858742,9.929102794,1.5446875,-1.299885507,0.414921883,83.15969897 +230.82,50.43278767,-2.56750631,48.6828,1.185382535,9.930434947,1.488125,-1.211522123,0.314208221,83.16722408 +230.83,50.43278778,-2.567504912,48.6682,1.188858728,9.930212869,1.43,-1.123949878,0.213220571,83.17474914 +230.84,50.43278789,-2.567503515,48.6542,1.185382539,9.929546725,1.371875,-1.037187108,0.112046939,83.18227425 +230.85,50.43278799,-2.567502117,48.6408,1.185382536,9.929324648,1.3146875,-0.951251919,0.010775617,83.18979931 +230.86,50.4327881,-2.56750072,48.6279,1.188858721,9.929102573,1.2565625,-0.8661623,-0.090505044,83.19732442 +230.87,50.43278821,-2.567499322,48.6156,1.181906327,9.928436432,1.1965625,-0.7819359,-0.191706865,83.20484948 +230.88,50.43278831,-2.567497925,48.604,1.171477748,9.928214359,1.136875,-0.698590423,-0.292741441,83.21237459 +230.89,50.43278842,-2.567496528,48.5929,1.171477744,9.929324486,1.078125,-0.616143286,-0.393520821,83.21989965 +230.9,50.43278852,-2.56749513,48.5824,1.181906312,9.930434613,1.0178125,-0.534611621,-0.493956999,83.22742476 +230.91,50.43278863,-2.567493732,48.5725,1.188858697,9.930434576,0.955,-0.454012502,-0.593962428,83.23494981 +230.92,50.43278874,-2.567492335,48.5633,1.181906318,9.930656573,0.891875,-0.374362717,-0.693449903,83.24247493 +230.93,50.43278884,-2.567490937,48.5547,1.171477737,9.931544669,0.8303125,-0.295678995,-0.792332735,83.24999998 +230.94,50.43278895,-2.567489539,48.5467,1.168001533,9.931544635,0.7696875,-0.217977668,-0.890524638,83.2575251 +230.95,50.43278905,-2.567488141,48.5393,1.168001532,9.930656468,0.708125,-0.141275063,-0.987939953,83.26505015 +230.96,50.43278916,-2.567486744,48.5325,1.168001542,9.930656436,0.645,-0.065587109,-1.08449377,83.27257527 +230.97,50.43278926,-2.567485346,48.5264,1.168001547,9.931766571,0.5815625,0.00907038,-1.180101919,83.28010032 +230.98,50.43278937,-2.567483948,48.5209,1.16800154,9.932654673,0.518125,0.082681763,-1.274680979,83.28762543 +230.99,50.43278947,-2.56748255,48.516,1.168001528,9.932654644,0.4534375,0.155231742,-1.368148501,83.29515049 +231,50.43278958,-2.567481152,48.5118,1.168001527,9.931766483,0.3884375,0.226705076,-1.460422953,83.3026756 +231.01,50.43278968,-2.567479754,48.5083,1.168001535,9.930656289,0.325,0.297086867,-1.551423949,83.31020066 +231.02,50.43278979,-2.567478357,48.5053,1.168001535,9.930656262,0.2615625,0.36636245,-1.641072019,83.31772577 +231.03,50.43278989,-2.567476959,48.503,1.168001525,9.931766402,0.1965625,0.434517326,-1.729289128,83.32525083 +231.04,50.43279,-2.567475561,48.5014,1.168001525,9.93265451,0.131875,0.501537288,-1.815998211,83.33277594 +231.05,50.4327901,-2.567474163,48.5004,1.164525341,9.93287652,0.0684375,0.567408298,-1.901123754,83.340301 +231.06,50.43279021,-2.567472765,48.5,1.154096761,9.932876499,0.0046875,0.632116662,-1.984591444,83.34782611 +231.07,50.43279031,-2.567471367,48.5003,1.147144364,9.932876478,-0.06,0.6956488,-2.066328571,83.35535117 +231.08,50.43279041,-2.567469969,48.5012,1.154096743,9.932876458,-0.125,0.757991478,-2.146263804,83.36287628 +231.09,50.43279052,-2.567468571,48.5028,1.16452533,9.932876438,-0.19,0.81913169,-2.22432747,83.37040133 +231.1,50.43279062,-2.567467173,48.505,1.164525341,9.932876419,-0.2546875,0.879056601,-2.300451502,83.37792645 +231.11,50.43279073,-2.567465775,48.5079,1.154096762,9.932876401,-0.3184375,0.937753835,-2.374569552,83.3854515 +231.12,50.43279083,-2.567464377,48.5114,1.147144363,9.933098418,-0.3815625,0.99521096,-2.446616875,83.39297662 +231.13,50.43279093,-2.567462979,48.5155,1.150620542,9.933986536,-0.445,1.051416114,-2.516530732,83.40050167 +231.14,50.43279104,-2.567461581,48.5203,1.147144345,9.935096688,-0.5084375,1.106357495,-2.584250161,83.40802673 +231.15,50.43279114,-2.567460182,48.5257,1.133239587,9.935096675,-0.5715625,1.160023645,-2.649716032,83.41555184 +231.16,50.43279124,-2.567458784,48.5317,1.133239603,9.93420853,-0.6353125,1.212403332,-2.712871336,83.4230769 +231.17,50.43279134,-2.567457386,48.5384,1.147144371,9.934208519,-0.6996875,1.26348567,-2.773661012,83.43060201 +231.18,50.43279145,-2.567455988,48.5457,1.150620545,9.935096642,-0.763125,1.313259946,-2.832031947,83.43812707 +231.19,50.43279155,-2.567454589,48.5537,1.147144354,9.935096632,-0.825,1.361715732,-2.887933377,83.44565218 +231.2,50.43279165,-2.567453191,48.5622,1.150620568,9.934208491,-0.8865625,1.408843,-2.941316427,83.45317723 +231.21,50.43279176,-2.567451793,48.5714,1.147144383,9.934208484,-0.9484375,1.454631897,-2.992134632,83.46070235 +231.22,50.43279186,-2.567450395,48.5812,1.129763401,9.93509661,-1.0096875,1.499072738,-3.040343645,83.4682274 +231.23,50.43279196,-2.567448996,48.5916,1.119334806,9.935318638,-1.07,1.542156414,-3.085901468,83.47575252 +231.24,50.43279206,-2.567447598,48.6026,1.129763394,9.935096601,-1.13,1.583873815,-3.128768279,83.48327757 +231.25,50.43279216,-2.5674462,48.6142,1.147144384,9.935540664,-1.1896875,1.624216231,-3.16890678,83.49080269 +231.26,50.43279227,-2.567444801,48.6264,1.147144393,9.936206761,-1.2484375,1.663175299,-3.206281963,83.49832774 +231.27,50.43279237,-2.567443403,48.6392,1.129763412,9.93620676,-1.3065625,1.700742824,-3.240861226,83.50585285 +231.28,50.43279247,-2.567442004,48.6525,1.115858621,9.93554066,-1.365,1.736911014,-3.272614375,83.51337791 +231.29,50.43279257,-2.567440606,48.6665,1.112382428,9.935096594,-1.4234375,1.771672306,-3.301513794,83.52090302 +231.3,50.43279267,-2.567439208,48.681,1.112382442,9.935540662,-1.48125,1.805019366,-3.327534214,83.52842808 +231.31,50.43279277,-2.567437809,48.6961,1.115858649,9.936428798,-1.538125,1.836945319,-3.350653003,83.53595319 +231.32,50.43279287,-2.567436411,48.7118,1.129763433,9.937316934,-1.593125,1.867443404,-3.370849937,83.54347825 +231.33,50.43279297,-2.567435012,48.728,1.147144405,9.937761004,-1.646875,1.896507376,-3.388107484,83.55100336 +231.34,50.43279308,-2.567433613,48.7447,1.147144397,9.937316941,-1.7015625,1.924131104,-3.402410516,83.55852842 +231.35,50.43279318,-2.567432215,48.762,1.129763422,9.936650847,-1.7565625,1.950308801,-3.4137466,83.56605353 +231.36,50.43279328,-2.567430816,48.7799,1.115858654,9.936650853,-1.8096875,1.975034966,-3.422105882,83.57357859 +231.37,50.43279338,-2.567429418,48.7982,1.112382471,9.937316961,-1.86125,1.998304558,-3.427480971,83.5811037 +231.38,50.43279348,-2.567428019,48.8171,1.112382474,9.937761036,-1.911875,2.020112592,-3.429867283,83.58862875 +231.39,50.43279358,-2.56742662,48.8365,1.112382469,9.937539012,-1.9615625,2.0404546,-3.429262698,83.59615387 +231.4,50.43279368,-2.567425222,48.8563,1.112382461,9.937539022,-2.0115625,2.059326282,-3.425667789,83.60367892 +231.41,50.43279378,-2.567423823,48.8767,1.112382465,9.937761066,-2.0615625,2.076723687,-3.419085593,83.61120404 +231.42,50.43279388,-2.567422424,48.8976,1.11238248,9.937539044,-2.109375,2.092643262,-3.409521896,83.61872909 +231.43,50.43279398,-2.567421026,48.9189,1.112382492,9.937761089,-2.155,2.107081627,-3.396985064,83.62625421 +231.44,50.43279408,-2.567419627,48.9407,1.112382496,9.938649234,-2.2,2.120035744,-3.381485982,83.63377926 +231.45,50.43279418,-2.567418228,48.9629,1.112382491,9.938871281,-2.245,2.131502922,-3.363038231,83.64130437 +231.46,50.43279428,-2.567416829,48.9856,1.112382484,9.938649263,-2.29,2.14148081,-3.341657852,83.64882943 +231.47,50.43279438,-2.567415431,49.0087,1.108906292,9.938871311,-2.334375,2.149967232,-3.317363525,83.65635454 +231.48,50.43279448,-2.567414031,49.0323,1.095001525,9.938871328,-2.3765625,2.156960525,-3.290176391,83.6638796 +231.49,50.43279458,-2.567412633,49.0563,1.077620559,9.938649311,-2.4165625,2.162459201,-3.260120114,83.67140466 +231.5,50.43279467,-2.567411234,49.0806,1.077620566,9.939093395,-2.4565625,2.166462056,-3.227221049,83.67892977 +231.51,50.43279477,-2.567409835,49.1054,1.095001546,9.939759512,-2.4965625,2.168968288,-3.19150773,83.68645482 +231.52,50.43279487,-2.567408436,49.1306,1.108906325,9.939981564,-2.534375,2.169977381,-3.153011441,83.69397994 +231.53,50.43279497,-2.567407037,49.1561,1.112382514,9.939981583,-2.57,2.169489107,-3.111765642,83.70150499 +231.54,50.43279507,-2.567405638,49.182,1.108906325,9.939981603,-2.605,2.167503579,-3.067806314,83.70903011 +231.55,50.43279517,-2.567404239,49.2082,1.095001564,9.939981623,-2.64,2.164021199,-3.021171847,83.71655516 +231.56,50.43279527,-2.56740284,49.2348,1.077620603,9.939981643,-2.6746875,2.159042711,-2.971902862,83.72408027 +231.57,50.43279536,-2.567401441,49.2617,1.077620603,9.939981664,-2.7078125,2.152569147,-2.920042333,83.73160533 +231.58,50.43279546,-2.567400042,49.289,1.095001569,9.939981686,-2.738125,2.144601883,-2.865635464,83.73913044 +231.59,50.43279556,-2.567398643,49.3165,1.105430141,9.940203742,-2.7665625,2.135142522,-2.808729754,83.7466555 +231.6,50.43279566,-2.567397244,49.3443,1.095001556,9.941091897,-2.7953125,2.124193069,-2.749374764,83.75418061 +231.61,50.43279576,-2.567395845,49.3724,1.077620604,9.942202086,-2.824375,2.111755874,-2.687622289,83.76170567 +231.62,50.43279585,-2.567394445,49.4008,1.077620629,9.94220211,-2.8515625,2.097833458,-2.623526131,83.76923078 +231.63,50.43279595,-2.567393046,49.4295,1.091525417,9.941091969,-2.87625,2.082428743,-2.557142267,83.77675584 +231.64,50.43279605,-2.567391647,49.4583,1.091525416,9.94020386,-2.8996875,2.065544937,-2.488528508,83.78428095 +231.65,50.43279615,-2.567390248,49.4875,1.077620632,9.940203885,-2.921875,2.04718565,-2.417744787,83.79180601 +231.66,50.43279624,-2.567388849,49.5168,1.074144433,9.941092043,-2.9428125,2.027354607,-2.344852695,83.79933112 +231.67,50.43279634,-2.56738745,49.5463,1.077620622,9.942202234,-2.9634375,2.00605599,-2.269915831,83.80685618 +231.68,50.43279644,-2.56738605,49.5761,1.074144431,9.942424294,-2.9828125,1.98329421,-2.192999628,83.81438129 +231.69,50.43279653,-2.567384651,49.606,1.074144448,9.942202287,-2.9996875,1.959074081,-2.114171063,83.82190634 +231.7,50.43279663,-2.567383252,49.6361,1.077620658,9.942424346,-3.0153125,1.933400644,-2.033498892,83.82943146 +231.71,50.43279673,-2.567381852,49.6663,1.074144469,9.942424373,-3.03125,1.906279286,-1.951053474,83.83695651 +231.72,50.43279682,-2.567380453,49.6967,1.074144474,9.942202368,-3.04625,1.877715621,-1.866906772,83.84448163 +231.73,50.43279692,-2.567379054,49.7273,1.077620673,9.942424428,-3.058125,1.847715608,-1.781132068,83.85200668 +231.74,50.43279702,-2.567377654,49.7579,1.070668277,9.942424455,-3.068125,1.81628555,-1.69380419,83.85953179 +231.75,50.43279711,-2.567376255,49.7886,1.060239683,9.94220245,-3.0784375,1.783432035,-1.604999284,83.86705685 +231.76,50.43279721,-2.567374856,49.8195,1.060239688,9.942646544,-3.0878125,1.749161825,-1.514794757,83.87458196 +231.77,50.4327973,-2.567373456,49.8504,1.070668293,9.943312671,-3.0946875,1.713482196,-1.423269333,83.88210702 +231.78,50.4327974,-2.567372057,49.8814,1.077620699,9.943534733,-3.1,1.676400482,-1.330502825,83.88963213 +231.79,50.4327975,-2.567370657,49.9124,1.070668314,9.943534761,-3.1046875,1.637924533,-1.236576077,83.89715719 +231.8,50.43279759,-2.567369258,49.9435,1.060239731,9.943312756,-3.108125,1.59806237,-1.141571023,83.9046823 +231.81,50.43279769,-2.567367858,49.9746,1.056763542,9.942646685,-3.109375,1.556822243,-1.045570512,83.91220736 +231.82,50.43279778,-2.567366459,50.0057,1.056763552,9.94242468,-3.1084375,1.514212804,-0.948658254,83.91973241 +231.83,50.43279788,-2.56736506,50.0368,1.056763553,9.943534875,-3.1065625,1.470242934,-0.850918701,83.92725753 +231.84,50.43279797,-2.56736366,50.0678,1.056763542,9.944645069,-3.105,1.424921858,-0.752437168,83.93478258 +231.85,50.43279807,-2.56736226,50.0989,1.056763541,9.944645097,-3.1028125,1.378259029,-0.653299541,83.9423077 +231.86,50.43279816,-2.567360861,50.1299,1.056763555,9.944645125,-3.0978125,1.330264188,-0.553592165,83.94983275 +231.87,50.43279826,-2.567359461,50.1609,1.056763569,9.944867187,-3.0903125,1.280947361,-0.453402072,83.95735786 +231.88,50.43279835,-2.567358061,50.1917,1.05328738,9.944645182,-3.0828125,1.230318805,-0.352816581,83.96488292 +231.89,50.43279845,-2.567356662,50.2225,1.042858796,9.944645211,-3.075,1.178389119,-0.251923469,83.97240803 +231.9,50.43279854,-2.567355262,50.2533,1.035906408,9.944867272,-3.0646875,1.12516919,-0.150810628,83.97993309 +231.91,50.43279863,-2.567353862,50.2838,1.042858806,9.944645266,-3.053125,1.070670074,-0.04956635,83.9874582 +231.92,50.43279873,-2.567352463,50.3143,1.053287398,9.944867328,-3.0415625,1.014903175,0.051721244,83.99498326 +231.93,50.43279882,-2.567351063,50.3447,1.053287394,9.945755488,-3.0278125,0.957880181,0.152963688,84.00250837 +231.94,50.43279892,-2.567349663,50.3749,1.042858799,9.945755515,-3.01125,0.899612894,0.254072748,84.01003343 +231.95,50.43279901,-2.567348263,50.4049,1.035906411,9.944867409,-2.9934375,0.840113634,0.354960246,84.01755854 +231.96,50.4327991,-2.567346864,50.4348,1.039382623,9.944867436,-2.975,0.779394661,0.455538174,84.0250836 +231.97,50.4327992,-2.567345464,50.4644,1.039382637,9.945977629,-2.95625,0.717468752,0.555718927,84.03260871 +231.98,50.43279929,-2.567344064,50.4939,1.03590645,9.946865788,-2.9365625,0.654348856,0.655415074,84.04013376 +231.99,50.43279938,-2.567342664,50.5232,1.039382658,9.946865814,-2.914375,0.590048095,0.754539694,84.04765888 +232,50.43279948,-2.567341264,50.5522,1.039382667,9.945977706,-2.89,0.524579932,0.85300633,84.05518393 +232.01,50.43279957,-2.567339864,50.581,1.035906471,9.944867566,-2.865,0.457958061,0.950729095,84.06270905 +232.02,50.43279966,-2.567338465,50.6095,1.039382665,9.944867591,-2.84,0.390196348,1.047622847,84.0702341 +232.03,50.43279976,-2.567337065,50.6378,1.035906471,9.946199815,-2.8146875,0.321308945,1.143603075,84.07775921 +232.04,50.43279985,-2.567335665,50.6658,1.022001687,9.947754071,-2.7878125,0.251310232,1.238586071,84.08528427 +232.05,50.43279994,-2.567334265,50.6936,1.022001683,9.948420194,-2.758125,0.180214879,1.332488983,84.09280938 +232.06,50.43280003,-2.567332864,50.721,1.035906462,9.947976151,-2.7265625,0.108037724,1.425229937,84.10033444 +232.07,50.43280013,-2.567331465,50.7481,1.035906467,9.947310074,-2.695,0.034793779,1.516728031,84.10785955 +232.08,50.43280022,-2.567330064,50.7749,1.018525499,9.947088064,-2.6628125,-0.039501601,1.606903567,84.11538461 +232.09,50.43280031,-2.567328665,50.8014,1.008096922,9.947088086,-2.628125,-0.114832889,1.695677877,84.12290972 +232.1,50.4328004,-2.567327264,50.8275,1.018525519,9.94731014,-2.5915625,-0.191184442,1.782973497,84.13043478 +232.11,50.43280049,-2.567325865,50.8532,1.035906508,9.947976261,-2.5553125,-0.268540219,1.868714339,84.13795989 +232.12,50.43280059,-2.567324464,50.8786,1.035906519,9.948420347,-2.5196875,-0.346884062,1.952825632,84.14548495 +232.13,50.43280068,-2.567323064,50.9036,1.018525544,9.9479763,-2.4828125,-0.426199698,2.035234037,84.15301006 +232.14,50.43280077,-2.567321664,50.9283,1.004620757,9.947532253,-2.443125,-0.506470512,2.115867706,84.16053512 +232.15,50.43280086,-2.567320264,50.9525,1.001144557,9.947976338,-2.4015625,-0.587679716,2.194656278,84.16806023 +232.16,50.43280095,-2.567318864,50.9763,1.001144559,9.948420423,-2.36,-0.669810409,2.271531057,84.17558528 +232.17,50.43280104,-2.567317463,50.9997,1.004620759,9.948198408,-2.318125,-0.752845401,2.346425063,84.18311034 +232.18,50.43280113,-2.567316064,51.0227,1.01852555,9.948198425,-2.2746875,-0.836767331,2.41927298,84.19063545 +232.19,50.43280122,-2.567314663,51.0452,1.035906535,9.948642506,-2.23,-0.921558725,2.490011209,84.19816051 +232.2,50.43280132,-2.567313263,51.0673,1.03590653,9.949086587,-2.185,-1.007201821,2.558578156,84.20568562 +232.21,50.43280141,-2.567311863,51.0889,1.018525538,9.949530668,-2.139375,-1.093678799,2.624913949,84.21321068 +232.22,50.4328015,-2.567310462,51.1101,1.004620757,9.949530682,-2.0915625,-1.180971555,2.688960776,84.22073579 +232.23,50.43280159,-2.567309062,51.1308,1.001144581,9.949308662,-2.0415625,-1.26906181,2.750662773,84.22826085 +232.24,50.43280168,-2.567307662,51.1509,1.001144597,9.949530708,-1.991875,-1.357931288,2.809966197,84.23578596 +232.25,50.43280177,-2.567306261,51.1706,1.001144598,9.949308687,-1.9434375,-1.447561368,2.866819252,84.24331102 +232.26,50.43280186,-2.567304861,51.1898,1.001144595,9.948420565,-1.894375,-1.537933314,2.921172434,84.25083613 +232.27,50.43280195,-2.567303461,51.2085,1.001144595,9.948642609,-1.843125,-1.629028217,2.972978247,84.25836118 +232.28,50.43280204,-2.567302061,51.2267,1.001144598,9.950418884,-1.79,-1.720827171,3.022191655,84.2658863 +232.29,50.43280213,-2.56730066,51.2443,1.001144601,9.951529058,-1.7365625,-1.813310925,3.068769628,84.27341135 +232.3,50.43280222,-2.567299259,51.2614,1.001144604,9.950640933,-1.683125,-1.906460169,3.112671603,84.28093647 +232.31,50.43280231,-2.567297859,51.278,0.997668411,9.949530773,-1.628125,-2.000255422,3.153859247,84.28846152 +232.32,50.4328024,-2.567296459,51.294,0.983763633,9.949752813,-1.5715625,-2.094677205,3.192296693,84.29598664 +232.33,50.43280249,-2.567295058,51.3094,0.966382655,9.950640951,-1.5153125,-2.189705693,3.227950425,84.30351169 +232.34,50.43280257,-2.567293658,51.3243,0.966382653,9.951529089,-1.4596875,-2.285321062,3.260789329,84.3110368 +232.35,50.43280266,-2.567292257,51.3386,0.983763633,9.95197316,-1.403125,-2.381503373,3.290784758,84.31856186 +232.36,50.43280275,-2.567290856,51.3524,0.997668421,9.951529096,-1.345,-2.478232514,3.317910585,84.32608697 +232.37,50.43280284,-2.567289456,51.3655,1.00114462,9.950862998,-1.2865625,-2.575488318,3.342143205,84.33361203 +232.38,50.43280293,-2.567288055,51.3781,1.001144624,9.950640966,-1.2284375,-2.673250388,3.36346136,84.34113714 +232.39,50.43280302,-2.567286655,51.3901,0.997668436,9.950640966,-1.1696875,-2.77149844,3.381846545,84.3486622 +232.4,50.43280311,-2.567285254,51.4015,0.983763654,9.950862999,-1.1096875,-2.870211849,3.397282715,84.35618731 +232.41,50.4328032,-2.567283854,51.4123,0.966382666,9.951529097,-1.0484375,-2.969370045,3.40975635,84.36371237 +232.42,50.43280328,-2.567282453,51.4225,0.966382661,9.95197316,-0.9865625,-3.068952345,3.419256678,84.37123748 +232.43,50.43280337,-2.567281052,51.432,0.983763646,9.951751123,-0.925,-3.168937892,3.425775391,84.37876254 +232.44,50.43280346,-2.567279652,51.441,0.994192238,9.951751118,-0.8634375,-3.269305831,3.429306701,84.38628765 +232.45,50.43280355,-2.567278251,51.4493,0.983763648,9.951973146,-0.80125,-3.370035192,3.429847688,84.3938127 +232.46,50.43280364,-2.56727685,51.457,0.966382664,9.951751106,-0.7384375,-3.471104947,3.427397721,84.40133782 +232.47,50.43280372,-2.56727545,51.4641,0.966382663,9.951973132,-0.675,-3.572494011,3.421959033,84.40886287 +232.48,50.43280381,-2.567274049,51.4705,0.980287446,9.95308329,-0.611875,-3.674181185,3.413536382,84.41638799 +232.49,50.4328039,-2.567272648,51.4763,0.980287447,9.953971414,-0.55,-3.77614527,3.402137043,84.42391304 +232.5,50.43280399,-2.567271247,51.4815,0.966382675,9.954193437,-0.488125,-3.878364894,3.387770985,84.43143816 +232.51,50.43280407,-2.567269846,51.4861,0.962906487,9.954193426,-0.4246875,-3.980818744,3.370450758,84.43896321 +232.52,50.43280416,-2.567268445,51.49,0.966382674,9.954193414,-0.36,-4.083485504,3.350191486,84.44648827 +232.53,50.43280425,-2.567267044,51.4933,0.962906466,9.953971367,-0.295,-4.186343632,3.327010759,84.45401338 +232.54,50.43280433,-2.567265643,51.4959,0.962906467,9.95308322,-0.23,-4.289371642,3.300928804,84.46153844 +232.55,50.43280442,-2.567264242,51.4979,0.966382675,9.951973039,-0.165,-4.392548106,3.271968423,84.46906355 +232.56,50.43280451,-2.567262842,51.4992,0.962906489,9.951973023,-0.1,-4.495851422,3.240154827,84.4765886 +232.57,50.43280459,-2.567261441,51.4999,0.962906481,9.953083172,-0.0353125,-4.599260048,3.205515746,84.48411372 +232.58,50.43280468,-2.56726004,51.4999,0.966382662,9.953971287,0.0284375,-4.702752326,3.168081434,84.49163877 +232.59,50.43280477,-2.567258639,51.4993,0.95943027,9.954193301,0.0915625,-4.806306656,3.127884492,84.49916389 +232.6,50.43280485,-2.567257238,51.4981,0.949001692,9.954193281,0.1553125,-4.909901493,3.084960041,84.50668894 +232.61,50.43280494,-2.567255837,51.4962,0.949001696,9.95419326,0.22,-5.013515123,3.039345381,84.51421406 +232.62,50.43280502,-2.567254436,51.4937,0.959430276,9.954193238,0.2846875,-5.117125946,2.99108039,84.52173911 +232.63,50.43280511,-2.567253035,51.4905,0.966382661,9.954193215,0.3484375,-5.220712304,2.940207181,84.52926422 +232.64,50.4328052,-2.567251634,51.4867,0.959430275,9.95419319,0.4115625,-5.324252538,2.886770043,84.53678928 +232.65,50.43280528,-2.567250233,51.4823,0.949001694,9.954193166,0.4753125,-5.427725049,2.830815558,84.54431439 +232.66,50.43280537,-2.567248832,51.4772,0.945525497,9.954415174,0.54,-5.531108293,2.772392598,84.55183945 +232.67,50.43280545,-2.567247431,51.4715,0.945525496,9.955081247,0.6046875,-5.634380555,2.711552044,84.55936456 +232.68,50.43280554,-2.56724603,51.4651,0.945525499,9.955525285,0.668125,-5.737520407,2.648347007,84.56688962 +232.69,50.43280562,-2.567244628,51.4581,0.9455255,9.955303224,0.73,-5.84050619,2.582832549,84.57441473 +232.7,50.43280571,-2.567243228,51.4505,0.945525497,9.955303194,0.791875,-5.943316476,2.515065851,84.58193979 +232.71,50.43280579,-2.567241826,51.4423,0.945525492,9.95574723,0.8546875,-6.045929722,2.445105928,84.5894649 +232.72,50.43280588,-2.567240425,51.4334,0.94552549,9.956191264,0.9165625,-6.148324557,2.373013857,84.59698996 +232.73,50.43280596,-2.567239024,51.4239,0.942049296,9.956635298,0.9765625,-6.250479551,2.298852549,84.60451507 +232.74,50.43280605,-2.567237622,51.4139,0.931620706,9.956635265,1.036875,-6.352373449,2.222686519,84.61204012 +232.75,50.43280613,-2.567236221,51.4032,0.924668308,9.956191165,1.0984375,-6.453984936,2.144582288,84.61956524 +232.76,50.43280621,-2.56723482,51.3919,0.931620694,9.955747063,1.1596875,-6.555292697,2.064607979,84.62709029 +232.77,50.4328063,-2.567233418,51.38,0.942049277,9.95530296,1.2196875,-6.656275707,1.982833323,84.63461541 +232.78,50.43280638,-2.567232018,51.3675,0.942049273,9.955524956,1.2784375,-6.756912821,1.899329537,84.64214046 +232.79,50.43280647,-2.567230616,51.3544,0.93162068,9.956635084,1.3365625,-6.857183014,1.814169559,84.64966558 +232.8,50.43280655,-2.567229215,51.3408,0.924668286,9.957301144,1.3946875,-6.957065371,1.727427588,84.65719063 +232.81,50.43280663,-2.567227813,51.3265,0.928144488,9.956857038,1.451875,-7.056539038,1.639179253,84.66471574 +232.82,50.43280672,-2.567226412,51.3117,0.92814449,9.956412932,1.5078125,-7.155583158,1.549501561,84.6722408 +232.83,50.4328068,-2.567225011,51.2964,0.924668286,9.956634924,1.56375,-7.254177162,1.458472662,84.67976591 +232.84,50.43280688,-2.567223609,51.2804,0.928144474,9.956634882,1.6196875,-7.352300424,1.366171969,84.68729097 +232.85,50.43280697,-2.567222208,51.264,0.92814447,9.956412805,1.6746875,-7.449932433,1.272679924,84.69481608 +232.86,50.43280705,-2.567220807,51.2469,0.92466827,9.956856827,1.7284375,-7.54705279,1.178078118,84.70234114 +232.87,50.43280713,-2.567219405,51.2294,0.928144467,9.957522882,1.78125,-7.643641213,1.082448998,84.70986619 +232.88,50.43280722,-2.567218004,51.2113,0.924668274,9.95774487,1.8334375,-7.739677533,0.98587593,84.71739131 +232.89,50.4328073,-2.567216602,51.1927,0.910763488,9.957744824,1.885,-7.835141756,0.888443197,84.72491636 +232.9,50.43280738,-2.567215201,51.1736,0.910763481,9.957744777,1.9365625,-7.930013884,0.79023571,84.73244148 +232.91,50.43280746,-2.567213799,51.154,0.924668259,9.957966762,1.9878125,-8.024274093,0.691339183,84.73996653 +232.92,50.43280755,-2.567212398,51.1338,0.924668256,9.958632813,2.0365625,-8.11790273,0.591839734,84.74749164 +232.93,50.43280763,-2.567210996,51.1132,0.907287276,9.95907683,2.083125,-8.210880259,0.491824221,84.7550167 +232.94,50.43280771,-2.567209594,51.0922,0.896858687,9.958632714,2.1303125,-8.303187197,0.39137985,84.76254181 +232.95,50.43280779,-2.567208193,51.0706,0.90728727,9.957966563,2.178125,-8.394804295,0.29059411,84.77006687 +232.96,50.43280787,-2.567206791,51.0486,0.924668244,9.957966512,2.224375,-8.485712471,0.189555065,84.77759198 +232.97,50.43280796,-2.56720539,51.0261,0.924668241,9.958632558,2.2684375,-8.575892705,0.088350665,84.78511704 +232.98,50.43280804,-2.567203988,51.0032,0.907287262,9.959076572,2.31125,-8.665326146,-0.012930741,84.79264215 +232.99,50.43280812,-2.567202586,50.9799,0.893382485,9.958632453,2.3534375,-8.753994115,-0.114200916,84.80016721 +233,50.4328082,-2.567201185,50.9561,0.889906292,9.9579663,2.395,-8.841878105,-0.215371455,84.80769232 +233.01,50.43280828,-2.567199783,50.932,0.889906282,9.957966246,2.43625,-8.928959783,-0.316354235,84.81521738 +233.02,50.43280836,-2.567198382,50.9074,0.893382464,9.958854323,2.4765625,-9.015220986,-0.417061136,84.82274249 +233.03,50.43280844,-2.56719698,50.8824,0.907287245,9.959964433,2.5146875,-9.100643607,-0.517404323,84.83026754 +233.04,50.43280852,-2.567195578,50.8571,0.924668227,9.959964376,2.5515625,-9.185209886,-0.617296363,84.83779266 +233.05,50.43280861,-2.567194176,50.8314,0.924668219,9.959076186,2.588125,-9.268902118,-0.71665011,84.84531771 +233.06,50.43280869,-2.567192775,50.8053,0.907287226,9.959076128,2.623125,-9.351702884,-0.815378931,84.85284283 +233.07,50.43280877,-2.567191373,50.7789,0.893382435,9.960186236,2.6565625,-9.433594825,-0.913396712,84.86036788 +233.08,50.43280885,-2.567189971,50.7522,0.889906241,9.960852277,2.69,-9.514560866,-1.010617967,84.867893 +233.09,50.43280893,-2.567188569,50.7251,0.889906242,9.960186118,2.7228125,-9.594584105,-1.106958013,84.87541805 +233.1,50.43280901,-2.567187167,50.6977,0.889906234,9.959075892,2.753125,-9.673647812,-1.202332739,84.88294316 +233.11,50.43280909,-2.567185766,50.67,0.889906223,9.959075833,2.7815625,-9.751735485,-1.29665901,84.89046822 +233.12,50.43280917,-2.567184364,50.6421,0.889906219,9.960185939,2.8096875,-9.828830853,-1.389854549,84.89799333 +233.13,50.43280925,-2.567182962,50.6138,0.889906222,9.961074011,2.8365625,-9.904917757,-1.481838167,84.90551839 +233.14,50.43280933,-2.56718156,50.5853,0.889906225,9.961295982,2.8615625,-9.979980328,-1.572529594,84.9130435 +233.15,50.43280941,-2.567180158,50.5566,0.889906225,9.96129592,2.8865625,-10.05400287,-1.661849704,84.92056856 +233.16,50.43280949,-2.567178756,50.5276,0.886430029,9.961295859,2.91125,-10.12697001,-1.749720688,84.92809367 +233.17,50.43280957,-2.567177354,50.4983,0.872525239,9.961295797,2.933125,-10.19886642,-1.836065886,84.93561873 +233.18,50.43280965,-2.567175952,50.4689,0.855144248,9.961295735,2.953125,-10.26967707,-1.920810011,84.94314384 +233.19,50.43280972,-2.56717455,50.4393,0.85514424,9.961295672,2.973125,-10.3393873,-2.003879208,84.9506689 +233.2,50.4328098,-2.567173148,50.4094,0.872525211,9.961295609,2.9915625,-10.40798238,-2.085200942,84.95819395 +233.21,50.43280988,-2.567171746,50.3794,0.886429986,9.961295546,3.0078125,-10.47544816,-2.164704336,84.96571906 +233.22,50.43280996,-2.567170344,50.3493,0.889906179,9.961295483,3.0234375,-10.54177037,-2.242320064,84.97324412 +233.23,50.43281004,-2.567168942,50.3189,0.889906181,9.961295418,3.038125,-10.60693533,-2.317980516,84.98076923 +233.24,50.43281012,-2.56716754,50.2885,0.886429985,9.961295353,3.05125,-10.67092933,-2.39161963,84.98829429 +233.25,50.4328102,-2.567166138,50.2579,0.872525195,9.961295289,3.0634375,-10.73373902,-2.463173178,84.9958194 +233.26,50.43281028,-2.567164736,50.2272,0.855144218,9.961517259,3.074375,-10.79535129,-2.532578879,85.00334446 +233.27,50.43281035,-2.567163334,50.1964,0.855144227,9.962405328,3.083125,-10.85575325,-2.599776056,85.01086957 +233.28,50.43281043,-2.567161932,50.1655,0.8725252,9.963515429,3.09,-10.91493234,-2.664706212,85.01839463 +233.29,50.43281051,-2.567160529,50.1346,0.882953767,9.963515364,3.09625,-10.97287619,-2.727312737,85.02591974 +233.3,50.43281059,-2.567159127,50.1036,0.872525165,9.962627167,3.1015625,-11.02957266,-2.787540972,85.0334448 +233.31,50.43281067,-2.567157725,50.0725,0.855144184,9.962627102,3.1046875,-11.08500994,-2.845338434,85.04096991 +233.32,50.43281074,-2.567156323,50.0415,0.855144184,9.96351517,3.1065625,-11.13917645,-2.900654759,85.04849496 +233.33,50.43281082,-2.56715492,50.0104,0.869048961,9.963515105,3.1084375,-11.19206085,-2.953441647,85.05602008 +233.34,50.4328109,-2.567153518,49.9793,0.86904895,9.962404875,3.109375,-11.24365209,-3.003653032,85.06354513 +233.35,50.43281098,-2.567152116,49.9482,0.855144161,9.96173871,3.108125,-11.29393945,-3.051245256,85.07107025 +233.36,50.43281105,-2.567150714,49.9171,0.851667969,9.962404745,3.1046875,-11.34291245,-3.096176721,85.0785953 +233.37,50.43281113,-2.567149312,49.8861,0.855144175,9.963514846,3.1,-11.39056077,-3.138408294,85.08612042 +233.38,50.43281121,-2.567147909,49.8551,0.851667983,9.963736815,3.0946875,-11.43687449,-3.177903134,85.09364547 +233.39,50.43281128,-2.567146507,49.8242,0.851667979,9.963514718,3.088125,-11.481844,-3.214626749,85.10117058 +233.4,50.43281136,-2.567145105,49.7933,0.855144162,9.963736687,3.0796875,-11.52545978,-3.248547169,85.10869564 +233.41,50.43281144,-2.567143702,49.7626,0.851667949,9.963736623,3.07,-11.5677129,-3.279634827,85.11622075 +233.42,50.43281151,-2.5671423,49.7319,0.851667936,9.963514525,3.0596875,-11.60859435,-3.307862624,85.12374581 +233.43,50.43281159,-2.567140898,49.7014,0.855144128,9.963736494,3.0478125,-11.64809573,-3.333205866,85.13127092 +233.44,50.43281167,-2.567139495,49.6709,0.848191741,9.963736431,3.0334375,-11.68620871,-3.355642549,85.13879598 +233.45,50.43281174,-2.567138093,49.6407,0.837763162,9.963736369,3.018125,-11.72292539,-3.375153022,85.14632109 +233.46,50.43281182,-2.567136691,49.6106,0.837763164,9.964846472,3.003125,-11.7582381,-3.391720326,85.15384615 +233.47,50.43281189,-2.567135288,49.5806,0.848191742,9.965734542,2.98625,-11.79213938,-3.405329965,85.16137126 +233.48,50.43281197,-2.567133885,49.5508,0.855144119,9.964846347,2.9665625,-11.82462225,-3.415970192,85.16889632 +233.49,50.43281205,-2.567132483,49.5213,0.848191721,9.963736118,2.9465625,-11.85567982,-3.423631554,85.17642143 +233.5,50.43281212,-2.567131081,49.4919,0.837763131,9.963958089,2.9265625,-11.88530575,-3.42830752,85.18394648 +233.51,50.4328122,-2.567129678,49.4627,0.834286929,9.964624128,2.904375,-11.91349373,-3.429993907,85.1914716 +233.52,50.43281227,-2.567128276,49.4338,0.834286925,9.9648461,2.8796875,-11.94023791,-3.428689282,85.19899665 +233.53,50.43281235,-2.567126873,49.4051,0.834286926,9.96484604,2.8534375,-11.96553274,-3.424394849,85.20652177 +233.54,50.43281242,-2.567125471,49.3767,0.834286927,9.96484598,2.8265625,-11.98937288,-3.417114217,85.21404682 +233.55,50.4328125,-2.567124068,49.3486,0.834286927,9.96484592,2.8,-12.01175336,-3.40685386,85.22157188 +233.56,50.43281257,-2.567122666,49.3207,0.834286924,9.964845861,2.7728125,-12.03266958,-3.393622661,85.22909699 +233.57,50.43281265,-2.567121263,49.2931,0.834286916,9.965067835,2.743125,-12.05211709,-3.377432191,85.23662205 +233.58,50.43281272,-2.567119861,49.2658,0.830810712,9.965733877,2.7115625,-12.0700918,-3.358296547,85.24414716 +233.59,50.4328128,-2.567118458,49.2389,0.820382117,9.966177886,2.6796875,-12.08659012,-3.3362324,85.25167222 +233.6,50.43281287,-2.567117055,49.2122,0.813429724,9.965955795,2.6465625,-12.10160844,-3.311259004,85.25919733 +233.61,50.43281294,-2.567115653,49.1859,0.820382123,9.966177772,2.61125,-12.11514365,-3.283398186,85.26672238 +233.62,50.43281302,-2.56711425,49.16,0.830810716,9.967065848,2.575,-12.12719301,-3.252674126,85.2742475 +233.63,50.43281309,-2.567112847,49.1344,0.830810713,9.967065793,2.5384375,-12.13775394,-3.219113754,85.28177255 +233.64,50.43281317,-2.567111444,49.1092,0.820382113,9.965955572,2.50125,-12.1468242,-3.182746232,85.28929767 +233.65,50.43281324,-2.567110042,49.0844,0.813429705,9.965289418,2.463125,-12.15440197,-3.143603302,85.29682272 +233.66,50.43281331,-2.567108639,49.0599,0.816905889,9.965955464,2.423125,-12.16048564,-3.101719113,85.30434784 +233.67,50.43281339,-2.567107237,49.0359,0.816905886,9.967065578,2.3815625,-12.16507388,-3.057130163,85.31187289 +233.68,50.43281346,-2.567105833,49.0123,0.813429696,9.967065526,2.34,-12.16816585,-3.009875411,85.319398 +233.69,50.43281353,-2.567104431,48.9891,0.816905902,9.966177341,2.2978125,-12.16976079,-2.95999594,85.32692306 +233.7,50.43281361,-2.567103028,48.9663,0.816905908,9.96617729,2.253125,-12.16985848,-2.907535294,85.33444817 +233.71,50.43281368,-2.567101626,48.944,0.81342971,9.967065372,2.206875,-12.1684588,-2.85253931,85.34197323 +233.72,50.43281375,-2.567100222,48.9222,0.816905894,9.967287356,2.1615625,-12.1655621,-2.795055829,85.34949834 +233.73,50.43281383,-2.56709882,48.9008,0.813429682,9.967065275,2.1165625,-12.16116895,-2.735134986,85.3570234 +233.74,50.4328139,-2.567097417,48.8798,0.79952489,9.967509292,2.069375,-12.15528026,-2.672829092,85.36454851 +233.75,50.43281397,-2.567096014,48.8594,0.799524897,9.968175344,2.02,-12.1478973,-2.608192463,85.37207357 +233.76,50.43281404,-2.567094611,48.8394,0.813429694,9.968175298,1.97,-12.13902155,-2.54128142,85.37959868 +233.77,50.43281412,-2.567093208,48.82,0.813429696,9.967509153,1.9196875,-12.12865497,-2.472154406,85.38712374 +233.78,50.43281419,-2.567091805,48.801,0.796048703,9.967065043,1.8684375,-12.11679967,-2.400871581,85.39464885 +233.79,50.43281426,-2.567090403,48.7826,0.785620105,9.967287032,1.81625,-12.10345806,-2.327495168,85.4021739 +233.8,50.43281433,-2.567088999,48.7647,0.796048691,9.967509023,1.7634375,-12.088633,-2.252089166,85.40969902 +233.81,50.4328144,-2.567087597,48.7473,0.813429674,9.967953046,1.7096875,-12.0723276,-2.174719295,85.41722407 +233.82,50.43281448,-2.567086194,48.7305,0.813429683,9.968619104,1.655,-12.05454522,-2.09545299,85.42474919 +233.83,50.43281455,-2.56708479,48.7142,0.796048705,9.96839703,1.6,-12.03528955,-2.014359466,85.43227424 +233.84,50.43281462,-2.567083388,48.6985,0.782143908,9.968174957,1.545,-12.01456469,-1.931509425,85.43979936 +233.85,50.43281469,-2.567081985,48.6833,0.778667701,9.968618985,1.4896875,-11.99237495,-1.846975003,85.44732441 +233.86,50.43281476,-2.567080581,48.6687,0.778667702,9.968396915,1.433125,-11.96872491,-1.760830053,85.45484952 +233.87,50.43281483,-2.567079179,48.6546,0.782143902,9.968396878,1.375,-11.94361956,-1.673149577,85.46237458 +233.88,50.4328149,-2.567077776,48.6412,0.796048694,9.969729041,1.3165625,-11.91706406,-1.584010121,85.46989969 +233.89,50.43281497,-2.567076372,48.6283,0.813429672,9.970173072,1.2584375,-11.88906407,-1.493489379,85.47742475 +233.9,50.43281505,-2.567074969,48.616,0.813429655,9.968618806,1.1996875,-11.85962538,-1.401666303,85.48494981 +233.91,50.43281512,-2.567073566,48.6043,0.79604866,9.967508607,1.14,-11.82875419,-1.308620994,85.49247492 +233.92,50.43281519,-2.567072164,48.5932,0.782143877,9.968396707,1.0796875,-11.79645684,-1.214434467,85.49999997 +233.93,50.43281526,-2.56707076,48.5827,0.778667696,9.969506841,1.0184375,-11.76274017,-1.119189,85.50752509 +233.94,50.43281533,-2.567069357,48.5728,0.77866771,9.969284778,0.9565625,-11.72761121,-1.022967556,85.51505014 +233.95,50.4328154,-2.567067954,48.5636,0.778667707,9.968840682,0.895,-11.69107724,-0.925854075,85.52257526 +233.96,50.43281547,-2.567066551,48.5549,0.778667695,9.969506753,0.8334375,-11.65314589,-0.827933181,85.53010031 +233.97,50.43281554,-2.567065148,48.5469,0.778667689,9.970616892,0.77125,-11.61382517,-0.729290361,85.53762542 +233.98,50.43281561,-2.567063744,48.5395,0.778667693,9.970616865,0.7084375,-11.57312322,-0.630011615,85.54515048 +233.99,50.43281568,-2.567062341,48.5327,0.778667703,9.969728708,0.645,-11.53104853,-0.530183459,85.55267559 +234,50.43281575,-2.567060938,48.5266,0.778667705,9.969728684,0.581875,-11.48760996,-0.429892984,85.56020065 +234.01,50.43281582,-2.567059535,48.5211,0.778667691,9.970616793,0.52,-11.44281652,-0.329227622,85.56772576 +234.02,50.43281589,-2.567058131,48.5162,0.775191488,9.970616771,0.4578125,-11.39667761,-0.228275209,85.57525082 +234.03,50.43281596,-2.567056728,48.5119,0.761286715,9.969506584,0.393125,-11.34920278,-0.127123693,85.58277593 +234.04,50.43281603,-2.567055325,48.5083,0.743905746,9.968840465,0.326875,-11.30040202,-0.025861367,85.59030099 +234.05,50.43281609,-2.567053922,48.5054,0.743905746,9.969506545,0.261875,-11.25028551,0.075423534,85.5978261 +234.06,50.43281616,-2.567052519,48.5031,0.761286714,9.970838726,0.1984375,-11.1988637,0.176642716,85.60535116 +234.07,50.43281623,-2.567051115,48.5014,0.775191486,9.971726841,0.1346875,-11.14614734,0.277707773,85.61287627 +234.08,50.4328163,-2.567049712,48.5004,0.778667688,9.971726825,0.07,-11.09214744,0.378530755,85.62040132 +234.09,50.43281637,-2.567048308,48.5,0.775191506,9.971060711,0.0053125,-11.03687524,0.479023599,85.62792644 +234.1,50.43281644,-2.567046905,48.5003,0.761286722,9.97061663,-0.0584375,-10.98034235,0.579098699,85.63545149 +234.11,50.43281651,-2.567045502,48.5012,0.743905734,9.971060684,-0.121875,-10.92256053,0.678668852,85.64297661 +234.12,50.43281657,-2.567044098,48.5027,0.74390573,9.971726772,-0.1865625,-10.86354187,0.777647197,85.65050166 +234.13,50.43281664,-2.567042695,48.5049,0.761286712,9.971726761,-0.251875,-10.80329868,0.875947446,85.65802678 +234.14,50.43281671,-2.567041291,48.5078,0.771715309,9.971060652,-0.31625,-10.74184357,0.973483827,85.66555183 +234.15,50.43281678,-2.567039888,48.5112,0.761286726,9.970616576,-0.38,-10.67918932,1.070171315,85.67307694 +234.16,50.43281685,-2.567038485,48.5154,0.743905736,9.971060634,-0.4434375,-10.61534904,1.165925568,85.680602 +234.17,50.43281691,-2.567037081,48.5201,0.74390573,9.971726727,-0.5065625,-10.55033609,1.260663166,85.68812711 +234.18,50.43281698,-2.567035678,48.5255,0.757810521,9.971948754,-0.5703125,-10.48416399,1.354301429,85.69565217 +234.19,50.43281705,-2.567034274,48.5315,0.757810531,9.971948749,-0.6346875,-10.41684661,1.446758712,85.70317728 +234.2,50.43281712,-2.567032871,48.5382,0.74390575,9.971948745,-0.698125,-10.34839803,1.537954456,85.71070234 +234.21,50.43281718,-2.567031467,48.5455,0.740429548,9.972170776,-0.76,-10.27883248,1.62780902,85.71822745 +234.22,50.43281725,-2.567030064,48.5534,0.743905743,9.972836874,-0.821875,-10.20816449,1.716244139,85.72575251 +234.23,50.43281732,-2.56702866,48.5619,0.740429557,9.973280939,-0.885,-10.13640886,1.803182635,85.73327762 +234.24,50.43281738,-2.567027256,48.5711,0.74042956,9.972836873,-0.9478125,-10.06358054,1.888548763,85.74080268 +234.25,50.43281745,-2.567025853,48.5809,0.743905744,9.972170775,-1.008125,-9.98969477,1.972268038,85.74832773 +234.26,50.43281752,-2.567024449,48.5913,0.740429543,9.971948744,-1.066875,-9.914766959,2.054267466,85.75585284 +234.27,50.43281758,-2.567023046,48.6022,0.740429553,9.971948747,-1.126875,-9.838812751,2.134475484,85.7633779 +234.28,50.43281765,-2.567021642,48.6138,0.743905759,9.972170784,-1.188125,-9.761848018,2.212822306,85.77090301 +234.29,50.43281772,-2.567020239,48.626,0.736953369,9.973058922,-1.248125,-9.68388886,2.289239463,85.77842807 +234.3,50.43281778,-2.567018835,48.6388,0.726524777,9.974169093,-1.3065625,-9.604951548,2.363660378,85.78595318 +234.31,50.43281785,-2.567017431,48.6521,0.726524777,9.9741691,-1.365,-9.525052526,2.436020135,85.79347824 +234.32,50.43281791,-2.567016027,48.6661,0.736953374,9.973058943,-1.423125,-9.444208467,2.506255651,85.80100335 +234.33,50.43281798,-2.567014624,48.6806,0.743905769,9.972170819,-1.4796875,-9.362436332,2.574305676,85.80852841 +234.34,50.43281805,-2.56701322,48.6957,0.736953368,9.972170829,-1.535,-9.279753136,2.640110853,85.81605352 +234.35,50.43281811,-2.567011817,48.7113,0.726524783,9.972836939,-1.59,-9.196176184,2.703613828,85.82357858 +234.36,50.43281818,-2.567010413,48.7275,0.723048601,9.973281016,-1.645,-9.11172295,2.764759254,85.83110369 +234.37,50.43281824,-2.567009009,48.7442,0.723048601,9.973058996,-1.6996875,-9.026410966,2.82349373,85.83862875 +234.38,50.43281831,-2.567007606,48.7615,0.723048594,9.973281042,-1.7534375,-8.940258167,2.879766035,85.84615386 +234.39,50.43281837,-2.567006202,48.7793,0.723048598,9.974391222,-1.8065625,-8.853282487,2.933527181,85.85367891 +234.4,50.43281844,-2.567004798,48.7976,0.723048607,9.975279369,-1.8596875,-8.765502087,2.984730299,85.86120403 +234.41,50.4328185,-2.567003394,48.8165,0.723048609,9.975501418,-1.9115625,-8.676935302,3.033330642,85.86872908 +234.42,50.43281857,-2.56700199,48.8359,0.723048604,9.975279401,-1.96125,-8.587600696,3.079285868,85.8762542 +234.43,50.43281863,-2.567000586,48.8557,0.719572409,9.974391286,-2.01,-8.497516777,3.122555869,85.88377925 +234.44,50.4328187,-2.566999182,48.8761,0.709143833,9.973281139,-2.0584375,-8.406702508,3.163103004,85.89130436 +234.45,50.43281876,-2.566997779,48.8969,0.702191446,9.973281158,-2.10625,-8.315176797,3.200891862,85.89882942 +234.46,50.43281882,-2.566996375,48.9182,0.709143827,9.974391343,-2.1534375,-8.222958725,3.2358895,85.90635453 +234.47,50.43281889,-2.566994971,48.94,0.71957241,9.975279496,-2.1996875,-8.130067541,3.268065434,85.91387959 +234.48,50.43281895,-2.566993567,48.9622,0.719572421,9.975279518,-2.245,-8.036522727,3.297391477,85.9214047 +234.49,50.43281902,-2.566992163,48.9849,0.709143845,9.97461344,-2.2896875,-7.942343821,3.323842245,85.92892976 +234.5,50.43281908,-2.566990759,49.008,0.702191461,9.974169396,-2.333125,-7.84755036,3.347394478,85.93645487 +234.51,50.43281914,-2.566989356,49.0316,0.705667666,9.974391452,-2.375,-7.752162284,3.368027777,85.94397993 +234.52,50.43281921,-2.566987951,49.0555,0.705667671,9.974391477,-2.41625,-7.656199416,3.385724094,85.95150504 +234.53,50.43281927,-2.566986548,49.0799,0.702191467,9.974169469,-2.4565625,-7.559681868,3.400468017,85.9590301 +234.54,50.43281933,-2.566985144,49.1047,0.705667654,9.974835594,-2.4946875,-7.46262975,3.412246711,85.96655521 +234.55,50.4328194,-2.56698374,49.1298,0.705667659,9.976167818,-2.5315625,-7.365063346,3.421049864,85.97408027 +234.56,50.43281946,-2.566982336,49.1553,0.702191473,9.976833944,-2.5684375,-7.267002994,3.426869797,85.98160538 +234.57,50.43281952,-2.566980931,49.1812,0.705667671,9.976389904,-2.6046875,-7.168469265,3.429701412,85.98913043 +234.58,50.43281959,-2.566979528,49.2074,0.702191472,9.975723833,-2.6396875,-7.069482612,3.429542302,85.99665549 +234.59,50.43281965,-2.566978123,49.234,0.688286689,9.975501828,-2.6734375,-6.970063835,3.426392581,86.0041806 +234.6,50.43281971,-2.56697672,49.2609,0.688286701,9.975501857,-2.70625,-6.870233617,3.420255,86.01170566 +234.61,50.43281977,-2.566975315,49.2881,0.702191492,9.975501887,-2.738125,-6.770012814,3.411134944,86.01923077 +234.62,50.43281984,-2.566973912,49.3157,0.70219149,9.975501917,-2.768125,-6.669422338,3.399040263,86.02675583 +234.63,50.4328199,-2.566972507,49.3435,0.684810516,9.97572398,-2.79625,-6.568483274,3.383981615,86.03428094 +234.64,50.43281996,-2.566971104,49.3716,0.674381932,9.97639011,-2.8234375,-6.467216651,3.365972061,86.041806 +234.65,50.43282002,-2.566969699,49.4,0.684810512,9.976834207,-2.8496875,-6.36564361,3.34502736,86.04933111 +234.66,50.43282008,-2.566968295,49.4286,0.702191496,9.976612206,-2.8746875,-6.26378535,3.321165673,86.05685617 +234.67,50.43282015,-2.566966891,49.4575,0.702191517,9.976612237,-2.898125,-6.161663186,3.294407971,86.06438128 +234.68,50.43282021,-2.566965487,49.4866,0.684810543,9.976834303,-2.92,-6.059298432,3.264777459,86.07190633 +234.69,50.43282027,-2.566964082,49.5159,0.670905751,9.976612303,-2.9415625,-5.956712401,3.232299976,86.07943145 +234.7,50.43282033,-2.566962679,49.5454,0.667429558,9.976612336,-2.963125,-5.853926638,3.197003943,86.0869565 +234.71,50.43282039,-2.566961274,49.5752,0.667429561,9.976834403,-2.9828125,-5.750962512,3.158920011,86.09448162 +234.72,50.43282045,-2.56695987,49.6051,0.670905749,9.976390371,-2.9996875,-5.647841568,3.11808147,86.10200667 +234.73,50.43282051,-2.566958466,49.6352,0.684810537,9.975946339,-3.015,-5.544585349,3.074523958,86.10953179 +234.74,50.43282057,-2.566957062,49.6654,0.702191531,9.976612473,-3.03,-5.44121534,3.028285347,86.11705684 +234.75,50.43282064,-2.566955658,49.6958,0.702191535,9.977722672,-3.0446875,-5.337753257,2.979406089,86.12458195 +234.76,50.4328207,-2.566954253,49.7263,0.684810557,9.977944739,-3.0578125,-5.234220586,2.927928753,86.13210701 +234.77,50.43282076,-2.566952849,49.757,0.670905787,9.977722742,-3.0684375,-5.130639041,2.873898145,86.13963212 +234.78,50.43282082,-2.566951445,49.7877,0.667429592,9.97794481,-3.0778125,-5.027030224,2.817361535,86.14715718 +234.79,50.43282088,-2.56695004,49.8185,0.667429578,9.977944845,-3.086875,-4.923415734,2.758368081,86.15468229 +234.8,50.43282094,-2.566948636,49.8495,0.667429579,9.977722848,-3.094375,-4.81981723,2.696969294,86.16220735 +234.81,50.432821,-2.566947232,49.8804,0.667429593,9.977944917,-3.0996875,-4.716256369,2.633218744,86.16973246 +234.82,50.43282106,-2.566945827,49.9115,0.667429597,9.97772292,-3.1034375,-4.612754751,2.567172008,86.17725752 +234.83,50.43282112,-2.566944423,49.9425,0.667429598,9.976834823,-3.10625,-4.509333979,2.498886611,86.18478263 +234.84,50.43282118,-2.566943019,49.9736,0.667429605,9.976834859,-3.1084375,-4.406015708,2.428422142,86.19230769 +234.85,50.43282124,-2.566941615,50.0047,0.667429606,9.977723027,-3.109375,-4.302821483,2.355840077,86.1998328 +234.86,50.4328213,-2.56694021,50.0358,0.66742961,9.977945096,-3.1084375,-4.199772903,2.281203673,86.20735785 +234.87,50.43282136,-2.566938806,50.0669,0.663953428,9.977723099,-3.10625,-4.096891398,2.204578074,86.21488297 +234.88,50.43282142,-2.566937402,50.0979,0.650048646,9.978167201,-3.103125,-3.994198454,2.126029972,86.22240802 +234.89,50.43282148,-2.566935997,50.129,0.632667656,9.978833337,-3.098125,-3.891715613,2.045628007,86.22993314 +234.9,50.43282153,-2.566934593,50.1599,0.63266766,9.979055406,-3.09125,-3.78946419,1.963442196,86.23745819 +234.91,50.43282159,-2.566933188,50.1908,0.650048644,9.979055443,-3.0834375,-3.687465613,1.879544216,86.24498331 +234.92,50.43282165,-2.566931784,50.2216,0.663953422,9.978833445,-3.0746875,-3.585741082,1.794007289,86.25250836 +234.93,50.43282171,-2.566930379,50.2523,0.667429621,9.978167381,-3.0646875,-3.484311968,1.706905901,86.26003342 +234.94,50.43282177,-2.566928975,50.2829,0.663953439,9.97772335,-3.053125,-3.383199355,1.618316141,86.26755853 +234.95,50.43282183,-2.566927571,50.3134,0.650048657,9.978167451,-3.04,-3.282424387,1.528315128,86.27508359 +234.96,50.43282189,-2.566926166,50.3437,0.632667678,9.979055619,-3.02625,-3.18200809,1.436981416,86.2826087 +234.97,50.43282194,-2.566924762,50.3739,0.632667692,9.979943787,-3.0115625,-3.081971493,1.344394645,86.29013375 +234.98,50.432822,-2.566923357,50.404,0.650048677,9.980165855,-2.9946875,-2.98233545,1.250635545,86.29765887 +234.99,50.43282206,-2.566921952,50.4338,0.660477258,9.979055723,-2.9765625,-2.88312076,1.15578582,86.30518392 +235,50.43282212,-2.566920548,50.4635,0.650048672,9.978167625,-2.958125,-2.784348165,1.059928319,86.31270904 +235.01,50.43282218,-2.566919144,50.493,0.632667695,9.979055791,-2.9378125,-2.686038233,0.963146465,86.32023409 +235.02,50.43282223,-2.566917739,50.5223,0.632667693,9.980165991,-2.915,-2.588211591,0.86552477,86.32775921 +235.03,50.43282229,-2.566916334,50.5513,0.646572487,9.980166024,-2.8915625,-2.490888636,0.767148318,86.33528426 +235.04,50.43282235,-2.56691493,50.5801,0.646572498,9.980166056,-2.868125,-2.394089651,0.668102937,86.34280937 +235.05,50.43282241,-2.566913525,50.6087,0.632667713,9.980388122,-2.8428125,-2.297834861,0.568474916,86.35033443 +235.06,50.43282246,-2.56691212,50.637,0.629191513,9.979944088,-2.815,-2.202144378,0.468351172,86.35785954 +235.07,50.43282252,-2.566910716,50.665,0.632667712,9.979278021,-2.7865625,-2.107038197,0.367819023,86.3653846 +235.08,50.43282258,-2.566909311,50.6927,0.629191525,9.979056019,-2.758125,-2.0125362,0.266966132,86.37290971 +235.09,50.43282263,-2.566907907,50.7202,0.62919153,9.979056049,-2.728125,-1.918658096,0.165880449,86.38043477 +235.1,50.43282269,-2.566906502,50.7473,0.63266772,9.979278113,-2.69625,-1.825423482,0.064650151,86.38795988 +235.11,50.43282275,-2.566905098,50.7741,0.629191522,9.979944243,-2.6634375,-1.732851837,-0.036636583,86.39548494 +235.12,50.4328228,-2.566903693,50.8006,0.629191529,9.980388338,-2.6296875,-1.64096247,-0.137891289,86.40301005 +235.13,50.43282286,-2.566902288,50.8267,0.632667726,9.980166334,-2.5946875,-1.549774632,-0.239025845,86.41053511 +235.14,50.43282292,-2.566900884,50.8525,0.625715335,9.980388396,-2.558125,-1.459307347,-0.339951903,86.41806022 +235.15,50.43282297,-2.566899479,50.8779,0.615286761,9.981276555,-2.52,-1.369579406,-0.440581569,86.42558527 +235.16,50.43282303,-2.566898074,50.9029,0.61528677,9.981276583,-2.4815625,-1.280609717,-0.54082701,86.43311039 +235.17,50.43282308,-2.566896669,50.9275,0.625715353,9.980388477,-2.443125,-1.19241673,-0.640600849,86.44063544 +235.18,50.43282314,-2.566895265,50.9518,0.63266774,9.980388503,-2.403125,-1.105018951,-0.739816054,86.44816056 +235.19,50.4328232,-2.56689386,50.9756,0.625715347,9.981276661,-2.36125,-1.018434543,-0.838386109,86.45568561 +235.2,50.43282325,-2.566892455,50.999,0.615286759,9.981276686,-2.3184375,-0.932681612,-0.936225127,86.46321073 +235.21,50.43282331,-2.56689105,51.022,0.611810567,9.980388578,-2.275,-0.847778147,-1.033247737,86.47073578 +235.22,50.43282336,-2.566889646,51.0445,0.611810575,9.980388601,-2.23125,-0.763741797,-1.129369314,86.47826089 +235.23,50.43282342,-2.566888241,51.0666,0.61181058,9.981498789,-2.1865625,-0.680590151,-1.224506091,86.48578595 +235.24,50.43282347,-2.566886836,51.0883,0.611810573,9.982386945,-2.1396875,-0.598340513,-1.318575104,86.49331106 +235.25,50.43282353,-2.566885431,51.1094,0.611810573,9.982609,-2.091875,-0.517010128,-1.411494248,86.50083612 +235.26,50.43282358,-2.566884026,51.1301,0.611810586,9.982386988,-2.045,-0.436616013,-1.503182564,86.50836123 +235.27,50.43282364,-2.566882621,51.1503,0.611810588,9.981498874,-1.9978125,-0.357174842,-1.593560067,86.51588629 +235.28,50.43282369,-2.566881216,51.1701,0.608334382,9.980388728,-1.9478125,-0.278703287,-1.682548033,86.52341134 +235.29,50.43282375,-2.566879812,51.1893,0.597905795,9.980388747,-1.895,-0.201217678,-1.770068711,86.53093646 +235.3,50.4328238,-2.566878407,51.208,0.590953412,9.98149893,-1.841875,-0.124734287,-1.856045899,86.53846151 +235.31,50.43282385,-2.566877002,51.2261,0.597905805,9.98238708,-1.79,-0.049268985,-1.940404595,86.54598663 +235.32,50.43282391,-2.566875597,51.2438,0.608334393,9.982609129,-1.738125,0.025162416,-2.023071175,86.55351168 +235.33,50.43282396,-2.566874192,51.2609,0.608334399,9.982609144,-1.6846875,0.098544329,-2.103973675,86.56103679 +235.34,50.43282402,-2.566872787,51.2775,0.597905812,9.982609159,-1.63,0.170861515,-2.183041449,86.56856185 +235.35,50.43282407,-2.566871382,51.2935,0.590953411,9.982609172,-1.5746875,0.24209879,-2.260205572,86.57608696 +235.36,50.43282412,-2.566869977,51.309,0.594429607,9.982609186,-1.5184375,0.312241372,-2.335398777,86.58361202 +235.37,50.43282418,-2.566868572,51.3239,0.594429622,9.982609198,-1.4615625,0.381274536,-2.40855546,86.59113713 +235.38,50.43282423,-2.566867167,51.3382,0.590953433,9.982387176,-1.405,0.4491839,-2.479611853,86.59866219 +235.39,50.43282428,-2.566865762,51.352,0.594429622,9.981721087,-1.348125,0.515955255,-2.548506017,86.6061873 +235.4,50.43282434,-2.566864357,51.3652,0.594429617,9.981499063,-1.2896875,0.581574679,-2.615177792,86.61371236 +235.41,50.43282439,-2.566862953,51.3778,0.590953426,9.982609237,-1.23,0.646028478,-2.679569138,86.62123747 +235.42,50.43282444,-2.566861547,51.3898,0.594429626,9.98371941,-1.17,0.709303187,-2.741623848,86.62876253 +235.43,50.4328245,-2.566860142,51.4012,0.590953421,9.983497383,-1.1096875,0.77138557,-2.801287834,86.63628764 +235.44,50.43282455,-2.566858737,51.412,0.573572433,9.982831289,-1.0484375,0.832262622,-2.858509014,86.64381269 +235.45,50.4328246,-2.566857332,51.4222,0.563143849,9.982609262,-0.986875,0.891921738,-2.913237599,86.65133781 +235.46,50.43282465,-2.566855927,51.4317,0.573572446,9.982609267,-0.9265625,0.95035037,-2.965425747,86.65886286 +235.47,50.4328247,-2.566854522,51.4407,0.590953434,9.98260927,-0.8665625,1.007536371,-3.015028021,86.66638798 +235.48,50.43282476,-2.566853117,51.4491,0.590953437,9.982609271,-0.804375,1.063467766,-3.062001106,86.67391303 +235.49,50.43282481,-2.566851712,51.4568,0.573572448,9.982831305,-0.7403125,1.118132924,-3.106304094,86.68143815 +235.5,50.43282486,-2.566850307,51.4639,0.563143853,9.983497405,-0.676875,1.171520329,-3.147898366,86.6889632 +235.51,50.43282491,-2.566848902,51.4703,0.573572451,9.983719438,-0.615,1.223618923,-3.186747597,86.69648831 +235.52,50.43282496,-2.566847496,51.4762,0.590953446,9.982831303,-0.553125,1.274417762,-3.222817983,86.70401337 +235.53,50.43282502,-2.566846092,51.4814,0.59095344,9.982609267,-0.4896875,1.323906304,-3.256077954,86.71153848 +235.54,50.43282507,-2.566844687,51.486,0.573572442,9.983941462,-0.425,1.372074179,-3.286498633,86.71906354 +235.55,50.43282512,-2.566843281,51.4899,0.559667658,9.984607557,-0.36,1.418911301,-3.314053433,86.72658865 +235.56,50.43282517,-2.566841876,51.4932,0.556191477,9.983719419,-0.2953125,1.464407932,-3.338718292,86.73411371 +235.57,50.43282522,-2.566840471,51.4958,0.556191479,9.98283128,-0.2315625,1.508554559,-3.360471781,86.74163882 +235.58,50.43282527,-2.566839066,51.4978,0.559667668,9.982831272,-0.168125,1.551341958,-3.379294877,86.74916388 +235.59,50.43282532,-2.566837661,51.4992,0.573572454,9.983719396,-0.1034375,1.592761135,-3.395171136,86.75668899 +235.6,50.43282537,-2.566836256,51.4999,0.590953441,9.984829552,-0.0384375,1.632803551,-3.408086808,86.76421405 +235.61,50.43282543,-2.56683485,51.4999,0.590953437,9.985051574,0.025,1.671460784,-3.418030548,86.77173916 +235.62,50.43282548,-2.566833445,51.4994,0.573572447,9.984829529,0.0884375,1.708724813,-3.424993704,86.77926421 +235.63,50.43282553,-2.56683204,51.4982,0.559667666,9.985051549,0.15375,1.744587731,-3.428970261,86.78678927 +235.64,50.43282558,-2.566830634,51.4963,0.556191477,9.984829502,0.2196875,1.779042204,-3.429956665,86.79431438 +235.65,50.43282563,-2.566829229,51.4938,0.55619147,9.983719323,0.2846875,1.812080899,-3.427952115,86.80183944 +235.66,50.43282568,-2.566827824,51.4906,0.556191457,9.983053208,0.3484375,1.843696997,-3.422958329,86.80936455 +235.67,50.43282573,-2.566826419,51.4868,0.556191461,9.983719291,0.4115625,1.873883908,-3.414979663,86.81688961 +235.68,50.43282578,-2.566825014,51.4824,0.556191476,9.984829439,0.475,1.902635274,-3.404023105,86.82441472 +235.69,50.43282583,-2.566823608,51.4773,0.556191476,9.985051453,0.5384375,1.929945078,-3.390098168,86.83193978 +235.7,50.43282588,-2.566822203,51.4716,0.552715263,9.984829401,0.6015625,1.955807706,-3.373217055,86.83946489 +235.71,50.43282593,-2.566820798,51.4653,0.53881047,9.985273448,0.665,1.980217656,-3.353394434,86.84698995 +235.72,50.43282598,-2.566819392,51.4583,0.521429497,9.985939527,0.728125,2.003169887,-3.330647552,86.85451506 +235.73,50.43282602,-2.566817987,51.4507,0.521429503,9.985939505,0.79,2.024659643,-3.304996346,86.86204011 +235.74,50.43282607,-2.566816581,51.4425,0.538810481,9.985051349,0.8515625,2.044682341,-3.276463105,86.86956523 +235.75,50.43282612,-2.566815176,51.4337,0.552715268,9.983941159,0.9134375,2.063233855,-3.245072753,86.87709028 +235.76,50.43282617,-2.566813771,51.4242,0.556191471,9.983941133,0.975,2.080310346,-3.210852676,86.8846154 +235.77,50.43282622,-2.566812366,51.4142,0.556191464,9.985051273,1.0365625,2.095908148,-3.17383267,86.89214045 +235.78,50.43282627,-2.56681096,51.4035,0.552715252,9.985939379,1.098125,2.110024052,-3.134045048,86.89966557 +235.79,50.43282632,-2.566809555,51.3922,0.538810468,9.986161384,1.158125,2.122655193,-3.091524475,86.90719062 +235.8,50.43282637,-2.566808149,51.3803,0.521429497,9.986161355,1.2165625,2.133798764,-3.046308021,86.91471573 +235.81,50.43282641,-2.566806744,51.3679,0.521429499,9.986161325,1.275,2.143452587,-2.998435163,86.92224079 +235.82,50.43282646,-2.566805338,51.3548,0.538810473,9.986161295,1.3334375,2.1516146,-2.947947612,86.9297659 +235.83,50.43282651,-2.566803933,51.3412,0.549239063,9.986161263,1.3915625,2.158283084,-2.894889428,86.93729096 +235.84,50.43282656,-2.566802527,51.327,0.538810482,9.986161231,1.45,2.163456663,-2.83930685,86.94481607 +235.85,50.43282661,-2.566801122,51.3122,0.521429501,9.986161199,1.5078125,2.167134193,-2.781248349,86.95234113 +235.86,50.43282665,-2.566799716,51.2968,0.521429486,9.986161165,1.563125,2.169314985,-2.720764575,86.95986624 +235.87,50.4328267,-2.566798311,51.2809,0.535334257,9.985939096,1.616875,2.169998581,-2.65790824,86.9673913 +235.88,50.43282675,-2.566796905,51.2645,0.53533426,9.985272961,1.6715625,2.169184809,-2.592734176,86.97491641 +235.89,50.4328268,-2.5667955,51.2475,0.521429487,9.984828858,1.7265625,2.166873841,-2.525299221,86.98244147 +235.9,50.43282684,-2.566794095,51.2299,0.521429487,9.985272887,1.7796875,2.163066135,-2.45566216,86.98996658 +235.91,50.43282689,-2.566792689,51.2119,0.535334265,9.985938949,1.8315625,2.157762552,-2.383883669,86.99749163 +235.92,50.43282694,-2.566791284,51.1933,0.535334263,9.986160943,1.8834375,2.150964121,-2.310026487,87.00501675 +235.93,50.43282699,-2.566789878,51.1742,0.517953286,9.986160903,1.9346875,2.142672333,-2.234154842,87.0125418 +235.94,50.43282703,-2.566788473,51.1546,0.504048497,9.986160862,1.985,2.132888907,-2.156335027,87.02006692 +235.95,50.43282708,-2.566787067,51.1345,0.504048486,9.986382854,2.0346875,2.121615847,-2.076634879,87.02759197 +235.96,50.43282712,-2.566785662,51.1139,0.514477075,9.987048912,2.083125,2.108855504,-1.99512384,87.03511709 +235.97,50.43282717,-2.566784256,51.0928,0.521429478,9.987492935,2.13,2.09461057,-1.911873015,87.04264214 +235.98,50.43282722,-2.56678285,51.0713,0.517953284,9.987048825,2.1765625,2.078884082,-1.826955055,87.0501672 +235.99,50.43282726,-2.566781445,51.0493,0.517953269,9.986382682,2.223125,2.061679191,-1.740443929,87.05769231 +236,50.43282731,-2.566780039,51.0268,0.521429449,9.986382638,2.2678125,2.042999564,-1.652415094,87.06521737 +236.01,50.43282736,-2.566778634,51.0039,0.514477058,9.987048692,2.31,2.022849154,-1.562945328,87.07274248 +236.02,50.4328274,-2.566777228,50.9806,0.504048481,9.987492711,2.351875,2.001232086,-1.472112724,87.08026753 +236.03,50.43282745,-2.566775822,50.9569,0.500572285,9.987270631,2.3946875,1.978152888,-1.379996352,87.08779265 +236.04,50.43282749,-2.566774417,50.9327,0.500572274,9.987270584,2.43625,1.953616371,-1.286676596,87.0953177 +236.05,50.43282754,-2.566773011,50.9081,0.500572272,9.98749257,2.4746875,1.927627693,-1.192234874,87.10284282 +236.06,50.43282758,-2.566771605,50.8832,0.500572279,9.987270488,2.511875,1.900192297,-1.096753462,87.11036787 +236.07,50.43282763,-2.5667702,50.8579,0.500572277,9.987270439,2.55,1.871315854,-1.00031567,87.11789299 +236.08,50.43282767,-2.566768794,50.8322,0.500572266,9.987492423,2.5878125,1.841004439,-0.903005607,87.12541804 +236.09,50.43282772,-2.566767388,50.8061,0.500572264,9.98727034,2.623125,1.809264353,-0.804908127,87.13294315 +236.1,50.43282776,-2.566765983,50.7797,0.500572273,9.987492323,2.65625,1.776102243,-0.706108775,87.14046821 +236.11,50.43282781,-2.566764577,50.753,0.500572277,9.988380403,2.6884375,1.741525043,-0.606693607,87.14799332 +236.12,50.43282785,-2.566763171,50.7259,0.500572269,9.988380351,2.72,1.70553997,-0.506749428,87.15551838 +236.13,50.4328279,-2.566761765,50.6986,0.500572255,9.987492166,2.75125,1.668154531,-0.406363383,87.16304349 +236.14,50.43282794,-2.56676036,50.6709,0.500572253,9.987492114,2.7815625,1.629376518,-0.305622964,87.17056855 +236.15,50.43282799,-2.566758954,50.6429,0.500572262,9.988380193,2.8096875,1.58921401,-0.204616063,87.17809366 +236.16,50.43282803,-2.566757548,50.6147,0.49709607,9.988380139,2.8365625,1.547675487,-0.103430685,87.18561872 +236.17,50.43282808,-2.566756142,50.5862,0.486667469,9.987491952,2.863125,1.504769542,-0.002155123,87.19314383 +236.18,50.43282812,-2.566754737,50.5574,0.479715056,9.987491899,2.8878125,1.460505172,0.099122272,87.20066889 +236.19,50.43282816,-2.566753331,50.5284,0.483191248,9.988379977,2.9096875,1.414891601,0.200313264,87.208194 +236.2,50.43282821,-2.566751925,50.4992,0.483191266,9.988379923,2.9303125,1.36793834,0.30132962,87.21571905 +236.21,50.43282825,-2.566750519,50.4698,0.479715076,9.987491736,2.9515625,1.319655244,0.402083159,87.22324417 +236.22,50.43282829,-2.566749114,50.4402,0.483191253,9.98749168,2.9728125,1.27005234,0.502486106,87.23076922 +236.23,50.43282834,-2.566747708,50.4103,0.483191239,9.98860179,2.99125,1.219140055,0.602450855,87.23829434 +236.24,50.43282838,-2.566746302,50.3803,0.479715054,9.989489866,3.0065625,1.166928932,0.701890259,87.24581939 +236.25,50.43282842,-2.566744896,50.3502,0.483191264,9.989489809,3.021875,1.113429972,0.800717571,87.25334451 +236.26,50.43282847,-2.56674349,50.3199,0.483191264,9.98860162,3.038125,1.05865429,0.898846735,87.26086956 +236.27,50.43282851,-2.566742084,50.2894,0.479715056,9.987491398,3.0528125,1.002613345,0.996192035,87.26839467 +236.28,50.43282855,-2.566740679,50.2588,0.483191239,9.987491341,3.064375,0.945318826,1.092668617,87.27591973 +236.29,50.4328286,-2.566739273,50.2281,0.479715043,9.988601449,3.0734375,0.88678265,1.188192427,87.28344484 +236.3,50.43282864,-2.566737867,50.1973,0.462334074,9.989489525,3.0815625,0.827017136,1.2826801,87.2909699 +236.31,50.43282868,-2.566736461,50.1665,0.451905485,9.989711502,3.0896875,0.766034775,1.376049245,87.29849495 +236.32,50.43282872,-2.566735055,50.1355,0.462334052,9.989489412,3.0965625,0.70384817,1.468218445,87.30602007 +236.33,50.43282876,-2.566733649,50.1045,0.479715022,9.988601222,3.10125,0.640470443,1.55910737,87.31354512 +236.34,50.43282881,-2.566732243,50.0735,0.479715038,9.987491,3.105,0.575914716,1.648636667,87.32107024 +236.35,50.43282885,-2.566730838,50.0424,0.462334065,9.987490942,3.108125,0.510194623,1.736728412,87.32859529 +236.36,50.43282889,-2.566729432,50.0113,0.451905463,9.988601049,3.1096875,0.443323745,1.823305658,87.33612041 +236.37,50.43282893,-2.566728026,49.9802,0.462334043,9.989711157,3.1096875,0.375316061,1.908292946,87.34364546 +236.38,50.43282897,-2.56672662,49.9491,0.47971503,9.990599232,3.108125,0.306185838,1.991616193,87.35117057 +236.39,50.43282902,-2.566725214,49.918,0.479715035,9.990821208,3.1046875,0.235947515,2.07320269,87.35869563 +236.4,50.43282906,-2.566723807,49.887,0.462334045,9.989710985,3.1,0.164615702,2.152981391,87.36622074 +236.41,50.4328291,-2.566722402,49.856,0.448429247,9.988600763,3.0946875,0.092205353,2.230882623,87.3737458 +236.42,50.43282914,-2.566720996,49.8251,0.444953049,9.988822739,3.088125,0.018731537,2.306838435,87.38127091 +236.43,50.43282918,-2.56671959,49.7942,0.444953058,9.989488781,3.0796875,-0.05579039,2.380782706,87.38879597 +236.44,50.43282922,-2.566718184,49.7635,0.444953062,9.989710757,3.0696875,-0.131344845,2.452650923,87.39632108 +236.45,50.43282926,-2.566716778,49.7328,0.444953053,9.989710702,3.0584375,-0.207916013,2.522380345,87.40384614 +236.46,50.4328293,-2.566715372,49.7023,0.44495304,9.989710646,3.04625,-0.285487967,2.589910239,87.41137125 +236.47,50.43282934,-2.566713966,49.6719,0.444953038,9.98971059,3.0334375,-0.364044491,2.655181706,87.41889631 +236.48,50.43282938,-2.56671256,49.6416,0.444953047,9.989710534,3.0196875,-0.4435692,2.718137792,87.42642142 +236.49,50.43282942,-2.566711154,49.6115,0.444953051,9.989710478,3.004375,-0.524045419,2.77872361,87.43394647 +236.5,50.43282946,-2.566709748,49.5815,0.444953045,9.989710423,2.9865625,-0.60545642,2.836886389,87.44147159 +236.51,50.4328295,-2.566708342,49.5517,0.444953038,9.989710368,2.9665625,-0.687785184,2.892575309,87.44899664 +236.52,50.43282954,-2.566706936,49.5222,0.444953041,9.989932346,2.9465625,-0.771014465,2.945741896,87.45652176 +236.53,50.43282958,-2.56670553,49.4928,0.444953045,9.990820425,2.9265625,-0.855126904,2.996339742,87.46404681 +236.54,50.43282962,-2.566704124,49.4636,0.444953043,9.991930536,2.904375,-0.940104968,3.044324728,87.47157193 +236.55,50.43282966,-2.566702717,49.4347,0.444953033,9.991930482,2.88,-1.025930837,3.089654971,87.47909698 +236.56,50.4328297,-2.566701311,49.406,0.444953019,9.990820263,2.855,-1.112586693,3.132291053,87.48662209 +236.57,50.43282974,-2.566699905,49.3776,0.444953017,9.989932078,2.8296875,-1.200054372,3.17219573,87.49414715 +236.58,50.43282978,-2.566698499,49.3494,0.444953027,9.989709993,2.8028125,-1.288315656,3.209334166,87.50167226 +236.59,50.43282982,-2.566697093,49.3215,0.444953031,9.989709941,2.773125,-1.377352037,3.243674048,87.50919732 +236.6,50.43282986,-2.566695687,49.2939,0.444953023,9.98970989,2.741875,-1.467144951,3.275185409,87.51672243 +236.61,50.4328299,-2.566694281,49.2667,0.441476816,9.989709838,2.7115625,-1.557675663,3.30384069,87.52424749 +236.62,50.43282994,-2.566692875,49.2397,0.427572038,9.989931821,2.68125,-1.648925323,3.329615024,87.5317726 +236.63,50.43282998,-2.566691469,49.213,0.410191072,9.990819904,2.6478125,-1.740874736,3.352485895,87.53929766 +236.64,50.43283001,-2.566690063,49.1867,0.410191073,9.99193002,2.6115625,-1.833504822,3.372433364,87.54682277 +236.65,50.43283005,-2.566688656,49.1608,0.427572037,9.991929971,2.5753125,-1.92679616,3.389439954,87.55434783 +236.66,50.43283009,-2.56668725,49.1352,0.441476805,9.991041791,2.5396875,-2.020729324,3.403490942,87.56187288 +236.67,50.43283013,-2.566685844,49.11,0.441476803,9.991041743,2.503125,-2.115284606,3.414574066,87.56939799 +236.68,50.43283017,-2.566684438,49.0851,0.42757203,9.991929829,2.4646875,-2.210442411,3.422679585,87.57692305 +236.69,50.43283021,-2.566683031,49.0607,0.410191058,9.991929783,2.4246875,-2.306182742,3.42780051,87.58444816 +236.7,50.43283024,-2.566681625,49.0366,0.410191056,9.990819572,2.3834375,-2.402485603,3.429932314,87.59197322 +236.71,50.43283028,-2.566680219,49.013,0.424095829,9.990153428,2.34125,-2.499330997,3.429073164,87.59949833 +236.72,50.43283032,-2.566678813,48.9898,0.424095819,9.990819483,2.2984375,-2.596698586,3.425223804,87.60702339 +236.73,50.43283036,-2.566677407,48.967,0.410191041,9.991929604,2.2546875,-2.694568028,3.418387616,87.6145485 +236.74,50.43283039,-2.566676,48.9447,0.406714859,9.991929562,2.2096875,-2.792918983,3.408570557,87.62207356 +236.75,50.43283043,-2.566674594,48.9228,0.410191056,9.991041388,2.1634375,-2.891730884,3.395781165,87.62959867 +236.76,50.43283047,-2.566673188,48.9014,0.406714846,9.991041347,2.1165625,-2.990983045,3.380030555,87.63712373 +236.77,50.4328305,-2.566671782,48.8805,0.406714833,9.991929438,2.0696875,-3.090654725,3.361332593,87.64464884 +236.78,50.43283054,-2.566670375,48.86,0.410191034,9.992151431,2.0215625,-3.190725185,3.339703436,87.6521739 +236.79,50.43283058,-2.566668969,48.84,0.406714853,9.991929359,1.97125,-3.291173452,3.315161992,87.65969901 +236.8,50.43283061,-2.566667563,48.8206,0.406714856,9.992151354,1.9203125,-3.391978616,3.287729747,87.66722406 +236.81,50.43283065,-2.566666156,48.8016,0.410191044,9.991929284,1.87,-3.493119647,3.257430478,87.67474918 +236.82,50.43283069,-2.56666475,48.7832,0.406714836,9.991041116,1.819375,-3.594575289,3.224290771,87.68227423 +236.83,50.43283072,-2.566663344,48.7652,0.406714824,9.99104108,1.7665625,-3.696324457,3.188339388,87.68979935 +236.84,50.43283076,-2.566661938,48.7478,0.410191018,9.991929177,1.7115625,-3.798345895,3.149607671,87.6973244 +236.85,50.4328308,-2.566660531,48.731,0.403238637,9.992151176,1.656875,-3.900618289,3.108129537,87.70484951 +236.86,50.43283083,-2.566659125,48.7147,0.392810058,9.99192911,1.603125,-4.003120266,3.063941027,87.71237457 +236.87,50.43283087,-2.566657719,48.6989,0.389333862,9.992151111,1.548125,-4.1058304,3.017080699,87.71989968 +236.88,50.4328309,-2.566656312,48.6837,0.389333854,9.99215108,1.49125,-4.208727317,2.967589464,87.72742474 +236.89,50.43283094,-2.566654906,48.6691,0.392810044,9.991929016,1.4334375,-4.311789475,2.915510408,87.73494985 +236.9,50.43283097,-2.5666535,48.655,0.403238634,9.99215102,1.375,-4.414995332,2.860889024,87.74247491 +236.91,50.43283101,-2.566652093,48.6416,0.410191033,9.992150992,1.316875,-4.518323343,2.803772867,87.75000002 +236.92,50.43283105,-2.566650687,48.6287,0.403238648,9.991928931,1.26,-4.621751965,2.744211841,87.75752508 +236.93,50.43283108,-2.566649281,48.6164,0.389333861,9.99237297,1.2028125,-4.725259598,2.682257743,87.76505019 +236.94,50.43283112,-2.566647874,48.6046,0.375429063,9.993039043,1.143125,-4.828824584,2.617964716,87.77257525 +236.95,50.43283115,-2.566646468,48.5935,0.368476665,9.993039019,1.0815625,-4.932425323,2.551388797,87.78010036 +236.96,50.43283118,-2.566645061,48.583,0.375429066,9.992372896,1.02,-5.036040214,2.482588025,87.78762542 +236.97,50.43283122,-2.566643655,48.5731,0.385857667,9.99215084,0.9584375,-5.139647542,2.411622389,87.79515053 +236.98,50.43283125,-2.566642249,48.5638,0.389333867,9.993260984,0.8965625,-5.243225706,2.338553769,87.80267558 +236.99,50.43283129,-2.566640842,48.5552,0.389333853,9.994149095,0.835,-5.346753049,2.263445877,87.8102007 +237,50.43283132,-2.566639435,48.5471,0.389333835,9.993260943,0.7734375,-5.450208028,2.186364261,87.81772575 +237.01,50.43283136,-2.566638029,48.5397,0.389333834,9.992150759,0.71125,-5.553568984,2.107376127,87.82525081 +237.02,50.43283139,-2.566636623,48.5329,0.385857656,9.992150741,0.6484375,-5.656814317,2.026550289,87.83277592 +237.03,50.43283143,-2.566635216,48.5267,0.375429083,9.992150724,0.5846875,-5.759922484,1.943957277,87.84030098 +237.04,50.43283146,-2.56663381,48.5212,0.368476687,9.992150708,0.5203125,-5.862871941,1.859669112,87.84782609 +237.05,50.43283149,-2.566632404,48.5163,0.371952867,9.993260859,0.4565625,-5.965641204,1.773759304,87.85535115 +237.06,50.43283153,-2.566630997,48.5121,0.371952855,9.994148977,0.3934375,-6.068208785,1.68630274,87.86287626 +237.07,50.43283156,-2.56662959,48.5084,0.368476666,9.993260832,0.3296875,-6.170553314,1.59737568,87.87040132 +237.08,50.43283159,-2.566628184,48.5055,0.371952877,9.992372688,0.265,-6.272653362,1.507055701,87.87792643 +237.09,50.43283163,-2.566626778,48.5031,0.371952879,9.993260809,0.2003125,-6.374487672,1.41542153,87.88545148 +237.1,50.43283166,-2.566625371,48.5015,0.36847667,9.994148932,0.1365625,-6.47603493,1.322553093,87.8929766 +237.11,50.43283169,-2.566623964,48.5004,0.371952855,9.993260791,0.0734375,-6.577273879,1.228531349,87.90050165 +237.12,50.43283173,-2.566622558,48.5,0.368476666,9.992150619,0.009375,-6.678183493,1.133438346,87.90802677 +237.13,50.43283176,-2.566621152,48.5002,0.3545719,9.992372646,-0.05625,-6.778742628,1.03735699,87.91555182 +237.14,50.43283179,-2.566619745,48.5011,0.354571906,9.993260773,-0.121875,-6.878930314,0.940370992,87.92307693 +237.15,50.43283182,-2.566618339,48.5027,0.36847669,9.9941489,-0.18625,-6.978725582,0.842564976,87.93060199 +237.16,50.43283186,-2.566616932,48.5048,0.368476691,9.994592962,-0.25,-7.078107633,0.744024257,87.9381271 +237.17,50.43283189,-2.566615525,48.5077,0.351095703,9.994148894,-0.31375,-7.177055668,0.64483472,87.94565216 +237.18,50.43283192,-2.566614119,48.5111,0.340667105,9.993482794,-0.3778125,-7.275549061,0.545082883,87.95317727 +237.19,50.43283195,-2.566612712,48.5152,0.351095694,9.993260761,-0.4421875,-7.373567243,0.444855777,87.96070233 +237.2,50.43283198,-2.566611306,48.52,0.368476678,9.993260761,-0.50625,-7.471089759,0.344240664,87.96822744 +237.21,50.43283202,-2.566609899,48.5253,0.368476681,9.993260763,-0.57,-7.568096212,0.243325435,87.9757525 +237.22,50.43283205,-2.566608493,48.5314,0.351095706,9.993260765,-0.6334375,-7.664566319,0.142197983,87.98327761 +237.23,50.43283208,-2.566607086,48.538,0.337190929,9.993482802,-0.69625,-7.760480027,0.040946543,87.99080267 +237.24,50.43283211,-2.56660568,48.5453,0.33371473,9.994148906,-0.7584375,-7.855817167,-0.060340592,87.99832778 +237.25,50.43283214,-2.566604273,48.5532,0.337190912,9.994592978,-0.82,-7.950557973,-0.16157513,88.00585284 +237.26,50.43283217,-2.566602866,48.5617,0.351095695,9.994148919,-0.8815625,-8.044682563,-0.262668777,88.01337795 +237.27,50.4328322,-2.56660146,48.5708,0.368476686,9.993482827,-0.9434375,-8.138171284,-0.363533356,88.020903 +237.28,50.43283224,-2.566600053,48.5806,0.368476688,9.993482835,-1.005,-8.231004656,-0.464080917,88.02842812 +237.29,50.43283227,-2.566598647,48.5909,0.351095698,9.994148944,-1.06625,-8.323163313,-0.564223798,88.03595317 +237.3,50.4328323,-2.56659724,48.6019,0.337190906,9.994593021,-1.126875,-8.414627947,-0.663874681,88.04347829 +237.31,50.43283233,-2.566595833,48.6135,0.333714718,9.994371,-1.18625,-8.505379419,-0.762946647,88.05100334 +237.32,50.43283236,-2.566594427,48.6256,0.333714734,9.994593045,-1.245,-8.595398939,-0.861353294,88.05852845 +237.33,50.43283239,-2.56659302,48.6384,0.333714741,9.995481191,-1.3034375,-8.684667539,-0.959008851,88.06605351 +237.34,50.43283242,-2.566591613,48.6517,0.333714744,9.995481206,-1.3615625,-8.773166658,-1.055828176,88.07357862 +237.35,50.43283245,-2.566590206,48.6656,0.333714745,9.994371056,-1.42,-8.860877787,-1.151726757,88.08110368 +237.36,50.43283248,-2.5665888,48.6801,0.333714735,9.99348294,-1.478125,-8.94778265,-1.246621001,88.08862874 +237.37,50.43283251,-2.566587393,48.6952,0.333714724,9.993482957,-1.5346875,-9.033863085,-1.340428173,88.09615385 +237.38,50.43283254,-2.566585987,48.7108,0.333714727,9.994149074,-1.59,-9.119101042,-1.43306651,88.1036789 +237.39,50.43283257,-2.56658458,48.727,0.333714737,9.994593159,-1.645,-9.203478817,-1.524455169,88.11120402 +237.4,50.4328326,-2.566583173,48.7437,0.333714747,9.994371145,-1.6996875,-9.286978707,-1.614514509,88.11872907 +237.41,50.43283263,-2.566581767,48.761,0.330238556,9.9945932,-1.753125,-9.36958335,-1.703165919,88.12625419 +237.42,50.43283266,-2.56658036,48.7788,0.316333773,9.995481354,-1.805,-9.451275501,-1.790332166,88.13377924 +237.43,50.43283269,-2.566578953,48.7971,0.298952794,9.995481377,-1.8565625,-9.53203797,-1.875937217,88.14130436 +237.44,50.43283271,-2.566577546,48.8159,0.298952788,9.994593268,-1.9084375,-9.611854027,-1.959906417,88.14882941 +237.45,50.43283274,-2.56657614,48.8353,0.316333754,9.994593293,-1.9596875,-9.690707,-2.042166597,88.15635452 +237.46,50.43283277,-2.566574733,48.8551,0.330238537,9.99548145,-2.0096875,-9.76858033,-2.122645911,88.16387958 +237.47,50.4328328,-2.566573326,48.8755,0.333714747,9.995481475,-2.058125,-9.845457801,-2.201274284,88.17140469 +237.48,50.43283283,-2.566571919,48.8963,0.333714755,9.994593369,-2.105,-9.921323372,-2.277983077,88.17892975 +237.49,50.43283286,-2.566570513,48.9176,0.33023856,9.994593395,-2.1515625,-9.996161171,-2.352705483,88.18645486 +237.5,50.43283289,-2.566569106,48.9393,0.316333772,9.995481555,-2.198125,-10.06995561,-2.425376241,88.19397992 +237.51,50.43283292,-2.566567699,48.9616,0.298952781,9.995481585,-2.2434375,-10.14269123,-2.495932097,88.20150503 +237.52,50.43283294,-2.566566292,48.9842,0.298952783,9.994593483,-2.2878125,-10.2143529,-2.564311401,88.20903009 +237.53,50.43283297,-2.566564886,49.0073,0.316333775,9.994593513,-2.331875,-10.2849256,-2.630454623,88.2165552 +237.54,50.432833,-2.566563479,49.0309,0.32676237,9.995481676,-2.374375,-10.35439461,-2.694304066,88.22408026 +237.55,50.43283303,-2.566562072,49.0548,0.316333786,9.995481708,-2.4146875,-10.42274544,-2.755803981,88.23160537 +237.56,50.43283306,-2.566560665,49.0792,0.298952809,9.994593608,-2.4534375,-10.48996376,-2.814900853,88.23913042 +237.57,50.43283308,-2.566559259,49.1039,0.295476603,9.994593641,-2.4915625,-10.55603559,-2.871543059,88.24665554 +237.58,50.43283311,-2.566557852,49.129,0.298952789,9.995481806,-2.53,-10.62094712,-2.925681269,88.25418059 +237.59,50.43283314,-2.566556445,49.1545,0.295476597,9.995703873,-2.568125,-10.68468478,-2.977268211,88.26170571 +237.6,50.43283316,-2.566555038,49.1804,0.298952803,9.995481874,-2.6046875,-10.74723527,-3.02625891,88.26923076 +237.61,50.43283319,-2.566553632,49.2066,0.312857598,9.995703943,-2.6396875,-10.80858553,-3.07261068,88.27675588 +237.62,50.43283322,-2.566552224,49.2332,0.312857611,9.995703979,-2.673125,-10.86872272,-3.116283128,88.28428093 +237.63,50.43283325,-2.566550818,49.2601,0.298952829,9.995481983,-2.7046875,-10.92763436,-3.157238093,88.29180604 +237.64,50.43283327,-2.566549411,49.2873,0.295476623,9.995926086,-2.735,-10.985308,-3.195439883,88.2993311 +237.65,50.4328333,-2.566548004,49.3148,0.298952809,9.996370189,-2.765,-11.04173174,-3.230855206,88.30685621 +237.66,50.43283333,-2.566546597,49.3426,0.29200041,9.995704127,-2.7946875,-11.09689377,-3.263453239,88.31438127 +237.67,50.43283335,-2.56654519,49.3707,0.281571821,9.994594001,-2.823125,-11.15078251,-3.293205447,88.32190638 +237.68,50.43283338,-2.566543784,49.3991,0.281571834,9.994594039,-2.8496875,-11.20338668,-3.320085934,88.32943144 +237.69,50.4328334,-2.566542377,49.4277,0.292000434,9.995704244,-2.8746875,-11.25469546,-3.344071208,88.33695649 +237.7,50.43283343,-2.56654097,49.4566,0.298952827,9.996592416,-2.898125,-11.30469794,-3.36514047,88.34448161 +237.71,50.43283346,-2.566539563,49.4857,0.292000438,9.99681449,-2.92,-11.35338383,-3.383275272,88.35200666 +237.72,50.43283348,-2.566538156,49.515,0.281571858,9.996592497,-2.9415625,-11.40074286,-3.3984598,88.35953178 +237.73,50.43283351,-2.566536749,49.5445,0.278095655,9.995926439,-2.963125,-11.44676517,-3.410680818,88.36705683 +237.74,50.43283353,-2.566535342,49.5743,0.278095636,9.995482413,-2.9828125,-11.49144116,-3.419927669,88.37458194 +237.75,50.43283356,-2.566533936,49.6042,0.278095635,9.995704487,-2.9996875,-11.53476147,-3.426192275,88.382107 +237.76,50.43283358,-2.566532528,49.6343,0.27809565,9.995704529,-3.015,-11.57671716,-3.429469192,88.38963211 +237.77,50.43283361,-2.566531122,49.6645,0.278095658,9.995482538,-3.0296875,-11.6172993,-3.429755614,88.39715717 +237.78,50.43283363,-2.566529715,49.6949,0.278095662,9.995926647,-3.0434375,-11.65649953,-3.427051196,88.40468228 +237.79,50.43283366,-2.566528308,49.7254,0.278095665,9.996592789,-3.05625,-11.69430964,-3.421358344,88.41220734 +237.8,50.43283368,-2.566526901,49.756,0.278095662,9.996814865,-3.068125,-11.73072174,-3.412681987,88.41973245 +237.81,50.43283371,-2.566525494,49.7868,0.278095657,9.996814908,-3.078125,-11.7657282,-3.401029745,88.42725751 +237.82,50.43283373,-2.566524087,49.8176,0.278095656,9.996592917,-3.08625,-11.79932175,-3.386411758,88.43478262 +237.83,50.43283376,-2.56652268,49.8485,0.278095657,9.995926861,-3.0934375,-11.83149533,-3.368840746,88.44230768 +237.84,50.43283378,-2.566521273,49.8795,0.274619465,9.995704871,-3.0996875,-11.86224225,-3.348332123,88.44983279 +237.85,50.43283381,-2.566519867,49.9105,0.264190884,9.996593046,-3.1046875,-11.89155609,-3.32490365,88.45735784 +237.86,50.43283383,-2.566518459,49.9416,0.257238497,9.997037156,-3.108125,-11.91943066,-3.298575838,88.46488296 +237.87,50.43283385,-2.566517052,49.9727,0.264190889,9.996371101,-3.1096875,-11.94586023,-3.269371549,88.47240801 +237.88,50.43283388,-2.566515646,50.0038,0.274619481,9.995927079,-3.1096875,-11.9708393,-3.237316394,88.47993313 +237.89,50.4328339,-2.566514238,50.0349,0.274619489,9.995927122,-3.108125,-11.99436254,-3.202438218,88.48745818 +237.9,50.43283393,-2.566512832,50.066,0.264190893,9.996371231,-3.105,-12.01642508,-3.164767504,88.4949833 +237.91,50.43283395,-2.566511425,50.097,0.257238481,9.997037373,-3.1015625,-12.03702234,-3.124337023,88.50250835 +237.92,50.43283397,-2.566510017,50.128,0.260714679,9.996815384,-3.098125,-12.05615002,-3.081182129,88.51003346 +237.93,50.432834,-2.566508611,50.159,0.2607147,9.996593395,-3.0928125,-12.07380411,-3.035340349,88.51755852 +237.94,50.43283402,-2.566507204,50.1899,0.257238514,9.997037505,-3.0846875,-12.08998095,-2.986851732,88.52508363 +237.95,50.43283404,-2.566505796,50.2207,0.260714705,9.996815515,-3.075,-12.10467714,-2.935758508,88.53260869 +237.96,50.43283407,-2.56650439,50.2514,0.25723851,9.996593525,-3.0646875,-12.1178896,-2.88210525,88.5401338 +237.97,50.43283409,-2.566502983,50.282,0.243333732,9.997037633,-3.053125,-12.12961553,-2.82593877,88.54765886 +237.98,50.43283411,-2.566501575,50.3125,0.243333724,9.99659361,-3.04,-12.13985257,-2.767308056,88.55518397 +237.99,50.43283413,-2.566500169,50.3428,0.257238491,9.995705521,-3.02625,-12.14859854,-2.706264216,88.56270903 +238,50.43283416,-2.566498762,50.373,0.25723849,9.995927597,-3.0115625,-12.15585167,-2.64286042,88.57023414 +238.01,50.43283418,-2.566497355,50.4031,0.243333719,9.996593739,-2.9946875,-12.1616103,-2.577152016,88.5777592 +238.02,50.4328342,-2.566495948,50.4329,0.243333727,9.996815814,-2.9765625,-12.16587339,-2.509196357,88.58528431 +238.03,50.43283422,-2.566494541,50.4626,0.257238518,9.996815855,-2.958125,-12.16863991,-2.439052571,88.59280936 +238.04,50.43283425,-2.566493134,50.4921,0.257238528,9.996815896,-2.9378125,-12.16990942,-2.366781967,88.60033442 +238.05,50.43283427,-2.566491727,50.5214,0.239857547,9.99703797,-2.915,-12.16968155,-2.292447454,88.60785953 +238.06,50.43283429,-2.56649032,50.5504,0.225952751,9.99770411,-2.8915625,-12.16795638,-2.216113891,88.61538459 +238.07,50.43283431,-2.566488913,50.5792,0.222476546,9.997926184,-2.868125,-12.16473429,-2.137847799,88.6229097 +238.08,50.43283433,-2.566487505,50.6078,0.225952742,9.997038093,-2.843125,-12.16001593,-2.057717531,88.63043476 +238.09,50.43283435,-2.566486099,50.6361,0.239857529,9.9968161,-2.81625,-12.15380231,-1.975792875,88.63795987 +238.1,50.43283437,-2.566484692,50.6641,0.257238516,9.998148337,-2.7884375,-12.14609471,-1.892145334,88.64548493 +238.11,50.4328344,-2.566483284,50.6919,0.257238525,9.998814474,-2.7596875,-12.13689473,-1.806847789,88.65301004 +238.12,50.43283442,-2.566481877,50.7193,0.239857554,9.99792638,-2.7296875,-12.12620431,-1.719974668,88.6605351 +238.13,50.43283444,-2.56648047,50.7465,0.225952769,9.997038286,-2.698125,-12.11402563,-1.631601657,88.66806021 +238.14,50.43283446,-2.566479063,50.7733,0.222476564,9.996816291,-2.6646875,-12.10036134,-1.541805935,88.67558526 +238.15,50.43283448,-2.566477656,50.7998,0.222476565,9.996816329,-2.63,-12.08521417,-1.450665654,88.68311038 +238.16,50.4328345,-2.566476249,50.8259,0.222476575,9.997038399,-2.5946875,-12.06858739,-1.358260453,88.69063543 +238.17,50.43283452,-2.566474842,50.8517,0.222476574,9.997704533,-2.5584375,-12.05048439,-1.264670776,88.69816055 +238.18,50.43283454,-2.566473435,50.8771,0.222476557,9.997926601,-2.52125,-12.030909,-1.169978271,88.7056856 +238.19,50.43283456,-2.566472027,50.9021,0.222476547,9.996816471,-2.4834375,-12.00986529,-1.074265556,88.71321072 +238.2,50.43283458,-2.566470621,50.9268,0.222476559,9.995928374,-2.4446875,-11.98735767,-0.977616056,88.72073577 +238.21,50.4328346,-2.566469214,50.951,0.222476577,9.997038573,-2.4046875,-11.96339085,-0.880114109,88.72826088 +238.22,50.43283462,-2.566467807,50.9749,0.22247658,9.998814871,-2.3634375,-11.9379698,-0.781844628,88.73578594 +238.23,50.43283464,-2.566466399,50.9983,0.222476572,9.999036936,-2.32125,-11.9110998,-0.682893385,88.74331105 +238.24,50.43283466,-2.566464992,51.0213,0.222476573,9.997926802,-2.278125,-11.88278657,-0.583346666,88.75083611 +238.25,50.43283468,-2.566463585,51.0439,0.22247658,9.9970387,-2.233125,-11.85303591,-0.483291218,88.75836122 +238.26,50.4328347,-2.566462178,51.066,0.222476572,9.996816698,-2.1865625,-11.82185412,-0.38281436,88.76588628 +238.27,50.43283472,-2.566460771,51.0876,0.222476553,9.996816728,-2.14,-11.78924766,-0.282003696,88.77341139 +238.28,50.43283474,-2.566459364,51.1088,0.219000357,9.99703879,-2.0934375,-11.75522331,-0.180947119,88.78093645 +238.29,50.43283476,-2.566457957,51.1295,0.205095592,9.997926951,-2.04625,-11.71978827,-0.079732749,88.78846156 +238.3,50.43283478,-2.56645655,51.1497,0.187714624,9.999037143,-1.998125,-11.68294989,0.021551177,88.79598662 +238.31,50.43283479,-2.566455142,51.1695,0.18771462,9.999037171,-1.948125,-11.64471585,0.122816311,88.80351173 +238.32,50.43283481,-2.566453735,51.1887,0.205095594,9.997927032,-1.8965625,-11.6050941,0.223974301,88.81103678 +238.33,50.43283483,-2.566452328,51.2074,0.219000383,9.997038925,-1.845,-11.56409301,0.324937028,88.8185619 +238.34,50.43283485,-2.566450921,51.2256,0.222476589,9.997038949,-1.793125,-11.52172112,0.42561637,88.82608695 +238.35,50.43283487,-2.566449514,51.2433,0.219000393,9.997927105,-1.7396875,-11.47798719,0.525924606,88.83361207 +238.36,50.43283489,-2.566448107,51.2604,0.205095597,9.999037293,-1.685,-11.43290046,0.625774191,88.84113712 +238.37,50.43283491,-2.566446699,51.277,0.18771461,9.999037315,-1.63,-11.38647025,0.72507809,88.84866224 +238.38,50.43283492,-2.566445292,51.293,0.187714613,9.997927171,-1.575,-11.33870637,0.82374973,88.85618729 +238.39,50.43283494,-2.566443885,51.3085,0.201619399,9.997261093,-1.52,-11.28961872,0.921703053,88.86371235 +238.4,50.43283496,-2.566442478,51.3234,0.201619399,9.997927212,-1.4646875,-11.23921752,1.018852631,88.87123746 +238.41,50.43283498,-2.566441071,51.3378,0.187714614,9.999037395,-1.408125,-11.18751335,1.115113723,88.87876252 +238.42,50.43283499,-2.566439663,51.3516,0.187714613,9.999037413,-1.3496875,-11.13451704,1.210402448,88.88628763 +238.43,50.43283501,-2.566438256,51.3648,0.201619403,9.997927265,-1.29,-11.0802396,1.304635728,88.89381268 +238.44,50.43283503,-2.566436849,51.3774,0.201619412,9.997261182,-1.23,-11.02469232,1.397731286,88.9013378 +238.45,50.43283505,-2.566435442,51.3894,0.187714625,9.997927296,-1.1703125,-10.96788693,1.489607991,88.90886285 +238.46,50.43283506,-2.566434035,51.4008,0.184238419,9.999037476,-1.1115625,-10.90983519,1.5801858,88.91638797 +238.47,50.43283508,-2.566432627,51.4116,0.187714616,9.999037489,-1.0528125,-10.8505493,1.669385588,88.92391302 +238.48,50.4328351,-2.56643122,51.4219,0.184238431,9.997927337,-0.9915625,-10.79004152,1.75712972,88.93143814 +238.49,50.43283511,-2.566429813,51.4315,0.184238438,9.997039216,-0.9284375,-10.72832463,1.843341534,88.93896319 +238.5,50.43283513,-2.566428406,51.4404,0.187714626,9.997039227,-0.866875,-10.66541146,1.927945971,88.9464883 +238.51,50.43283515,-2.566426999,51.4488,0.184238409,9.997927368,-0.8065625,-10.60131507,2.010869236,88.95401336 +238.52,50.43283516,-2.566425592,51.4566,0.184238399,9.999037542,-0.744375,-10.53604899,2.092038964,88.96153847 +238.53,50.43283518,-2.566424184,51.4637,0.187714607,9.99903755,-0.68,-10.46962674,2.171384394,88.96906353 +238.54,50.4328352,-2.566422777,51.4702,0.180762233,9.997927391,-0.6153125,-10.40206224,2.248836313,88.97658864 +238.55,50.43283521,-2.56642137,51.476,0.170333651,9.997261298,-0.551875,-10.33336958,2.324327284,88.9841137 +238.56,50.43283523,-2.566419963,51.4812,0.166857447,9.997927402,-0.49,-10.2635631,2.39779136,88.99163881 +238.57,50.43283524,-2.566418556,51.4858,0.166857436,9.999037571,-0.4278125,-10.19265745,2.46916454,88.99916387 +238.58,50.43283526,-2.566417148,51.4898,0.166857436,9.999259607,-0.3634375,-10.12066731,2.538384603,89.00668898 +238.59,50.43283527,-2.566415741,51.4931,0.166857448,9.999037576,-0.298125,-10.04760785,2.6053911,89.01421404 +238.6,50.43283529,-2.566414334,51.4957,0.166857457,9.99925961,-0.23375,-9.973494216,2.670125705,89.02173915 +238.61,50.4328353,-2.566412926,51.4978,0.166857454,9.999037578,-0.17,-9.89834192,2.732531867,89.0292642 +238.62,50.43283532,-2.566411519,51.4991,0.166857437,9.997927411,-0.10625,-9.822166723,2.79255527,89.03678932 +238.63,50.43283533,-2.566410112,51.4999,0.166857415,9.997261309,-0.041875,-9.744984438,2.850143487,89.04431437 +238.64,50.43283535,-2.566408705,51.5,0.166857415,9.997927405,0.0234375,-9.666811222,2.905246385,89.05183949 +238.65,50.43283536,-2.566407298,51.4994,0.166857437,9.9992596,0.088125,-9.587663406,2.957815836,89.05936454 +238.66,50.43283538,-2.56640589,51.4982,0.166857454,10.00014773,0.151875,-9.507557546,3.007806002,89.06688966 +238.67,50.43283539,-2.566404483,51.4964,0.166857457,10.00014772,0.2165625,-9.426510259,3.05517334,89.07441471 +238.68,50.43283541,-2.566403075,51.4939,0.166857448,9.999259582,0.2815625,-9.34453862,3.099876538,89.08193982 +238.69,50.43283542,-2.566401668,51.4907,0.163381239,9.997927376,0.345,-9.261659702,3.141876579,89.08946488 +238.7,50.43283544,-2.566400261,51.487,0.152952648,9.997039235,0.4084375,-9.177890751,3.181136851,89.09698999 +238.71,50.43283545,-2.566398854,51.4826,0.146000265,9.997039225,0.4734375,-9.093249301,3.217623147,89.10451505 +238.72,50.43283546,-2.566397447,51.4775,0.152952666,9.997927346,0.5378125,-9.007753054,3.251303611,89.11204016 +238.73,50.43283548,-2.56639604,51.4718,0.16338125,9.999259533,0.6,-8.921419773,3.282148909,89.11956522 +238.74,50.43283549,-2.566394632,51.4655,0.163381239,10.00014765,0.661875,-8.834267622,3.31013211,89.12709027 +238.75,50.43283551,-2.566393225,51.4586,0.152952645,10.00014764,0.725,-8.746314704,3.335228808,89.13461539 +238.76,50.43283552,-2.566391817,51.451,0.146000253,9.999481524,0.7884375,-8.657579412,3.357417171,89.14214044 +238.77,50.43283553,-2.56639041,51.4428,0.149476448,9.999037443,0.85125,-8.568080311,3.376677778,89.14966556 +238.78,50.43283555,-2.566389003,51.434,0.14947645,9.999259459,0.9134375,-8.47783602,3.392993897,89.15719061 +238.79,50.43283556,-2.566387595,51.4245,0.146000261,9.999037408,0.9746875,-8.386865449,3.406351319,89.16471572 +238.8,50.43283557,-2.566386188,51.4145,0.149476458,9.997927225,1.035,-8.295187618,3.416738299,89.17224078 +238.81,50.43283559,-2.566384781,51.4038,0.146000252,9.997261106,1.095,-8.20282155,3.424145841,89.17976589 +238.82,50.4328356,-2.566383374,51.3926,0.132095464,9.997927185,1.155,-8.109786669,3.428567471,89.18729095 +238.83,50.43283561,-2.566381967,51.3807,0.132095475,9.999259362,1.215,-8.016102339,3.42999935,89.19481606 +238.84,50.43283562,-2.566380559,51.3683,0.146000271,10.00014747,1.2746875,-7.921788101,3.42844016,89.20234112 +238.85,50.43283564,-2.566379152,51.3552,0.146000273,10.00014745,1.3334375,-7.826863719,3.423891391,89.20986623 +238.86,50.43283565,-2.566377744,51.3416,0.128619286,9.999481327,1.39125,-7.731348962,3.416356938,89.21739129 +238.87,50.43283566,-2.566376337,51.3274,0.118190686,9.999037236,1.4484375,-7.635263825,3.405843335,89.2249164 +238.88,50.43283567,-2.56637493,51.3126,0.128619265,9.999259243,1.5046875,-7.538628362,3.392359804,89.23244146 +238.89,50.43283568,-2.566373522,51.2973,0.14600025,9.999037183,1.56,-7.441462684,3.375918093,89.23996657 +238.9,50.4328357,-2.566372115,51.2814,0.14600026,9.998149024,1.615,-7.343787188,3.356532524,89.24749162 +238.91,50.43283571,-2.566370708,51.265,0.128619284,9.998148996,1.67,-7.245622157,3.334220001,89.25501674 +238.92,50.43283572,-2.566369301,51.248,0.114714498,9.999037099,1.725,-7.146988218,3.308999946,89.26254179 +238.93,50.43283573,-2.566367893,51.2305,0.114714494,9.999259102,1.779375,-7.047905881,3.280894475,89.27006691 +238.94,50.43283574,-2.566366486,51.2124,0.128619263,9.999037038,1.8315625,-6.948395889,3.249927997,89.27759196 +238.95,50.43283575,-2.566365079,51.1938,0.146000225,9.999481073,1.8815625,-6.848478983,3.216127498,89.28511708 +238.96,50.43283577,-2.566363671,51.1748,0.146000225,10.00014714,1.931875,-6.748176017,3.179522485,89.29264213 +238.97,50.43283578,-2.566362264,51.1552,0.128619262,10.00014711,1.983125,-6.64750802,3.140144929,89.30016724 +238.98,50.43283579,-2.566360856,51.1351,0.114714492,9.999480973,2.033125,-6.546495904,3.098029093,89.3076923 +238.99,50.4328358,-2.566359449,51.1145,0.111238299,9.999036874,2.0815625,-6.44516087,3.053211704,89.31521741 +239,50.43283581,-2.566358042,51.0935,0.111238299,9.999480905,2.1296875,-6.343524001,3.005731895,89.32274247 +239.01,50.43283582,-2.566356634,51.0719,0.111238296,10.00014697,2.1765625,-6.241606612,2.955631033,89.33026758 +239.02,50.43283583,-2.566355227,51.0499,0.111238287,10.00014693,2.22125,-6.139429846,2.902952835,89.33779264 +239.03,50.43283584,-2.566353819,51.0275,0.111238276,9.999258761,2.265,-6.037015187,2.847743252,89.34531775 +239.04,50.43283585,-2.566352412,51.0046,0.111238275,9.998148558,2.3084375,-5.93438395,2.790050356,89.35284281 +239.05,50.43283586,-2.566351005,50.9813,0.111238286,9.99814852,2.35125,-5.831557563,2.729924451,89.36036792 +239.06,50.43283587,-2.566349598,50.9576,0.111238294,9.999036613,2.393125,-5.728557513,2.667418079,89.36789298 +239.07,50.43283588,-2.56634819,50.9334,0.111238296,9.999258605,2.4334375,-5.625405343,2.60258567,89.37541803 +239.08,50.43283589,-2.566346783,50.9089,0.111238296,9.999036532,2.4728125,-5.522122539,2.535483717,89.38294314 +239.09,50.4328359,-2.566345376,50.884,0.111238295,9.999258525,2.511875,-5.4187307,2.466170836,89.3904682 +239.1,50.43283591,-2.566343968,50.8586,0.111238293,9.999258483,2.5496875,-5.315251429,2.394707414,89.39799331 +239.11,50.43283592,-2.566342561,50.833,0.111238281,9.999036408,2.58625,-5.211706267,2.321155733,89.40551837 +239.12,50.43283593,-2.566341154,50.8069,0.107762064,9.999480431,2.6215625,-5.10811693,2.245579965,89.41304348 +239.13,50.43283594,-2.566339746,50.7805,0.093857266,10.00014649,2.6546875,-5.004505018,2.168046055,89.42056854 +239.14,50.43283595,-2.566338339,50.7538,0.076476293,10.00014644,2.686875,-4.90089219,2.088621557,89.42809365 +239.15,50.43283595,-2.566336931,50.7268,0.076476313,9.999480301,2.7196875,-4.797300045,2.007375798,89.43561871 +239.16,50.43283596,-2.566335524,50.6994,0.093857306,9.99903619,2.75125,-4.693750185,1.924379538,89.44314382 +239.17,50.43283597,-2.566334117,50.6717,0.107762095,9.999480211,2.7796875,-4.590264325,1.8397052,89.45066888 +239.18,50.43283598,-2.566332709,50.6438,0.111238291,10.00014626,2.806875,-4.486864064,1.753426579,89.45819399 +239.19,50.43283599,-2.566331302,50.6156,0.107762094,10.00036825,2.835,-4.383570889,1.665618964,89.46571905 +239.2,50.432836,-2.566329894,50.5871,0.093857307,10.0003682,2.8628125,-4.280406514,1.5763589,89.47324416 +239.21,50.43283601,-2.566328487,50.5583,0.076476322,10.00014612,2.8878125,-4.17739237,1.485724253,89.48076921 +239.22,50.43283601,-2.566327079,50.5293,0.076476313,9.999479979,2.9096875,-4.074550055,1.393794035,89.48829433 +239.23,50.43283602,-2.566325672,50.5001,0.093857284,9.999035866,2.9303125,-3.971900999,1.300648401,89.49581938 +239.24,50.43283603,-2.566324265,50.4707,0.104285873,9.999479884,2.9515625,-3.869466631,1.206368539,89.5033445 +239.25,50.43283604,-2.566322857,50.4411,0.093857294,10.00014594,2.9728125,-3.767268378,1.111036727,89.51086955 +239.26,50.43283605,-2.56632145,50.4112,0.07647632,10.00014589,2.99125,-3.665327555,1.014736101,89.51839466 +239.27,50.43283605,-2.566320042,50.3812,0.073000125,9.999479739,3.0065625,-3.563665419,0.917550599,89.52591972 +239.28,50.43283606,-2.566318635,50.3511,0.076476322,9.999035624,3.0215625,-3.462303284,0.819564961,89.53344483 +239.29,50.43283607,-2.566317228,50.3208,0.073000125,9.999479641,3.0365625,-3.361262291,0.720864673,89.54096989 +239.3,50.43283607,-2.56631582,50.2903,0.076476321,10.00014569,3.0496875,-3.260563526,0.621535793,89.548495 +239.31,50.43283608,-2.566314413,50.2598,0.090381106,10.00014564,3.0615625,-3.160228016,0.521664894,89.55602006 +239.32,50.43283609,-2.566313005,50.2291,0.090381103,9.999479494,3.073125,-3.060276675,0.421339068,89.56354517 +239.33,50.4328361,-2.566311598,50.1983,0.076476309,9.999035378,3.0828125,-2.960730472,0.320645861,89.57107023 +239.34,50.4328361,-2.566310191,50.1674,0.073000101,9.999479394,3.09,-2.861610149,0.21967305,89.57859534 +239.35,50.43283611,-2.566308783,50.1365,0.076476297,10.00014544,3.0965625,-2.762936388,0.1185087,89.5861204 +239.36,50.43283612,-2.566307376,50.1055,0.069523915,10.00014539,3.1028125,-2.664729761,0.017240988,89.59364551 +239.37,50.43283612,-2.566305968,50.0744,0.059095335,9.999479245,3.10625,-2.567010892,-0.084041736,89.60117056 +239.38,50.43283613,-2.566304561,50.0433,0.059095336,9.999035129,3.1065625,-2.469800065,-0.185251235,89.60869568 +239.39,50.43283613,-2.566303154,50.0123,0.069523925,9.999479145,3.106875,-2.373117677,-0.286299161,89.61622073 +239.4,50.43283614,-2.566301746,49.9812,0.076476315,10.00014519,3.1084375,-2.276983896,-0.387097391,89.62374585 +239.41,50.43283615,-2.566300339,49.9501,0.069523913,10.00014514,3.1090625,-2.181418718,-0.487558092,89.6312709 +239.42,50.43283615,-2.566298931,49.919,0.059095313,9.999478995,3.1065625,-2.086442255,-0.587593658,89.63879596 +239.43,50.43283616,-2.566297524,49.8879,0.055619117,9.999034879,3.10125,-1.992074158,-0.687116828,89.64632107 +239.44,50.43283616,-2.566296117,49.857,0.055619128,9.999478896,3.095,-1.898334309,-0.786040799,89.65384613 +239.45,50.43283617,-2.566294709,49.826,0.055619136,10.00014495,3.088125,-1.805242132,-0.884279341,89.66137124 +239.46,50.43283617,-2.566293302,49.7952,0.055619138,10.00036693,3.0796875,-1.712817164,-0.981746795,89.6688963 +239.47,50.43283618,-2.566291894,49.7644,0.055619138,10.00036688,3.07,-1.621078714,-1.078358137,89.67642141 +239.48,50.43283618,-2.566290487,49.7338,0.055619135,10.0001448,3.0596875,-1.530045862,-1.17402914,89.68394647 +239.49,50.43283619,-2.566289079,49.7032,0.055619126,9.99947865,3.048125,-1.439737687,-1.268676324,89.69147158 +239.5,50.43283619,-2.566287672,49.6728,0.055619115,9.999034536,3.0346875,-1.350173039,-1.362217242,89.69899663 +239.51,50.4328362,-2.566286265,49.6425,0.055619115,9.999478553,3.02,-1.261370597,-1.454570304,89.70652175 +239.52,50.4328362,-2.566284857,49.6124,0.052142929,10.0001446,3.004375,-1.173348924,-1.545654951,89.7140468 +239.53,50.43283621,-2.56628345,49.5824,0.04171435,10.00036659,2.9865625,-1.086126413,-1.635391773,89.72157192 +239.54,50.43283621,-2.566282042,49.5526,0.03476196,10.00036654,2.9665625,-0.999721226,-1.723702503,89.72909697 +239.55,50.43283621,-2.566280635,49.5231,0.041714352,10.00014446,2.9465625,-0.914151469,-1.810510078,89.73662208 +239.56,50.43283622,-2.566279227,49.4937,0.052142939,9.999478316,2.9265625,-0.829435018,-1.895738925,89.74414714 +239.57,50.43283622,-2.56627782,49.4645,0.052142939,9.999034203,2.9046875,-0.745589463,-1.979314674,89.75167225 +239.58,50.43283623,-2.566276413,49.4356,0.041714351,9.999478223,2.88125,-0.662632451,-2.061164388,89.75919731 +239.59,50.43283623,-2.566275005,49.4069,0.034761959,10.00014428,2.8565625,-0.580581228,-2.141216734,89.76672242 +239.6,50.43283623,-2.566273598,49.3784,0.038238155,10.00036626,2.8296875,-0.499452925,-2.219401924,89.77424748 +239.61,50.43283624,-2.56627219,49.3503,0.038238155,10.00036622,2.8015625,-0.419264559,-2.295651778,89.78177259 +239.62,50.43283624,-2.566270783,49.3224,0.034761959,10.00036617,2.7734375,-0.340032747,-2.369899774,89.78929765 +239.63,50.43283624,-2.566269375,49.2948,0.038238154,10.00036613,2.7446875,-0.261774161,-2.442081169,89.79682276 +239.64,50.43283625,-2.566267968,49.2675,0.038238154,10.00014406,2.7146875,-0.184505072,-2.512133052,89.80434782 +239.65,50.43283625,-2.56626656,49.2405,0.034761958,9.999477913,2.6828125,-0.10824164,-2.579994345,89.81187293 +239.66,50.43283625,-2.566265153,49.2138,0.038238154,9.999033805,2.648125,-0.032999791,-2.645605805,89.81939799 +239.67,50.43283626,-2.566263746,49.1875,0.034761958,9.999477829,2.611875,0.041204775,-2.70891025,89.8269231 +239.68,50.43283626,-2.566262338,49.1616,0.020857175,10.00014389,2.5765625,0.114356532,-2.769852505,89.83444815 +239.69,50.43283626,-2.566260931,49.136,0.020857175,10.00036588,2.5415625,0.187254067,-2.828379399,89.84197327 +239.7,50.43283626,-2.566259523,49.1107,0.034761958,10.00036584,2.5046875,0.263951228,-2.884439938,89.84949832 +239.71,50.43283627,-2.566258116,49.0859,0.034761958,10.0003658,2.46625,0.349316096,-2.937985136,89.85702344 +239.72,50.43283627,-2.566256708,49.0614,0.017380979,10.00036576,2.4265625,0.448216862,-2.98896841,89.86454849 +239.73,50.43283627,-2.566255301,49.0373,0.006952389,10.00036572,2.3846875,0.565521949,-3.037345242,89.8720736 +239.74,50.43283627,-2.566253893,49.0137,0.017380967,10.00036569,2.3415625,0.706100066,-3.08307352,89.87959866 +239.75,50.43283627,-2.566252486,48.9905,0.034761935,10.00014362,2.2984375,0.874820151,-3.12611325,89.88712377 +239.76,50.43283628,-2.566251078,48.9677,0.034761935,9.999477481,2.255,1.076551314,-3.166426961,89.89464883 +239.77,50.43283628,-2.566249671,48.9454,0.017380967,9.99903338,2.21125,1.31453535,-3.203979532,89.90217389 +239.78,50.43283628,-2.566248264,48.9235,0.003476193,9.999477411,2.1665625,1.585503937,-3.238738189,89.909699 +239.79,50.43283628,-2.566246856,48.902,-3.09E-11,10.00014348,2.1196875,1.884561321,-3.270672564,89.91722405 +239.8,50.43283628,-2.566245449,48.8811,-2.64E-11,10.00036548,2.0715625,2.206812036,-3.299754928,89.92474917 +239.81,50.43283628,-2.566244041,48.8606,-1.50E-11,10.00036544,2.023125,2.547360903,-3.32595984,89.93226173 +239.82,50.43283628,-2.566242634,48.8406,0.003476196,10.00036541,1.973125,2.901312915,-3.34926444,89.93969901 +239.83,50.43283628,-2.566241226,48.8211,0.017380978,10.00036538,1.9215625,3.263773408,-3.369648445,89.94698577 +239.84,50.43283628,-2.566239819,48.8022,0.034761956,10.00036535,1.87,3.629847946,-3.387094036,89.95404685 +239.85,50.43283629,-2.566238411,48.7837,0.034761956,10.00036532,1.8184375,3.994642324,-3.401586087,89.96080683 +239.86,50.43283629,-2.566237004,48.7658,0.017380978,10.00014326,1.76625,4.353262682,-3.413111877,89.96719061 +239.87,50.43283629,-2.566235596,48.7484,0.003476196,9.999477134,1.7134375,4.700815328,-3.421661382,89.97312291 +239.88,50.43283629,-2.566234189,48.7315,1.64E-11,9.999033042,1.6596875,5.032406917,-3.427227151,89.97852842 +239.89,50.43283629,-2.566232782,48.7152,1.72E-11,9.999477083,1.605,5.343144446,-3.429804315,89.98333192 +239.9,50.43283629,-2.566231374,48.6994,1.89E-11,10.00014316,1.5496875,5.628134972,-3.429390697,89.98745819 +239.91,50.43283629,-2.566229967,48.6842,2.66E-11,10.00036517,1.493125,5.882486063,-3.425986526,89.99085704 +239.92,50.43283629,-2.566228559,48.6695,3.05E-11,10.00036514,1.4353125,6.101305406,-3.419594895,89.99357859 +239.93,50.43283629,-2.566227152,48.6555,1.55E-11,10.00014309,1.378125,6.281328688,-3.410221305,89.99569819 +239.94,50.43283629,-2.566225744,48.642,-1.02E-11,9.999476969,1.3215625,6.425802173,-3.397873893,89.99729095 +239.95,50.43283629,-2.566224337,48.629,-2.02E-11,9.999032882,1.2628125,6.539600185,-3.382563544,89.99843228 +239.96,50.43283629,-2.56622293,48.6167,-1.31E-11,9.999476929,1.201875,6.627597106,-3.364303551,89.9991973 +239.97,50.43283629,-2.566221522,48.605,-1.25E-11,10.00014301,1.141875,6.69466789,-3.343109842,89.99966139 +239.98,50.43283629,-2.566220115,48.5939,-2.17E-11,10.00036503,1.083125,6.745687489,-3.319000867,89.99989969 +239.99,50.43283629,-2.566218707,48.5833,-2.19E-11,10.00036501,1.023125,6.785531376,-3.29199771,89.99998746 +240,50.43283629,-2.5662173,48.5734,-7.66E-12,10.00036499,0.96125,6.819075247,-3.262123862,90.00000001 +240.01,50.43283629,-2.566215892,48.5641,1.09E-11,10.00036498,0.89875,6.850381202,-3.229405394,90.00000001 +240.02,50.43283629,-2.566214485,48.5554,2.67E-11,10.00014293,0.8365625,6.88025654,-3.193870838,90.00000001 +240.03,50.43283629,-2.566213077,48.5474,3.37E-11,9.999476821,0.775,6.908695013,-3.155551134,90.00000001 +240.04,50.43283629,-2.56621167,48.5399,2.97E-11,9.999032743,0.713125,6.935690722,-3.1144798,90.00000001 +240.05,50.43283629,-2.566210263,48.5331,2.25E-11,9.999476798,0.6496875,6.961237936,-3.070692589,90.00000001 +240.06,50.43283629,-2.566208855,48.5269,1.64E-11,10.00014289,0.5853125,6.985331442,-3.02422766,90.00000001 +240.07,50.43283629,-2.566207448,48.5214,7.81E-12,10.00036491,0.521875,7.007966139,-2.975125578,90.00000001 +240.08,50.43283629,-2.56620604,48.5165,4.84E-12,10.0003649,0.4596875,7.029137331,-2.923429143,90.00000001 +240.09,50.43283629,-2.566204633,48.5122,1.94E-11,10.00014286,0.3965625,7.048840547,-2.869183447,90.00000001 +240.1,50.43283629,-2.566203225,48.5085,3.89E-11,9.99947676,0.3315625,7.067071721,-2.812435759,90.00000001 +240.11,50.43283629,-2.566201818,48.5056,4.12E-11,9.999032689,0.266875,7.083827069,-2.753235583,90.00000001 +240.12,50.43283629,-2.566200411,48.5032,2.89E-11,9.999476752,0.2034375,7.099102983,-2.691634541,90.00000001 +240.13,50.43283629,-2.566199003,48.5015,1.95E-11,10.00014285,0.1396875,7.112896369,-2.627686378,90.00000001 +240.14,50.43283629,-2.566197596,48.5004,1.80E-11,10.00036488,0.075,7.125204305,-2.561446784,90.00000001 +240.15,50.43283629,-2.566196188,48.5,1.84E-11,10.00036488,0.01,7.136024269,-2.492973629,90.00000001 +240.16,50.43283629,-2.566194781,48.5002,1.80E-11,10.00014285,-0.055,7.145353913,-2.422326501,90.00000001 +240.17,50.43283629,-2.566193373,48.5011,1.72E-11,9.999476749,-0.12,7.153191403,-2.349567106,90.00000001 +240.18,50.43283629,-2.566191966,48.5026,1.48E-11,9.999032685,-0.1846875,7.159534962,-2.274758872,90.00000001 +240.19,50.43283629,-2.566190559,48.5048,6.09E-12,9.999476754,-0.2484375,7.164383388,-2.197967,90.00000001 +240.2,50.43283629,-2.566189151,48.5076,-7.97E-12,10.00014286,-0.3115625,7.16773565,-2.11925847,90.00000001 +240.21,50.43283629,-2.566187744,48.511,-1.81E-11,10.0003649,-0.3753125,7.169591002,-2.038701922,90.00000001 +240.22,50.43283629,-2.566186336,48.5151,-2.11E-11,10.0003649,-0.44,7.169949043,-1.9563676,90.00000001 +240.23,50.43283629,-2.566184929,48.5198,-1.89E-11,10.00036491,-0.5046875,7.168809774,-1.872327239,90.00000001 +240.24,50.43283629,-2.566183521,48.5252,-1.17E-11,10.00036492,-0.568125,7.166173366,-1.786654235,90.00000001 +240.25,50.43283629,-2.566182114,48.5312,-6.25E-12,10.00014289,-0.63,7.162040392,-1.699423244,90.00000001 +240.26,50.43283629,-2.566180706,48.5378,-9.38E-12,9.999476806,-0.691875,7.156411769,-1.610710298,90.00000001 +240.27,50.43283629,-2.566179299,48.545,-1.27E-11,9.999032751,-0.755,7.149288529,-1.520592803,90.00000001 +240.28,50.43283629,-2.566177892,48.5529,-5.47E-12,9.999476829,-0.8184375,7.140672332,-1.429149369,90.00000001 +240.29,50.43283629,-2.566176484,48.5614,1.02E-11,10.00014294,-0.88125,7.130564841,-1.336459638,90.00000001 +240.3,50.43283629,-2.566175077,48.5705,2.59E-11,10.00036499,-0.9434375,7.11896829,-1.24260451,90.00000001 +240.31,50.43283629,-2.566173669,48.5803,3.52E-11,10.000365,-1.0046875,7.10588497,-1.147665804,90.00000001 +240.32,50.43283629,-2.566172262,48.5906,3.53E-11,10.00036502,-1.0646875,7.09131769,-1.051726313,90.00000001 +240.33,50.43283629,-2.566170854,48.6016,2.42E-11,10.00036504,-1.12375,7.075269486,-0.954869746,90.00000001 +240.34,50.43283629,-2.566169447,48.6131,1.56E-12,10.00036506,-1.183125,7.057743739,-0.857180499,90.00000001 +240.35,50.43283629,-2.566168039,48.6252,-1.95E-11,10.00036507,-1.2434375,7.038744057,-0.758743772,90.00000001 +240.36,50.43283629,-2.566166632,48.638,-2.25E-11,10.00036509,-1.303125,7.018274395,-0.659645393,90.00000001 +240.37,50.43283629,-2.566165224,48.6513,-8.44E-12,10.00036511,-1.36125,6.99633905,-0.559971821,90.00000001 +240.38,50.43283629,-2.566163817,48.6652,8.75E-12,10.0001431,-1.4184375,6.972942662,-0.459809918,90.00000001 +240.39,50.43283629,-2.566162409,48.6797,1.64E-11,9.999477028,-1.475,6.948089987,-0.359247059,90.00000001 +240.4,50.43283629,-2.566161002,48.6947,9.53E-12,9.999032985,-1.5315625,6.921786354,-0.258370963,90.00000001 +240.41,50.43283629,-2.566159595,48.7103,-2.34E-12,9.999477075,-1.588125,6.894037149,-0.157269524,90.00000001 +240.42,50.43283629,-2.566158187,48.7265,-2.97E-12,10.0001432,-1.643125,6.864848272,-0.056030975,90.00000001 +240.43,50.43283629,-2.56615678,48.7432,7.97E-12,10.00036526,-1.6965625,6.834225741,0.045256447,90.00000001 +240.44,50.43283629,-2.566155372,48.7604,1.50E-11,10.00036529,-1.75,6.802175914,0.146504449,90.00000001 +240.45,50.43283629,-2.566153965,48.7782,8.59E-12,10.00036531,-1.8034375,6.76870561,0.247624624,90.00000001 +240.46,50.43283629,-2.566152557,48.7965,-7.81E-12,10.00036534,-1.85625,6.733821705,0.348528909,90.00000001 +240.47,50.43283629,-2.56615115,48.8153,-2.27E-11,10.00036537,-1.908125,6.697531533,0.44912924,90.00000001 +240.48,50.43283629,-2.566149742,48.8347,-2.33E-11,10.0003654,-1.958125,6.659842713,0.549337954,90.00000001 +240.49,50.43283629,-2.566148335,48.8545,-1.17E-11,10.00036543,-2.0065625,6.62076298,0.649067618,90.00000001 +240.5,50.43283629,-2.566146927,48.8748,-2.34E-12,10.00036546,-2.0553125,6.580300643,0.748231314,90.00000001 +240.51,50.43283629,-2.56614552,48.8956,2.34E-12,10.00014346,-2.1046875,6.538464125,0.846742526,90.00000001 +240.52,50.43283629,-2.566144112,48.9169,7.19E-12,9.999477399,-2.1528125,6.495262076,0.944515368,90.00000001 +240.53,50.43283629,-2.566142705,48.9387,5.47E-12,9.999033366,-2.198125,6.450703606,1.041464582,90.00000001 +240.54,50.43283629,-2.566141298,48.9609,-5.47E-12,9.999477467,-2.2415625,6.404797999,1.137505601,90.00000001 +240.55,50.43283629,-2.56613989,48.9835,-1.50E-11,10.0001436,-2.2853125,6.357554821,1.232554716,90.00000001 +240.56,50.43283629,-2.566138483,49.0066,-2.11E-11,10.00036567,-2.3296875,6.308983928,1.326529019,90.00000001 +240.57,50.43283629,-2.566137075,49.0301,-2.72E-11,10.00036571,-2.3728125,6.259095462,1.419346577,90.00000001 +240.58,50.43283629,-2.566135668,49.0541,-2.25E-11,10.00036575,-2.4134375,6.207899906,1.510926432,90.00000001 +240.59,50.43283629,-2.56613426,49.0784,1.67E-16,10.00036578,-2.453125,6.15540792,1.601188714,90.00000001 +240.6,50.43283629,-2.566132853,49.1031,2.03E-11,10.00036582,-2.493125,6.101630445,1.690054754,90.00000001 +240.61,50.43283629,-2.566131445,49.1283,1.64E-11,10.00036586,-2.53125,6.046578712,1.77744709,90.00000001 +240.62,50.43283629,-2.566130038,49.1538,1.57E-13,10.0003659,-2.5665625,5.990264237,1.863289403,90.00000001 +240.63,50.43283629,-2.56612863,49.1796,-2.34E-12,10.00036594,-2.601875,5.932698766,1.947506922,90.00000001 +240.64,50.43283629,-2.566127223,49.2058,6.25E-12,10.00014395,-2.638125,5.873894332,2.030026195,90.00000001 +240.65,50.43283629,-2.566125815,49.2324,7.03E-12,9.999477892,-2.6728125,5.813863194,2.110775257,90.00000001 +240.66,50.43283629,-2.566124408,49.2593,9.38E-13,9.999033868,-2.7046875,5.752617902,2.189683692,90.00000001 +240.67,50.43283629,-2.566123001,49.2865,-1.56E-12,9.999477977,-2.735,5.690171289,2.266682688,90.00000001 +240.68,50.43283629,-2.566121593,49.314,-3.28E-12,10.00014412,-2.7646875,5.626536305,2.341705094,90.00000001 +240.69,50.43283629,-2.566120186,49.3418,-1.03E-11,10.0003662,-2.793125,5.561726356,2.414685479,90.00000001 +240.7,50.43283629,-2.566118778,49.3699,-1.56E-11,10.00036624,-2.82,5.495754849,2.485560243,90.00000001 +240.71,50.43283629,-2.566117371,49.3982,-8.59E-12,10.00036628,-2.8465625,5.428635651,2.554267566,90.00000001 +240.72,50.43283629,-2.566115963,49.4268,3.91E-12,10.00036633,-2.873125,5.360382741,2.620747515,90.00000001 +240.73,50.43283629,-2.566114556,49.4557,4.53E-12,10.00014434,-2.898125,5.291010386,2.684942165,90.00000001 +240.74,50.43283629,-2.566113148,49.4848,-9.37E-12,9.999478287,-2.92125,5.220533083,2.74679548,90.00000001 +240.75,50.43283629,-2.566111741,49.5141,-2.33E-11,9.999034266,-2.943125,5.148965555,2.806253545,90.00000001 +240.76,50.43283629,-2.566110334,49.5437,-2.27E-11,9.999478379,-2.963125,5.076322699,2.863264507,90.00000001 +240.77,50.43283629,-2.566108926,49.5734,-7.81E-12,10.00014452,-2.98125,5.002619758,2.917778691,90.00000001 +240.78,50.43283629,-2.566107519,49.6033,8.59E-12,10.0003666,-2.9984375,4.927872028,2.969748484,90.00000001 +240.79,50.43283629,-2.566106111,49.6334,1.72E-11,10.00036665,-3.0146875,4.852095208,3.01912868,90.00000001 +240.8,50.43283629,-2.566104704,49.6636,1.66E-11,10.00014467,-3.0296875,4.775305112,3.065876077,90.00000001 +240.81,50.43283629,-2.566103296,49.694,9.37E-12,9.999478613,-3.043125,4.697517727,3.109950053,90.00000001 +240.82,50.43283629,-2.566101889,49.7245,4.69E-12,9.999034595,-3.055,4.618749322,3.151312048,90.00000001 +240.83,50.43283629,-2.566100482,49.7551,1.17E-11,9.99947871,-3.0665625,4.539016344,3.189926081,90.00000001 +240.84,50.43283629,-2.566099074,49.7858,2.34E-11,10.00014486,-3.078125,4.458335464,3.22575846,90.00000001 +240.85,50.43283629,-2.566097667,49.8167,2.58E-11,10.00036694,-3.0878125,4.376723527,3.258777903,90.00000001 +240.86,50.43283629,-2.566096259,49.8476,1.89E-11,10.00036699,-3.094375,4.294197551,3.288955647,90.00000001 +240.87,50.43283629,-2.566094852,49.8786,7.81E-12,10.000145,-3.0984375,4.210774782,3.316265394,90.00000001 +240.88,50.43283629,-2.566093444,49.9096,-5.47E-12,9.999478951,-3.1015625,4.126472636,3.340683309,90.00000001 +240.89,50.43283629,-2.566092037,49.9406,-1.25E-11,9.999034934,-3.105,4.041308763,3.362188076,90.00000001 +240.9,50.43283629,-2.56609063,49.9717,-8.59E-12,9.999479049,-3.108125,3.955300865,3.380760961,90.00000001 +240.91,50.43283629,-2.566089222,50.0028,-2.19E-12,10.0001452,-3.1096875,3.868466991,3.396385807,90.00000001 +240.92,50.43283629,-2.566087815,50.0339,-2.34E-12,10.00036728,-3.1096875,3.780825247,3.409048919,90.00000001 +240.93,50.43283629,-2.566086407,50.065,-7.03E-12,10.00036733,-3.1078125,3.692393909,3.418739297,90.00000001 +240.94,50.43283629,-2.566085,50.0961,-4.69E-12,10.00014534,-3.103125,3.603191485,3.425448518,90.00000001 +240.95,50.43283629,-2.566083592,50.1271,7.03E-12,9.999479292,-3.0965625,3.513236539,3.429170624,90.00000001 +240.96,50.43283629,-2.566082185,50.158,1.64E-11,9.999035274,-3.0903125,3.422547919,3.42990252,90.00000001 +240.97,50.43283629,-2.566080778,50.1889,2.11E-11,9.999479388,-3.0846875,3.331144593,3.427643462,90.00000001 +240.98,50.43283629,-2.56607937,50.2197,2.58E-11,10.00014554,-3.0778125,3.239045523,3.422395398,90.00000001 +240.99,50.43283629,-2.566077963,50.2505,2.58E-11,10.00036762,-3.0678125,3.146270077,3.414163026,90.00000001 +241,50.43283629,-2.566076555,50.2811,2.11E-11,10.00036766,-3.0546875,3.052837506,3.40295345,90.00000001 +241.01,50.43283629,-2.566075148,50.3116,1.64E-11,10.00036771,-3.0403125,2.958767461,3.388776412,90.00000001 +241.02,50.43283629,-2.56607374,50.3419,4.69E-12,10.00036776,-3.02625,2.864079482,3.371644286,90.00000001 +241.03,50.43283629,-2.566072333,50.3721,-1.64E-11,10.00014577,-3.0115625,2.768793335,3.351572085,90.00000001 +241.04,50.43283629,-2.566070925,50.4022,-3.05E-11,9.999479722,-2.9946875,2.672929016,3.328577283,90.00000001 +241.05,50.43283629,-2.566069518,50.432,-2.56E-11,9.999035703,-2.9765625,2.576506464,3.302679877,90.00000001 +241.06,50.43283629,-2.566068111,50.4617,-1.09E-11,9.999479815,-2.9584375,2.479545905,3.273902499,90.00000001 +241.07,50.43283629,-2.566066703,50.4912,1.56E-12,10.00014596,-2.939375,2.38206745,3.242270187,90.00000001 +241.08,50.43283629,-2.566065296,50.5205,8.59E-12,10.00036804,-2.9178125,2.284091552,3.207810614,90.00000001 +241.09,50.43283629,-2.566063888,50.5496,3.12E-12,10.00036808,-2.8934375,2.185638667,3.170553747,90.00000001 +241.1,50.43283629,-2.566062481,50.5784,-1.88E-11,10.00036813,-2.868125,2.086729307,3.13053213,90.00000001 +241.11,50.43283629,-2.566061073,50.6069,-3.83E-11,10.00036817,-2.843125,1.987384212,3.087780654,90.00000001 +241.12,50.43283629,-2.566059666,50.6353,-3.20E-11,10.00036822,-2.8165625,1.887624009,3.042336564,90.00000001 +241.13,50.43283629,-2.566058258,50.6633,-3.75E-12,10.00036826,-2.7878125,1.787469669,2.994239565,90.00000001 +241.14,50.43283629,-2.566056851,50.691,2.34E-11,10.00036831,-2.75875,1.686941989,2.943531482,90.00000001 +241.15,50.43283629,-2.566055443,50.7185,3.66E-11,10.00036835,-2.7296875,1.586061998,2.890256606,90.00000001 +241.16,50.43283629,-2.566054036,50.7456,3.42E-11,10.00014636,-2.699375,1.484850837,2.834461403,90.00000001 +241.17,50.43283629,-2.566052628,50.7725,1.64E-11,9.999480301,-2.6665625,1.383329534,2.776194517,90.00000001 +241.18,50.43283629,-2.566051221,50.799,-6.25E-12,9.999036276,-2.63125,1.281519402,2.715506713,90.00000001 +241.19,50.43283629,-2.566049814,50.8251,-1.88E-11,9.999480383,-2.5953125,1.179441585,2.652450989,90.00000001 +241.2,50.43283629,-2.566048406,50.8509,-2.36E-11,10.00014652,-2.5596875,1.077117454,2.587082234,90.00000001 +241.21,50.43283629,-2.566046999,50.8763,-3.06E-11,10.0003686,-2.523125,0.974568436,2.519457515,90.00000001 +241.22,50.43283629,-2.566045591,50.9014,-3.53E-11,10.00036864,-2.485,0.871815847,2.449635847,90.00000001 +241.23,50.43283629,-2.566044184,50.926,-2.58E-11,10.00036867,-2.44625,0.768881172,2.37767802,90.00000001 +241.24,50.43283629,-2.566042776,50.9503,-4.06E-12,10.00036871,-2.4065625,0.665785953,2.303646831,90.00000001 +241.25,50.43283629,-2.566041369,50.9742,1.08E-11,10.00036875,-2.3646875,0.562551736,2.227606794,90.00000001 +241.26,50.43283629,-2.566039961,50.9976,6.09E-12,10.00036879,-2.3215625,0.459199947,2.149624316,90.00000001 +241.27,50.43283629,-2.566038554,51.0206,-8.59E-12,10.00014679,-2.2784375,0.35575236,2.069767292,90.00000001 +241.28,50.43283629,-2.566037146,51.0432,-1.80E-11,9.999480724,-2.2346875,0.252230403,1.988105394,90.00000001 +241.29,50.43283629,-2.566035739,51.0653,-1.72E-11,9.999036693,-2.1896875,0.148655791,1.90470984,90.00000001 +241.3,50.43283629,-2.566034332,51.087,-9.53E-12,9.999480793,-2.143125,0.045050124,1.819653338,90.00000001 +241.31,50.43283629,-2.566032924,51.1082,-4.69E-12,10.00014693,-2.095,-0.058564938,1.733010145,90.00000001 +241.32,50.43283629,-2.566031517,51.1289,-1.17E-11,10.00036899,-2.0465625,-0.16216774,1.644855661,90.00000001 +241.33,50.43283629,-2.566030109,51.1491,-2.34E-11,10.00036902,-1.998125,-0.265736737,1.555266891,90.00000001 +241.34,50.43283629,-2.566028702,51.1689,-2.13E-11,10.00036905,-1.9484375,-0.369250157,1.464321873,90.00000001 +241.35,50.43283629,-2.566027294,51.1881,1.56E-12,10.00036908,-1.8978125,-0.472686514,1.372099962,90.00000001 +241.36,50.43283629,-2.566025887,51.2068,3.13E-11,10.00036911,-1.846875,-0.576024151,1.278681542,90.00000001 +241.37,50.43283629,-2.566024479,51.2251,4.77E-11,10.00036914,-1.7946875,-0.679241523,1.18414809,90.00000001 +241.38,50.43283629,-2.566023072,51.2427,4.36E-11,10.00036917,-1.7415625,-0.782317032,1.088582053,90.00000001 +241.39,50.43283629,-2.566021664,51.2599,2.95E-11,10.0003692,-1.6884375,-0.885229133,0.992066739,90.00000001 +241.4,50.43283629,-2.566020257,51.2765,1.70E-11,10.00014719,-1.634375,-0.987956397,0.894686374,90.00000001 +241.41,50.43283629,-2.566018849,51.2926,4.84E-12,9.999481114,-1.5784375,-1.090477283,0.796525812,90.00000001 +241.42,50.43283629,-2.566017442,51.3081,-8.59E-12,9.999037073,-1.5215625,-1.192770532,0.697670654,90.00000001 +241.43,50.43283629,-2.566016035,51.323,-1.41E-11,9.999481163,-1.465,-1.294814602,0.598207128,90.00000001 +241.44,50.43283629,-2.566014627,51.3374,-7.97E-12,10.00014728,-1.408125,-1.396588293,0.498221925,90.00000001 +241.45,50.43283629,-2.56601322,51.3512,-9.37E-13,10.00036934,-1.3496875,-1.498070348,0.397802305,90.00000001 +241.46,50.43283629,-2.566011812,51.3644,2.34E-12,10.00036936,-1.2903125,-1.599239511,0.29703576,90.00000001 +241.47,50.43283629,-2.566010405,51.377,1.03E-11,10.00036938,-1.2315625,-1.700074697,0.196010237,90.00000001 +241.48,50.43283629,-2.566008997,51.389,2.42E-11,10.0003694,-1.1734375,-1.800554879,0.094813743,90.00000001 +241.49,50.43283629,-2.56600759,51.4005,3.44E-11,10.00036942,-1.1146875,-1.900659028,-0.00646537,90.00000001 +241.5,50.43283629,-2.566006182,51.4113,3.50E-11,10.00036943,-1.0546875,-2.000366232,-0.107738927,90.00000001 +241.51,50.43283629,-2.566004775,51.4216,2.59E-11,10.00014742,-0.9934375,-2.099655693,-0.20891846,90.00000001 +241.52,50.43283629,-2.566003367,51.4312,1.02E-11,9.999481332,-0.93125,-2.198506669,-0.309915851,90.00000001 +241.53,50.43283629,-2.56600196,51.4402,-7.81E-12,9.999037279,-0.86875,-2.296898534,-0.410642977,90.00000001 +241.54,50.43283629,-2.566000553,51.4486,-2.44E-11,9.999481358,-0.8065625,-2.394810661,-0.511012005,90.00000001 +241.55,50.43283629,-2.565999145,51.4563,-3.05E-11,10.00014747,-0.7446875,-2.492222711,-0.610935443,90.00000001 +241.56,50.43283629,-2.565997738,51.4635,-1.55E-11,10.00036951,-0.681875,-2.589114286,-0.710326145,90.00000001 +241.57,50.43283629,-2.56599633,51.47,1.27E-11,10.00036952,-0.618125,-2.685465161,-0.809097423,90.00000001 +241.58,50.43283629,-2.565994923,51.4758,3.03E-11,10.0001475,-0.5553125,-2.781255224,-0.90716316,90.00000001 +241.59,50.43283629,-2.565993515,51.4811,2.88E-11,9.999481409,-0.493125,-2.876464423,-1.004437815,90.00000001 +241.6,50.43283629,-2.565992108,51.4857,2.09E-11,9.999037351,-0.4296875,-2.971072933,-1.100836589,90.00000001 +241.61,50.43283629,-2.565990701,51.4897,1.73E-11,9.999481423,-0.365,-3.06506093,-1.196275429,90.00000001 +241.62,50.43283629,-2.565989293,51.493,1.72E-11,10.00014753,-0.3,-3.158408875,-1.290671085,90.00000001 +241.63,50.43283629,-2.565987886,51.4957,1.56E-11,10.00036956,-0.2353125,-3.251097232,-1.383941281,90.00000001 +241.64,50.43283629,-2.565986478,51.4977,6.87E-12,10.00036957,-0.1715625,-3.343106634,-1.476004655,90.00000001 +241.65,50.43283629,-2.565985071,51.4991,-4.69E-12,10.00014754,-0.108125,-3.434417829,-1.566780879,90.00000001 +241.66,50.43283629,-2.565983663,51.4999,-4.69E-12,9.999481439,-0.043125,-3.525011795,-1.656190886,90.00000001 +241.67,50.43283629,-2.565982256,51.5,4.69E-12,9.999037373,0.023125,-3.614869683,-1.744156695,90.00000001 +241.68,50.43283629,-2.565980849,51.4994,4.69E-12,9.999481438,0.088125,-3.703972584,-1.830601531,90.00000001 +241.69,50.43283629,-2.565979441,51.4982,-7.03E-12,10.00014754,0.1515625,-3.792301935,-1.915450106,90.00000001 +241.7,50.43283629,-2.565978034,51.4964,-1.42E-11,10.00036957,0.215,-3.879839401,-1.998628337,90.00000001 +241.71,50.43283629,-2.565976626,51.4939,-7.81E-12,10.00036956,0.2784375,-3.966566533,-2.080063745,90.00000001 +241.72,50.43283629,-2.565975219,51.4908,5.31E-12,10.00014752,0.3415625,-4.05246534,-2.159685341,90.00000001 +241.73,50.43283629,-2.565973811,51.4871,1.41E-11,9.999481418,0.4053125,-4.13751783,-2.237423624,90.00000001 +241.74,50.43283629,-2.565972404,51.4827,1.62E-11,9.999037345,0.47,-4.221706243,-2.313210814,90.00000001 +241.75,50.43283629,-2.565970997,51.4777,1.41E-11,9.999481404,0.5346875,-4.305012989,-2.386980906,90.00000001 +241.76,50.43283629,-2.565969589,51.472,5.47E-12,10.00014749,0.5984375,-4.387420764,-2.4586695,90.00000001 +241.77,50.43283629,-2.565968182,51.4657,-7.03E-12,10.00036952,0.6615625,-4.468912207,-2.528214086,90.00000001 +241.78,50.43283629,-2.565966774,51.4588,-1.27E-11,10.00036951,0.725,-4.549470417,-2.595553988,90.00000001 +241.79,50.43283629,-2.565965367,51.4512,-7.81E-12,10.00014746,0.788125,-4.629078491,-2.660630591,90.00000001 +241.8,50.43283629,-2.565963959,51.443,-1.56E-12,9.99948135,0.8496875,-4.70771987,-2.72338706,90.00000001 +241.81,50.43283629,-2.565962552,51.4342,1.56E-13,9.99903727,0.91,-4.785378112,-2.783768733,90.00000001 +241.82,50.43283629,-2.565961145,51.4248,-2.34E-12,9.999481321,0.9703125,-4.862036942,-2.841722841,90.00000001 +241.83,50.43283629,-2.565959737,51.4148,-1.17E-11,10.00014741,1.0315625,-4.937680435,-2.897198964,90.00000001 +241.84,50.43283629,-2.56595833,51.4042,-2.34E-11,10.00036942,1.093125,-5.012292775,-2.950148744,90.00000001 +241.85,50.43283629,-2.565956922,51.3929,-2.09E-11,10.0003694,1.1534375,-5.085858321,-3.000525886,90.00000001 +241.86,50.43283629,-2.565955515,51.3811,7.81E-13,10.00036938,1.213125,-5.158361776,-3.048286502,90.00000001 +241.87,50.43283629,-2.565954107,51.3687,2.27E-11,10.00036937,1.2734375,-5.229787955,-3.093389052,90.00000001 +241.88,50.43283629,-2.5659527,51.3556,2.72E-11,10.00036935,1.3328125,-5.300121962,-3.135794059,90.00000001 +241.89,50.43283629,-2.565951292,51.342,2.11E-11,10.00036932,1.3896875,-5.36934913,-3.175464626,90.00000001 +241.9,50.43283629,-2.565949885,51.3278,1.48E-11,10.0003693,1.4453125,-5.437454961,-3.212366087,90.00000001 +241.91,50.43283629,-2.565948477,51.3131,4.84E-12,10.00036928,1.5015625,-5.504425248,-3.246466415,90.00000001 +241.92,50.43283629,-2.56594707,51.2978,-8.59E-12,10.00014722,1.5584375,-5.570245952,-3.277735701,90.00000001 +241.93,50.43283629,-2.565945662,51.2819,-1.64E-11,9.999481098,1.6146875,-5.634903437,-3.306146788,90.00000001 +241.94,50.43283629,-2.565944255,51.2655,-1.50E-11,9.999037005,1.6696875,-5.698384181,-3.331674865,90.00000001 +241.95,50.43283629,-2.565942848,51.2485,-5.47E-12,9.999481045,1.7234375,-5.760674835,-3.354297645,90.00000001 +241.96,50.43283629,-2.56594144,51.231,7.97E-12,10.00014712,1.7765625,-5.821762449,-3.373995418,90.00000001 +241.97,50.43283629,-2.565940033,51.213,1.27E-11,10.00036912,1.8296875,-5.881634304,-3.390751054,90.00000001 +241.98,50.43283629,-2.565938625,51.1944,-7.82E-13,10.00036909,1.8815625,-5.940277795,-3.404549883,90.00000001 +241.99,50.43283629,-2.565937218,51.1753,-1.95E-11,10.00036906,1.9315625,-5.997680775,-3.415379931,90.00000001 +242,50.43283629,-2.56593581,51.1558,-2.03E-11,10.00036903,1.9815625,-6.053831211,-3.423231687,90.00000001 +242.01,50.43283629,-2.565934403,51.1357,-2.19E-12,10.000369,2.0315625,-6.108717417,-3.428098333,90.00000001 +242.02,50.43283629,-2.565932995,51.1151,1.16E-11,10.00036897,2.0796875,-6.162327817,-3.42997563,90.00000001 +242.03,50.43283629,-2.565931588,51.0941,6.25E-12,10.00036894,2.1265625,-6.214651355,-3.428861914,90.00000001 +242.04,50.43283629,-2.56593018,51.0726,-8.59E-12,10.0003689,2.1734375,-6.265677028,-3.424758219,90.00000001 +242.05,50.43283629,-2.565928773,51.0506,-1.80E-11,10.00014684,2.2196875,-6.31539418,-3.417668095,90.00000001 +242.06,50.43283629,-2.565927365,51.0282,-1.73E-11,9.999480701,2.2646875,-6.36379244,-3.407597674,90.00000001 +242.07,50.43283629,-2.565925958,51.0053,-1.03E-11,9.999036599,2.308125,-6.410861725,-3.39455578,90.00000001 +242.08,50.43283629,-2.565924551,50.982,-6.25E-12,9.999480629,2.35,-6.45659218,-3.378553813,90.00000001 +242.09,50.43283629,-2.565923143,50.9583,-1.31E-11,10.00014669,2.3915625,-6.500974236,-3.359605641,90.00000001 +242.1,50.43283629,-2.565921736,50.9342,-2.34E-11,10.00036869,2.433125,-6.543998668,-3.337727878,90.00000001 +242.11,50.43283629,-2.565920328,50.9096,-2.19E-11,10.00036865,2.473125,-6.585656481,-3.312939603,90.00000001 +242.12,50.43283629,-2.565918921,50.8847,-7.03E-12,10.00036861,2.51125,-6.625938966,-3.285262361,90.00000001 +242.13,50.43283629,-2.565917513,50.8594,9.53E-12,10.00036857,2.5484375,-6.664837644,-3.254720273,90.00000001 +242.14,50.43283629,-2.565916106,50.8337,1.88E-11,10.00036853,2.5846875,-6.70234455,-3.221340096,90.00000001 +242.15,50.43283629,-2.565914698,50.8077,1.80E-11,10.00036849,2.6196875,-6.738451663,-3.185150821,90.00000001 +242.16,50.43283629,-2.565913291,50.7813,7.03E-12,10.00014641,2.6534375,-6.773151591,-3.146184076,90.00000001 +242.17,50.43283629,-2.565911883,50.7546,-1.08E-11,9.999480273,2.68625,-6.806437058,-3.10447378,90.00000001 +242.18,50.43283629,-2.565910476,50.7276,-2.72E-11,9.999036165,2.7184375,-6.838301018,-3.060056373,90.00000001 +242.19,50.43283629,-2.565909069,50.7002,-3.52E-11,9.999480188,2.7496875,-6.868736937,-3.012970529,90.00000001 +242.2,50.43283629,-2.565907661,50.6726,-3.38E-11,10.00014624,2.7796875,-6.897738399,-2.96325733,90.00000001 +242.21,50.43283629,-2.565906254,50.6446,-2.66E-11,10.00036823,2.808125,-6.92529933,-2.910960092,90.00000001 +242.22,50.43283629,-2.565904846,50.6164,-2.03E-11,10.00036819,2.8346875,-6.951414059,-2.856124536,90.00000001 +242.23,50.43283629,-2.565903439,50.5879,-1.86E-11,10.00036814,2.86,-6.976077027,-2.798798332,90.00000001 +242.24,50.43283629,-2.565902031,50.5592,-1.62E-11,10.0003681,2.8846875,-6.999283136,-2.739031558,90.00000001 +242.25,50.43283629,-2.565900624,50.5302,-8.59E-12,10.00036805,2.908125,-7.021027572,-2.676876294,90.00000001 +242.26,50.43283629,-2.565899216,50.501,-3.12E-12,10.00036801,2.93,-7.041305694,-2.612386743,90.00000001 +242.27,50.43283629,-2.565897809,50.4716,-1.25E-11,10.00036796,2.95125,-7.060113377,-2.545619169,90.00000001 +242.28,50.43283629,-2.565896401,50.442,-3.44E-11,10.00036792,2.9715625,-7.077446611,-2.476631785,90.00000001 +242.29,50.43283629,-2.565894994,50.4121,-4.91E-11,10.00014584,2.9896875,-7.093301843,-2.40548475,90.00000001 +242.3,50.43283629,-2.565893586,50.3822,-4.45E-11,9.999479691,3.0065625,-7.107675693,-2.332240118,90.00000001 +242.31,50.43283629,-2.565892179,50.352,-3.28E-11,9.999035578,3.023125,-7.120565238,-2.256961657,90.00000001 +242.32,50.43283629,-2.565890772,50.3217,-3.05E-11,9.999479596,3.0378125,-7.131967728,-2.179715143,90.00000001 +242.33,50.43283629,-2.565889364,50.2912,-3.28E-11,10.00014565,3.05,-7.141880815,-2.100567899,90.00000001 +242.34,50.43283629,-2.565887957,50.2607,-2.58E-11,10.00036763,3.0615625,-7.150302377,-2.019588909,90.00000001 +242.35,50.43283629,-2.565886549,50.23,-1.41E-11,10.00036758,3.073125,-7.157230698,-1.936848819,90.00000001 +242.36,50.43283629,-2.565885142,50.1992,-1.17E-11,10.0001455,3.0828125,-7.162664343,-1.852419763,90.00000001 +242.37,50.43283629,-2.565883734,50.1683,-1.64E-11,9.999479356,3.0896875,-7.16660211,-1.766375311,90.00000001 +242.38,50.43283629,-2.565882327,50.1374,-1.87E-11,9.999035242,3.095,-7.169043254,-1.678790633,90.00000001 +242.39,50.43283629,-2.56588092,50.1064,-1.88E-11,9.999479259,3.1,-7.169987259,-1.589741991,90.00000001 +242.4,50.43283629,-2.565879512,50.0754,-1.64E-11,10.00014531,3.1046875,-7.169433897,-1.499307077,90.00000001 +242.41,50.43283629,-2.565878105,50.0443,-9.38E-12,10.00036729,3.108125,-7.167383281,-1.407564732,90.00000001 +242.42,50.43283629,-2.565876697,50.0132,-2.50E-12,10.00036725,3.1096875,-7.163835812,-1.314594995,90.00000001 +242.43,50.43283629,-2.56587529,49.9821,-3.12E-12,10.00014516,3.1096875,-7.158792294,-1.220478885,90.00000001 +242.44,50.43283629,-2.565873882,49.951,-1.09E-11,9.999479017,3.108125,-7.152253814,-1.125298506,90.00000001 +242.45,50.43283629,-2.565872475,49.9199,-1.80E-11,9.999034902,3.1046875,-7.144221576,-1.029136879,90.00000001 +242.46,50.43283629,-2.565871068,49.8889,-1.95E-11,9.999478919,3.1,-7.134697414,-0.932077829,90.00000001 +242.47,50.43283629,-2.56586966,49.8579,-1.89E-11,10.00014497,3.095,-7.123683274,-0.834205923,90.00000001 +242.48,50.43283629,-2.565868253,49.827,-1.41E-11,10.00036695,3.089375,-7.111181392,-0.735606648,90.00000001 +242.49,50.43283629,-2.565866845,49.7961,2.34E-12,10.00036691,3.0815625,-7.097194461,-0.636365888,90.00000001 +242.5,50.43283629,-2.565865438,49.7653,2.34E-11,10.00014482,3.07125,-7.081725403,-0.53657022,90.00000001 +242.51,50.43283629,-2.56586403,49.7347,3.28E-11,9.999478677,3.06,-7.064777368,-0.436306616,90.00000001 +242.52,50.43283629,-2.565862623,49.7041,2.81E-11,9.999034564,3.048125,-7.046353968,-0.335662626,90.00000001 +242.53,50.43283629,-2.565861216,49.6737,2.11E-11,9.999478583,3.0346875,-7.02645904,-0.234725854,90.00000001 +242.54,50.43283629,-2.565859808,49.6434,1.89E-11,10.00014463,3.02,-7.005096709,-0.133584422,90.00000001 +242.55,50.43283629,-2.565858401,49.6133,1.72E-11,10.00036662,3.0046875,-6.982271446,-0.032326508,90.00000001 +242.56,50.43283629,-2.565856993,49.5833,1.33E-11,10.00036657,2.9878125,-6.957988062,0.068959596,90.00000001 +242.57,50.43283629,-2.565855586,49.5535,1.56E-11,10.00014449,2.968125,-6.932251543,0.170185539,90.00000001 +242.58,50.43283629,-2.565854178,49.5239,2.42E-11,9.999478349,2.946875,-6.905067331,0.271263144,90.00000001 +242.59,50.43283629,-2.565852771,49.4946,2.13E-11,9.999034236,2.9265625,-6.876441099,0.372104174,90.00000001 +242.6,50.43283629,-2.565851364,49.4654,4.69E-12,9.999478256,2.90625,-6.846378806,0.472620681,90.00000001 +242.61,50.43283629,-2.565849956,49.4364,-2.50E-12,10.00014431,2.8828125,-6.814886696,0.572725117,90.00000001 +242.62,50.43283629,-2.565848549,49.4077,6.25E-12,10.0003663,2.8565625,-6.781971417,0.672330105,90.00000001 +242.63,50.43283629,-2.565847141,49.3793,1.25E-11,10.00036625,2.83,-6.747639786,0.771348786,90.00000001 +242.64,50.43283629,-2.565845734,49.3511,7.97E-12,10.00036621,2.803125,-6.711899022,0.869694872,90.00000001 +242.65,50.43283629,-2.565844326,49.3232,2.34E-12,10.00036617,2.7746875,-6.674756575,0.967282533,90.00000001 +242.66,50.43283629,-2.565842919,49.2956,1.41E-12,10.00036612,2.745,-6.636220178,1.064026743,90.00000001 +242.67,50.43283629,-2.565841511,49.2683,-9.38E-13,10.00036608,2.7146875,-6.596297912,1.159843106,90.00000001 +242.68,50.43283629,-2.565840104,49.2413,-9.38E-12,10.000144,2.683125,-6.554998025,1.254648083,90.00000001 +242.69,50.43283629,-2.565838696,49.2146,-1.80E-11,9.999477864,2.6496875,-6.512329285,1.34835894,90.00000001 +242.7,50.43283629,-2.565837289,49.1883,-1.88E-11,9.999033757,2.6146875,-6.468300515,1.44089403,90.00000001 +242.71,50.43283629,-2.565835882,49.1623,-9.53E-12,9.999477783,2.5784375,-6.422920883,1.532172681,90.00000001 +242.72,50.43283629,-2.565834474,49.1367,4.53E-12,10.00014384,2.5415625,-6.376199899,1.622115195,90.00000001 +242.73,50.43283629,-2.565833067,49.1115,9.22E-12,10.00036583,2.5046875,-6.328147361,1.710643248,90.00000001 +242.74,50.43283629,-2.565831659,49.0866,-4.69E-12,10.0003658,2.4665625,-6.278773296,1.797679548,90.00000001 +242.75,50.43283629,-2.565830252,49.0621,-2.50E-11,10.00036576,2.42625,-6.22808796,1.883148292,90.00000001 +242.76,50.43283629,-2.565828844,49.0381,-3.28E-11,10.00036572,2.385,-6.176101952,1.966974825,90.00000001 +242.77,50.43283629,-2.565827437,49.0144,-2.44E-11,10.00036568,2.3434375,-6.122826159,2.049086209,90.00000001 +242.78,50.43283629,-2.565826029,48.9912,-7.81E-12,10.00036565,2.30125,-6.068271696,2.129410709,90.00000001 +242.79,50.43283629,-2.565824622,48.9684,5.47E-12,10.00036561,2.258125,-6.012449965,2.207878368,90.00000001 +242.8,50.43283629,-2.565823214,48.946,4.84E-12,10.00036558,2.213125,-5.955372597,2.284420716,90.00000001 +242.81,50.43283629,-2.565821807,48.9241,-7.03E-12,10.00014351,2.1665625,-5.897051509,2.358971005,90.00000001 +242.82,50.43283629,-2.565820399,48.9027,-1.41E-11,9.999477376,2.12,-5.837498907,2.431464204,90.00000001 +242.83,50.43283629,-2.565818992,48.8817,-9.38E-12,9.999033278,2.073125,-5.776727221,2.501837172,90.00000001 +242.84,50.43283629,-2.565817585,48.8612,-2.34E-12,9.999477312,2.0246875,-5.714749173,2.570028489,90.00000001 +242.85,50.43283629,-2.565816177,48.8412,-2.34E-12,10.00014338,1.9746875,-5.651577654,2.635978739,90.00000001 +242.86,50.43283629,-2.56581477,48.8217,-1.17E-11,10.00036538,1.9234375,-5.587225842,2.699630339,90.00000001 +242.87,50.43283629,-2.565813362,48.8027,-2.59E-11,10.00036535,1.8715625,-5.521707259,2.760927828,90.00000001 +242.88,50.43283629,-2.565811955,48.7843,-3.36E-11,10.00036532,1.82,-5.455035483,2.819817747,90.00000001 +242.89,50.43283629,-2.565810547,48.7663,-2.97E-11,10.0003653,1.768125,-5.387224553,2.876248705,90.00000001 +242.9,50.43283629,-2.56580914,48.7489,-2.25E-11,10.00036527,1.7146875,-5.318288506,2.930171596,90.00000001 +242.91,50.43283629,-2.565807732,48.732,-1.64E-11,10.00036524,1.6603125,-5.248241837,2.981539325,90.00000001 +242.92,50.43283629,-2.565806325,48.7157,-3.13E-12,10.00036522,1.60625,-5.177099157,3.030307086,90.00000001 +242.93,50.43283629,-2.565804917,48.6999,1.86E-11,10.00036519,1.5515625,-5.104875249,3.076432366,90.00000001 +242.94,50.43283629,-2.56580351,48.6846,3.20E-11,10.00014313,1.4946875,-5.031585295,3.119874943,90.00000001 +242.95,50.43283629,-2.565802102,48.67,2.81E-11,9.999477012,1.436875,-4.957244594,3.160596944,90.00000001 +242.96,50.43283629,-2.565800695,48.6559,2.20E-11,9.999032925,1.38,-4.881868559,3.198562904,90.00000001 +242.97,50.43283629,-2.565799288,48.6424,2.66E-11,9.99947697,1.323125,-4.805473059,3.233739647,90.00000001 +242.98,50.43283629,-2.56579788,48.6294,3.44E-11,10.00014305,1.2646875,-4.728073967,3.266096522,90.00000001 +242.99,50.43283629,-2.565796473,48.6171,3.75E-11,10.00036506,1.205,-4.649687496,3.295605281,90.00000001 +243,50.43283629,-2.565795065,48.6053,3.83E-11,10.00036504,1.145,-4.570330034,3.322240255,90.00000001 +243.01,50.43283629,-2.565793658,48.5942,3.66E-11,10.00036503,1.0846875,-4.490018024,3.345978183,90.00000001 +243.02,50.43283629,-2.56579225,48.5836,2.66E-11,10.00036501,1.0234375,-4.408768426,3.366798324,90.00000001 +243.03,50.43283629,-2.565790843,48.5737,1.09E-11,10.00036499,0.9615625,-4.326598085,3.384682628,90.00000001 +243.04,50.43283629,-2.565789435,48.5644,9.38E-13,10.00036498,0.9003125,-4.243524133,3.399615398,90.00000001 +243.05,50.43283629,-2.565788028,48.5557,-3.28E-12,10.00014293,0.8396875,-4.159564043,3.411583684,90.00000001 +243.06,50.43283629,-2.56578662,48.5476,-1.03E-11,9.999476821,0.778125,-4.074735235,3.420577002,90.00000001 +243.07,50.43283629,-2.565785213,48.5401,-1.56E-11,9.999032744,0.715,-3.989055528,3.426587558,90.00000001 +243.08,50.43283629,-2.565783806,48.5333,-8.44E-12,9.999476798,0.6515625,-3.902542682,3.429610025,90.00000001 +243.09,50.43283629,-2.565782398,48.5271,7.03E-12,10.00014289,0.5884375,-3.815214919,3.429641824,90.00000001 +243.1,50.43283629,-2.565780991,48.5215,1.56E-11,10.00036491,0.525,-3.727090343,3.426682956,90.00000001 +243.11,50.43283629,-2.565779583,48.5166,9.22E-12,10.0003649,0.4615625,-3.638187404,3.420735998,90.00000001 +243.12,50.43283629,-2.565778176,48.5123,-2.97E-12,10.0003649,0.398125,-3.548524723,3.411806049,90.00000001 +243.13,50.43283629,-2.565776768,48.5086,-1.41E-12,10.00036489,0.3334375,-3.458120978,3.39990096,90.00000001 +243.14,50.43283629,-2.565775361,48.5056,1.97E-11,10.00014285,0.268125,-3.36699502,3.385031101,90.00000001 +243.15,50.43283629,-2.565773953,48.5033,4.38E-11,9.999476752,0.20375,-3.275165928,3.367209478,90.00000001 +243.16,50.43283629,-2.565772546,48.5015,5.31E-11,9.999032683,0.14,-3.18265284,3.346451618,90.00000001 +243.17,50.43283629,-2.565771139,48.5005,4.30E-11,9.999476747,0.07625,-3.089475063,3.32277557,90.00000001 +243.18,50.43283629,-2.565769731,48.5,1.91E-11,10.00014285,0.011875,-2.995652135,3.296201959,90.00000001 +243.19,50.43283629,-2.565768324,48.5002,-1.56E-12,10.00036488,-0.0534375,-2.901203595,3.266754106,90.00000001 +243.2,50.43283629,-2.565766916,48.5011,-3.13E-12,10.00036488,-0.118125,-2.806149209,3.234457564,90.00000001 +243.21,50.43283629,-2.565765509,48.5026,8.59E-12,10.00014285,-0.1815625,-2.710508745,3.199340465,90.00000001 +243.22,50.43283629,-2.565764101,48.5047,1.73E-11,9.999476754,-0.2453125,-2.614302255,3.161433577,90.00000001 +243.23,50.43283629,-2.565762694,48.5075,1.97E-11,9.999032693,-0.31,-2.517549795,3.120769845,90.00000001 +243.24,50.43283629,-2.565761287,48.5109,1.81E-11,9.999476764,-0.3746875,-2.420271531,3.077384736,90.00000001 +243.25,50.43283629,-2.565759879,48.515,9.38E-12,10.00014287,-0.4384375,-2.32248786,3.031316122,90.00000001 +243.26,50.43283629,-2.565758472,48.5197,-4.53E-12,10.00036491,-0.5015625,-2.224219181,2.98260411,90.00000001 +243.27,50.43283629,-2.565757064,48.525,-1.17E-11,10.00036492,-0.565,-2.125486005,2.93129127,90.00000001 +243.28,50.43283629,-2.565755657,48.531,-5.47E-12,10.00014289,-0.6284375,-2.026308959,2.877422294,90.00000001 +243.29,50.43283629,-2.565754249,48.5376,9.38E-12,9.999476805,-0.69125,-1.926708726,2.821044164,90.00000001 +243.3,50.43283629,-2.565752842,48.5448,2.44E-11,9.99903275,-0.7534375,-1.826706105,2.762206039,90.00000001 +243.31,50.43283629,-2.565751435,48.5527,2.89E-11,9.999476829,-0.8153125,-1.726322009,2.700959257,90.00000001 +243.32,50.43283629,-2.565750027,48.5611,1.33E-11,10.00014294,-0.878125,-1.625577407,2.63735716,90.00000001 +243.33,50.43283629,-2.56574862,48.5702,-1.19E-11,10.00036499,-0.9415625,-1.524493328,2.571455268,90.00000001 +243.34,50.43283629,-2.565747212,48.58,-2.11E-11,10.000365,-1.0028125,-1.423090856,2.503310991,90.00000001 +243.35,50.43283629,-2.565745805,48.5903,-1.42E-11,10.00014299,-1.061875,-1.321391192,2.432983802,90.00000001 +243.36,50.43283629,-2.565744397,48.6012,-1.48E-11,9.999476905,-1.121875,-1.21941559,2.360535065,90.00000001 +243.37,50.43283629,-2.56574299,48.6127,-2.50E-11,9.999032857,-1.183125,-1.117185309,2.286027863,90.00000001 +243.38,50.43283629,-2.565741583,48.6249,-2.50E-11,9.999476942,-1.243125,-1.01472172,2.209527226,90.00000001 +243.39,50.43283629,-2.565740175,48.6376,-1.03E-11,10.00014306,-1.30125,-0.91204625,2.131099846,90.00000001 +243.4,50.43283629,-2.565738768,48.6509,8.44E-12,10.00036511,-1.35875,-0.809180273,2.050814078,90.00000001 +243.41,50.43283629,-2.56573736,48.6648,2.64E-11,10.00036514,-1.41625,-0.70614533,1.968739993,90.00000001 +243.42,50.43283629,-2.565735953,48.6792,4.22E-11,10.00036516,-1.4734375,-0.602962907,1.884949156,90.00000001 +243.43,50.43283629,-2.565734545,48.6943,4.91E-11,10.00036518,-1.53,-0.499654549,1.799514617,90.00000001 +243.44,50.43283629,-2.565733138,48.7098,3.98E-11,10.00014317,-1.58625,-0.396241912,1.712510861,90.00000001 +243.45,50.43283629,-2.56573173,48.726,1.72E-11,9.9994771,-1.641875,-0.292746426,1.624013805,90.00000001 +243.46,50.43283629,-2.565730323,48.7427,-4.69E-12,9.99903306,-1.69625,-0.189189862,1.534100513,90.00000001 +243.47,50.43283629,-2.565728916,48.7599,-1.27E-11,9.999477153,-1.75,-0.085593821,1.442849535,90.00000001 +243.48,50.43283629,-2.565727508,48.7777,-7.81E-12,10.00014328,-1.803125,0.018020153,1.350340343,90.00000001 +243.49,50.43283629,-2.565726101,48.796,-1.56E-12,10.00036534,-1.8546875,0.121630346,1.256653607,90.00000001 +243.5,50.43283629,-2.565724693,48.8148,1.56E-13,10.00036537,-1.905,0.225215156,1.16187109,90.00000001 +243.51,50.43283629,-2.565723286,48.8341,5.55E-17,10.0003654,-1.955,0.328752927,1.066075354,90.00000001 +243.52,50.43283629,-2.565721878,48.8539,5.55E-17,10.00036543,-2.005,0.432222,0.969350051,90.00000001 +243.53,50.43283629,-2.565720471,48.8742,2.34E-12,10.00036546,-2.0546875,0.535600832,0.871779407,90.00000001 +243.54,50.43283629,-2.565719063,48.895,9.37E-12,10.0003655,-2.103125,0.638867823,0.773448562,90.00000001 +243.55,50.43283629,-2.565717656,48.9163,1.62E-11,10.00036553,-2.1496875,0.742001372,0.674443288,90.00000001 +243.56,50.43283629,-2.565716248,48.938,1.80E-11,10.00036556,-2.195,0.844979993,0.574849874,90.00000001 +243.57,50.43283629,-2.565714841,48.9602,1.72E-11,10.00014357,-2.24,0.947782144,0.474755178,90.00000001 +243.58,50.43283629,-2.565713433,48.9828,1.50E-11,9.999477502,-2.2846875,1.050386394,0.374246521,90.00000001 +243.59,50.43283629,-2.565712026,49.0059,7.03E-12,9.999033472,-2.3284375,1.152771202,0.273411449,90.00000001 +243.6,50.43283629,-2.565710619,49.0294,-7.97E-12,9.999477574,-2.37125,1.25491531,0.172338027,90.00000001 +243.61,50.43283629,-2.565709211,49.0533,-2.20E-11,10.00014371,-2.413125,1.356797348,0.071114261,90.00000001 +243.62,50.43283629,-2.565707804,49.0777,-2.34E-11,10.00036578,-2.453125,1.458396057,-0.030171442,90.00000001 +243.63,50.43283629,-2.565706396,49.1024,-1.09E-11,10.00036582,-2.49125,1.559690183,-0.131430903,90.00000001 +243.64,50.43283629,-2.565704989,49.1275,4.69E-12,10.00036586,-2.5284375,1.660658582,-0.232575716,90.00000001 +243.65,50.43283629,-2.565703581,49.153,1.16E-11,10.0003659,-2.565,1.761280169,-0.333517759,90.00000001 +243.66,50.43283629,-2.565702174,49.1788,2.34E-12,10.00036594,-2.60125,1.861533975,-0.434168911,90.00000001 +243.67,50.43283629,-2.565700766,49.205,-1.80E-11,10.00036598,-2.6365625,1.961398972,-0.534441509,90.00000001 +243.68,50.43283629,-2.565699359,49.2316,-3.05E-11,10.00036602,-2.6696875,2.060854361,-0.634248065,90.00000001 +243.69,50.43283629,-2.565697951,49.2584,-2.44E-11,10.00036606,-2.7015625,2.159879401,-0.733501543,90.00000001 +243.7,50.43283629,-2.565696544,49.2856,-1.03E-11,10.00014407,-2.7334375,2.258453352,-0.832115372,90.00000001 +243.71,50.43283629,-2.565695136,49.3131,-2.34E-12,9.999478019,-2.7646875,2.356555644,-0.930003607,90.00000001 +243.72,50.43283629,-2.565693729,49.3409,-3.75E-12,9.999033996,-2.7946875,2.454165823,-1.02708082,90.00000001 +243.73,50.43283629,-2.565692322,49.369,-8.59E-12,9.999478106,-2.8228125,2.551263491,-1.123262443,90.00000001 +243.74,50.43283629,-2.565690914,49.3974,-5.47E-12,10.00014425,-2.848125,2.647828308,-1.218464595,90.00000001 +243.75,50.43283629,-2.565689507,49.426,6.88E-12,10.00036633,-2.8715625,2.743840221,-1.312604196,90.00000001 +243.76,50.43283629,-2.565688099,49.4548,1.64E-11,10.00036637,-2.8953125,2.839279061,-1.405599143,90.00000001 +243.77,50.43283629,-2.565686692,49.4839,2.13E-11,10.00036642,-2.9196875,2.934125005,-1.497368475,90.00000001 +243.78,50.43283629,-2.565685284,49.5132,2.66E-11,10.00036646,-2.9428125,3.02835817,-1.587831979,90.00000001 +243.79,50.43283629,-2.565683877,49.5428,2.73E-11,10.00036651,-2.9628125,3.121958905,-1.676910931,90.00000001 +243.8,50.43283629,-2.565682469,49.5725,2.50E-11,10.00036656,-2.98,3.214907671,-1.764527579,90.00000001 +243.81,50.43283629,-2.565681062,49.6024,2.89E-11,10.0003666,-2.996875,3.307185045,-1.85060555,90.00000001 +243.82,50.43283629,-2.565679654,49.6324,3.06E-11,10.00036665,-3.0146875,3.398771718,-1.935069785,90.00000001 +243.83,50.43283629,-2.565678247,49.6627,1.87E-11,10.00014466,-3.03125,3.489648611,-2.017846544,90.00000001 +243.84,50.43283629,-2.565676839,49.6931,4.69E-12,9.999478613,-3.044375,3.579796759,-2.098863751,90.00000001 +243.85,50.43283629,-2.565675432,49.7236,8.33E-17,9.999034594,-3.055,3.669197312,-2.178050701,90.00000001 +243.86,50.43283629,-2.565674025,49.7542,1.94E-16,9.999478708,-3.065,3.757831591,-2.25533841,90.00000001 +243.87,50.43283629,-2.565672617,49.7849,2.22E-16,10.00014485,-3.075,3.84568109,-2.330659384,90.00000001 +243.88,50.43283629,-2.56567121,49.8157,-2.34E-12,10.00036694,-3.0846875,3.932727474,-2.403947963,90.00000001 +243.89,50.43283629,-2.565669802,49.8466,-9.37E-12,10.00036699,-3.093125,4.01895258,-2.475140318,90.00000001 +243.9,50.43283629,-2.565668395,49.8776,-1.64E-11,10.00036703,-3.0996875,4.10433836,-2.544174284,90.00000001 +243.91,50.43283629,-2.565666987,49.9086,-1.66E-11,10.00036708,-3.1046875,4.188866996,-2.6109897,90.00000001 +243.92,50.43283629,-2.56566558,49.9397,-1.02E-11,10.0001451,-3.108125,4.272520839,-2.675528296,90.00000001 +243.93,50.43283629,-2.565664172,49.9708,-3.91E-12,9.999479047,-3.1096875,4.355282415,-2.737733808,90.00000001 +243.94,50.43283629,-2.565662765,50.0019,-3.91E-12,9.999035029,-3.1096875,4.437134478,-2.79755192,90.00000001 +243.95,50.43283629,-2.565661358,50.033,-1.02E-11,9.999479144,-3.108125,4.518059839,-2.854930549,90.00000001 +243.96,50.43283629,-2.56565995,50.0641,-1.42E-11,10.00014529,-3.105,4.598041711,-2.909819677,90.00000001 +243.97,50.43283629,-2.565658543,50.0951,-7.03E-12,10.00036737,-3.1015625,4.677063362,-2.962171346,90.00000001 +243.98,50.43283629,-2.565657135,50.1261,4.69E-12,10.00036742,-3.098125,4.755108236,-3.011940007,90.00000001 +243.99,50.43283629,-2.565655728,50.1571,7.03E-12,10.00014544,-3.0928125,4.832160058,-3.059082173,90.00000001 +244,50.43283629,-2.56565432,50.188,2.34E-12,9.999479387,-3.0846875,4.90820273,-3.103556818,90.00000001 +244.01,50.43283629,-2.565652913,50.2188,-8.33E-17,9.999035369,-3.075,4.983220438,-3.14532504,90.00000001 +244.02,50.43283629,-2.565651506,50.2495,5.55E-17,9.999479483,-3.065,5.057197426,-3.184350571,90.00000001 +244.03,50.43283629,-2.565650098,50.2801,2.34E-12,10.00014563,-3.0546875,5.13011828,-3.220599261,90.00000001 +244.04,50.43283629,-2.565648691,50.3106,9.38E-12,10.00036771,-3.043125,5.201967818,-3.254039542,90.00000001 +244.05,50.43283629,-2.565647283,50.341,1.88E-11,10.00036776,-3.029375,5.27273097,-3.284642249,90.00000001 +244.06,50.43283629,-2.565645876,50.3712,2.81E-11,10.00014577,-3.013125,5.342392955,-3.312380683,90.00000001 +244.07,50.43283629,-2.565644468,50.4013,3.30E-11,9.99947972,-2.995,5.410939276,-3.337230722,90.00000001 +244.08,50.43283629,-2.565643061,50.4311,2.66E-11,9.999035701,-2.9765625,5.478355611,-3.359170594,90.00000001 +244.09,50.43283629,-2.565641654,50.4608,1.33E-11,9.999479813,-2.9584375,5.544627805,-3.378181276,90.00000001 +244.1,50.43283629,-2.565640246,50.4903,1.56E-12,10.00014596,-2.939375,5.60974211,-3.394246096,90.00000001 +244.11,50.43283629,-2.565638839,50.5196,-8.59E-12,10.00036804,-2.918125,5.673684887,-3.407351073,90.00000001 +244.12,50.43283629,-2.565637431,50.5487,-1.63E-11,10.00036808,-2.8946875,5.736442788,-3.417484806,90.00000001 +244.13,50.43283629,-2.565636024,50.5775,-1.63E-11,10.00036813,-2.8696875,5.798002691,-3.42463847,90.00000001 +244.14,50.43283629,-2.565634616,50.6061,-6.25E-12,10.00036817,-2.8434375,5.858351763,-3.428805764,90.00000001 +244.15,50.43283629,-2.565633209,50.6344,8.59E-12,10.00014618,-2.8165625,5.917477398,-3.429983078,90.00000001 +244.16,50.43283629,-2.565631801,50.6624,1.31E-11,9.999480129,-2.7896875,5.975367277,-3.42816938,90.00000001 +244.17,50.43283629,-2.565630394,50.6902,-2.34E-12,9.999036106,-2.7615625,6.032009254,-3.423366332,90.00000001 +244.18,50.43283629,-2.565628987,50.7177,-2.48E-11,9.999480215,-2.73125,6.087391527,-3.415578002,90.00000001 +244.19,50.43283629,-2.565627579,50.7448,-3.19E-11,10.00014636,-2.6996875,6.141502463,-3.404811266,90.00000001 +244.2,50.43283629,-2.565626172,50.7717,-1.64E-11,10.00036843,-2.6665625,6.194330891,-3.391075462,90.00000001 +244.21,50.43283629,-2.565624764,50.7982,3.91E-12,10.00036847,-2.6315625,6.245865694,-3.374382623,90.00000001 +244.22,50.43283629,-2.565623357,50.8243,4.69E-12,10.00014648,-2.5965625,6.296096159,-3.354747245,90.00000001 +244.23,50.43283629,-2.565621949,50.8501,-1.39E-11,9.999480423,-2.5615625,6.345011743,-3.332186516,90.00000001 +244.24,50.43283629,-2.565620542,50.8756,-2.81E-11,9.999036397,-2.5246875,6.392602248,-3.306720032,90.00000001 +244.25,50.43283629,-2.565619135,50.9006,-2.42E-11,9.999480502,-2.4865625,6.438857704,-3.278370023,90.00000001 +244.26,50.43283629,-2.565617727,50.9253,-1.41E-11,10.00014664,-2.448125,6.483768542,-3.247161241,90.00000001 +244.27,50.43283629,-2.56561632,50.9496,-1.31E-11,10.00036871,-2.4078125,6.52732531,-3.213120902,90.00000001 +244.28,50.43283629,-2.565614912,50.9735,-1.55E-11,10.00036875,-2.365,6.569518896,-3.176278684,90.00000001 +244.29,50.43283629,-2.565613505,50.9969,-9.37E-12,10.00036878,-2.321875,6.610340592,-3.136666674,90.00000001 +244.3,50.43283629,-2.565612097,51.0199,-5.62E-12,10.00036882,-2.2796875,6.649781746,-3.094319478,90.00000001 +244.31,50.43283629,-2.56561069,51.0425,-1.72E-11,10.00036886,-2.23625,6.687834222,-3.049273995,90.00000001 +244.32,50.43283629,-2.565609282,51.0647,-2.73E-11,10.00036889,-2.19,6.724489999,-3.001569471,90.00000001 +244.33,50.43283629,-2.565607875,51.0863,-1.39E-11,10.00014689,-2.143125,6.759741457,-2.951247505,90.00000001 +244.34,50.43283629,-2.565606467,51.1075,1.41E-11,9.999480825,-2.096875,6.793581203,-2.898352041,90.00000001 +244.35,50.43283629,-2.56560506,51.1283,3.28E-11,9.999036791,-2.049375,6.826002249,-2.842929203,90.00000001 +244.36,50.43283629,-2.565603653,51.1485,3.75E-11,9.999480889,-2,6.856997719,-2.785027235,90.00000001 +244.37,50.43283629,-2.565602245,51.1683,3.77E-11,10.00014702,-1.95,6.886561253,-2.724696727,90.00000001 +244.38,50.43283629,-2.565600838,51.1875,3.59E-11,10.00036908,-1.8996875,6.914686548,-2.661990163,90.00000001 +244.39,50.43283629,-2.56559943,51.2063,2.73E-11,10.00036911,-1.8484375,6.941367874,-2.596962375,90.00000001 +244.4,50.43283629,-2.565598023,51.2245,1.08E-11,10.00036914,-1.79625,6.966599503,-2.529669972,90.00000001 +244.41,50.43283629,-2.565596615,51.2422,-7.03E-12,10.00036917,-1.7434375,6.990376335,-2.460171681,90.00000001 +244.42,50.43283629,-2.565595208,51.2594,-1.78E-11,10.00036919,-1.6896875,7.01269327,-2.388528064,90.00000001 +244.43,50.43283629,-2.5655938,51.276,-1.78E-11,10.00036922,-1.6346875,7.033545668,-2.314801631,90.00000001 +244.44,50.43283629,-2.565592393,51.2921,-7.19E-12,10.00036925,-1.5784375,7.052929232,-2.239056668,90.00000001 +244.45,50.43283629,-2.565590985,51.3076,5.31E-12,10.00036927,-1.521875,7.070839892,-2.161359179,90.00000001 +244.46,50.43283629,-2.565589578,51.3225,2.19E-12,10.00014726,-1.4665625,7.087273869,-2.081776946,90.00000001 +244.47,50.43283629,-2.56558817,51.3369,-1.55E-11,9.999481184,-1.41125,7.102227781,-2.00037941,90.00000001 +244.48,50.43283629,-2.565586763,51.3508,-2.02E-11,9.999037139,-1.353125,7.115698477,-1.917237505,90.00000001 +244.49,50.43283629,-2.565585356,51.364,-2.78E-16,9.999481226,-1.293125,7.12768315,-1.832423708,90.00000001 +244.5,50.43283629,-2.565583948,51.3766,2.48E-11,10.00014735,-1.23375,7.138179278,-1.746012047,90.00000001 +244.51,50.43283629,-2.565582541,51.3887,3.44E-11,10.0003694,-1.175,7.147184742,-1.658077808,90.00000001 +244.52,50.43283629,-2.565581133,51.4001,2.42E-11,10.00036941,-1.11625,7.154697537,-1.568697767,90.00000001 +244.53,50.43283629,-2.565579726,51.411,2.50E-12,10.00036943,-1.0565625,7.160716229,-1.477949732,90.00000001 +244.54,50.43283629,-2.565578318,51.4213,-1.19E-11,10.00036945,-0.9946875,7.165239444,-1.385912943,90.00000001 +244.55,50.43283629,-2.565576911,51.4309,-1.02E-11,10.00036946,-0.931875,7.168266323,-1.292667557,90.00000001 +244.56,50.43283629,-2.565575503,51.4399,-3.91E-12,10.00036948,-0.8703125,7.169796178,-1.198294991,90.00000001 +244.57,50.43283629,-2.565574096,51.4483,9.37E-13,10.00036949,-0.8096875,7.169828722,-1.102877464,90.00000001 +244.58,50.43283629,-2.565572688,51.4561,9.37E-12,10.0003695,-0.748125,7.168363955,-1.006498228,90.00000001 +244.59,50.43283629,-2.565571281,51.4633,1.78E-11,10.00014748,-0.6846875,7.165402164,-0.909241336,90.00000001 +244.6,50.43283629,-2.565569873,51.4698,2.25E-11,9.999481391,-0.6203125,7.16094398,-0.811191584,90.00000001 +244.61,50.43283629,-2.565568466,51.4757,3.06E-11,9.999037334,-0.5565625,7.154990318,-0.712434401,90.00000001 +244.62,50.43283629,-2.565567059,51.4809,4.39E-11,9.999481409,-0.4934375,7.147542382,-0.613056017,90.00000001 +244.63,50.43283629,-2.565565651,51.4856,5.17E-11,10.00014752,-0.43,7.138601834,-0.513143007,90.00000001 +244.64,50.43283629,-2.565564244,51.4895,4.59E-11,10.00036956,-0.3665625,7.12817045,-0.412782516,90.00000001 +244.65,50.43283629,-2.565562836,51.4929,3.20E-11,10.00036956,-0.3034375,7.116250464,-0.312062093,90.00000001 +244.66,50.43283629,-2.565561429,51.4956,1.95E-11,10.00036956,-0.239375,7.102844341,-0.211069573,90.00000001 +244.67,50.43283629,-2.565560021,51.4977,4.84E-12,10.00036957,-0.17375,7.087954829,-0.109892961,90.00000001 +244.68,50.43283629,-2.565558614,51.4991,-1.64E-11,10.00036957,-0.1084375,7.071585138,-0.008620494,90.00000001 +244.69,50.43283629,-2.565557206,51.4998,-2.81E-11,10.00036957,-0.045,7.053738592,0.092659422,90.00000001 +244.7,50.43283629,-2.565555799,51.5,-1.64E-11,10.00014754,0.0184375,7.034419028,0.193858551,90.00000001 +244.71,50.43283629,-2.565554391,51.4995,4.69E-12,9.999481438,0.08375,7.013630343,0.294888657,90.00000001 +244.72,50.43283629,-2.565552984,51.4983,1.64E-11,9.99903737,0.1496875,6.991377006,0.39566162,90.00000001 +244.73,50.43283629,-2.565551577,51.4965,1.66E-11,9.999481433,0.2146875,6.9676636,0.496089548,90.00000001 +244.74,50.43283629,-2.565550169,51.494,7.81E-12,10.00014753,0.2784375,6.942495054,0.596084893,90.00000001 +244.75,50.43283629,-2.565548762,51.4909,-5.31E-12,10.00036956,0.3415625,6.915876696,0.69556045,90.00000001 +244.76,50.43283629,-2.565547354,51.4872,-1.17E-11,10.00036955,0.405,6.887814025,0.794429417,90.00000001 +244.77,50.43283629,-2.565545947,51.4828,-4.53E-12,10.00014751,0.4684375,6.858312944,0.892605678,90.00000001 +244.78,50.43283629,-2.565544539,51.4778,9.37E-12,9.999481403,0.5315625,6.827379583,0.990003518,90.00000001 +244.79,50.43283629,-2.565543132,51.4722,1.56E-11,9.999037329,0.595,6.795020359,1.08653814,90.00000001 +244.8,50.43283629,-2.565541725,51.4659,7.03E-12,9.999481386,0.6584375,6.761242148,1.182125205,90.00000001 +244.81,50.43283629,-2.565540317,51.459,-8.44E-12,10.00014747,0.7215625,6.726051882,1.276681519,90.00000001 +244.82,50.43283629,-2.56553891,51.4515,-1.56E-11,10.0003695,0.785,6.68945701,1.370124461,90.00000001 +244.83,50.43283629,-2.565537502,51.4433,-1.02E-11,10.00036948,0.848125,6.651465153,1.462372728,90.00000001 +244.84,50.43283629,-2.565536095,51.4345,-2.50E-12,10.00014744,0.9096875,6.612084159,1.553345706,90.00000001 +244.85,50.43283629,-2.565534687,51.4251,2.78E-16,9.999481322,0.97,6.571322338,1.642964155,90.00000001 +244.86,50.43283629,-2.56553328,51.4151,1.67E-16,9.99903724,1.03,6.529188225,1.73114998,90.00000001 +244.87,50.43283629,-2.565531873,51.4045,2.34E-12,9.999481289,1.0903125,6.485690529,1.817826119,90.00000001 +244.88,50.43283629,-2.565530465,51.3933,1.16E-11,10.00014737,1.1515625,6.440838419,1.902917169,90.00000001 +244.89,50.43283629,-2.565529058,51.3815,2.27E-11,10.00036939,1.213125,6.394641176,1.98634882,90.00000001 +244.9,50.43283629,-2.56552765,51.369,2.42E-11,10.00036937,1.2728125,6.347108482,2.068048304,90.00000001 +244.91,50.43283629,-2.565526243,51.356,1.97E-11,10.00036935,1.3296875,6.298250309,2.147944461,90.00000001 +244.92,50.43283629,-2.565524835,51.3424,1.64E-11,10.00036932,1.3853125,6.248076853,2.225967562,90.00000001 +244.93,50.43283629,-2.565523428,51.3283,1.09E-11,10.00014727,1.441875,6.196598543,2.302049654,90.00000001 +244.94,50.43283629,-2.56552202,51.3136,6.88E-12,9.999481148,1.5,6.143826151,2.376124216,90.00000001 +244.95,50.43283629,-2.565520613,51.2983,1.09E-11,9.999037057,1.558125,6.089770677,2.448126848,90.00000001 +244.96,50.43283629,-2.565519206,51.2824,1.64E-11,9.999481098,1.6146875,6.034443466,2.517994639,90.00000001 +244.97,50.43283629,-2.565517798,51.266,1.50E-11,10.00014717,1.6696875,5.977855977,2.585666684,90.00000001 +244.98,50.43283629,-2.565516391,51.249,7.97E-12,10.00036918,1.723125,5.920020184,2.651084026,90.00000001 +244.99,50.43283629,-2.565514983,51.2315,4.69E-12,10.00036915,1.775,5.860948006,2.71418954,90.00000001 +245,50.43283629,-2.565513576,51.2135,1.31E-11,10.00014709,1.8265625,5.800651876,2.77492828,90.00000001 +245.01,50.43283629,-2.565512168,51.195,2.73E-11,9.999480962,1.8784375,5.739144284,2.833247248,90.00000001 +245.02,50.43283629,-2.565510761,51.1759,3.59E-11,9.999036866,1.9296875,5.676438236,2.889095564,90.00000001 +245.03,50.43283629,-2.565509354,51.1564,3.77E-11,9.999480902,1.98,5.612546681,2.942424528,90.00000001 +245.04,50.43283629,-2.565507946,51.1363,3.75E-11,10.00014697,2.03,5.547483026,2.993187672,90.00000001 +245.05,50.43283629,-2.565506539,51.1158,3.30E-11,10.00036897,2.079375,5.481260908,3.041340706,90.00000001 +245.06,50.43283629,-2.565505131,51.0947,1.72E-11,10.00036894,2.1265625,5.41389402,3.086841634,90.00000001 +245.07,50.43283629,-2.565503724,51.0732,-7.81E-13,10.0003689,2.1715625,5.345396572,3.129650806,90.00000001 +245.08,50.43283629,-2.565502316,51.0513,-3.12E-12,10.00036887,2.216875,5.275782772,3.169730923,90.00000001 +245.09,50.43283629,-2.565500909,51.0289,5.63E-12,10.0001468,2.263125,5.205067176,3.207046919,90.00000001 +245.1,50.43283629,-2.565499501,51.006,7.97E-12,9.999480666,2.3078125,5.133264563,3.241566366,90.00000001 +245.11,50.43283629,-2.565498094,50.9827,3.91E-12,9.999036564,2.3496875,5.060390004,3.273259068,90.00000001 +245.12,50.43283629,-2.565496687,50.959,1.41E-12,9.999480593,2.39,4.986458567,3.302097466,90.00000001 +245.13,50.43283629,-2.565495279,50.9349,0,10.00014665,2.43,4.911485836,3.328056407,90.00000001 +245.14,50.43283629,-2.565493872,50.9104,-1.56E-12,10.00036865,2.47,4.835487339,3.351113203,90.00000001 +245.15,50.43283629,-2.565492464,50.8855,-4.69E-12,10.00036861,2.5096875,4.758479061,3.371247799,90.00000001 +245.16,50.43283629,-2.565491057,50.8602,-1.19E-11,10.00036857,2.548125,4.680477045,3.388442607,90.00000001 +245.17,50.43283629,-2.565489649,50.8345,-1.88E-11,10.00036853,2.5846875,4.601497506,3.40268267,90.00000001 +245.18,50.43283629,-2.565488242,50.8085,-1.80E-11,10.00036849,2.6196875,4.521557059,3.4139555,90.00000001 +245.19,50.43283629,-2.565486834,50.7821,-9.38E-12,10.00036845,2.653125,4.440672321,3.422251299,90.00000001 +245.2,50.43283629,-2.565485427,50.7554,-3.28E-12,10.00036841,2.685,4.35886025,3.427562904,90.00000001 +245.21,50.43283629,-2.565484019,50.7284,-1.03E-11,10.00036836,2.7165625,4.276137864,3.429885561,90.00000001 +245.22,50.43283629,-2.565482612,50.7011,-2.34E-11,10.00014629,2.748125,4.192522409,3.429217377,90.00000001 +245.23,50.43283629,-2.565481204,50.6734,-2.48E-11,9.999480146,2.778125,4.108031474,3.425558813,90.00000001 +245.24,50.43283629,-2.565479797,50.6455,-1.09E-11,9.999036036,2.80625,4.022682592,3.418913132,90.00000001 +245.25,50.43283629,-2.56547839,50.6173,6.25E-12,9.999480058,2.8334375,3.936493583,3.409286066,90.00000001 +245.26,50.43283629,-2.565476982,50.5888,1.64E-11,10.00014611,2.8596875,3.84948255,3.396686094,90.00000001 +245.27,50.43283629,-2.565475575,50.5601,1.72E-11,10.0003681,2.8846875,3.761667601,3.381124159,90.00000001 +245.28,50.43283629,-2.565474167,50.5311,1.09E-11,10.00036806,2.908125,3.673067069,3.362613841,90.00000001 +245.29,50.43283629,-2.56547276,50.5019,3.91E-12,10.00036801,2.9296875,3.583699404,3.341171239,90.00000001 +245.3,50.43283629,-2.565471352,50.4725,7.81E-13,10.00036796,2.95,3.493583399,3.31681509,90.00000001 +245.31,50.43283629,-2.565469945,50.4429,1.56E-13,10.00036792,2.97,3.402737789,3.28956665,90.00000001 +245.32,50.43283629,-2.565468537,50.4131,2.34E-12,10.00036787,2.9896875,3.31118154,3.259449639,90.00000001 +245.33,50.43283629,-2.56546713,50.3831,7.03E-12,10.00036782,3.0078125,3.218933845,3.226490356,90.00000001 +245.34,50.43283629,-2.565465722,50.3529,4.69E-12,10.00036778,3.023125,3.126013842,3.190717564,90.00000001 +245.35,50.43283629,-2.565464315,50.3226,-7.03E-12,10.0001457,3.0365625,3.032441067,3.152162375,90.00000001 +245.36,50.43283629,-2.565462907,50.2922,-1.41E-11,9.999479549,3.05,2.938235003,3.11085842,90.00000001 +245.37,50.43283629,-2.5654615,50.2616,-1.17E-11,9.999035436,3.0628125,2.843415301,3.066841797,90.00000001 +245.38,50.43283629,-2.565460093,50.2309,-1.41E-11,9.999479454,3.073125,2.748001785,3.020150836,90.00000001 +245.39,50.43283629,-2.565458685,50.2001,-2.81E-11,10.00014551,3.08125,2.652014395,2.970826275,90.00000001 +245.4,50.43283629,-2.565457278,50.1693,-4.45E-11,10.00036749,3.0884375,2.555473184,2.918911085,90.00000001 +245.41,50.43283629,-2.56545587,50.1383,-5.16E-11,10.00036744,3.095,2.458398262,2.864450529,90.00000001 +245.42,50.43283629,-2.565454463,50.1074,-4.22E-11,10.00036739,3.10125,2.360809971,2.807492165,90.00000001 +245.43,50.43283629,-2.565453055,50.0763,-2.11E-11,10.00036734,3.1065625,2.262728591,2.748085666,90.00000001 +245.44,50.43283629,-2.565451648,50.0452,-4.69E-12,10.0003673,3.109375,2.164174751,2.686282714,90.00000001 +245.45,50.43283629,-2.56545024,50.0141,-2.34E-12,10.00036725,3.1096875,2.065168905,2.622137339,90.00000001 +245.46,50.43283629,-2.565448833,49.983,-1.17E-11,10.0003672,3.1084375,1.965731793,2.555705403,90.00000001 +245.47,50.43283629,-2.565447425,49.9519,-2.58E-11,10.00036715,3.1065625,1.865884157,2.487044891,90.00000001 +245.48,50.43283629,-2.565446018,49.9209,-3.06E-11,10.00014507,3.1046875,1.765646852,2.41621562,90.00000001 +245.49,50.43283629,-2.56544461,49.8898,-1.72E-11,9.99947892,3.1015625,1.665040792,2.343279353,90.00000001 +245.5,50.43283629,-2.565443203,49.8588,5.47E-12,9.999034806,3.0959375,1.564087061,2.268299689,90.00000001 +245.51,50.43283629,-2.565441796,49.8279,2.42E-11,9.999478824,3.0884375,1.462806629,2.191342061,90.00000001 +245.52,50.43283629,-2.565440388,49.797,3.44E-11,10.00014487,3.0796875,1.361220754,2.112473561,90.00000001 +245.53,50.43283629,-2.565438981,49.7663,3.73E-11,10.00036686,3.07,1.259350577,2.031762944,90.00000001 +245.54,50.43283629,-2.565437573,49.7356,3.75E-11,10.00036681,3.06,1.157217412,1.949280628,90.00000001 +245.55,50.43283629,-2.565436166,49.7051,3.27E-11,10.00014473,3.049375,1.054842574,1.86509846,90.00000001 +245.56,50.43283629,-2.565434758,49.6746,1.56E-11,9.999478584,3.0365625,0.95224749,1.779289894,90.00000001 +245.57,50.43283629,-2.565433351,49.6443,-6.25E-12,9.99903447,3.02125,0.849453476,1.691929816,90.00000001 +245.58,50.43283629,-2.565431944,49.6142,-1.56E-11,9.999478489,3.005,0.746482131,1.603094314,90.00000001 +245.59,50.43283629,-2.565430536,49.5842,-1.02E-11,10.00014454,2.988125,0.643354828,1.51286091,90.00000001 +245.6,50.43283629,-2.565429129,49.5544,-1.56E-13,10.00036653,2.969375,0.540093222,1.42130827,90.00000001 +245.61,50.43283629,-2.565427721,49.5248,1.17E-11,10.00036648,2.9484375,0.436718745,1.328516208,90.00000001 +245.62,50.43283629,-2.565426314,49.4954,2.58E-11,10.00036644,2.9265625,0.333253167,1.234565626,90.00000001 +245.63,50.43283629,-2.565424906,49.4663,3.03E-11,10.00036639,2.9046875,0.229717917,1.13953857,90.00000001 +245.64,50.43283629,-2.565423499,49.4373,1.56E-11,10.00014431,2.8815625,0.126134711,1.043517719,90.00000001 +245.65,50.43283629,-2.565422091,49.4086,-6.25E-12,9.999478168,2.85625,0.022525205,0.946587011,90.00000001 +245.66,50.43283629,-2.565420684,49.3802,-1.80E-11,9.999034057,2.8303125,-0.081089055,0.848830786,90.00000001 +245.67,50.43283629,-2.565419277,49.352,-2.20E-11,9.999478079,2.8046875,-0.184686356,0.750334413,90.00000001 +245.68,50.43283629,-2.565417869,49.3241,-2.67E-11,10.00014413,2.7778125,-0.288245097,0.651183723,90.00000001 +245.69,50.43283629,-2.565416462,49.2964,-2.50E-11,10.00036612,2.748125,-0.391743678,0.551465174,90.00000001 +245.7,50.43283629,-2.565415054,49.2691,-1.08E-11,10.00036608,2.71625,-0.495160382,0.451265742,90.00000001 +245.71,50.43283629,-2.565413647,49.2421,7.03E-12,10.00014401,2.6834375,-0.598473726,0.350672802,90.00000001 +245.72,50.43283629,-2.565412239,49.2154,1.80E-11,9.999477866,2.6496875,-0.701662049,0.249774075,90.00000001 +245.73,50.43283629,-2.565410832,49.1891,2.11E-11,9.999033758,2.615,-0.804703868,0.148657567,90.00000001 +245.74,50.43283629,-2.565409425,49.1631,2.36E-11,9.999477783,2.5796875,-0.907577638,0.047411398,90.00000001 +245.75,50.43283629,-2.565408017,49.1375,3.06E-11,10.00014384,2.543125,-1.010261816,-0.053876081,90.00000001 +245.76,50.43283629,-2.56540661,49.1122,3.53E-11,10.00036584,2.505,-1.112735089,-0.155116635,90.00000001 +245.77,50.43283629,-2.565405202,49.0874,2.81E-11,10.0003658,2.4665625,-1.214975912,-0.256221856,90.00000001 +245.78,50.43283629,-2.565403795,49.0629,1.58E-11,10.00014373,2.428125,-1.31696303,-0.357103738,90.00000001 +245.79,50.43283629,-2.565402387,49.0388,1.27E-11,9.999477589,2.3878125,-1.418675128,-0.45767416,90.00000001 +245.8,50.43283629,-2.56540098,49.0151,1.50E-11,9.999033486,2.345,-1.52009095,-0.55784546,90.00000001 +245.81,50.43283629,-2.565399573,48.9919,8.59E-12,9.999477516,2.3015625,-1.621189353,-0.657530376,90.00000001 +245.82,50.43283629,-2.565398165,48.9691,-5.47E-12,10.00014358,2.2584375,-1.721949137,-0.756641876,90.00000001 +245.83,50.43283629,-2.565396758,48.9467,-1.56E-11,10.00036558,2.2146875,-1.822349334,-0.855093558,90.00000001 +245.84,50.43283629,-2.56539535,48.9248,-1.63E-11,10.00036554,2.1696875,-1.922368972,-0.952799592,90.00000001 +245.85,50.43283629,-2.565393943,48.9033,-9.38E-12,10.00014348,2.123125,-2.021987139,-1.049674838,90.00000001 +245.86,50.43283629,-2.565392535,48.8823,-2.34E-12,9.999477345,2.0746875,-2.121183035,-1.145634669,90.00000001 +245.87,50.43283629,-2.565391128,48.8618,8.33E-17,9.999033247,2.025,-2.219935978,-1.240595548,90.00000001 +245.88,50.43283629,-2.565389721,48.8418,1.94E-16,9.999477281,1.975,-2.318225283,-1.334474568,90.00000001 +245.89,50.43283629,-2.565388313,48.8223,1.94E-16,10.00014335,1.925,-2.41603044,-1.427189911,90.00000001 +245.9,50.43283629,-2.565386906,48.8033,2.50E-12,10.00036535,1.8746875,-2.513331049,-1.518660732,90.00000001 +245.91,50.43283629,-2.565385498,48.7848,1.02E-11,10.00036532,1.823125,-2.610106829,-1.608807276,90.00000001 +245.92,50.43283629,-2.565384091,48.7668,1.56E-11,10.0003653,1.77,-2.706337497,-1.697550876,90.00000001 +245.93,50.43283629,-2.565382683,48.7494,8.44E-12,10.00036527,1.7165625,-2.802002943,-1.784814239,90.00000001 +245.94,50.43283629,-2.565381276,48.7325,-4.69E-12,10.00036524,1.663125,-2.897083283,-1.870521162,90.00000001 +245.95,50.43283629,-2.565379868,48.7161,-6.25E-12,10.00036522,1.608125,-2.991558581,-1.954596989,90.00000001 +245.96,50.43283629,-2.565378461,48.7003,4.84E-12,10.00036519,1.5515625,-3.085409125,-2.036968381,90.00000001 +245.97,50.43283629,-2.565377053,48.6851,1.25E-11,10.00036517,1.495,-3.178615321,-2.117563489,90.00000001 +245.98,50.43283629,-2.565375646,48.6704,7.03E-12,10.00014311,1.4384375,-3.271157688,-2.196312069,90.00000001 +245.99,50.43283629,-2.565374238,48.6563,-5.62E-12,9.999476991,1.3815625,-3.363016917,-2.273145423,90.00000001 +246,50.43283629,-2.565372831,48.6428,-1.02E-11,9.999032904,1.3246875,-3.454173872,-2.347996572,90.00000001 +246.01,50.43283629,-2.565371424,48.6298,3.13E-12,9.999476949,1.2665625,-3.544609416,-2.420800199,90.00000001 +246.02,50.43283629,-2.565370016,48.6174,2.36E-11,10.00014303,1.20625,-3.634304698,-2.491492935,90.00000001 +246.03,50.43283629,-2.565368609,48.6057,3.52E-11,10.00036504,1.1453125,-3.72324104,-2.560012957,90.00000001 +246.04,50.43283629,-2.565367201,48.5945,3.75E-11,10.00036503,1.085,-3.811399822,-2.626300679,90.00000001 +246.05,50.43283629,-2.565365794,48.584,3.75E-11,10.00036501,1.025,-3.89876265,-2.690298174,90.00000001 +246.06,50.43283629,-2.565364386,48.574,3.75E-11,10.00036499,0.965,-3.985311306,-2.751949693,90.00000001 +246.07,50.43283629,-2.565362979,48.5647,3.28E-11,10.00036498,0.904375,-4.071027625,-2.811201494,90.00000001 +246.08,50.43283629,-2.565361571,48.5559,1.42E-11,10.00036497,0.841875,-4.15589379,-2.868001894,90.00000001 +246.09,50.43283629,-2.565360164,48.5478,-1.33E-11,10.00036495,0.778125,-4.239892038,-2.922301333,90.00000001 +246.1,50.43283629,-2.565358756,48.5404,-2.89E-11,10.00036494,0.7153125,-4.323004838,-2.974052486,90.00000001 +246.11,50.43283629,-2.565357349,48.5335,-2.44E-11,10.0001429,0.6534375,-4.405214828,-3.023210259,90.00000001 +246.12,50.43283629,-2.565355941,48.5273,-9.37E-12,9.99947679,0.59125,-4.486504819,-3.069731682,90.00000001 +246.13,50.43283629,-2.565354534,48.5217,3.13E-12,9.999032715,0.528125,-4.56685791,-3.113576303,90.00000001 +246.14,50.43283629,-2.565353127,48.5167,1.57E-13,9.999476773,0.4634375,-4.646257255,-3.154705792,90.00000001 +246.15,50.43283629,-2.565351719,48.5124,-1.81E-11,10.00014286,0.3984375,-4.724686297,-3.193084396,90.00000001 +246.16,50.43283629,-2.565350312,48.5088,-2.91E-11,10.00036489,0.335,-4.802128647,-3.228678539,90.00000001 +246.17,50.43283629,-2.565348904,48.5057,-1.73E-11,10.00036489,0.2715625,-4.878568093,-3.261457226,90.00000001 +246.18,50.43283629,-2.565347497,48.5033,7.81E-13,10.00036488,0.2065625,-4.953988762,-3.291391864,90.00000001 +246.19,50.43283629,-2.565346089,48.5016,3.12E-12,10.00036488,0.141875,-5.028374841,-3.318456385,90.00000001 +246.2,50.43283629,-2.565344682,48.5005,-7.81E-12,10.00036488,0.0784375,-5.101710803,-3.342627182,90.00000001 +246.21,50.43283629,-2.565343274,48.5,-1.67E-11,10.00036488,0.0146875,-5.17398135,-3.363883114,90.00000001 +246.22,50.43283629,-2.565341867,48.5002,-1.95E-11,10.00036488,-0.05,-5.245171356,-3.382205732,90.00000001 +246.23,50.43283629,-2.565340459,48.501,-2.03E-11,10.00036488,-0.115,-5.315265982,-3.397578992,90.00000001 +246.24,50.43283629,-2.565339052,48.5025,-2.03E-11,10.00014285,-0.18,-5.384250616,-3.409989487,90.00000001 +246.25,50.43283629,-2.565337644,48.5046,-1.73E-11,9.999476755,-0.2446875,-5.452110763,-3.419426445,90.00000001 +246.26,50.43283629,-2.565336237,48.5074,-7.97E-12,9.999032693,-0.3084375,-5.518832329,-3.425881617,90.00000001 +246.27,50.43283629,-2.56533483,48.5108,5.31E-12,9.999476763,-0.3715625,-5.58440139,-3.429349387,90.00000001 +246.28,50.43283629,-2.565333422,48.5148,1.41E-11,10.00014287,-0.4353125,-5.648804195,-3.429826661,90.00000001 +246.29,50.43283629,-2.565332015,48.5195,1.62E-11,10.00036491,-0.5,-5.71202728,-3.427313095,90.00000001 +246.3,50.43283629,-2.565330607,48.5248,1.41E-11,10.00036492,-0.5646875,-5.774057524,-3.421810924,90.00000001 +246.31,50.43283629,-2.5653292,48.5308,7.81E-12,10.00036493,-0.628125,-5.834881922,-3.413324789,90.00000001 +246.32,50.43283629,-2.565327792,48.5374,4.69E-12,10.00036494,-0.69,-5.89448781,-3.401862252,90.00000001 +246.33,50.43283629,-2.565326385,48.5446,1.08E-11,10.00036495,-0.751875,-5.952862698,-3.387433227,90.00000001 +246.34,50.43283629,-2.565324977,48.5524,1.56E-11,10.00036496,-0.815,-6.009994382,-3.37005026,90.00000001 +246.35,50.43283629,-2.56532357,48.5609,1.02E-11,10.00014294,-0.878125,-6.065870945,-3.349728593,90.00000001 +246.36,50.43283629,-2.565322162,48.57,2.50E-12,9.999476856,-0.9396875,-6.120480756,-3.32648593,90.00000001 +246.37,50.43283629,-2.565320755,48.5797,-1.88E-22,9.999032805,-1,-6.173812355,-3.300342496,90.00000001 +246.38,50.43283629,-2.565319348,48.59,2.50E-16,9.999476888,-1.06,-6.225854685,-3.271321152,90.00000001 +246.39,50.43283629,-2.56531794,48.6009,-1.56E-13,10.000143,-1.12,-6.276596801,-3.239447109,90.00000001 +246.4,50.43283629,-2.565316533,48.6124,-7.81E-13,10.00036505,-1.18,-6.326028105,-3.204748269,90.00000001 +246.41,50.43283629,-2.565315125,48.6245,7.81E-13,10.00036507,-1.2396875,-6.374138282,-3.167254828,90.00000001 +246.42,50.43283629,-2.565313718,48.6372,1.03E-11,10.00014306,-1.2984375,-6.420917364,-3.126999501,90.00000001 +246.43,50.43283629,-2.56531231,48.6505,2.58E-11,9.999476982,-1.3565625,-6.466355495,-3.084017353,90.00000001 +246.44,50.43283629,-2.565310903,48.6643,3.44E-11,9.999032938,-1.415,-6.510443223,-3.038345913,90.00000001 +246.45,50.43283629,-2.565309496,48.6788,3.05E-11,9.999477026,-1.473125,-6.553171264,-2.990025002,90.00000001 +246.46,50.43283629,-2.565308088,48.6938,2.36E-11,10.00014315,-1.5296875,-6.594530852,-2.939096732,90.00000001 +246.47,50.43283629,-2.565306681,48.7094,2.11E-11,10.00036521,-1.585,-6.634513165,-2.885605564,90.00000001 +246.48,50.43283629,-2.565305273,48.7255,1.80E-11,10.00036523,-1.6396875,-6.673110009,-2.829598022,90.00000001 +246.49,50.43283629,-2.565303866,48.7422,7.03E-12,10.00014322,-1.6934375,-6.710313247,-2.771123096,90.00000001 +246.5,50.43283629,-2.565302458,48.7594,-8.44E-12,9.999477152,-1.7465625,-6.746115088,-2.71023172,90.00000001 +246.51,50.43283629,-2.565301051,48.7771,-1.56E-11,9.999033114,-1.8,-6.78050814,-2.64697695,90.00000001 +246.52,50.43283629,-2.565299644,48.7954,-1.02E-11,9.999477209,-1.853125,-6.813485127,-2.581413962,90.00000001 +246.53,50.43283629,-2.565298236,48.8142,-2.50E-12,10.00014334,-1.9046875,-6.84503923,-2.513599938,90.00000001 +246.54,50.43283629,-2.565296829,48.8335,-2.22E-16,10.0003654,-1.955,-6.875163862,-2.443594064,90.00000001 +246.55,50.43283629,-2.565295421,48.8533,2.34E-12,10.00036543,-2.0046875,-6.903852661,-2.371457303,90.00000001 +246.56,50.43283629,-2.565294014,48.8736,9.37E-12,10.00014343,-2.053125,-6.931099669,-2.297252622,90.00000001 +246.57,50.43283629,-2.565292606,48.8944,1.41E-11,9.999477363,-2.1,-6.956899271,-2.221044651,90.00000001 +246.58,50.43283629,-2.565291199,48.9156,7.19E-12,9.99903333,-2.1465625,-6.981245966,-2.142899969,90.00000001 +246.59,50.43283629,-2.565289792,48.9373,-6.25E-12,9.99947743,-2.1934375,-7.004134713,-2.062886585,90.00000001 +246.6,50.43283629,-2.565288384,48.9595,-1.48E-11,10.00014356,-2.2396875,-7.025560699,-1.9810744,90.00000001 +246.61,50.43283629,-2.565286977,48.9821,-1.48E-11,10.00036563,-2.2846875,-7.045519569,-1.897534632,90.00000001 +246.62,50.43283629,-2.565285569,49.0052,-8.44E-12,10.00036567,-2.328125,-7.064007027,-1.812340162,90.00000001 +246.63,50.43283629,-2.565284162,49.0287,-1.41E-12,10.00014367,-2.3696875,-7.081019232,-1.725565361,90.00000001 +246.64,50.43283629,-2.565282754,49.0526,1.72E-12,9.999477611,-2.41,-7.096552691,-1.637285857,90.00000001 +246.65,50.43283629,-2.565281347,49.0769,2.34E-12,9.999033583,-2.45,-7.110604137,-1.547578543,90.00000001 +246.66,50.43283629,-2.56527994,49.1016,1.56E-13,9.999477688,-2.4896875,-7.123170649,-1.456521798,90.00000001 +246.67,50.43283629,-2.565278532,49.1267,-6.88E-12,10.00014383,-2.528125,-7.134249532,-1.364194863,90.00000001 +246.68,50.43283629,-2.565277125,49.1522,-1.16E-11,10.0003659,-2.565,-7.143838497,-1.270678411,90.00000001 +246.69,50.43283629,-2.565275717,49.178,-2.34E-12,10.00036594,-2.60125,-7.151935594,-1.176053858,90.00000001 +246.7,50.43283629,-2.56527431,49.2042,1.80E-11,10.00036598,-2.6365625,-7.158539104,-1.080403768,90.00000001 +246.71,50.43283629,-2.565272902,49.2308,3.05E-11,10.00036602,-2.6696875,-7.163647653,-0.983811563,90.00000001 +246.72,50.43283629,-2.565271495,49.2576,2.44E-11,10.00036606,-2.7015625,-7.167260152,-0.886361469,90.00000001 +246.73,50.43283629,-2.565270087,49.2848,1.03E-11,10.00036611,-2.7334375,-7.169375856,-0.788138398,90.00000001 +246.74,50.43283629,-2.56526868,49.3123,-2.22E-16,10.00036615,-2.764375,-7.169994364,-0.68922812,90.00000001 +246.75,50.43283629,-2.565267272,49.3401,-7.97E-12,10.00036619,-2.793125,-7.169115447,-0.589716811,90.00000001 +246.76,50.43283629,-2.565265865,49.3682,-1.25E-11,10.0001442,-2.82,-7.166739391,-0.489691271,90.00000001 +246.77,50.43283629,-2.565264457,49.3965,-3.91E-12,9.999478149,-2.84625,-7.162866654,-0.389238706,90.00000001 +246.78,50.43283629,-2.56526305,49.4251,1.66E-11,9.999034128,-2.8715625,-7.15749804,-0.288446721,90.00000001 +246.79,50.43283629,-2.565261643,49.454,2.83E-11,9.999478238,-2.895,-7.150634693,-0.18740315,90.00000001 +246.8,50.43283629,-2.565260235,49.483,1.48E-11,10.00014438,-2.918125,-7.142277989,-0.086196229,90.00000001 +246.81,50.43283629,-2.565258828,49.5123,-1.02E-11,10.00036646,-2.9415625,-7.132429704,0.015085864,90.00000001 +246.82,50.43283629,-2.56525742,49.5419,-2.19E-11,10.00036651,-2.9625,-7.121091958,0.116354837,90.00000001 +246.83,50.43283629,-2.565256013,49.5716,-2.27E-11,10.00036655,-2.98,-7.108267042,0.217522338,90.00000001 +246.84,50.43283629,-2.565254605,49.6015,-3.03E-11,10.0003666,-2.9965625,-7.093957593,0.318500134,90.00000001 +246.85,50.43283629,-2.565253198,49.6315,-4.22E-11,10.00036665,-3.013125,-7.078166762,0.419200216,90.00000001 +246.86,50.43283629,-2.56525179,49.6618,-3.98E-11,10.0003667,-3.0284375,-7.060897699,0.519534695,90.00000001 +246.87,50.43283629,-2.565250383,49.6921,-1.64E-11,10.00014471,-3.0428125,-7.042154015,0.619416193,90.00000001 +246.88,50.43283629,-2.565248975,49.7226,1.17E-11,9.999478659,-3.0565625,-7.021939721,0.718757506,90.00000001 +246.89,50.43283629,-2.565247568,49.7533,2.11E-11,9.999034641,-3.0678125,-7.000258998,0.817472118,90.00000001 +246.9,50.43283629,-2.565246161,49.784,1.17E-11,9.999478755,-3.0765625,-6.977116315,0.915473799,90.00000001 +246.91,50.43283629,-2.565244753,49.8148,4.69E-12,10.0001449,-3.085,-6.952516602,1.012677234,90.00000001 +246.92,50.43283629,-2.565243346,49.8457,9.38E-12,10.00036698,-3.093125,-6.926464898,1.10899757,90.00000001 +246.93,50.43283629,-2.565241938,49.8767,1.88E-11,10.00036703,-3.099375,-6.898966706,1.204350868,90.00000001 +246.94,50.43283629,-2.565240531,49.9077,2.81E-11,10.00036708,-3.103125,-6.870027753,1.298653934,90.00000001 +246.95,50.43283629,-2.565239123,49.9388,3.28E-11,10.00036713,-3.105,-6.839654057,1.39182455,90.00000001 +246.96,50.43283629,-2.565237716,49.9698,2.59E-11,10.00036718,-3.1065625,-6.807852035,1.483781525,90.00000001 +246.97,50.43283629,-2.565236308,50.0009,1.25E-11,10.00036723,-3.1084375,-6.774628275,1.574444534,90.00000001 +246.98,50.43283629,-2.565234901,50.032,1.56E-12,10.00036727,-3.109375,-6.739989711,1.663734677,90.00000001 +246.99,50.43283629,-2.565233493,50.0631,-7.81E-12,10.00036732,-3.108125,-6.703943561,1.751573978,90.00000001 +247,50.43283629,-2.565232086,50.0942,-1.56E-11,10.00014534,-3.1046875,-6.666497388,1.837885887,90.00000001 +247.01,50.43283629,-2.565230678,50.1252,-1.62E-11,9.999479288,-3.0996875,-6.627659043,1.922595176,90.00000001 +247.02,50.43283629,-2.565229271,50.1562,-9.37E-12,9.999035271,-3.093125,-6.587436546,2.005627876,90.00000001 +247.03,50.43283629,-2.565227864,50.1871,-2.34E-12,9.999479386,-3.0846875,-6.545838378,2.086911679,90.00000001 +247.04,50.43283629,-2.565226456,50.2179,2.22E-16,10.00014553,-3.075,-6.50287319,2.166375654,90.00000001 +247.05,50.43283629,-2.565225049,50.2486,1.94E-16,10.00036761,-3.065,-6.45854992,2.243950473,90.00000001 +247.06,50.43283629,-2.565223641,50.2792,-2.34E-12,10.00036766,-3.0546875,-6.412877907,2.319568583,90.00000001 +247.07,50.43283629,-2.565222234,50.3097,-9.38E-12,10.00036771,-3.043125,-6.365866662,2.393163981,90.00000001 +247.08,50.43283629,-2.565220826,50.3401,-1.88E-11,10.00036776,-3.029375,-6.317525984,2.464672494,90.00000001 +247.09,50.43283629,-2.565219419,50.3703,-2.80E-11,10.0003678,-3.013125,-6.267865898,2.534031785,90.00000001 +247.1,50.43283629,-2.565218011,50.4004,-3.20E-11,10.00036785,-2.995,-6.216896948,2.60118135,90.00000001 +247.11,50.43283629,-2.565216604,50.4302,-2.42E-11,10.0003679,-2.9765625,-6.164629618,2.66606269,90.00000001 +247.12,50.43283629,-2.565215196,50.4599,-1.02E-11,10.00036794,-2.9584375,-6.111074909,2.728619139,90.00000001 +247.13,50.43283629,-2.565213789,50.4894,7.81E-13,10.00014596,-2.939375,-6.056243937,2.788796208,90.00000001 +247.14,50.43283629,-2.565212381,50.5187,9.53E-12,9.999479904,-2.918125,-6.000148275,2.846541416,90.00000001 +247.15,50.43283629,-2.565210974,50.5478,1.66E-11,9.999035883,-2.8946875,-5.942799497,2.901804398,90.00000001 +247.16,50.43283629,-2.565209567,50.5766,1.95E-11,9.999479994,-2.87,-5.884209635,2.954536913,90.00000001 +247.17,50.43283629,-2.565208159,50.6052,2.03E-11,10.00014614,-2.845,-5.82439095,3.004693065,90.00000001 +247.18,50.43283629,-2.565206752,50.6335,1.56E-11,10.00036822,-2.819375,-5.763355933,3.052229082,90.00000001 +247.19,50.43283629,-2.565205344,50.6616,-1.41E-12,10.00036826,-2.7915625,-5.701117304,3.097103537,90.00000001 +247.2,50.43283629,-2.565203937,50.6894,-2.02E-11,10.00014627,-2.7615625,-5.637688069,3.139277242,90.00000001 +247.21,50.43283629,-2.565202529,50.7168,-1.95E-11,9.999480214,-2.7315625,-5.573081462,3.178713411,90.00000001 +247.22,50.43283629,-2.565201122,50.744,-3.28E-12,9.999036191,-2.70125,-5.507311007,3.215377782,90.00000001 +247.23,50.43283629,-2.565199715,50.7709,-3.61E-16,9.999480298,-2.668125,-5.440390396,3.249238213,90.00000001 +247.24,50.43283629,-2.565198307,50.7974,-2.03E-11,10.00014644,-2.633125,-5.372333667,3.28026531,90.00000001 +247.25,50.43283629,-2.5651969,50.8235,-4.22E-11,10.00036851,-2.5984375,-5.303154972,3.308431973,90.00000001 +247.26,50.43283629,-2.565195492,50.8494,-4.47E-11,10.00036855,-2.563125,-5.232868749,3.333713563,90.00000001 +247.27,50.43283629,-2.565194085,50.8748,-3.05E-11,10.00014656,-2.52625,-5.161489724,3.356088196,90.00000001 +247.28,50.43283629,-2.565192677,50.8999,-1.56E-11,9.9994805,-2.488125,-5.089032851,3.375536217,90.00000001 +247.29,50.43283629,-2.56519127,50.9246,-1.41E-11,9.999036473,-2.448125,-5.015513142,3.392040724,90.00000001 +247.3,50.43283629,-2.565189863,50.9489,-2.44E-11,9.999480577,-2.4065625,-4.940946008,3.405587337,90.00000001 +247.31,50.43283629,-2.565188455,50.9727,-3.14E-11,10.00014671,-2.365,-4.865347034,3.416164195,90.00000001 +247.32,50.43283629,-2.565187048,50.9962,-2.58E-11,10.00036878,-2.3234375,-4.788731977,3.423762132,90.00000001 +247.33,50.43283629,-2.56518564,51.0192,-1.08E-11,10.00036882,-2.28125,-4.71111688,3.428374499,90.00000001 +247.34,50.43283629,-2.565184233,51.0418,3.13E-12,10.00014682,-2.238125,-4.632517899,3.429997287,90.00000001 +247.35,50.43283629,-2.565182825,51.064,3.91E-12,9.999480757,-2.193125,-4.552951479,3.428629064,90.00000001 +247.36,50.43283629,-2.565181418,51.0857,-9.53E-12,9.999036725,-2.14625,-4.472434293,3.424270975,90.00000001 +247.37,50.43283629,-2.565180011,51.1069,-2.58E-11,9.999480824,-2.0984375,-4.390983014,3.416926917,90.00000001 +247.38,50.43283629,-2.565178603,51.1277,-3.28E-11,10.00014696,-2.05,-4.308614774,3.406603249,90.00000001 +247.39,50.43283629,-2.565177196,51.1479,-2.34E-11,10.00036902,-2.00125,-4.22534676,3.393308966,90.00000001 +247.4,50.43283629,-2.565175788,51.1677,-1.56E-13,10.00036905,-1.951875,-4.141196277,3.377055643,90.00000001 +247.41,50.43283629,-2.565174381,51.187,2.27E-11,10.00014705,-1.90125,-4.056180971,3.357857547,90.00000001 +247.42,50.43283629,-2.565172973,51.2057,3.13E-11,9.999480978,-1.85,-3.970318604,3.335731292,90.00000001 +247.43,50.43283629,-2.565171566,51.224,2.67E-11,9.999036941,-1.798125,-3.883627111,3.310696245,90.00000001 +247.44,50.43283629,-2.565170159,51.2417,2.11E-11,9.999481035,-1.7446875,-3.796124538,3.282774178,90.00000001 +247.45,50.43283629,-2.565168751,51.2589,2.02E-11,10.00014716,-1.69,-3.707829221,3.251989556,90.00000001 +247.46,50.43283629,-2.565167344,51.2755,2.02E-11,10.00036922,-1.635,-3.618759551,3.218369081,90.00000001 +247.47,50.43283629,-2.565165936,51.2916,1.89E-11,10.00036925,-1.58,-3.52893415,3.1819422,90.00000001 +247.48,50.43283629,-2.565164529,51.3071,1.58E-11,10.00036927,-1.5246875,-3.438371753,3.142740542,90.00000001 +247.49,50.43283629,-2.565163121,51.3221,7.19E-12,10.00036929,-1.4684375,-3.347091326,3.100798427,90.00000001 +247.5,50.43283629,-2.565161714,51.3365,-5.62E-12,10.00036932,-1.4115625,-3.25511189,3.056152353,90.00000001 +247.51,50.43283629,-2.565160306,51.3503,-1.02E-11,10.00036934,-1.3546875,-3.16245264,3.00884128,90.00000001 +247.52,50.43283629,-2.565158899,51.3636,3.28E-12,10.00014733,-1.2965625,-3.069132998,2.958906461,90.00000001 +247.53,50.43283629,-2.565157491,51.3763,2.20E-11,9.999481246,-1.2365625,-2.975172389,2.906391441,90.00000001 +247.54,50.43283629,-2.565156084,51.3883,2.27E-11,9.999037198,-1.1765625,-2.880590464,2.851341943,90.00000001 +247.55,50.43283629,-2.565154677,51.3998,1.56E-12,9.999481282,-1.116875,-2.785406934,2.793806094,90.00000001 +247.56,50.43283629,-2.565153269,51.4107,-2.27E-11,10.0001474,-1.05625,-2.689641736,2.733833971,90.00000001 +247.57,50.43283629,-2.565151862,51.4209,-3.48E-11,10.00036945,-0.9953125,-2.593314869,2.671477943,90.00000001 +247.58,50.43283629,-2.565150454,51.4306,-3.67E-11,10.00036946,-0.935,-2.496446384,2.606792326,90.00000001 +247.59,50.43283629,-2.565149047,51.4396,-3.12E-11,10.00036948,-0.874375,-2.399056508,2.539833498,90.00000001 +247.6,50.43283629,-2.565147639,51.4481,-1.27E-11,10.00036949,-0.811875,-2.301165694,2.47065996,90.00000001 +247.61,50.43283629,-2.565146232,51.4559,1.41E-11,10.0003695,-0.748125,-2.202794284,2.399331928,90.00000001 +247.62,50.43283629,-2.565144824,51.463,2.91E-11,10.00036951,-0.6853125,-2.103962846,2.325911684,90.00000001 +247.63,50.43283629,-2.565143417,51.4696,2.67E-11,10.00036952,-0.623125,-2.004692006,2.250463169,90.00000001 +247.64,50.43283629,-2.565142009,51.4755,2.09E-11,10.00036953,-0.5596875,-1.905002507,2.173052274,90.00000001 +247.65,50.43283629,-2.565140602,51.4808,1.70E-11,10.00014751,-0.4953125,-1.804915202,2.093746378,90.00000001 +247.66,50.43283629,-2.565139194,51.4854,6.87E-12,9.999481416,-0.4315625,-1.704450949,2.012614752,90.00000001 +247.67,50.43283629,-2.565137787,51.4894,-8.44E-12,9.999037356,-0.3684375,-1.603630774,1.929728099,90.00000001 +247.68,50.43283629,-2.56513638,51.4928,-1.80E-11,9.999481427,-0.3046875,-1.502475649,1.845158669,90.00000001 +247.69,50.43283629,-2.565134972,51.4955,-1.95E-11,10.00014753,-0.24,-1.401006771,1.758980202,90.00000001 +247.7,50.43283629,-2.565133565,51.4976,-1.66E-11,10.00036957,-0.1753125,-1.299245341,1.671267926,90.00000001 +247.71,50.43283629,-2.565132157,51.499,-7.03E-12,10.00036957,-0.1115625,-1.197212559,1.582098276,90.00000001 +247.72,50.43283629,-2.56513075,51.4998,4.69E-12,10.00036957,-0.048125,-1.094929738,1.491549,90.00000001 +247.73,50.43283629,-2.565129342,51.5,4.69E-12,10.00036957,0.016875,-0.992418249,1.399699052,90.00000001 +247.74,50.43283629,-2.565127935,51.4995,-4.69E-12,10.00036957,0.083125,-0.889699521,1.30662859,90.00000001 +247.75,50.43283629,-2.565126527,51.4983,-4.69E-12,10.00036957,0.148125,-0.786794983,1.212418687,90.00000001 +247.76,50.43283629,-2.56512512,51.4965,6.87E-12,10.00014753,0.2115625,-0.683726179,1.117151562,90.00000001 +247.77,50.43283629,-2.565123712,51.4941,1.33E-11,9.999481429,0.275,-0.580514535,1.020910294,90.00000001 +247.78,50.43283629,-2.565122305,51.491,5.31E-12,9.999037359,0.3384375,-0.477181712,0.923778707,90.00000001 +247.79,50.43283629,-2.565120898,51.4873,-9.38E-12,9.999481419,0.4015625,-0.373749193,0.825841656,90.00000001 +247.8,50.43283629,-2.56511949,51.483,-1.89E-11,10.00014751,0.4653125,-0.270238638,0.727184397,90.00000001 +247.81,50.43283629,-2.565118083,51.478,-2.11E-11,10.00036954,0.53,-0.166671589,0.627893046,90.00000001 +247.82,50.43283629,-2.565116675,51.4724,-1.80E-11,10.00036953,0.5946875,-0.063069819,0.528054119,90.00000001 +247.83,50.43283629,-2.565115268,51.4661,-9.37E-12,10.00036952,0.658125,0.040545186,0.427754763,90.00000001 +247.84,50.43283629,-2.56511386,51.4592,-3.28E-12,10.00036951,0.72,0.144151712,0.327082411,90.00000001 +247.85,50.43283629,-2.565112453,51.4517,-7.81E-12,10.0003695,0.781875,0.2477281,0.226124784,90.00000001 +247.86,50.43283629,-2.565111045,51.4436,-1.33E-11,10.00036948,0.845,0.35125275,0.124970002,90.00000001 +247.87,50.43283629,-2.565109638,51.4348,-9.22E-12,10.00036947,0.908125,0.454704062,0.023706243,90.00000001 +247.88,50.43283629,-2.56510823,51.4254,-2.34E-12,10.00036945,0.9696875,0.558060434,-0.077578142,90.00000001 +247.89,50.43283629,-2.565106823,51.4154,-2.78E-16,10.00014741,1.03,0.661300267,-0.178794918,90.00000001 +247.9,50.43283629,-2.565105415,51.4048,-2.50E-16,9.999481289,1.09,0.764401959,-0.279855792,90.00000001 +247.91,50.43283629,-2.565104008,51.3936,1.56E-13,9.999037206,1.15,0.867344026,-0.380672643,90.00000001 +247.92,50.43283629,-2.565102601,51.3818,3.13E-12,9.999481254,1.2096875,0.970104981,-0.481157523,90.00000001 +247.93,50.43283629,-2.565101193,51.3694,1.33E-11,10.00014733,1.2684375,1.072663337,-0.581222769,90.00000001 +247.94,50.43283629,-2.565099786,51.3564,2.72E-11,10.00036935,1.3265625,1.174997667,-0.680781233,90.00000001 +247.95,50.43283629,-2.565098378,51.3429,3.28E-11,10.00036933,1.385,1.277086657,-0.779746056,90.00000001 +247.96,50.43283629,-2.565096971,51.3287,2.66E-11,10.0003693,1.443125,1.378908878,-0.878030949,90.00000001 +247.97,50.43283629,-2.565095563,51.314,1.87E-11,10.00036928,1.4996875,1.480443187,-0.975550142,90.00000001 +247.98,50.43283629,-2.565094156,51.2987,1.63E-11,10.00014722,1.555,1.581668271,-1.072218665,90.00000001 +247.99,50.43283629,-2.565092748,51.2829,1.64E-11,9.999481099,1.61,1.682563102,-1.167952177,90.00000001 +248,50.43283629,-2.565091341,51.2665,1.70E-11,9.999037007,1.665,1.783106481,-1.2626672,90.00000001 +248.01,50.43283629,-2.565089934,51.2496,1.55E-11,9.999481047,1.7196875,1.883277551,-1.356281227,90.00000001 +248.02,50.43283629,-2.565088526,51.2321,6.09E-12,10.00014712,1.7734375,1.983055287,-1.448712498,90.00000001 +248.03,50.43283629,-2.565087119,51.2141,-1.09E-11,10.00036912,1.82625,2.082418888,-1.539880453,90.00000001 +248.04,50.43283629,-2.565085711,51.1956,-2.73E-11,10.0003691,1.8784375,2.181347614,-1.629705683,90.00000001 +248.05,50.43283629,-2.565084304,51.1765,-3.59E-11,10.00014703,1.9296875,2.279820782,-1.718109747,90.00000001 +248.06,50.43283629,-2.565082896,51.157,-3.53E-11,9.999480902,1.9796875,2.377817822,-1.805015585,90.00000001 +248.07,50.43283629,-2.565081489,51.1369,-2.58E-11,9.999036805,2.0284375,2.475318336,-1.890347392,90.00000001 +248.08,50.43283629,-2.565080082,51.1164,-9.38E-12,9.999480839,2.07625,2.572301871,-1.974030858,90.00000001 +248.09,50.43283629,-2.565078674,51.0954,7.19E-12,10.00014691,2.1234375,2.6687482,-2.055992871,90.00000001 +248.1,50.43283629,-2.565077267,51.0739,1.48E-11,10.0003689,2.17,2.764637214,-2.1361621,90.00000001 +248.11,50.43283629,-2.565075859,51.052,6.25E-12,10.00036887,2.21625,2.859948857,-2.214468528,90.00000001 +248.12,50.43283629,-2.565074452,51.0296,-1.50E-11,10.0001468,2.2615625,2.954663307,-2.290843917,90.00000001 +248.13,50.43283629,-2.565073044,51.0067,-3.05E-11,9.999480668,2.3046875,3.048760624,-2.365221631,90.00000001 +248.14,50.43283629,-2.565071637,50.9835,-2.95E-11,9.999036565,2.346875,3.142221271,-2.437536812,90.00000001 +248.15,50.43283629,-2.56507023,50.9598,-2.48E-11,9.999480594,2.39,3.235025709,-2.507726491,90.00000001 +248.16,50.43283629,-2.565068822,50.9357,-2.34E-11,10.00014666,2.4325,3.327154572,-2.575729362,90.00000001 +248.17,50.43283629,-2.565067415,50.9111,-1.02E-11,10.00036865,2.4715625,3.418588609,-2.641486181,90.00000001 +248.18,50.43283629,-2.565066007,50.8862,1.64E-11,10.00036861,2.508125,3.509308684,-2.704939538,90.00000001 +248.19,50.43283629,-2.5650646,50.861,3.30E-11,10.00014654,2.5453125,3.599295888,-2.766034199,90.00000001 +248.2,50.43283629,-2.565063192,50.8353,3.06E-11,9.999480399,2.583125,3.688531429,-2.824716823,90.00000001 +248.21,50.43283629,-2.565061785,50.8093,2.13E-11,9.999036293,2.619375,3.776996686,-2.880936244,90.00000001 +248.22,50.43283629,-2.565060378,50.7829,1.17E-11,9.999480318,2.653125,3.864673151,-2.934643417,90.00000001 +248.23,50.43283629,-2.56505897,50.7562,4.06E-12,10.00014637,2.6846875,3.951542548,-2.985791589,90.00000001 +248.24,50.43283629,-2.565057563,50.7292,-1.41E-12,10.00036837,2.7153125,4.037586714,-3.034336068,90.00000001 +248.25,50.43283629,-2.565056155,50.7019,-1.08E-11,10.00036832,2.7465625,4.122787658,-3.080234571,90.00000001 +248.26,50.43283629,-2.565054748,50.6743,-1.95E-11,10.00036828,2.7778125,4.207127619,-3.123447105,90.00000001 +248.27,50.43283629,-2.56505334,50.6463,-1.02E-11,10.00036824,2.8065625,4.290588948,-3.163935913,90.00000001 +248.28,50.43283629,-2.565051933,50.6181,1.73E-11,10.00014616,2.8328125,4.373154287,-3.201665699,90.00000001 +248.29,50.43283629,-2.565050525,50.5897,4.08E-11,9.999480015,2.8584375,4.45480633,-3.236603577,90.00000001 +248.3,50.43283629,-2.565049118,50.5609,4.37E-11,9.999035905,2.883125,4.535528062,-3.268719122,90.00000001 +248.31,50.43283629,-2.565047711,50.532,2.97E-11,9.999479925,2.90625,4.61530258,-3.297984316,90.00000001 +248.32,50.43283629,-2.565046303,50.5028,1.25E-11,10.00014598,2.9284375,4.694113269,-3.324373607,90.00000001 +248.33,50.43283629,-2.565044896,50.4734,2.50E-12,10.00036796,2.9496875,4.771943626,-3.347863959,90.00000001 +248.34,50.43283629,-2.565043488,50.4438,-4.16E-16,10.00036792,2.97,4.848777439,-3.36843492,90.00000001 +248.35,50.43283629,-2.565042081,50.414,-2.34E-12,10.00036787,2.9896875,4.924598663,-3.386068613,90.00000001 +248.36,50.43283629,-2.565040673,50.384,-7.03E-12,10.00036783,3.0078125,4.999391427,-3.400749568,90.00000001 +248.37,50.43283629,-2.565039266,50.3538,-4.69E-12,10.00036778,3.023125,5.073140148,-3.412465008,90.00000001 +248.38,50.43283629,-2.565037858,50.3235,9.37E-12,10.00036773,3.03625,5.145829413,-3.421204734,90.00000001 +248.39,50.43283629,-2.565036451,50.2931,2.58E-11,10.00036768,3.0484375,5.217444038,-3.426961127,90.00000001 +248.4,50.43283629,-2.565035043,50.2625,3.28E-11,10.00036764,3.06,5.287969069,-3.4297292,90.00000001 +248.41,50.43283629,-2.565033636,50.2319,2.34E-11,10.00014555,3.07125,5.357389724,-3.429506434,90.00000001 +248.42,50.43283629,-2.565032228,50.2011,2.34E-12,9.999479407,3.0815625,5.425691622,-3.426293115,90.00000001 +248.43,50.43283629,-2.565030821,50.1702,-1.17E-11,9.999035293,3.0896875,5.492860381,-3.420091993,90.00000001 +248.44,50.43283629,-2.565029414,50.1393,-4.69E-12,9.999479311,3.09625,5.558882079,-3.410908568,90.00000001 +248.45,50.43283629,-2.565028006,50.1083,1.64E-11,10.00014536,3.1015625,5.623742849,-3.39875069,90.00000001 +248.46,50.43283629,-2.565026599,50.0772,3.05E-11,10.00036735,3.1046875,5.687429171,-3.383629131,90.00000001 +248.47,50.43283629,-2.565025191,50.0462,2.58E-11,10.0003673,3.1065625,5.749927751,-3.365556953,90.00000001 +248.48,50.43283629,-2.565023784,50.0151,1.17E-11,10.00036725,3.1084375,5.811225526,-3.344549971,90.00000001 +248.49,50.43283629,-2.565022376,49.984,-2.50E-16,10.0003672,3.109375,5.871309662,-3.320626463,90.00000001 +248.5,50.43283629,-2.565020969,49.9529,-9.38E-12,10.00036715,3.108125,5.930167725,-3.293807339,90.00000001 +248.51,50.43283629,-2.565019561,49.9218,-1.41E-11,10.0003671,3.105,5.987787283,-3.264115979,90.00000001 +248.52,50.43283629,-2.565018154,49.8908,-4.69E-12,10.00036705,3.10125,6.044156418,-3.231578221,90.00000001 +248.53,50.43283629,-2.565016746,49.8598,1.64E-11,10.00036701,3.0965625,6.09926327,-3.196222543,90.00000001 +248.54,50.43283629,-2.565015339,49.8288,3.05E-11,10.00014492,3.0896875,6.153096436,-3.158079654,90.00000001 +248.55,50.43283629,-2.565013931,49.798,2.34E-11,9.999478776,3.08125,6.205644515,-3.1171829,90.00000001 +248.56,50.43283629,-2.565012524,49.7672,-2.22E-16,9.999034662,3.071875,6.256896679,-3.073567921,90.00000001 +248.57,50.43283629,-2.565011117,49.7365,-2.58E-11,9.999478681,3.0609375,6.306842155,-3.027272759,90.00000001 +248.58,50.43283629,-2.565009709,49.706,-4.45E-11,10.00014473,3.0484375,6.355470572,-2.978337751,90.00000001 +248.59,50.43283629,-2.565008302,49.6755,-5.16E-11,10.00036672,3.035,6.402771676,-2.926805584,90.00000001 +248.6,50.43283629,-2.565006894,49.6453,-4.22E-11,10.00036667,3.02125,6.448735668,-2.872721175,90.00000001 +248.61,50.43283629,-2.565005487,49.6151,-2.11E-11,10.00036662,3.0065625,6.493352923,-2.816131738,90.00000001 +248.62,50.43283629,-2.565004079,49.5851,-4.69E-12,10.00036658,2.989375,6.536614101,-2.757086604,90.00000001 +248.63,50.43283629,-2.565002672,49.5553,4.16E-16,10.00036653,2.97,6.578510208,-2.695637224,90.00000001 +248.64,50.43283629,-2.565001264,49.5257,2.34E-12,10.00036648,2.9496875,6.619032476,-2.631837228,90.00000001 +248.65,50.43283629,-2.564999857,49.4963,9.38E-12,10.0001444,2.928125,6.658172426,-2.565742192,90.00000001 +248.66,50.43283629,-2.564998449,49.4671,1.42E-11,9.999478259,2.905,6.695921922,-2.497409813,90.00000001 +248.67,50.43283629,-2.564997042,49.4382,7.81E-12,9.999034148,2.8815625,6.732273058,-2.426899678,90.00000001 +248.68,50.43283629,-2.564995635,49.4095,-3.13E-12,9.999478169,2.858125,6.767218269,-2.354273267,90.00000001 +248.69,50.43283629,-2.564994227,49.381,-5.47E-12,10.00014422,2.8328125,6.800750166,-2.279593833,90.00000001 +248.7,50.43283629,-2.56499282,49.3528,-3.75E-12,10.00036621,2.805,6.832861872,-2.20292658,90.00000001 +248.71,50.43283629,-2.564991412,49.3249,-1.08E-11,10.00036617,2.7765625,6.863546627,-2.124338371,90.00000001 +248.72,50.43283629,-2.564990005,49.2973,-1.94E-11,10.00036613,2.7478125,6.892797956,-2.043897675,90.00000001 +248.73,50.43283629,-2.564988597,49.2699,-9.37E-12,10.00036608,2.7165625,6.9206099,-1.961674679,90.00000001 +248.74,50.43283629,-2.56498719,49.2429,1.64E-11,10.00036604,2.683125,6.946976501,-1.877741117,90.00000001 +248.75,50.43283629,-2.564985782,49.2163,2.97E-11,10.000366,2.65,6.971892316,-1.7921701,90.00000001 +248.76,50.43283629,-2.564984375,49.1899,1.64E-11,10.00014392,2.6165625,6.995352187,-1.705036283,90.00000001 +248.77,50.43283629,-2.564982967,49.1639,-6.25E-12,9.999477785,2.58125,7.017351131,-1.61641564,90.00000001 +248.78,50.43283629,-2.56498156,49.1383,-1.63E-11,9.999033679,2.545,7.037884563,-1.526385464,90.00000001 +248.79,50.43283629,-2.564980153,49.113,-1.09E-11,9.999477706,2.508125,7.056948301,-1.43502425,90.00000001 +248.8,50.43283629,-2.564978745,49.0881,-2.34E-12,10.00014377,2.4696875,7.07453822,-1.342411695,90.00000001 +248.81,50.43283629,-2.564977338,49.0636,-9.37E-13,10.00036576,2.4296875,7.09065071,-1.248628531,90.00000001 +248.82,50.43283629,-2.56497593,49.0395,-1.03E-11,10.00036572,2.3884375,7.105282448,-1.153756518,90.00000001 +248.83,50.43283629,-2.564974523,49.0158,-2.81E-11,10.00014365,2.34625,7.11843034,-1.057878448,90.00000001 +248.84,50.43283629,-2.564973115,48.9926,-4.59E-11,9.999477517,2.3034375,7.130091635,-0.961077859,90.00000001 +248.85,50.43283629,-2.564971708,48.9697,-5.55E-11,9.999033415,2.2596875,7.14026387,-0.863439204,90.00000001 +248.86,50.43283629,-2.564970301,48.9474,-5.47E-11,9.999477446,2.2146875,7.148944983,-0.765047626,90.00000001 +248.87,50.43283629,-2.564968893,48.9254,-4.47E-11,10.00014351,2.1684375,7.156133082,-0.665988952,90.00000001 +248.88,50.43283629,-2.564967486,48.904,-3.05E-11,10.00036551,2.1215625,7.161826793,-0.566349472,90.00000001 +248.89,50.43283629,-2.564966078,48.883,-2.34E-11,10.00036548,2.075,7.166024798,-0.466216159,90.00000001 +248.9,50.43283629,-2.564964671,48.8625,-2.58E-11,10.00014341,2.0278125,7.168726294,-0.365676275,90.00000001 +248.91,50.43283629,-2.564963263,48.8424,-2.34E-11,9.999477282,1.978125,7.169930651,-0.264817483,90.00000001 +248.92,50.43283629,-2.564961856,48.8229,-1.17E-11,9.999033186,1.9265625,7.169637698,-0.163727847,90.00000001 +248.93,50.43283629,-2.564960449,48.8039,-2.50E-12,9.999477222,1.8753125,7.167847434,-0.062495372,90.00000001 +248.94,50.43283629,-2.564959041,48.7854,1.56E-12,10.00014329,1.8246875,7.16456026,0.038791535,90.00000001 +248.95,50.43283629,-2.564957634,48.7674,7.66E-12,10.0003653,1.773125,7.159776865,0.140044693,90.00000001 +248.96,50.43283629,-2.564956226,48.7499,1.41E-11,10.00036527,1.7196875,7.153498279,0.241175698,90.00000001 +248.97,50.43283629,-2.564954819,48.733,1.64E-11,10.00014321,1.665,7.145725705,0.342096369,90.00000001 +248.98,50.43283629,-2.564953411,48.7166,1.72E-11,9.999477086,1.61,7.13646092,0.442718759,90.00000001 +248.99,50.43283629,-2.564952004,48.7008,1.62E-11,9.999032994,1.5546875,7.1257057,0.542955032,90.00000001 +249,50.43283629,-2.564950597,48.6855,1.00E-11,9.999477037,1.498125,7.113462394,0.642717928,90.00000001 +249.01,50.43283629,-2.564949189,48.6708,4.53E-12,10.00014311,1.44,7.099733581,0.741920299,90.00000001 +249.02,50.43283629,-2.564947782,48.6567,7.97E-12,10.00036512,1.381875,7.08452201,0.840475743,90.00000001 +249.03,50.43283629,-2.564946374,48.6432,1.25E-11,10.0003651,1.325,7.067830947,0.93829826,90.00000001 +249.04,50.43283629,-2.564944967,48.6302,8.59E-12,10.00036508,1.268125,7.049663888,1.035302536,90.00000001 +249.05,50.43283629,-2.564943559,48.6178,-1.56E-13,10.00036506,1.209375,7.030024556,1.131404059,90.00000001 +249.06,50.43283629,-2.564942152,48.606,-1.17E-11,10.00014301,1.1484375,7.008917135,1.226519006,90.00000001 +249.07,50.43283629,-2.564940744,48.5948,-2.34E-11,9.999476895,1.086875,6.986345921,1.320564356,90.00000001 +249.08,50.43283629,-2.564939337,48.5843,-2.11E-11,9.999032812,1.0265625,6.962315784,1.413458175,90.00000001 +249.09,50.43283629,-2.56493793,48.5743,-2.34E-12,9.999476863,0.9665625,6.936831596,1.505119448,90.00000001 +249.1,50.43283629,-2.564936522,48.5649,1.17E-11,10.00014295,0.9046875,6.909898798,1.595468188,90.00000001 +249.11,50.43283629,-2.564935115,48.5562,9.22E-12,10.00036497,0.841875,6.881522891,1.684425673,90.00000001 +249.12,50.43283629,-2.564933707,48.5481,3.91E-12,10.00036495,0.78,6.851709892,1.77191438,90.00000001 +249.13,50.43283629,-2.5649323,48.5406,7.81E-12,10.00036494,0.718125,6.820465987,1.857857878,90.00000001 +249.14,50.43283629,-2.564930892,48.5337,1.27E-11,10.00036493,0.655,6.787797767,1.942181337,90.00000001 +249.15,50.43283629,-2.564929485,48.5275,9.37E-12,10.00036492,0.591875,6.753711935,2.024811133,90.00000001 +249.16,50.43283629,-2.564928077,48.5219,8.59E-12,10.00036491,0.5296875,6.71821571,2.105675302,90.00000001 +249.17,50.43283629,-2.56492667,48.5169,2.33E-11,10.00014287,0.4665625,6.681316483,2.184703314,90.00000001 +249.18,50.43283629,-2.564925262,48.5125,4.16E-11,9.999476766,0.4015625,6.643021932,2.261826183,90.00000001 +249.19,50.43283629,-2.564923855,48.5089,4.31E-11,9.999032694,0.336875,6.603340079,2.336976702,90.00000001 +249.2,50.43283629,-2.564922448,48.5058,3.14E-11,9.999476755,0.2734375,6.56227923,2.410089383,90.00000001 +249.21,50.43283629,-2.56492104,48.5034,2.27E-11,10.00014285,0.2096875,6.519847867,2.481100454,90.00000001 +249.22,50.43283629,-2.564919633,48.5016,2.03E-11,10.00036488,0.145,6.476054983,2.549947922,90.00000001 +249.23,50.43283629,-2.564918225,48.5005,1.95E-11,10.00036488,0.08,6.430909633,2.616571799,90.00000001 +249.24,50.43283629,-2.564916818,48.5,1.91E-11,10.00036488,0.015,6.384421213,2.680913985,90.00000001 +249.25,50.43283629,-2.56491541,48.5002,1.95E-11,10.00036488,-0.05,6.336599577,2.742918389,90.00000001 +249.26,50.43283629,-2.564914003,48.501,1.80E-11,10.00036488,-0.1146875,6.287454581,2.802530923,90.00000001 +249.27,50.43283629,-2.564912595,48.5025,8.59E-12,10.00036488,-0.1784375,6.236996537,2.859699621,90.00000001 +249.28,50.43283629,-2.564911188,48.5046,-6.09E-12,10.00036489,-0.2415625,6.185235988,2.914374577,90.00000001 +249.29,50.43283629,-2.56490978,48.5073,-1.55E-11,10.00036489,-0.3053125,6.132183706,2.966508178,90.00000001 +249.3,50.43283629,-2.564908373,48.5107,-1.70E-11,10.00014286,-0.37,6.077850805,3.016054933,90.00000001 +249.31,50.43283629,-2.564906965,48.5147,-1.41E-11,9.99947677,-0.4346875,6.022248632,3.062971639,90.00000001 +249.32,50.43283629,-2.564905558,48.5194,-4.53E-12,9.999032711,-0.4984375,5.965388759,3.107217446,90.00000001 +249.33,50.43283629,-2.564904151,48.5247,9.37E-12,9.999476785,-0.5615625,5.907283103,3.148753677,90.00000001 +249.34,50.43283629,-2.564902743,48.5306,1.56E-11,10.00014289,-0.625,5.847943813,3.187544123,90.00000001 +249.35,50.43283629,-2.564901336,48.5372,9.37E-12,10.00036494,-0.688125,5.787383262,3.223554979,90.00000001 +249.36,50.43283629,-2.564899928,48.5444,3.28E-12,10.00036495,-0.75,5.725614057,3.256754904,90.00000001 +249.37,50.43283629,-2.564898521,48.5522,7.81E-12,10.00036496,-0.811875,5.662649147,3.287114849,90.00000001 +249.38,50.43283629,-2.564897113,48.5606,1.09E-11,10.00036497,-0.8746875,5.598501652,3.314608343,90.00000001 +249.39,50.43283629,-2.564895706,48.5697,-2.50E-12,10.00036499,-0.9365625,5.533184979,3.339211495,90.00000001 +249.4,50.43283629,-2.564894298,48.5794,-2.11E-11,10.000365,-0.9965625,5.466712822,3.360902817,90.00000001 +249.41,50.43283629,-2.564892891,48.5896,-2.34E-11,10.00036502,-1.056875,5.399098932,3.379663403,90.00000001 +249.42,50.43283629,-2.564891483,48.6005,-1.16E-11,10.00036504,-1.1184375,5.330357575,3.395476809,90.00000001 +249.43,50.43283629,-2.564890076,48.612,-1.56E-12,10.00014302,-1.1796875,5.260503019,3.408329341,90.00000001 +249.44,50.43283629,-2.564888668,48.6241,-7.81E-13,9.999476941,-1.2396875,5.189549874,3.418209769,90.00000001 +249.45,50.43283629,-2.564887261,48.6368,-7.97E-12,9.999032895,-1.298125,5.117512922,3.425109442,90.00000001 +249.46,50.43283629,-2.564885854,48.6501,-1.41E-11,9.999476981,-1.355,5.044407289,3.4290224,90.00000001 +249.47,50.43283629,-2.564884446,48.6639,-1.09E-11,10.0001431,-1.411875,4.970248215,3.429945148,90.00000001 +249.48,50.43283629,-2.564883039,48.6783,-7.03E-12,10.00036516,-1.47,4.895051114,3.427877,90.00000001 +249.49,50.43283629,-2.564881631,48.6933,-1.19E-11,10.00036518,-1.528125,4.818831799,3.422819616,90.00000001 +249.5,50.43283629,-2.564880224,48.7089,-2.11E-11,10.00036521,-1.584375,4.741606084,3.414777523,90.00000001 +249.51,50.43283629,-2.564878816,48.725,-3.20E-11,10.00036523,-1.6384375,4.663390126,3.403757711,90.00000001 +249.52,50.43283629,-2.564877409,48.7417,-4.45E-11,10.00036526,-1.6915625,4.584200368,3.389769749,90.00000001 +249.53,50.43283629,-2.564876001,48.7588,-5.02E-11,10.00036528,-1.745,4.504053199,3.37282584,90.00000001 +249.54,50.43283629,-2.564874594,48.7766,-4.30E-11,10.00014328,-1.7984375,4.422965404,3.352940824,90.00000001 +249.55,50.43283629,-2.564873186,48.7948,-2.73E-11,9.999477207,-1.85125,4.340953944,3.330131947,90.00000001 +249.56,50.43283629,-2.564871779,48.8136,-1.16E-11,9.999033171,-1.9034375,4.25803595,3.304419205,90.00000001 +249.57,50.43283629,-2.564870372,48.8329,2.22E-16,9.999477267,-1.954375,4.174228669,3.275824887,90.00000001 +249.58,50.43283629,-2.564868964,48.8527,1.17E-11,10.0001434,-2.0034375,4.089549689,3.244374031,90.00000001 +249.59,50.43283629,-2.564867557,48.873,2.58E-11,10.00036546,-2.0515625,4.004016659,3.21009408,90.00000001 +249.6,50.43283629,-2.564866149,48.8937,3.05E-11,10.00036549,-2.0996875,3.917647454,3.17301483,90.00000001 +249.61,50.43283629,-2.564864742,48.915,1.41E-11,10.00014349,-2.146875,3.830460122,3.133168652,90.00000001 +249.62,50.43283629,-2.564863334,48.9367,-1.62E-11,9.99947743,-2.1928125,3.74247277,3.090590325,90.00000001 +249.63,50.43283629,-2.564861927,48.9588,-3.91E-11,9.999033398,-2.2384375,3.653703903,3.045316976,90.00000001 +249.64,50.43283629,-2.56486052,48.9815,-4.06E-11,9.999477499,-2.283125,3.564172028,2.997388025,90.00000001 +249.65,50.43283629,-2.564859112,49.0045,-2.67E-11,10.00014363,-2.32625,3.473895767,2.946845355,90.00000001 +249.66,50.43283629,-2.564857705,49.028,-1.17E-11,10.0003657,-2.3684375,3.382894026,2.89373297,90.00000001 +249.67,50.43283629,-2.564856297,49.0519,-3.91E-12,10.00036574,-2.4096875,3.291185828,2.838097164,90.00000001 +249.68,50.43283629,-2.56485489,49.0762,-4.69E-12,10.00014375,-2.4496875,3.198790368,2.779986524,90.00000001 +249.69,50.43283629,-2.564853482,49.1009,-1.42E-11,9.999477686,-2.4884375,3.105726781,2.719451699,90.00000001 +249.7,50.43283629,-2.564852075,49.126,-3.06E-11,9.999033659,-2.52625,3.012014664,2.656545517,90.00000001 +249.71,50.43283629,-2.564850668,49.1514,-4.70E-11,9.999477766,-2.5634375,2.917673496,2.591322752,90.00000001 +249.72,50.43283629,-2.56484926,49.1773,-5.64E-11,10.00014391,-2.5996875,2.822723045,2.523840298,90.00000001 +249.73,50.43283629,-2.564847853,49.2034,-5.64E-11,10.00036598,-2.6346875,2.727183077,2.454156999,90.00000001 +249.74,50.43283629,-2.564846445,49.23,-4.69E-11,10.00036602,-2.6684375,2.63107359,2.382333703,90.00000001 +249.75,50.43283629,-2.564845038,49.2568,-2.75E-11,10.00036606,-2.7009375,2.534414635,2.308432919,90.00000001 +249.76,50.43283629,-2.56484363,49.284,-9.38E-13,10.00036611,-2.731875,2.437226383,2.232519163,90.00000001 +249.77,50.43283629,-2.564842223,49.3115,2.25E-11,10.00014411,-2.76125,2.339529172,2.15465861,90.00000001 +249.78,50.43283629,-2.564840815,49.3392,3.13E-11,9.999478058,-2.79,2.241343343,2.074919214,90.00000001 +249.79,50.43283629,-2.564839408,49.3673,2.42E-11,9.999034037,-2.8184375,2.142689464,1.993370418,90.00000001 +249.8,50.43283629,-2.564838001,49.3956,8.59E-12,9.999478148,-2.84625,2.043588106,1.910083382,90.00000001 +249.81,50.43283629,-2.564836593,49.4242,-2.34E-12,10.00014429,-2.8728125,1.944059951,1.8251307,90.00000001 +249.82,50.43283629,-2.564835186,49.4531,7.81E-12,10.00036637,-2.8965625,1.844125856,1.738586514,90.00000001 +249.83,50.43283629,-2.564833778,49.4822,3.44E-11,10.00036641,-2.918125,1.743806618,1.650526224,90.00000001 +249.84,50.43283629,-2.564832371,49.5114,4.84E-11,10.00014443,-2.94,1.643123208,1.561026664,90.00000001 +249.85,50.43283629,-2.564830963,49.541,3.83E-11,9.999478375,-2.96125,1.542096597,1.470165871,90.00000001 +249.86,50.43283629,-2.564829556,49.5707,2.36E-11,9.999034355,-2.979375,1.440747983,1.378023028,90.00000001 +249.87,50.43283629,-2.564828149,49.6006,1.64E-11,9.999478467,-2.9953125,1.33909851,1.284678577,90.00000001 +249.88,50.43283629,-2.564826741,49.6306,7.03E-12,10.00014461,-3.0115625,1.237169375,1.190213879,90.00000001 +249.89,50.43283629,-2.564825334,49.6608,-4.69E-12,10.00036669,-3.028125,1.134981837,1.094711269,90.00000001 +249.9,50.43283629,-2.564823926,49.6912,-4.69E-12,10.00036674,-3.043125,1.032557323,0.998254053,90.00000001 +249.91,50.43283629,-2.564822519,49.7217,9.37E-12,10.00036679,-3.05625,0.929917148,0.900926343,90.00000001 +249.92,50.43283629,-2.564821111,49.7523,2.34E-11,10.00036684,-3.068125,0.82708274,0.80281305,90.00000001 +249.93,50.43283629,-2.564819704,49.7831,2.58E-11,10.00014485,-3.0778125,0.724075643,0.70399966,90.00000001 +249.94,50.43283629,-2.564818296,49.8139,2.34E-11,9.999478802,-3.085,0.620917342,0.604572346,90.00000001 +249.95,50.43283629,-2.564816889,49.8448,3.05E-11,9.999034783,-3.0915625,0.517629324,0.504617853,90.00000001 +249.96,50.43283629,-2.564815482,49.8757,4.22E-11,9.999478898,-3.098125,0.414233245,0.404223329,90.00000001 +249.97,50.43283629,-2.564814074,49.9068,4.22E-11,10.00014505,-3.103125,0.31075065,0.303476321,90.00000001 +249.98,50.43283629,-2.564812667,49.9378,2.81E-11,10.00036713,-3.10625,0.207203139,0.202464721,90.00000001 +249.99,50.43283629,-2.564811259,49.9689,1.17E-11,10.00036718,-3.1084375,0.103612427,0.101276536,90.00000001 +250,50.43283629,-2.564809852,50,1.67E-16,10.00036722,-3.109375,0,0,90.00000001 +250.01,50.43283629,-2.564808444,50.0311,-1.19E-11,10.00036727,-3.1084375,-0.103612427,-0.101276536,90.00000001 +250.02,50.43283629,-2.564807037,50.0622,-2.89E-11,10.00036732,-3.10625,-0.207203139,-0.202464721,90.00000001 +250.03,50.43283629,-2.564805629,50.0932,-4.37E-11,10.00036737,-3.103125,-0.31075065,-0.303476321,90.00000001 +250.04,50.43283629,-2.564804222,50.1243,-4.37E-11,10.00036742,-3.098125,-0.414233245,-0.404223329,90.00000001 +250.05,50.43283629,-2.564802814,50.1552,-3.12E-11,10.00036747,-3.0915625,-0.517629324,-0.504617853,90.00000001 +250.06,50.43283629,-2.564801407,50.1861,-2.36E-11,10.00014548,-3.085,-0.620917342,-0.604572346,90.00000001 +250.07,50.43283629,-2.564799999,50.2169,-2.58E-11,9.999479432,-3.0778125,-0.724075643,-0.70399966,90.00000001 +250.08,50.43283629,-2.564798592,50.2477,-2.34E-11,9.999035414,-3.068125,-0.82708274,-0.80281305,90.00000001 +250.09,50.43283629,-2.564797185,50.2783,-9.37E-12,9.999479528,-3.05625,-0.929917148,-0.900926343,90.00000001 +250.1,50.43283629,-2.564795777,50.3088,4.69E-12,10.00014568,-3.043125,-1.032557323,-0.998254053,90.00000001 +250.11,50.43283629,-2.56479437,50.3392,4.84E-12,10.00036776,-3.028125,-1.134981837,-1.094711269,90.00000001 +250.12,50.43283629,-2.564792962,50.3694,-6.25E-12,10.0003678,-3.0115625,-1.237169375,-1.190213879,90.00000001 +250.13,50.43283629,-2.564791555,50.3994,-1.48E-11,10.00036785,-2.9953125,-1.33909851,-1.284678577,90.00000001 +250.14,50.43283629,-2.564790147,50.4293,-2.19E-11,10.0003679,-2.979375,-1.440747983,-1.378023028,90.00000001 +250.15,50.43283629,-2.56478874,50.459,-3.67E-11,10.00036794,-2.96125,-1.542096597,-1.470165871,90.00000001 +250.16,50.43283629,-2.564787332,50.4886,-4.67E-11,10.00036799,-2.94,-1.643123208,-1.561026664,90.00000001 +250.17,50.43283629,-2.564785925,50.5178,-3.28E-11,10.00036803,-2.918125,-1.743806618,-1.650526224,90.00000001 +250.18,50.43283629,-2.564784517,50.5469,-7.19E-12,10.00036808,-2.8965625,-1.844125856,-1.738586514,90.00000001 +250.19,50.43283629,-2.56478311,50.5758,1.56E-12,10.00014609,-2.8728125,-1.944059951,-1.8251307,90.00000001 +250.2,50.43283629,-2.564781702,50.6044,-1.09E-11,9.999480038,-2.84625,-2.043588106,-1.910083382,90.00000001 +250.21,50.43283629,-2.564780295,50.6327,-2.73E-11,9.999036016,-2.8184375,-2.142689464,-1.993370418,90.00000001 +250.22,50.43283629,-2.564778888,50.6608,-3.38E-11,9.999480126,-2.79,-2.241343343,-2.074919214,90.00000001 +250.23,50.43283629,-2.56477748,50.6885,-2.44E-11,10.00014627,-2.76125,-2.339529172,-2.15465861,90.00000001 +250.24,50.43283629,-2.564776073,50.716,-1.72E-12,10.00036835,-2.731875,-2.437226383,-2.232519163,90.00000001 +250.25,50.43283629,-2.564774665,50.7432,2.34E-11,10.00036839,-2.7009375,-2.534414635,-2.308432919,90.00000001 +250.26,50.43283629,-2.564773258,50.77,4.22E-11,10.00036843,-2.6684375,-2.63107359,-2.382333703,90.00000001 +250.27,50.43283629,-2.56477185,50.7966,5.23E-11,10.00036847,-2.6346875,-2.727183077,-2.454156999,90.00000001 +250.28,50.43283629,-2.564770443,50.8227,5.39E-11,10.00036851,-2.5996875,-2.822723045,-2.523840298,90.00000001 +250.29,50.43283629,-2.564769035,50.8486,4.61E-11,10.00036855,-2.5634375,-2.917673496,-2.591322752,90.00000001 +250.3,50.43283629,-2.564767628,50.874,3.03E-11,10.00036859,-2.52625,-3.012014664,-2.656545517,90.00000001 +250.31,50.43283629,-2.56476622,50.8991,1.33E-11,10.00036863,-2.4884375,-3.105726781,-2.719451699,90.00000001 +250.32,50.43283629,-2.564764813,50.9238,2.34E-12,10.00014664,-2.4496875,-3.198790368,-2.779986524,90.00000001 +250.33,50.43283629,-2.564763405,50.9481,9.37E-13,9.999480576,-2.4096875,-3.291185828,-2.838097164,90.00000001 +250.34,50.43283629,-2.564761998,50.972,1.02E-11,9.999036547,-2.3684375,-3.382894026,-2.89373297,90.00000001 +250.35,50.43283629,-2.564760591,50.9955,2.72E-11,9.99948065,-2.32625,-3.473895767,-2.946845355,90.00000001 +250.36,50.43283629,-2.564759183,51.0185,4.13E-11,10.00014679,-2.283125,-3.564172028,-2.997388025,90.00000001 +250.37,50.43283629,-2.564757776,51.0412,3.83E-11,10.00036885,-2.2384375,-3.653703903,-3.045316976,90.00000001 +250.38,50.43283629,-2.564756368,51.0633,1.48E-11,10.00036889,-2.1928125,-3.74247277,-3.090590325,90.00000001 +250.39,50.43283629,-2.564754961,51.085,-1.48E-11,10.00014689,-2.146875,-3.830460122,-3.133168652,90.00000001 +250.4,50.43283629,-2.564753553,51.1063,-3.06E-11,9.999480823,-2.0996875,-3.917647454,-3.17301483,90.00000001 +250.41,50.43283629,-2.564752146,51.127,-2.58E-11,9.99903679,-2.0515625,-4.004016659,-3.21009408,90.00000001 +250.42,50.43283629,-2.564750739,51.1473,-1.17E-11,9.999480887,-2.0034375,-4.089549689,-3.244374031,90.00000001 +250.43,50.43283629,-2.564749331,51.1671,1.56E-13,10.00014702,-1.954375,-4.174228669,-3.275824887,90.00000001 +250.44,50.43283629,-2.564747924,51.1864,1.25E-11,10.00036908,-1.9034375,-4.25803595,-3.304419205,90.00000001 +250.45,50.43283629,-2.564746516,51.2052,2.97E-11,10.00036911,-1.85125,-4.340953944,-3.330131947,90.00000001 +250.46,50.43283629,-2.564745109,51.2234,4.59E-11,10.00014711,-1.7984375,-4.422965404,-3.352940824,90.00000001 +250.47,50.43283629,-2.564743701,51.2412,5.16E-11,9.999481034,-1.745,-4.504053199,-3.37282584,90.00000001 +250.48,50.43283629,-2.564742294,51.2583,4.30E-11,9.999036995,-1.6915625,-4.584200368,-3.389769749,90.00000001 +250.49,50.43283629,-2.564740887,51.275,2.81E-11,9.999481087,-1.6384375,-4.663390126,-3.403757711,90.00000001 +250.5,50.43283629,-2.564739479,51.2911,1.62E-11,10.00014721,-1.584375,-4.741606084,-3.414777523,90.00000001 +250.51,50.43283629,-2.564738072,51.3067,6.87E-12,10.00036927,-1.528125,-4.818831799,-3.422819616,90.00000001 +250.52,50.43283629,-2.564736664,51.3217,2.19E-12,10.00036929,-1.47,-4.895051114,-3.427877,90.00000001 +250.53,50.43283629,-2.564735257,51.3361,7.03E-12,10.00036931,-1.411875,-4.970248215,-3.429945148,90.00000001 +250.54,50.43283629,-2.564733849,51.3499,1.23E-11,10.00036934,-1.355,-5.044407289,-3.4290224,90.00000001 +250.55,50.43283629,-2.564732442,51.3632,8.44E-12,10.00014732,-1.298125,-5.117512922,-3.425109442,90.00000001 +250.56,50.43283629,-2.564731034,51.3759,1.41E-12,9.999481245,-1.2396875,-5.189549874,-3.418209769,90.00000001 +250.57,50.43283629,-2.564729627,51.388,7.81E-13,9.999037197,-1.1796875,-5.260503019,-3.408329341,90.00000001 +250.58,50.43283629,-2.56472822,51.3995,1.02E-11,9.999481282,-1.1184375,-5.330357575,-3.395476809,90.00000001 +250.59,50.43283629,-2.564726812,51.4104,2.28E-11,10.0001474,-1.056875,-5.399098932,-3.379663403,90.00000001 +250.6,50.43283629,-2.564725405,51.4206,2.17E-11,10.00036945,-0.9965625,-5.466712822,-3.360902817,90.00000001 +250.61,50.43283629,-2.564723997,51.4303,3.91E-12,10.00036946,-0.9365625,-5.533184979,-3.339211495,90.00000001 +250.62,50.43283629,-2.56472259,51.4394,-1.02E-11,10.00014744,-0.8746875,-5.598501652,-3.314608343,90.00000001 +250.63,50.43283629,-2.564721182,51.4478,-8.44E-12,9.999481358,-0.811875,-5.662649147,-3.287114849,90.00000001 +250.64,50.43283629,-2.564719775,51.4556,-3.75E-12,9.999037304,-0.75,-5.725614057,-3.256754904,90.00000001 +250.65,50.43283629,-2.564718368,51.4628,-7.81E-12,9.999481381,-0.688125,-5.787383262,-3.223554979,90.00000001 +250.66,50.43283629,-2.56471696,51.4694,-1.27E-11,10.00014749,-0.625,-5.847943813,-3.187544123,90.00000001 +250.67,50.43283629,-2.564715553,51.4753,-6.87E-12,10.00036953,-0.5615625,-5.907283103,-3.148753677,90.00000001 +250.68,50.43283629,-2.564714145,51.4806,6.41E-12,10.00036954,-0.4984375,-5.965388759,-3.107217446,90.00000001 +250.69,50.43283629,-2.564712738,51.4853,1.66E-11,10.00014751,-0.4346875,-6.022248632,-3.062971639,90.00000001 +250.7,50.43283629,-2.56471133,51.4893,2.02E-11,9.999481421,-0.37,-6.077850805,-3.016054933,90.00000001 +250.71,50.43283629,-2.564709923,51.4927,1.80E-11,9.999037361,-0.3053125,-6.132183706,-2.966508178,90.00000001 +250.72,50.43283629,-2.564708516,51.4954,7.81E-12,9.999481432,-0.2415625,-6.185235988,-2.914374577,90.00000001 +250.73,50.43283629,-2.564707108,51.4975,-6.88E-12,10.00014753,-0.1784375,-6.236996537,-2.859699621,90.00000001 +250.74,50.43283629,-2.564705701,51.499,-1.64E-11,10.00036957,-0.1146875,-6.287454581,-2.802530923,90.00000001 +250.75,50.43283629,-2.564704293,51.4998,-1.87E-11,10.00036957,-0.05,-6.336599577,-2.742918389,90.00000001 +250.76,50.43283629,-2.564702886,51.5,-1.87E-11,10.00036957,0.015,-6.384421213,-2.680913985,90.00000001 +250.77,50.43283629,-2.564701478,51.4995,-1.88E-11,10.00036957,0.08,-6.430909633,-2.616571799,90.00000001 +250.78,50.43283629,-2.564700071,51.4984,-1.88E-11,10.00036957,0.145,-6.476054983,-2.549947922,90.00000001 +250.79,50.43283629,-2.564698663,51.4966,-2.09E-11,10.00036957,0.2096875,-6.519847867,-2.481100454,90.00000001 +250.8,50.43283629,-2.564697256,51.4942,-2.97E-11,10.00036956,0.2734375,-6.56227923,-2.410089383,90.00000001 +250.81,50.43283629,-2.564695848,51.4911,-4.05E-11,10.00036956,0.336875,-6.603340079,-2.336976702,90.00000001 +250.82,50.43283629,-2.564694441,51.4875,-3.75E-11,10.00014752,0.4015625,-6.643021932,-2.261826183,90.00000001 +250.83,50.43283629,-2.564693033,51.4831,-1.86E-11,9.999481412,0.4665625,-6.681316483,-2.184703314,90.00000001 +250.84,50.43283629,-2.564691626,51.4781,-4.69E-12,9.999037339,0.5296875,-6.71821571,-2.105675302,90.00000001 +250.85,50.43283629,-2.564690219,51.4725,-7.81E-12,9.999481396,0.591875,-6.753711935,-2.024811133,90.00000001 +250.86,50.43283629,-2.564688811,51.4663,-1.41E-11,10.00014749,0.655,-6.787797767,-1.942181337,90.00000001 +250.87,50.43283629,-2.564687404,51.4594,-1.08E-11,10.00036951,0.718125,-6.820465987,-1.857857878,90.00000001 +250.88,50.43283629,-2.564685996,51.4519,-6.25E-12,10.0003695,0.78,-6.851709892,-1.77191438,90.00000001 +250.89,50.43283629,-2.564684589,51.4438,-1.02E-11,10.00036948,0.841875,-6.881522891,-1.684425673,90.00000001 +250.9,50.43283629,-2.564683181,51.4351,-1.19E-11,10.00036947,0.9046875,-6.909898798,-1.595468188,90.00000001 +250.91,50.43283629,-2.564681774,51.4257,2.34E-12,10.00036946,0.9665625,-6.936831596,-1.505119448,90.00000001 +250.92,50.43283629,-2.564680366,51.4157,2.11E-11,10.00036944,1.0265625,-6.962315784,-1.413458175,90.00000001 +250.93,50.43283629,-2.564678959,51.4052,2.34E-11,10.00036942,1.086875,-6.986345921,-1.320564356,90.00000001 +250.94,50.43283629,-2.564677551,51.394,1.16E-11,10.00036941,1.1484375,-7.008917135,-1.226519006,90.00000001 +250.95,50.43283629,-2.564676144,51.3822,-7.82E-13,10.00014735,1.209375,-7.030024556,-1.131404059,90.00000001 +250.96,50.43283629,-2.564674736,51.3698,-1.09E-11,9.999481235,1.268125,-7.049663888,-1.035302536,90.00000001 +250.97,50.43283629,-2.564673329,51.3568,-1.55E-11,9.999037149,1.325,-7.067830947,-0.93829826,90.00000001 +250.98,50.43283629,-2.564671922,51.3433,-9.38E-12,9.999481194,1.381875,-7.08452201,-0.840475743,90.00000001 +250.99,50.43283629,-2.564670514,51.3292,-3.13E-12,10.00014727,1.44,-7.099733581,-0.741920299,90.00000001 +251,50.43283629,-2.564669107,51.3145,-7.03E-12,10.00036928,1.498125,-7.113462394,-0.642717928,90.00000001 +251.01,50.43283629,-2.564667699,51.2992,-1.39E-11,10.00036926,1.5546875,-7.1257057,-0.542955032,90.00000001 +251.02,50.43283629,-2.564666292,51.2834,-1.64E-11,10.00036923,1.61,-7.13646092,-0.442718759,90.00000001 +251.03,50.43283629,-2.564664884,51.267,-1.70E-11,10.00036921,1.665,-7.145725705,-0.342096369,90.00000001 +251.04,50.43283629,-2.564663477,51.2501,-1.55E-11,10.00036918,1.7196875,-7.153498279,-0.241175698,90.00000001 +251.05,50.43283629,-2.564662069,51.2326,-8.44E-12,10.00036915,1.773125,-7.159776865,-0.140044693,90.00000001 +251.06,50.43283629,-2.564660662,51.2146,-7.81E-13,10.00036913,1.8246875,-7.16456026,-0.038791535,90.00000001 +251.07,50.43283629,-2.564659254,51.1961,3.91E-12,10.0003691,1.8753125,-7.167847434,0.062495372,90.00000001 +251.08,50.43283629,-2.564657847,51.1771,1.25E-11,10.00014703,1.9265625,-7.169637698,0.163727847,90.00000001 +251.09,50.43283629,-2.564656439,51.1576,2.36E-11,9.999480903,1.978125,-7.169930651,0.264817483,90.00000001 +251.1,50.43283629,-2.564655032,51.1375,2.58E-11,9.999036806,2.0278125,-7.168726294,0.365676275,90.00000001 +251.11,50.43283629,-2.564653625,51.117,2.34E-11,9.99948084,2.075,-7.166024798,0.466216159,90.00000001 +251.12,50.43283629,-2.564652217,51.096,3.03E-11,10.00014691,2.1215625,-7.161826793,0.566349472,90.00000001 +251.13,50.43283629,-2.56465081,51.0746,4.38E-11,10.00036891,2.1684375,-7.156133082,0.665988952,90.00000001 +251.14,50.43283629,-2.564649402,51.0526,5.23E-11,10.00036887,2.2146875,-7.148944983,0.765047626,90.00000001 +251.15,50.43283629,-2.564647995,51.0303,5.23E-11,10.00036884,2.2596875,-7.14026387,0.863439204,90.00000001 +251.16,50.43283629,-2.564646587,51.0074,4.36E-11,10.0003688,2.3034375,-7.130091635,0.961077859,90.00000001 +251.17,50.43283629,-2.56464518,50.9842,2.72E-11,10.00014673,2.34625,-7.11843034,1.057878448,90.00000001 +251.18,50.43283629,-2.564643772,50.9605,1.00E-11,9.999480595,2.3884375,-7.105282448,1.153756518,90.00000001 +251.19,50.43283629,-2.564642365,50.9364,-6.66E-16,9.999036491,2.4296875,-7.09065071,1.248628531,90.00000001 +251.2,50.43283629,-2.564640958,50.9119,-1.57E-13,9.999480519,2.4696875,-7.07453822,1.342411695,90.00000001 +251.21,50.43283629,-2.56463955,50.887,6.87E-12,10.00014658,2.508125,-7.056948301,1.43502425,90.00000001 +251.22,50.43283629,-2.564638143,50.8617,1.16E-11,10.00036857,2.545,-7.037884563,1.526385464,90.00000001 +251.23,50.43283629,-2.564636735,50.8361,2.19E-12,10.00036853,2.58125,-7.017351131,1.61641564,90.00000001 +251.24,50.43283629,-2.564635328,50.8101,-1.89E-11,10.00036849,2.6165625,-6.995352187,1.705036283,90.00000001 +251.25,50.43283629,-2.56463392,50.7837,-3.05E-11,10.00036845,2.65,-6.971892316,1.7921701,90.00000001 +251.26,50.43283629,-2.564632513,50.7571,-1.56E-11,10.00014638,2.683125,-6.946976501,1.877741117,90.00000001 +251.27,50.43283629,-2.564631105,50.7301,1.17E-11,9.999480234,2.7165625,-6.9206099,1.961674679,90.00000001 +251.28,50.43283629,-2.564629698,50.7027,2.25E-11,9.999036126,2.7478125,-6.892797956,2.043897675,90.00000001 +251.29,50.43283629,-2.564628291,50.6751,1.33E-11,9.999480149,2.7765625,-6.863546627,2.124338371,90.00000001 +251.3,50.43283629,-2.564626883,50.6472,5.47E-12,10.0001462,2.805,-6.832861872,2.20292658,90.00000001 +251.31,50.43283629,-2.564625476,50.619,7.03E-12,10.00036819,2.8328125,-6.800750166,2.279593833,90.00000001 +251.32,50.43283629,-2.564624068,50.5905,3.91E-12,10.00036815,2.858125,-6.767218269,2.354273267,90.00000001 +251.33,50.43283629,-2.564622661,50.5618,-8.59E-12,10.00014607,2.8815625,-6.732273058,2.426899678,90.00000001 +251.34,50.43283629,-2.564621253,50.5329,-1.56E-11,9.999479926,2.905,-6.695921922,2.497409813,90.00000001 +251.35,50.43283629,-2.564619846,50.5037,-1.02E-11,9.999035814,2.928125,-6.658172426,2.565742192,90.00000001 +251.36,50.43283629,-2.564618439,50.4743,-2.50E-12,9.999479834,2.9496875,-6.619032476,2.631837228,90.00000001 +251.37,50.43283629,-2.564617031,50.4447,-4.44E-16,10.00014589,2.97,-6.578510208,2.695637224,90.00000001 +251.38,50.43283629,-2.564615624,50.4149,4.69E-12,10.00036787,2.989375,-6.536614101,2.757086604,90.00000001 +251.39,50.43283629,-2.564614216,50.3849,2.11E-11,10.00036783,3.0065625,-6.493352923,2.816131738,90.00000001 +251.4,50.43283629,-2.564612809,50.3547,4.22E-11,10.00014575,3.02125,-6.448735668,2.872721175,90.00000001 +251.41,50.43283629,-2.564611401,50.3245,5.16E-11,9.9994796,3.035,-6.402771676,2.926805584,90.00000001 +251.42,50.43283629,-2.564609994,50.294,4.45E-11,9.999035487,3.0484375,-6.355470572,2.978337751,90.00000001 +251.43,50.43283629,-2.564608587,50.2635,2.58E-11,9.999479505,3.0609375,-6.306842155,3.027272759,90.00000001 +251.44,50.43283629,-2.564607179,50.2328,2.22E-16,10.00014556,3.071875,-6.256896679,3.073567921,90.00000001 +251.45,50.43283629,-2.564605772,50.202,-2.34E-11,10.00036754,3.08125,-6.205644515,3.1171829,90.00000001 +251.46,50.43283629,-2.564604364,50.1712,-3.05E-11,10.00036749,3.0896875,-6.153096436,3.158079654,90.00000001 +251.47,50.43283629,-2.564602957,50.1402,-1.64E-11,10.00014541,3.0965625,-6.09926327,3.196222543,90.00000001 +251.48,50.43283629,-2.564601549,50.1092,4.69E-12,9.999479263,3.10125,-6.044156418,3.231578221,90.00000001 +251.49,50.43283629,-2.564600142,50.0782,1.41E-11,9.999035149,3.105,-5.987787283,3.264115979,90.00000001 +251.5,50.43283629,-2.564598735,50.0471,9.38E-12,9.999479167,3.108125,-5.930167725,3.293807339,90.00000001 +251.51,50.43283629,-2.564597327,50.016,2.50E-16,10.00014522,3.109375,-5.871309662,3.320626463,90.00000001 +251.52,50.43283629,-2.56459592,49.9849,-1.17E-11,10.0003672,3.1084375,-5.811225526,3.344549971,90.00000001 +251.53,50.43283629,-2.564594512,49.9538,-2.58E-11,10.00036715,3.1065625,-5.749927751,3.365556953,90.00000001 +251.54,50.43283629,-2.564593105,49.9228,-3.05E-11,10.0003671,3.1046875,-5.687429171,3.383629131,90.00000001 +251.55,50.43283629,-2.564591697,49.8917,-1.64E-11,10.00036706,3.1015625,-5.623742849,3.39875069,90.00000001 +251.56,50.43283629,-2.56459029,49.8607,4.69E-12,10.00036701,3.09625,-5.558882079,3.410908568,90.00000001 +251.57,50.43283629,-2.564588882,49.8298,1.17E-11,10.00036696,3.0896875,-5.492860381,3.420091993,90.00000001 +251.58,50.43283629,-2.564587475,49.7989,-2.34E-12,10.00014488,3.0815625,-5.425691622,3.426293115,90.00000001 +251.59,50.43283629,-2.564586067,49.7681,-2.34E-11,9.99947873,3.07125,-5.357389724,3.429506434,90.00000001 +251.6,50.43283629,-2.56458466,49.7375,-3.28E-11,9.999034616,3.06,-5.287969069,3.4297292,90.00000001 +251.61,50.43283629,-2.564583253,49.7069,-2.58E-11,9.999478634,3.0484375,-5.217444038,3.426961127,90.00000001 +251.62,50.43283629,-2.564581845,49.6765,-9.37E-12,10.00014469,3.03625,-5.145829413,3.421204734,90.00000001 +251.63,50.43283629,-2.564580438,49.6462,4.69E-12,10.00036667,3.023125,-5.073140148,3.412465008,90.00000001 +251.64,50.43283629,-2.56457903,49.616,7.03E-12,10.00036662,3.0078125,-4.999391427,3.400749568,90.00000001 +251.65,50.43283629,-2.564577623,49.586,2.34E-12,10.00036658,2.9896875,-4.924598663,3.386068613,90.00000001 +251.66,50.43283629,-2.564576215,49.5562,4.44E-16,10.00036653,2.97,-4.848777439,3.36843492,90.00000001 +251.67,50.43283629,-2.564574808,49.5266,-2.34E-12,10.00036648,2.9496875,-4.771943626,3.347863959,90.00000001 +251.68,50.43283629,-2.5645734,49.4972,-1.16E-11,10.00036644,2.9284375,-4.694113269,3.324373607,90.00000001 +251.69,50.43283629,-2.564571993,49.468,-2.73E-11,10.00036639,2.90625,-4.61530258,3.297984316,90.00000001 +251.7,50.43283629,-2.564570585,49.4391,-4.06E-11,10.00036635,2.883125,-4.535528062,3.268719122,90.00000001 +251.71,50.43283629,-2.564569178,49.4103,-3.83E-11,10.00014427,2.8584375,-4.45480633,3.236603577,90.00000001 +251.72,50.43283629,-2.56456777,49.3819,-1.55E-11,9.999478126,2.8328125,-4.373154287,3.201665699,90.00000001 +251.73,50.43283629,-2.564566363,49.3537,1.27E-11,9.999034016,2.8065625,-4.290588948,3.163935913,90.00000001 +251.74,50.43283629,-2.564564956,49.3257,2.27E-11,9.999478038,2.7778125,-4.207127619,3.123447105,90.00000001 +251.75,50.43283629,-2.564563548,49.2981,1.31E-11,10.00014409,2.7465625,-4.122787658,3.080234571,90.00000001 +251.76,50.43283629,-2.564562141,49.2708,2.34E-12,10.00036608,2.7153125,-4.037586714,3.034336068,90.00000001 +251.77,50.43283629,-2.564560733,49.2438,-3.75E-12,10.00036604,2.6846875,-3.951542548,2.985791589,90.00000001 +251.78,50.43283629,-2.564559326,49.2171,-1.08E-11,10.000366,2.653125,-3.864673151,2.934643417,90.00000001 +251.79,50.43283629,-2.564557918,49.1907,-1.88E-11,10.00036596,2.619375,-3.776996686,2.880936244,90.00000001 +251.8,50.43283629,-2.564556511,49.1647,-2.66E-11,10.00036592,2.583125,-3.688531429,2.824716823,90.00000001 +251.81,50.43283629,-2.564555103,49.139,-2.83E-11,10.00036588,2.5453125,-3.599295888,2.766034199,90.00000001 +251.82,50.43283629,-2.564553696,49.1138,-1.25E-11,10.00036584,2.508125,-3.509308684,2.704939538,90.00000001 +251.83,50.43283629,-2.564552288,49.0889,1.17E-11,10.0003658,2.4715625,-3.418588609,2.641486181,90.00000001 +251.84,50.43283629,-2.564550881,49.0643,2.20E-11,10.00014373,2.4325,-3.327154572,2.575729362,90.00000001 +251.85,50.43283629,-2.564549473,49.0402,2.20E-11,9.999477592,2.39,-3.235025709,2.507726491,90.00000001 +251.86,50.43283629,-2.564548066,49.0165,2.81E-11,9.999033488,2.346875,-3.142221271,2.437536812,90.00000001 +251.87,50.43283629,-2.564546659,48.9933,3.19E-11,9.999477517,2.3046875,-3.048760624,2.365221631,90.00000001 +251.88,50.43283629,-2.564545251,48.9704,1.80E-11,10.00014358,2.2615625,-2.954663307,2.290843917,90.00000001 +251.89,50.43283629,-2.564543844,48.948,-3.91E-12,10.00036558,2.21625,-2.859948857,2.214468528,90.00000001 +251.9,50.43283629,-2.564542436,48.9261,-1.39E-11,10.00036555,2.17,-2.764637214,2.1361621,90.00000001 +251.91,50.43283629,-2.564541029,48.9046,-7.03E-12,10.00036551,2.1234375,-2.6687482,2.055992871,90.00000001 +251.92,50.43283629,-2.564539621,48.8836,9.38E-12,10.00036548,2.07625,-2.572301871,1.974030858,90.00000001 +251.93,50.43283629,-2.564538214,48.8631,2.58E-11,10.00036545,2.0284375,-2.475318336,1.890347392,90.00000001 +251.94,50.43283629,-2.564536806,48.843,3.52E-11,10.00036542,1.9796875,-2.377817822,1.805015585,90.00000001 +251.95,50.43283629,-2.564535399,48.8235,3.50E-11,10.00014335,1.9296875,-2.279820782,1.718109747,90.00000001 +251.96,50.43283629,-2.564533991,48.8044,2.50E-11,9.999477222,1.8784375,-2.181347614,1.629705683,90.00000001 +251.97,50.43283629,-2.564532584,48.7859,7.81E-12,9.999033127,1.82625,-2.082418888,1.539880453,90.00000001 +251.98,50.43283629,-2.564531177,48.7679,-8.44E-12,9.999477166,1.7734375,-1.983055287,1.448712498,90.00000001 +251.99,50.43283629,-2.564529769,48.7504,-1.64E-11,10.00014324,1.7196875,-1.883277551,1.356281227,90.00000001 +252,50.43283629,-2.564528362,48.7335,-1.72E-11,10.00036524,1.665,-1.783106481,1.2626672,90.00000001 +252.01,50.43283629,-2.564526954,48.7171,-1.64E-11,10.00036522,1.61,-1.682563102,1.167952177,90.00000001 +252.02,50.43283629,-2.564525547,48.7013,-1.63E-11,10.00036519,1.555,-1.581668271,1.072218665,90.00000001 +252.03,50.43283629,-2.564524139,48.686,-1.86E-11,10.00036517,1.4996875,-1.480443187,0.975550142,90.00000001 +252.04,50.43283629,-2.564522732,48.6713,-2.56E-11,10.00014311,1.443125,-1.378908878,0.878030949,90.00000001 +252.05,50.43283629,-2.564521324,48.6571,-3.05E-11,9.999476992,1.385,-1.277086657,0.779746056,90.00000001 +252.06,50.43283629,-2.564519917,48.6436,-2.41E-11,9.999032905,1.3265625,-1.174997667,0.680781233,90.00000001 +252.07,50.43283629,-2.56451851,48.6306,-1.09E-11,9.999476951,1.2684375,-1.072663337,0.581222769,90.00000001 +252.08,50.43283629,-2.564517102,48.6182,-2.19E-12,10.00014303,1.2096875,-0.970104981,0.481157523,90.00000001 +252.09,50.43283629,-2.564515695,48.6064,1.67E-16,10.00036504,1.15,-0.867344026,0.380672643,90.00000001 +252.1,50.43283629,-2.564514287,48.5952,2.78E-16,10.00036503,1.09,-0.764401959,0.279855792,90.00000001 +252.11,50.43283629,-2.56451288,48.5846,2.78E-16,10.00014298,1.03,-0.661300267,0.178794918,90.00000001 +252.12,50.43283629,-2.564511472,48.5746,2.34E-12,9.999476864,0.9696875,-0.558060434,0.077578142,90.00000001 +252.13,50.43283629,-2.564510065,48.5652,9.38E-12,9.999032782,0.908125,-0.454704062,-0.023706243,90.00000001 +252.14,50.43283629,-2.564508658,48.5564,1.42E-11,9.999476834,0.845,-0.35125275,-0.124970002,90.00000001 +252.15,50.43283629,-2.56450725,48.5483,1.02E-11,10.00014292,0.781875,-0.2477281,-0.226124784,90.00000001 +252.16,50.43283629,-2.564505843,48.5408,6.25E-12,10.00036494,0.72,-0.144151712,-0.327082411,90.00000001 +252.17,50.43283629,-2.564504435,48.5339,1.08E-11,10.00036493,0.658125,-0.040545186,-0.427754763,90.00000001 +252.18,50.43283629,-2.564503028,48.5276,1.66E-11,10.00014289,0.5946875,0.063069819,-0.528054119,90.00000001 +252.19,50.43283629,-2.56450162,48.522,1.81E-11,9.999476781,0.53,0.166671589,-0.627893046,90.00000001 +252.2,50.43283629,-2.564500213,48.517,1.66E-11,9.999032707,0.4653125,0.270238638,-0.727184397,90.00000001 +252.21,50.43283629,-2.564498806,48.5127,8.44E-12,9.999476767,0.4015625,0.373749193,-0.825841656,90.00000001 +252.22,50.43283629,-2.564497398,48.509,-5.62E-12,10.00014286,0.3384375,0.477181712,-0.923778707,90.00000001 +252.23,50.43283629,-2.564495991,48.5059,-1.41E-11,10.00036489,0.275,0.580514535,-1.020910294,90.00000001 +252.24,50.43283629,-2.564494583,48.5035,-8.44E-12,10.00036488,0.2115625,0.683726179,-1.117151562,90.00000001 +252.25,50.43283629,-2.564493176,48.5017,3.13E-12,10.00014285,0.148125,0.786794983,-1.212418687,90.00000001 +252.26,50.43283629,-2.564491768,48.5005,3.91E-12,9.999476747,0.083125,0.889699521,-1.30662859,90.00000001 +252.27,50.43283629,-2.564490361,48.5,-5.00E-12,9.99903268,0.016875,0.992418249,-1.399699052,90.00000001 +252.28,50.43283629,-2.564488954,48.5002,-5.47E-12,9.999476747,-0.048125,1.094929738,-1.491549,90.00000001 +252.29,50.43283629,-2.564487546,48.501,5.47E-12,10.00014285,-0.1115625,1.197212559,-1.582098276,90.00000001 +252.3,50.43283629,-2.564486139,48.5024,1.48E-11,10.00036488,-0.1753125,1.299245341,-1.671267926,90.00000001 +252.31,50.43283629,-2.564484731,48.5045,1.78E-11,10.00036489,-0.24,1.401006771,-1.758980202,90.00000001 +252.32,50.43283629,-2.564483324,48.5072,1.55E-11,10.00036489,-0.3046875,1.502475649,-1.845158669,90.00000001 +252.33,50.43283629,-2.564481916,48.5106,5.31E-12,10.00036489,-0.3684375,1.603630774,-1.929728099,90.00000001 +252.34,50.43283629,-2.564480509,48.5146,-9.37E-12,10.0003649,-0.4315625,1.704450949,-2.012614752,90.00000001 +252.35,50.43283629,-2.564479101,48.5192,-1.89E-11,10.00036491,-0.4953125,1.804915202,-2.093746378,90.00000001 +252.36,50.43283629,-2.564477694,48.5245,-2.34E-11,10.00014288,-0.5596875,1.905002507,-2.173052274,90.00000001 +252.37,50.43283629,-2.564476286,48.5304,-2.97E-11,9.999476794,-0.623125,2.004692006,-2.250463169,90.00000001 +252.38,50.43283629,-2.564474879,48.537,-3.05E-11,9.999032738,-0.6853125,2.103962846,-2.325911684,90.00000001 +252.39,50.43283629,-2.564473472,48.5441,-1.27E-11,9.999476816,-0.748125,2.202794284,-2.399331928,90.00000001 +252.4,50.43283629,-2.564472064,48.5519,1.56E-11,10.00014293,-0.811875,2.301165694,-2.47065996,90.00000001 +252.41,50.43283629,-2.564470657,48.5604,3.36E-11,10.00036497,-0.874375,2.399056508,-2.539833498,90.00000001 +252.42,50.43283629,-2.564469249,48.5694,3.77E-11,10.00036499,-0.935,2.496446384,-2.606792326,90.00000001 +252.43,50.43283629,-2.564467842,48.5791,3.52E-11,10.000365,-0.9953125,2.593314869,-2.671477943,90.00000001 +252.44,50.43283629,-2.564466434,48.5893,2.34E-11,10.00036502,-1.05625,2.689641736,-2.733833971,90.00000001 +252.45,50.43283629,-2.564465027,48.6002,-1.56E-13,10.00036504,-1.116875,2.785406934,-2.793806094,90.00000001 +252.46,50.43283629,-2.564463619,48.6117,-2.19E-11,10.00036505,-1.1765625,2.880590464,-2.851341943,90.00000001 +252.47,50.43283629,-2.564462212,48.6237,-2.27E-11,10.00014304,-1.2365625,2.975172389,-2.906391441,90.00000001 +252.48,50.43283629,-2.564460804,48.6364,-3.75E-12,9.99947696,-1.2965625,3.069132998,-2.958906461,90.00000001 +252.49,50.43283629,-2.564459397,48.6497,1.17E-11,9.999032914,-1.3546875,3.16245264,-3.00884128,90.00000001 +252.5,50.43283629,-2.56445799,48.6635,8.59E-12,9.999477002,-1.4115625,3.25511189,-3.056152353,90.00000001 +252.51,50.43283629,-2.564456582,48.6779,-4.69E-12,10.00014312,-1.4684375,3.347091326,-3.100798427,90.00000001 +252.52,50.43283629,-2.564455175,48.6929,-1.39E-11,10.00036518,-1.5246875,3.438371753,-3.142740542,90.00000001 +252.53,50.43283629,-2.564453767,48.7084,-1.64E-11,10.0003652,-1.58,3.52893415,-3.1819422,90.00000001 +252.54,50.43283629,-2.56445236,48.7245,-1.72E-11,10.00036523,-1.635,3.618759551,-3.218369081,90.00000001 +252.55,50.43283629,-2.564450952,48.7411,-1.88E-11,10.00036526,-1.69,3.707829221,-3.251989556,90.00000001 +252.56,50.43283629,-2.564449545,48.7583,-2.25E-11,10.00036528,-1.7446875,3.796124538,-3.282774178,90.00000001 +252.57,50.43283629,-2.564448137,48.776,-2.97E-11,10.00036531,-1.798125,3.883627111,-3.310696245,90.00000001 +252.58,50.43283629,-2.56444673,48.7943,-3.36E-11,10.00036534,-1.85,3.970318604,-3.335731292,90.00000001 +252.59,50.43283629,-2.564445322,48.813,-2.36E-11,10.00036537,-1.90125,4.056180971,-3.357857547,90.00000001 +252.6,50.43283629,-2.564443915,48.8323,1.94E-16,10.00014337,-1.951875,4.141196277,-3.377055643,90.00000001 +252.61,50.43283629,-2.564442507,48.8521,2.34E-11,9.999477297,-2.00125,4.22534676,-3.393308966,90.00000001 +252.62,50.43283629,-2.5644411,48.8723,3.28E-11,9.999033262,-2.05,4.308614774,-3.406603249,90.00000001 +252.63,50.43283629,-2.564439693,48.8931,2.58E-11,9.999477361,-2.0984375,4.390983014,-3.416926917,90.00000001 +252.64,50.43283629,-2.564438285,48.9143,9.38E-12,10.00014349,-2.14625,4.472434293,-3.424270975,90.00000001 +252.65,50.43283629,-2.564436878,48.936,-4.84E-12,10.00036556,-2.193125,4.552951479,-3.428629064,90.00000001 +252.66,50.43283629,-2.56443547,48.9582,-5.47E-12,10.0003656,-2.238125,4.632517899,-3.429997287,90.00000001 +252.67,50.43283629,-2.564434063,48.9808,7.81E-12,10.00036563,-2.28125,4.71111688,-3.428374499,90.00000001 +252.68,50.43283629,-2.564432655,49.0038,2.44E-11,10.00036567,-2.3234375,4.788731977,-3.423762132,90.00000001 +252.69,50.43283629,-2.564431248,49.0273,3.28E-11,10.0003657,-2.365,4.865347034,-3.416164195,90.00000001 +252.7,50.43283629,-2.56442984,49.0511,2.73E-11,10.00036574,-2.4065625,4.940946008,-3.405587337,90.00000001 +252.71,50.43283629,-2.564428433,49.0754,1.64E-11,10.00036578,-2.448125,5.015513142,-3.392040724,90.00000001 +252.72,50.43283629,-2.564427025,49.1001,1.66E-11,10.00036582,-2.488125,5.089032851,-3.375536217,90.00000001 +252.73,50.43283629,-2.564425618,49.1252,3.06E-11,10.00014382,-2.52625,5.161489724,-3.356088196,90.00000001 +252.74,50.43283629,-2.56442421,49.1506,4.47E-11,9.999477764,-2.563125,5.232868749,-3.333713563,90.00000001 +252.75,50.43283629,-2.564422803,49.1765,4.23E-11,9.999033738,-2.5984375,5.303154972,-3.308431973,90.00000001 +252.76,50.43283629,-2.564421396,49.2026,2.12E-11,9.999477845,-2.633125,5.372333667,-3.28026531,90.00000001 +252.77,50.43283629,-2.564419988,49.2291,2.34E-12,10.00014399,-2.668125,5.440390396,-3.249238213,90.00000001 +252.78,50.43283629,-2.564418581,49.256,6.25E-12,10.00036606,-2.70125,5.507311007,-3.215377782,90.00000001 +252.79,50.43283629,-2.564417173,49.2832,2.11E-11,10.0003661,-2.7315625,5.573081462,-3.178713411,90.00000001 +252.8,50.43283629,-2.564415766,49.3106,1.97E-11,10.00036615,-2.7615625,5.637688069,-3.139277242,90.00000001 +252.81,50.43283629,-2.564414358,49.3384,7.82E-13,10.00036619,-2.7915625,5.701117304,-3.097103537,90.00000001 +252.82,50.43283629,-2.564412951,49.3665,-1.48E-11,10.0001442,-2.819375,5.763355933,-3.052229082,90.00000001 +252.83,50.43283629,-2.564411543,49.3948,-1.87E-11,9.999478146,-2.845,5.82439095,-3.004693065,90.00000001 +252.84,50.43283629,-2.564410136,49.4234,-1.80E-11,9.999034125,-2.87,5.884209635,-2.954536913,90.00000001 +252.85,50.43283629,-2.564408729,49.4522,-1.48E-11,9.999478236,-2.8946875,5.942799497,-2.901804398,90.00000001 +252.86,50.43283629,-2.564407321,49.4813,-7.81E-12,10.00014438,-2.918125,6.000148275,-2.846541416,90.00000001 +252.87,50.43283629,-2.564405914,49.5106,7.81E-13,10.00036646,-2.939375,6.056243937,-2.788796208,90.00000001 +252.88,50.43283629,-2.564404506,49.5401,1.19E-11,10.00036651,-2.9584375,6.111074909,-2.728619139,90.00000001 +252.89,50.43283629,-2.564403099,49.5698,2.58E-11,10.00014452,-2.9765625,6.164629618,-2.66606269,90.00000001 +252.9,50.43283629,-2.564401691,49.5996,3.28E-11,9.999478466,-2.995,6.216896948,-2.60118135,90.00000001 +252.91,50.43283629,-2.564400284,49.6297,2.81E-11,9.999034447,-3.013125,6.267865898,-2.534031785,90.00000001 +252.92,50.43283629,-2.564398877,49.6599,1.87E-11,9.999478561,-3.029375,6.317525984,-2.464672494,90.00000001 +252.93,50.43283629,-2.564397469,49.6903,9.37E-12,10.00014471,-3.043125,6.365866662,-2.393163981,90.00000001 +252.94,50.43283629,-2.564396062,49.7208,2.34E-12,10.00036679,-3.0546875,6.412877907,-2.319568583,90.00000001 +252.95,50.43283629,-2.564394654,49.7514,-2.22E-16,10.00036684,-3.065,6.45854992,-2.243950473,90.00000001 +252.96,50.43283629,-2.564393247,49.7821,-1.94E-16,10.00014485,-3.075,6.50287319,-2.166375654,90.00000001 +252.97,50.43283629,-2.564391839,49.8129,2.34E-12,9.9994788,-3.0846875,6.545838378,-2.086911679,90.00000001 +252.98,50.43283629,-2.564390432,49.8438,9.38E-12,9.999034782,-3.093125,6.587436546,-2.005627876,90.00000001 +252.99,50.43283629,-2.564389025,49.8748,1.64E-11,9.999478897,-3.0996875,6.627659043,-1.922595176,90.00000001 +253,50.43283629,-2.564387617,49.9058,1.64E-11,10.00014504,-3.1046875,6.666497388,-1.837885887,90.00000001 +253.01,50.43283629,-2.56438621,49.9369,9.37E-12,10.00036713,-3.108125,6.703943561,-1.751573978,90.00000001 +253.02,50.43283629,-2.564384802,49.968,-2.50E-16,10.00036717,-3.109375,6.739989711,-1.663734677,90.00000001 +253.03,50.43283629,-2.564383395,49.9991,-1.17E-11,10.00014519,-3.1084375,6.774628275,-1.574444534,90.00000001 +253.04,50.43283629,-2.564381987,50.0302,-2.58E-11,9.99947914,-3.1065625,6.807852035,-1.483781525,90.00000001 +253.05,50.43283629,-2.56438058,50.0612,-3.28E-11,9.999035123,-3.105,6.839654057,-1.39182455,90.00000001 +253.06,50.43283629,-2.564379173,50.0923,-2.80E-11,9.999479237,-3.103125,6.870027753,-1.298653934,90.00000001 +253.07,50.43283629,-2.564377765,50.1233,-1.80E-11,10.00014538,-3.099375,6.898966706,-1.204350868,90.00000001 +253.08,50.43283629,-2.564376358,50.1543,-7.81E-12,10.00036747,-3.093125,6.926464898,-1.10899757,90.00000001 +253.09,50.43283629,-2.56437495,50.1852,-3.13E-12,10.00036751,-3.085,6.952516602,-1.012677234,90.00000001 +253.1,50.43283629,-2.564373543,50.216,-1.09E-11,10.00036756,-3.0765625,6.977116315,-0.915473799,90.00000001 +253.11,50.43283629,-2.564372135,50.2467,-2.09E-11,10.00036761,-3.0678125,7.000258998,-0.817472118,90.00000001 +253.12,50.43283629,-2.564370728,50.2774,-1.19E-11,10.00014563,-3.0565625,7.021939721,-0.718757506,90.00000001 +253.13,50.43283629,-2.56436932,50.3079,1.56E-11,9.999479575,-3.0428125,7.042154015,-0.619416193,90.00000001 +253.14,50.43283629,-2.564367913,50.3382,3.83E-11,9.999035556,-3.0284375,7.060897699,-0.519534695,90.00000001 +253.15,50.43283629,-2.564366506,50.3685,4.06E-11,9.999479669,-3.013125,7.078166762,-0.419200216,90.00000001 +253.16,50.43283629,-2.564365098,50.3985,2.97E-11,10.00014582,-2.9965625,7.093957593,-0.318500134,90.00000001 +253.17,50.43283629,-2.564363691,50.4284,2.33E-11,10.0003679,-2.98,7.108267042,-0.217522338,90.00000001 +253.18,50.43283629,-2.564362283,50.4581,2.34E-11,10.00036794,-2.9625,7.121091958,-0.116354837,90.00000001 +253.19,50.43283629,-2.564360876,50.4877,1.17E-11,10.00036799,-2.9415625,7.132429704,-0.015085864,90.00000001 +253.2,50.43283629,-2.564359468,50.517,-1.41E-11,10.00036803,-2.918125,7.142277989,0.086196229,90.00000001 +253.21,50.43283629,-2.564358061,50.546,-2.80E-11,10.00036808,-2.895,7.150634693,0.18740315,90.00000001 +253.22,50.43283629,-2.564356653,50.5749,-1.56E-11,10.00036812,-2.8715625,7.15749804,0.288446721,90.00000001 +253.23,50.43283629,-2.564355246,50.6035,6.25E-12,10.00036817,-2.84625,7.162866654,0.389238706,90.00000001 +253.24,50.43283629,-2.564353838,50.6318,1.55E-11,10.00036821,-2.82,7.166739391,0.489691271,90.00000001 +253.25,50.43283629,-2.564352431,50.6599,9.38E-12,10.00014622,-2.793125,7.169115447,0.589716811,90.00000001 +253.26,50.43283629,-2.564351023,50.6877,-1.41E-12,9.999480169,-2.764375,7.169994364,0.68922812,90.00000001 +253.27,50.43283629,-2.564349616,50.7152,-1.31E-11,9.999036145,-2.7334375,7.169375856,0.788138398,90.00000001 +253.28,50.43283629,-2.564348209,50.7424,-2.58E-11,9.999480253,-2.7015625,7.167260152,0.886361469,90.00000001 +253.29,50.43283629,-2.564346801,50.7692,-2.89E-11,10.00014639,-2.6696875,7.163647653,0.983811563,90.00000001 +253.3,50.43283629,-2.564345394,50.7958,-1.41E-11,10.00036847,-2.6365625,7.158539104,1.080403768,90.00000001 +253.31,50.43283629,-2.564343986,50.822,7.19E-12,10.00036851,-2.60125,7.151935594,1.176053858,90.00000001 +253.32,50.43283629,-2.564342579,50.8478,1.66E-11,10.00036855,-2.565,7.143838497,1.270678411,90.00000001 +253.33,50.43283629,-2.564341171,50.8733,1.19E-11,10.00036859,-2.528125,7.134249532,1.364194863,90.00000001 +253.34,50.43283629,-2.564339764,50.8984,4.84E-12,10.00036863,-2.4896875,7.123170649,1.456521798,90.00000001 +253.35,50.43283629,-2.564338356,50.9231,2.50E-12,10.00036867,-2.45,7.110604137,1.547578543,90.00000001 +253.36,50.43283629,-2.564336949,50.9474,2.34E-12,10.00014667,-2.41,7.096552691,1.637285857,90.00000001 +253.37,50.43283629,-2.564335541,50.9713,4.06E-12,9.999480611,-2.3696875,7.081019232,1.725565361,90.00000001 +253.38,50.43283629,-2.564334134,50.9948,1.03E-11,9.999036582,-2.328125,7.064007027,1.812340162,90.00000001 +253.39,50.43283629,-2.564332727,51.0179,1.73E-11,9.999480685,-2.2846875,7.045519569,1.897534632,90.00000001 +253.4,50.43283629,-2.564331319,51.0405,1.80E-11,10.00014682,-2.2396875,7.025560699,1.9810744,90.00000001 +253.41,50.43283629,-2.564329912,51.0627,8.59E-12,10.00036889,-2.1934375,7.004134713,2.062886585,90.00000001 +253.42,50.43283629,-2.564328504,51.0844,-6.25E-12,10.00036892,-2.1465625,6.981245966,2.142899969,90.00000001 +253.43,50.43283629,-2.564327097,51.1056,-1.39E-11,10.00036895,-2.1,6.956899271,2.221044651,90.00000001 +253.44,50.43283629,-2.564325689,51.1264,-9.38E-12,10.00036899,-2.053125,6.931099669,2.297252622,90.00000001 +253.45,50.43283629,-2.564324282,51.1467,-2.19E-12,10.00036902,-2.0046875,6.903852661,2.371457303,90.00000001 +253.46,50.43283629,-2.564322874,51.1665,7.81E-13,10.00036905,-1.955,6.875163862,2.443594064,90.00000001 +253.47,50.43283629,-2.564321467,51.1858,3.91E-12,10.00036908,-1.9046875,6.84503923,2.513599938,90.00000001 +253.48,50.43283629,-2.564320059,51.2046,1.09E-11,10.00036911,-1.853125,6.813485127,2.581413962,90.00000001 +253.49,50.43283629,-2.564318652,51.2229,1.50E-11,10.0001471,-1.8,6.78050814,2.64697695,90.00000001 +253.5,50.43283629,-2.564317244,51.2406,7.97E-12,9.999481033,-1.7465625,6.746115088,2.71023172,90.00000001 +253.51,50.43283629,-2.564315837,51.2578,-5.31E-12,9.999036994,-1.6934375,6.710313247,2.771123096,90.00000001 +253.52,50.43283629,-2.56431443,51.2745,-1.41E-11,9.999481087,-1.6396875,6.673110009,2.829598022,90.00000001 +253.53,50.43283629,-2.564313022,51.2906,-1.63E-11,10.00014721,-1.585,6.634513165,2.885605564,90.00000001 +253.54,50.43283629,-2.564311615,51.3062,-1.86E-11,10.00036927,-1.5296875,6.594530852,2.939096732,90.00000001 +253.55,50.43283629,-2.564310207,51.3212,-2.56E-11,10.00036929,-1.473125,6.553171264,2.990025002,90.00000001 +253.56,50.43283629,-2.5643088,51.3357,-3.05E-11,10.00036931,-1.415,6.510443223,3.038345913,90.00000001 +253.57,50.43283629,-2.564307392,51.3495,-2.41E-11,10.00036934,-1.3565625,6.466355495,3.084017353,90.00000001 +253.58,50.43283629,-2.564305985,51.3628,-1.08E-11,10.00036936,-1.2984375,6.420917364,3.126999501,90.00000001 +253.59,50.43283629,-2.564304577,51.3755,-1.41E-12,10.00036938,-1.2396875,6.374138282,3.167254828,90.00000001 +253.6,50.43283629,-2.56430317,51.3876,1.56E-12,10.00014736,-1.18,6.326028105,3.204748269,90.00000001 +253.61,50.43283629,-2.564301762,51.3991,1.56E-12,9.999481282,-1.12,6.276596801,3.239447109,90.00000001 +253.62,50.43283629,-2.564300355,51.41,6.25E-13,9.999037233,-1.06,6.225854685,3.271321152,90.00000001 +253.63,50.43283629,-2.564298948,51.4203,-6.25E-13,9.999481314,-1,6.173812355,3.300342496,90.00000001 +253.64,50.43283629,-2.56429754,51.43,-3.91E-12,10.00014743,-0.9396875,6.120480756,3.32648593,90.00000001 +253.65,50.43283629,-2.564296133,51.4391,-1.09E-11,10.00036948,-0.878125,6.065870945,3.349728593,90.00000001 +253.66,50.43283629,-2.564294725,51.4476,-1.50E-11,10.00036949,-0.815,6.009994382,3.37005026,90.00000001 +253.67,50.43283629,-2.564293318,51.4554,-1.03E-11,10.00014747,-0.751875,5.952862698,3.387433227,90.00000001 +253.68,50.43283629,-2.56429191,51.4626,-6.25E-12,9.99948138,-0.69,5.89448781,3.401862252,90.00000001 +253.69,50.43283629,-2.564290503,51.4692,-1.08E-11,9.999037325,-0.628125,5.834881922,3.413324789,90.00000001 +253.7,50.43283629,-2.564289096,51.4752,-1.66E-11,9.999481401,-0.5646875,5.774057524,3.421810924,90.00000001 +253.71,50.43283629,-2.564287688,51.4805,-1.81E-11,10.00014751,-0.5,5.71202728,3.427313095,90.00000001 +253.72,50.43283629,-2.564286281,51.4852,-1.66E-11,10.00036955,-0.4353125,5.648804195,3.429826661,90.00000001 +253.73,50.43283629,-2.564284873,51.4892,-8.44E-12,10.00036955,-0.3715625,5.58440139,3.429349387,90.00000001 +253.74,50.43283629,-2.564283466,51.4926,5.47E-12,10.00014753,-0.3084375,5.518832329,3.425881617,90.00000001 +253.75,50.43283629,-2.564282058,51.4954,1.56E-11,9.999481432,-0.2446875,5.452110763,3.419426445,90.00000001 +253.76,50.43283629,-2.564280651,51.4975,1.86E-11,9.999037369,-0.18,5.384250616,3.409989487,90.00000001 +253.77,50.43283629,-2.564279244,51.499,1.87E-11,9.999481437,-0.115,5.315265982,3.397578992,90.00000001 +253.78,50.43283629,-2.564277836,51.4998,1.87E-11,10.00014754,-0.05,5.245171356,3.382205732,90.00000001 +253.79,50.43283629,-2.564276429,51.5,1.64E-11,10.00036957,0.0146875,5.17398135,3.363883114,90.00000001 +253.8,50.43283629,-2.564275021,51.4995,7.03E-12,10.00036957,0.0784375,5.101710803,3.342627182,90.00000001 +253.81,50.43283629,-2.564273614,51.4984,-4.69E-12,10.00014754,0.141875,5.028374841,3.318456385,90.00000001 +253.82,50.43283629,-2.564272206,51.4967,-2.50E-12,9.999481433,0.2065625,4.953988762,3.291391864,90.00000001 +253.83,50.43283629,-2.564270799,51.4943,1.56E-11,9.999037364,0.2715625,4.878568093,3.261457226,90.00000001 +253.84,50.43283629,-2.564269392,51.4912,2.64E-11,9.999481425,0.335,4.802128647,3.228678539,90.00000001 +253.85,50.43283629,-2.564267984,51.4876,1.41E-11,10.00014752,0.3984375,4.724686297,3.193084396,90.00000001 +253.86,50.43283629,-2.564266577,51.4833,-4.84E-12,10.00036955,0.4634375,4.646257255,3.154705792,90.00000001 +253.87,50.43283629,-2.564265169,51.4783,-7.03E-12,10.00036954,0.528125,4.56685791,3.113576303,90.00000001 +253.88,50.43283629,-2.564263762,51.4727,7.81E-12,10.0001475,0.59125,4.486504819,3.069731682,90.00000001 +253.89,50.43283629,-2.564262354,51.4665,2.58E-11,9.999481386,0.6534375,4.405214828,3.023210259,90.00000001 +253.9,50.43283629,-2.564260947,51.4596,3.19E-11,9.999037309,0.7153125,4.323004838,2.974052486,90.00000001 +253.91,50.43283629,-2.56425954,51.4522,1.56E-11,9.999481364,0.778125,4.239892038,2.922301333,90.00000001 +253.92,50.43283629,-2.564258132,51.4441,-1.33E-11,10.00014745,0.841875,4.15589379,2.868001894,90.00000001 +253.93,50.43283629,-2.564256725,51.4353,-3.27E-11,10.00036947,0.904375,4.071027625,2.811201494,90.00000001 +253.94,50.43283629,-2.564255317,51.426,-3.75E-11,10.00036946,0.965,3.985311306,2.751949693,90.00000001 +253.95,50.43283629,-2.56425391,51.416,-3.75E-11,10.00036944,1.025,3.89876265,2.690298174,90.00000001 +253.96,50.43283629,-2.564252502,51.4055,-3.75E-11,10.00036942,1.085,3.811399822,2.626300679,90.00000001 +253.97,50.43283629,-2.564251095,51.3943,-3.50E-11,10.00036941,1.1453125,3.72324104,2.560012957,90.00000001 +253.98,50.43283629,-2.564249687,51.3826,-2.27E-11,10.00036939,1.20625,3.634304698,2.491492935,90.00000001 +253.99,50.43283629,-2.56424828,51.3702,-7.81E-13,10.00036937,1.2665625,3.544609416,2.420800199,90.00000001 +254,50.43283629,-2.564246872,51.3572,1.31E-11,10.00036935,1.3246875,3.454173872,2.347996572,90.00000001 +254.01,50.43283629,-2.564245465,51.3437,7.03E-12,10.00014729,1.3815625,3.363016917,2.273145423,90.00000001 +254.02,50.43283629,-2.564244057,51.3296,-8.59E-12,9.999481172,1.4384375,3.271157688,2.196312069,90.00000001 +254.03,50.43283629,-2.56424265,51.3149,-1.64E-11,9.999037083,1.495,3.178615321,2.117563489,90.00000001 +254.04,50.43283629,-2.564241243,51.2997,-9.53E-12,9.999481126,1.5515625,3.085409125,2.036968381,90.00000001 +254.05,50.43283629,-2.564239835,51.2839,2.34E-12,10.0001472,1.608125,2.991558581,1.954596989,90.00000001 +254.06,50.43283629,-2.564238428,51.2675,3.13E-12,10.00036921,1.663125,2.897083283,1.870521162,90.00000001 +254.07,50.43283629,-2.56423702,51.2506,-7.03E-12,10.00036918,1.7165625,2.802002943,1.784814239,90.00000001 +254.08,50.43283629,-2.564235613,51.2332,-1.27E-11,10.00036915,1.77,2.706337497,1.697550876,90.00000001 +254.09,50.43283629,-2.564234205,51.2152,-7.81E-12,10.00036913,1.823125,2.610106829,1.608807276,90.00000001 +254.1,50.43283629,-2.564232798,51.1967,-1.56E-12,10.0003691,1.8746875,2.513331049,1.518660732,90.00000001 +254.11,50.43283629,-2.56423139,51.1777,1.56E-13,10.00036907,1.925,2.41603044,1.427189911,90.00000001 +254.12,50.43283629,-2.564229983,51.1582,-1.94E-16,10.00036904,1.975,2.318225283,1.334474568,90.00000001 +254.13,50.43283629,-2.564228575,51.1382,-8.33E-17,10.00036901,2.025,2.219935978,1.240595548,90.00000001 +254.14,50.43283629,-2.564227168,51.1177,2.34E-12,10.00014694,2.0746875,2.121183035,1.145634669,90.00000001 +254.15,50.43283629,-2.56422576,51.0967,9.53E-12,9.999480808,2.123125,2.021987139,1.049674838,90.00000001 +254.16,50.43283629,-2.564224353,51.0752,1.72E-11,9.999036708,2.1696875,1.922368972,0.952799592,90.00000001 +254.17,50.43283629,-2.564222946,51.0533,1.80E-11,9.99948074,2.2146875,1.822349334,0.855093558,90.00000001 +254.18,50.43283629,-2.564221538,51.0309,8.59E-12,10.0001468,2.2584375,1.721949137,0.756641876,90.00000001 +254.19,50.43283629,-2.564220131,51.0081,-6.09E-12,10.0003688,2.3015625,1.621189353,0.657530376,90.00000001 +254.2,50.43283629,-2.564218723,50.9849,-1.31E-11,10.00036876,2.345,1.52009095,0.55784546,90.00000001 +254.21,50.43283629,-2.564217316,50.9612,-1.00E-11,10.00036873,2.3878125,1.418675128,0.45767416,90.00000001 +254.22,50.43283629,-2.564215908,50.9371,-1.17E-11,10.00036869,2.428125,1.31696303,0.357103738,90.00000001 +254.23,50.43283629,-2.564214501,50.9126,-2.33E-11,10.00036865,2.4665625,1.214975912,0.256221856,90.00000001 +254.24,50.43283629,-2.564213093,50.8878,-3.03E-11,10.00036861,2.505,1.112735089,0.155116635,90.00000001 +254.25,50.43283629,-2.564211686,50.8625,-2.56E-11,10.00036857,2.543125,1.010261816,0.053876081,90.00000001 +254.26,50.43283629,-2.564210278,50.8369,-1.86E-11,10.00036853,2.5796875,0.907577638,-0.047411398,90.00000001 +254.27,50.43283629,-2.564208871,50.8109,-1.62E-11,10.00014646,2.615,0.804703868,-0.148657567,90.00000001 +254.28,50.43283629,-2.564207463,50.7846,-1.41E-11,9.99948032,2.6496875,0.701662049,-0.249774075,90.00000001 +254.29,50.43283629,-2.564206056,50.7579,-5.47E-12,9.999036212,2.6834375,0.598473726,-0.350672802,90.00000001 +254.3,50.43283629,-2.564204649,50.7309,9.38E-12,9.999480236,2.71625,0.495160382,-0.451265742,90.00000001 +254.31,50.43283629,-2.564203241,50.7036,2.20E-11,10.00014629,2.748125,0.391743678,-0.551465174,90.00000001 +254.32,50.43283629,-2.564201834,50.6759,2.42E-11,10.00036828,2.7778125,0.288245097,-0.651183723,90.00000001 +254.33,50.43283629,-2.564200426,50.648,2.02E-11,10.00036824,2.8046875,0.184686356,-0.750334413,90.00000001 +254.34,50.43283629,-2.564199019,50.6198,1.55E-11,10.00036819,2.8303125,0.081089055,-0.848830786,90.00000001 +254.35,50.43283629,-2.564197611,50.5914,3.12E-12,10.00036815,2.85625,-0.022525205,-0.946587011,90.00000001 +254.36,50.43283629,-2.564196204,50.5627,-1.80E-11,10.0003681,2.8815625,-0.126134711,-1.043517719,90.00000001 +254.37,50.43283629,-2.564194796,50.5337,-3.13E-11,10.00036806,2.9046875,-0.229717917,-1.13953857,90.00000001 +254.38,50.43283629,-2.564193389,50.5046,-2.59E-11,10.00014598,2.9265625,-0.333253167,-1.234565626,90.00000001 +254.39,50.43283629,-2.564191981,50.4752,-1.17E-11,9.999479837,2.9484375,-0.436718745,-1.328516208,90.00000001 +254.4,50.43283629,-2.564190574,50.4456,-4.44E-16,9.999035724,2.969375,-0.540093222,-1.42130827,90.00000001 +254.41,50.43283629,-2.564189167,50.4158,9.37E-12,9.999479743,2.988125,-0.643354828,-1.51286091,90.00000001 +254.42,50.43283629,-2.564187759,50.3858,1.41E-11,10.0001458,3.005,-0.746482131,-1.603094314,90.00000001 +254.43,50.43283629,-2.564186352,50.3557,4.69E-12,10.00036778,3.02125,-0.849453476,-1.691929816,90.00000001 +254.44,50.43283629,-2.564184944,50.3254,-1.64E-11,10.00036773,3.0365625,-0.95224749,-1.779289894,90.00000001 +254.45,50.43283629,-2.564183537,50.2949,-3.28E-11,10.00014565,3.049375,-1.054842574,-1.86509846,90.00000001 +254.46,50.43283629,-2.564182129,50.2644,-3.75E-11,9.999479506,3.06,-1.157217412,-1.949280628,90.00000001 +254.47,50.43283629,-2.564180722,50.2337,-3.75E-11,9.999035392,3.07,-1.259350577,-2.031762944,90.00000001 +254.48,50.43283629,-2.564179315,50.203,-3.52E-11,9.999479411,3.0796875,-1.361220754,-2.112473561,90.00000001 +254.49,50.43283629,-2.564177907,50.1721,-2.58E-11,10.00014546,3.0884375,-1.462806629,-2.191342061,90.00000001 +254.5,50.43283629,-2.5641765,50.1412,-7.03E-12,10.00036745,3.0959375,-1.564087061,-2.268299689,90.00000001 +254.51,50.43283629,-2.564175092,50.1102,1.64E-11,10.0003674,3.1015625,-1.665040792,-2.343279353,90.00000001 +254.52,50.43283629,-2.564173685,50.0791,3.05E-11,10.00014532,3.1046875,-1.765646852,-2.41621562,90.00000001 +254.53,50.43283629,-2.564172277,50.0481,2.58E-11,9.999479168,3.1065625,-1.865884157,-2.487044891,90.00000001 +254.54,50.43283629,-2.56417087,50.017,1.17E-11,9.999035053,3.1084375,-1.965731793,-2.555705403,90.00000001 +254.55,50.43283629,-2.564169463,49.9859,2.34E-12,9.99947907,3.1096875,-2.065168905,-2.622137339,90.00000001 +254.56,50.43283629,-2.564168055,49.9548,4.69E-12,10.00014512,3.109375,-2.164174751,-2.686282714,90.00000001 +254.57,50.43283629,-2.564166648,49.9237,2.11E-11,10.00036711,3.1065625,-2.262728591,-2.748085666,90.00000001 +254.58,50.43283629,-2.56416524,49.8926,4.22E-11,10.00036706,3.10125,-2.360809971,-2.807492165,90.00000001 +254.59,50.43283629,-2.564163833,49.8617,5.16E-11,10.00014498,3.095,-2.458398262,-2.864450529,90.00000001 +254.6,50.43283629,-2.564162425,49.8307,4.45E-11,9.999478828,3.0884375,-2.555473184,-2.918911085,90.00000001 +254.61,50.43283629,-2.564161018,49.7999,2.81E-11,9.999034714,3.08125,-2.652014395,-2.970826275,90.00000001 +254.62,50.43283629,-2.564159611,49.7691,1.41E-11,9.999478732,3.073125,-2.748001785,-3.020150836,90.00000001 +254.63,50.43283629,-2.564158203,49.7384,1.17E-11,10.00014478,3.0628125,-2.843415301,-3.066841797,90.00000001 +254.64,50.43283629,-2.564156796,49.7078,1.41E-11,10.00036677,3.05,-2.938235003,-3.11085842,90.00000001 +254.65,50.43283629,-2.564155388,49.6774,7.03E-12,10.00036672,3.0365625,-3.032441067,-3.152162375,90.00000001 +254.66,50.43283629,-2.564153981,49.6471,-4.69E-12,10.00036667,3.023125,-3.126013842,-3.190717564,90.00000001 +254.67,50.43283629,-2.564152573,49.6169,-7.03E-12,10.00036663,3.0078125,-3.218933845,-3.226490356,90.00000001 +254.68,50.43283629,-2.564151166,49.5869,-2.34E-12,10.00014455,2.9896875,-3.31118154,-3.259449639,90.00000001 +254.69,50.43283629,-2.564149758,49.5571,4.44E-16,9.9994784,2.97,-3.402737789,-3.28956665,90.00000001 +254.7,50.43283629,-2.564148351,49.5275,4.44E-16,9.999034288,2.95,-3.493583399,-3.31681509,90.00000001 +254.71,50.43283629,-2.564146944,49.4981,-2.50E-12,9.999478308,2.9296875,-3.583699404,-3.341171239,90.00000001 +254.72,50.43283629,-2.564145536,49.4689,-1.02E-11,10.00014436,2.908125,-3.673067069,-3.362613841,90.00000001 +254.73,50.43283629,-2.564144129,49.4399,-1.80E-11,10.00036635,2.8846875,-3.761667601,-3.381124159,90.00000001 +254.74,50.43283629,-2.564142721,49.4112,-1.80E-11,10.0003663,2.8596875,-3.84948255,-3.396686094,90.00000001 +254.75,50.43283629,-2.564141314,49.3827,-7.97E-12,10.00036626,2.8334375,-3.936493583,-3.409286066,90.00000001 +254.76,50.43283629,-2.564139906,49.3545,8.44E-12,10.00036621,2.80625,-4.022682592,-3.418913132,90.00000001 +254.77,50.43283629,-2.564138499,49.3266,2.19E-11,10.00014414,2.778125,-4.108031474,-3.425558813,90.00000001 +254.78,50.43283629,-2.564137091,49.2989,2.20E-11,9.999477996,2.748125,-4.192522409,-3.429217377,90.00000001 +254.79,50.43283629,-2.564135684,49.2716,1.17E-11,9.999033888,2.7165625,-4.276137864,-3.429885561,90.00000001 +254.8,50.43283629,-2.564134277,49.2446,6.25E-12,9.999477911,2.685,-4.35886025,-3.427562904,90.00000001 +254.81,50.43283629,-2.564132869,49.2179,1.17E-11,10.00014397,2.653125,-4.440672321,-3.422251299,90.00000001 +254.82,50.43283629,-2.564131462,49.1915,1.89E-11,10.00036596,2.6196875,-4.521557059,-3.4139555,90.00000001 +254.83,50.43283629,-2.564130054,49.1655,1.89E-11,10.00036592,2.5846875,-4.601497506,-3.40268267,90.00000001 +254.84,50.43283629,-2.564128647,49.1398,1.19E-11,10.00036588,2.548125,-4.680477045,-3.388442607,90.00000001 +254.85,50.43283629,-2.564127239,49.1145,4.84E-12,10.00036584,2.5096875,-4.758479061,-3.371247799,90.00000001 +254.86,50.43283629,-2.564125832,49.0896,2.50E-12,10.0003658,2.47,-4.835487339,-3.351113203,90.00000001 +254.87,50.43283629,-2.564124424,49.0651,2.34E-12,10.00036576,2.43,-4.911485836,-3.328056407,90.00000001 +254.88,50.43283629,-2.564123017,49.041,1.56E-12,10.00036573,2.39,-4.986458567,-3.302097466,90.00000001 +254.89,50.43283629,-2.564121609,49.0173,-2.34E-12,10.00036569,2.3496875,-5.060390004,-3.273259068,90.00000001 +254.9,50.43283629,-2.564120202,48.994,-8.44E-12,10.00014362,2.3078125,-5.133264563,-3.241566366,90.00000001 +254.91,50.43283629,-2.564118794,48.9711,-6.25E-12,9.999477483,2.263125,-5.205067176,-3.207046919,90.00000001 +254.92,50.43283629,-2.564117387,48.9487,3.91E-12,9.999033383,2.216875,-5.275782772,-3.169730923,90.00000001 +254.93,50.43283629,-2.56411598,48.9268,2.19E-12,9.999477414,2.1715625,-5.345396572,-3.129650806,90.00000001 +254.94,50.43283629,-2.564114572,48.9053,-1.64E-11,10.00014348,2.1265625,-5.41389402,-3.086841634,90.00000001 +254.95,50.43283629,-2.564113165,48.8842,-3.28E-11,10.00036548,2.079375,-5.481260908,-3.041340706,90.00000001 +254.96,50.43283629,-2.564111757,48.8637,-3.75E-11,10.00036545,2.03,-5.547483026,-2.993187672,90.00000001 +254.97,50.43283629,-2.56411035,48.8436,-3.75E-11,10.00036542,1.98,-5.612546681,-2.942424528,90.00000001 +254.98,50.43283629,-2.564108942,48.8241,-3.50E-11,10.00036539,1.9296875,-5.676438236,-2.889095564,90.00000001 +254.99,50.43283629,-2.564107535,48.805,-2.50E-11,10.00036536,1.8784375,-5.739144284,-2.833247248,90.00000001 +255,50.43283629,-2.564106127,48.7865,-1.02E-11,10.00036533,1.8265625,-5.800651876,-2.77492828,90.00000001 +255.01,50.43283629,-2.56410472,48.7685,-3.28E-12,10.0003653,1.775,-5.860948006,-2.71418954,90.00000001 +255.02,50.43283629,-2.564103312,48.751,-9.38E-12,10.00036527,1.723125,-5.920020184,-2.651084026,90.00000001 +255.03,50.43283629,-2.564101905,48.734,-1.80E-11,10.00014321,1.6696875,-5.977855977,-2.585666684,90.00000001 +255.04,50.43283629,-2.564100497,48.7176,-1.88E-11,9.999477087,1.6146875,-6.034443466,-2.517994639,90.00000001 +255.05,50.43283629,-2.56409909,48.7017,-1.19E-11,9.999032996,1.558125,-6.089770677,-2.448126848,90.00000001 +255.06,50.43283629,-2.564097683,48.6864,-7.19E-12,9.999477038,1.5,-6.143826151,-2.376124216,90.00000001 +255.07,50.43283629,-2.564096275,48.6717,-1.19E-11,10.00014311,1.441875,-6.196598543,-2.302049654,90.00000001 +255.08,50.43283629,-2.564094868,48.6576,-1.88E-11,10.00036512,1.3853125,-6.248076853,-2.225967562,90.00000001 +255.09,50.43283629,-2.56409346,48.644,-2.28E-11,10.0003651,1.3296875,-6.298250309,-2.147944461,90.00000001 +255.1,50.43283629,-2.564092053,48.631,-2.66E-11,10.00036508,1.2728125,-6.347108482,-2.068048304,90.00000001 +255.11,50.43283629,-2.564090645,48.6185,-2.36E-11,10.00036506,1.213125,-6.394641176,-1.98634882,90.00000001 +255.12,50.43283629,-2.564089238,48.6067,-1.17E-11,10.00036505,1.1515625,-6.440838419,-1.902917169,90.00000001 +255.13,50.43283629,-2.56408783,48.5955,-2.34E-12,10.00036503,1.0903125,-6.485690529,-1.817826119,90.00000001 +255.14,50.43283629,-2.564086423,48.5849,-1.67E-16,10.00036501,1.03,-6.529188225,-1.73114998,90.00000001 +255.15,50.43283629,-2.564085015,48.5749,-2.78E-16,10.000365,0.97,-6.571322338,-1.642964155,90.00000001 +255.16,50.43283629,-2.564083608,48.5655,2.34E-12,10.00014295,0.9096875,-6.612084159,-1.553345706,90.00000001 +255.17,50.43283629,-2.5640822,48.5567,9.22E-12,9.999476835,0.848125,-6.651465153,-1.462372728,90.00000001 +255.18,50.43283629,-2.564080793,48.5485,1.33E-11,9.999032756,0.785,-6.68945701,-1.370124461,90.00000001 +255.19,50.43283629,-2.564079386,48.541,5.47E-12,9.99947681,0.7215625,-6.726051882,-1.276681519,90.00000001 +255.2,50.43283629,-2.564077978,48.5341,-8.44E-12,10.0001429,0.6584375,-6.761242148,-1.182125205,90.00000001 +255.21,50.43283629,-2.564076571,48.5278,-1.42E-11,10.00036492,0.595,-6.795020359,-1.08653814,90.00000001 +255.22,50.43283629,-2.564075163,48.5222,-6.41E-12,10.00036491,0.5315625,-6.827379583,-0.990003518,90.00000001 +255.23,50.43283629,-2.564073756,48.5172,6.88E-12,10.00014287,0.4684375,-6.858312944,-0.892605678,90.00000001 +255.24,50.43283629,-2.564072348,48.5128,1.27E-11,9.999476766,0.405,-6.887814025,-0.794429417,90.00000001 +255.25,50.43283629,-2.564070941,48.5091,5.63E-12,9.999032695,0.3415625,-6.915876696,-0.69556045,90.00000001 +255.26,50.43283629,-2.564069534,48.506,-7.03E-12,9.999476756,0.2784375,-6.942495054,-0.596084893,90.00000001 +255.27,50.43283629,-2.564068126,48.5035,-1.50E-11,10.00014285,0.2146875,-6.9676636,-0.496089548,90.00000001 +255.28,50.43283629,-2.564066719,48.5017,-1.48E-11,10.00036488,0.1496875,-6.991377006,-0.39566162,90.00000001 +255.29,50.43283629,-2.564065311,48.5005,-3.91E-12,10.00036488,0.08375,-7.013630343,-0.294888657,90.00000001 +255.3,50.43283629,-2.564063904,48.5,1.66E-11,10.00014285,0.0184375,-7.034419028,-0.193858551,90.00000001 +255.31,50.43283629,-2.564062496,48.5002,2.80E-11,9.999476747,-0.045,-7.053738592,-0.092659422,90.00000001 +255.32,50.43283629,-2.564061089,48.5009,1.56E-11,9.999032682,-0.1084375,-7.071585138,0.008620494,90.00000001 +255.33,50.43283629,-2.564059682,48.5023,-6.25E-12,9.99947675,-0.17375,-7.087954829,0.109892961,90.00000001 +255.34,50.43283629,-2.564058274,48.5044,-2.02E-11,10.00014285,-0.239375,-7.102844341,0.211069573,90.00000001 +255.35,50.43283629,-2.564056867,48.5071,-3.05E-11,10.00036489,-0.3034375,-7.116250464,0.312062093,90.00000001 +255.36,50.43283629,-2.564055459,48.5105,-4.30E-11,10.00036489,-0.3665625,-7.12817045,0.412782516,90.00000001 +255.37,50.43283629,-2.564054052,48.5144,-4.92E-11,10.00014287,-0.43,-7.138601834,0.513143007,90.00000001 +255.38,50.43283629,-2.564052644,48.5191,-4.20E-11,9.999476776,-0.4934375,-7.147542382,0.613056017,90.00000001 +255.39,50.43283629,-2.564051237,48.5243,-2.81E-11,9.999032719,-0.5565625,-7.154990318,0.712434401,90.00000001 +255.4,50.43283629,-2.56404983,48.5302,-1.95E-11,9.999476794,-0.6203125,-7.16094398,0.811191584,90.00000001 +255.41,50.43283629,-2.564048422,48.5367,-1.64E-11,10.0001429,-0.6846875,-7.165402164,0.909241336,90.00000001 +255.42,50.43283629,-2.564047015,48.5439,-1.08E-11,10.00036495,-0.748125,-7.168363955,1.006498228,90.00000001 +255.43,50.43283629,-2.564045607,48.5517,-3.91E-12,10.00036496,-0.8096875,-7.169828722,1.102877464,90.00000001 +255.44,50.43283629,-2.5640442,48.5601,1.56E-12,10.00036497,-0.8703125,-7.169796178,1.198294991,90.00000001 +255.45,50.43283629,-2.564042792,48.5691,9.22E-12,10.00036499,-0.931875,-7.168266323,1.292667557,90.00000001 +255.46,50.43283629,-2.564041385,48.5787,1.17E-11,10.00014297,-0.9946875,-7.165239444,1.385912943,90.00000001 +255.47,50.43283629,-2.564039977,48.589,-2.34E-12,9.999476886,-1.0565625,-7.160716229,1.477949732,90.00000001 +255.48,50.43283629,-2.56403857,48.5999,-2.33E-11,9.999032837,-1.11625,-7.154697537,1.568697767,90.00000001 +255.49,50.43283629,-2.564037163,48.6113,-3.20E-11,9.999476921,-1.175,-7.147184742,1.658077808,90.00000001 +255.5,50.43283629,-2.564035755,48.6234,-2.19E-11,10.00014304,-1.23375,-7.138179278,1.746012047,90.00000001 +255.51,50.43283629,-2.564034348,48.636,1.41E-12,10.00036509,-1.293125,-7.12768315,1.832423708,90.00000001 +255.52,50.43283629,-2.56403294,48.6492,1.88E-11,10.00036511,-1.353125,-7.115698477,1.917237505,90.00000001 +255.53,50.43283629,-2.564031533,48.6631,1.25E-11,10.0001431,-1.41125,-7.102227781,2.00037941,90.00000001 +255.54,50.43283629,-2.564030125,48.6775,-4.69E-12,9.999477025,-1.4665625,-7.087273869,2.081776946,90.00000001 +255.55,50.43283629,-2.564028718,48.6924,-7.19E-12,9.999032982,-1.521875,-7.070839892,2.161359179,90.00000001 +255.56,50.43283629,-2.564027311,48.7079,4.69E-12,9.999477072,-1.5784375,-7.052929232,2.239056668,90.00000001 +255.57,50.43283629,-2.564025903,48.724,1.48E-11,10.0001432,-1.6346875,-7.033545668,2.314801631,90.00000001 +255.58,50.43283629,-2.564024496,48.7406,1.64E-11,10.00036526,-1.6896875,-7.01269327,2.388528064,90.00000001 +255.59,50.43283629,-2.564023088,48.7578,8.44E-12,10.00036528,-1.7434375,-6.990376335,2.460171681,90.00000001 +255.6,50.43283629,-2.564021681,48.7755,-7.81E-12,10.00036531,-1.79625,-6.966599503,2.529669972,90.00000001 +255.61,50.43283629,-2.564020273,48.7937,-2.50E-11,10.00036534,-1.8484375,-6.941367874,2.596962375,90.00000001 +255.62,50.43283629,-2.564018866,48.8125,-3.50E-11,10.00036537,-1.8996875,-6.914686548,2.661990163,90.00000001 +255.63,50.43283629,-2.564017458,48.8317,-3.75E-11,10.0003654,-1.95,-6.886561253,2.724696727,90.00000001 +255.64,50.43283629,-2.564016051,48.8515,-3.75E-11,10.00036543,-2,-6.856997719,2.785027235,90.00000001 +255.65,50.43283629,-2.564014643,48.8717,-3.28E-11,10.00036546,-2.049375,-6.826002249,2.842929203,90.00000001 +255.66,50.43283629,-2.564013236,48.8925,-1.41E-11,10.00014346,-2.096875,-6.793581203,2.898352041,90.00000001 +255.67,50.43283629,-2.564011828,48.9137,1.41E-11,9.999477394,-2.143125,-6.759741457,2.951247505,90.00000001 +255.68,50.43283629,-2.564010421,48.9353,2.83E-11,9.999033362,-2.19,-6.724489999,3.001569471,90.00000001 +255.69,50.43283629,-2.564009014,48.9575,1.95E-11,9.999477462,-2.23625,-6.687834222,3.049273995,90.00000001 +255.7,50.43283629,-2.564007606,48.9801,8.59E-12,10.0001436,-2.2796875,-6.649781746,3.094319478,90.00000001 +255.71,50.43283629,-2.564006199,49.0031,1.08E-11,10.00036567,-2.321875,-6.610340592,3.136666674,90.00000001 +255.72,50.43283629,-2.564004791,49.0265,1.41E-11,10.0003657,-2.365,-6.569518896,3.176278684,90.00000001 +255.73,50.43283629,-2.564003384,49.0504,1.03E-11,10.00036574,-2.4078125,-6.52732531,3.213120902,90.00000001 +255.74,50.43283629,-2.564001976,49.0747,1.27E-11,10.00036578,-2.448125,-6.483768542,3.247161241,90.00000001 +255.75,50.43283629,-2.564000569,49.0994,2.56E-11,10.00036582,-2.4865625,-6.438857704,3.278370023,90.00000001 +255.76,50.43283629,-2.563999161,49.1244,3.11E-11,10.00036586,-2.5246875,-6.392602248,3.306720032,90.00000001 +255.77,50.43283629,-2.563997754,49.1499,1.62E-11,10.00036589,-2.5615625,-6.345011743,3.332186516,90.00000001 +255.78,50.43283629,-2.563996346,49.1757,-3.91E-12,10.00036594,-2.5965625,-6.296096159,3.354747245,90.00000001 +255.79,50.43283629,-2.563994939,49.2018,-4.69E-12,10.00014394,-2.6315625,-6.245865694,3.374382623,90.00000001 +255.8,50.43283629,-2.563993531,49.2283,1.41E-11,9.999477886,-2.6665625,-6.194330891,3.391075462,90.00000001 +255.81,50.43283629,-2.563992124,49.2552,2.89E-11,9.999033862,-2.6996875,-6.141502463,3.404811266,90.00000001 +255.82,50.43283629,-2.563990717,49.2823,2.34E-11,9.99947797,-2.73125,-6.087391527,3.415578002,90.00000001 +255.83,50.43283629,-2.563989309,49.3098,3.75E-12,10.00014411,-2.7615625,-6.032009254,3.423366332,90.00000001 +255.84,50.43283629,-2.563987902,49.3376,-1.02E-11,10.00036619,-2.7896875,-5.975367277,3.42816938,90.00000001 +255.85,50.43283629,-2.563986494,49.3656,-6.25E-12,10.00036623,-2.8165625,-5.917477398,3.429983078,90.00000001 +255.86,50.43283629,-2.563985087,49.3939,7.03E-12,10.00036628,-2.8434375,-5.858351763,3.428805764,90.00000001 +255.87,50.43283629,-2.563983679,49.4225,1.56E-11,10.00036632,-2.8696875,-5.798002691,3.42463847,90.00000001 +255.88,50.43283629,-2.563982272,49.4513,1.48E-11,10.00036637,-2.8946875,-5.736442788,3.417484806,90.00000001 +255.89,50.43283629,-2.563980864,49.4804,7.81E-12,10.00036641,-2.918125,-5.673684887,3.407351073,90.00000001 +255.9,50.43283629,-2.563979457,49.5097,-7.81E-13,10.00036646,-2.939375,-5.60974211,3.394246096,90.00000001 +255.91,50.43283629,-2.563978049,49.5392,-1.19E-11,10.0003665,-2.9584375,-5.544627805,3.378181276,90.00000001 +255.92,50.43283629,-2.563976642,49.5689,-2.58E-11,10.00014452,-2.9765625,-5.478355611,3.359170594,90.00000001 +255.93,50.43283629,-2.563975234,49.5987,-3.28E-11,9.999478465,-2.995,-5.410939276,3.337230722,90.00000001 +255.94,50.43283629,-2.563973827,49.6288,-2.81E-11,9.999034446,-3.013125,-5.342392955,3.312380683,90.00000001 +255.95,50.43283629,-2.56397242,49.659,-1.88E-11,9.999478559,-3.029375,-5.27273097,3.284642249,90.00000001 +255.96,50.43283629,-2.563971012,49.6894,-9.38E-12,10.00014471,-3.043125,-5.201967818,3.254039542,90.00000001 +255.97,50.43283629,-2.563969605,49.7199,-2.34E-12,10.00036679,-3.0546875,-5.13011828,3.220599261,90.00000001 +255.98,50.43283629,-2.563968197,49.7505,-5.55E-17,10.00036683,-3.065,-5.057197426,3.184350571,90.00000001 +255.99,50.43283629,-2.56396679,49.7812,8.33E-17,10.00036688,-3.075,-4.983220438,3.14532504,90.00000001 +256,50.43283629,-2.563965382,49.812,-2.34E-12,10.00036693,-3.0846875,-4.90820273,3.103556818,90.00000001 +256.01,50.43283629,-2.563963975,49.8429,-7.03E-12,10.00014495,-3.0928125,-4.832160058,3.059082173,90.00000001 +256.02,50.43283629,-2.563962567,49.8739,-4.69E-12,9.999478895,-3.098125,-4.755108236,3.011940007,90.00000001 +256.03,50.43283629,-2.56396116,49.9049,7.03E-12,9.999034878,-3.1015625,-4.677063362,2.962171346,90.00000001 +256.04,50.43283629,-2.563959753,49.9359,1.41E-11,9.999478992,-3.105,-4.598041711,2.909819677,90.00000001 +256.05,50.43283629,-2.563958345,49.967,9.38E-12,10.00014514,-3.108125,-4.518059839,2.854930549,90.00000001 +256.06,50.43283629,-2.563956938,49.9981,2.34E-12,10.00036722,-3.1096875,-4.437134478,2.79755192,90.00000001 +256.07,50.43283629,-2.56395553,50.0292,2.34E-12,10.00036727,-3.1096875,-4.355282415,2.737733808,90.00000001 +256.08,50.43283629,-2.563954123,50.0603,9.38E-12,10.00014529,-3.108125,-4.272520839,2.675528296,90.00000001 +256.09,50.43283629,-2.563952715,50.0914,1.64E-11,9.999479235,-3.1046875,-4.188866996,2.6109897,90.00000001 +256.1,50.43283629,-2.563951308,50.1224,1.64E-11,9.999035218,-3.0996875,-4.10433836,2.544174284,90.00000001 +256.11,50.43283629,-2.563949901,50.1534,9.38E-12,9.999479333,-3.093125,-4.01895258,2.475140318,90.00000001 +256.12,50.43283629,-2.563948493,50.1843,2.34E-12,10.00014548,-3.0846875,-3.932727474,2.403947963,90.00000001 +256.13,50.43283629,-2.563947086,50.2151,2.22E-16,10.00036756,-3.075,-3.84568109,2.330659384,90.00000001 +256.14,50.43283629,-2.563945678,50.2458,-5.55E-17,10.00036761,-3.065,-3.757831591,2.25533841,90.00000001 +256.15,50.43283629,-2.563944271,50.2764,-1.94E-16,10.00036766,-3.055,-3.669197312,2.178050701,90.00000001 +256.16,50.43283629,-2.563942863,50.3069,-4.69E-12,10.00036771,-3.044375,-3.579796759,2.098863751,90.00000001 +256.17,50.43283629,-2.563941456,50.3373,-1.88E-11,10.00014572,-3.03125,-3.489648611,2.017846544,90.00000001 +256.18,50.43283629,-2.563940048,50.3676,-3.05E-11,9.999479667,-3.0146875,-3.398771718,1.935069785,90.00000001 +256.19,50.43283629,-2.563938641,50.3976,-2.81E-11,9.999035649,-2.996875,-3.307185045,1.85060555,90.00000001 +256.2,50.43283629,-2.563937234,50.4275,-2.34E-11,9.999479762,-2.98,-3.214907671,1.764527579,90.00000001 +256.21,50.43283629,-2.563935826,50.4572,-2.58E-11,10.00014591,-2.9628125,-3.121958905,1.676910931,90.00000001 +256.22,50.43283629,-2.563934419,50.4868,-2.58E-11,10.00036799,-2.9428125,-3.02835817,1.587831979,90.00000001 +256.23,50.43283629,-2.563933011,50.5161,-2.09E-11,10.00036803,-2.9196875,-2.934125005,1.497368475,90.00000001 +256.24,50.43283629,-2.563931604,50.5452,-1.56E-11,10.00014604,-2.8953125,-2.839279061,1.405599143,90.00000001 +256.25,50.43283629,-2.563930196,50.574,-5.47E-12,9.99947999,-2.8715625,-2.743840221,1.312604196,90.00000001 +256.26,50.43283629,-2.563928789,50.6026,6.25E-12,9.999035969,-2.848125,-2.647828308,1.218464595,90.00000001 +256.27,50.43283629,-2.563927382,50.631,7.97E-12,9.99948008,-2.8228125,-2.551263491,1.123262443,90.00000001 +256.28,50.43283629,-2.563925974,50.6591,3.28E-12,10.00014622,-2.7946875,-2.454165823,1.02708082,90.00000001 +256.29,50.43283629,-2.563924567,50.6869,3.91E-12,10.0003683,-2.7646875,-2.356555644,0.930003607,90.00000001 +256.3,50.43283629,-2.563923159,50.7144,1.31E-11,10.00036834,-2.7334375,-2.258453352,0.832115372,90.00000001 +256.31,50.43283629,-2.563921752,50.7416,2.58E-11,10.00014635,-2.7015625,-2.159879401,0.733501543,90.00000001 +256.32,50.43283629,-2.563920344,50.7684,2.89E-11,9.999480295,-2.6696875,-2.060854361,0.634248065,90.00000001 +256.33,50.43283629,-2.563918937,50.795,1.41E-11,9.999036271,-2.6365625,-1.961398972,0.534441509,90.00000001 +256.34,50.43283629,-2.56391753,50.8212,-7.19E-12,9.999480377,-2.60125,-1.861533975,0.434168911,90.00000001 +256.35,50.43283629,-2.563916122,50.847,-1.66E-11,10.00014652,-2.565,-1.761280169,0.333517759,90.00000001 +256.36,50.43283629,-2.563914715,50.8725,-9.53E-12,10.00036859,-2.5284375,-1.660658582,0.232575716,90.00000001 +256.37,50.43283629,-2.563913307,50.8976,6.88E-12,10.00036863,-2.49125,-1.559690183,0.131430903,90.00000001 +256.38,50.43283629,-2.5639119,50.9223,2.09E-11,10.00036867,-2.453125,-1.458396057,0.030171442,90.00000001 +256.39,50.43283629,-2.563910492,50.9467,2.11E-11,10.00036871,-2.413125,-1.356797348,-0.071114261,90.00000001 +256.4,50.43283629,-2.563909085,50.9706,7.66E-12,10.00036874,-2.37125,-1.25491531,-0.172338027,90.00000001 +256.41,50.43283629,-2.563907677,50.9941,-7.81E-12,10.00036878,-2.3284375,-1.152771202,-0.273411449,90.00000001 +256.42,50.43283629,-2.56390627,51.0172,-1.64E-11,10.00014678,-2.2846875,-1.050386394,-0.374246521,90.00000001 +256.43,50.43283629,-2.563904862,51.0398,-1.80E-11,9.999480719,-2.24,-0.947782144,-0.474755178,90.00000001 +256.44,50.43283629,-2.563903455,51.062,-1.72E-11,9.999036687,-2.195,-0.844979993,-0.574849874,90.00000001 +256.45,50.43283629,-2.563902048,51.0837,-1.48E-11,9.999480788,-2.1496875,-0.742001372,-0.674443288,90.00000001 +256.46,50.43283629,-2.56390064,51.105,-8.59E-12,10.00014692,-2.103125,-0.638867823,-0.773448562,90.00000001 +256.47,50.43283629,-2.563899233,51.1258,-2.19E-12,10.00036899,-2.0546875,-0.535600832,-0.871779407,90.00000001 +256.48,50.43283629,-2.563897825,51.1461,-1.56E-13,10.00036902,-2.005,-0.432222,-0.969350051,90.00000001 +256.49,50.43283629,-2.563896418,51.1659,-7.81E-13,10.00036905,-1.955,-0.328752927,-1.066075354,90.00000001 +256.5,50.43283629,-2.56389501,51.1852,-1.56E-12,10.00036908,-1.905,-0.225215156,-1.16187109,90.00000001 +256.51,50.43283629,-2.563893603,51.204,7.82E-13,10.00036911,-1.8546875,-0.121630346,-1.256653607,90.00000001 +256.52,50.43283629,-2.563892195,51.2223,8.44E-12,10.00036914,-1.803125,-0.018020153,-1.350340343,90.00000001 +256.53,50.43283629,-2.563890788,51.2401,1.31E-11,10.00036917,-1.75,0.085593821,-1.442849535,90.00000001 +256.54,50.43283629,-2.56388938,51.2573,2.97E-12,10.00036919,-1.69625,0.189189862,-1.534100513,90.00000001 +256.55,50.43283629,-2.563887973,51.274,-2.11E-11,10.00014719,-1.641875,0.292746426,-1.624013805,90.00000001 +256.56,50.43283629,-2.563886565,51.2902,-4.47E-11,9.99948111,-1.58625,0.396241912,-1.712510861,90.00000001 +256.57,50.43283629,-2.563885158,51.3057,-5.41E-11,9.999037068,-1.53,0.499654549,-1.799514617,90.00000001 +256.58,50.43283629,-2.563883751,51.3208,-4.70E-11,9.999481158,-1.4734375,0.602962907,-1.884949156,90.00000001 +256.59,50.43283629,-2.563882343,51.3352,-3.05E-11,10.00014728,-1.41625,0.70614533,-1.968739993,90.00000001 +256.6,50.43283629,-2.563880936,51.3491,-1.11E-11,10.00036934,-1.35875,0.809180273,-2.050814078,90.00000001 +256.61,50.43283629,-2.563879528,51.3624,8.44E-12,10.00036936,-1.30125,0.91204625,-2.131099846,90.00000001 +256.62,50.43283629,-2.563878121,51.3751,2.25E-11,10.00036938,-1.243125,1.01472172,-2.209527226,90.00000001 +256.63,50.43283629,-2.563876713,51.3873,2.19E-11,10.0003694,-1.183125,1.117185309,-2.286027863,90.00000001 +256.64,50.43283629,-2.563875306,51.3988,1.25E-11,10.00036941,-1.121875,1.21941559,-2.360535065,90.00000001 +256.65,50.43283629,-2.563873898,51.4097,1.34E-11,10.00036943,-1.061875,1.321391192,-2.432983802,90.00000001 +256.66,50.43283629,-2.563872491,51.42,2.17E-11,10.00036945,-1.0028125,1.423090856,-2.503310991,90.00000001 +256.67,50.43283629,-2.563871083,51.4298,1.33E-11,10.00036946,-0.9415625,1.524493328,-2.571455268,90.00000001 +256.68,50.43283629,-2.563869676,51.4389,-1.25E-11,10.00014744,-0.878125,1.625577407,-2.63735716,90.00000001 +256.69,50.43283629,-2.563868268,51.4473,-2.95E-11,9.999481356,-0.8153125,1.726322009,-2.700959257,90.00000001 +256.7,50.43283629,-2.563866861,51.4552,-2.48E-11,9.999037302,-0.7534375,1.826706105,-2.762206039,90.00000001 +256.71,50.43283629,-2.563865454,51.4624,-7.81E-12,9.99948138,-0.69125,1.926708726,-2.821044164,90.00000001 +256.72,50.43283629,-2.563864046,51.469,8.44E-12,10.00014749,-0.6284375,2.026308959,-2.877422294,90.00000001 +256.73,50.43283629,-2.563862639,51.475,1.42E-11,10.00036953,-0.565,2.125486005,-2.93129127,90.00000001 +256.74,50.43283629,-2.563861231,51.4803,6.41E-12,10.00036954,-0.5015625,2.224219181,-2.98260411,90.00000001 +256.75,50.43283629,-2.563859824,51.485,-6.88E-12,10.00036955,-0.4384375,2.32248786,-3.031316122,90.00000001 +256.76,50.43283629,-2.563858416,51.4891,-1.50E-11,10.00036955,-0.3746875,2.420271531,-3.077384736,90.00000001 +256.77,50.43283629,-2.563857009,51.4925,-1.72E-11,10.00036956,-0.31,2.517549795,-3.120769845,90.00000001 +256.78,50.43283629,-2.563855601,51.4953,-1.56E-11,10.00036956,-0.2453125,2.614302255,-3.161433577,90.00000001 +256.79,50.43283629,-2.563854194,51.4974,-6.87E-12,10.00014753,-0.1815625,2.710508745,-3.199340465,90.00000001 +256.8,50.43283629,-2.563852786,51.4989,4.69E-12,9.999481438,-0.118125,2.806149209,-3.234457564,90.00000001 +256.81,50.43283629,-2.563851379,51.4998,2.34E-12,9.999037373,-0.0534375,2.901203595,-3.266754106,90.00000001 +256.82,50.43283629,-2.563849972,51.5,-1.87E-11,9.999481439,0.011875,2.995652135,-3.296201959,90.00000001 +256.83,50.43283629,-2.563848564,51.4995,-4.22E-11,10.00014754,0.07625,3.089475063,-3.32277557,90.00000001 +256.84,50.43283629,-2.563847157,51.4985,-5.16E-11,10.00036957,0.14,3.18265284,-3.346451618,90.00000001 +256.85,50.43283629,-2.563845749,51.4967,-4.20E-11,10.00036957,0.20375,3.275165928,-3.367209478,90.00000001 +256.86,50.43283629,-2.563844342,51.4944,-1.80E-11,10.00014753,0.268125,3.36699502,-3.385031101,90.00000001 +256.87,50.43283629,-2.563842934,51.4914,4.06E-12,9.999481425,0.3334375,3.458120978,-3.39990096,90.00000001 +256.88,50.43283629,-2.563841527,51.4877,7.03E-12,9.999037353,0.398125,3.548524723,-3.411806049,90.00000001 +256.89,50.43283629,-2.56384012,51.4834,-4.53E-12,9.999481413,0.4615625,3.638187404,-3.420735998,90.00000001 +256.9,50.43283629,-2.563838712,51.4785,-1.16E-11,10.0001475,0.525,3.727090343,-3.426682956,90.00000001 +256.91,50.43283629,-2.563837305,51.4729,-4.53E-12,10.00036953,0.5884375,3.815214919,-3.429641824,90.00000001 +256.92,50.43283629,-2.563835897,51.4667,9.37E-12,10.00036952,0.6515625,3.902542682,-3.429610025,90.00000001 +256.93,50.43283629,-2.56383449,51.4599,1.58E-11,10.00036951,0.715,3.989055528,-3.426587558,90.00000001 +256.94,50.43283629,-2.563833082,51.4524,1.02E-11,10.0003695,0.778125,4.074735235,-3.420577002,90.00000001 +256.95,50.43283629,-2.563831675,51.4443,2.50E-12,10.00014745,0.8396875,4.159564043,-3.411583684,90.00000001 +256.96,50.43283629,-2.563830267,51.4356,-2.34E-12,9.999481337,0.9003125,4.243524133,-3.399615398,90.00000001 +256.97,50.43283629,-2.56382886,51.4263,-1.17E-11,9.999037257,0.9615625,4.326598085,-3.384682628,90.00000001 +256.98,50.43283629,-2.563827453,51.4164,-2.58E-11,9.999481309,1.0234375,4.408768426,-3.366798324,90.00000001 +256.99,50.43283629,-2.563826045,51.4058,-3.52E-11,10.00014739,1.0846875,4.490018024,-3.345978183,90.00000001 +257,50.43283629,-2.563824638,51.3947,-3.77E-11,10.00036941,1.145,4.570330034,-3.322240255,90.00000001 +257.01,50.43283629,-2.56382323,51.3829,-3.83E-11,10.00036939,1.205,4.649687496,-3.295605281,90.00000001 +257.02,50.43283629,-2.563821823,51.3706,-3.67E-11,10.00014734,1.2646875,4.728073967,-3.266096522,90.00000001 +257.03,50.43283629,-2.563820415,51.3576,-2.95E-11,9.999481217,1.323125,4.805473059,-3.233739647,90.00000001 +257.04,50.43283629,-2.563819008,51.3441,-2.34E-11,9.999037129,1.38,4.881868559,-3.198562904,90.00000001 +257.05,50.43283629,-2.563817601,51.33,-2.66E-11,9.999481172,1.436875,4.957244594,-3.160596944,90.00000001 +257.06,50.43283629,-2.563816193,51.3154,-2.81E-11,10.00014725,1.4946875,5.031585295,-3.119874943,90.00000001 +257.07,50.43283629,-2.563814786,51.3001,-1.39E-11,10.00036926,1.5515625,5.104875249,-3.076432366,90.00000001 +257.08,50.43283629,-2.563813378,51.2843,7.03E-12,10.00036923,1.60625,5.177099157,-3.030307086,90.00000001 +257.09,50.43283629,-2.563811971,51.268,1.80E-11,10.00014718,1.6603125,5.248241837,-2.981539325,90.00000001 +257.1,50.43283629,-2.563810563,51.2511,2.11E-11,9.999481049,1.7146875,5.318288506,-2.930171596,90.00000001 +257.11,50.43283629,-2.563809156,51.2337,2.67E-11,9.999036956,1.768125,5.387224553,-2.876248705,90.00000001 +257.12,50.43283629,-2.563807749,51.2157,3.13E-11,9.999480994,1.82,5.455035483,-2.819817747,90.00000001 +257.13,50.43283629,-2.563806341,51.1973,2.50E-11,10.00014706,1.8715625,5.521707259,-2.760927828,90.00000001 +257.14,50.43283629,-2.563804934,51.1783,1.16E-11,10.00036907,1.9234375,5.587225842,-2.699630339,90.00000001 +257.15,50.43283629,-2.563803526,51.1588,2.34E-12,10.00036904,1.9746875,5.651577654,-2.635978739,90.00000001 +257.16,50.43283629,-2.563802119,51.1388,2.34E-12,10.00036901,2.0246875,5.714749173,-2.570028489,90.00000001 +257.17,50.43283629,-2.563800711,51.1183,9.37E-12,10.00036897,2.073125,5.776727221,-2.501837172,90.00000001 +257.18,50.43283629,-2.563799304,51.0973,1.41E-11,10.00014691,2.12,5.837498907,-2.431464204,90.00000001 +257.19,50.43283629,-2.563797896,51.0759,7.19E-12,9.999480775,2.1665625,5.897051509,-2.358971005,90.00000001 +257.2,50.43283629,-2.563796489,51.054,-3.91E-12,9.999036675,2.213125,5.955372597,-2.284420716,90.00000001 +257.21,50.43283629,-2.563795082,51.0316,-3.12E-12,9.999480706,2.258125,6.012449965,-2.207878368,90.00000001 +257.22,50.43283629,-2.563793674,51.0088,1.08E-11,10.00014677,2.30125,6.068271696,-2.129410709,90.00000001 +257.23,50.43283629,-2.563792267,50.9856,2.58E-11,10.00036877,2.3434375,6.122826159,-2.049086209,90.00000001 +257.24,50.43283629,-2.563790859,50.9619,3.12E-11,10.00036873,2.385,6.176101952,-1.966974825,90.00000001 +257.25,50.43283629,-2.563789452,50.9379,2.11E-11,10.00036869,2.42625,6.22808796,-1.883148292,90.00000001 +257.26,50.43283629,-2.563788044,50.9134,-1.56E-13,10.00036865,2.4665625,6.278773296,-1.797679548,90.00000001 +257.27,50.43283629,-2.563786637,50.8885,-1.42E-11,10.00036861,2.5046875,6.328147361,-1.710643248,90.00000001 +257.28,50.43283629,-2.563785229,50.8633,-9.53E-12,10.00036858,2.5415625,6.376199899,-1.622115195,90.00000001 +257.29,50.43283629,-2.563783822,50.8377,4.53E-12,10.00036854,2.5784375,6.422920883,-1.532172681,90.00000001 +257.3,50.43283629,-2.563782414,50.8117,1.39E-11,10.00036849,2.6146875,6.468300515,-1.44089403,90.00000001 +257.31,50.43283629,-2.563781007,50.7854,1.41E-11,10.00014642,2.6496875,6.512329285,-1.34835894,90.00000001 +257.32,50.43283629,-2.563779599,50.7587,7.81E-12,9.999480279,2.683125,6.554998025,-1.254648083,90.00000001 +257.33,50.43283629,-2.563778192,50.7317,2.34E-12,9.999036171,2.7146875,6.596297912,-1.159843106,90.00000001 +257.34,50.43283629,-2.563776785,50.7044,1.41E-12,9.999480195,2.745,6.636220178,-1.064026743,90.00000001 +257.35,50.43283629,-2.563775377,50.6768,-7.81E-13,10.00014625,2.7746875,6.674756575,-0.967282533,90.00000001 +257.36,50.43283629,-2.56377397,50.6489,-8.44E-12,10.00036824,2.803125,6.711899022,-0.869694872,90.00000001 +257.37,50.43283629,-2.563772562,50.6207,-1.31E-11,10.0003682,2.83,6.747639786,-0.771348786,90.00000001 +257.38,50.43283629,-2.563771155,50.5923,-5.47E-12,10.00036815,2.8565625,6.781971417,-0.672330105,90.00000001 +257.39,50.43283629,-2.563769747,50.5636,3.91E-12,10.00036811,2.8828125,6.814886696,-0.572725117,90.00000001 +257.4,50.43283629,-2.56376834,50.5346,-3.91E-12,10.00036806,2.90625,6.846378806,-0.472620681,90.00000001 +257.41,50.43283629,-2.563766932,50.5054,-2.09E-11,10.00036802,2.9265625,6.876441099,-0.372104174,90.00000001 +257.42,50.43283629,-2.563765525,50.4761,-2.34E-11,10.00036797,2.946875,6.905067331,-0.271263144,90.00000001 +257.43,50.43283629,-2.563764117,50.4465,-1.41E-11,10.00036792,2.968125,6.932251543,-0.170185539,90.00000001 +257.44,50.43283629,-2.56376271,50.4167,-1.17E-11,10.00014584,2.9878125,6.957988062,-0.068959596,90.00000001 +257.45,50.43283629,-2.563761302,50.3867,-1.64E-11,9.999479697,3.0046875,6.982271446,0.032326508,90.00000001 +257.46,50.43283629,-2.563759895,50.3566,-1.88E-11,9.999035584,3.02,7.005096709,0.133584422,90.00000001 +257.47,50.43283629,-2.563758488,50.3263,-2.11E-11,9.999479603,3.0346875,7.02645904,0.234725854,90.00000001 +257.48,50.43283629,-2.56375708,50.2959,-2.81E-11,10.00014565,3.048125,7.046353968,0.335662626,90.00000001 +257.49,50.43283629,-2.563755673,50.2653,-3.28E-11,10.00036764,3.06,7.064777368,0.436306616,90.00000001 +257.5,50.43283629,-2.563754265,50.2347,-2.34E-11,10.00036759,3.07125,7.081725403,0.53657022,90.00000001 +257.51,50.43283629,-2.563752858,50.2039,-2.34E-12,10.00036754,3.0815625,7.097194461,0.636365888,90.00000001 +257.52,50.43283629,-2.56375145,50.173,1.41E-11,10.00036749,3.089375,7.111181392,0.735606648,90.00000001 +257.53,50.43283629,-2.563750043,50.1421,1.87E-11,10.00036745,3.095,7.123683274,0.834205923,90.00000001 +257.54,50.43283629,-2.563748635,50.1111,1.88E-11,10.0003674,3.1,7.134697414,0.932077829,90.00000001 +257.55,50.43283629,-2.563747228,50.0801,1.64E-11,10.00036735,3.1046875,7.144221576,1.029136879,90.00000001 +257.56,50.43283629,-2.56374582,50.049,9.38E-12,10.0003673,3.108125,7.152253814,1.125298506,90.00000001 +257.57,50.43283629,-2.563744413,50.0179,2.34E-12,10.00014522,3.1096875,7.158792294,1.220478885,90.00000001 +257.58,50.43283629,-2.563743005,49.9868,2.34E-12,9.999479072,3.1096875,7.163835812,1.314594995,90.00000001 +257.59,50.43283629,-2.563741598,49.9557,9.37E-12,9.999034958,3.108125,7.167383281,1.407564732,90.00000001 +257.6,50.43283629,-2.563740191,49.9246,1.64E-11,9.999478975,3.1046875,7.169433897,1.499307077,90.00000001 +257.61,50.43283629,-2.563738783,49.8936,1.87E-11,10.00014502,3.1,7.169987259,1.589741991,90.00000001 +257.62,50.43283629,-2.563737376,49.8626,1.87E-11,10.00036701,3.095,7.169043254,1.678790633,90.00000001 +257.63,50.43283629,-2.563735968,49.8317,1.64E-11,10.00036696,3.0896875,7.16660211,1.766375311,90.00000001 +257.64,50.43283629,-2.563734561,49.8008,1.17E-11,10.00036691,3.0828125,7.162664343,1.852419763,90.00000001 +257.65,50.43283629,-2.563733153,49.77,1.41E-11,10.00036686,3.073125,7.157230698,1.936848819,90.00000001 +257.66,50.43283629,-2.563731746,49.7393,2.58E-11,10.00014478,3.0615625,7.150302377,2.019588909,90.00000001 +257.67,50.43283629,-2.563730338,49.7088,3.28E-11,9.999478637,3.05,7.141880815,2.100567899,90.00000001 +257.68,50.43283629,-2.563728931,49.6783,3.05E-11,9.999034524,3.0378125,7.131967728,2.179715143,90.00000001 +257.69,50.43283629,-2.563727524,49.648,3.28E-11,9.999478542,3.023125,7.120565238,2.256961657,90.00000001 +257.7,50.43283629,-2.563726116,49.6178,4.45E-11,10.00014459,3.0065625,7.107675693,2.332240118,90.00000001 +257.71,50.43283629,-2.563724709,49.5879,4.92E-11,10.00036658,2.9896875,7.093301843,2.40548475,90.00000001 +257.72,50.43283629,-2.563723301,49.558,3.52E-11,10.00036653,2.9715625,7.077446611,2.476631785,90.00000001 +257.73,50.43283629,-2.563721894,49.5284,1.39E-11,10.00014445,2.95125,7.060113377,2.545619169,90.00000001 +257.74,50.43283629,-2.563720486,49.499,3.91E-12,9.999478309,2.93,7.041305694,2.612386743,90.00000001 +257.75,50.43283629,-2.563719079,49.4698,7.81E-12,9.999034197,2.908125,7.021027572,2.676876294,90.00000001 +257.76,50.43283629,-2.563717672,49.4408,1.48E-11,9.999478218,2.8846875,6.999283136,2.739031558,90.00000001 +257.77,50.43283629,-2.563716264,49.4121,1.80E-11,10.00014427,2.86,6.976077027,2.798798332,90.00000001 +257.78,50.43283629,-2.563714857,49.3836,2.11E-11,10.00036626,2.8346875,6.951414059,2.856124536,90.00000001 +257.79,50.43283629,-2.563713449,49.3554,2.89E-11,10.00036622,2.808125,6.92529933,2.910960092,90.00000001 +257.8,50.43283629,-2.563712042,49.3274,3.67E-11,10.00014414,2.7796875,6.897738399,2.96325733,90.00000001 +257.81,50.43283629,-2.563710634,49.2998,3.66E-11,9.999477998,2.7496875,6.868736937,3.012970529,90.00000001 +257.82,50.43283629,-2.563709227,49.2724,2.58E-11,9.999033889,2.7184375,6.838301018,3.060056373,90.00000001 +257.83,50.43283629,-2.56370782,49.2454,7.81E-12,9.999477912,2.68625,6.806437058,3.10447378,90.00000001 +257.84,50.43283629,-2.563706412,49.2187,-9.37E-12,10.00014397,2.6534375,6.773151591,3.146184076,90.00000001 +257.85,50.43283629,-2.563705005,49.1923,-1.89E-11,10.00036596,2.6196875,6.738451663,3.185150821,90.00000001 +257.86,50.43283629,-2.563703597,49.1663,-1.89E-11,10.00036592,2.5846875,6.70234455,3.221340096,90.00000001 +257.87,50.43283629,-2.56370219,49.1406,-9.53E-12,10.00014385,2.5484375,6.664837644,3.254720273,90.00000001 +257.88,50.43283629,-2.563700782,49.1153,6.88E-12,9.999477708,2.51125,6.625938966,3.285262361,90.00000001 +257.89,50.43283629,-2.563699375,49.0904,2.09E-11,9.999033604,2.473125,6.585656481,3.312939603,90.00000001 +257.9,50.43283629,-2.563697968,49.0658,2.11E-11,9.999477632,2.433125,6.543998668,3.337727878,90.00000001 +257.91,50.43283629,-2.56369656,49.0417,1.00E-11,10.00014369,2.3915625,6.500974236,3.359605641,90.00000001 +257.92,50.43283629,-2.563695153,49.018,3.75E-12,10.00036569,2.35,6.45659218,3.378553813,90.00000001 +257.93,50.43283629,-2.563693745,48.9947,8.44E-12,10.00036565,2.308125,6.410861725,3.39455578,90.00000001 +257.94,50.43283629,-2.563692338,48.9718,1.48E-11,10.00036562,2.2646875,6.36379244,3.407597674,90.00000001 +257.95,50.43283629,-2.56369093,48.9494,1.48E-11,10.00036558,2.2196875,6.31539418,3.417668095,90.00000001 +257.96,50.43283629,-2.563689523,48.9274,6.25E-12,10.00014351,2.1734375,6.265677028,3.424758219,90.00000001 +257.97,50.43283629,-2.563688115,48.9059,-7.19E-12,9.999477381,2.1265625,6.214651355,3.428861914,90.00000001 +257.98,50.43283629,-2.563686708,48.8849,-1.17E-11,9.999033282,2.0796875,6.162327817,3.42997563,90.00000001 +257.99,50.43283629,-2.563685301,48.8643,2.34E-12,9.999477317,2.0315625,6.108717417,3.428098333,90.00000001 +258,50.43283629,-2.563683893,48.8442,2.11E-11,10.00014338,1.9815625,6.053831211,3.423231687,90.00000001 +258.01,50.43283629,-2.563682486,48.8247,2.09E-11,10.00036539,1.9315625,5.997680775,3.415379931,90.00000001 +258.02,50.43283629,-2.563681078,48.8056,1.56E-12,10.00036536,1.8815625,5.940277795,3.404549883,90.00000001 +258.03,50.43283629,-2.563679671,48.787,-1.33E-11,10.00036533,1.8296875,5.881634304,3.390751054,90.00000001 +258.04,50.43283629,-2.563678263,48.769,-8.44E-12,10.0003653,1.7765625,5.821762449,3.373995418,90.00000001 +258.05,50.43283629,-2.563676856,48.7515,7.03E-12,10.00036527,1.7234375,5.760674835,3.354297645,90.00000001 +258.06,50.43283629,-2.563675448,48.7345,1.80E-11,10.00036525,1.6696875,5.698384181,3.331674865,90.00000001 +258.07,50.43283629,-2.563674041,48.7181,1.87E-11,10.00014319,1.6146875,5.634903437,3.306146788,90.00000001 +258.08,50.43283629,-2.563672633,48.7022,9.53E-12,9.999477063,1.5584375,5.570245952,3.277735701,90.00000001 +258.09,50.43283629,-2.563671226,48.6869,-4.53E-12,9.999032973,1.5015625,5.504425248,3.246466415,90.00000001 +258.1,50.43283629,-2.563669819,48.6722,-1.39E-11,9.999477016,1.4453125,5.437454961,3.212366087,90.00000001 +258.11,50.43283629,-2.563668411,48.658,-1.88E-11,10.00014309,1.3896875,5.36934913,3.175464626,90.00000001 +258.12,50.43283629,-2.563667004,48.6444,-2.41E-11,10.0003651,1.3328125,5.300121962,3.135794059,90.00000001 +258.13,50.43283629,-2.563665596,48.6313,-2.03E-11,10.00036508,1.2734375,5.229787955,3.093389052,90.00000001 +258.14,50.43283629,-2.563664189,48.6189,1.57E-13,10.00036506,1.213125,5.158361776,3.048286502,90.00000001 +258.15,50.43283629,-2.563662781,48.6071,2.11E-11,10.00036505,1.1534375,5.085858321,3.000525886,90.00000001 +258.16,50.43283629,-2.563661374,48.5958,2.34E-11,10.00036503,1.093125,5.012292775,2.950148744,90.00000001 +258.17,50.43283629,-2.563659966,48.5852,1.17E-11,10.00036501,1.0315625,4.937680435,2.897198964,90.00000001 +258.18,50.43283629,-2.563658559,48.5752,2.34E-12,10.000365,0.9703125,4.862036942,2.841722841,90.00000001 +258.19,50.43283629,-2.563657151,48.5658,2.78E-17,10.00036498,0.91,4.785378112,2.783768733,90.00000001 +258.2,50.43283629,-2.563655744,48.557,2.50E-12,10.00014293,0.8496875,4.70771987,2.72338706,90.00000001 +258.21,50.43283629,-2.563654336,48.5488,1.02E-11,9.999476823,0.788125,4.629078491,2.660630591,90.00000001 +258.22,50.43283629,-2.563652929,48.5412,1.56E-11,9.999032745,0.725,4.549470417,2.595553988,90.00000001 +258.23,50.43283629,-2.563651522,48.5343,8.44E-12,9.9994768,0.6615625,4.468912207,2.528214086,90.00000001 +258.24,50.43283629,-2.563650114,48.528,-6.88E-12,10.00014289,0.5984375,4.387420764,2.4586695,90.00000001 +258.25,50.43283629,-2.563648707,48.5223,-1.70E-11,10.00036491,0.5346875,4.305012989,2.386980906,90.00000001 +258.26,50.43283629,-2.563647299,48.5173,-1.86E-11,10.00036491,0.47,4.221706243,2.313210814,90.00000001 +258.27,50.43283629,-2.563645892,48.5129,-1.50E-11,10.0003649,0.4053125,4.13751783,2.237423624,90.00000001 +258.28,50.43283629,-2.563644484,48.5092,-5.62E-12,10.00036489,0.3415625,4.05246534,2.159685341,90.00000001 +258.29,50.43283629,-2.563643077,48.5061,7.03E-12,10.00036489,0.2784375,3.966566533,2.080063745,90.00000001 +258.3,50.43283629,-2.563641669,48.5036,1.27E-11,10.00036488,0.215,3.879839401,1.998628337,90.00000001 +258.31,50.43283629,-2.563640262,48.5018,5.47E-12,10.00036488,0.1515625,3.792301935,1.915450106,90.00000001 +258.32,50.43283629,-2.563638854,48.5006,-5.47E-12,10.00036488,0.088125,3.703972584,1.830601531,90.00000001 +258.33,50.43283629,-2.563637447,48.5,-4.84E-12,10.00014285,0.023125,3.614869683,1.744156695,90.00000001 +258.34,50.43283629,-2.563636039,48.5001,4.84E-12,9.999476748,-0.043125,3.525011795,1.656190886,90.00000001 +258.35,50.43283629,-2.563634632,48.5009,5.47E-12,9.999032683,-0.108125,3.434417829,1.566780879,90.00000001 +258.36,50.43283629,-2.563633225,48.5023,-5.47E-12,9.99947675,-0.1715625,3.343106634,1.476004655,90.00000001 +258.37,50.43283629,-2.563631817,48.5043,-1.50E-11,10.00014285,-0.2353125,3.251097232,1.383941281,90.00000001 +258.38,50.43283629,-2.56363041,48.507,-1.88E-11,10.00036489,-0.3,3.158408875,1.290671085,90.00000001 +258.39,50.43283629,-2.563629002,48.5103,-2.03E-11,10.00036489,-0.365,3.06506093,1.196275429,90.00000001 +258.4,50.43283629,-2.563627595,48.5143,-2.34E-11,10.0003649,-0.4296875,2.971072933,1.100836589,90.00000001 +258.41,50.43283629,-2.563626187,48.5189,-3.06E-11,10.00036491,-0.493125,2.876464423,1.004437815,90.00000001 +258.42,50.43283629,-2.56362478,48.5242,-3.28E-11,10.00036492,-0.5553125,2.781255224,0.90716316,90.00000001 +258.43,50.43283629,-2.563623372,48.53,-1.56E-11,10.00036493,-0.618125,2.685465161,0.809097423,90.00000001 +258.44,50.43283629,-2.563621965,48.5365,1.41E-11,10.0001429,-0.681875,2.589114286,0.710326145,90.00000001 +258.45,50.43283629,-2.563620557,48.5437,3.19E-11,9.999476815,-0.7446875,2.492222711,0.610935443,90.00000001 +258.46,50.43283629,-2.56361915,48.5514,2.73E-11,9.999032761,-0.8065625,2.394810661,0.511012005,90.00000001 +258.47,50.43283629,-2.563617743,48.5598,1.02E-11,9.99947684,-0.86875,2.296898534,0.410642977,90.00000001 +258.48,50.43283629,-2.563616335,48.5688,-9.22E-12,10.00014295,-0.93125,2.198506669,0.309915851,90.00000001 +258.49,50.43283629,-2.563614928,48.5784,-2.58E-11,10.000365,-0.9934375,2.099655693,0.20891846,90.00000001 +258.5,50.43283629,-2.56361352,48.5887,-3.52E-11,10.00036502,-1.0546875,2.000366232,0.107738927,90.00000001 +258.51,50.43283629,-2.563612113,48.5995,-3.53E-11,10.000143,-1.1146875,1.900659028,0.00646537,90.00000001 +258.52,50.43283629,-2.563610705,48.611,-2.66E-11,9.99947692,-1.1734375,1.800554879,-0.094813743,90.00000001 +258.53,50.43283629,-2.563609298,48.623,-1.33E-11,9.999032873,-1.2315625,1.700074697,-0.196010237,90.00000001 +258.54,50.43283629,-2.563607891,48.6356,-3.75E-12,9.999476958,-1.2903125,1.599239511,-0.29703576,90.00000001 +258.55,50.43283629,-2.563606483,48.6488,2.34E-12,10.00014308,-1.3496875,1.498070348,-0.397802305,90.00000001 +258.56,50.43283629,-2.563605076,48.6626,1.09E-11,10.00036513,-1.408125,1.396588293,-0.498221925,90.00000001 +258.57,50.43283629,-2.563603668,48.677,1.64E-11,10.00036515,-1.465,1.294814602,-0.598207128,90.00000001 +258.58,50.43283629,-2.563602261,48.6919,9.53E-12,10.00014315,-1.5215625,1.192770532,-0.697670654,90.00000001 +258.59,50.43283629,-2.563600853,48.7074,-4.53E-12,9.999477071,-1.5784375,1.090477283,-0.796525812,90.00000001 +258.6,50.43283629,-2.563599446,48.7235,-1.63E-11,9.999033031,-1.634375,0.987956397,-0.894686374,90.00000001 +258.61,50.43283629,-2.563598039,48.7401,-2.81E-11,9.999477122,-1.6884375,0.885229133,-0.992066739,90.00000001 +258.62,50.43283629,-2.563596631,48.7573,-4.28E-11,10.00014325,-1.7415625,0.782317032,-1.088582053,90.00000001 +258.63,50.43283629,-2.563595224,48.7749,-4.84E-11,10.00036531,-1.7946875,0.679241523,-1.18414809,90.00000001 +258.64,50.43283629,-2.563593816,48.7932,-3.27E-11,10.00036534,-1.846875,0.576024151,-1.278681542,90.00000001 +258.65,50.43283629,-2.563592409,48.8119,-2.34E-12,10.00014333,-1.8978125,0.472686514,-1.372099962,90.00000001 +258.66,50.43283629,-2.563591001,48.8311,2.11E-11,9.999477264,-1.9484375,0.369250157,-1.464321873,90.00000001 +258.67,50.43283629,-2.563589594,48.8509,2.34E-11,9.999033229,-1.998125,0.265736737,-1.555266891,90.00000001 +258.68,50.43283629,-2.563588187,48.8711,1.17E-11,9.999477327,-2.0465625,0.16216774,-1.644855661,90.00000001 +258.69,50.43283629,-2.563586779,48.8918,4.69E-12,10.00014346,-2.095,0.058564938,-1.733010145,90.00000001 +258.7,50.43283629,-2.563585372,48.913,9.37E-12,10.00036552,-2.143125,-0.045050124,-1.819653338,90.00000001 +258.71,50.43283629,-2.563583964,48.9347,1.62E-11,10.00036556,-2.1896875,-0.148655791,-1.90470984,90.00000001 +258.72,50.43283629,-2.563582557,48.9568,1.56E-11,10.00014356,-2.2346875,-0.252230403,-1.988105394,90.00000001 +258.73,50.43283629,-2.563581149,48.9794,5.47E-12,9.999477497,-2.2784375,-0.35575236,-2.069767292,90.00000001 +258.74,50.43283629,-2.563579742,49.0024,-8.44E-12,9.999033467,-2.3215625,-0.459199947,-2.149624316,90.00000001 +258.75,50.43283629,-2.563578335,49.0258,-1.17E-11,9.999477569,-2.3646875,-0.562551736,-2.227606794,90.00000001 +258.76,50.43283629,-2.563576927,49.0497,3.75E-12,10.00014371,-2.4065625,-0.665785953,-2.303646831,90.00000001 +258.77,50.43283629,-2.56357552,49.074,2.48E-11,10.00036578,-2.44625,-0.768881172,-2.37767802,90.00000001 +258.78,50.43283629,-2.563574112,49.0986,3.28E-11,10.00036582,-2.485,-0.871815847,-2.449635847,90.00000001 +258.79,50.43283629,-2.563572705,49.1237,2.66E-11,10.00036585,-2.523125,-0.974568436,-2.519457515,90.00000001 +258.8,50.43283629,-2.563571297,49.1491,1.89E-11,10.00036589,-2.5596875,-1.077117454,-2.587082234,90.00000001 +258.81,50.43283629,-2.56356989,49.1749,1.48E-11,10.00036593,-2.5953125,-1.179441585,-2.652450989,90.00000001 +258.82,50.43283629,-2.563568482,49.201,4.69E-12,10.00036597,-2.63125,-1.281519402,-2.715506713,90.00000001 +258.83,50.43283629,-2.563567075,49.2275,-1.50E-11,10.00036602,-2.6665625,-1.383329534,-2.776194517,90.00000001 +258.84,50.43283629,-2.563565667,49.2544,-3.14E-11,10.00036606,-2.699375,-1.484850837,-2.834461403,90.00000001 +258.85,50.43283629,-2.56356426,49.2815,-3.52E-11,10.00014407,-2.7296875,-1.586061998,-2.890256606,90.00000001 +258.86,50.43283629,-2.563562852,49.309,-2.48E-11,9.999478012,-2.75875,-1.686941989,-2.943531482,90.00000001 +258.87,50.43283629,-2.563561445,49.3367,7.81E-13,9.999033989,-2.7878125,-1.787469669,-2.994239565,90.00000001 +258.88,50.43283629,-2.563560038,49.3647,2.95E-11,9.999478099,-2.8165625,-1.887624009,-3.042336564,90.00000001 +258.89,50.43283629,-2.56355863,49.3931,3.66E-11,10.00014424,-2.843125,-1.987384212,-3.087780654,90.00000001 +258.9,50.43283629,-2.563557223,49.4216,1.72E-11,10.00036632,-2.868125,-2.086729307,-3.13053213,90.00000001 +258.91,50.43283629,-2.563555815,49.4504,-3.91E-12,10.00036636,-2.8934375,-2.185638667,-3.170553747,90.00000001 +258.92,50.43283629,-2.563554408,49.4795,-7.81E-12,10.00036641,-2.9178125,-2.284091552,-3.207810614,90.00000001 +258.93,50.43283629,-2.563553,49.5088,-1.56E-13,10.00036646,-2.939375,-2.38206745,-3.242270187,90.00000001 +258.94,50.43283629,-2.563551593,49.5383,1.17E-11,10.0003665,-2.9584375,-2.479545905,-3.273902499,90.00000001 +258.95,50.43283629,-2.563550185,49.568,2.58E-11,10.00036655,-2.9765625,-2.576506464,-3.302679877,90.00000001 +258.96,50.43283629,-2.563548778,49.5978,3.05E-11,10.00014456,-2.9946875,-2.672929016,-3.328577283,90.00000001 +258.97,50.43283629,-2.56354737,49.6279,1.64E-11,9.99947851,-3.0115625,-2.768793335,-3.351572085,90.00000001 +258.98,50.43283629,-2.563545963,49.6581,-4.69E-12,9.999034492,-3.02625,-2.864079482,-3.371644286,90.00000001 +258.99,50.43283629,-2.563544556,49.6884,-1.64E-11,9.999478606,-3.0403125,-2.958767461,-3.388776412,90.00000001 +259,50.43283629,-2.563543148,49.7189,-2.11E-11,10.00014475,-3.0546875,-3.052837506,-3.40295345,90.00000001 +259.01,50.43283629,-2.563541741,49.7495,-2.58E-11,10.00036683,-3.0678125,-3.146270077,-3.414163026,90.00000001 +259.02,50.43283629,-2.563540333,49.7803,-2.58E-11,10.00036688,-3.0778125,-3.239045523,-3.422395398,90.00000001 +259.03,50.43283629,-2.563538926,49.8111,-2.11E-11,10.00036693,-3.0846875,-3.331144593,-3.427643462,90.00000001 +259.04,50.43283629,-2.563537518,49.842,-1.64E-11,10.00036698,-3.0903125,-3.422547919,-3.42990252,90.00000001 +259.05,50.43283629,-2.563536111,49.8729,-7.03E-12,10.00036703,-3.0965625,-3.513236539,-3.429170624,90.00000001 +259.06,50.43283629,-2.563534703,49.9039,4.69E-12,10.00036707,-3.103125,-3.603191485,-3.425448518,90.00000001 +259.07,50.43283629,-2.563533296,49.935,7.03E-12,10.00036712,-3.1078125,-3.692393909,-3.418739297,90.00000001 +259.08,50.43283629,-2.563531888,49.9661,2.34E-12,10.00036717,-3.1096875,-3.780825247,-3.409048919,90.00000001 +259.09,50.43283629,-2.563530481,49.9972,2.34E-12,10.00014519,-3.1096875,-3.868466991,-3.396385807,90.00000001 +259.1,50.43283629,-2.563529073,50.0283,9.38E-12,9.999479137,-3.108125,-3.955300865,-3.380760961,90.00000001 +259.11,50.43283629,-2.563527666,50.0594,1.41E-11,9.99903512,-3.105,-4.041308763,-3.362188076,90.00000001 +259.12,50.43283629,-2.563526259,50.0904,7.03E-12,9.999479235,-3.1015625,-4.126472636,-3.340683309,90.00000001 +259.13,50.43283629,-2.563524851,50.1214,-7.03E-12,10.00014538,-3.0984375,-4.210774782,-3.316265394,90.00000001 +259.14,50.43283629,-2.563523444,50.1524,-1.88E-11,10.00036746,-3.094375,-4.294197551,-3.288955647,90.00000001 +259.15,50.43283629,-2.563522036,50.1833,-2.58E-11,10.00036751,-3.0878125,-4.376723527,-3.258777903,90.00000001 +259.16,50.43283629,-2.563520629,50.2142,-2.34E-11,10.00036756,-3.078125,-4.458335464,-3.22575846,90.00000001 +259.17,50.43283629,-2.563519221,50.2449,-1.17E-11,10.00036761,-3.0665625,-4.539016344,-3.189926081,90.00000001 +259.18,50.43283629,-2.563517814,50.2755,-4.69E-12,10.00036766,-3.055,-4.618749322,-3.151312048,90.00000001 +259.19,50.43283629,-2.563516406,50.306,-9.38E-12,10.0003677,-3.043125,-4.697517727,-3.109950053,90.00000001 +259.2,50.43283629,-2.563514999,50.3364,-1.64E-11,10.00036775,-3.0296875,-4.775305112,-3.065876077,90.00000001 +259.21,50.43283629,-2.563513591,50.3666,-1.64E-11,10.0003678,-3.0146875,-4.852095208,-3.01912868,90.00000001 +259.22,50.43283629,-2.563512184,50.3967,-7.03E-12,10.00014581,-2.9984375,-4.927872028,-2.969748484,90.00000001 +259.23,50.43283629,-2.563510776,50.4266,9.37E-12,9.999479759,-2.98125,-5.002619758,-2.917778691,90.00000001 +259.24,50.43283629,-2.563509369,50.4563,2.34E-11,9.99903574,-2.963125,-5.076322699,-2.863264507,90.00000001 +259.25,50.43283629,-2.563507962,50.4859,2.34E-11,9.999479853,-2.943125,-5.148965555,-2.806253545,90.00000001 +259.26,50.43283629,-2.563506554,50.5152,9.22E-12,10.000146,-2.92125,-5.220533083,-2.74679548,90.00000001 +259.27,50.43283629,-2.563505147,50.5443,-5.47E-12,10.00036808,-2.898125,-5.291010386,-2.684942165,90.00000001 +259.28,50.43283629,-2.563503739,50.5732,-6.25E-12,10.00036812,-2.873125,-5.360382741,-2.620747515,90.00000001 +259.29,50.43283629,-2.563502332,50.6018,5.47E-12,10.00014613,-2.8465625,-5.428635651,-2.554267566,90.00000001 +259.3,50.43283629,-2.563500924,50.6301,1.31E-11,9.999480079,-2.82,-5.495754849,-2.485560243,90.00000001 +259.31,50.43283629,-2.563499517,50.6582,8.44E-12,9.999036056,-2.793125,-5.561726356,-2.414685479,90.00000001 +259.32,50.43283629,-2.56349811,50.686,7.81E-13,9.999480165,-2.7646875,-5.626536305,-2.341705094,90.00000001 +259.33,50.43283629,-2.563496702,50.7135,-1.41E-12,10.00014631,-2.735,-5.690171289,-2.266682688,90.00000001 +259.34,50.43283629,-2.563495295,50.7407,-2.34E-12,10.00036838,-2.7046875,-5.752617902,-2.189683692,90.00000001 +259.35,50.43283629,-2.563493887,50.7676,-5.47E-12,10.00036843,-2.6728125,-5.813863194,-2.110775257,90.00000001 +259.36,50.43283629,-2.56349248,50.7942,-2.34E-12,10.00014643,-2.638125,-5.873894332,-2.030026195,90.00000001 +259.37,50.43283629,-2.563491072,50.8204,7.19E-12,9.999480376,-2.601875,-5.932698766,-1.947506922,90.00000001 +259.38,50.43283629,-2.563489665,50.8462,4.84E-12,9.99903635,-2.5665625,-5.990264237,-1.863289403,90.00000001 +259.39,50.43283629,-2.563488258,50.8717,-1.16E-11,9.999480457,-2.53125,-6.046578712,-1.77744709,90.00000001 +259.4,50.43283629,-2.56348685,50.8969,-1.64E-11,10.0001466,-2.493125,-6.101630445,-1.690054754,90.00000001 +259.41,50.43283629,-2.563485443,50.9216,1.56E-12,10.00036867,-2.453125,-6.15540792,-1.601188714,90.00000001 +259.42,50.43283629,-2.563484035,50.9459,2.11E-11,10.0003687,-2.4134375,-6.207899906,-1.510926432,90.00000001 +259.43,50.43283629,-2.563482628,50.9699,2.44E-11,10.00014671,-2.3728125,-6.259095462,-1.419346577,90.00000001 +259.44,50.43283629,-2.56348122,50.9934,1.95E-11,9.999480647,-2.3296875,-6.308983928,-1.326529019,90.00000001 +259.45,50.43283629,-2.563479813,51.0165,1.55E-11,9.999036617,-2.2853125,-6.357554821,-1.232554716,90.00000001 +259.46,50.43283629,-2.563478406,51.0391,6.09E-12,9.999480718,-2.2415625,-6.404797999,-1.137505601,90.00000001 +259.47,50.43283629,-2.563476998,51.0613,-6.25E-12,10.00014685,-2.198125,-6.450703606,-1.041464582,90.00000001 +259.48,50.43283629,-2.563475591,51.0831,-8.59E-12,10.00036892,-2.1528125,-6.495262076,-0.944515368,90.00000001 +259.49,50.43283629,-2.563474183,51.1044,-3.13E-12,10.00036895,-2.1046875,-6.538464125,-0.846742526,90.00000001 +259.5,50.43283629,-2.563472776,51.1252,2.19E-12,10.00014695,-2.0553125,-6.580300643,-0.748231314,90.00000001 +259.51,50.43283629,-2.563471368,51.1455,1.19E-11,9.999480884,-2.0065625,-6.62076298,-0.649067618,90.00000001 +259.52,50.43283629,-2.563469961,51.1653,2.42E-11,9.999036849,-1.958125,-6.659842713,-0.549337954,90.00000001 +259.53,50.43283629,-2.563468554,51.1847,2.50E-11,9.999480946,-1.908125,-6.697531533,-0.44912924,90.00000001 +259.54,50.43283629,-2.563467146,51.2035,1.09E-11,10.00014707,-1.85625,-6.733821705,-0.348528909,90.00000001 +259.55,50.43283629,-2.563465739,51.2218,-6.09E-12,10.00036914,-1.8034375,-6.76870561,-0.247624624,90.00000001 +259.56,50.43283629,-2.563464331,51.2396,-1.31E-11,10.00036916,-1.75,-6.802175914,-0.146504449,90.00000001 +259.57,50.43283629,-2.563462924,51.2568,-5.31E-12,10.00036919,-1.6965625,-6.834225741,-0.045256447,90.00000001 +259.58,50.43283629,-2.563461516,51.2735,7.03E-12,10.00036922,-1.643125,-6.864848272,0.056030975,90.00000001 +259.59,50.43283629,-2.563460109,51.2897,7.19E-12,10.00036924,-1.588125,-6.894037149,0.157269524,90.00000001 +259.6,50.43283629,-2.563458701,51.3053,-4.53E-12,10.00036927,-1.5315625,-6.921786354,0.258370963,90.00000001 +259.61,50.43283629,-2.563457294,51.3203,-1.16E-11,10.00014726,-1.475,-6.948089987,0.359247059,90.00000001 +259.62,50.43283629,-2.563455886,51.3348,-4.69E-12,9.999481181,-1.4184375,-6.972942662,0.459809918,90.00000001 +259.63,50.43283629,-2.563454479,51.3487,1.11E-11,9.999037136,-1.36125,-6.99633905,0.559971821,90.00000001 +259.64,50.43283629,-2.563453072,51.362,2.42E-11,9.999481223,-1.303125,-7.018274395,0.659645393,90.00000001 +259.65,50.43283629,-2.563451664,51.3748,2.11E-11,10.00014734,-1.2434375,-7.038744057,0.758743772,90.00000001 +259.66,50.43283629,-2.563450257,51.3869,-7.81E-13,10.00036939,-1.183125,-7.057743739,0.857180499,90.00000001 +259.67,50.43283629,-2.563448849,51.3984,-2.50E-11,10.00036941,-1.12375,-7.075269486,0.954869746,90.00000001 +259.68,50.43283629,-2.563447442,51.4094,-3.69E-11,10.00036943,-1.0646875,-7.09131769,1.051726313,90.00000001 +259.69,50.43283629,-2.563446034,51.4197,-3.67E-11,10.00036945,-1.0046875,-7.10588497,1.147665804,90.00000001 +259.7,50.43283629,-2.563444627,51.4295,-2.75E-11,10.00036946,-0.9434375,-7.11896829,1.24260451,90.00000001 +259.71,50.43283629,-2.563443219,51.4386,-1.09E-11,10.00036947,-0.88125,-7.130564841,1.336459638,90.00000001 +259.72,50.43283629,-2.563441812,51.4471,6.09E-12,10.00036949,-0.8184375,-7.140672332,1.429149369,90.00000001 +259.73,50.43283629,-2.563440404,51.455,1.31E-11,10.0003695,-0.755,-7.149288529,1.520592803,90.00000001 +259.74,50.43283629,-2.563438997,51.4622,7.66E-12,10.00014748,-0.691875,-7.156411769,1.610710298,90.00000001 +259.75,50.43283629,-2.563437589,51.4688,2.34E-12,9.99948139,-0.63,-7.162040392,1.699423244,90.00000001 +259.76,50.43283629,-2.563436182,51.4748,6.88E-12,9.999037333,-0.568125,-7.166173366,1.786654235,90.00000001 +259.77,50.43283629,-2.563434775,51.4802,1.39E-11,9.999481408,-0.5046875,-7.168809774,1.872327239,90.00000001 +259.78,50.43283629,-2.563433367,51.4849,1.63E-11,10.00014751,-0.44,-7.169949043,1.9563676,90.00000001 +259.79,50.43283629,-2.56343196,51.489,1.41E-11,10.00036955,-0.3753125,-7.169591002,2.038701922,90.00000001 +259.8,50.43283629,-2.563430552,51.4924,5.31E-12,10.00036956,-0.3115625,-7.16773565,2.11925847,90.00000001 +259.81,50.43283629,-2.563429145,51.4952,-7.81E-12,10.00036956,-0.2484375,-7.164383388,2.197967,90.00000001 +259.82,50.43283629,-2.563427737,51.4974,-1.66E-11,10.00036957,-0.1846875,-7.159534962,2.274758872,90.00000001 +259.83,50.43283629,-2.56342633,51.4989,-1.88E-11,10.00036957,-0.12,-7.153191403,2.349567106,90.00000001 +259.84,50.43283629,-2.563424922,51.4998,-1.87E-11,10.00036957,-0.055,-7.145353913,2.422326501,90.00000001 +259.85,50.43283629,-2.563423515,51.5,-1.87E-11,10.00036957,0.01,-7.136024269,2.492973629,90.00000001 +259.86,50.43283629,-2.563422107,51.4996,-1.87E-11,10.00036957,0.075,-7.125204305,2.561446784,90.00000001 +259.87,50.43283629,-2.5634207,51.4985,-2.11E-11,10.00014754,0.1396875,-7.112896369,2.627686378,90.00000001 +259.88,50.43283629,-2.563419292,51.4968,-3.06E-11,9.999481434,0.2034375,-7.099102983,2.691634541,90.00000001 +259.89,50.43283629,-2.563417885,51.4944,-4.30E-11,9.999037363,0.266875,-7.083827069,2.753235583,90.00000001 +259.9,50.43283629,-2.563416478,51.4915,-4.16E-11,9.999481425,0.3315625,-7.067071721,2.812435759,90.00000001 +259.91,50.43283629,-2.56341507,51.4878,-2.34E-11,10.00014752,0.3965625,-7.048840547,2.869183447,90.00000001 +259.92,50.43283629,-2.563413663,51.4835,-9.53E-12,10.00036955,0.4596875,-7.029137331,2.923429143,90.00000001 +259.93,50.43283629,-2.563412255,51.4786,-1.19E-11,10.00036954,0.521875,-7.007966139,2.975125578,90.00000001 +259.94,50.43283629,-2.563410848,51.4731,-1.89E-11,10.00036953,0.5853125,-6.985331442,3.02422766,90.00000001 +259.95,50.43283629,-2.56340944,51.4669,-2.34E-11,10.00036952,0.6496875,-6.961237936,3.070692589,90.00000001 +259.96,50.43283629,-2.563408033,51.4601,-2.98E-11,10.00036951,0.713125,-6.935690722,3.1144798,90.00000001 +259.97,50.43283629,-2.563406625,51.4526,-3.36E-11,10.0003695,0.775,-6.908695013,3.155551134,90.00000001 +259.98,50.43283629,-2.563405218,51.4446,-2.59E-11,10.00014745,0.8365625,-6.88025654,3.193870838,90.00000001 +259.99,50.43283629,-2.56340381,51.4359,-9.38E-12,9.999481338,0.89875,-6.850381202,3.229405394,90.00000001 +260,50.43283629,-2.563402403,51.4266,9.37E-12,9.999037258,0.96125,-6.819075247,3.262123862,90.00000001 +260.01,50.43283629,-2.563400996,51.4167,2.34E-11,9.999481309,1.023125,-6.786345205,3.29199771,90.00000001 +260.02,50.43283629,-2.563399588,51.4061,2.34E-11,10.00014739,1.083125,-6.752197894,3.319000867,90.00000001 +260.03,50.43283629,-2.563398181,51.395,1.41E-11,10.00036941,1.141875,-6.716640535,3.343109842,90.00000001 +260.04,50.43283629,-2.563396773,51.3833,1.39E-11,10.00036939,1.201875,-6.67968046,3.364303551,90.00000001 +260.05,50.43283629,-2.563395366,51.371,2.03E-11,10.00036937,1.2628125,-6.641325462,3.382563544,90.00000001 +260.06,50.43283629,-2.563393958,51.358,1.00E-11,10.00036935,1.3215625,-6.601583447,3.397873893,90.00000001 +260.07,50.43283629,-2.563392551,51.3445,-1.64E-11,10.00014729,1.378125,-6.560462782,3.410221305,90.00000001 +260.08,50.43283629,-2.563391143,51.3305,-3.30E-11,9.999481173,1.4353125,-6.51797206,3.419594895,90.00000001 +260.09,50.43283629,-2.563389736,51.3158,-3.06E-11,9.999037084,1.493125,-6.474120162,3.425986526,90.00000001 +260.1,50.43283629,-2.563388329,51.3006,-2.36E-11,9.999481127,1.5496875,-6.428916256,3.429390697,90.00000001 +260.11,50.43283629,-2.563386921,51.2848,-2.11E-11,10.0001472,1.605,-6.38236968,3.429804315,90.00000001 +260.12,50.43283629,-2.563385514,51.2685,-1.80E-11,10.00036921,1.6596875,-6.33449029,3.427227151,90.00000001 +260.13,50.43283629,-2.563384106,51.2516,-7.03E-12,10.00036918,1.7134375,-6.285287998,3.421661382,90.00000001 +260.14,50.43283629,-2.563382699,51.2342,1.08E-11,10.00014712,1.76625,-6.234773059,3.413111877,90.00000001 +260.15,50.43283629,-2.563381291,51.2163,2.73E-11,9.999480995,1.8184375,-6.182956131,3.401586087,90.00000001 +260.16,50.43283629,-2.563379884,51.1978,3.36E-11,9.9990369,1.87,-6.129847929,3.387094036,90.00000001 +260.17,50.43283629,-2.563378477,51.1789,2.59E-11,9.999480936,1.9215625,-6.075459623,3.369648445,90.00000001 +260.18,50.43283629,-2.563377069,51.1594,1.41E-11,10.00014701,1.973125,-6.019802503,3.34926444,90.00000001 +260.19,50.43283629,-2.563375662,51.1394,1.41E-11,10.00036901,2.023125,-5.962888256,3.32595984,90.00000001 +260.2,50.43283629,-2.563374254,51.1189,2.58E-11,10.00036898,2.0715625,-5.904728743,3.299754928,90.00000001 +260.21,50.43283629,-2.563372847,51.098,3.05E-11,10.00014691,2.1196875,-5.845336052,3.270672564,90.00000001 +260.22,50.43283629,-2.563371439,51.0765,1.63E-11,9.999480777,2.1665625,-5.784722675,3.238738189,90.00000001 +260.23,50.43283629,-2.563370032,51.0546,-5.47E-12,9.999036676,2.21125,-5.722901217,3.203979532,90.00000001 +260.24,50.43283629,-2.563368625,51.0323,-1.56E-11,9.999480707,2.255,-5.659884626,3.166426961,90.00000001 +260.25,50.43283629,-2.563367217,51.0095,-8.44E-12,10.00014677,2.2984375,-5.595686022,3.12611325,90.00000001 +260.26,50.43283629,-2.56336581,50.9863,7.03E-12,10.00036877,2.3415625,-5.530318815,3.08307352,90.00000001 +260.27,50.43283629,-2.563364402,50.9627,1.31E-11,10.00036873,2.3846875,-5.463796696,3.037345242,90.00000001 +260.28,50.43283629,-2.563362995,50.9386,-9.38E-13,10.00036869,2.4265625,-5.396133531,2.98896841,90.00000001 +260.29,50.43283629,-2.563361587,50.9141,-2.34E-11,10.00036865,2.46625,-5.327343474,2.937985136,90.00000001 +260.3,50.43283629,-2.56336018,50.8893,-3.20E-11,10.00014658,2.5046875,-5.257440846,2.884439938,90.00000001 +260.31,50.43283629,-2.563358772,50.864,-1.86E-11,9.999480445,2.5415625,-5.18644026,2.828379399,90.00000001 +260.32,50.43283629,-2.563357365,50.8384,7.81E-13,9.999036338,2.5765625,-5.114356555,2.769852505,90.00000001 +260.33,50.43283629,-2.563355958,50.8125,4.69E-12,9.999480363,2.611875,-5.041204798,2.70891025,90.00000001 +260.34,50.43283629,-2.56335455,50.7862,-3.12E-12,10.00014642,2.648125,-4.967000232,2.645605805,90.00000001 +260.35,50.43283629,-2.563353143,50.7595,-4.69E-12,10.00036841,2.6828125,-4.891758383,2.579994345,90.00000001 +260.36,50.43283629,-2.563351735,50.7325,6.25E-23,10.00036837,2.7146875,-4.815494951,2.512133052,90.00000001 +260.37,50.43283629,-2.563350328,50.7052,-6.25E-13,10.00014629,2.7446875,-4.738225862,2.442081169,90.00000001 +260.38,50.43283629,-2.56334892,50.6776,-1.08E-11,9.999480152,2.7734375,-4.659967276,2.369899774,90.00000001 +260.39,50.43283629,-2.563347513,50.6497,-2.48E-11,9.999036043,2.8015625,-4.580735463,2.295651778,90.00000001 +260.4,50.43283629,-2.563346106,50.6216,-2.89E-11,9.999480065,2.8296875,-4.500547041,2.219401924,90.00000001 +260.41,50.43283629,-2.563344698,50.5931,-1.48E-11,10.00014612,2.8565625,-4.419418795,2.141216734,90.00000001 +260.42,50.43283629,-2.563343291,50.5644,5.47E-12,10.00036811,2.88125,-4.337367515,2.061164388,90.00000001 +260.43,50.43283629,-2.563341883,50.5355,1.19E-11,10.00036806,2.9046875,-4.254410502,1.979314674,90.00000001 +260.44,50.43283629,-2.563340476,50.5063,-2.34E-12,10.00036802,2.9265625,-4.170565005,1.895738925,90.00000001 +260.45,50.43283629,-2.563339068,50.4769,-2.11E-11,10.00036797,2.9465625,-4.085848496,1.810510078,90.00000001 +260.46,50.43283629,-2.563337661,50.4474,-2.11E-11,10.00036792,2.9665625,-4.000278739,1.723702503,90.00000001 +260.47,50.43283629,-2.563336253,50.4176,-2.34E-12,10.00036788,2.9865625,-3.91387361,1.635391773,90.00000001 +260.48,50.43283629,-2.563334846,50.3876,1.41E-11,10.00036783,3.004375,-3.826651042,1.545654951,90.00000001 +260.49,50.43283629,-2.563333438,50.3575,1.88E-11,10.00036778,3.02,-3.738629369,1.454570304,90.00000001 +260.5,50.43283629,-2.563332031,50.3272,2.11E-11,10.0001457,3.0346875,-3.649826927,1.362217242,90.00000001 +260.51,50.43283629,-2.563330623,50.2968,2.81E-11,9.999479557,3.048125,-3.560262279,1.268676324,90.00000001 +260.52,50.43283629,-2.563329216,50.2662,3.52E-11,9.999035443,3.0596875,-3.469954104,1.17402914,90.00000001 +260.53,50.43283629,-2.563327809,50.2356,3.75E-11,9.999479462,3.07,-3.378921309,1.078358137,90.00000001 +260.54,50.43283629,-2.563326401,50.2048,3.98E-11,10.00014551,3.0796875,-3.287182801,0.981746795,90.00000001 +260.55,50.43283629,-2.563324994,50.174,4.69E-11,10.0003675,3.088125,-3.194757834,0.884279341,90.00000001 +260.56,50.43283629,-2.563323586,50.143,5.16E-11,10.00036745,3.095,-3.101665714,0.786040799,90.00000001 +260.57,50.43283629,-2.563322179,50.1121,4.22E-11,10.0003674,3.10125,-3.007925808,0.687116828,90.00000001 +260.58,50.43283629,-2.563320771,50.081,2.11E-11,10.00036735,3.1065625,-2.913557768,0.587593658,90.00000001 +260.59,50.43283629,-2.563319364,50.0499,2.34E-12,10.0003673,3.1090625,-2.818581247,0.487558092,90.00000001 +260.6,50.43283629,-2.563317956,50.0188,-1.17E-11,10.00036725,3.1084375,-2.723016127,0.387097391,90.00000001 +260.61,50.43283629,-2.563316549,49.9877,-2.34E-11,10.00036721,3.106875,-2.626882289,0.286299161,90.00000001 +260.62,50.43283629,-2.563315141,49.9567,-2.11E-11,10.00036716,3.1065625,-2.530199901,0.185251235,90.00000001 +260.63,50.43283629,-2.563313734,49.9256,-4.69E-12,10.00014507,3.10625,-2.432989131,0.084041736,90.00000001 +260.64,50.43283629,-2.563312326,49.8945,2.34E-12,9.999478927,3.1028125,-2.335270205,-0.017240988,90.00000001 +260.65,50.43283629,-2.563310919,49.8635,-7.03E-12,9.999034813,3.0965625,-2.237063635,-0.1185087,90.00000001 +260.66,50.43283629,-2.563309512,49.8326,-1.41E-11,9.999478831,3.09,-2.138389874,-0.21967305,90.00000001 +260.67,50.43283629,-2.563308104,49.8017,-1.17E-11,10.00014488,3.0828125,-2.039269551,-0.320645861,90.00000001 +260.68,50.43283629,-2.563306697,49.7709,-1.41E-11,10.00036687,3.073125,-1.939723291,-0.421339068,90.00000001 +260.69,50.43283629,-2.563305289,49.7402,-2.58E-11,10.00036682,3.0615625,-1.839772007,-0.521664894,90.00000001 +260.7,50.43283629,-2.563303882,49.7097,-3.05E-11,10.00036677,3.0496875,-1.739436497,-0.621535793,90.00000001 +260.71,50.43283629,-2.563302474,49.6792,-1.64E-11,10.00036672,3.0365625,-1.638737732,-0.720864673,90.00000001 +260.72,50.43283629,-2.563301067,49.6489,2.34E-12,10.00036668,3.0215625,-1.537696682,-0.819564961,90.00000001 +260.73,50.43283629,-2.563299659,49.6188,2.34E-12,10.00036663,3.0065625,-1.436334547,-0.917550599,90.00000001 +260.74,50.43283629,-2.563298252,49.5888,-1.41E-11,10.00036658,2.99125,-1.334672468,-1.014736101,90.00000001 +260.75,50.43283629,-2.563296844,49.5589,-2.11E-11,10.00036654,2.9728125,-1.232731645,-1.111036727,90.00000001 +260.76,50.43283629,-2.563295437,49.5293,-1.16E-11,10.00014446,2.9515625,-1.130533392,-1.206368539,90.00000001 +260.77,50.43283629,-2.563294029,49.4999,-1.56E-12,9.99947831,2.9303125,-1.028099024,-1.300648401,90.00000001 +260.78,50.43283629,-2.563292622,49.4707,3.91E-12,9.999034199,2.9096875,-0.925449968,-1.393794035,90.00000001 +260.79,50.43283629,-2.563291215,49.4417,8.59E-12,9.99947822,2.8878125,-0.822607596,-1.485724253,90.00000001 +260.8,50.43283629,-2.563289807,49.4129,7.81E-12,10.00014427,2.8628125,-0.719593509,-1.5763589,90.00000001 +260.81,50.43283629,-2.5632884,49.3844,4.69E-12,10.00036626,2.835,-0.616429077,-1.665618964,90.00000001 +260.82,50.43283629,-2.563286992,49.3562,8.59E-12,10.00036622,2.806875,-0.513135959,-1.753426579,90.00000001 +260.83,50.43283629,-2.563285585,49.3283,1.02E-11,10.00036617,2.7796875,-0.409735641,-1.8397052,90.00000001 +260.84,50.43283629,-2.563284177,49.3006,-1.41E-12,10.00036613,2.75125,-0.30624978,-1.924379538,90.00000001 +260.85,50.43283629,-2.56328277,49.2732,-1.17E-11,10.00014405,2.7196875,-0.202699977,-2.007375798,90.00000001 +260.86,50.43283629,-2.563281362,49.2462,-7.81E-12,9.999477914,2.686875,-0.099107833,-2.088621557,90.00000001 +260.87,50.43283629,-2.563279955,49.2195,-4.69E-12,9.999033806,2.6546875,0.004505053,-2.168046055,90.00000001 +260.88,50.43283629,-2.563278548,49.1931,-1.86E-11,9.999477831,2.6215625,0.108116964,-2.245579965,90.00000001 +260.89,50.43283629,-2.56327714,49.167,-3.97E-11,10.00014389,2.58625,0.211706301,-2.321155733,90.00000001 +260.9,50.43283629,-2.563275733,49.1414,-4.67E-11,10.00036588,2.5496875,0.315251406,-2.394707414,90.00000001 +260.91,50.43283629,-2.563274325,49.116,-3.03E-11,10.00036584,2.511875,0.418730677,-2.466170836,90.00000001 +260.92,50.43283629,-2.563272918,49.0911,1.57E-13,10.00014377,2.4728125,0.522122516,-2.535483717,90.00000001 +260.93,50.43283629,-2.56327151,49.0666,2.34E-11,9.999477633,2.4334375,0.62540532,-2.60258567,90.00000001 +260.94,50.43283629,-2.563270103,49.0424,2.52E-11,9.999033529,2.393125,0.728557548,-2.667418079,90.00000001 +260.95,50.43283629,-2.563268696,49.0187,1.03E-11,9.999477558,2.35125,0.83155754,-2.729924451,90.00000001 +260.96,50.43283629,-2.563267288,48.9954,-6.09E-12,10.00014362,2.3084375,0.934383927,-2.790050356,90.00000001 +260.97,50.43283629,-2.563265881,48.9725,-1.25E-11,10.00036562,2.265,1.037015164,-2.847743252,90.00000001 +260.98,50.43283629,-2.563264473,48.9501,-3.12E-12,10.00036558,2.22125,1.13942988,-2.902952835,90.00000001 +260.99,50.43283629,-2.563263066,48.9281,1.72E-11,10.00014352,2.1765625,1.241606589,-2.955631033,90.00000001 +261,50.43283629,-2.563261658,48.9065,3.06E-11,9.999477383,2.1296875,1.343524036,-3.005731895,90.00000001 +261.01,50.43283629,-2.563260251,48.8855,2.58E-11,9.999033284,2.0815625,1.445160904,-3.053211704,90.00000001 +261.02,50.43283629,-2.563258844,48.8649,1.41E-11,9.999477317,2.033125,1.546495939,-3.098029093,90.00000001 +261.03,50.43283629,-2.563257436,48.8448,1.41E-11,10.00014338,1.983125,1.647507997,-3.140144929,90.00000001 +261.04,50.43283629,-2.563256029,48.8252,2.36E-11,10.00036539,1.931875,1.748176051,-3.179522485,90.00000001 +261.05,50.43283629,-2.563254621,48.8062,2.19E-11,10.00036536,1.8815625,1.84847896,-3.216127498,90.00000001 +261.06,50.43283629,-2.563253214,48.7876,3.91E-12,10.00036533,1.8315625,1.948395866,-3.249927997,90.00000001 +261.07,50.43283629,-2.563251806,48.7695,-1.27E-11,10.0003653,1.779375,2.047905916,-3.280894475,90.00000001 +261.08,50.43283629,-2.563250399,48.752,-1.88E-11,10.00014324,1.725,2.146988195,-3.308999946,90.00000001 +261.09,50.43283629,-2.563248991,48.735,-2.03E-11,9.999477114,1.67,2.245622192,-3.334220001,90.00000001 +261.1,50.43283629,-2.563247584,48.7186,-2.11E-11,9.999033022,1.615,2.343787165,-3.356532524,90.00000001 +261.11,50.43283629,-2.563246177,48.7027,-2.13E-11,9.999477063,1.56,2.441462718,-3.375918093,90.00000001 +261.12,50.43283629,-2.563244769,48.6874,-1.89E-11,10.00014314,1.5046875,2.538628339,-3.392359804,90.00000001 +261.13,50.43283629,-2.563243362,48.6726,-9.53E-12,10.00036515,1.4484375,2.635263859,-3.405843335,90.00000001 +261.14,50.43283629,-2.563241954,48.6584,7.03E-12,10.00036513,1.39125,2.731348996,-3.416356938,90.00000001 +261.15,50.43283629,-2.563240547,48.6448,2.41E-11,10.00014307,1.3334375,2.826863753,-3.423891391,90.00000001 +261.16,50.43283629,-2.563239139,48.6317,3.44E-11,9.999476952,1.2746875,2.921788135,-3.42844016,90.00000001 +261.17,50.43283629,-2.563237732,48.6193,3.73E-11,9.999032867,1.215,3.016102317,-3.42999935,90.00000001 +261.18,50.43283629,-2.563236325,48.6074,3.75E-11,9.999476915,1.155,3.109786646,-3.428567471,90.00000001 +261.19,50.43283629,-2.563234917,48.5962,3.75E-11,10.000143,1.095,3.202821584,-3.424145841,90.00000001 +261.2,50.43283629,-2.56323351,48.5855,3.75E-11,10.00036501,1.035,3.295187595,-3.416738299,90.00000001 +261.21,50.43283629,-2.563232102,48.5755,3.52E-11,10.000365,0.9746875,3.386865483,-3.406351319,90.00000001 +261.22,50.43283629,-2.563230695,48.566,2.58E-11,10.00036498,0.9134375,3.477836055,-3.392993897,90.00000001 +261.23,50.43283629,-2.563229287,48.5572,9.22E-12,10.00036497,0.85125,3.568080288,-3.376677778,90.00000001 +261.24,50.43283629,-2.56322788,48.549,-7.81E-12,10.00036496,0.7884375,3.657579447,-3.357417171,90.00000001 +261.25,50.43283629,-2.563226472,48.5414,-1.56E-11,10.00036494,0.725,3.746314681,-3.335228808,90.00000001 +261.26,50.43283629,-2.563225065,48.5345,-1.08E-11,10.0001429,0.661875,3.834267599,-3.31013211,90.00000001 +261.27,50.43283629,-2.563223657,48.5282,-4.84E-12,9.999476791,0.6,3.921419808,-3.282148909,90.00000001 +261.28,50.43283629,-2.56322225,48.5225,-6.41E-12,9.999032716,0.5378125,4.007753031,-3.251303611,90.00000001 +261.29,50.43283629,-2.563220843,48.5174,-2.50E-12,9.999476773,0.4734375,4.093249278,-3.217623147,90.00000001 +261.3,50.43283629,-2.563219435,48.513,1.50E-11,10.00014287,0.4084375,4.177890728,-3.181136851,90.00000001 +261.31,50.43283629,-2.563218028,48.5093,2.67E-11,10.00036489,0.345,4.261659679,-3.141876579,90.00000001 +261.32,50.43283629,-2.56321662,48.5061,1.64E-11,10.00036489,0.2815625,4.344538654,-3.099876538,90.00000001 +261.33,50.43283629,-2.563215213,48.5036,-9.38E-13,10.00036488,0.2165625,4.426510294,-3.05517334,90.00000001 +261.34,50.43283629,-2.563213805,48.5018,-3.13E-12,10.00036488,0.151875,4.507557523,-3.007806002,90.00000001 +261.35,50.43283629,-2.563212398,48.5006,5.47E-12,10.00036488,0.088125,4.587663383,-2.957815836,90.00000001 +261.36,50.43283629,-2.56321099,48.5,2.50E-12,10.00036488,0.0234375,4.666811199,-2.905246385,90.00000001 +261.37,50.43283629,-2.563209583,48.5001,-1.89E-11,10.00036488,-0.041875,4.744984415,-2.850143487,90.00000001 +261.38,50.43283629,-2.563208175,48.5009,-4.30E-11,10.00036488,-0.10625,4.8221667,-2.79255527,90.00000001 +261.39,50.43283629,-2.563206768,48.5022,-5.31E-11,10.00014285,-0.17,4.898341955,-2.732531867,90.00000001 +261.4,50.43283629,-2.56320536,48.5043,-4.36E-11,9.999476754,-0.23375,4.973494193,-2.670125705,90.00000001 +261.41,50.43283629,-2.563203953,48.5069,-1.87E-11,9.999032692,-0.298125,5.047607831,-2.6053911,90.00000001 +261.42,50.43283629,-2.563202546,48.5102,3.91E-12,9.999476762,-0.3634375,5.120667341,-2.538384603,90.00000001 +261.43,50.43283629,-2.563201138,48.5142,9.37E-12,10.00014287,-0.4278125,5.192657425,-2.46916454,90.00000001 +261.44,50.43283629,-2.563199731,48.5188,7.19E-12,10.00036491,-0.49,5.26356313,-2.39779136,90.00000001 +261.45,50.43283629,-2.563198323,48.524,1.17E-11,10.00036492,-0.551875,5.333369557,-2.324327284,90.00000001 +261.46,50.43283629,-2.563196916,48.5298,1.80E-11,10.00036492,-0.6153125,5.402062212,-2.248836313,90.00000001 +261.47,50.43283629,-2.563195508,48.5363,1.87E-11,10.00036493,-0.68,5.469626713,-2.171384394,90.00000001 +261.48,50.43283629,-2.563194101,48.5434,1.27E-11,10.00036495,-0.744375,5.536048966,-2.092038964,90.00000001 +261.49,50.43283629,-2.563192693,48.5512,-3.91E-12,10.00036496,-0.8065625,5.601315104,-2.010869236,90.00000001 +261.5,50.43283629,-2.563191286,48.5596,-1.95E-11,10.00036497,-0.866875,5.665411434,-1.927945971,90.00000001 +261.51,50.43283629,-2.563189878,48.5685,-1.19E-11,10.00036499,-0.9284375,5.728324663,-1.843341534,90.00000001 +261.52,50.43283629,-2.563188471,48.5781,1.17E-11,10.00014297,-0.9915625,5.790041557,-1.75712972,90.00000001 +261.53,50.43283629,-2.563187063,48.5884,2.11E-11,9.999476885,-1.0528125,5.850549281,-1.669385588,90.00000001 +261.54,50.43283629,-2.563185656,48.5992,1.19E-11,9.999032836,-1.1115625,5.909835229,-1.5801858,90.00000001 +261.55,50.43283629,-2.563184249,48.6106,3.12E-12,9.999476919,-1.1703125,5.967886912,-1.489607991,90.00000001 +261.56,50.43283629,-2.563182841,48.6226,1.56E-12,10.00014304,-1.23,6.024692354,-1.397731286,90.00000001 +261.57,50.43283629,-2.563181434,48.6352,1.41E-12,10.00036509,-1.29,6.080239581,-1.304635728,90.00000001 +261.58,50.43283629,-2.563180026,48.6484,-2.34E-12,10.00036511,-1.3496875,6.134517019,-1.210402448,90.00000001 +261.59,50.43283629,-2.563178619,48.6622,-1.09E-11,10.00036513,-1.408125,6.18751338,-1.115113723,90.00000001 +261.6,50.43283629,-2.563177211,48.6766,-1.87E-11,10.00036515,-1.4646875,6.239217493,-1.018852631,90.00000001 +261.61,50.43283629,-2.563175804,48.6915,-2.12E-11,10.00036518,-1.52,6.289618699,-0.921703053,90.00000001 +261.62,50.43283629,-2.563174396,48.707,-2.12E-11,10.0003652,-1.575,6.338706343,-0.82374973,90.00000001 +261.63,50.43283629,-2.563172989,48.723,-2.12E-11,10.00014319,-1.63,6.386470282,-0.72507809,90.00000001 +261.64,50.43283629,-2.563171581,48.7396,-2.11E-11,9.999477121,-1.685,6.432900432,-0.625774191,90.00000001 +261.65,50.43283629,-2.563170174,48.7567,-1.81E-11,9.999033083,-1.7396875,6.477987169,-0.525924606,90.00000001 +261.66,50.43283629,-2.563168767,48.7744,-1.02E-11,9.999477176,-1.793125,6.521721095,-0.42561637,90.00000001 +261.67,50.43283629,-2.563167359,48.7926,-4.84E-12,10.0001433,-1.845,6.564093043,-0.324937028,90.00000001 +261.68,50.43283629,-2.563165952,48.8113,-1.17E-11,10.00036537,-1.8965625,6.605094132,-0.223974301,90.00000001 +261.69,50.43283629,-2.563164544,48.8305,-2.34E-11,10.0003654,-1.948125,6.644715825,-0.122816311,90.00000001 +261.7,50.43283629,-2.563163137,48.8503,-2.34E-11,10.00014339,-1.998125,6.682949871,-0.021551177,90.00000001 +261.71,50.43283629,-2.563161729,48.8705,-9.38E-12,9.999477327,-2.04625,6.71978825,0.079732749,90.00000001 +261.72,50.43283629,-2.563160322,48.8912,7.03E-12,9.999033293,-2.0934375,6.755223341,0.180947119,90.00000001 +261.73,50.43283629,-2.563158915,48.9124,1.41E-11,9.999477391,-2.14,6.789247637,0.282003696,90.00000001 +261.74,50.43283629,-2.563157507,48.934,7.03E-12,10.00014352,-2.1865625,6.821854092,0.38281436,90.00000001 +261.75,50.43283629,-2.5631561,48.9561,-4.84E-12,10.00036559,-2.233125,6.853035888,0.483291218,90.00000001 +261.76,50.43283629,-2.563154692,48.9787,-5.47E-12,10.00036563,-2.278125,6.882786549,0.583346666,90.00000001 +261.77,50.43283629,-2.563153285,49.0017,7.81E-12,10.00036566,-2.32125,6.911099832,0.682893385,90.00000001 +261.78,50.43283629,-2.563151877,49.0251,2.44E-11,10.0003657,-2.3634375,6.937969776,0.781844628,90.00000001 +261.79,50.43283629,-2.56315047,49.049,3.52E-11,10.0001437,-2.4046875,6.963390825,0.880114109,90.00000001 +261.8,50.43283629,-2.563149062,49.0732,3.67E-11,9.999477644,-2.4446875,6.98735765,0.977616056,90.00000001 +261.81,50.43283629,-2.563147655,49.0979,2.81E-11,9.999033616,-2.4834375,7.009865323,1.074265556,90.00000001 +261.82,50.43283629,-2.563146248,49.1229,1.19E-11,9.999477721,-2.52125,7.030908974,1.169978271,90.00000001 +261.83,50.43283629,-2.56314484,49.1483,-4.69E-12,10.00014386,-2.5584375,7.050484363,1.264670776,90.00000001 +261.84,50.43283629,-2.563143433,49.1741,-1.48E-11,10.00036593,-2.5946875,7.068587366,1.358260453,90.00000001 +261.85,50.43283629,-2.563142025,49.2002,-1.88E-11,10.00036597,-2.63,7.085214143,1.450665654,90.00000001 +261.86,50.43283629,-2.563140618,49.2267,-2.25E-11,10.00014398,-2.6646875,7.100361313,1.541805935,90.00000001 +261.87,50.43283629,-2.56313921,49.2535,-2.95E-11,9.999477925,-2.698125,7.114025612,1.631601657,90.00000001 +261.88,50.43283629,-2.563137803,49.2807,-3.52E-11,9.999033902,-2.7296875,7.126204288,1.719974668,90.00000001 +261.89,50.43283629,-2.563136396,49.3081,-3.38E-11,9.999478011,-2.7596875,7.136894707,1.806847789,90.00000001 +261.9,50.43283629,-2.563134988,49.3359,-2.42E-11,10.00014415,-2.7884375,7.14609469,1.892145334,90.00000001 +261.91,50.43283629,-2.563133581,49.3639,-8.44E-12,10.00036623,-2.81625,7.15380229,1.975792875,90.00000001 +261.92,50.43283629,-2.563132173,49.3922,5.62E-12,10.00036627,-2.843125,7.16001596,2.057717531,90.00000001 +261.93,50.43283629,-2.563130766,49.4208,6.25E-12,10.00014429,-2.868125,7.164734325,2.137847799,90.00000001 +261.94,50.43283629,-2.563129358,49.4496,-5.47E-12,9.999478232,-2.8915625,7.16795641,2.216113891,90.00000001 +261.95,50.43283629,-2.563127951,49.4786,-1.33E-11,9.999034211,-2.915,7.169681586,2.292447454,90.00000001 +261.96,50.43283629,-2.563126544,49.5079,-1.16E-11,9.999478322,-2.9378125,7.169909394,2.366781967,90.00000001 +261.97,50.43283629,-2.563125136,49.5374,-1.41E-11,10.00014447,-2.958125,7.168639949,2.439052571,90.00000001 +261.98,50.43283629,-2.563123729,49.5671,-2.58E-11,10.00036655,-2.9765625,7.165873365,2.509196357,90.00000001 +261.99,50.43283629,-2.563122321,49.5969,-3.05E-11,10.00036659,-2.9946875,7.16161033,2.577152016,90.00000001 +262,50.43283629,-2.563120914,49.627,-1.64E-11,10.00036664,-3.0115625,7.155851646,2.64286042,90.00000001 +262.01,50.43283629,-2.563119506,49.6572,4.69E-12,10.00036669,-3.02625,7.148598573,2.706264216,90.00000001 +262.02,50.43283629,-2.563118099,49.6875,1.41E-11,10.0001447,-3.04,7.139852601,2.767308056,90.00000001 +262.03,50.43283629,-2.563116691,49.718,9.38E-12,9.999478651,-3.053125,7.129615564,2.82593877,90.00000001 +262.04,50.43283629,-2.563115284,49.7486,2.34E-12,9.999034633,-3.0646875,7.117889582,2.88210525,90.00000001 +262.05,50.43283629,-2.563113877,49.7793,-2.22E-16,9.999478748,-3.075,7.104677118,2.935758508,90.00000001 +262.06,50.43283629,-2.563112469,49.8101,-2.34E-12,10.0001449,-3.0846875,7.08998098,2.986851732,90.00000001 +262.07,50.43283629,-2.563111062,49.841,-7.03E-12,10.00036698,-3.0928125,7.073804147,3.035340349,90.00000001 +262.08,50.43283629,-2.563109654,49.872,-4.69E-12,10.00036702,-3.098125,7.056150056,3.081182129,90.00000001 +262.09,50.43283629,-2.563108247,49.903,7.03E-12,10.00036707,-3.1015625,7.037022376,3.124337023,90.00000001 +262.1,50.43283629,-2.563106839,49.934,1.41E-11,10.00036712,-3.105,7.016425059,3.164767504,90.00000001 +262.11,50.43283629,-2.563105432,49.9651,9.38E-12,10.00036717,-3.108125,6.994362517,3.202438218,90.00000001 +262.12,50.43283629,-2.563104024,49.9962,2.34E-12,10.00036722,-3.1096875,6.970839276,3.237316394,90.00000001 +262.13,50.43283629,-2.563102617,50.0273,2.34E-12,10.00036727,-3.1096875,6.945860265,3.269371549,90.00000001 +262.14,50.43283629,-2.563101209,50.0584,9.38E-12,10.00036732,-3.108125,6.919430695,3.298575838,90.00000001 +262.15,50.43283629,-2.563099802,50.0895,1.64E-11,10.00014533,-3.1046875,6.89155607,3.32490365,90.00000001 +262.16,50.43283629,-2.563098394,50.1205,1.64E-11,9.999479281,-3.0996875,6.862242231,3.348332123,90.00000001 +262.17,50.43283629,-2.563096987,50.1515,7.03E-12,9.999035263,-3.0934375,6.831495368,3.368840746,90.00000001 +262.18,50.43283629,-2.56309558,50.1824,-9.38E-12,9.999479378,-3.08625,6.799321782,3.386411758,90.00000001 +262.19,50.43283629,-2.563094172,50.2132,-2.34E-11,10.00014553,-3.078125,6.765728235,3.401029745,90.00000001 +262.2,50.43283629,-2.563092765,50.244,-2.34E-11,10.00036761,-3.068125,6.730721774,3.412681987,90.00000001 +262.21,50.43283629,-2.563091357,50.2746,-9.38E-12,10.00036765,-3.05625,6.694309676,3.421358344,90.00000001 +262.22,50.43283629,-2.56308995,50.3051,7.03E-12,10.0003677,-3.0434375,6.656499561,3.427051196,90.00000001 +262.23,50.43283629,-2.563088542,50.3355,1.64E-11,10.00036775,-3.0296875,6.617299336,3.429755614,90.00000001 +262.24,50.43283629,-2.563087135,50.3657,1.87E-11,10.0003678,-3.015,6.576717136,3.429469192,90.00000001 +262.25,50.43283629,-2.563085727,50.3958,2.11E-11,10.00036784,-2.9996875,6.5347615,3.426192275,90.00000001 +262.26,50.43283629,-2.56308432,50.4257,2.58E-11,10.00036789,-2.9828125,6.491441135,3.419927669,90.00000001 +262.27,50.43283629,-2.563082912,50.4555,2.34E-11,10.00036794,-2.963125,6.446765152,3.410680818,90.00000001 +262.28,50.43283629,-2.563081505,50.485,1.16E-11,10.00014595,-2.9415625,6.400742832,3.3984598,90.00000001 +262.29,50.43283629,-2.563080097,50.5143,3.91E-12,9.999479897,-2.92,6.353383803,3.383275272,90.00000001 +262.3,50.43283629,-2.56307869,50.5434,7.81E-12,9.999035877,-2.898125,6.304697917,3.36514047,90.00000001 +262.31,50.43283629,-2.563077283,50.5723,1.48E-11,9.999479988,-2.8746875,6.254695432,3.344071208,90.00000001 +262.32,50.43283629,-2.563075875,50.6009,1.56E-11,10.00014613,-2.8496875,6.203386718,3.320085934,90.00000001 +262.33,50.43283629,-2.563074468,50.6293,9.37E-12,10.00036821,-2.823125,6.150782489,3.293205447,90.00000001 +262.34,50.43283629,-2.56307306,50.6574,3.13E-12,10.00036825,-2.7946875,6.096893745,3.263453239,90.00000001 +262.35,50.43283629,-2.563071653,50.6852,1.56E-12,10.0003683,-2.765,6.041731775,3.230855206,90.00000001 +262.36,50.43283629,-2.563070245,50.7127,1.41E-12,10.00036834,-2.735,5.985308037,3.195439883,90.00000001 +262.37,50.43283629,-2.563068838,50.7399,2.34E-12,10.00036838,-2.7046875,5.927634335,3.157238093,90.00000001 +262.38,50.43283629,-2.56306743,50.7668,7.81E-12,10.00036842,-2.673125,5.868722757,3.116283128,90.00000001 +262.39,50.43283629,-2.563066023,50.7934,1.41E-11,10.00036847,-2.6396875,5.808585508,3.07261068,90.00000001 +262.4,50.43283629,-2.563064615,50.8196,1.39E-11,10.00036851,-2.6046875,5.747235307,3.02625891,90.00000001 +262.41,50.43283629,-2.563063208,50.8455,6.88E-12,10.00014651,-2.568125,5.684684817,2.977268211,90.00000001 +262.42,50.43283629,-2.5630618,50.871,2.19E-12,9.999480455,-2.53,5.620947101,2.925681269,90.00000001 +262.43,50.43283629,-2.563060393,50.8961,9.38E-12,9.999036428,-2.4915625,5.556035624,2.871543059,90.00000001 +262.44,50.43283629,-2.563058986,50.9208,2.42E-11,9.999480533,-2.4534375,5.489963793,2.814900853,90.00000001 +262.45,50.43283629,-2.563057578,50.9452,3.52E-11,10.00014667,-2.4146875,5.422745416,2.755803981,90.00000001 +262.46,50.43283629,-2.563056171,50.9691,3.42E-11,10.00036874,-2.374375,5.354394587,2.694304066,90.00000001 +262.47,50.43283629,-2.563054763,50.9927,1.56E-11,10.00036878,-2.331875,5.284925632,2.630454623,90.00000001 +262.48,50.43283629,-2.563053356,51.0158,-1.56E-11,10.00014678,-2.2878125,5.214352931,2.564311401,90.00000001 +262.49,50.43283629,-2.563051948,51.0384,-3.98E-11,9.999480717,-2.2434375,5.142691266,2.495932097,90.00000001 +262.5,50.43283629,-2.563050541,51.0607,-4.30E-11,9.999036686,-2.198125,5.069955649,2.425376241,90.00000001 +262.51,50.43283629,-2.563049134,51.0824,-3.20E-11,9.999480786,-2.1515625,4.996161206,2.352705483,90.00000001 +262.52,50.43283629,-2.563047726,51.1037,-2.50E-11,10.00014692,-2.105,4.921323349,2.277983077,90.00000001 +262.53,50.43283629,-2.563046319,51.1245,-2.88E-11,10.00036898,-2.058125,4.845457836,2.201274284,90.00000001 +262.54,50.43283629,-2.563044911,51.1449,-3.45E-11,10.00036902,-2.0096875,4.768580307,2.122645911,90.00000001 +262.55,50.43283629,-2.563043504,51.1647,-3.36E-11,10.00036905,-1.9596875,4.690706977,2.042166597,90.00000001 +262.56,50.43283629,-2.563042096,51.1841,-2.42E-11,10.00036908,-1.9084375,4.611854062,1.959906417,90.00000001 +262.57,50.43283629,-2.563040689,51.2029,-1.09E-11,10.00014707,-1.8565625,4.532038004,1.875937217,90.00000001 +262.58,50.43283629,-2.563039281,51.2212,-4.69E-12,9.999481004,-1.805,4.451275478,1.790332166,90.00000001 +262.59,50.43283629,-2.563037874,51.239,-1.02E-11,9.999036965,-1.753125,4.369583385,1.703165919,90.00000001 +262.6,50.43283629,-2.563036467,51.2563,-1.81E-11,9.999481057,-1.6996875,4.286978741,1.614514509,90.00000001 +262.61,50.43283629,-2.563035059,51.273,-2.11E-11,10.00014718,-1.645,4.203478794,1.524455169,90.00000001 +262.62,50.43283629,-2.563033652,51.2892,-2.12E-11,10.00036924,-1.59,4.119101019,1.43306651,90.00000001 +262.63,50.43283629,-2.563032244,51.3048,-1.89E-11,10.00036927,-1.5346875,4.033863062,1.340428173,90.00000001 +262.64,50.43283629,-2.563030837,51.3199,-1.19E-11,10.00014726,-1.478125,3.947782627,1.246621001,90.00000001 +262.65,50.43283629,-2.563029429,51.3344,-7.03E-12,9.99948118,-1.42,3.860877821,1.151726757,90.00000001 +262.66,50.43283629,-2.563028022,51.3483,-1.34E-11,9.999037136,-1.3615625,3.773166635,1.055828176,90.00000001 +262.67,50.43283629,-2.563026615,51.3616,-2.66E-11,9.999481223,-1.3034375,3.684667516,0.959008851,90.00000001 +262.68,50.43283629,-2.563025207,51.3744,-3.28E-11,10.00014734,-1.245,3.595398916,0.861353294,90.00000001 +262.69,50.43283629,-2.5630238,51.3865,-2.27E-11,10.00036939,-1.18625,3.505379454,0.762946647,90.00000001 +262.7,50.43283629,-2.563022392,51.3981,1.41E-12,10.00036941,-1.126875,3.414627924,0.663874681,90.00000001 +262.71,50.43283629,-2.563020985,51.4091,2.42E-11,10.0001474,-1.06625,3.32316329,0.564223798,90.00000001 +262.72,50.43283629,-2.563019577,51.4194,3.20E-11,9.999481313,-1.005,3.231004691,0.464080917,90.00000001 +262.73,50.43283629,-2.56301817,51.4292,2.44E-11,9.999037262,-0.9434375,3.138171261,0.363533356,90.00000001 +262.74,50.43283629,-2.563016763,51.4383,1.09E-11,9.999481342,-0.8815625,3.04468254,0.262668777,90.00000001 +262.75,50.43283629,-2.563015355,51.4468,4.69E-12,10.00014745,-0.82,2.95055795,0.16157513,90.00000001 +262.76,50.43283629,-2.563013948,51.4547,1.25E-11,10.0003695,-0.7584375,2.855817201,0.060340592,90.00000001 +262.77,50.43283629,-2.56301254,51.462,2.98E-11,10.00036951,-0.69625,2.760480004,-0.040946543,90.00000001 +262.78,50.43283629,-2.563011133,51.4686,4.69E-11,10.00014749,-0.6334375,2.664566353,-0.142197983,90.00000001 +262.79,50.43283629,-2.563009725,51.4747,5.41E-11,9.999481399,-0.57,2.568096189,-0.243325435,90.00000001 +262.8,50.43283629,-2.563008318,51.48,4.47E-11,9.999037341,-0.50625,2.471089736,-0.344240664,90.00000001 +262.81,50.43283629,-2.563006911,51.4848,1.89E-11,9.999481416,-0.4421875,2.373567277,-0.444855777,90.00000001 +262.82,50.43283629,-2.563005503,51.4889,-1.41E-11,10.00014752,-0.3778125,2.275549095,-0.545082883,90.00000001 +262.83,50.43283629,-2.563004096,51.4923,-4.05E-11,10.00036956,-0.31375,2.177055645,-0.64483472,90.00000001 +262.84,50.43283629,-2.563002688,51.4952,-5.08E-11,10.00036956,-0.25,2.07810761,-0.744024257,90.00000001 +262.85,50.43283629,-2.563001281,51.4973,-4.20E-11,10.00036957,-0.18625,1.978725559,-0.842564976,90.00000001 +262.86,50.43283629,-2.562999873,51.4989,-1.88E-11,10.00036957,-0.121875,1.878930291,-0.940370992,90.00000001 +262.87,50.43283629,-2.562998466,51.4998,4.69E-12,10.00036957,-0.05625,1.778742605,-1.03735699,90.00000001 +262.88,50.43283629,-2.562997058,51.5,1.87E-11,10.00036957,0.009375,1.67818347,-1.133438346,90.00000001 +262.89,50.43283629,-2.562995651,51.4996,3.05E-11,10.00036957,0.0734375,1.577273914,-1.228531349,90.00000001 +262.9,50.43283629,-2.562994243,51.4985,4.45E-11,10.00036957,0.1365625,1.476034907,-1.322553093,90.00000001 +262.91,50.43283629,-2.562992836,51.4969,5.41E-11,10.00014753,0.2003125,1.374487649,-1.41542153,90.00000001 +262.92,50.43283629,-2.562991428,51.4945,5.70E-11,9.99948143,0.265,1.272653396,-1.507055701,90.00000001 +262.93,50.43283629,-2.562990021,51.4916,5.56E-11,9.99903736,0.3296875,1.170553291,-1.59737568,90.00000001 +262.94,50.43283629,-2.562988614,51.4879,4.69E-11,9.999481421,0.3934375,1.068208762,-1.68630274,90.00000001 +262.95,50.43283629,-2.562987206,51.4837,3.30E-11,10.00014751,0.4565625,0.965641181,-1.773759304,90.00000001 +262.96,50.43283629,-2.562985799,51.4788,2.36E-11,10.00036954,0.5203125,0.862871918,-1.859669112,90.00000001 +262.97,50.43283629,-2.562984391,51.4733,1.89E-11,10.00036953,0.5846875,0.759922461,-1.943957277,90.00000001 +262.98,50.43283629,-2.562982984,51.4671,9.37E-12,10.00036952,0.6484375,0.656814294,-2.026550289,90.00000001 +262.99,50.43283629,-2.562981576,51.4603,-7.66E-12,10.00036951,0.71125,0.553568961,-2.107376127,90.00000001 +263,50.43283629,-2.562980169,51.4529,-2.50E-11,10.0003695,0.7734375,0.450208005,-2.186364261,90.00000001 +263.01,50.43283629,-2.562978761,51.4448,-3.27E-11,10.00036948,0.835,0.346753084,-2.263445877,90.00000001 +263.02,50.43283629,-2.562977354,51.4362,-2.58E-11,10.00036947,0.8965625,0.243225683,-2.338553769,90.00000001 +263.03,50.43283629,-2.562975946,51.4269,-1.17E-11,10.00036946,0.9584375,0.139647519,-2.411622389,90.00000001 +263.04,50.43283629,-2.562974539,51.417,-4.69E-12,10.00014741,1.02,0.036040191,-2.482588025,90.00000001 +263.05,50.43283629,-2.562973131,51.4065,-1.17E-11,9.999481292,1.0815625,-0.067574642,-2.551388797,90.00000001 +263.06,50.43283629,-2.562971724,51.3954,-2.34E-11,9.999037209,1.143125,-0.171175381,-2.617964716,90.00000001 +263.07,50.43283629,-2.562970317,51.3836,-2.56E-11,9.999481257,1.2028125,-0.274740425,-2.682257743,90.00000001 +263.08,50.43283629,-2.562968909,51.3713,-2.27E-11,10.00014734,1.26,-0.378248001,-2.744211841,90.00000001 +263.09,50.43283629,-2.562967502,51.3584,-2.64E-11,10.00036935,1.316875,-0.481676623,-2.803772867,90.00000001 +263.1,50.43283629,-2.562966094,51.345,-3.05E-11,10.00036933,1.375,-0.585004691,-2.860889024,90.00000001 +263.11,50.43283629,-2.562964687,51.3309,-2.33E-11,10.00036931,1.4334375,-0.688210547,-2.915510408,90.00000001 +263.12,50.43283629,-2.562963279,51.3163,-6.88E-12,10.00036928,1.49125,-0.791272706,-2.967589464,90.00000001 +263.13,50.43283629,-2.562961872,51.3011,7.19E-12,10.00036926,1.548125,-0.894169566,-3.017080699,90.00000001 +263.14,50.43283629,-2.562960464,51.2853,7.03E-12,10.00036924,1.603125,-0.996879757,-3.063941027,90.00000001 +263.15,50.43283629,-2.562959057,51.269,-3.12E-12,10.00036921,1.656875,-1.099381734,-3.108129537,90.00000001 +263.16,50.43283629,-2.562957649,51.2522,-2.34E-12,10.00036918,1.7115625,-1.201654128,-3.149607671,90.00000001 +263.17,50.43283629,-2.562956242,51.2348,1.50E-11,10.00014712,1.7665625,-1.303675508,-3.188339388,90.00000001 +263.18,50.43283629,-2.562954834,51.2168,3.12E-11,9.999480996,1.819375,-1.405424734,-3.224290771,90.00000001 +263.19,50.43283629,-2.562953427,51.1984,3.67E-11,9.999036901,1.87,-1.506880376,-3.257430478,90.00000001 +263.2,50.43283629,-2.56295202,51.1794,3.50E-11,9.999480938,1.9203125,-1.60802135,-3.287729747,90.00000001 +263.21,50.43283629,-2.562950612,51.16,2.34E-11,10.00014701,1.97125,-1.708826513,-3.315161992,90.00000001 +263.22,50.43283629,-2.562949205,51.14,2.34E-12,10.00036901,2.0215625,-1.809274838,-3.339703436,90.00000001 +263.23,50.43283629,-2.562947797,51.1195,-1.17E-11,10.00036898,2.0696875,-1.90934524,-3.361332593,90.00000001 +263.24,50.43283629,-2.56294639,51.0986,-7.03E-12,10.00036894,2.1165625,-2.009016978,-3.380030555,90.00000001 +263.25,50.43283629,-2.562944982,51.0772,7.19E-12,10.00036891,2.1634375,-2.108269139,-3.395781165,90.00000001 +263.26,50.43283629,-2.562943575,51.0553,1.72E-11,10.00036888,2.2096875,-2.207080982,-3.408570557,90.00000001 +263.27,50.43283629,-2.562942167,51.033,1.80E-11,10.00036884,2.2546875,-2.305431938,-3.418387616,90.00000001 +263.28,50.43283629,-2.56294076,51.0102,8.44E-12,10.00014677,2.2984375,-2.403301437,-3.425223804,90.00000001 +263.29,50.43283629,-2.562939352,50.987,-9.38E-12,9.999480637,2.34125,-2.500669026,-3.429073164,90.00000001 +263.3,50.43283629,-2.562937945,50.9634,-2.72E-11,9.999036533,2.3834375,-2.597514363,-3.429932314,90.00000001 +263.31,50.43283629,-2.562936538,50.9393,-3.66E-11,9.999480561,2.4246875,-2.693817281,-3.42780051,90.00000001 +263.32,50.43283629,-2.56293513,50.9149,-3.52E-11,10.00014662,2.4646875,-2.789557612,-3.422679585,90.00000001 +263.33,50.43283629,-2.562933723,50.89,-2.66E-11,10.00036862,2.503125,-2.884715359,-3.414574066,90.00000001 +263.34,50.43283629,-2.562932315,50.8648,-1.87E-11,10.00036858,2.5396875,-2.979270699,-3.403490942,90.00000001 +263.35,50.43283629,-2.562930908,50.8392,-1.39E-11,10.0001465,2.5753125,-3.073203863,-3.389439954,90.00000001 +263.36,50.43283629,-2.5629295,50.8133,-4.69E-12,9.999480365,2.6115625,-3.166495201,-3.372433364,90.00000001 +263.37,50.43283629,-2.562928093,50.787,3.91E-12,9.999036258,2.6478125,-3.259125287,-3.352485895,90.00000001 +263.38,50.43283629,-2.562926686,50.7603,-4.69E-12,9.999480282,2.68125,-3.3510747,-3.329615024,90.00000001 +263.39,50.43283629,-2.562925278,50.7333,-2.25E-11,10.00014634,2.7115625,-3.442324302,-3.30384069,90.00000001 +263.4,50.43283629,-2.562923871,50.7061,-2.50E-11,10.00036833,2.741875,-3.532855015,-3.275185409,90.00000001 +263.41,50.43283629,-2.562922463,50.6785,-1.50E-11,10.00036829,2.773125,-3.622647986,-3.243674048,90.00000001 +263.42,50.43283629,-2.562921056,50.6506,-1.27E-11,10.00014621,2.8028125,-3.711684367,-3.209334166,90.00000001 +263.43,50.43283629,-2.562919648,50.6224,-1.80E-11,9.999480066,2.8296875,-3.799945593,-3.17219573,90.00000001 +263.44,50.43283629,-2.562918241,50.594,-2.03E-11,9.999035955,2.855,-3.887413273,-3.132291053,90.00000001 +263.45,50.43283629,-2.562916834,50.5653,-1.95E-11,9.999479977,2.88,-3.974069129,-3.089654971,90.00000001 +263.46,50.43283629,-2.562915426,50.5364,-1.42E-11,10.00014603,2.904375,-4.059895055,-3.044324728,90.00000001 +263.47,50.43283629,-2.562914019,50.5072,2.34E-12,10.00036802,2.9265625,-4.144873119,-2.996339742,90.00000001 +263.48,50.43283629,-2.562912611,50.4778,2.11E-11,10.00036797,2.9465625,-4.228985558,-2.945741896,90.00000001 +263.49,50.43283629,-2.562911204,50.4483,2.11E-11,10.00014589,2.9665625,-4.312214839,-2.892575309,90.00000001 +263.5,50.43283629,-2.562909796,50.4185,2.50E-12,9.999479747,2.9865625,-4.394543603,-2.836886389,90.00000001 +263.51,50.43283629,-2.562908389,50.3885,-1.33E-11,9.999035635,3.004375,-4.475954546,-2.77872361,90.00000001 +263.52,50.43283629,-2.562906982,50.3584,-1.48E-11,9.999479653,3.0196875,-4.556430823,-2.718137792,90.00000001 +263.53,50.43283629,-2.562905574,50.3281,-5.47E-12,10.0001457,3.0334375,-4.635955474,-2.655181706,90.00000001 +263.54,50.43283629,-2.562904167,50.2977,1.02E-11,10.00036769,3.04625,-4.714511999,-2.589910239,90.00000001 +263.55,50.43283629,-2.562902759,50.2672,2.59E-11,10.00036764,3.0584375,-4.79208401,-2.522380345,90.00000001 +263.56,50.43283629,-2.562901352,50.2365,3.50E-11,10.00014556,3.0696875,-4.868655178,-2.452650923,90.00000001 +263.57,50.43283629,-2.562899944,50.2058,3.44E-11,9.999479414,3.0796875,-4.944209633,-2.380782706,90.00000001 +263.58,50.43283629,-2.562898537,50.1749,2.66E-11,9.9990353,3.088125,-5.01873156,-2.306838435,90.00000001 +263.59,50.43283629,-2.56289713,50.144,1.95E-11,9.999479318,3.0946875,-5.092205319,-2.230882623,90.00000001 +263.6,50.43283629,-2.562895722,50.113,1.80E-11,10.00014537,3.1,-5.164615725,-2.152981391,90.00000001 +263.61,50.43283629,-2.562894315,50.082,1.63E-11,10.00036735,3.1046875,-5.235947538,-2.07320269,90.00000001 +263.62,50.43283629,-2.562892907,50.0509,9.37E-12,10.0003673,3.108125,-5.306185861,-1.991616193,90.00000001 +263.63,50.43283629,-2.5628915,50.0198,2.34E-12,10.00036726,3.1096875,-5.375316084,-1.908292946,90.00000001 +263.64,50.43283629,-2.562890092,49.9887,2.34E-12,10.00036721,3.1096875,-5.44332371,-1.823305658,90.00000001 +263.65,50.43283629,-2.562888685,49.9576,9.37E-12,10.00036716,3.108125,-5.510194589,-1.736728412,90.00000001 +263.66,50.43283629,-2.562887277,49.9265,1.41E-11,10.00036711,3.105,-5.575914739,-1.648636667,90.00000001 +263.67,50.43283629,-2.56288587,49.8955,4.69E-12,10.00014503,3.10125,-5.640470409,-1.55910737,90.00000001 +263.68,50.43283629,-2.562884462,49.8645,-1.64E-11,9.999478881,3.0965625,-5.703848193,-1.468218445,90.00000001 +263.69,50.43283629,-2.562883055,49.8335,-3.05E-11,9.999034767,3.0896875,-5.76603474,-1.376049245,90.00000001 +263.7,50.43283629,-2.562881648,49.8027,-2.58E-11,9.999478784,3.0815625,-5.827017159,-1.2826801,90.00000001 +263.71,50.43283629,-2.56288024,49.7719,-1.17E-11,10.00014483,3.0734375,-5.886782673,-1.188192427,90.00000001 +263.72,50.43283629,-2.562878833,49.7412,5.55E-17,10.00036682,3.064375,-5.945318792,-1.092668617,90.00000001 +263.73,50.43283629,-2.562877425,49.7106,7.03E-12,10.00036677,3.0528125,-6.002613311,-0.996192035,90.00000001 +263.74,50.43283629,-2.562876018,49.6801,4.69E-12,10.00036672,3.038125,-6.058654313,-0.898846735,90.00000001 +263.75,50.43283629,-2.56287461,49.6498,-4.69E-12,10.00036668,3.021875,-6.113429995,-0.800717571,90.00000001 +263.76,50.43283629,-2.562873203,49.6197,-2.34E-12,10.00036663,3.0065625,-6.166928955,-0.701890259,90.00000001 +263.77,50.43283629,-2.562871795,49.5897,1.41E-11,10.00036658,2.99125,-6.21914002,-0.602450855,90.00000001 +263.78,50.43283629,-2.562870388,49.5598,2.13E-11,10.00036654,2.9728125,-6.270052363,-0.502486106,90.00000001 +263.79,50.43283629,-2.56286898,49.5302,1.25E-11,10.00036649,2.9515625,-6.31965521,-0.402083159,90.00000001 +263.8,50.43283629,-2.562867573,49.5008,3.91E-12,10.00014441,2.9303125,-6.367938363,-0.30132962,90.00000001 +263.81,50.43283629,-2.562866165,49.4716,-7.81E-13,9.999478267,2.9096875,-6.414891567,-0.200313264,90.00000001 +263.82,50.43283629,-2.562864758,49.4426,-6.25E-12,9.999034155,2.8878125,-6.460505138,-0.099122272,90.00000001 +263.83,50.43283629,-2.562863351,49.4138,-4.69E-12,9.999478176,2.863125,-6.504769508,0.002155123,90.00000001 +263.84,50.43283629,-2.562861943,49.3853,6.25E-12,10.00014423,2.8365625,-6.547675453,0.103430685,90.00000001 +263.85,50.43283629,-2.562860536,49.3571,1.02E-11,10.00036622,2.8096875,-6.589214033,0.204616063,90.00000001 +263.86,50.43283629,-2.562859128,49.3291,-3.75E-12,10.00036618,2.7815625,-6.629376484,0.305622964,90.00000001 +263.87,50.43283629,-2.562857721,49.3014,-2.34E-11,10.00036613,2.75125,-6.668154497,0.406363383,90.00000001 +263.88,50.43283629,-2.562856313,49.2741,-3.14E-11,10.00036609,2.72,-6.705539936,0.506749428,90.00000001 +263.89,50.43283629,-2.562854906,49.247,-2.44E-11,10.00036605,2.6884375,-6.741525066,0.606693607,90.00000001 +263.9,50.43283629,-2.562853498,49.2203,-9.38E-12,10.00036601,2.65625,-6.776102266,0.706108775,90.00000001 +263.91,50.43283629,-2.562852091,49.1939,3.12E-12,10.00036596,2.623125,-6.809264376,0.804908127,90.00000001 +263.92,50.43283629,-2.562850683,49.1678,4.69E-12,10.00036592,2.5878125,-6.841004404,0.903005607,90.00000001 +263.93,50.43283629,-2.562849276,49.1421,2.19E-12,10.00014385,2.55,-6.87131582,1.00031567,90.00000001 +263.94,50.43283629,-2.562847868,49.1168,7.03E-12,9.999477712,2.511875,-6.900192262,1.096753462,90.00000001 +263.95,50.43283629,-2.562846461,49.0919,1.02E-11,9.999033606,2.4746875,-6.927627716,1.192234874,90.00000001 +263.96,50.43283629,-2.562845054,49.0673,-2.78E-17,9.999477633,2.43625,-6.953616337,1.286676596,90.00000001 +263.97,50.43283629,-2.562843646,49.0431,-1.03E-11,10.00014369,2.3946875,-6.978152853,1.379996352,90.00000001 +263.98,50.43283629,-2.562842239,49.0194,-7.97E-12,10.00036569,2.351875,-7.001232052,1.472112724,90.00000001 +263.99,50.43283629,-2.562840831,48.9961,-4.69E-12,10.00036565,2.31,-7.022849119,1.562945328,90.00000001 +264,50.43283629,-2.562839424,48.9732,-8.44E-12,10.00036562,2.2678125,-7.042999586,1.652415094,90.00000001 +264.01,50.43283629,-2.562838016,48.9507,-6.25E-12,10.00036558,2.223125,-7.061679214,1.740443929,90.00000001 +264.02,50.43283629,-2.562836609,48.9287,6.25E-12,10.00036555,2.1765625,-7.078884048,1.826955055,90.00000001 +264.03,50.43283629,-2.562835201,48.9072,1.39E-11,10.00036552,2.13,-7.094610593,1.911873015,90.00000001 +264.04,50.43283629,-2.562833794,48.8861,9.37E-12,10.00036548,2.083125,-7.108855527,1.99512384,90.00000001 +264.05,50.43283629,-2.562832386,48.8655,2.34E-12,10.00036545,2.0346875,-7.121615813,2.076634879,90.00000001 +264.06,50.43283629,-2.562830979,48.8454,1.56E-13,10.00014339,1.985,-7.132888872,2.156335027,90.00000001 +264.07,50.43283629,-2.562829571,48.8258,-1.56E-12,9.999477257,1.9346875,-7.142672356,2.234154842,90.00000001 +264.08,50.43283629,-2.562828164,48.8067,-1.02E-11,9.99903316,1.8834375,-7.150964144,2.310026487,90.00000001 +264.09,50.43283629,-2.562826757,48.7881,-2.42E-11,9.999477197,1.8315625,-7.157762517,2.383883669,90.00000001 +264.1,50.43283629,-2.562825349,48.7701,-2.95E-11,10.00014327,1.7796875,-7.163066158,2.45566216,90.00000001 +264.11,50.43283629,-2.562823942,48.7525,-1.55E-11,10.00036527,1.7265625,-7.166873807,2.525299221,90.00000001 +264.12,50.43283629,-2.562822534,48.7355,4.06E-12,10.00036525,1.6715625,-7.169184775,2.592734176,90.00000001 +264.13,50.43283629,-2.562821127,48.7191,7.03E-12,10.00014319,1.616875,-7.169998604,2.65790824,90.00000001 +264.14,50.43283629,-2.562819719,48.7032,-2.19E-12,9.999477064,1.563125,-7.169315008,2.720764575,90.00000001 +264.15,50.43283629,-2.562818312,48.6878,-4.69E-12,9.999032974,1.5078125,-7.167134216,2.781248349,90.00000001 +264.16,50.43283629,-2.562816905,48.673,-3.13E-12,9.999477018,1.45,-7.163456629,2.83930685,90.00000001 +264.17,50.43283629,-2.562815497,48.6588,-1.17E-11,10.00014309,1.3915625,-7.158283107,2.894889428,90.00000001 +264.18,50.43283629,-2.56281409,48.6452,-2.72E-11,10.00036511,1.3334375,-7.151614623,2.947947612,90.00000001 +264.19,50.43283629,-2.562812682,48.6321,-3.44E-11,10.00036509,1.275,-7.14345261,2.998435163,90.00000001 +264.2,50.43283629,-2.562811275,48.6197,-2.66E-11,10.00014303,1.2165625,-7.133798787,3.046308021,90.00000001 +264.21,50.43283629,-2.562809867,48.6078,-1.42E-11,9.999476916,1.158125,-7.122655159,3.091524475,90.00000001 +264.22,50.43283629,-2.56280846,48.5965,-1.41E-11,9.999032831,1.098125,-7.110024075,3.134045048,90.00000001 +264.23,50.43283629,-2.562807053,48.5858,-2.58E-11,9.99947688,1.0365625,-7.095908171,3.17383267,90.00000001 +264.24,50.43283629,-2.562805645,48.5758,-3.28E-11,10.00014296,0.975,-7.080310312,3.210852676,90.00000001 +264.25,50.43283629,-2.562804238,48.5663,-2.58E-11,10.00036498,0.9134375,-7.063233877,3.245072753,90.00000001 +264.26,50.43283629,-2.56280283,48.5575,-1.16E-11,10.00036497,0.8515625,-7.044682363,3.276463105,90.00000001 +264.27,50.43283629,-2.562801423,48.5493,-3.91E-12,10.00014292,0.79,-7.024659608,3.304996346,90.00000001 +264.28,50.43283629,-2.562800015,48.5417,-7.81E-12,9.999476812,0.728125,-7.00316991,3.330647552,90.00000001 +264.29,50.43283629,-2.562798608,48.5347,-1.27E-11,9.999032735,0.665,-6.980217679,3.353394434,90.00000001 +264.3,50.43283629,-2.562797201,48.5284,-6.88E-12,9.999476791,0.6015625,-6.955807671,3.373217055,90.00000001 +264.31,50.43283629,-2.562795793,48.5227,6.41E-12,10.00014288,0.5384375,-6.929945101,3.390098168,90.00000001 +264.32,50.43283629,-2.562794386,48.5176,1.42E-11,10.00036491,0.475,-6.90263524,3.404023105,90.00000001 +264.33,50.43283629,-2.562792978,48.5132,8.44E-12,10.0003649,0.4115625,-6.873883874,3.414979663,90.00000001 +264.34,50.43283629,-2.562791571,48.5094,-5.63E-12,10.00014286,0.3484375,-6.84369702,3.422958329,90.00000001 +264.35,50.43283629,-2.562790163,48.5062,-1.64E-11,9.999476756,0.2846875,-6.812080922,3.427952115,90.00000001 +264.36,50.43283629,-2.562788756,48.5037,-1.78E-11,9.999032686,0.2196875,-6.77904217,3.429956665,90.00000001 +264.37,50.43283629,-2.562787349,48.5018,-6.25E-12,9.999476749,0.15375,-6.744587754,3.428970261,90.00000001 +264.38,50.43283629,-2.562785941,48.5006,1.56E-11,10.00014285,0.0884375,-6.708724779,3.424993704,90.00000001 +264.39,50.43283629,-2.562784534,48.5001,2.80E-11,10.00036488,0.025,-6.671460807,3.418030548,90.00000001 +264.4,50.43283629,-2.562783126,48.5001,1.66E-11,10.00036488,-0.0384375,-6.632803574,3.408086808,90.00000001 +264.41,50.43283629,-2.562781719,48.5008,-1.56E-12,10.00036488,-0.1034375,-6.592761158,3.395171136,90.00000001 +264.42,50.43283629,-2.562780311,48.5022,-3.13E-12,10.00036488,-0.168125,-6.551341924,3.379294877,90.00000001 +264.43,50.43283629,-2.562778904,48.5042,8.44E-12,10.00036489,-0.2315625,-6.508554525,3.360471781,90.00000001 +264.44,50.43283629,-2.562777496,48.5068,1.64E-11,10.00036489,-0.2953125,-6.464407897,3.338718292,90.00000001 +264.45,50.43283629,-2.562776089,48.5101,1.72E-11,10.00014286,-0.36,-6.418911324,3.314053433,90.00000001 +264.46,50.43283629,-2.562774681,48.514,1.64E-11,9.999476769,-0.425,-6.372074144,3.286498633,90.00000001 +264.47,50.43283629,-2.562773274,48.5186,1.86E-11,9.99903271,-0.4896875,-6.323906327,3.256077954,90.00000001 +264.48,50.43283629,-2.562771867,48.5238,2.58E-11,9.999476784,-0.553125,-6.274417785,3.222817983,90.00000001 +264.49,50.43283629,-2.562770459,48.5297,3.13E-11,10.00014289,-0.615,-6.223618889,3.186747597,90.00000001 +264.5,50.43283629,-2.562769052,48.5361,2.81E-11,10.00036493,-0.676875,-6.171520352,3.147898366,90.00000001 +264.51,50.43283629,-2.562767644,48.5432,2.25E-11,10.00036495,-0.7403125,-6.11813289,3.106304094,90.00000001 +264.52,50.43283629,-2.562766237,48.5509,1.56E-11,10.00036496,-0.804375,-6.063467789,3.062001106,90.00000001 +264.53,50.43283629,-2.562764829,48.5593,-1.56E-12,10.00036497,-0.8665625,-6.007536394,3.015028021,90.00000001 +264.54,50.43283629,-2.562763422,48.5683,-2.09E-11,10.00036499,-0.9265625,-5.950350393,2.965425747,90.00000001 +264.55,50.43283629,-2.562762014,48.5778,-2.34E-11,10.000365,-0.986875,-5.891921761,2.913237599,90.00000001 +264.56,50.43283629,-2.562760607,48.588,-1.17E-11,10.00014298,-1.0484375,-5.832262645,2.858509014,90.00000001 +264.57,50.43283629,-2.562759199,48.5988,-2.34E-12,9.999476901,-1.1096875,-5.771385536,2.801287834,90.00000001 +264.58,50.43283629,-2.562757792,48.6102,1.56E-13,9.999032853,-1.17,-5.709303209,2.741623848,90.00000001 +264.59,50.43283629,-2.562756385,48.6222,7.81E-13,9.999476938,-1.23,-5.646028501,2.679569138,90.00000001 +264.6,50.43283629,-2.562754977,48.6348,-6.25E-13,10.00014306,-1.2896875,-5.581574702,2.615177792,90.00000001 +264.61,50.43283629,-2.56275357,48.648,-7.03E-12,10.00036511,-1.348125,-5.515955278,2.548506017,90.00000001 +264.62,50.43283629,-2.562752162,48.6618,-1.16E-11,10.00036513,-1.405,-5.449183923,2.479611853,90.00000001 +264.63,50.43283629,-2.562750755,48.6761,-4.53E-12,10.00036515,-1.4615625,-5.381274559,2.40855546,90.00000001 +264.64,50.43283629,-2.562749347,48.691,9.53E-12,10.00036518,-1.5184375,-5.312241395,2.335398777,90.00000001 +264.65,50.43283629,-2.56274794,48.7065,1.89E-11,10.0003652,-1.5746875,-5.242098813,2.260205572,90.00000001 +264.66,50.43283629,-2.562746532,48.7225,2.13E-11,10.00036523,-1.63,-5.170861481,2.183041449,90.00000001 +264.67,50.43283629,-2.562745125,48.7391,2.34E-11,10.00036525,-1.6846875,-5.098544352,2.103973675,90.00000001 +264.68,50.43283629,-2.562743717,48.7562,2.98E-11,10.00036528,-1.738125,-5.025162381,2.023071175,90.00000001 +264.69,50.43283629,-2.56274231,48.7739,3.36E-11,10.00014327,-1.79,-4.950730981,1.940404595,90.00000001 +264.7,50.43283629,-2.562740902,48.792,2.83E-11,9.999477203,-1.841875,-4.875265736,1.856045899,90.00000001 +264.71,50.43283629,-2.562739495,48.8107,2.34E-11,9.999033166,-1.895,-4.798782287,1.770068711,90.00000001 +264.72,50.43283629,-2.562738088,48.8299,2.58E-11,9.999477263,-1.9478125,-4.721296736,1.682548033,90.00000001 +264.73,50.43283629,-2.56273668,48.8497,2.58E-11,10.00014339,-1.9978125,-4.642825181,1.593560067,90.00000001 +264.74,50.43283629,-2.562735273,48.8699,2.34E-11,10.00036546,-2.045,-4.56338401,1.503182564,90.00000001 +264.75,50.43283629,-2.562733865,48.8906,2.81E-11,10.00036549,-2.091875,-4.482989838,1.411494248,90.00000001 +264.76,50.43283629,-2.562732458,48.9117,3.05E-11,10.00036552,-2.1396875,-4.401659453,1.318575104,90.00000001 +264.77,50.43283629,-2.56273105,48.9334,1.64E-11,10.00036556,-2.1865625,-4.319409871,1.224506091,90.00000001 +264.78,50.43283629,-2.562729643,48.9555,-4.53E-12,10.00036559,-2.23125,-4.236258226,1.129369314,90.00000001 +264.79,50.43283629,-2.562728235,48.978,-1.33E-11,10.00036563,-2.275,-4.152221875,1.033247737,90.00000001 +264.8,50.43283629,-2.562726828,49.001,-5.47E-12,10.00036566,-2.3184375,-4.067318354,0.936225127,90.00000001 +264.81,50.43283629,-2.56272542,49.0244,1.08E-11,10.0003657,-2.36125,-3.981565479,0.838386109,90.00000001 +264.82,50.43283629,-2.562724013,49.0482,2.34E-11,10.0001437,-2.403125,-3.894981071,0.739816054,90.00000001 +264.83,50.43283629,-2.562722605,49.0725,2.19E-11,9.999477642,-2.443125,-3.807583293,0.640600849,90.00000001 +264.84,50.43283629,-2.562721198,49.0971,9.38E-12,9.999033614,-2.4815625,-3.719390306,0.54082701,90.00000001 +264.85,50.43283629,-2.562719791,49.1221,2.19E-12,9.99947772,-2.52,-3.63042056,0.440581569,90.00000001 +264.86,50.43283629,-2.562718383,49.1475,6.88E-12,10.00014386,-2.558125,-3.540692676,0.339951903,90.00000001 +264.87,50.43283629,-2.562716976,49.1733,1.39E-11,10.00036593,-2.5946875,-3.450225333,0.239025845,90.00000001 +264.88,50.43283629,-2.562715568,49.1994,1.41E-11,10.00036597,-2.6296875,-3.359037496,0.137891289,90.00000001 +264.89,50.43283629,-2.562714161,49.2259,5.47E-12,10.00036601,-2.6634375,-3.267148186,0.036636583,90.00000001 +264.9,50.43283629,-2.562712753,49.2527,-9.38E-12,10.00036606,-2.69625,-3.174576541,-0.064650151,90.00000001 +264.91,50.43283629,-2.562711346,49.2798,-2.20E-11,10.00014407,-2.728125,-3.081341927,-0.165880449,90.00000001 +264.92,50.43283629,-2.562709938,49.3073,-2.19E-11,9.999478009,-2.758125,-2.987463766,-0.266966132,90.00000001 +264.93,50.43283629,-2.562708531,49.335,-1.08E-11,9.999033986,-2.7865625,-2.892961769,-0.367819023,90.00000001 +264.94,50.43283629,-2.562707124,49.363,-3.75E-12,9.999478097,-2.815,-2.797855588,-0.468351172,90.00000001 +264.95,50.43283629,-2.562705716,49.3913,-5.47E-12,10.00014424,-2.8428125,-2.702165161,-0.568474916,90.00000001 +264.96,50.43283629,-2.562704309,49.4199,-3.12E-12,10.00036632,-2.868125,-2.605910372,-0.668102937,90.00000001 +264.97,50.43283629,-2.562702901,49.4487,7.81E-12,10.00036636,-2.8915625,-2.509111387,-0.767148318,90.00000001 +264.98,50.43283629,-2.562701494,49.4777,1.42E-11,10.00014437,-2.915,-2.411788375,-0.86552477,90.00000001 +264.99,50.43283629,-2.562700086,49.507,1.17E-11,9.999478322,-2.9378125,-2.313961733,-0.963146465,90.00000001 +265,50.43283629,-2.562698679,49.5365,1.41E-11,9.999034302,-2.958125,-2.215651858,-1.059928319,90.00000001 +265.01,50.43283629,-2.562697272,49.5662,2.58E-11,9.999478414,-2.9765625,-2.116879263,-1.15578582,90.00000001 +265.02,50.43283629,-2.562695864,49.596,3.05E-11,10.00014456,-2.9946875,-2.017664573,-1.250635545,90.00000001 +265.03,50.43283629,-2.562694457,49.6261,1.64E-11,10.00036664,-3.0115625,-1.91802853,-1.344394645,90.00000001 +265.04,50.43283629,-2.562693049,49.6563,-4.69E-12,10.00036669,-3.02625,-1.817991875,-1.436981416,90.00000001 +265.05,50.43283629,-2.562691642,49.6866,-1.41E-11,10.0001447,-3.04,-1.717575636,-1.528315128,90.00000001 +265.06,50.43283629,-2.562690234,49.7171,-9.38E-12,9.999478649,-3.053125,-1.616800668,-1.618316141,90.00000001 +265.07,50.43283629,-2.562688827,49.7477,-2.34E-12,9.999034632,-3.0646875,-1.515688055,-1.706905901,90.00000001 +265.08,50.43283629,-2.56268742,49.7784,-2.34E-12,9.999478747,-3.0746875,-1.414258884,-1.794007289,90.00000001 +265.09,50.43283629,-2.562686012,49.8092,-1.17E-11,10.00014489,-3.0834375,-1.31253441,-1.879544216,90.00000001 +265.1,50.43283629,-2.562684605,49.8401,-2.81E-11,10.00036697,-3.09125,-1.210535776,-1.963442196,90.00000001 +265.11,50.43283629,-2.562683197,49.871,-4.22E-11,10.00036702,-3.098125,-1.10828441,-2.045628007,90.00000001 +265.12,50.43283629,-2.56268179,49.9021,-4.22E-11,10.00014504,-3.103125,-1.005801512,-2.126029972,90.00000001 +265.13,50.43283629,-2.562680382,49.9331,-2.81E-11,9.999478989,-3.10625,-0.903108624,-2.204578074,90.00000001 +265.14,50.43283629,-2.562678975,49.9642,-1.17E-11,9.999034971,-3.1084375,-0.80022712,-2.281203673,90.00000001 +265.15,50.43283629,-2.562677568,49.9953,2.50E-16,9.999479085,-3.109375,-0.697178483,-2.355840077,90.00000001 +265.16,50.43283629,-2.56267616,50.0264,1.17E-11,10.00014523,-3.1084375,-0.593984258,-2.428422142,90.00000001 +265.17,50.43283629,-2.562674753,50.0575,2.81E-11,10.00036731,-3.10625,-0.490665987,-2.498886611,90.00000001 +265.18,50.43283629,-2.562673345,50.0885,4.45E-11,10.00036736,-3.1034375,-0.387245271,-2.567172008,90.00000001 +265.19,50.43283629,-2.562671938,50.1196,5.39E-11,10.00036741,-3.0996875,-0.283743654,-2.633218744,90.00000001 +265.2,50.43283629,-2.56267053,50.1505,5.16E-11,10.00036746,-3.094375,-0.180182793,-2.696969294,90.00000001 +265.21,50.43283629,-2.562669123,50.1815,3.28E-11,10.00014548,-3.086875,-0.076584289,-2.758368081,90.00000001 +265.22,50.43283629,-2.562667715,50.2123,2.34E-12,9.999479425,-3.0778125,0.027030201,-2.817361535,90.00000001 +265.23,50.43283629,-2.562666308,50.243,-2.11E-11,9.999035407,-3.0684375,0.130639018,-2.873898145,90.00000001 +265.24,50.43283629,-2.562664901,50.2737,-2.58E-11,9.99947952,-3.0578125,0.23422062,-2.927928753,90.00000001 +265.25,50.43283629,-2.562663493,50.3042,-2.11E-11,10.00014567,-3.0446875,0.337753234,-2.979406089,90.00000001 +265.26,50.43283629,-2.562662086,50.3346,-1.88E-11,10.00036775,-3.03,0.441215375,-3.028285347,90.00000001 +265.27,50.43283629,-2.562660678,50.3648,-1.88E-11,10.0003678,-3.015,0.544585326,-3.074523958,90.00000001 +265.28,50.43283629,-2.562659271,50.3949,-2.11E-11,10.00036784,-2.9996875,0.647841545,-3.11808147,90.00000001 +265.29,50.43283629,-2.562657863,50.4248,-2.58E-11,10.00036789,-2.9828125,0.750962547,-3.158920011,90.00000001 +265.3,50.43283629,-2.562656456,50.4546,-2.34E-11,10.00036794,-2.963125,0.853926615,-3.197003943,90.00000001 +265.31,50.43283629,-2.562655048,50.4841,-1.16E-11,10.00036798,-2.9415625,0.956712436,-3.232299976,90.00000001 +265.32,50.43283629,-2.562653641,50.5134,-3.91E-12,10.00036803,-2.92,1.059298409,-3.264777459,90.00000001 +265.33,50.43283629,-2.562652233,50.5425,-7.81E-12,10.00036807,-2.898125,1.161663163,-3.294407971,90.00000001 +265.34,50.43283629,-2.562650826,50.5714,-1.48E-11,10.00014609,-2.8746875,1.263785327,-3.321165673,90.00000001 +265.35,50.43283629,-2.562649418,50.6,-1.55E-11,9.999480031,-2.8496875,1.365643587,-3.34502736,90.00000001 +265.36,50.43283629,-2.562648011,50.6284,-6.09E-12,9.999036009,-2.8234375,1.467216628,-3.365972061,90.00000001 +265.37,50.43283629,-2.562646604,50.6565,1.09E-11,9.999480119,-2.79625,1.568483251,-3.383981615,90.00000001 +265.38,50.43283629,-2.562645196,50.6843,2.48E-11,10.00014626,-2.768125,1.669422372,-3.399040263,90.00000001 +265.39,50.43283629,-2.562643789,50.7119,2.34E-11,10.00036834,-2.738125,1.770012791,-3.411134944,90.00000001 +265.4,50.43283629,-2.562642381,50.7391,7.97E-12,10.00036838,-2.70625,1.870233594,-3.420255,90.00000001 +265.41,50.43283629,-2.562640974,50.766,-8.44E-12,10.00036842,-2.6734375,1.970063812,-3.426392581,90.00000001 +265.42,50.43283629,-2.562639566,50.7926,-1.64E-11,10.00036846,-2.6396875,2.069482647,-3.429542302,90.00000001 +265.43,50.43283629,-2.562638159,50.8188,-1.48E-11,10.00036851,-2.6046875,2.168469242,-3.429701412,90.00000001 +265.44,50.43283629,-2.562636751,50.8447,-4.69E-12,10.00036855,-2.5684375,2.267003028,-3.426869797,90.00000001 +265.45,50.43283629,-2.562635344,50.8702,9.53E-12,10.00036859,-2.5315625,2.365063323,-3.421049864,90.00000001 +265.46,50.43283629,-2.562633936,50.8953,1.41E-11,10.00036863,-2.4946875,2.462629727,-3.412246711,90.00000001 +265.47,50.43283629,-2.562632529,50.9201,-7.82E-13,10.00014663,-2.4565625,2.559681845,-3.400468017,90.00000001 +265.48,50.43283629,-2.562631121,50.9445,-2.34E-11,9.99948057,-2.41625,2.65619945,-3.385724094,90.00000001 +265.49,50.43283629,-2.562629714,50.9684,-3.42E-11,9.999036541,-2.375,2.752162261,-3.368027777,90.00000001 +265.5,50.43283629,-2.562628307,50.992,-2.97E-11,9.999480644,-2.333125,2.847550394,-3.347394478,90.00000001 +265.51,50.43283629,-2.562626899,51.0151,-2.19E-11,10.00014678,-2.2896875,2.942343798,-3.323842245,90.00000001 +265.52,50.43283629,-2.562625492,51.0378,-1.87E-11,10.00036885,-2.245,3.036522762,-3.297391477,90.00000001 +265.53,50.43283629,-2.562624084,51.06,-1.56E-11,10.00036888,-2.1996875,3.130067575,-3.268065434,90.00000001 +265.54,50.43283629,-2.562622677,51.0818,-5.47E-12,10.00036892,-2.1534375,3.222958702,-3.2358895,90.00000001 +265.55,50.43283629,-2.562621269,51.1031,1.09E-11,10.00036895,-2.10625,3.315176774,-3.200891862,90.00000001 +265.56,50.43283629,-2.562619862,51.1239,2.64E-11,10.00036898,-2.0584375,3.406702485,-3.163103004,90.00000001 +265.57,50.43283629,-2.562618454,51.1443,3.22E-11,10.00036901,-2.01,3.497516811,-3.122555869,90.00000001 +265.58,50.43283629,-2.562617047,51.1641,2.19E-11,10.00014701,-1.96125,3.587600674,-3.079285868,90.00000001 +265.59,50.43283629,-2.562615639,51.1835,7.82E-13,9.999480944,-1.9115625,3.676935336,-3.033330642,90.00000001 +265.6,50.43283629,-2.562614232,51.2024,-1.27E-11,9.999036908,-1.8596875,3.765502121,-2.984730299,90.00000001 +265.61,50.43283629,-2.562612825,51.2207,-7.97E-12,9.999481002,-1.8065625,3.853282464,-2.933527181,90.00000001 +265.62,50.43283629,-2.562611417,51.2385,5.47E-12,10.00014713,-1.7534375,3.940258202,-2.879766035,90.00000001 +265.63,50.43283629,-2.56261001,51.2558,1.50E-11,10.00036919,-1.6996875,4.026411001,-2.82349373,90.00000001 +265.64,50.43283629,-2.562608602,51.2725,1.87E-11,10.00036922,-1.645,4.111722927,-2.764759254,90.00000001 +265.65,50.43283629,-2.562607195,51.2887,2.03E-11,10.00036924,-1.59,4.196176218,-2.703613828,90.00000001 +265.66,50.43283629,-2.562605787,51.3043,2.11E-11,10.00036927,-1.535,4.279753171,-2.640110853,90.00000001 +265.67,50.43283629,-2.56260438,51.3194,2.36E-11,10.00036929,-1.4796875,4.362436309,-2.574305676,90.00000001 +265.68,50.43283629,-2.562602972,51.3339,3.05E-11,10.00036931,-1.423125,4.444208502,-2.506255651,90.00000001 +265.69,50.43283629,-2.562601565,51.3479,3.45E-11,10.0001473,-1.365,4.525052503,-2.436020135,90.00000001 +265.7,50.43283629,-2.562600157,51.3612,2.66E-11,9.999481222,-1.3065625,4.604951525,-2.363660378,90.00000001 +265.71,50.43283629,-2.56259875,51.374,1.42E-11,9.999037175,-1.248125,4.683888837,-2.289239463,90.00000001 +265.72,50.43283629,-2.562597343,51.3862,1.42E-11,9.999481261,-1.188125,4.761848053,-2.212822306,90.00000001 +265.73,50.43283629,-2.562595935,51.3978,2.44E-11,10.00014738,-1.126875,4.838812729,-2.134475484,90.00000001 +265.74,50.43283629,-2.562594528,51.4087,2.58E-11,10.00036943,-1.066875,4.914766936,-2.054267466,90.00000001 +265.75,50.43283629,-2.56259312,51.4191,1.72E-11,10.00036944,-1.008125,4.989694747,-1.972268038,90.00000001 +265.76,50.43283629,-2.562591713,51.4289,1.41E-11,10.00014743,-0.9478125,5.063580519,-1.888548763,90.00000001 +265.77,50.43283629,-2.562590305,51.4381,1.50E-11,9.999481342,-0.885,5.136408841,-1.803182635,90.00000001 +265.78,50.43283629,-2.562588898,51.4466,9.37E-12,9.99903729,-0.821875,5.208164471,-1.716244139,90.00000001 +265.79,50.43283629,-2.562587491,51.4545,3.91E-12,9.999481368,-0.76,5.278832455,-1.62780902,90.00000001 +265.8,50.43283629,-2.562586083,51.4618,7.66E-12,10.00014748,-0.698125,5.348398011,-1.537954456,90.00000001 +265.81,50.43283629,-2.562584676,51.4685,1.41E-11,10.00036952,-0.6346875,5.416846643,-1.446758712,90.00000001 +265.82,50.43283629,-2.562583268,51.4745,1.86E-11,10.00036953,-0.5703125,5.484164028,-1.354301429,90.00000001 +265.83,50.43283629,-2.562581861,51.4799,2.80E-11,10.00014751,-0.5065625,5.550336069,-1.260663166,90.00000001 +265.84,50.43283629,-2.562580453,51.4846,4.20E-11,9.999481415,-0.4434375,5.615349075,-1.165925568,90.00000001 +265.85,50.43283629,-2.562579046,51.4888,4.92E-11,9.999037355,-0.38,5.67918935,-1.070171315,90.00000001 +265.86,50.43283629,-2.562577639,51.4922,4.05E-11,9.999481427,-0.31625,5.741843545,-0.973483827,90.00000001 +265.87,50.43283629,-2.562576231,51.4951,1.80E-11,10.00014753,-0.251875,5.803298712,-0.875947446,90.00000001 +265.88,50.43283629,-2.562574824,51.4973,-2.50E-12,10.00036957,-0.1865625,5.863541901,-0.777647197,90.00000001 +265.89,50.43283629,-2.562573416,51.4988,-4.69E-12,10.00036957,-0.121875,5.922560565,-0.678668852,90.00000001 +265.9,50.43283629,-2.562572009,51.4997,7.03E-12,10.00014754,-0.0584375,5.980342384,-0.579098699,90.00000001 +265.91,50.43283629,-2.562570601,51.5,1.64E-11,9.999481439,0.0053125,6.03687527,-0.479023599,90.00000001 +265.92,50.43283629,-2.562569194,51.4996,1.88E-11,9.999037372,0.07,6.09214742,-0.378530755,90.00000001 +265.93,50.43283629,-2.562567787,51.4986,1.64E-11,9.999481436,0.1346875,6.146147317,-0.277707773,90.00000001 +265.94,50.43283629,-2.562566379,51.4969,6.88E-12,10.00014753,0.1984375,6.198863674,-0.176642716,90.00000001 +265.95,50.43283629,-2.562564972,51.4946,-5.47E-12,10.00036956,0.261875,6.250285491,-0.075423534,90.00000001 +265.96,50.43283629,-2.562563564,51.4917,-6.41E-12,10.00036956,0.326875,6.300401994,0.025861367,90.00000001 +265.97,50.43283629,-2.562562157,51.4881,2.34E-12,10.00036955,0.393125,6.349202758,0.127123693,90.00000001 +265.98,50.43283629,-2.562560749,51.4838,4.53E-12,10.00036955,0.4578125,6.396677582,0.228275209,90.00000001 +265.99,50.43283629,-2.562559342,51.4789,2.19E-12,10.00014751,0.52,6.442816498,0.329227622,90.00000001 +266,50.43283629,-2.562557934,51.4734,6.88E-12,9.999481397,0.581875,6.487609938,0.429892984,90.00000001 +266.01,50.43283629,-2.562556527,51.4673,1.17E-11,9.999037321,0.645,6.531048561,0.530183459,90.00000001 +266.02,50.43283629,-2.56255512,51.4605,5.31E-12,9.999481377,0.7084375,6.573123201,0.630011615,90.00000001 +266.03,50.43283629,-2.562553712,51.4531,-1.02E-11,10.00014746,0.77125,6.613825149,0.729290361,90.00000001 +266.04,50.43283629,-2.562552305,51.4451,-2.59E-11,10.00036949,0.8334375,6.653145925,0.827933181,90.00000001 +266.05,50.43283629,-2.562550897,51.4364,-3.28E-11,10.00036947,0.895,6.69107722,0.925854075,90.00000001 +266.06,50.43283629,-2.56254949,51.4272,-2.58E-11,10.00036946,0.9565625,6.727611187,1.022967556,90.00000001 +266.07,50.43283629,-2.562548082,51.4173,-1.17E-11,10.00036944,1.0184375,6.762740146,1.119189,90.00000001 +266.08,50.43283629,-2.562546675,51.4068,-2.34E-12,10.00036943,1.0796875,6.796456879,1.214434467,90.00000001 +266.09,50.43283629,-2.562545267,51.3957,1.39E-16,10.00036941,1.14,6.828754166,1.308620994,90.00000001 +266.1,50.43283629,-2.56254386,51.384,2.19E-12,10.00014736,1.1996875,6.859625418,1.401666303,90.00000001 +266.11,50.43283629,-2.562542452,51.3717,1.09E-11,9.999481238,1.2584375,6.889064104,1.493489379,90.00000001 +266.12,50.43283629,-2.562541045,51.3588,2.41E-11,9.999037152,1.3165625,6.917064093,1.584010121,90.00000001 +266.13,50.43283629,-2.562539638,51.3454,3.05E-11,9.999481198,1.375,6.943619541,1.673149577,90.00000001 +266.14,50.43283629,-2.56253823,51.3313,2.56E-11,10.00014727,1.433125,6.96872489,1.760830053,90.00000001 +266.15,50.43283629,-2.562536823,51.3167,1.86E-11,10.00036928,1.4896875,6.992374926,1.846975003,90.00000001 +266.16,50.43283629,-2.562535415,51.3015,1.63E-11,10.00036926,1.545,7.014564722,1.931509425,90.00000001 +266.17,50.43283629,-2.562534008,51.2858,1.64E-11,10.00036924,1.6,7.03528958,2.014359466,90.00000001 +266.18,50.43283629,-2.5625326,51.2695,1.72E-11,10.00036921,1.655,7.054545202,2.09545299,90.00000001 +266.19,50.43283629,-2.562531193,51.2527,1.64E-11,10.00036918,1.7096875,7.072327577,2.174719295,90.00000001 +266.2,50.43283629,-2.562529785,51.2353,8.44E-12,10.00036916,1.7634375,7.088632982,2.252089166,90.00000001 +266.21,50.43283629,-2.562528378,51.2174,-7.81E-12,10.00036913,1.81625,7.103458036,2.327495168,90.00000001 +266.22,50.43283629,-2.56252697,51.199,-2.50E-11,10.0003691,1.8684375,7.116799644,2.400871581,90.00000001 +266.23,50.43283629,-2.562525563,51.18,-3.50E-11,10.00014704,1.9196875,7.128655001,2.472154406,90.00000001 +266.24,50.43283629,-2.562524155,51.1606,-3.75E-11,9.999480908,1.97,7.139021583,2.54128142,90.00000001 +266.25,50.43283629,-2.562522748,51.1406,-3.75E-11,9.999036811,2.02,7.147897273,2.608192463,90.00000001 +266.26,50.43283629,-2.562521341,51.1202,-3.28E-11,9.999480846,2.069375,7.155280235,2.672829092,90.00000001 +266.27,50.43283629,-2.562519933,51.0992,-1.64E-11,10.00014691,2.1165625,7.161168923,2.735134986,90.00000001 +266.28,50.43283629,-2.562518526,51.0778,2.19E-12,10.00036891,2.1615625,7.165562077,2.795055829,90.00000001 +266.29,50.43283629,-2.562517118,51.056,3.91E-12,10.00036888,2.206875,7.16845878,2.85253931,90.00000001 +266.3,50.43283629,-2.562515711,51.0337,-6.25E-12,10.00036884,2.253125,7.169858458,2.907535294,90.00000001 +266.31,50.43283629,-2.562514303,51.0109,-8.59E-12,10.00036881,2.2978125,7.169760826,2.95999594,90.00000001 +266.32,50.43283629,-2.562512896,50.9877,-5.63E-12,10.00036877,2.34,7.168165826,3.009875411,90.00000001 +266.33,50.43283629,-2.562511488,50.9641,-1.27E-11,10.00036873,2.3815625,7.165073917,3.057130163,90.00000001 +266.34,50.43283629,-2.562510081,50.9401,-2.52E-11,10.0003687,2.423125,7.160485614,3.101719113,90.00000001 +266.35,50.43283629,-2.562508673,50.9156,-2.58E-11,10.00036866,2.463125,7.154401948,3.143603302,90.00000001 +266.36,50.43283629,-2.562507266,50.8908,-1.19E-11,10.00014659,2.50125,7.14682418,3.182746232,90.00000001 +266.37,50.43283629,-2.562505858,50.8656,4.53E-12,9.999480446,2.5384375,7.137753914,3.219113754,90.00000001 +266.38,50.43283629,-2.562504451,50.84,1.16E-11,9.999036341,2.575,7.127192984,3.252674126,90.00000001 +266.39,50.43283629,-2.562503044,50.8141,2.34E-12,9.999480367,2.61125,7.115143682,3.283398186,90.00000001 +266.4,50.43283629,-2.562501636,50.7878,-1.80E-11,10.00014642,2.6465625,7.101608413,3.311259004,90.00000001 +266.41,50.43283629,-2.562500229,50.7611,-3.05E-11,10.00036842,2.6796875,7.086590101,3.3362324,90.00000001 +266.42,50.43283629,-2.562498821,50.7342,-2.44E-11,10.00036837,2.7115625,7.070091838,3.358296547,90.00000001 +266.43,50.43283629,-2.562497414,50.7069,-1.25E-11,10.00036833,2.743125,7.052117064,3.377432191,90.00000001 +266.44,50.43283629,-2.562496006,50.6793,-1.08E-11,10.00036829,2.7728125,7.032669558,3.393622661,90.00000001 +266.45,50.43283629,-2.562494599,50.6514,-1.31E-11,10.00036824,2.8,7.01175339,3.40685386,90.00000001 +266.46,50.43283629,-2.562493191,50.6233,-5.47E-12,10.0003682,2.8265625,6.989372857,3.417114217,90.00000001 +266.47,50.43283629,-2.562491784,50.5949,8.59E-12,10.00014612,2.8534375,6.965532713,3.424394849,90.00000001 +266.48,50.43283629,-2.562490376,50.5662,1.72E-11,9.999479979,2.8796875,6.940237887,3.428689282,90.00000001 +266.49,50.43283629,-2.562488969,50.5373,1.42E-11,9.999035867,2.904375,6.913493707,3.429993907,90.00000001 +266.5,50.43283629,-2.562487562,50.5081,-2.34E-12,9.999479887,2.9265625,6.88530573,3.42830752,90.00000001 +266.51,50.43283629,-2.562486154,50.4787,-2.13E-11,10.00014594,2.9465625,6.855679859,3.423631554,90.00000001 +266.52,50.43283629,-2.562484747,50.4492,-2.19E-11,10.00036793,2.9665625,6.824622223,3.415970192,90.00000001 +266.53,50.43283629,-2.562483339,50.4194,-6.25E-12,10.00036788,2.98625,6.792139355,3.405329965,90.00000001 +266.54,50.43283629,-2.562481932,50.3894,-1.56E-12,10.0001458,3.003125,6.758238073,3.391720326,90.00000001 +266.55,50.43283629,-2.562480524,50.3593,-1.95E-11,9.999479655,3.018125,6.722925423,3.375153022,90.00000001 +266.56,50.43283629,-2.562479117,50.3291,-4.00E-11,9.999035541,3.0334375,6.686208741,3.355642549,90.00000001 +266.57,50.43283629,-2.56247771,50.2986,-4.45E-11,9.99947956,3.0478125,6.64809576,3.333205866,90.00000001 +266.58,50.43283629,-2.562476302,50.2681,-3.98E-11,10.00014561,3.0596875,6.608594388,3.307862624,90.00000001 +266.59,50.43283629,-2.562474895,50.2374,-3.75E-11,10.0003676,3.07,6.567712875,3.279634827,90.00000001 +266.6,50.43283629,-2.562473487,50.2067,-3.52E-11,10.00036755,3.0796875,6.525459816,3.248547169,90.00000001 +266.61,50.43283629,-2.56247208,50.1758,-2.80E-11,10.00014547,3.088125,6.481843977,3.214626749,90.00000001 +266.62,50.43283629,-2.562470672,50.1449,-2.03E-11,9.99947932,3.0946875,6.436874525,3.177903134,90.00000001 +266.63,50.43283629,-2.562469265,50.1139,-1.72E-11,9.999035205,3.1,6.390560742,3.138408294,90.00000001 +266.64,50.43283629,-2.562467858,50.0829,-1.48E-11,9.999479222,3.1046875,6.342912426,3.096176721,90.00000001 +266.65,50.43283629,-2.56246645,50.0518,-8.59E-12,10.00014527,3.108125,6.293939489,3.051245256,90.00000001 +266.66,50.43283629,-2.562465043,50.0207,1.56E-13,10.00036726,3.109375,6.243652129,3.003653032,90.00000001 +266.67,50.43283629,-2.562463635,49.9896,1.17E-11,10.00036721,3.1084375,6.192060832,2.953441647,90.00000001 +266.68,50.43283629,-2.562462228,49.9585,2.58E-11,10.00036716,3.1065625,6.139176426,2.900654759,90.00000001 +266.69,50.43283629,-2.56246082,49.9275,3.05E-11,10.00036711,3.1046875,6.085009913,2.845338434,90.00000001 +266.7,50.43283629,-2.562459413,49.8964,1.64E-11,10.00014503,3.1015625,6.029572637,2.787540972,90.00000001 +266.71,50.43283629,-2.562458005,49.8654,-4.69E-12,9.999478882,3.09625,5.972876171,2.727312737,90.00000001 +266.72,50.43283629,-2.562456598,49.8345,-1.41E-11,9.999034767,3.09,5.914932376,2.664706212,90.00000001 +266.73,50.43283629,-2.562455191,49.8036,-9.38E-12,9.999478785,3.083125,5.855753285,2.599776056,90.00000001 +266.74,50.43283629,-2.562453783,49.7728,-5.55E-17,10.00014484,3.074375,5.795351272,2.532578879,90.00000001 +266.75,50.43283629,-2.562452376,49.7421,1.17E-11,10.00036682,3.0634375,5.733739,2.463173178,90.00000001 +266.76,50.43283629,-2.562450968,49.7115,2.81E-11,10.00036677,3.05125,5.670929304,2.39161963,90.00000001 +266.77,50.43283629,-2.562449561,49.6811,4.22E-11,10.00014469,3.038125,5.606935304,2.317980516,90.00000001 +266.78,50.43283629,-2.562448153,49.6507,3.98E-11,9.999478547,3.0234375,5.541770407,2.242320064,90.00000001 +266.79,50.43283629,-2.562446746,49.6206,1.64E-11,9.999034434,3.0078125,5.475448136,2.164704336,90.00000001 +266.8,50.43283629,-2.562445339,49.5906,-1.17E-11,9.999478453,2.9915625,5.407982413,2.085200942,90.00000001 +266.81,50.43283629,-2.562443931,49.5607,-1.89E-11,10.0001445,2.973125,5.339387276,2.003879208,90.00000001 +266.82,50.43283629,-2.562442524,49.5311,-7.81E-13,10.00036649,2.953125,5.269677105,1.920810011,90.00000001 +266.83,50.43283629,-2.562441116,49.5017,1.72E-11,10.00036645,2.933125,5.198866397,1.836065886,90.00000001 +266.84,50.43283629,-2.562439709,49.4724,1.25E-11,10.0003664,2.91125,5.126969991,1.749720688,90.00000001 +266.85,50.43283629,-2.562438301,49.4434,-3.12E-12,10.00036635,2.8865625,5.054002899,1.661849704,90.00000001 +266.86,50.43283629,-2.562436894,49.4147,-2.34E-12,10.00014428,2.8615625,4.979980305,1.572529594,90.00000001 +266.87,50.43283629,-2.562435486,49.3862,1.72E-11,9.999478133,2.8365625,4.904917734,1.481838167,90.00000001 +266.88,50.43283629,-2.562434079,49.3579,3.20E-11,9.999034023,2.8096875,4.82883083,1.389854549,90.00000001 +266.89,50.43283629,-2.562432672,49.33,2.72E-11,9.999478044,2.7815625,4.75173552,1.29665901,90.00000001 +266.9,50.43283629,-2.562431264,49.3023,1.41E-11,10.0001441,2.753125,4.673647789,1.202332739,90.00000001 +266.91,50.43283629,-2.562429857,49.2749,1.03E-11,10.00036609,2.7228125,4.594584083,1.106958013,90.00000001 +266.92,50.43283629,-2.562428449,49.2478,1.27E-11,10.00036605,2.69,4.514560843,1.010617967,90.00000001 +266.93,50.43283629,-2.562427042,49.2211,7.03E-12,10.00036601,2.6565625,4.433594802,0.913396712,90.00000001 +266.94,50.43283629,-2.562425634,49.1947,-3.13E-12,10.00036596,2.623125,4.351702861,0.815378931,90.00000001 +266.95,50.43283629,-2.562424227,49.1686,-2.34E-12,10.00036592,2.588125,4.268902152,0.71665011,90.00000001 +266.96,50.43283629,-2.562422819,49.1429,9.53E-12,10.00036588,2.5515625,4.185209863,0.617296363,90.00000001 +266.97,50.43283629,-2.562421412,49.1176,1.41E-11,10.00036584,2.5146875,4.100643584,0.517404323,90.00000001 +266.98,50.43283629,-2.562420004,49.0926,-7.82E-13,10.00036581,2.4765625,4.015220963,0.417061136,90.00000001 +266.99,50.43283629,-2.562418597,49.068,-2.34E-11,10.00014373,2.43625,3.928959818,0.316354235,90.00000001 +267,50.43283629,-2.562417189,49.0439,-3.42E-11,9.999477597,2.395,3.84187814,0.215371455,90.00000001 +267.01,50.43283629,-2.562415782,49.0201,-2.73E-11,9.999033495,2.3534375,3.753994092,0.114200916,90.00000001 +267.02,50.43283629,-2.562414375,48.9968,-1.03E-11,9.999477523,2.31125,3.665326123,0.012930741,90.00000001 +267.03,50.43283629,-2.562412967,48.9739,6.09E-12,10.00014359,2.2684375,3.575892682,-0.088350665,90.00000001 +267.04,50.43283629,-2.56241156,48.9514,1.72E-11,10.00036558,2.224375,3.485712448,-0.189555065,90.00000001 +267.05,50.43283629,-2.562410152,48.9294,2.66E-11,10.00036555,2.178125,3.394804329,-0.29059411,90.00000001 +267.06,50.43283629,-2.562408745,48.9078,2.97E-11,10.00036552,2.1303125,3.303187174,-0.39137985,90.00000001 +267.07,50.43283629,-2.562407337,48.8868,1.39E-11,10.00036548,2.083125,3.210880236,-0.491824221,90.00000001 +267.08,50.43283629,-2.56240593,48.8662,-1.17E-11,10.00036545,2.0365625,3.117902707,-0.591839734,90.00000001 +267.09,50.43283629,-2.562404522,48.846,-2.13E-11,10.00036542,1.9878125,3.02427407,-0.691339183,90.00000001 +267.1,50.43283629,-2.562403115,48.8264,-1.25E-11,10.00036539,1.9365625,2.930013861,-0.79023571,90.00000001 +267.11,50.43283629,-2.562401707,48.8073,-6.25E-12,10.00036536,1.885,2.835141733,-0.888443197,90.00000001 +267.12,50.43283629,-2.5624003,48.7887,-1.33E-11,10.0001433,1.8334375,2.739677568,-0.98587593,90.00000001 +267.13,50.43283629,-2.562398892,48.7706,-2.91E-11,9.99947717,1.78125,2.64364119,-1.082448998,90.00000001 +267.14,50.43283629,-2.562397485,48.7531,-4.55E-11,9.999033076,1.7284375,2.547052767,-1.178078118,90.00000001 +267.15,50.43283629,-2.562396078,48.736,-5.56E-11,9.999477115,1.6746875,2.44993241,-1.272679924,90.00000001 +267.16,50.43283629,-2.56239467,48.7196,-5.63E-11,10.00014319,1.6196875,2.352300401,-1.366171969,90.00000001 +267.17,50.43283629,-2.562393263,48.7036,-4.47E-11,10.0003652,1.56375,2.254177196,-1.458472662,90.00000001 +267.18,50.43283629,-2.562391855,48.6883,-1.88E-11,10.00036517,1.5078125,2.155583192,-1.549501561,90.00000001 +267.19,50.43283629,-2.562390448,48.6735,1.25E-11,10.00036515,1.451875,2.056539015,-1.639179253,90.00000001 +267.2,50.43283629,-2.56238904,48.6592,3.05E-11,10.00036513,1.3946875,1.957065405,-1.727427588,90.00000001 +267.21,50.43283629,-2.562387633,48.6456,2.72E-11,10.00036511,1.3365625,1.857183048,-1.814169559,90.00000001 +267.22,50.43283629,-2.562386225,48.6325,1.33E-11,10.00036509,1.2784375,1.756912798,-1.899329537,90.00000001 +267.23,50.43283629,-2.562384818,48.62,3.12E-12,10.00036507,1.2196875,1.656275741,-1.982833323,90.00000001 +267.24,50.43283629,-2.56238341,48.6081,2.50E-12,10.00036505,1.1596875,1.555292732,-2.064607979,90.00000001 +267.25,50.43283629,-2.562382003,48.5968,1.17E-11,10.000143,1.0984375,1.453984913,-2.144582288,90.00000001 +267.26,50.43283629,-2.562380595,48.5861,2.34E-11,9.999476881,1.036875,1.352373483,-2.222686519,90.00000001 +267.27,50.43283629,-2.562379188,48.5761,2.11E-11,9.999032799,0.9765625,1.250479586,-2.298852549,90.00000001 +267.28,50.43283629,-2.562377781,48.5666,2.34E-12,9.99947685,0.9165625,1.148324534,-2.373013857,90.00000001 +267.29,50.43283629,-2.562376373,48.5577,-1.19E-11,10.00014294,0.8546875,1.045929699,-2.445105928,90.00000001 +267.3,50.43283629,-2.562374966,48.5495,-1.02E-11,10.00036496,0.791875,0.943316453,-2.515065851,90.00000001 +267.31,50.43283629,-2.562373558,48.5419,-6.41E-12,10.00036494,0.73,0.840506167,-2.582832549,90.00000001 +267.32,50.43283629,-2.562372151,48.5349,-1.17E-11,10.0001429,0.668125,0.737520384,-2.648347007,90.00000001 +267.33,50.43283629,-2.562370743,48.5285,-1.89E-11,9.999476791,0.6046875,0.63438059,-2.711552044,90.00000001 +267.34,50.43283629,-2.562369336,48.5228,-2.13E-11,9.999032716,0.54,0.53110827,-2.772392598,90.00000001 +267.35,50.43283629,-2.562367929,48.5177,-1.89E-11,9.999476774,0.4753125,0.427725083,-2.830815558,90.00000001 +267.36,50.43283629,-2.562366521,48.5133,-9.38E-12,10.00014287,0.4115625,0.324252515,-2.886770043,90.00000001 +267.37,50.43283629,-2.562365114,48.5095,5.47E-12,10.00036489,0.3484375,0.220712281,-2.940207181,90.00000001 +267.38,50.43283629,-2.562363706,48.5063,1.64E-11,10.00036489,0.2846875,0.117125923,-2.99108039,90.00000001 +267.39,50.43283629,-2.562362299,48.5038,2.02E-11,10.00014285,0.22,0.0135151,-3.039345381,90.00000001 +267.4,50.43283629,-2.562360891,48.5019,1.80E-11,9.99947675,0.1553125,-0.09009853,-3.084960041,90.00000001 +267.41,50.43283629,-2.562359484,48.5007,7.81E-12,9.999032682,0.0915625,-0.19369331,-3.127884492,90.00000001 +267.42,50.43283629,-2.562358077,48.5001,-6.87E-12,9.999476746,0.0284375,-0.297247697,-3.168081434,90.00000001 +267.43,50.43283629,-2.562356669,48.5001,-1.66E-11,10.00014285,-0.0353125,-0.400739975,-3.205515746,90.00000001 +267.44,50.43283629,-2.562355262,48.5008,-1.95E-11,10.00036488,-0.1,-0.504148543,-3.240154827,90.00000001 +267.45,50.43283629,-2.562353854,48.5021,-2.03E-11,10.00036488,-0.165,-0.60745186,-3.271968423,90.00000001 +267.46,50.43283629,-2.562352447,48.5041,-2.02E-11,10.00036488,-0.23,-0.710628323,-3.300928804,90.00000001 +267.47,50.43283629,-2.562351039,48.5067,-1.87E-11,10.00036489,-0.295,-0.813656391,-3.327010759,90.00000001 +267.48,50.43283629,-2.562349632,48.51,-1.72E-11,10.00014286,-0.36,-0.916514519,-3.350191486,90.00000001 +267.49,50.43283629,-2.562348224,48.5139,-1.41E-11,9.999476769,-0.4246875,-1.019181222,-3.370450758,90.00000001 +267.5,50.43283629,-2.562346817,48.5185,-6.87E-12,9.99903271,-0.488125,-1.121635129,-3.387770985,90.00000001 +267.51,50.43283629,-2.56234541,48.5237,-2.19E-12,9.999476783,-0.55,-1.223854753,-3.402137043,90.00000001 +267.52,50.43283629,-2.562344002,48.5295,-6.88E-12,10.00014289,-0.611875,-1.325818838,-3.413536382,90.00000001 +267.53,50.43283629,-2.562342595,48.5359,-1.17E-11,10.00036493,-0.675,-1.427506012,-3.421959033,90.00000001 +267.54,50.43283629,-2.562341187,48.543,-5.31E-12,10.00036495,-0.7384375,-1.528895019,-3.427397721,90.00000001 +267.55,50.43283629,-2.56233978,48.5507,1.02E-11,10.00014292,-0.80125,-1.629964831,-3.429847688,90.00000001 +267.56,50.43283629,-2.562338372,48.559,2.59E-11,9.999476839,-0.8634375,-1.730694192,-3.429306701,90.00000001 +267.57,50.43283629,-2.562336965,48.568,3.28E-11,9.999032787,-0.925,-1.831062131,-3.425775391,90.00000001 +267.58,50.43283629,-2.562335558,48.5775,2.58E-11,9.999476868,-0.9865625,-1.931047678,-3.419256678,90.00000001 +267.59,50.43283629,-2.56233415,48.5877,1.17E-11,10.00014298,-1.0484375,-2.03062992,-3.40975635,90.00000001 +267.6,50.43283629,-2.562332743,48.5985,2.34E-12,10.00036503,-1.1096875,-2.129788116,-3.397282715,90.00000001 +267.61,50.43283629,-2.562331335,48.6099,2.19E-12,10.00036505,-1.1696875,-2.228501582,-3.381846545,90.00000001 +267.62,50.43283629,-2.562329928,48.6219,1.09E-11,10.00014304,-1.2284375,-2.326749578,-3.36346136,90.00000001 +267.63,50.43283629,-2.56232852,48.6345,2.42E-11,9.999476957,-1.2865625,-2.424511705,-3.342143205,90.00000001 +267.64,50.43283629,-2.562327113,48.6476,3.14E-11,9.999032911,-1.345,-2.521767509,-3.317910585,90.00000001 +267.65,50.43283629,-2.562325706,48.6614,2.81E-11,9.999476999,-1.403125,-2.61849665,-3.290784758,90.00000001 +267.66,50.43283629,-2.562324298,48.6757,2.27E-11,10.00014312,-1.4596875,-2.714678961,-3.260789329,90.00000001 +267.67,50.43283629,-2.562322891,48.6906,1.86E-11,10.00036518,-1.5153125,-2.81029433,-3.227950425,90.00000001 +267.68,50.43283629,-2.562321483,48.706,8.59E-12,10.0003652,-1.5715625,-2.905322818,-3.192296693,90.00000001 +267.69,50.43283629,-2.562320076,48.722,-4.69E-12,10.00036523,-1.628125,-2.999744543,-3.153859247,90.00000001 +267.7,50.43283629,-2.562318668,48.7386,-6.09E-12,10.00036525,-1.683125,-3.093539854,-3.112671603,90.00000001 +267.71,50.43283629,-2.562317261,48.7557,5.47E-12,10.00036528,-1.7365625,-3.186689098,-3.068769628,90.00000001 +267.72,50.43283629,-2.562315853,48.7733,1.33E-11,10.00036531,-1.79,-3.279172851,-3.022191655,90.00000001 +267.73,50.43283629,-2.562314446,48.7915,9.38E-12,10.00036533,-1.843125,-3.370971748,-2.972978247,90.00000001 +267.74,50.43283629,-2.562313038,48.8102,7.82E-13,10.00036536,-1.894375,-3.462066709,-2.921172434,90.00000001 +267.75,50.43283629,-2.562311631,48.8294,-1.03E-11,10.00014336,-1.9434375,-3.552438655,-2.866819252,90.00000001 +267.76,50.43283629,-2.562310223,48.8491,-2.27E-11,9.999477293,-1.991875,-3.642068734,-2.809966197,90.00000001 +267.77,50.43283629,-2.562308816,48.8692,-2.19E-11,9.999033258,-2.0415625,-3.730938155,-2.750662773,90.00000001 +267.78,50.43283629,-2.562307409,48.8899,-3.75E-12,9.999477356,-2.0915625,-3.819028468,-2.688960776,90.00000001 +267.79,50.43283629,-2.562306001,48.9111,1.33E-11,10.00014349,-2.139375,-3.906321224,-2.624913949,90.00000001 +267.8,50.43283629,-2.562304594,48.9327,1.86E-11,10.00036556,-2.185,-3.992798145,-2.558578156,90.00000001 +267.81,50.43283629,-2.562303186,48.9548,1.86E-11,10.00036559,-2.23,-4.078441298,-2.490011209,90.00000001 +267.82,50.43283629,-2.562301779,48.9773,1.56E-11,10.00036562,-2.2746875,-4.163232692,-2.41927298,90.00000001 +267.83,50.43283629,-2.562300371,49.0003,7.81E-12,10.00036566,-2.318125,-4.247154622,-2.346425063,90.00000001 +267.84,50.43283629,-2.562298964,49.0237,3.28E-12,10.0003657,-2.36,-4.330189614,-2.271531057,90.00000001 +267.85,50.43283629,-2.562297556,49.0475,1.17E-11,10.00036574,-2.4015625,-4.412320249,-2.194656278,90.00000001 +267.86,50.43283629,-2.562296149,49.0717,2.50E-11,10.00036577,-2.443125,-4.493529511,-2.115867706,90.00000001 +267.87,50.43283629,-2.562294741,49.0964,2.81E-11,10.00036581,-2.4828125,-4.573800325,-2.035234037,90.00000001 +267.88,50.43283629,-2.562293334,49.1214,2.36E-11,10.00014382,-2.5196875,-4.653115904,-1.952825632,90.00000001 +267.89,50.43283629,-2.562291926,49.1468,1.89E-11,9.999477758,-2.5553125,-4.731459804,-1.868714339,90.00000001 +267.9,50.43283629,-2.562290519,49.1725,9.53E-12,9.999033732,-2.5915625,-4.80881558,-1.782973497,90.00000001 +267.91,50.43283629,-2.562289112,49.1986,-2.34E-12,9.999477839,-2.628125,-4.885167077,-1.695677877,90.00000001 +267.92,50.43283629,-2.562287704,49.2251,-5.47E-12,10.00014398,-2.6628125,-4.960498422,-1.606903567,90.00000001 +267.93,50.43283629,-2.562286297,49.2519,-4.69E-12,10.00036606,-2.695,-5.034793802,-1.516728031,90.00000001 +267.94,50.43283629,-2.562284889,49.279,-1.31E-11,10.0003661,-2.7265625,-5.10803769,-1.425229937,90.00000001 +267.95,50.43283629,-2.562283482,49.3064,-2.50E-11,10.00036614,-2.758125,-5.180214902,-1.332488983,90.00000001 +267.96,50.43283629,-2.562282074,49.3342,-2.67E-11,10.00036618,-2.7878125,-5.251310255,-1.238586071,90.00000001 +267.97,50.43283629,-2.562280667,49.3622,-2.20E-11,10.00036623,-2.8146875,-5.32130891,-1.143603075,90.00000001 +267.98,50.43283629,-2.562279259,49.3905,-2.03E-11,10.00036627,-2.84,-5.390196314,-1.047622847,90.00000001 +267.99,50.43283629,-2.562277852,49.419,-2.03E-11,10.00036632,-2.865,-5.457958027,-0.950729095,90.00000001 +268,50.43283629,-2.562276444,49.4478,-1.95E-11,10.00036636,-2.89,-5.524579955,-0.85300633,90.00000001 +268.01,50.43283629,-2.562275037,49.4768,-1.42E-11,10.00014437,-2.914375,-5.590048118,-0.754539694,90.00000001 +268.02,50.43283629,-2.562273629,49.5061,2.34E-12,9.99947832,-2.9365625,-5.654348879,-0.655415074,90.00000001 +268.03,50.43283629,-2.562272222,49.5356,2.34E-11,9.9990343,-2.95625,-5.717468775,-0.555718927,90.00000001 +268.04,50.43283629,-2.562270815,49.5652,3.28E-11,9.999478412,-2.975,-5.779394684,-0.455538174,90.00000001 +268.05,50.43283629,-2.562269407,49.5951,2.58E-11,10.00014456,-2.9934375,-5.840113599,-0.354960246,90.00000001 +268.06,50.43283629,-2.562268,49.6251,9.38E-12,10.00036664,-3.01125,-5.899612917,-0.254072748,90.00000001 +268.07,50.43283629,-2.562266592,49.6553,-2.34E-12,10.00036669,-3.0278125,-5.957880147,-0.152963688,90.00000001 +268.08,50.43283629,-2.562265185,49.6857,7.03E-12,10.00036673,-3.0415625,-6.014903198,-0.051721244,90.00000001 +268.09,50.43283629,-2.562263777,49.7162,3.28E-11,10.00036678,-3.053125,-6.070670097,0.04956635,90.00000001 +268.1,50.43283629,-2.56226237,49.7467,4.45E-11,10.0001448,-3.0646875,-6.125169213,0.150810628,90.00000001 +268.11,50.43283629,-2.562260962,49.7775,2.34E-11,9.999478744,-3.075,-6.178389142,0.251923469,90.00000001 +268.12,50.43283629,-2.562259555,49.8083,-1.17E-11,9.999034726,-3.0828125,-6.230318771,0.352816581,90.00000001 +268.13,50.43283629,-2.562258148,49.8391,-3.05E-11,9.999478841,-3.0903125,-6.280947327,0.453402072,90.00000001 +268.14,50.43283629,-2.56225674,49.8701,-3.05E-11,10.00014499,-3.0978125,-6.330264154,0.553592165,90.00000001 +268.15,50.43283629,-2.562255333,49.9011,-3.05E-11,10.00036707,-3.1028125,-6.378259052,0.653299541,90.00000001 +268.16,50.43283629,-2.562253925,49.9322,-3.28E-11,10.00036712,-3.105,-6.424921881,0.752437168,90.00000001 +268.17,50.43283629,-2.562252518,49.9632,-2.58E-11,10.00036717,-3.1065625,-6.470242957,0.850918701,90.00000001 +268.18,50.43283629,-2.56225111,49.9943,-1.17E-11,10.00036722,-3.1084375,-6.514212769,0.948658254,90.00000001 +268.19,50.43283629,-2.562249703,50.0254,2.78E-16,10.00014523,-3.109375,-6.556822208,1.045570512,90.00000001 +268.2,50.43283629,-2.562248295,50.0565,9.38E-12,9.999479181,-3.108125,-6.598062335,1.141571023,90.00000001 +268.21,50.43283629,-2.562246888,50.0876,1.64E-11,9.999035163,-3.1046875,-6.637924556,1.236576077,90.00000001 +268.22,50.43283629,-2.562245481,50.1186,1.88E-11,9.999479278,-3.1,-6.676400505,1.330502825,90.00000001 +268.23,50.43283629,-2.562244073,50.1496,2.11E-11,10.00014543,-3.0946875,-6.713482162,1.423269333,90.00000001 +268.24,50.43283629,-2.562242666,50.1805,2.58E-11,10.00036751,-3.0878125,-6.749161848,1.514794757,90.00000001 +268.25,50.43283629,-2.562241258,50.2114,2.11E-11,10.00036756,-3.0784375,-6.783432001,1.604999284,90.00000001 +268.26,50.43283629,-2.562239851,50.2421,4.72E-16,10.00014557,-3.068125,-6.816285573,1.69380419,90.00000001 +268.27,50.43283629,-2.562238443,50.2727,-1.87E-11,9.999479519,-3.058125,-6.847715631,1.781132068,90.00000001 +268.28,50.43283629,-2.562237036,50.3033,-1.41E-11,9.999035501,-3.04625,-6.877715586,1.866906772,90.00000001 +268.29,50.43283629,-2.562235629,50.3337,4.69E-12,9.999479614,-3.03125,-6.906279309,1.951053474,90.00000001 +268.3,50.43283629,-2.562234221,50.3639,1.64E-11,10.00014576,-3.0153125,-6.933400667,2.033498892,90.00000001 +268.31,50.43283629,-2.562232814,50.394,2.11E-11,10.00036784,-2.9996875,-6.959074104,2.114171063,90.00000001 +268.32,50.43283629,-2.562231406,50.4239,2.58E-11,10.00036789,-2.9828125,-6.983294233,2.192999628,90.00000001 +268.33,50.43283629,-2.562229999,50.4537,2.12E-11,10.0001459,-2.9634375,-7.006055955,2.269915831,90.00000001 +268.34,50.43283629,-2.562228591,50.4832,-1.56E-12,9.999479848,-2.9428125,-7.027354573,2.344852695,90.00000001 +268.35,50.43283629,-2.562227184,50.5125,-3.13E-11,9.999035828,-2.921875,-7.047185616,2.417744787,90.00000001 +268.36,50.43283629,-2.562225777,50.5417,-4.77E-11,9.99947994,-2.8996875,-7.06554496,2.488528508,90.00000001 +268.37,50.43283629,-2.562224369,50.5705,-4.14E-11,10.00014608,-2.87625,-7.082428766,2.557142267,90.00000001 +268.38,50.43283629,-2.562222962,50.5992,-2.11E-11,10.00036816,-2.8515625,-7.097833481,2.623526131,90.00000001 +268.39,50.43283629,-2.562221554,50.6276,-5.47E-12,10.00036821,-2.824375,-7.111755897,2.687622289,90.00000001 +268.4,50.43283629,-2.562220147,50.6557,7.81E-13,10.00014622,-2.7953125,-7.124193092,2.749374764,90.00000001 +268.41,50.43283629,-2.562218739,50.6835,1.03E-11,9.999480162,-2.7665625,-7.135142544,2.808729754,90.00000001 +268.42,50.43283629,-2.562217332,50.711,2.34E-11,9.999036139,-2.738125,-7.144601848,2.865635464,90.00000001 +268.43,50.43283629,-2.562215925,50.7383,2.72E-11,9.999480247,-2.7078125,-7.152569113,2.920042333,90.00000001 +268.44,50.43283629,-2.562214517,50.7652,2.25E-11,10.00014639,-2.6746875,-7.159042677,2.971902862,90.00000001 +268.45,50.43283629,-2.56221311,50.7918,1.87E-11,10.00036846,-2.64,-7.164021164,3.021171847,90.00000001 +268.46,50.43283629,-2.562211702,50.818,1.72E-11,10.0003685,-2.605,-7.167503545,3.067806314,90.00000001 +268.47,50.43283629,-2.562210295,50.8439,1.64E-11,10.00036854,-2.57,-7.169489072,3.111765642,90.00000001 +268.48,50.43283629,-2.562208887,50.8694,1.16E-11,10.00036858,-2.534375,-7.169977347,3.153011441,90.00000001 +268.49,50.43283629,-2.56220748,50.8946,-4.69E-12,10.00036862,-2.4965625,-7.168968254,3.19150773,90.00000001 +268.5,50.43283629,-2.562206072,50.9194,-2.27E-11,10.00036866,-2.4565625,-7.166462022,3.227221049,90.00000001 +268.51,50.43283629,-2.562204665,50.9437,-2.11E-11,10.00014667,-2.4165625,-7.162459167,3.260120114,90.00000001 +268.52,50.43283629,-2.562203257,50.9677,-9.37E-13,9.999480606,-2.3765625,-7.156960548,3.290176391,90.00000001 +268.53,50.43283629,-2.56220185,50.9913,1.56E-11,9.999036577,-2.334375,-7.149967254,3.317363525,90.00000001 +268.54,50.43283629,-2.562200443,51.0144,1.95E-11,9.99948068,-2.29,-7.141480775,3.341657852,90.00000001 +268.55,50.43283629,-2.562199035,51.0371,1.89E-11,10.00014681,-2.245,-7.131502945,3.363038231,90.00000001 +268.56,50.43283629,-2.562197628,51.0593,1.89E-11,10.00036888,-2.2,-7.12003571,3.381485982,90.00000001 +268.57,50.43283629,-2.56219622,51.0811,1.95E-11,10.00036892,-2.155,-7.107081593,3.396985064,90.00000001 +268.58,50.43283629,-2.562194813,51.1024,1.55E-11,10.00036895,-2.109375,-7.092643285,3.409521896,90.00000001 +268.59,50.43283629,-2.562193405,51.1233,-1.56E-12,10.00036898,-2.0615625,-7.07672371,3.419085593,90.00000001 +268.6,50.43283629,-2.562191998,51.1437,-2.19E-11,10.00036901,-2.0115625,-7.059326305,3.425667789,90.00000001 +268.61,50.43283629,-2.56219059,51.1635,-2.25E-11,10.00036904,-1.9615625,-7.040454623,3.429262698,90.00000001 +268.62,50.43283629,-2.562189183,51.1829,-7.81E-13,10.00036908,-1.911875,-7.020112615,3.429867283,90.00000001 +268.63,50.43283629,-2.562187775,51.2018,2.34E-11,10.00036911,-1.86125,-6.998304524,3.427480971,90.00000001 +268.64,50.43283629,-2.562186368,51.2201,3.12E-11,10.0001471,-1.8096875,-6.975034989,3.422105882,90.00000001 +268.65,50.43283629,-2.56218496,51.238,1.80E-11,9.999481028,-1.7565625,-6.950308766,3.4137466,90.00000001 +268.66,50.43283629,-2.562183553,51.2553,-9.38E-13,9.99903699,-1.7015625,-6.924131069,3.402410516,90.00000001 +268.67,50.43283629,-2.562182146,51.272,-4.69E-12,9.999481083,-1.646875,-6.896507399,3.388107484,90.00000001 +268.68,50.43283629,-2.562180738,51.2882,3.12E-12,10.00014721,-1.593125,-6.867443427,3.370849937,90.00000001 +268.69,50.43283629,-2.562179331,51.3039,2.50E-12,10.00036926,-1.538125,-6.836945285,3.350653003,90.00000001 +268.7,50.43283629,-2.562177923,51.319,-1.09E-11,10.00036929,-1.48125,-6.805019332,3.327534214,90.00000001 +268.71,50.43283629,-2.562176516,51.3335,-2.58E-11,10.00036931,-1.4234375,-6.771672271,3.301513794,90.00000001 +268.72,50.43283629,-2.562175108,51.3475,-3.14E-11,10.00036933,-1.365,-6.736911036,3.272614375,90.00000001 +268.73,50.43283629,-2.562173701,51.3608,-2.42E-11,10.00036935,-1.3065625,-6.700742846,3.240861226,90.00000001 +268.74,50.43283629,-2.562172293,51.3736,-1.09E-11,10.00036937,-1.2484375,-6.663175322,3.206281963,90.00000001 +268.75,50.43283629,-2.562170886,51.3858,-2.19E-12,10.00036939,-1.1896875,-6.624216254,3.16890678,90.00000001 +268.76,50.43283629,-2.562169478,51.3974,-2.50E-16,10.00036941,-1.13,-6.58387378,3.128768279,90.00000001 +268.77,50.43283629,-2.562168071,51.4084,-2.78E-16,10.00014739,-1.07,-6.542156437,3.085901468,90.00000001 +268.78,50.43283629,-2.562166663,51.4188,-2.34E-12,9.999481312,-1.0096875,-6.499072761,3.040343645,90.00000001 +268.79,50.43283629,-2.562165256,51.4286,-1.17E-11,9.999037261,-0.9484375,-6.454631862,2.992134632,90.00000001 +268.8,50.43283629,-2.562163849,51.4378,-2.58E-11,9.999481342,-0.8865625,-6.408843023,2.941316427,90.00000001 +268.81,50.43283629,-2.562162441,51.4463,-3.27E-11,10.00014745,-0.825,-6.361715755,2.887933377,90.00000001 +268.82,50.43283629,-2.562161034,51.4543,-2.73E-11,10.0003695,-0.763125,-6.313259912,2.832031947,90.00000001 +268.83,50.43283629,-2.562159626,51.4616,-1.94E-11,10.00036951,-0.6996875,-6.263485636,2.773661012,90.00000001 +268.84,50.43283629,-2.562158219,51.4683,-1.41E-11,10.00036952,-0.6353125,-6.212403355,2.712871336,90.00000001 +268.85,50.43283629,-2.562156811,51.4743,-4.53E-12,10.00036953,-0.5715625,-6.16002361,2.649716032,90.00000001 +268.86,50.43283629,-2.562155404,51.4797,9.53E-12,10.00036954,-0.5084375,-6.106357461,2.584250161,90.00000001 +268.87,50.43283629,-2.562153996,51.4845,1.66E-11,10.00036955,-0.445,-6.05141608,2.516530732,90.00000001 +268.88,50.43283629,-2.562152589,51.4886,9.37E-12,10.00036955,-0.3815625,-5.995210983,2.446616875,90.00000001 +268.89,50.43283629,-2.562151181,51.4921,-5.31E-12,10.00036956,-0.3184375,-5.937753801,2.374569552,90.00000001 +268.9,50.43283629,-2.562149774,51.495,-1.56E-11,10.00014753,-0.2546875,-5.879056624,2.300451502,90.00000001 +268.91,50.43283629,-2.562148366,51.4972,-1.86E-11,9.999481434,-0.19,-5.819131656,2.22432747,90.00000001 +268.92,50.43283629,-2.562146959,51.4988,-1.87E-11,9.999037371,-0.125,-5.757991444,2.146263804,90.00000001 +268.93,50.43283629,-2.562145552,51.4997,-1.87E-11,9.999481439,-0.06,-5.695648766,2.066328571,90.00000001 +268.94,50.43283629,-2.562144144,51.5,-1.64E-11,10.00014754,0.0046875,-5.632116627,1.984591444,90.00000001 +268.95,50.43283629,-2.562142737,51.4996,-7.03E-12,10.00036957,0.0684375,-5.567408321,1.901123754,90.00000001 +268.96,50.43283629,-2.562141329,51.4986,4.69E-12,10.00036957,0.131875,-5.501537254,1.815998211,90.00000001 +268.97,50.43283629,-2.562139922,51.497,2.50E-12,10.00014753,0.1965625,-5.434517292,1.729289128,90.00000001 +268.98,50.43283629,-2.562138514,51.4947,-1.56E-11,9.999481431,0.2615625,-5.366362415,1.641072019,90.00000001 +268.99,50.43283629,-2.562137107,51.4917,-2.64E-11,9.99903736,0.325,-5.29708689,1.551423949,90.00000001 +269,50.43283629,-2.5621357,51.4882,-1.41E-11,9.99948142,0.3884375,-5.226705041,1.460422953,90.00000001 +269.01,50.43283629,-2.562134292,51.484,4.84E-12,10.00014751,0.4534375,-5.155231708,1.368148501,90.00000001 +269.02,50.43283629,-2.562132885,51.4791,7.19E-12,10.00036954,0.518125,-5.082681786,1.274680979,90.00000001 +269.03,50.43283629,-2.562131477,51.4736,-4.53E-12,10.00036953,0.5815625,-5.009070403,1.180101919,90.00000001 +269.04,50.43283629,-2.56213007,51.4675,-1.17E-11,10.00014749,0.645,-4.934412914,1.08449377,90.00000001 +269.05,50.43283629,-2.562128662,51.4607,-7.66E-12,9.999481377,0.708125,-4.85872496,0.987939953,90.00000001 +269.06,50.43283629,-2.562127255,51.4533,-1.56E-12,9.999037299,0.7696875,-4.782022298,0.890524638,90.00000001 +269.07,50.43283629,-2.562125848,51.4453,2.50E-12,9.999481353,0.8303125,-4.704321027,0.792332735,90.00000001 +269.08,50.43283629,-2.56212444,51.4367,9.37E-12,10.00014744,0.891875,-4.625637249,0.693449903,90.00000001 +269.09,50.43283629,-2.562123033,51.4275,1.41E-11,10.00036946,0.955,-4.545987521,0.593962428,90.00000001 +269.1,50.43283629,-2.562121625,51.4176,1.17E-11,10.00036944,1.0178125,-4.465388402,0.493956999,90.00000001 +269.11,50.43283629,-2.562120218,51.4071,1.41E-11,10.00014739,1.078125,-4.383856737,0.393520821,90.00000001 +269.12,50.43283629,-2.56211881,51.396,2.34E-11,9.999481276,1.136875,-4.301409543,0.292741441,90.00000001 +269.13,50.43283629,-2.562117403,51.3844,2.12E-11,9.999037191,1.1965625,-4.218064065,0.191706865,90.00000001 +269.14,50.43283629,-2.562115996,51.3721,3.12E-12,9.999481238,1.2565625,-4.133837722,0.090505044,90.00000001 +269.15,50.43283629,-2.562114588,51.3592,-1.02E-11,10.00014732,1.3146875,-4.048748047,-0.010775617,90.00000001 +269.16,50.43283629,-2.562113181,51.3458,-7.97E-12,10.00036933,1.371875,-3.962812915,-0.112046939,90.00000001 +269.17,50.43283629,-2.562111773,51.3318,-4.53E-12,10.00036931,1.43,-3.876050145,-0.213220571,90.00000001 +269.18,50.43283629,-2.562110366,51.3172,-1.00E-11,10.00014725,1.488125,-3.7884779,-0.314208221,90.00000001 +269.19,50.43283629,-2.562108958,51.302,-1.62E-11,9.999481129,1.5446875,-3.700114458,-0.414921883,90.00000001 +269.2,50.43283629,-2.562107551,51.2863,-1.72E-11,9.999037038,1.6,-3.610978383,-0.515273779,90.00000001 +269.21,50.43283629,-2.562106144,51.27,-1.64E-11,9.999481078,1.655,-3.521088123,-0.615176305,90.00000001 +269.22,50.43283629,-2.562104736,51.2532,-1.41E-11,10.00014715,1.7096875,-3.430462529,-0.71454237,90.00000001 +269.23,50.43283629,-2.562103329,51.2358,-7.66E-12,10.00036916,1.763125,-3.339120566,-0.813285401,90.00000001 +269.24,50.43283629,-2.562101921,51.2179,-1.56E-12,10.00036913,1.8146875,-3.247081256,-0.911319224,90.00000001 +269.25,50.43283629,-2.562100514,51.1995,2.50E-12,10.0003691,1.8653125,-3.154363851,-1.008558298,90.00000001 +269.26,50.43283629,-2.562099106,51.1806,1.17E-11,10.00036907,1.9165625,-3.060987658,-1.104917939,90.00000001 +269.27,50.43283629,-2.562097699,51.1612,2.34E-11,10.00014701,1.968125,-2.966972274,-1.200314094,90.00000001 +269.28,50.43283629,-2.562096291,51.1412,2.34E-11,9.999480878,2.018125,-2.872337236,-1.294663513,90.00000001 +269.29,50.43283629,-2.562094884,51.1208,9.38E-12,9.999036779,2.06625,-2.777102369,-1.387884032,90.00000001 +269.3,50.43283629,-2.562093477,51.0999,-7.03E-12,9.999480812,2.1134375,-2.681287496,-1.479894236,90.00000001 +269.31,50.43283629,-2.562092069,51.0785,-1.41E-11,10.00014688,2.16,-2.584912729,-1.570613967,90.00000001 +269.32,50.43283629,-2.562090662,51.0567,-7.19E-12,10.00036888,2.2065625,-2.487998064,-1.659964099,90.00000001 +269.33,50.43283629,-2.562089254,51.0344,3.91E-12,10.00036884,2.253125,-2.390563898,-1.747866711,90.00000001 +269.34,50.43283629,-2.562087847,51.0116,5.47E-12,10.00036881,2.2978125,-2.292630457,-1.834245198,90.00000001 +269.35,50.43283629,-2.562086439,50.9884,9.37E-13,10.00036877,2.3396875,-2.194218194,-1.919024159,90.00000001 +269.36,50.43283629,-2.562085032,50.9648,-2.78E-17,10.00036873,2.38,-2.095347738,-2.002129682,90.00000001 +269.37,50.43283629,-2.562083624,50.9408,1.56E-12,10.0003687,2.42,-1.996039656,-2.083489345,90.00000001 +269.38,50.43283629,-2.562082217,50.9164,2.34E-12,10.00036866,2.46,-1.896314748,-2.163032159,90.00000001 +269.39,50.43283629,-2.562080809,50.8916,2.50E-12,10.00036862,2.5,-1.796193868,-2.240688796,90.00000001 +269.4,50.43283629,-2.562079402,50.8664,7.19E-12,10.00014655,2.539375,-1.695697816,-2.316391532,90.00000001 +269.41,50.43283629,-2.562077994,50.8408,2.36E-11,9.999480408,2.5765625,-1.594847675,-2.390074306,90.00000001 +269.42,50.43283629,-2.562076587,50.8148,4.45E-11,9.999036301,2.61125,-1.493664417,-2.461672945,90.00000001 +269.43,50.43283629,-2.56207518,50.7886,5.31E-11,9.999480326,2.645,-1.392169241,-2.531124941,90.00000001 +269.44,50.43283629,-2.562073772,50.7619,4.45E-11,10.00014638,2.6784375,-1.290383346,-2.598369732,90.00000001 +269.45,50.43283629,-2.562072365,50.735,2.44E-11,10.00036837,2.7109375,-1.188327989,-2.663348761,90.00000001 +269.46,50.43283629,-2.562070957,50.7077,-1.41E-12,10.00036833,2.741875,-1.086024484,-2.726005248,90.00000001 +269.47,50.43283629,-2.56206955,50.6801,-2.34E-11,10.00036829,2.77125,-0.983494145,-2.786284648,90.00000001 +269.48,50.43283629,-2.562068142,50.6523,-2.91E-11,10.00036825,2.7996875,-0.8807584,-2.844134363,90.00000001 +269.49,50.43283629,-2.562066735,50.6241,-1.25E-11,10.0003682,2.826875,-0.777838736,-2.899503973,90.00000001 +269.5,50.43283629,-2.562065327,50.5957,1.72E-11,10.00036816,2.8528125,-0.674756582,-2.952345177,90.00000001 +269.51,50.43283629,-2.56206392,50.5671,4.00E-11,10.00036811,2.8784375,-0.571533594,-3.002611853,90.00000001 +269.52,50.43283629,-2.562062512,50.5381,4.45E-11,10.00036807,2.9028125,-0.468191202,-3.050260227,90.00000001 +269.53,50.43283629,-2.562061105,50.509,3.97E-11,10.00014599,2.9246875,-0.364751063,-3.095248701,90.00000001 +269.54,50.43283629,-2.562059697,50.4796,3.67E-11,9.999479843,2.945,-0.261234721,-3.137538086,90.00000001 +269.55,50.43283629,-2.56205829,50.4501,3.59E-11,9.999035731,2.965,-0.157663833,-3.177091539,90.00000001 +269.56,50.43283629,-2.562056883,50.4203,3.83E-11,9.99947975,2.9846875,-0.05406,-3.213874456,90.00000001 +269.57,50.43283629,-2.562055475,50.3904,4.37E-11,10.0001458,3.0028125,0.049555062,-3.247854864,90.00000001 +269.58,50.43283629,-2.562054068,50.3602,3.97E-11,10.00036779,3.0184375,0.153159869,-3.279003084,90.00000001 +269.59,50.43283629,-2.56205266,50.33,1.64E-11,10.00036774,3.0328125,0.25673259,-3.307291958,90.00000001 +269.6,50.43283629,-2.562051253,50.2996,-1.41E-11,10.00036769,3.046875,0.36025174,-3.33269685,90.00000001 +269.61,50.43283629,-2.562049845,50.269,-3.28E-11,10.00036765,3.059375,0.46369566,-3.355195585,90.00000001 +269.62,50.43283629,-2.562048438,50.2384,-3.52E-11,10.0003676,3.0696875,0.567042751,-3.37476851,90.00000001 +269.63,50.43283629,-2.56204703,50.2076,-2.58E-11,10.00036755,3.0784375,0.670271411,-3.391398553,90.00000001 +269.64,50.43283629,-2.562045623,50.1768,-1.17E-11,10.0003675,3.0865625,0.773360097,-3.405071332,90.00000001 +269.65,50.43283629,-2.562044215,50.1459,-7.03E-12,10.00036745,3.0946875,0.876287267,-3.415774756,90.00000001 +269.66,50.43283629,-2.562042808,50.1149,-1.89E-11,10.00014537,3.10125,0.979031434,-3.423499602,90.00000001 +269.67,50.43283629,-2.5620414,50.0838,-3.12E-11,9.999479224,3.1046875,1.081571169,-3.428239109,90.00000001 +269.68,50.43283629,-2.562039993,50.0528,-2.73E-11,9.99903511,3.1065625,1.183885045,-3.429989151,90.00000001 +269.69,50.43283629,-2.562038586,50.0217,-1.33E-11,9.999479126,3.1084375,1.285951632,-3.428748182,90.00000001 +269.7,50.43283629,-2.562037178,49.9906,-7.81E-13,10.00014518,3.109375,1.387749674,-3.42451729,90.00000001 +269.71,50.43283629,-2.562035771,49.9595,1.16E-11,10.00036716,3.1084375,1.489257913,-3.417300199,90.00000001 +269.72,50.43283629,-2.562034363,49.9284,2.81E-11,10.00036711,3.10625,1.590455152,-3.407103154,90.00000001 +269.73,50.43283629,-2.562032956,49.8974,4.22E-11,10.00036706,3.103125,1.691320246,-3.393935037,90.00000001 +269.74,50.43283629,-2.562031548,49.8663,4.22E-11,10.00036702,3.098125,1.791832112,-3.377807421,90.00000001 +269.75,50.43283629,-2.562030141,49.8354,2.81E-11,10.00014493,3.09125,1.891969779,-3.358734229,90.00000001 +269.76,50.43283629,-2.562028733,49.8045,1.41E-11,9.999478788,3.083125,1.991712335,-3.336732192,90.00000001 +269.77,50.43283629,-2.562027326,49.7737,1.41E-11,9.999034673,3.073125,2.091038923,-3.311820502,90.00000001 +269.78,50.43283629,-2.562025919,49.743,2.58E-11,9.999478691,3.0615625,2.18992886,-3.284020877,90.00000001 +269.79,50.43283629,-2.562024511,49.7125,3.28E-11,10.00014474,3.05,2.288361463,-3.253357493,90.00000001 +269.8,50.43283629,-2.562023104,49.682,2.81E-11,10.00036673,3.038125,2.386316161,-3.219857109,90.00000001 +269.81,50.43283629,-2.562021696,49.6517,2.11E-11,10.00036668,3.0246875,2.4837725,-3.183549003,90.00000001 +269.82,50.43283629,-2.562020289,49.6215,2.11E-11,10.0001446,3.0096875,2.580710084,-3.144464802,90.00000001 +269.83,50.43283629,-2.562018881,49.5915,2.80E-11,9.999478454,2.993125,2.6771088,-3.102638539,90.00000001 +269.84,50.43283629,-2.562017474,49.5616,3.44E-11,9.999034342,2.9746875,2.772948425,-3.058106769,90.00000001 +269.85,50.43283629,-2.562016067,49.532,3.36E-11,9.999478361,2.9546875,2.868208903,-3.010908282,90.00000001 +269.86,50.43283629,-2.562014659,49.5025,2.42E-11,10.00014441,2.9334375,2.962870412,-2.961084216,90.00000001 +269.87,50.43283629,-2.562013252,49.4733,8.59E-12,10.0003664,2.91125,3.056913184,-2.908678058,90.00000001 +269.88,50.43283629,-2.562011844,49.4443,-4.84E-12,10.00036636,2.888125,3.150317565,-2.853735474,90.00000001 +269.89,50.43283629,-2.562010437,49.4155,-4.84E-12,10.00014428,2.863125,3.24306402,-2.796304419,90.00000001 +269.9,50.43283629,-2.562009029,49.387,6.25E-12,9.999478134,2.8365625,3.335133238,-2.736434913,90.00000001 +269.91,50.43283629,-2.562007622,49.3588,1.25E-11,9.999034024,2.81,3.426505912,-2.67417921,90.00000001 +269.92,50.43283629,-2.562006215,49.3308,7.97E-12,9.999478046,2.783125,3.517163018,-2.609591568,90.00000001 +269.93,50.43283629,-2.562004807,49.3031,1.94E-16,10.0001441,2.754375,3.60708565,-2.542728368,90.00000001 +269.94,50.43283629,-2.5620034,49.2757,-7.97E-12,10.00036609,2.723125,3.696254957,-2.47364782,90.00000001 +269.95,50.43283629,-2.562001992,49.2486,-1.27E-11,10.00036605,2.69,3.784652318,-2.402410259,90.00000001 +269.96,50.43283629,-2.562000585,49.2219,-7.03E-12,10.00014397,2.6565625,3.872259341,-2.329077734,90.00000001 +269.97,50.43283629,-2.561999177,49.1955,5.47E-12,9.999477834,2.6234375,3.959057692,-2.253714189,90.00000001 +269.98,50.43283629,-2.56199777,49.1694,1.64E-11,9.999033727,2.589375,4.045029207,-2.176385399,90.00000001 +269.99,50.43283629,-2.561996363,49.1437,2.56E-11,9.999477754,2.553125,4.13015601,-2.0971588,90.00000001 +270,50.43283629,-2.561994955,49.1183,3.05E-11,10.00014381,2.515,4.214420283,-2.016103435,90.00000001 +270.01,50.43283629,-2.561993548,49.0934,2.42E-11,10.00036581,2.4765625,4.297804378,-1.933289949,90.00000001 +270.02,50.43283629,-2.56199214,49.0688,1.41E-11,10.00036577,2.438125,4.380290992,-1.848790649,90.00000001 +270.03,50.43283629,-2.561990733,49.0446,1.31E-11,10.00036573,2.3978125,4.461862821,-1.76267916,90.00000001 +270.04,50.43283629,-2.561989325,49.0208,1.56E-11,10.00036569,2.355,4.542502792,-1.675030598,90.00000001 +270.05,50.43283629,-2.561987918,48.9975,7.97E-12,10.00014362,2.3115625,4.622194174,-1.585921394,90.00000001 +270.06,50.43283629,-2.56198651,48.9746,-6.09E-12,9.999477488,2.2684375,4.700920294,-1.495429242,90.00000001 +270.07,50.43283629,-2.561985103,48.9521,-1.48E-11,9.999033387,2.2246875,4.778664651,-1.403633038,90.00000001 +270.08,50.43283629,-2.561983696,48.9301,-1.48E-11,9.999477419,2.1796875,4.855411029,-1.310612824,90.00000001 +270.09,50.43283629,-2.561982288,48.9085,-6.25E-12,10.00014348,2.1334375,4.931143445,-1.216449789,90.00000001 +270.1,50.43283629,-2.561980881,48.8874,9.53E-12,10.00036548,2.08625,5.005846026,-1.121225922,90.00000001 +270.11,50.43283629,-2.561979473,48.8668,2.34E-11,10.00036545,2.038125,5.079503246,-1.025024418,90.00000001 +270.12,50.43283629,-2.561978066,48.8466,2.36E-11,10.00036542,1.988125,5.152099634,-0.927928984,90.00000001 +270.13,50.43283629,-2.561976658,48.827,1.25E-11,10.00036539,1.9365625,5.223620122,-0.83002442,90.00000001 +270.14,50.43283629,-2.561975251,48.8079,3.91E-12,10.00036536,1.8853125,5.294049698,-0.731396095,90.00000001 +270.15,50.43283629,-2.561973843,48.7893,1.56E-12,10.00036533,1.835,5.363373638,-0.632129954,90.00000001 +270.16,50.43283629,-2.561972436,48.7712,5.62E-12,10.00014327,1.784375,5.43157756,-0.53231257,90.00000001 +270.17,50.43283629,-2.561971028,48.7536,2.20E-11,9.999477143,1.7315625,5.49864714,-0.432031033,90.00000001 +270.18,50.43283629,-2.561969621,48.7365,4.16E-11,9.99903305,1.6765625,5.564568398,-0.331372776,90.00000001 +270.19,50.43283629,-2.561968214,48.7201,4.22E-11,9.999477091,1.6215625,5.629327583,-0.23042552,90.00000001 +270.2,50.43283629,-2.561966806,48.7041,2.36E-11,10.00014317,1.5665625,5.692911173,-0.129277327,90.00000001 +270.21,50.43283629,-2.561965399,48.6887,9.38E-12,10.00036517,1.5096875,5.755305819,-0.028016433,90.00000001 +270.22,50.43283629,-2.561963991,48.6739,1.09E-11,10.00036515,1.451875,5.816498571,0.073268926,90.00000001 +270.23,50.43283629,-2.561962584,48.6597,1.41E-11,10.00036513,1.395,5.876476652,0.1744904,90.00000001 +270.24,50.43283629,-2.561961176,48.646,7.97E-12,10.00036511,1.338125,5.935227458,0.275559697,90.00000001 +270.25,50.43283629,-2.561959769,48.6329,7.81E-13,10.00036509,1.2796875,5.992738784,0.376388695,90.00000001 +270.26,50.43283629,-2.561958361,48.6204,-7.81E-13,10.00036507,1.22,6.048998599,0.476889446,90.00000001 +270.27,50.43283629,-2.561956954,48.6085,-1.56E-13,10.00036505,1.16,6.103995156,0.576974401,90.00000001 +270.28,50.43283629,-2.561955546,48.5972,2.50E-16,10.00036503,1.1,6.157716997,0.676556185,90.00000001 +270.29,50.43283629,-2.561954139,48.5865,-1.88E-22,10.00014298,1.04,6.210152834,0.775548051,90.00000001 +270.3,50.43283629,-2.561952731,48.5764,-2.50E-16,9.999476866,0.98,6.261291781,0.873863598,90.00000001 +270.31,50.43283629,-2.561951324,48.5669,-2.34E-12,9.999032785,0.9196875,6.311123181,0.971417111,90.00000001 +270.32,50.43283629,-2.561949917,48.558,-9.22E-12,9.999476837,0.858125,6.359636548,1.068123563,90.00000001 +270.33,50.43283629,-2.561948509,48.5497,-1.33E-11,10.00014292,0.795,6.406821743,1.163898558,90.00000001 +270.34,50.43283629,-2.561947102,48.5421,-5.31E-12,10.00036494,0.7315625,6.452669023,1.258658616,90.00000001 +270.35,50.43283629,-2.561945694,48.5351,9.37E-12,10.00036493,0.6684375,6.497168707,1.352321172,90.00000001 +270.36,50.43283629,-2.561944287,48.5287,1.66E-11,10.00036492,0.605,6.54031157,1.44480441,90.00000001 +270.37,50.43283629,-2.561942879,48.523,9.53E-12,10.00036491,0.5415625,6.582088558,1.536027771,90.00000001 +270.38,50.43283629,-2.561941472,48.5179,-4.53E-12,10.00036491,0.4784375,6.622490906,1.625911728,90.00000001 +270.39,50.43283629,-2.561940064,48.5134,-1.17E-11,10.0003649,0.415,6.661510306,1.714377844,90.00000001 +270.4,50.43283629,-2.561938657,48.5096,-5.47E-12,10.00036489,0.3515625,6.699138507,1.801348998,90.00000001 +270.41,50.43283629,-2.561937249,48.5064,4.69E-12,10.00036489,0.288125,6.735367717,1.886749332,90.00000001 +270.42,50.43283629,-2.561935842,48.5038,3.28E-12,10.00014285,0.223125,6.770190259,1.970504417,90.00000001 +270.43,50.43283629,-2.561934434,48.5019,-6.25E-12,9.99947675,0.156875,6.803598969,2.052541144,90.00000001 +270.44,50.43283629,-2.561933027,48.5007,-5.47E-12,9.999032681,0.091875,6.835586859,2.132788066,90.00000001 +270.45,50.43283629,-2.56193162,48.5001,6.87E-12,9.999476746,0.0284375,6.866147225,2.211175167,90.00000001 +270.46,50.43283629,-2.561930212,48.5001,1.66E-11,10.00014285,-0.0353125,6.895273649,2.287634093,90.00000001 +270.47,50.43283629,-2.561928805,48.5008,1.95E-11,10.00036488,-0.1,6.922960058,2.362098152,90.00000001 +270.48,50.43283629,-2.561927397,48.5021,1.80E-11,10.00036488,-0.1646875,6.94920078,2.434502484,90.00000001 +270.49,50.43283629,-2.56192599,48.5041,8.44E-12,10.00036488,-0.2284375,6.9739902,2.504783837,90.00000001 +270.5,50.43283629,-2.561924582,48.5067,-7.03E-12,10.00036489,-0.2915625,6.997323162,2.572880959,90.00000001 +270.51,50.43283629,-2.561923175,48.5099,-1.80E-11,10.00036489,-0.3553125,7.019194852,2.638734551,90.00000001 +270.52,50.43283629,-2.561921767,48.5138,-2.11E-11,10.0003649,-0.42,7.039600686,2.702287087,90.00000001 +270.53,50.43283629,-2.56192036,48.5183,-1.89E-11,10.00014287,-0.4846875,7.058536426,2.763483162,90.00000001 +270.54,50.43283629,-2.561918952,48.5235,-9.53E-12,9.999476783,-0.5484375,7.075998002,2.822269491,90.00000001 +270.55,50.43283629,-2.561917545,48.5293,4.53E-12,9.999032726,-0.6115625,7.091981863,2.878594738,90.00000001 +270.56,50.43283629,-2.561916138,48.5357,1.17E-11,9.999476802,-0.675,7.106484685,2.932409856,90.00000001 +270.57,50.43283629,-2.56191473,48.5428,7.66E-12,10.00014291,-0.738125,7.119503432,2.983667806,90.00000001 +270.58,50.43283629,-2.561913323,48.5505,1.56E-12,10.00036496,-0.7996875,7.131035297,3.032323955,90.00000001 +270.59,50.43283629,-2.561911915,48.5588,-2.50E-12,10.00036497,-0.8603125,7.141077986,3.078335904,90.00000001 +270.6,50.43283629,-2.561910508,48.5677,-9.37E-12,10.00014295,-0.921875,7.149629324,3.121663488,90.00000001 +270.61,50.43283629,-2.5619091,48.5772,-1.17E-11,9.999476867,-0.9846875,7.156687534,3.162268949,90.00000001 +270.62,50.43283629,-2.561907693,48.5874,2.34E-12,9.999032817,-1.0465625,7.162251183,3.200116822,90.00000001 +270.63,50.43283629,-2.561906286,48.5982,2.11E-11,9.9994769,-1.1065625,7.166319126,3.235174162,90.00000001 +270.64,50.43283629,-2.561904878,48.6095,2.12E-11,10.00014302,-1.1665625,7.168890446,3.267410372,90.00000001 +270.65,50.43283629,-2.561903471,48.6215,3.12E-12,10.00036507,-1.2265625,7.169964627,3.296797377,90.00000001 +270.66,50.43283629,-2.561902063,48.6341,-1.02E-11,10.00036509,-1.2846875,7.169541441,3.323309567,90.00000001 +270.67,50.43283629,-2.561900656,48.6472,-7.97E-12,10.00014308,-1.341875,7.167621001,3.346923678,90.00000001 +270.68,50.43283629,-2.561899248,48.6609,-4.69E-12,9.999476998,-1.4,7.164203709,3.367619315,90.00000001 +270.69,50.43283629,-2.561897841,48.6752,-1.09E-11,9.999032955,-1.458125,7.159290252,3.385378314,90.00000001 +270.7,50.43283629,-2.561896434,48.6901,-1.63E-11,9.999477044,-1.515,7.152881662,3.400185147,90.00000001 +270.71,50.43283629,-2.561895026,48.7055,-8.59E-12,10.00014317,-1.5715625,7.144979313,3.412027039,90.00000001 +270.72,50.43283629,-2.561893619,48.7215,4.69E-12,10.00036522,-1.628125,7.135584811,3.420893561,90.00000001 +270.73,50.43283629,-2.561892211,48.7381,8.44E-12,10.00036525,-1.6828125,7.124700102,3.426777035,90.00000001 +270.74,50.43283629,-2.561890804,48.7552,6.25E-12,10.00014324,-1.735,7.112327537,3.429672306,90.00000001 +270.75,50.43283629,-2.561889396,48.7728,1.02E-11,9.999477173,-1.786875,7.098469636,3.429576851,90.00000001 +270.76,50.43283629,-2.561887989,48.7909,1.17E-11,9.999033136,-1.8396875,7.083129321,3.426490728,90.00000001 +270.77,50.43283629,-2.561886582,48.8096,-3.13E-12,9.999477231,-1.8915625,7.066309744,3.420416688,90.00000001 +270.78,50.43283629,-2.561885174,48.8288,-2.27E-11,10.00014336,-1.9415625,7.048014514,3.411360002,90.00000001 +270.79,50.43283629,-2.561883767,48.8484,-2.28E-11,10.00036542,-1.9915625,7.028247356,3.399328518,90.00000001 +270.8,50.43283629,-2.561882359,48.8686,-3.91E-12,10.00036545,-2.0415625,7.007012451,3.38433278,90.00000001 +270.81,50.43283629,-2.561880952,48.8893,1.00E-11,10.00014345,-2.0896875,6.984314212,3.366385851,90.00000001 +270.82,50.43283629,-2.561879544,48.9104,5.47E-12,9.999477389,-2.1365625,6.960157395,3.345503431,90.00000001 +270.83,50.43283629,-2.561878137,48.932,-7.81E-12,9.999033356,-2.1834375,6.934547041,3.321703623,90.00000001 +270.84,50.43283629,-2.56187673,48.9541,-1.64E-11,9.999477457,-2.2296875,6.907488536,3.295007285,90.00000001 +270.85,50.43283629,-2.561875322,48.9766,-1.56E-11,10.00014359,-2.2746875,6.878987438,3.265437621,90.00000001 +270.86,50.43283629,-2.561873915,48.9996,-7.81E-12,10.00036566,-2.318125,6.849049763,3.233020471,90.00000001 +270.87,50.43283629,-2.561872507,49.023,-9.38E-13,10.0003657,-2.3596875,6.817681756,3.197784025,90.00000001 +270.88,50.43283629,-2.5618711,49.0468,-2.78E-17,10.00036573,-2.4,6.784889949,3.159759108,90.00000001 +270.89,50.43283629,-2.561869692,49.071,-1.56E-12,10.00036577,-2.44,6.750681218,3.118978837,90.00000001 +270.9,50.43283629,-2.561868285,49.0956,-4.69E-12,10.00036581,-2.4796875,6.715062666,3.075478735,90.00000001 +270.91,50.43283629,-2.561866877,49.1206,-1.42E-11,10.00036585,-2.5184375,6.6780418,3.02929679,90.00000001 +270.92,50.43283629,-2.56186547,49.146,-3.06E-11,10.00036589,-2.55625,6.639626298,2.98047328,90.00000001 +270.93,50.43283629,-2.561864062,49.1717,-4.47E-11,10.00036593,-2.593125,6.59982418,2.929050719,90.00000001 +270.94,50.43283629,-2.561862655,49.1979,-4.45E-11,10.00014394,-2.628125,6.558643813,2.875074026,90.00000001 +270.95,50.43283629,-2.561861247,49.2243,-2.97E-11,9.99947788,-2.66125,6.516093732,2.818590185,90.00000001 +270.96,50.43283629,-2.56185984,49.2511,-1.17E-11,9.999033855,-2.6934375,6.47218282,2.75964847,90.00000001 +270.97,50.43283629,-2.561858433,49.2782,-9.37E-13,9.999477963,-2.7246875,6.4269203,2.698300332,90.00000001 +270.98,50.43283629,-2.561857025,49.3056,1.56E-12,10.00014411,-2.755,6.380315627,2.634599285,90.00000001 +270.99,50.43283629,-2.561855618,49.3333,3.28E-12,10.00036618,-2.7846875,6.332378482,2.568600735,90.00000001 +271,50.43283629,-2.56185421,49.3613,1.03E-11,10.00036623,-2.813125,6.283118894,2.500362379,90.00000001 +271.01,50.43283629,-2.561852803,49.3896,1.56E-11,10.00036627,-2.84,6.232547176,2.429943688,90.00000001 +271.02,50.43283629,-2.561851395,49.4181,6.25E-12,10.00036631,-2.86625,6.180673869,2.357406028,90.00000001 +271.03,50.43283629,-2.561849988,49.4469,-1.56E-11,10.00036636,-2.8915625,6.127509802,2.282812653,90.00000001 +271.04,50.43283629,-2.56184858,49.476,-3.27E-11,10.00036641,-2.914375,6.073066035,2.20622865,90.00000001 +271.05,50.43283629,-2.561847173,49.5052,-3.75E-11,10.00036645,-2.935,6.017354025,2.12772077,90.00000001 +271.06,50.43283629,-2.561845765,49.5347,-3.75E-11,10.0003665,-2.955,5.960385405,2.04735748,90.00000001 +271.07,50.43283629,-2.561844358,49.5643,-3.50E-11,10.00014451,-2.9746875,5.902171976,1.965208912,90.00000001 +271.08,50.43283629,-2.56184295,49.5942,-2.50E-11,9.999478458,-2.9934375,5.842726,1.881346626,90.00000001 +271.09,50.43283629,-2.561841543,49.6242,-5.47E-12,9.999034439,-3.0109375,5.782059797,1.795843791,90.00000001 +271.1,50.43283629,-2.561840136,49.6544,1.80E-11,9.999478552,-3.0265625,5.720186142,1.70877489,90.00000001 +271.11,50.43283629,-2.561838728,49.6848,3.12E-11,10.0001447,-3.0396875,5.65711787,1.620215955,90.00000001 +271.12,50.43283629,-2.561837321,49.7152,2.59E-11,10.00036678,-3.0515625,5.592868159,1.53024422,90.00000001 +271.13,50.43283629,-2.561835913,49.7458,1.17E-11,10.00036683,-3.0634375,5.527450473,1.43893801,90.00000001 +271.14,50.43283629,-2.561834506,49.7765,2.50E-12,10.00036687,-3.0746875,5.46087845,1.346377079,90.00000001 +271.15,50.43283629,-2.561833098,49.8073,3.12E-12,10.00036692,-3.0846875,5.393166011,1.252642043,90.00000001 +271.16,50.43283629,-2.561831691,49.8382,8.59E-12,10.00036697,-3.0928125,5.324327252,1.15781472,90.00000001 +271.17,50.43283629,-2.561830283,49.8692,6.25E-12,10.00036702,-3.098125,5.254376554,1.061977732,90.00000001 +271.18,50.43283629,-2.561828876,49.9002,-6.25E-12,10.00014504,-3.1015625,5.183328584,0.965214728,90.00000001 +271.19,50.43283629,-2.561827468,49.9312,-1.39E-11,9.999478985,-3.105,5.111198125,0.867609993,90.00000001 +271.2,50.43283629,-2.561826061,49.9623,-9.37E-12,9.999034968,-3.108125,5.038000303,0.769248724,90.00000001 +271.21,50.43283629,-2.561824654,49.9934,-2.34E-12,9.999479083,-3.1096875,4.963750301,0.670216636,90.00000001 +271.22,50.43283629,-2.561823246,50.0245,-2.34E-12,10.00014523,-3.1096875,4.888463704,0.570600131,90.00000001 +271.23,50.43283629,-2.561821839,50.0556,-9.38E-12,10.00036731,-3.108125,4.812156211,0.470486012,90.00000001 +271.24,50.43283629,-2.561820431,50.0867,-1.64E-11,10.00036736,-3.1046875,4.73484375,0.369961656,90.00000001 +271.25,50.43283629,-2.561819024,50.1177,-1.64E-11,10.00036741,-3.0996875,4.656542478,0.269114724,90.00000001 +271.26,50.43283629,-2.561817616,50.1487,-7.03E-12,10.00036746,-3.0934375,4.577268782,0.168033051,90.00000001 +271.27,50.43283629,-2.561816209,50.1796,9.37E-12,10.00036751,-3.08625,4.497039164,0.066804874,90.00000001 +271.28,50.43283629,-2.561814801,50.2104,2.34E-11,10.00036755,-3.078125,4.41587041,-0.034481517,90.00000001 +271.29,50.43283629,-2.561813394,50.2412,2.34E-11,10.0003676,-3.068125,4.333779424,-0.135737884,90.00000001 +271.3,50.43283629,-2.561811986,50.2718,1.17E-11,10.00036765,-3.0565625,4.250783393,-0.236875879,90.00000001 +271.31,50.43283629,-2.561810579,50.3023,4.69E-12,10.00014566,-3.045,4.166899679,-0.337807322,90.00000001 +271.32,50.43283629,-2.561809171,50.3327,7.03E-12,9.999479612,-3.0328125,4.082145699,-0.438444207,90.00000001 +271.33,50.43283629,-2.561807764,50.363,4.69E-12,9.999035594,-3.018125,3.996539273,-0.538698701,90.00000001 +271.34,50.43283629,-2.561806357,50.3931,-9.38E-12,9.999479708,-3.00125,3.910098162,-0.638483483,90.00000001 +271.35,50.43283629,-2.561804949,50.423,-2.58E-11,10.00014585,-2.9834375,3.822840528,-0.737711465,90.00000001 +271.36,50.43283629,-2.561803542,50.4528,-3.53E-11,10.00036793,-2.9646875,3.734784536,-0.836296188,90.00000001 +271.37,50.43283629,-2.561802134,50.4823,-3.59E-11,10.00036798,-2.9446875,3.645948575,-0.93415165,90.00000001 +271.38,50.43283629,-2.561800727,50.5117,-2.97E-11,10.00014599,-2.923125,3.556351154,-1.031192537,90.00000001 +271.39,50.43283629,-2.561799319,50.5408,-2.27E-11,9.999479939,-2.8996875,3.466011123,-1.127334168,90.00000001 +271.4,50.43283629,-2.561797912,50.5697,-1.95E-11,9.999035918,-2.875,3.374947216,-1.222492717,90.00000001 +271.41,50.43283629,-2.561796505,50.5983,-1.87E-11,9.999480028,-2.85,3.283178457,-1.316585279,90.00000001 +271.42,50.43283629,-2.561795097,50.6267,-2.03E-11,10.00014617,-2.8246875,3.190724096,-1.409529805,90.00000001 +271.43,50.43283629,-2.56179369,50.6548,-2.66E-11,10.00036825,-2.798125,3.097603386,-1.501245107,90.00000001 +271.44,50.43283629,-2.561792282,50.6827,-3.37E-11,10.00036829,-2.7696875,3.003835806,-1.591651373,90.00000001 +271.45,50.43283629,-2.561790875,50.7102,-3.52E-11,10.0001463,-2.7396875,2.909440837,-1.680669648,90.00000001 +271.46,50.43283629,-2.561789467,50.7375,-2.97E-11,9.999480246,-2.708125,2.814438361,-1.768222355,90.00000001 +271.47,50.43283629,-2.56178806,50.7644,-2.34E-11,9.999036222,-2.6746875,2.718848088,-1.854233175,90.00000001 +271.48,50.43283629,-2.561786653,50.791,-1.87E-11,9.99948033,-2.6403125,2.622690014,-1.938627051,90.00000001 +271.49,50.43283629,-2.561785245,50.8172,-6.25E-12,10.00014647,-2.60625,2.525984192,-2.021330472,90.00000001 +271.5,50.43283629,-2.561783838,50.8431,1.63E-11,10.00036854,-2.5715625,2.428750905,-2.102271188,90.00000001 +271.51,50.43283629,-2.56178243,50.8687,3.11E-11,10.00036858,-2.5346875,2.331010378,-2.181378726,90.00000001 +271.52,50.43283629,-2.561781023,50.8938,2.56E-11,10.00014659,-2.4965625,2.232783067,-2.258584044,90.00000001 +271.53,50.43283629,-2.561779615,50.9186,1.03E-11,9.99948053,-2.4584375,2.134089425,-2.333819877,90.00000001 +271.54,50.43283629,-2.561778208,50.943,-1.41E-12,9.999036501,-2.419375,2.034950137,-2.407020564,90.00000001 +271.55,50.43283629,-2.561776801,50.967,-9.37E-12,9.999480605,-2.378125,1.935385886,-2.478122334,90.00000001 +271.56,50.43283629,-2.561775393,50.9906,-1.27E-11,10.00014674,-2.335,1.835417413,-2.54706308,90.00000001 +271.57,50.43283629,-2.561773986,51.0137,-5.47E-12,10.00036881,-2.2915625,1.735065688,-2.613782812,90.00000001 +271.58,50.43283629,-2.561772578,51.0364,5.47E-12,10.00036885,-2.248125,1.634351568,-2.678223261,90.00000001 +271.59,50.43283629,-2.561771171,51.0587,4.84E-12,10.00036888,-2.203125,1.533296194,-2.740328219,90.00000001 +271.6,50.43283629,-2.561769763,51.0805,-7.03E-12,10.00036892,-2.1565625,1.431920537,-2.800043656,90.00000001 +271.61,50.43283629,-2.561768356,51.1018,-1.17E-11,10.00014692,-2.1096875,1.330245911,-2.85731732,90.00000001 +271.62,50.43283629,-2.561766948,51.1227,2.34E-12,9.999480848,-2.0615625,1.228293457,-2.912099419,90.00000001 +271.63,50.43283629,-2.561765541,51.1431,2.11E-11,9.999036814,-2.0115625,1.12608449,-2.964342111,90.00000001 +271.64,50.43283629,-2.561764134,51.1629,2.34E-11,9.999480912,-1.961875,1.023640323,-3.013999848,90.00000001 +271.65,50.43283629,-2.561762726,51.1823,1.41E-11,10.00014704,-1.913125,0.920982387,-3.061029312,90.00000001 +271.66,50.43283629,-2.561761319,51.2012,1.16E-11,10.0003691,-1.8628125,0.818132165,-3.105389538,90.00000001 +271.67,50.43283629,-2.561759911,51.2196,1.33E-11,10.00036913,-1.81,0.715111031,-3.147041851,90.00000001 +271.68,50.43283629,-2.561758504,51.2374,5.47E-12,10.00036916,-1.7565625,0.611940583,-3.185949868,90.00000001 +271.69,50.43283629,-2.561757096,51.2547,-8.44E-12,10.00036919,-1.7034375,0.508642366,-3.22207967,90.00000001 +271.7,50.43283629,-2.561755689,51.2715,-1.64E-11,10.00014718,-1.6496875,0.405237865,-3.255399801,90.00000001 +271.71,50.43283629,-2.561754281,51.2877,-1.72E-11,9.999481107,-1.595,0.301748796,-3.285881156,90.00000001 +271.72,50.43283629,-2.561752874,51.3034,-1.89E-11,9.999037065,-1.5396875,0.198196701,-3.313497149,90.00000001 +271.73,50.43283629,-2.561751467,51.3185,-2.66E-11,9.999481155,-1.483125,0.094603181,-3.338223773,90.00000001 +271.74,50.43283629,-2.561750059,51.3331,-3.28E-11,10.00014728,-1.425,-0.009010105,-3.36003937,90.00000001 +271.75,50.43283629,-2.561748652,51.347,-2.95E-11,10.00036933,-1.366875,-0.112621444,-3.378924975,90.00000001 +271.76,50.43283629,-2.561747244,51.3604,-2.50E-11,10.00036935,-1.31,-0.216209348,-3.394864146,90.00000001 +271.77,50.43283629,-2.561745837,51.3732,-2.66E-11,10.00036937,-1.2528125,-0.319752046,-3.4078429,90.00000001 +271.78,50.43283629,-2.561744429,51.3855,-2.36E-11,10.00036939,-1.193125,-0.423227938,-3.417850009,90.00000001 +271.79,50.43283629,-2.561743022,51.3971,-1.17E-11,10.00036941,-1.1315625,-0.526615536,-3.424876649,90.00000001 +271.8,50.43283629,-2.561741614,51.4081,-2.34E-12,10.00036943,-1.0703125,-0.62989307,-3.428916746,90.00000001 +271.81,50.43283629,-2.561740207,51.4185,2.78E-16,10.00036944,-1.01,-0.733039109,-3.429966806,90.00000001 +271.82,50.43283629,-2.561738799,51.4283,-2.34E-12,10.00036946,-0.9496875,-0.836032054,-3.428025912,90.00000001 +271.83,50.43283629,-2.561737392,51.4375,-1.17E-11,10.00014744,-0.8884375,-0.938850362,-3.423095667,90.00000001 +271.84,50.43283629,-2.561735984,51.4461,-2.59E-11,9.999481354,-0.8265625,-1.041472661,-3.415180484,90.00000001 +271.85,50.43283629,-2.561734577,51.454,-3.12E-11,9.999037301,-0.7646875,-1.143877465,-3.404287181,90.00000001 +271.86,50.43283629,-2.56173317,51.4614,-1.58E-11,9.999481379,-0.701875,-1.246043345,-3.39042527,90.00000001 +271.87,50.43283629,-2.561731762,51.4681,1.17E-11,10.00014749,-0.638125,-1.347948989,-3.373606896,90.00000001 +271.88,50.43283629,-2.561730355,51.4741,2.56E-11,10.00036953,-0.575,-1.449573195,-3.35384667,90.00000001 +271.89,50.43283629,-2.561728947,51.4796,1.39E-11,10.00036954,-0.5115625,-1.55089465,-3.331161839,90.00000001 +271.9,50.43283629,-2.56172754,51.4844,-4.84E-12,10.00036955,-0.4465625,-1.651892213,-3.305572226,90.00000001 +271.91,50.43283629,-2.561726132,51.4885,-9.38E-12,10.00036955,-0.3821875,-1.752544797,-3.277100062,90.00000001 +271.92,50.43283629,-2.561724725,51.492,-8.75E-12,10.00036956,-0.3196875,-1.852831376,-3.245770214,90.00000001 +271.93,50.43283629,-2.561723317,51.4949,-2.19E-11,10.00036956,-0.2565625,-1.952731037,-3.211610012,90.00000001 +271.94,50.43283629,-2.56172191,51.4972,-4.00E-11,10.00036957,-0.1915625,-2.052222866,-3.17464925,90.00000001 +271.95,50.43283629,-2.561720502,51.4987,-4.22E-11,10.00036957,-0.126875,-2.151286123,-3.134920127,90.00000001 +271.96,50.43283629,-2.561719095,51.4997,-3.05E-11,10.00014754,-0.0634375,-2.249900124,-3.092457365,90.00000001 +271.97,50.43283629,-2.561717687,51.5,-1.88E-11,9.999481438,0.000625,-2.348044242,-3.047297863,90.00000001 +271.98,50.43283629,-2.56171628,51.4997,-4.69E-12,9.999037372,0.06625,-2.445698022,-2.999481097,90.00000001 +271.99,50.43283629,-2.561714873,51.4987,1.87E-11,9.999481437,0.131875,-2.542841068,-2.949048779,90.00000001 +272,50.43283629,-2.561713465,51.497,4.20E-11,10.00014753,0.19625,-2.63945304,-2.896044797,90.00000001 +272.01,50.43283629,-2.561712058,51.4948,5.08E-11,10.00036956,0.26,-2.735513826,-2.840515447,90.00000001 +272.02,50.43283629,-2.56171065,51.4918,4.28E-11,10.00036956,0.3234375,-2.831003316,-2.782509085,90.00000001 +272.03,50.43283629,-2.561709243,51.4883,2.81E-11,10.00036955,0.3865625,-2.925901571,-2.722076362,90.00000001 +272.04,50.43283629,-2.561707835,51.4841,1.86E-11,10.00036955,0.4503125,-3.020188823,-2.659269931,90.00000001 +272.05,50.43283629,-2.561706428,51.4793,1.62E-11,10.00036954,0.515,-3.113845307,-2.594144626,90.00000001 +272.06,50.43283629,-2.56170502,51.4738,1.86E-11,10.00036953,0.5796875,-3.20685154,-2.526757112,90.00000001 +272.07,50.43283629,-2.561703613,51.4677,2.58E-11,10.00014749,0.643125,-3.299188043,-2.457166288,90.00000001 +272.08,50.43283629,-2.561702205,51.4609,3.11E-11,9.999481378,0.705,-3.390835565,-2.385432774,90.00000001 +272.09,50.43283629,-2.561700798,51.4536,2.73E-11,9.9990373,0.766875,-3.481774968,-2.31161908,90.00000001 +272.1,50.43283629,-2.561699391,51.4456,2.33E-11,9.999481354,0.83,-3.57198723,-2.235789663,90.00000001 +272.11,50.43283629,-2.561697983,51.437,2.58E-11,10.00014744,0.8928125,-3.661453501,-2.158010585,90.00000001 +272.12,50.43283629,-2.561696576,51.4277,2.11E-11,10.00036946,0.9534375,-3.75015516,-2.078349742,90.00000001 +272.13,50.43283629,-2.561695168,51.4179,2.34E-12,10.00036944,1.0134375,-3.838073643,-1.996876461,90.00000001 +272.14,50.43283629,-2.561693761,51.4075,-9.37E-12,10.00036943,1.075,-3.925190558,-1.913661962,90.00000001 +272.15,50.43283629,-2.561692353,51.3964,2.34E-12,10.00036941,1.1365625,-4.011487799,-1.828778665,90.00000001 +272.16,50.43283629,-2.561690946,51.3847,2.33E-11,10.00014736,1.19625,-4.096947262,-1.742300656,90.00000001 +272.17,50.43283629,-2.561689538,51.3725,3.20E-11,9.99948124,1.255,-4.181551127,-1.654303334,90.00000001 +272.18,50.43283629,-2.561688131,51.3596,2.42E-11,9.999037153,1.3134375,-4.265281746,-1.564863419,90.00000001 +272.19,50.43283629,-2.561686724,51.3462,7.97E-12,9.999481198,1.37125,-4.348121589,-1.474058947,90.00000001 +272.2,50.43283629,-2.561685316,51.3322,-7.03E-12,10.00014728,1.4284375,-4.430053407,-1.381969103,90.00000001 +272.21,50.43283629,-2.561683909,51.3176,-1.25E-11,10.00036929,1.485,-4.511060071,-1.288674098,90.00000001 +272.22,50.43283629,-2.561682501,51.3025,-4.84E-12,10.00036926,1.5415625,-4.591124678,-1.194255352,90.00000001 +272.23,50.43283629,-2.561681094,51.2868,6.25E-12,10.0001472,1.598125,-4.67023044,-1.098795255,90.00000001 +272.24,50.43283629,-2.561679686,51.2705,4.69E-12,9.999481079,1.653125,-4.748360913,-1.002376943,90.00000001 +272.25,50.43283629,-2.561678279,51.2537,-8.44E-12,9.999036987,1.7065625,-4.82549971,-0.905084584,90.00000001 +272.26,50.43283629,-2.561676872,51.2364,-1.56E-11,9.999481027,1.76,-4.90163079,-0.807002918,90.00000001 +272.27,50.43283629,-2.561675464,51.2185,-1.02E-11,10.0001471,1.813125,-4.976738223,-0.708217603,90.00000001 +272.28,50.43283629,-2.561674057,51.2001,-4.84E-12,10.0003691,1.865,-5.050806368,-0.60881464,90.00000001 +272.29,50.43283629,-2.561672649,51.1812,-1.17E-11,10.00036907,1.9165625,-5.123819698,-0.508880831,90.00000001 +272.3,50.43283629,-2.561671242,51.1618,-2.34E-11,10.00036904,1.968125,-5.195762971,-0.408503266,90.00000001 +272.31,50.43283629,-2.561669834,51.1418,-2.58E-11,10.00036901,2.0178125,-5.26662112,-0.307769494,90.00000001 +272.32,50.43283629,-2.561668427,51.1214,-2.34E-11,10.00014695,2.065,-5.336379476,-0.20676729,90.00000001 +272.33,50.43283629,-2.561667019,51.1005,-2.81E-11,9.999480814,2.111875,-5.405023373,-0.105584834,90.00000001 +272.34,50.43283629,-2.561665612,51.0792,-3.05E-11,9.999036714,2.1596875,-5.472538542,-0.004310247,90.00000001 +272.35,50.43283629,-2.561664205,51.0573,-1.62E-11,9.999480746,2.2065625,-5.538910775,0.096968065,90.00000001 +272.36,50.43283629,-2.561662797,51.035,5.47E-12,10.00014681,2.25125,-5.604126321,0.198161808,90.00000001 +272.37,50.43283629,-2.56166139,51.0123,1.56E-11,10.00036881,2.295,-5.668171486,0.299182747,90.00000001 +272.38,50.43283629,-2.561659982,50.9891,1.08E-11,10.00036877,2.338125,-5.731032978,0.399942818,90.00000001 +272.39,50.43283629,-2.561658575,50.9655,2.34E-12,10.0001467,2.3796875,-5.79269756,0.50035413,90.00000001 +272.4,50.43283629,-2.561657167,50.9415,-1.56E-12,9.999480566,2.42,-5.8531524,0.600329078,90.00000001 +272.41,50.43283629,-2.56165576,50.9171,-4.69E-12,9.999036461,2.4596875,-5.912384949,0.699780571,90.00000001 +272.42,50.43283629,-2.561654353,50.8923,-1.42E-11,9.999480488,2.4984375,-5.970382716,0.798621864,90.00000001 +272.43,50.43283629,-2.561652945,50.8671,-3.06E-11,10.00014655,2.53625,-6.02713367,0.896766727,90.00000001 +272.44,50.43283629,-2.561651538,50.8416,-4.47E-11,10.00036854,2.573125,-6.08262595,0.994129559,90.00000001 +272.45,50.43283629,-2.56165013,50.8156,-4.23E-11,10.0003685,2.6084375,-6.136847926,1.090625564,90.00000001 +272.46,50.43283629,-2.561648723,50.7894,-2.13E-11,10.00014643,2.643125,-6.189788309,1.186170459,90.00000001 +272.47,50.43283629,-2.561647315,50.7628,-2.34E-12,9.999480286,2.678125,-6.241436043,1.280681051,90.00000001 +272.48,50.43283629,-2.561645908,50.7358,-6.41E-12,9.999036178,2.71125,-6.291780355,1.374074833,90.00000001 +272.49,50.43283629,-2.561644501,50.7085,-2.44E-11,9.999480201,2.74125,-6.340810645,1.466270446,90.00000001 +272.5,50.43283629,-2.561643093,50.681,-3.37E-11,10.00014626,2.77,-6.388516773,1.557187389,90.00000001 +272.51,50.43283629,-2.561641686,50.6531,-2.73E-11,10.00036825,2.7984375,-6.434888768,1.646746479,90.00000001 +272.52,50.43283629,-2.561640278,50.625,-1.09E-11,10.0003682,2.82625,-6.479916891,1.734869622,90.00000001 +272.53,50.43283629,-2.561638871,50.5966,3.91E-12,10.00036816,2.853125,-6.523591745,1.821479871,90.00000001 +272.54,50.43283629,-2.561637463,50.5679,4.53E-12,10.00036811,2.878125,-6.565904219,1.906501765,90.00000001 +272.55,50.43283629,-2.561636056,50.539,-9.53E-12,10.00036807,2.90125,-6.606845549,1.989861166,90.00000001 +272.56,50.43283629,-2.561634648,50.5099,-2.66E-11,10.00036802,2.9234375,-6.646407081,2.071485421,90.00000001 +272.57,50.43283629,-2.561633241,50.4805,-3.67E-11,10.00036798,2.9446875,-6.684580624,2.151303255,90.00000001 +272.58,50.43283629,-2.561631833,50.451,-3.67E-11,10.00036793,2.9646875,-6.721358154,2.229245167,90.00000001 +272.59,50.43283629,-2.561630426,50.4212,-2.66E-11,10.00014585,2.9834375,-6.756732053,2.305243091,90.00000001 +272.6,50.43283629,-2.561629018,50.3913,-9.53E-12,9.999479705,3.00125,-6.790694871,2.37923085,90.00000001 +272.61,50.43283629,-2.561627611,50.3612,4.69E-12,9.999035592,3.018125,-6.823239504,2.451143872,90.00000001 +272.62,50.43283629,-2.561626204,50.3309,4.69E-12,9.99947961,3.033125,-6.854359248,2.520919474,90.00000001 +272.63,50.43283629,-2.561624796,50.3005,-9.37E-12,10.00014566,3.04625,-6.884047515,2.588496752,90.00000001 +272.64,50.43283629,-2.561623389,50.27,-2.58E-11,10.00036765,3.0584375,-6.912298116,2.653816863,90.00000001 +272.65,50.43283629,-2.561621981,50.2393,-3.52E-11,10.0003676,3.0696875,-6.939105207,2.716822797,90.00000001 +272.66,50.43283629,-2.561620574,50.2086,-3.52E-11,10.00036755,3.0796875,-6.964463173,2.777459608,90.00000001 +272.67,50.43283629,-2.561619166,50.1777,-2.81E-11,10.0003675,3.088125,-6.988366628,2.835674469,90.00000001 +272.68,50.43283629,-2.561617759,50.1468,-2.11E-11,10.00036745,3.0946875,-7.010810703,2.891416559,90.00000001 +272.69,50.43283629,-2.561616351,50.1158,-1.87E-11,10.00036741,3.1,-7.031790641,2.944637233,90.00000001 +272.7,50.43283629,-2.561614944,50.0848,-1.64E-11,10.00036736,3.1046875,-7.051302146,2.995290198,90.00000001 +272.71,50.43283629,-2.561613536,50.0537,-9.22E-12,10.00036731,3.108125,-7.069340977,3.043331219,90.00000001 +272.72,50.43283629,-2.561612129,50.0226,-1.56E-12,10.00014523,3.1096875,-7.085903526,3.088718414,90.00000001 +272.73,50.43283629,-2.561610721,49.9915,-7.81E-13,9.999479079,3.1096875,-7.100986296,3.131412193,90.00000001 +272.74,50.43283629,-2.561609314,49.9604,-7.81E-12,9.999034964,3.108125,-7.114586079,3.171375369,90.00000001 +272.75,50.43283629,-2.561607907,49.9293,-1.33E-11,9.999478982,3.105,-7.126700069,3.208573049,90.00000001 +272.76,50.43283629,-2.561606499,49.8983,-4.53E-12,10.00014503,3.10125,-7.137325743,3.242972748,90.00000001 +272.77,50.43283629,-2.561605092,49.8673,1.64E-11,10.00036702,3.0965625,-7.146460867,3.274544556,90.00000001 +272.78,50.43283629,-2.561603684,49.8363,3.05E-11,10.00036697,3.0896875,-7.154103551,3.303260914,90.00000001 +272.79,50.43283629,-2.561602277,49.8055,2.58E-11,10.00036692,3.0815625,-7.160252191,3.329096841,90.00000001 +272.8,50.43283629,-2.561600869,49.7747,1.17E-11,10.00036687,3.0734375,-7.164905525,3.352029649,90.00000001 +272.81,50.43283629,-2.561599462,49.744,-2.22E-16,10.00036682,3.064375,-7.168062522,3.372039512,90.00000001 +272.82,50.43283629,-2.561598054,49.7134,-9.38E-12,10.00036678,3.053125,-7.16972261,3.389108842,90.00000001 +272.83,50.43283629,-2.561596647,49.6829,-1.64E-11,10.00036673,3.0396875,-7.169885387,3.403222855,90.00000001 +272.84,50.43283629,-2.561595239,49.6526,-1.87E-11,10.00036668,3.025,-7.168550797,3.414369233,90.00000001 +272.85,50.43283629,-2.561593832,49.6224,-2.12E-11,10.0001446,3.0096875,-7.165719125,3.422538179,90.00000001 +272.86,50.43283629,-2.561592424,49.5924,-2.89E-11,9.999478455,2.993125,-7.161391059,3.427722645,90.00000001 +272.87,50.43283629,-2.561591017,49.5625,-3.67E-11,9.999034342,2.9746875,-7.155567344,3.429918105,90.00000001 +272.88,50.43283629,-2.56158961,49.5329,-3.67E-11,9.999478362,2.9546875,-7.148249355,3.429122553,90.00000001 +272.89,50.43283629,-2.561588202,49.5034,-2.66E-11,10.00014441,2.9334375,-7.139438467,3.425336849,90.00000001 +272.9,50.43283629,-2.561586795,49.4742,-9.53E-12,10.0003664,2.91125,-7.129136686,3.418564144,90.00000001 +272.91,50.43283629,-2.561585387,49.4452,6.88E-12,10.00036636,2.8884375,-7.117346017,3.408810397,90.00000001 +272.92,50.43283629,-2.56158398,49.4164,1.56E-11,10.00036631,2.8646875,-7.104068981,3.396084145,90.00000001 +272.93,50.43283629,-2.561582572,49.3879,1.48E-11,10.00036627,2.8396875,-7.089308385,3.380396446,90.00000001 +272.94,50.43283629,-2.561581165,49.3596,7.81E-12,10.00014419,2.813125,-7.073067266,3.361760993,90.00000001 +272.95,50.43283629,-2.561579757,49.3316,-9.38E-13,9.999478048,2.784375,-7.055349004,3.340194003,90.00000001 +272.96,50.43283629,-2.56157835,49.3039,-1.27E-11,9.999033938,2.7534375,-7.036157382,3.315714381,90.00000001 +272.97,50.43283629,-2.561576943,49.2765,-2.75E-11,9.999477961,2.7215625,-7.015496294,3.288343327,90.00000001 +272.98,50.43283629,-2.561575535,49.2495,-3.52E-11,10.00014402,2.69,-6.993370097,3.25810485,90.00000001 +272.99,50.43283629,-2.561574128,49.2227,-2.81E-11,10.00036601,2.6584375,-6.969783487,3.225025246,90.00000001 +273,50.43283629,-2.56157272,49.1963,-8.59E-12,10.00036597,2.6259375,-6.944741278,3.189133336,90.00000001 +273.01,50.43283629,-2.561571313,49.1702,1.62E-11,10.00014389,2.5915625,-6.918248741,3.150460518,90.00000001 +273.02,50.43283629,-2.561569905,49.1444,3.11E-11,9.999477754,2.5546875,-6.890311433,3.109040368,90.00000001 +273.03,50.43283629,-2.561568498,49.1191,2.56E-11,9.999033649,2.5165625,-6.8609352,3.064909153,90.00000001 +273.04,50.43283629,-2.561567091,49.0941,1.02E-11,9.999477676,2.4784375,-6.830126113,3.018105262,90.00000001 +273.05,50.43283629,-2.561565683,49.0695,-2.34E-12,10.00014374,2.439375,-6.797890648,2.968669547,90.00000001 +273.06,50.43283629,-2.561564276,49.0453,-1.41E-11,10.00036573,2.3984375,-6.764235508,2.916645151,90.00000001 +273.07,50.43283629,-2.561562868,49.0215,-2.98E-11,10.00036569,2.35625,-6.729167798,2.862077338,90.00000001 +273.08,50.43283629,-2.561561461,48.9982,-4.53E-11,10.00036566,2.3134375,-6.692694737,2.805013779,90.00000001 +273.09,50.43283629,-2.561560053,48.9752,-5.16E-11,10.00036562,2.27,-6.654824061,2.745504205,90.00000001 +273.1,50.43283629,-2.561558646,48.9528,-4.14E-11,10.00014355,2.22625,-6.61556356,2.683600469,90.00000001 +273.11,50.43283629,-2.561557238,48.9307,-1.95E-11,9.99947742,2.1815625,-6.574921487,2.61935666,90.00000001 +273.12,50.43283629,-2.561555831,48.9091,-5.47E-12,9.99903332,2.1346875,-6.53290632,2.552828697,90.00000001 +273.13,50.43283629,-2.561554424,48.888,-1.09E-11,9.999477354,2.0865625,-6.489526825,2.484074621,90.00000001 +273.14,50.43283629,-2.561553016,48.8674,-2.55E-11,10.00014342,2.0384375,-6.444792114,2.413154421,90.00000001 +273.15,50.43283629,-2.561551609,48.8472,-3.44E-11,10.00036542,1.9896875,-6.398711468,2.340129861,90.00000001 +273.16,50.43283629,-2.561550201,48.8276,-3.36E-11,10.00036539,1.9396875,-6.351294569,2.265064712,90.00000001 +273.17,50.43283629,-2.561548794,48.8084,-2.42E-11,10.00014333,1.8884375,-6.302551216,2.188024406,90.00000001 +273.18,50.43283629,-2.561547386,48.7898,-8.44E-12,9.9994772,1.83625,-6.252491722,2.109076093,90.00000001 +273.19,50.43283629,-2.561545979,48.7717,1.03E-11,9.999033105,1.78375,-6.201126399,2.028288643,90.00000001 +273.2,50.43283629,-2.561544572,48.7541,2.97E-11,9.999477144,1.73125,-6.148466135,1.945732472,90.00000001 +273.21,50.43283629,-2.561543164,48.7371,4.36E-11,10.00014322,1.678125,-6.094521815,1.861479659,90.00000001 +273.22,50.43283629,-2.561541757,48.7205,4.22E-11,10.00036522,1.623125,-6.039304726,1.775603541,90.00000001 +273.23,50.43283629,-2.561540349,48.7046,2.89E-11,10.0003652,1.5665625,-5.982826385,1.688179062,90.00000001 +273.24,50.43283629,-2.561538942,48.6892,1.89E-11,10.00014314,1.5103125,-5.925098596,1.59928254,90.00000001 +273.25,50.43283629,-2.561537534,48.6744,1.48E-11,9.999477019,1.4546875,-5.866133446,1.508991325,90.00000001 +273.26,50.43283629,-2.561536127,48.6601,9.37E-12,9.999032931,1.398125,-5.805943256,1.417384311,90.00000001 +273.27,50.43283629,-2.56153472,48.6464,6.09E-12,9.999476976,1.34,-5.744540572,1.324541314,90.00000001 +273.28,50.43283629,-2.561533312,48.6333,1.33E-11,10.00014305,1.2815625,-5.681938172,1.23054329,90.00000001 +273.29,50.43283629,-2.561531905,48.6208,2.42E-11,10.00036507,1.223125,-5.618149177,1.135472231,90.00000001 +273.3,50.43283629,-2.561530497,48.6088,2.36E-11,10.00036505,1.163125,-5.553186935,1.039410987,90.00000001 +273.31,50.43283629,-2.56152909,48.5975,1.41E-11,10.00036503,1.101875,-5.48706497,0.94244338,90.00000001 +273.32,50.43283629,-2.561527682,48.5868,1.64E-11,10.00036501,1.0415625,-5.419797089,0.844653923,90.00000001 +273.33,50.43283629,-2.561526275,48.5767,3.52E-11,10.000365,0.9815625,-5.351397388,0.746127929,90.00000001 +273.34,50.43283629,-2.561524867,48.5671,4.69E-11,10.00036498,0.92,-5.281880075,0.646951341,90.00000001 +273.35,50.43283629,-2.56152346,48.5583,3.27E-11,10.00014294,0.858125,-5.211259703,0.547210562,90.00000001 +273.36,50.43283629,-2.561522052,48.55,3.91E-12,9.999476825,0.796875,-5.139551056,0.446992623,90.00000001 +273.37,50.43283629,-2.561520645,48.5423,-1.58E-11,9.999032747,0.734375,-5.066769087,0.346384844,90.00000001 +273.38,50.43283629,-2.561519238,48.5353,-2.34E-11,9.999476801,0.6703125,-4.992928979,0.245475058,90.00000001 +273.39,50.43283629,-2.56151783,48.5289,-3.06E-11,10.00014289,0.606875,-4.918046145,0.144351216,90.00000001 +273.4,50.43283629,-2.561516423,48.5232,-3.30E-11,10.00036491,0.5446875,-4.842136228,0.043101495,90.00000001 +273.41,50.43283629,-2.561515015,48.518,-1.89E-11,10.00036491,0.4815625,-4.765215097,-0.058185812,90.00000001 +273.42,50.43283629,-2.561513608,48.5135,-3.61E-16,10.0003649,0.4165625,-4.687298852,-0.159422355,90.00000001 +273.43,50.43283629,-2.5615122,48.5097,3.12E-12,10.00036489,0.351875,-4.60840371,-0.260519899,90.00000001 +273.44,50.43283629,-2.561510793,48.5065,-7.03E-12,10.00036489,0.2884375,-4.528546113,-0.361390264,90.00000001 +273.45,50.43283629,-2.561509385,48.5039,-1.50E-11,10.00036488,0.2246875,-4.447742849,-0.461945503,90.00000001 +273.46,50.43283629,-2.561507978,48.502,-1.72E-11,10.00036488,0.16,-4.366010706,-0.562097896,90.00000001 +273.47,50.43283629,-2.56150657,48.5007,-1.56E-11,10.00036488,0.0953125,-4.283366815,-0.66176018,90.00000001 +273.48,50.43283629,-2.561505163,48.5001,-6.87E-12,10.00014285,0.0315625,-4.199828308,-0.760845324,90.00000001 +273.49,50.43283629,-2.561503755,48.5001,4.53E-12,9.999476747,-0.031875,-4.115412775,-0.859267097,90.00000001 +273.5,50.43283629,-2.561502348,48.5007,3.91E-12,9.999032682,-0.096875,-4.030137805,-0.956939499,90.00000001 +273.51,50.43283629,-2.561500941,48.502,-6.25E-12,9.99947675,-0.163125,-3.944021217,-1.053777445,90.00000001 +273.52,50.43283629,-2.561499533,48.504,-6.09E-12,10.00014285,-0.228125,-3.857080887,-1.149696481,90.00000001 +273.53,50.43283629,-2.561498126,48.5066,7.03E-12,10.00036489,-0.2915625,-3.769335094,-1.244613014,90.00000001 +273.54,50.43283629,-2.561496718,48.5098,1.56E-11,10.00036489,-0.355,-3.680802171,-1.338444192,90.00000001 +273.55,50.43283629,-2.561495311,48.5137,9.38E-12,10.0003649,-0.4184375,-3.591500511,-1.431108198,90.00000001 +273.56,50.43283629,-2.561493903,48.5182,-4.53E-12,10.00036491,-0.4815625,-3.501448791,-1.522524301,90.00000001 +273.57,50.43283629,-2.561492496,48.5233,-1.39E-11,10.00036491,-0.5453125,-3.410665863,-1.61261269,90.00000001 +273.58,50.43283629,-2.561491088,48.5291,-1.86E-11,10.00036492,-0.6096875,-3.319170691,-1.701294926,90.00000001 +273.59,50.43283629,-2.561489681,48.5355,-2.58E-11,10.00036493,-0.673125,-3.226982298,-1.788493544,90.00000001 +273.6,50.43283629,-2.561488273,48.5426,-3.11E-11,10.00036494,-0.735,-3.134120049,-1.874132629,90.00000001 +273.61,50.43283629,-2.561486866,48.5502,-2.73E-11,10.00014292,-0.796875,-3.040603252,-1.958137409,90.00000001 +273.62,50.43283629,-2.561485458,48.5585,-2.33E-11,9.999476839,-0.86,-2.946451447,-2.040434661,90.00000001 +273.63,50.43283629,-2.561484051,48.5674,-2.58E-11,9.999032787,-0.9228125,-2.851684342,-2.120952591,90.00000001 +273.64,50.43283629,-2.561482644,48.577,-2.11E-11,9.999476867,-0.9834375,-2.756321705,-2.199621072,90.00000001 +273.65,50.43283629,-2.561481236,48.5871,-1.75E-22,10.00014298,-1.043125,-2.660383417,-2.276371461,90.00000001 +273.66,50.43283629,-2.561479829,48.5978,2.34E-11,10.00036503,-1.10375,-2.563889533,-2.351136781,90.00000001 +273.67,50.43283629,-2.561478421,48.6092,3.50E-11,10.00036505,-1.1646875,-2.466860219,-2.423851886,90.00000001 +273.68,50.43283629,-2.561477014,48.6211,3.44E-11,10.00036507,-1.2246875,-2.369315758,-2.49445335,90.00000001 +273.69,50.43283629,-2.561475606,48.6337,2.42E-11,10.00036509,-1.2834375,-2.271276492,-2.562879637,90.00000001 +273.7,50.43283629,-2.561474199,48.6468,7.97E-12,10.00036511,-1.34125,-2.172762873,-2.629070987,90.00000001 +273.71,50.43283629,-2.561472791,48.6605,-9.37E-12,10.00036513,-1.39875,-2.073795529,-2.692969819,90.00000001 +273.72,50.43283629,-2.561471384,48.6748,-2.66E-11,10.00014312,-1.45625,-1.974395087,-2.754520326,90.00000001 +273.73,50.43283629,-2.561469976,48.6896,-4.23E-11,9.999477043,-1.5134375,-1.874582344,-2.813668822,90.00000001 +273.74,50.43283629,-2.561468569,48.7051,-5.23E-11,9.999033001,-1.5696875,-1.774378042,-2.870363798,90.00000001 +273.75,50.43283629,-2.561467162,48.721,-5.39E-11,9.999477093,-1.6246875,-1.673803265,-2.92455575,90.00000001 +273.76,50.43283629,-2.561465754,48.7376,-4.36E-11,10.00014322,-1.67875,-1.572878926,-2.976197468,90.00000001 +273.77,50.43283629,-2.561464347,48.7546,-1.80E-11,10.00036528,-1.7328125,-1.471626054,-3.025243858,90.00000001 +273.78,50.43283629,-2.561462939,48.7722,1.31E-11,10.0003653,-1.786875,-1.370065904,-3.071652236,90.00000001 +273.79,50.43283629,-2.561461532,48.7904,3.19E-11,10.00036533,-1.839375,-1.26821962,-3.115382094,90.00000001 +273.8,50.43283629,-2.561460124,48.809,3.59E-11,10.00036536,-1.89,-1.166108456,-3.156395215,90.00000001 +273.81,50.43283629,-2.561458717,48.8282,3.36E-11,10.00014336,-1.9403125,-1.063753786,-3.194655962,90.00000001 +273.82,50.43283629,-2.561457309,48.8478,2.27E-11,9.99947729,-1.99125,-0.96117698,-3.23013093,90.00000001 +273.83,50.43283629,-2.561455902,48.868,2.03E-12,9.999033256,-2.0415625,-0.858399467,-3.262789181,90.00000001 +273.84,50.43283629,-2.561454495,48.8887,-1.48E-11,9.999477355,-2.089375,-0.755442618,-3.292602237,90.00000001 +273.85,50.43283629,-2.561453087,48.9098,-2.03E-11,10.00014349,-2.135,-0.652328034,-3.319544031,90.00000001 +273.86,50.43283629,-2.56145168,48.9314,-1.80E-11,10.00036555,-2.1803125,-0.549077258,-3.343591184,90.00000001 +273.87,50.43283629,-2.561450272,48.9534,-5.47E-12,10.00036559,-2.22625,-0.445711776,-3.36472267,90.00000001 +273.88,50.43283629,-2.561448865,48.9759,1.64E-11,10.00014359,-2.2715625,-0.342253245,-3.382920096,90.00000001 +273.89,50.43283629,-2.561447457,48.9989,3.12E-11,9.999477527,-2.3146875,-0.238723209,-3.398167534,90.00000001 +273.9,50.43283629,-2.56144605,49.0222,2.98E-11,9.999033497,-2.356875,-0.135143326,-3.410451692,90.00000001 +273.91,50.43283629,-2.561444643,49.046,2.81E-11,9.9994776,-2.3996875,-0.031535196,-3.419761912,90.00000001 +273.92,50.43283629,-2.561443235,49.0702,4.00E-11,10.00014374,-2.44125,0.072079466,-3.426090059,90.00000001 +273.93,50.43283629,-2.561441828,49.0949,4.94E-11,10.00036581,-2.48,0.175679116,-3.429430632,90.00000001 +273.94,50.43283629,-2.56144042,49.1198,3.53E-11,10.00036585,-2.518125,0.279242097,-3.429780652,90.00000001 +273.95,50.43283629,-2.561439013,49.1452,9.53E-12,10.00014385,-2.5565625,0.382746693,-3.427139832,90.00000001 +273.96,50.43283629,-2.561437605,49.171,1.56E-13,9.999477796,-2.5928125,0.48617142,-3.421510522,90.00000001 +273.97,50.43283629,-2.561436198,49.1971,9.37E-12,9.999033771,-2.6265625,0.589494618,-3.412897591,90.00000001 +273.98,50.43283629,-2.561434791,49.2235,1.56E-11,9.999477878,-2.66,0.69269463,-3.401308603,90.00000001 +273.99,50.43283629,-2.561433383,49.2503,9.37E-12,10.00014402,-2.693125,0.795750085,-3.386753584,90.00000001 +274,50.43283629,-2.561431976,49.2774,9.37E-13,10.00036609,-2.7246875,0.898639267,-3.369245255,90.00000001 +274.01,50.43283629,-2.561430568,49.3048,9.38E-13,10.00036614,-2.7546875,1.001340863,-3.348798912,90.00000001 +274.02,50.43283629,-2.561429161,49.3325,1.17E-11,10.00014415,-2.7834375,1.103833273,-3.325432375,90.00000001 +274.03,50.43283629,-2.561427753,49.3605,2.72E-11,9.999478092,-2.8115625,1.206095181,-3.299166042,90.00000001 +274.04,50.43283629,-2.561426346,49.3887,3.20E-11,9.99903407,-2.8396875,1.308105217,-3.270022715,90.00000001 +274.05,50.43283629,-2.561424939,49.4173,1.95E-11,9.999478181,-2.86625,1.409842067,-3.23802795,90.00000001 +274.06,50.43283629,-2.561423531,49.4461,7.19E-12,10.00014433,-2.8896875,1.511284531,-3.203209534,90.00000001 +274.07,50.43283629,-2.561422124,49.4751,1.17E-11,10.0003664,-2.9115625,1.612411353,-3.165597834,90.00000001 +274.08,50.43283629,-2.561420716,49.5043,2.56E-11,10.00036645,-2.9334375,1.71320139,-3.125225738,90.00000001 +274.09,50.43283629,-2.561419309,49.5338,3.44E-11,10.0003665,-2.9546875,1.813633729,-3.082128426,90.00000001 +274.1,50.43283629,-2.561417901,49.5634,3.36E-11,10.00036654,-2.9746875,1.913687286,-3.036343426,90.00000001 +274.11,50.43283629,-2.561416494,49.5933,2.66E-11,10.00014456,-2.993125,2.013341148,-2.987910673,90.00000001 +274.12,50.43283629,-2.561415086,49.6233,2.03E-11,9.999478503,-3.0096875,2.112574631,-2.936872395,90.00000001 +274.13,50.43283629,-2.561413679,49.6535,1.86E-11,9.999034484,-3.025,2.211366879,-2.883273167,90.00000001 +274.14,50.43283629,-2.561412272,49.6838,1.64E-11,9.999478598,-3.0396875,2.309697322,-2.827159686,90.00000001 +274.15,50.43283629,-2.561410864,49.7143,9.37E-12,10.00014475,-3.053125,2.407545393,-2.768580825,90.00000001 +274.16,50.43283629,-2.561409457,49.7449,2.34E-12,10.00036683,-3.0646875,2.504890693,-2.707587749,90.00000001 +274.17,50.43283629,-2.561408049,49.7756,2.34E-12,10.00036687,-3.0746875,2.601712883,-2.644233628,90.00000001 +274.18,50.43283629,-2.561406642,49.8064,9.37E-12,10.00036692,-3.083125,2.697991737,-2.578573696,90.00000001 +274.19,50.43283629,-2.561405234,49.8373,1.39E-11,10.00036697,-3.09,2.793707144,-2.510665191,90.00000001 +274.2,50.43283629,-2.561403827,49.8682,6.25E-12,10.00036702,-3.0965625,2.888839166,-2.440567357,90.00000001 +274.21,50.43283629,-2.561402419,49.8992,-6.25E-12,10.00036707,-3.103125,2.983367805,-2.368341329,90.00000001 +274.22,50.43283629,-2.561401012,49.9303,-8.59E-12,10.00036712,-3.1078125,3.077273468,-2.294050074,90.00000001 +274.23,50.43283629,-2.561399604,49.9614,-3.12E-12,10.00036717,-3.1096875,3.170536501,-2.217758337,90.00000001 +274.24,50.43283629,-2.561398197,49.9925,-2.50E-12,10.00014518,-3.1096875,3.263137367,-2.139532696,90.00000001 +274.25,50.43283629,-2.561396789,50.0236,-9.37E-12,9.999479129,-3.108125,3.355056757,-2.05944139,90.00000001 +274.26,50.43283629,-2.561395382,50.0547,-1.41E-11,9.999035112,-3.105,3.446275534,-1.977554147,90.00000001 +274.27,50.43283629,-2.561393975,50.0857,-7.03E-12,9.999479227,-3.1015625,3.536774562,-1.89394253,90.00000001 +274.28,50.43283629,-2.561392567,50.1167,7.03E-12,10.00014537,-3.0984375,3.626534989,-1.808679306,90.00000001 +274.29,50.43283629,-2.56139116,50.1477,1.87E-11,10.00036746,-3.094375,3.715538081,-1.7218389,90.00000001 +274.3,50.43283629,-2.561389752,50.1786,2.81E-11,10.0003675,-3.088125,3.803765216,-1.633497059,90.00000001 +274.31,50.43283629,-2.561388345,50.2095,3.52E-11,10.00036755,-3.0796875,3.891197946,-1.54373073,90.00000001 +274.32,50.43283629,-2.561386937,50.2402,3.52E-11,10.0003676,-3.0696875,3.977818106,-1.452618294,90.00000001 +274.33,50.43283629,-2.56138553,50.2709,2.58E-11,10.00036765,-3.0584375,4.063607535,-1.360239105,90.00000001 +274.34,50.43283629,-2.561384122,50.3014,9.37E-12,10.0003677,-3.04625,4.148548299,-1.266673779,90.00000001 +274.35,50.43283629,-2.561382715,50.3318,-4.69E-12,10.00036774,-3.033125,4.232622694,-1.172003906,90.00000001 +274.36,50.43283629,-2.561381307,50.3621,-4.69E-12,10.00036779,-3.018125,4.315813186,-1.076312047,90.00000001 +274.37,50.43283629,-2.5613799,50.3922,9.37E-12,10.00014581,-3.00125,4.398102416,-0.979681626,90.00000001 +274.38,50.43283629,-2.561378492,50.4221,2.56E-11,9.999479753,-2.9834375,4.47947308,-0.882196868,90.00000001 +274.39,50.43283629,-2.561377085,50.4519,3.44E-11,9.999035733,-2.9646875,4.559908333,-0.783942857,90.00000001 +274.4,50.43283629,-2.561375678,50.4814,3.36E-11,9.999479846,-2.9446875,4.639391273,-0.68500525,90.00000001 +274.41,50.43283629,-2.56137427,50.5108,2.42E-11,10.00014599,-2.9234375,4.717905284,-0.585470277,90.00000001 +274.42,50.43283629,-2.561372863,50.5399,6.25E-12,10.00036807,-2.9009375,4.795434094,-0.485424741,90.00000001 +274.43,50.43283629,-2.561371455,50.5688,-1.88E-11,10.00036811,-2.876875,4.871961431,-0.384955961,90.00000001 +274.44,50.43283629,-2.561370048,50.5975,-4.14E-11,10.00036816,-2.85125,4.94747131,-0.284151486,90.00000001 +274.45,50.43283629,-2.56136864,50.6258,-5.00E-11,10.0003682,-2.825,5.021947973,-0.183099206,90.00000001 +274.46,50.43283629,-2.561367233,50.654,-4.53E-11,10.00036825,-2.798125,5.095375838,-0.081887243,90.00000001 +274.47,50.43283629,-2.561365825,50.6818,-3.89E-11,10.00036829,-2.7696875,5.167739605,0.019396111,90.00000001 +274.48,50.43283629,-2.561364418,50.7094,-3.66E-11,10.00036833,-2.74,5.239024207,0.120662505,90.00000001 +274.49,50.43283629,-2.56136301,50.7366,-3.11E-11,10.00036838,-2.709375,5.309214688,0.221823762,90.00000001 +274.5,50.43283629,-2.561361603,50.7636,-1.41E-11,10.00014639,-2.6765625,5.378296381,0.32279153,90.00000001 +274.51,50.43283629,-2.561360195,50.7902,4.84E-12,9.999480328,-2.6415625,5.446254905,0.423477805,90.00000001 +274.52,50.43283629,-2.561358788,50.8164,7.19E-12,9.999036303,-2.606875,5.513076051,0.523794865,90.00000001 +274.53,50.43283629,-2.561357381,50.8423,-2.19E-12,9.99948041,-2.573125,5.578745838,0.623655106,90.00000001 +274.54,50.43283629,-2.561355973,50.8679,-4.53E-12,10.00014655,-2.5378125,5.643250572,0.722971553,90.00000001 +274.55,50.43283629,-2.561354566,50.8931,1.56E-13,10.00036862,-2.4996875,5.70657679,0.821657517,90.00000001 +274.56,50.43283629,-2.561353158,50.9179,2.22E-16,10.00036866,-2.4596875,5.768711312,0.919626998,90.00000001 +274.57,50.43283629,-2.561351751,50.9423,-1.02E-11,10.0003687,-2.4184375,5.829641077,1.016794566,90.00000001 +274.58,50.43283629,-2.561350343,50.9663,-2.58E-11,10.00036874,-2.3765625,5.889353363,1.113075483,90.00000001 +274.59,50.43283629,-2.561348936,50.9898,-3.42E-11,10.00014674,-2.335,5.947835796,1.208385752,90.00000001 +274.6,50.43283629,-2.561347528,51.013,-2.97E-11,9.999480677,-2.293125,6.005076055,1.302642294,90.00000001 +274.61,50.43283629,-2.561346121,51.0357,-2.19E-11,9.999036647,-2.2496875,6.061062225,1.395762947,90.00000001 +274.62,50.43283629,-2.561344714,51.058,-2.13E-11,9.999480748,-2.2046875,6.115782674,1.487666409,90.00000001 +274.63,50.43283629,-2.561343306,51.0798,-2.81E-11,10.00014688,-2.158125,6.169225885,1.578272636,90.00000001 +274.64,50.43283629,-2.561341899,51.1012,-3.05E-11,10.00036895,-2.1103125,6.221380687,1.66750262,90.00000001 +274.65,50.43283629,-2.561340491,51.122,-1.41E-11,10.00036898,-2.063125,6.272236306,1.755278493,90.00000001 +274.66,50.43283629,-2.561339084,51.1424,1.17E-11,10.00014698,-2.0165625,6.321782029,1.84152371,90.00000001 +274.67,50.43283629,-2.561337676,51.1624,2.34E-11,9.999480911,-1.9675,6.370007486,1.926163156,90.00000001 +274.68,50.43283629,-2.561336269,51.1818,2.34E-11,9.999036875,-1.915,6.416902706,2.009122918,90.00000001 +274.69,50.43283629,-2.561334862,51.2007,2.83E-11,9.999480971,-1.861875,6.462457835,2.09033069,90.00000001 +274.7,50.43283629,-2.561333454,51.219,3.36E-11,10.0001471,-1.81,6.506663306,2.169715654,90.00000001 +274.71,50.43283629,-2.561332047,51.2369,2.73E-11,10.00036916,-1.7584375,6.549510006,2.247208597,90.00000001 +274.72,50.43283629,-2.561330639,51.2542,8.44E-12,10.00036919,-1.7059375,6.590988885,2.322741967,90.00000001 +274.73,50.43283629,-2.561329232,51.271,-1.88E-11,10.00014718,-1.651875,6.631091347,2.396249874,90.00000001 +274.74,50.43283629,-2.561327824,51.2873,-4.38E-11,9.999481106,-1.59625,6.66980897,2.467668204,90.00000001 +274.75,50.43283629,-2.561326417,51.3029,-5.38E-11,9.999037065,-1.54,6.707133675,2.536934676,90.00000001 +274.76,50.43283629,-2.56132501,51.3181,-4.61E-11,9.999481155,-1.4834375,6.743057728,2.603988901,90.00000001 +274.77,50.43283629,-2.561323602,51.3326,-3.05E-11,10.00014728,-1.4265625,6.777573565,2.668772436,90.00000001 +274.78,50.43283629,-2.561322195,51.3466,-2.20E-11,10.00036933,-1.37,6.810673967,2.731228732,90.00000001 +274.79,50.43283629,-2.561320787,51.36,-2.42E-11,10.00036935,-1.3128125,6.842352058,2.791303357,90.00000001 +274.8,50.43283629,-2.56131938,51.3729,-2.03E-11,10.00014734,-1.2534375,6.872601251,2.848943942,90.00000001 +274.81,50.43283629,-2.561317972,51.3851,1.56E-13,9.999481259,-1.193125,6.901415126,2.904100183,90.00000001 +274.82,50.43283629,-2.561316565,51.3967,2.11E-11,9.999037211,-1.1334375,6.928787784,2.956724007,90.00000001 +274.83,50.43283629,-2.561315158,51.4078,2.34E-11,9.999481294,-1.073125,6.954713379,3.006769579,90.00000001 +274.84,50.43283629,-2.56131375,51.4182,1.17E-11,10.00014741,-1.0115625,6.979186641,3.054193124,90.00000001 +274.85,50.43283629,-2.561312343,51.428,2.34E-12,10.00036946,-0.9503125,7.002202356,3.098953446,90.00000001 +274.86,50.43283629,-2.561310935,51.4372,0,10.00036947,-0.89,7.023755768,3.141011356,90.00000001 +274.87,50.43283629,-2.561309528,51.4458,2.50E-12,10.00014745,-0.8296875,7.04384235,3.180330298,90.00000001 +274.88,50.43283629,-2.56130812,51.4538,1.02E-11,9.999481366,-0.768125,7.062457921,3.216875953,90.00000001 +274.89,50.43283629,-2.561306713,51.4612,1.81E-11,9.999037312,-0.7046875,7.079598583,3.250616463,90.00000001 +274.9,50.43283629,-2.561305306,51.4679,2.11E-11,9.999481389,-0.64,7.095260786,3.281522322,90.00000001 +274.91,50.43283629,-2.561303898,51.474,1.89E-11,10.0001475,-0.5753125,7.109441205,3.309566716,90.00000001 +274.92,50.43283629,-2.561302491,51.4794,9.53E-12,10.00036954,-0.5115625,7.122136918,3.334725063,90.00000001 +274.93,50.43283629,-2.561301083,51.4842,-4.53E-12,10.00036955,-0.4484375,7.133345233,3.356975478,90.00000001 +274.94,50.43283629,-2.561299676,51.4884,-1.17E-11,10.00036955,-0.385,7.143063858,3.376298594,90.00000001 +274.95,50.43283629,-2.561298268,51.4919,-5.31E-12,10.00036956,-0.3215625,7.151290787,3.39267751,90.00000001 +274.96,50.43283629,-2.561296861,51.4948,7.81E-12,10.00036956,-0.2584375,7.158024244,3.406097957,90.00000001 +274.97,50.43283629,-2.561295453,51.4971,1.66E-11,10.00036957,-0.1946875,7.163262797,3.416548249,90.00000001 +274.98,50.43283629,-2.561294046,51.4987,1.88E-11,10.00036957,-0.13,7.167005415,3.424019275,90.00000001 +274.99,50.43283629,-2.561292638,51.4997,1.88E-11,10.00036957,-0.065,7.169251295,3.428504503,90.00000001 +275,50.43283629,-2.561291231,51.5,1.88E-11,10.00014754,-5.55E-17,7.169999979,3.42999998,90.00000001 +275.01,50.43283629,-2.561289823,51.4997,1.88E-11,9.999481438,0.065,7.169251295,3.428504503,90.00000001 +275.02,50.43283629,-2.561288416,51.4987,1.88E-11,9.999037371,0.13,7.167005415,3.424019275,90.00000001 +275.03,50.43283629,-2.561287009,51.4971,1.66E-11,9.999481435,0.1946875,7.163262797,3.416548249,90.00000001 +275.04,50.43283629,-2.561285601,51.4948,7.81E-12,10.00014753,0.2584375,7.158024244,3.406097957,90.00000001 +275.05,50.43283629,-2.561284194,51.4919,-5.31E-12,10.00036956,0.3215625,7.151290787,3.39267751,90.00000001 +275.06,50.43283629,-2.561282786,51.4884,-1.17E-11,10.00036955,0.385,7.143063858,3.376298594,90.00000001 +275.07,50.43283629,-2.561281379,51.4842,-4.53E-12,10.00036955,0.4484375,7.133345233,3.356975478,90.00000001 +275.08,50.43283629,-2.561279971,51.4794,9.53E-12,10.00036954,0.5115625,7.122136918,3.334725063,90.00000001 +275.09,50.43283629,-2.561278564,51.474,1.89E-11,10.00036953,0.5753125,7.109441205,3.309566716,90.00000001 +275.1,50.43283629,-2.561277156,51.4679,2.11E-11,10.00036952,0.64,7.095260786,3.281522322,90.00000001 +275.11,50.43283629,-2.561275749,51.4612,1.81E-11,10.00036951,0.7046875,7.079598583,3.250616463,90.00000001 +275.12,50.43283629,-2.561274341,51.4538,1.02E-11,10.0003695,0.768125,7.062457921,3.216875953,90.00000001 +275.13,50.43283629,-2.561272934,51.4458,2.50E-12,10.00014745,0.8296875,7.04384235,3.180330298,90.00000001 +275.14,50.43283629,-2.561271526,51.4372,0,9.999481341,0.89,7.023755768,3.141011356,90.00000001 +275.15,50.43283629,-2.561270119,51.428,2.34E-12,9.99903726,0.9503125,7.002202356,3.098953446,90.00000001 +275.16,50.43283629,-2.561268712,51.4182,1.17E-11,9.999481311,1.0115625,6.979186641,3.054193124,90.00000001 +275.17,50.43283629,-2.561267304,51.4078,2.34E-11,10.00014739,1.073125,6.954713379,3.006769579,90.00000001 +275.18,50.43283629,-2.561265897,51.3967,2.11E-11,10.00036941,1.1334375,6.928787784,2.956724007,90.00000001 +275.19,50.43283629,-2.561264489,51.3851,1.56E-13,10.00036939,1.193125,6.901415126,2.904100183,90.00000001 +275.2,50.43283629,-2.561263082,51.3729,-2.03E-11,10.00036937,1.2534375,6.872601251,2.848943942,90.00000001 +275.21,50.43283629,-2.561261674,51.36,-2.42E-11,10.00036935,1.3128125,6.842352058,2.791303357,90.00000001 +275.22,50.43283629,-2.561260267,51.3466,-2.20E-11,10.00036933,1.37,6.810673967,2.731228732,90.00000001 +275.23,50.43283629,-2.561258859,51.3326,-3.05E-11,10.00036931,1.4265625,6.777573565,2.668772436,90.00000001 +275.24,50.43283629,-2.561257452,51.3181,-4.61E-11,10.00036929,1.4834375,6.743057728,2.603988901,90.00000001 +275.25,50.43283629,-2.561256044,51.3029,-5.38E-11,10.00036926,1.54,6.707133675,2.536934676,90.00000001 +275.26,50.43283629,-2.561254637,51.2873,-4.38E-11,10.00014721,1.59625,6.66980897,2.467668204,90.00000001 +275.27,50.43283629,-2.561253229,51.271,-1.88E-11,9.99948108,1.651875,6.631091347,2.396249874,90.00000001 +275.28,50.43283629,-2.561251822,51.2542,8.44E-12,9.999036988,1.7059375,6.590988885,2.322741967,90.00000001 +275.29,50.43283629,-2.561250415,51.2369,2.73E-11,9.999481027,1.7584375,6.549510006,2.247208597,90.00000001 +275.3,50.43283629,-2.561249007,51.219,3.36E-11,10.0001471,1.81,6.506663306,2.169715654,90.00000001 +275.31,50.43283629,-2.5612476,51.2007,2.83E-11,10.0003691,1.861875,6.462457835,2.09033069,90.00000001 +275.32,50.43283629,-2.561246192,51.1818,2.34E-11,10.00036907,1.915,6.416902706,2.009122918,90.00000001 +275.33,50.43283629,-2.561244785,51.1624,2.34E-11,10.00036904,1.9675,6.370007486,1.926163156,90.00000001 +275.34,50.43283629,-2.561243377,51.1424,1.17E-11,10.00036901,2.0165625,6.321782029,1.84152371,90.00000001 +275.35,50.43283629,-2.56124197,51.122,-1.41E-11,10.00036898,2.063125,6.272236306,1.755278493,90.00000001 +275.36,50.43283629,-2.561240562,51.1012,-3.05E-11,10.00036895,2.1103125,6.221380687,1.66750262,90.00000001 +275.37,50.43283629,-2.561239155,51.0798,-2.81E-11,10.00014688,2.158125,6.169225885,1.578272636,90.00000001 +275.38,50.43283629,-2.561237747,51.058,-2.13E-11,9.999480747,2.2046875,6.115782674,1.487666409,90.00000001 +275.39,50.43283629,-2.56123634,51.0357,-2.19E-11,9.999036646,2.2496875,6.061062225,1.395762947,90.00000001 +275.4,50.43283629,-2.561234933,51.013,-2.97E-11,9.999480677,2.293125,6.005076055,1.302642294,90.00000001 +275.41,50.43283629,-2.561233525,50.9898,-3.42E-11,10.00014674,2.335,5.947835796,1.208385752,90.00000001 +275.42,50.43283629,-2.561232118,50.9663,-2.58E-11,10.00036874,2.3765625,5.889353363,1.113075483,90.00000001 +275.43,50.43283629,-2.56123071,50.9423,-1.02E-11,10.0003687,2.4184375,5.829641077,1.016794566,90.00000001 +275.44,50.43283629,-2.561229303,50.9179,2.22E-16,10.00014663,2.4596875,5.768711312,0.919626998,90.00000001 +275.45,50.43283629,-2.561227895,50.8931,1.56E-13,9.99948049,2.4996875,5.70657679,0.821657517,90.00000001 +275.46,50.43283629,-2.561226488,50.8679,-4.53E-12,9.999036384,2.5378125,5.643250572,0.722971553,90.00000001 +275.47,50.43283629,-2.561225081,50.8423,-2.19E-12,9.99948041,2.573125,5.578745838,0.623655106,90.00000001 +275.48,50.43283629,-2.561223673,50.8164,7.19E-12,10.00014647,2.606875,5.513076051,0.523794865,90.00000001 +275.49,50.43283629,-2.561222266,50.7902,4.84E-12,10.00036846,2.6415625,5.446254905,0.423477805,90.00000001 +275.5,50.43283629,-2.561220858,50.7636,-1.41E-11,10.00036842,2.6765625,5.378296381,0.32279153,90.00000001 +275.51,50.43283629,-2.561219451,50.7366,-3.11E-11,10.00014634,2.709375,5.309214688,0.221823762,90.00000001 +275.52,50.43283629,-2.561218043,50.7094,-3.66E-11,9.999480202,2.74,5.239024207,0.120662505,90.00000001 +275.53,50.43283629,-2.561216636,50.6818,-3.89E-11,9.999036093,2.7696875,5.167739605,0.019396111,90.00000001 +275.54,50.43283629,-2.561215229,50.654,-4.53E-11,9.999480116,2.798125,5.095375838,-0.081887243,90.00000001 +275.55,50.43283629,-2.561213821,50.6258,-5.00E-11,10.00014617,2.825,5.021947973,-0.183099206,90.00000001 +275.56,50.43283629,-2.561212414,50.5975,-4.14E-11,10.00036816,2.85125,4.94747131,-0.284151486,90.00000001 +275.57,50.43283629,-2.561211006,50.5688,-1.88E-11,10.00036811,2.876875,4.871961431,-0.384955961,90.00000001 +275.58,50.43283629,-2.561209599,50.5399,6.25E-12,10.00014604,2.9009375,4.795434094,-0.485424741,90.00000001 +275.59,50.43283629,-2.561208191,50.5108,2.42E-11,9.999479892,2.9234375,4.717905284,-0.585470277,90.00000001 +275.6,50.43283629,-2.561206784,50.4814,3.36E-11,9.99903578,2.9446875,4.639391273,-0.68500525,90.00000001 +275.61,50.43283629,-2.561205377,50.4519,3.44E-11,9.999479799,2.9646875,4.559908333,-0.783942857,90.00000001 +275.62,50.43283629,-2.561203969,50.4221,2.56E-11,10.00014585,2.9834375,4.47947308,-0.882196868,90.00000001 +275.63,50.43283629,-2.561202562,50.3922,9.37E-12,10.00036784,3.00125,4.398102416,-0.979681626,90.00000001 +275.64,50.43283629,-2.561201154,50.3621,-4.69E-12,10.00036779,3.018125,4.315813186,-1.076312047,90.00000001 +275.65,50.43283629,-2.561199747,50.3318,-4.69E-12,10.00014571,3.033125,4.232622694,-1.172003906,90.00000001 +275.66,50.43283629,-2.561198339,50.3014,9.37E-12,9.999479564,3.04625,4.148548299,-1.266673779,90.00000001 +275.67,50.43283629,-2.561196932,50.2709,2.58E-11,9.999035451,3.0584375,4.063607535,-1.360239105,90.00000001 +275.68,50.43283629,-2.561195525,50.2402,3.52E-11,9.999479469,3.0696875,3.977818106,-1.452618294,90.00000001 +275.69,50.43283629,-2.561194117,50.2095,3.52E-11,10.00014552,3.0796875,3.891197946,-1.54373073,90.00000001 +275.7,50.43283629,-2.56119271,50.1786,2.81E-11,10.0003675,3.088125,3.803765216,-1.633497059,90.00000001 +275.71,50.43283629,-2.561191302,50.1477,1.87E-11,10.00036746,3.094375,3.715538081,-1.7218389,90.00000001 +275.72,50.43283629,-2.561189895,50.1167,7.03E-12,10.00036741,3.0984375,3.626534989,-1.808679306,90.00000001 +275.73,50.43283629,-2.561188487,50.0857,-7.03E-12,10.00036736,3.1015625,3.536774562,-1.89394253,90.00000001 +275.74,50.43283629,-2.56118708,50.0547,-1.41E-11,10.00036731,3.105,3.446275534,-1.977554147,90.00000001 +275.75,50.43283629,-2.561185672,50.0236,-9.37E-12,10.00036726,3.108125,3.355056757,-2.05944139,90.00000001 +275.76,50.43283629,-2.561184265,49.9925,-2.50E-12,10.00014518,3.1096875,3.263137367,-2.139532696,90.00000001 +275.77,50.43283629,-2.561182857,49.9614,-3.12E-12,9.999479033,3.1096875,3.170536501,-2.217758337,90.00000001 +275.78,50.43283629,-2.56118145,49.9303,-8.59E-12,9.999034918,3.1078125,3.077273468,-2.294050074,90.00000001 +275.79,50.43283629,-2.561180043,49.8992,-6.25E-12,9.999478935,3.103125,2.983367805,-2.368341329,90.00000001 +275.8,50.43283629,-2.561178635,49.8682,6.25E-12,10.00014499,3.0965625,2.888839166,-2.440567357,90.00000001 +275.81,50.43283629,-2.561177228,49.8373,1.39E-11,10.00036697,3.09,2.793707144,-2.510665191,90.00000001 +275.82,50.43283629,-2.56117582,49.8064,9.37E-12,10.00036692,3.083125,2.697991737,-2.578573696,90.00000001 +275.83,50.43283629,-2.561174413,49.7756,2.34E-12,10.00036687,3.0746875,2.601712883,-2.644233628,90.00000001 +275.84,50.43283629,-2.561173005,49.7449,2.34E-12,10.00036683,3.0646875,2.504890693,-2.707587749,90.00000001 +275.85,50.43283629,-2.561171598,49.7143,9.37E-12,10.00036678,3.053125,2.407545393,-2.768580825,90.00000001 +275.86,50.43283629,-2.56117019,49.6838,1.64E-11,10.00036673,3.0396875,2.309697322,-2.827159686,90.00000001 +275.87,50.43283629,-2.561168783,49.6535,1.86E-11,10.00036668,3.025,2.211366879,-2.883273167,90.00000001 +275.88,50.43283629,-2.561167375,49.6233,2.03E-11,10.00036664,3.0096875,2.112574631,-2.936872395,90.00000001 +275.89,50.43283629,-2.561165968,49.5933,2.66E-11,10.00014456,2.993125,2.013341148,-2.987910673,90.00000001 +275.9,50.43283629,-2.56116456,49.5634,3.36E-11,9.99947841,2.9746875,1.913687286,-3.036343426,90.00000001 +275.91,50.43283629,-2.561163153,49.5338,3.44E-11,9.999034298,2.9546875,1.813633729,-3.082128426,90.00000001 +275.92,50.43283629,-2.561161746,49.5043,2.56E-11,9.999478317,2.9334375,1.71320139,-3.125225738,90.00000001 +275.93,50.43283629,-2.561160338,49.4751,1.17E-11,10.00014437,2.9115625,1.612411353,-3.165597834,90.00000001 +275.94,50.43283629,-2.561158931,49.4461,7.19E-12,10.00036636,2.8896875,1.511284531,-3.203209534,90.00000001 +275.95,50.43283629,-2.561157523,49.4173,1.95E-11,10.00036631,2.86625,1.409842067,-3.23802795,90.00000001 +275.96,50.43283629,-2.561156116,49.3887,3.20E-11,10.00036627,2.8396875,1.308105217,-3.270022715,90.00000001 +275.97,50.43283629,-2.561154708,49.3605,2.73E-11,10.00036622,2.8115625,1.206095181,-3.299166042,90.00000001 +275.98,50.43283629,-2.561153301,49.3325,1.27E-11,10.00036618,2.7834375,1.103833273,-3.325432375,90.00000001 +275.99,50.43283629,-2.561151893,49.3048,3.28E-12,10.00036614,2.7546875,1.001340863,-3.348798912,90.00000001 +276,50.43283629,-2.561150486,49.2774,4.06E-12,10.00036609,2.7246875,0.898639267,-3.369245255,90.00000001 +276.01,50.43283629,-2.561149078,49.2503,1.17E-11,10.00036605,2.693125,0.795750085,-3.386753584,90.00000001 +276.02,50.43283629,-2.561147671,49.2235,1.66E-11,10.00014398,2.66,0.69269463,-3.401308603,90.00000001 +276.03,50.43283629,-2.561146263,49.1971,9.53E-12,9.999477837,2.6265625,0.589494618,-3.412897591,90.00000001 +276.04,50.43283629,-2.561144856,49.171,1.56E-13,9.99903373,2.5928125,0.48617142,-3.421510522,90.00000001 +276.05,50.43283629,-2.561143449,49.1452,9.53E-12,9.999477755,2.5565625,0.382746693,-3.427139832,90.00000001 +276.06,50.43283629,-2.561142041,49.1198,3.53E-11,10.00014382,2.518125,0.279242097,-3.429780652,90.00000001 +276.07,50.43283629,-2.561140634,49.0949,4.94E-11,10.00036581,2.48,0.175679116,-3.429430632,90.00000001 +276.08,50.43283629,-2.561139226,49.0702,4.00E-11,10.00036577,2.44125,0.072079466,-3.426090059,90.00000001 +276.09,50.43283629,-2.561137819,49.046,2.81E-11,10.00036573,2.3996875,-0.031535196,-3.419761912,90.00000001 +276.1,50.43283629,-2.561136411,49.0222,2.98E-11,10.0003657,2.356875,-0.135143326,-3.410451692,90.00000001 +276.11,50.43283629,-2.561135004,48.9989,3.12E-11,10.00036566,2.3146875,-0.238723209,-3.398167534,90.00000001 +276.12,50.43283629,-2.561133596,48.9759,1.64E-11,10.00036562,2.2715625,-0.342253245,-3.382920096,90.00000001 +276.13,50.43283629,-2.561132189,48.9534,-5.47E-12,10.00036559,2.22625,-0.445711776,-3.36472267,90.00000001 +276.14,50.43283629,-2.561130781,48.9314,-1.80E-11,10.00036555,2.1803125,-0.549077258,-3.343591184,90.00000001 +276.15,50.43283629,-2.561129374,48.9098,-2.03E-11,10.00014349,2.135,-0.652328034,-3.319544031,90.00000001 +276.16,50.43283629,-2.561127966,48.8887,-1.48E-11,9.999477355,2.089375,-0.755442618,-3.292602237,90.00000001 +276.17,50.43283629,-2.561126559,48.868,2.03E-12,9.999033256,2.0415625,-0.858399467,-3.262789181,90.00000001 +276.18,50.43283629,-2.561125152,48.8478,2.27E-11,9.99947729,1.99125,-0.96117698,-3.23013093,90.00000001 +276.19,50.43283629,-2.561123744,48.8282,3.36E-11,10.00014336,1.9403125,-1.063753786,-3.194655962,90.00000001 +276.2,50.43283629,-2.561122337,48.809,3.59E-11,10.00036536,1.89,-1.166108456,-3.156395215,90.00000001 +276.21,50.43283629,-2.561120929,48.7904,3.19E-11,10.00036533,1.839375,-1.26821962,-3.115382094,90.00000001 +276.22,50.43283629,-2.561119522,48.7722,1.31E-11,10.00014327,1.786875,-1.370065904,-3.071652236,90.00000001 +276.23,50.43283629,-2.561118114,48.7546,-1.80E-11,9.999477144,1.7328125,-1.471626054,-3.025243858,90.00000001 +276.24,50.43283629,-2.561116707,48.7376,-4.36E-11,9.999033052,1.67875,-1.572878926,-2.976197468,90.00000001 +276.25,50.43283629,-2.5611153,48.721,-5.39E-11,9.999477092,1.6246875,-1.673803265,-2.92455575,90.00000001 +276.26,50.43283629,-2.561113892,48.7051,-5.23E-11,10.00014317,1.5696875,-1.774378042,-2.870363798,90.00000001 +276.27,50.43283629,-2.561112485,48.6896,-4.23E-11,10.00036518,1.5134375,-1.874582344,-2.813668822,90.00000001 +276.28,50.43283629,-2.561111077,48.6748,-2.66E-11,10.00036515,1.45625,-1.974395087,-2.754520326,90.00000001 +276.29,50.43283629,-2.56110967,48.6605,-9.37E-12,10.0001431,1.39875,-2.073795529,-2.692969819,90.00000001 +276.3,50.43283629,-2.561108262,48.6468,7.97E-12,9.999476976,1.34125,-2.172762873,-2.629070987,90.00000001 +276.31,50.43283629,-2.561106855,48.6337,2.42E-11,9.999032889,1.2834375,-2.271276492,-2.562879637,90.00000001 +276.32,50.43283629,-2.561105448,48.6211,3.44E-11,9.999476935,1.2246875,-2.369315758,-2.49445335,90.00000001 +276.33,50.43283629,-2.56110404,48.6092,3.50E-11,10.00014302,1.1646875,-2.466860219,-2.423851886,90.00000001 +276.34,50.43283629,-2.561102633,48.5978,2.34E-11,10.00036503,1.10375,-2.563889533,-2.351136781,90.00000001 +276.35,50.43283629,-2.561101225,48.5871,-1.75E-22,10.00036501,1.043125,-2.660383417,-2.276371461,90.00000001 +276.36,50.43283629,-2.561099818,48.577,-2.11E-11,10.00014297,0.9834375,-2.756321705,-2.199621072,90.00000001 +276.37,50.43283629,-2.56109841,48.5674,-2.58E-11,9.999476852,0.9228125,-2.851684342,-2.120952591,90.00000001 +276.38,50.43283629,-2.561097003,48.5585,-2.33E-11,9.999032772,0.86,-2.946451447,-2.040434661,90.00000001 +276.39,50.43283629,-2.561095596,48.5502,-2.73E-11,9.999476824,0.796875,-3.040603252,-1.958137409,90.00000001 +276.4,50.43283629,-2.561094188,48.5426,-3.11E-11,10.00014291,0.735,-3.134120049,-1.874132629,90.00000001 +276.41,50.43283629,-2.561092781,48.5355,-2.58E-11,10.00036493,0.673125,-3.226982298,-1.788493544,90.00000001 +276.42,50.43283629,-2.561091373,48.5291,-1.86E-11,10.00036492,0.6096875,-3.319170691,-1.701294926,90.00000001 +276.43,50.43283629,-2.561089966,48.5233,-1.39E-11,10.00014288,0.5453125,-3.410665863,-1.61261269,90.00000001 +276.44,50.43283629,-2.561088558,48.5182,-4.53E-12,9.999476775,0.4815625,-3.501448791,-1.522524301,90.00000001 +276.45,50.43283629,-2.561087151,48.5137,9.38E-12,9.999032702,0.4184375,-3.591500511,-1.431108198,90.00000001 +276.46,50.43283629,-2.561085744,48.5098,1.56E-11,9.999476762,0.355,-3.680802171,-1.338444192,90.00000001 +276.47,50.43283629,-2.561084336,48.5066,7.03E-12,10.00014286,0.2915625,-3.769335094,-1.244613014,90.00000001 +276.48,50.43283629,-2.561082929,48.504,-6.09E-12,10.00036488,0.228125,-3.857080887,-1.149696481,90.00000001 +276.49,50.43283629,-2.561081521,48.502,-6.25E-12,10.00036488,0.163125,-3.944021217,-1.053777445,90.00000001 +276.5,50.43283629,-2.561080114,48.5007,3.91E-12,10.00036488,0.096875,-4.030137805,-0.956939499,90.00000001 +276.51,50.43283629,-2.561078706,48.5001,4.53E-12,10.00036488,0.031875,-4.115412775,-0.859267097,90.00000001 +276.52,50.43283629,-2.561077299,48.5001,-6.87E-12,10.00036488,-0.0315625,-4.199828308,-0.760845324,90.00000001 +276.53,50.43283629,-2.561075891,48.5007,-1.56E-11,10.00036488,-0.0953125,-4.283366815,-0.66176018,90.00000001 +276.54,50.43283629,-2.561074484,48.502,-1.72E-11,10.00014285,-0.16,-4.366010706,-0.562097896,90.00000001 +276.55,50.43283629,-2.561073076,48.5039,-1.50E-11,9.999476753,-0.2246875,-4.447742849,-0.461945503,90.00000001 +276.56,50.43283629,-2.561071669,48.5065,-7.03E-12,9.999032691,-0.2884375,-4.528546113,-0.361390264,90.00000001 +276.57,50.43283629,-2.561070262,48.5097,3.12E-12,9.999476761,-0.351875,-4.60840371,-0.260519899,90.00000001 +276.58,50.43283629,-2.561068854,48.5135,-3.61E-16,10.00014287,-0.4165625,-4.687298852,-0.159422355,90.00000001 +276.59,50.43283629,-2.561067447,48.518,-1.89E-11,10.00036491,-0.4815625,-4.765215097,-0.058185812,90.00000001 +276.6,50.43283629,-2.561066039,48.5232,-3.30E-11,10.00036491,-0.5446875,-4.842136228,0.043101495,90.00000001 +276.61,50.43283629,-2.561064632,48.5289,-3.06E-11,10.00036492,-0.606875,-4.918046145,0.144351216,90.00000001 +276.62,50.43283629,-2.561063224,48.5353,-2.34E-11,10.00036493,-0.6703125,-4.992928979,0.245475058,90.00000001 +276.63,50.43283629,-2.561061817,48.5423,-1.58E-11,10.00036495,-0.734375,-5.066769087,0.346384844,90.00000001 +276.64,50.43283629,-2.561060409,48.55,3.91E-12,10.00036496,-0.796875,-5.139551056,0.446992623,90.00000001 +276.65,50.43283629,-2.561059002,48.5583,3.27E-11,10.00036497,-0.858125,-5.211259703,0.547210562,90.00000001 +276.66,50.43283629,-2.561057594,48.5671,4.69E-11,10.00036498,-0.92,-5.281880075,0.646951341,90.00000001 +276.67,50.43283629,-2.561056187,48.5767,3.52E-11,10.00014297,-0.9815625,-5.351397388,0.746127929,90.00000001 +276.68,50.43283629,-2.561054779,48.5868,1.64E-11,9.999476882,-1.0415625,-5.419797089,0.844653923,90.00000001 +276.69,50.43283629,-2.561053372,48.5975,1.41E-11,9.999032833,-1.101875,-5.48706497,0.94244338,90.00000001 +276.7,50.43283629,-2.561051965,48.6088,2.36E-11,9.999476916,-1.163125,-5.553186935,1.039410987,90.00000001 +276.71,50.43283629,-2.561050557,48.6208,2.42E-11,10.00014303,-1.223125,-5.618149177,1.135472231,90.00000001 +276.72,50.43283629,-2.56104915,48.6333,1.33E-11,10.00036509,-1.2815625,-5.681938172,1.23054329,90.00000001 +276.73,50.43283629,-2.561047742,48.6464,6.09E-12,10.00036511,-1.34,-5.744540572,1.324541314,90.00000001 +276.74,50.43283629,-2.561046335,48.6601,9.37E-12,10.00036513,-1.398125,-5.805943256,1.417384311,90.00000001 +276.75,50.43283629,-2.561044927,48.6744,1.48E-11,10.00036515,-1.4546875,-5.866133446,1.508991325,90.00000001 +276.76,50.43283629,-2.56104352,48.6892,1.89E-11,10.00036517,-1.5103125,-5.925098596,1.59928254,90.00000001 +276.77,50.43283629,-2.561042112,48.7046,2.89E-11,10.0003652,-1.5665625,-5.982826385,1.688179062,90.00000001 +276.78,50.43283629,-2.561040705,48.7205,4.22E-11,10.00014319,-1.623125,-6.039304726,1.775603541,90.00000001 +276.79,50.43283629,-2.561039297,48.7371,4.36E-11,9.999477117,-1.678125,-6.094521815,1.861479659,90.00000001 +276.8,50.43283629,-2.56103789,48.7541,2.97E-11,9.999033078,-1.73125,-6.148466135,1.945732472,90.00000001 +276.81,50.43283629,-2.561036483,48.7717,1.03E-11,9.999477172,-1.78375,-6.201126399,2.028288643,90.00000001 +276.82,50.43283629,-2.561035075,48.7898,-8.44E-12,10.0001433,-1.83625,-6.252491722,2.109076093,90.00000001 +276.83,50.43283629,-2.561033668,48.8084,-2.42E-11,10.00036536,-1.8884375,-6.302551216,2.188024406,90.00000001 +276.84,50.43283629,-2.56103226,48.8276,-3.36E-11,10.00036539,-1.9396875,-6.351294569,2.265064712,90.00000001 +276.85,50.43283629,-2.561030853,48.8472,-3.44E-11,10.00036542,-1.9896875,-6.398711468,2.340129861,90.00000001 +276.86,50.43283629,-2.561029445,48.8674,-2.55E-11,10.00036545,-2.0384375,-6.444792114,2.413154421,90.00000001 +276.87,50.43283629,-2.561028038,48.888,-1.09E-11,10.00036549,-2.0865625,-6.489526825,2.484074621,90.00000001 +276.88,50.43283629,-2.56102663,48.9091,-5.47E-12,10.00036552,-2.1346875,-6.53290632,2.552828697,90.00000001 +276.89,50.43283629,-2.561025223,48.9307,-1.95E-11,10.00036555,-2.1815625,-6.574921487,2.61935666,90.00000001 +276.9,50.43283629,-2.561023815,48.9528,-4.14E-11,10.00036559,-2.22625,-6.61556356,2.683600469,90.00000001 +276.91,50.43283629,-2.561022408,48.9752,-5.16E-11,10.00014359,-2.27,-6.654824061,2.745504205,90.00000001 +276.92,50.43283629,-2.561021,48.9982,-4.53E-11,9.999477526,-2.3134375,-6.692694737,2.805013779,90.00000001 +276.93,50.43283629,-2.561019593,49.0215,-2.98E-11,9.999033497,-2.35625,-6.729167798,2.862077338,90.00000001 +276.94,50.43283629,-2.561018186,49.0453,-1.41E-11,9.9994776,-2.3984375,-6.764235508,2.916645151,90.00000001 +276.95,50.43283629,-2.561016778,49.0695,-2.34E-12,10.00014374,-2.439375,-6.797890648,2.968669547,90.00000001 +276.96,50.43283629,-2.561015371,49.0941,1.02E-11,10.00036581,-2.4784375,-6.830126113,3.018105262,90.00000001 +276.97,50.43283629,-2.561013963,49.1191,2.56E-11,10.00036585,-2.5165625,-6.8609352,3.064909153,90.00000001 +276.98,50.43283629,-2.561012556,49.1444,3.11E-11,10.00036589,-2.5546875,-6.890311433,3.109040368,90.00000001 +276.99,50.43283629,-2.561011148,49.1702,1.62E-11,10.00036593,-2.5915625,-6.918248741,3.150460518,90.00000001 +277,50.43283629,-2.561009741,49.1963,-8.59E-12,10.00014393,-2.6259375,-6.944741278,3.189133336,90.00000001 +277.01,50.43283629,-2.561008333,49.2227,-2.81E-11,9.999477877,-2.6584375,-6.969783487,3.225025246,90.00000001 +277.02,50.43283629,-2.561006926,49.2495,-3.52E-11,9.999033853,-2.69,-6.993370097,3.25810485,90.00000001 +277.03,50.43283629,-2.561005519,49.2765,-2.75E-11,9.999477962,-2.7215625,-7.015496294,3.288343327,90.00000001 +277.04,50.43283629,-2.561004111,49.3039,-1.27E-11,10.0001441,-2.7534375,-7.036157382,3.315714381,90.00000001 +277.05,50.43283629,-2.561002704,49.3316,-9.38E-13,10.00036618,-2.784375,-7.055349004,3.340194003,90.00000001 +277.06,50.43283629,-2.561001296,49.3596,7.81E-12,10.00036622,-2.813125,-7.073067266,3.361760993,90.00000001 +277.07,50.43283629,-2.560999889,49.3879,1.48E-11,10.00014423,-2.8396875,-7.089308385,3.380396446,90.00000001 +277.08,50.43283629,-2.560998481,49.4164,1.56E-11,9.99947818,-2.8646875,-7.104068981,3.396084145,90.00000001 +277.09,50.43283629,-2.560997074,49.4452,6.88E-12,9.999034159,-2.8884375,-7.117346017,3.408810397,90.00000001 +277.1,50.43283629,-2.560995667,49.4742,-9.53E-12,9.99947827,-2.91125,-7.129136686,3.418564144,90.00000001 +277.11,50.43283629,-2.560994259,49.5034,-2.66E-11,10.00014441,-2.9334375,-7.139438467,3.425336849,90.00000001 +277.12,50.43283629,-2.560992852,49.5329,-3.67E-11,10.00036649,-2.9546875,-7.148249355,3.429122553,90.00000001 +277.13,50.43283629,-2.560991444,49.5625,-3.67E-11,10.00036654,-2.9746875,-7.155567344,3.429918105,90.00000001 +277.14,50.43283629,-2.560990037,49.5924,-2.89E-11,10.00014455,-2.993125,-7.161391059,3.427722645,90.00000001 +277.15,50.43283629,-2.560988629,49.6224,-2.12E-11,9.999478501,-3.0096875,-7.165719125,3.422538179,90.00000001 +277.16,50.43283629,-2.560987222,49.6526,-1.87E-11,9.999034483,-3.025,-7.168550797,3.414369233,90.00000001 +277.17,50.43283629,-2.560985815,49.6829,-1.64E-11,9.999478597,-3.0396875,-7.169885387,3.403222855,90.00000001 +277.18,50.43283629,-2.560984407,49.7134,-9.38E-12,10.00014474,-3.053125,-7.16972261,3.389108842,90.00000001 +277.19,50.43283629,-2.560983,49.744,-2.22E-16,10.00036682,-3.064375,-7.168062522,3.372039512,90.00000001 +277.2,50.43283629,-2.560981592,49.7747,1.17E-11,10.00036687,-3.0734375,-7.164905525,3.352029649,90.00000001 +277.21,50.43283629,-2.560980185,49.8055,2.58E-11,10.00036692,-3.0815625,-7.160252191,3.329096841,90.00000001 +277.22,50.43283629,-2.560978777,49.8363,3.05E-11,10.00036697,-3.0896875,-7.154103551,3.303260914,90.00000001 +277.23,50.43283629,-2.56097737,49.8673,1.64E-11,10.00014498,-3.0965625,-7.146460867,3.274544556,90.00000001 +277.24,50.43283629,-2.560975962,49.8983,-4.53E-12,9.999478933,-3.10125,-7.137325743,3.242972748,90.00000001 +277.25,50.43283629,-2.560974555,49.9293,-1.33E-11,9.999034916,-3.105,-7.126700069,3.208573049,90.00000001 +277.26,50.43283629,-2.560973148,49.9604,-7.81E-12,9.999479031,-3.108125,-7.114586079,3.171375369,90.00000001 +277.27,50.43283629,-2.56097174,49.9915,-7.81E-13,10.00014518,-3.1096875,-7.100986296,3.131412193,90.00000001 +277.28,50.43283629,-2.560970333,50.0226,-1.56E-12,10.00036726,-3.1096875,-7.085903526,3.088718414,90.00000001 +277.29,50.43283629,-2.560968925,50.0537,-9.22E-12,10.00036731,-3.108125,-7.069340977,3.043331219,90.00000001 +277.3,50.43283629,-2.560967518,50.0848,-1.64E-11,10.00014533,-3.1046875,-7.051302146,2.995290198,90.00000001 +277.31,50.43283629,-2.56096611,50.1158,-1.87E-11,9.999479274,-3.1,-7.031790641,2.944637233,90.00000001 +277.32,50.43283629,-2.560964703,50.1468,-2.11E-11,9.999035256,-3.0946875,-7.010810703,2.891416559,90.00000001 +277.33,50.43283629,-2.560963296,50.1777,-2.81E-11,9.99947937,-3.088125,-6.988366628,2.835674469,90.00000001 +277.34,50.43283629,-2.560961888,50.2086,-3.52E-11,10.00014552,-3.0796875,-6.964463173,2.777459608,90.00000001 +277.35,50.43283629,-2.560960481,50.2393,-3.52E-11,10.0003676,-3.0696875,-6.939105207,2.716822797,90.00000001 +277.36,50.43283629,-2.560959073,50.27,-2.58E-11,10.00036765,-3.0584375,-6.912298116,2.653816863,90.00000001 +277.37,50.43283629,-2.560957666,50.3005,-9.37E-12,10.00036769,-3.04625,-6.884047515,2.588496752,90.00000001 +277.38,50.43283629,-2.560956258,50.3309,4.69E-12,10.00036774,-3.033125,-6.854359248,2.520919474,90.00000001 +277.39,50.43283629,-2.560954851,50.3612,4.69E-12,10.00036779,-3.018125,-6.823239504,2.451143872,90.00000001 +277.4,50.43283629,-2.560953443,50.3913,-9.53E-12,10.00036784,-3.00125,-6.790694871,2.37923085,90.00000001 +277.41,50.43283629,-2.560952036,50.4212,-2.66E-11,10.00036788,-2.9834375,-6.756732053,2.305243091,90.00000001 +277.42,50.43283629,-2.560950628,50.451,-3.67E-11,10.00036793,-2.9646875,-6.721358154,2.229245167,90.00000001 +277.43,50.43283629,-2.560949221,50.4805,-3.67E-11,10.00014594,-2.9446875,-6.684580624,2.151303255,90.00000001 +277.44,50.43283629,-2.560947813,50.5099,-2.66E-11,9.99947989,-2.9234375,-6.646407081,2.071485421,90.00000001 +277.45,50.43283629,-2.560946406,50.539,-9.53E-12,9.999035869,-2.90125,-6.606845549,1.989861166,90.00000001 +277.46,50.43283629,-2.560944999,50.5679,4.53E-12,9.999479981,-2.878125,-6.565904219,1.906501765,90.00000001 +277.47,50.43283629,-2.560943591,50.5966,3.91E-12,10.00014613,-2.853125,-6.523591745,1.821479871,90.00000001 +277.48,50.43283629,-2.560942184,50.625,-1.09E-11,10.0003682,-2.82625,-6.479916891,1.734869622,90.00000001 +277.49,50.43283629,-2.560940776,50.6531,-2.73E-11,10.00036825,-2.7984375,-6.434888768,1.646746479,90.00000001 +277.5,50.43283629,-2.560939369,50.681,-3.37E-11,10.00036829,-2.77,-6.388516773,1.557187389,90.00000001 +277.51,50.43283629,-2.560937961,50.7085,-2.44E-11,10.00036833,-2.74125,-6.340810645,1.466270446,90.00000001 +277.52,50.43283629,-2.560936554,50.7358,-6.41E-12,10.00036838,-2.71125,-6.291780355,1.374074833,90.00000001 +277.53,50.43283629,-2.560935146,50.7628,-2.34E-12,10.00036842,-2.678125,-6.241436043,1.280681051,90.00000001 +277.54,50.43283629,-2.560933739,50.7894,-2.13E-11,10.00036846,-2.643125,-6.189788309,1.186170459,90.00000001 +277.55,50.43283629,-2.560932331,50.8156,-4.23E-11,10.0003685,-2.6084375,-6.136847926,1.090625564,90.00000001 +277.56,50.43283629,-2.560930924,50.8416,-4.47E-11,10.00014651,-2.573125,-6.08262595,0.994129559,90.00000001 +277.57,50.43283629,-2.560929516,50.8671,-3.06E-11,9.999480449,-2.53625,-6.02713367,0.896766727,90.00000001 +277.58,50.43283629,-2.560928109,50.8923,-1.42E-11,9.999036422,-2.4984375,-5.970382716,0.798621864,90.00000001 +277.59,50.43283629,-2.560926702,50.9171,-4.69E-12,9.999480527,-2.4596875,-5.912384949,0.699780571,90.00000001 +277.6,50.43283629,-2.560925294,50.9415,-1.56E-12,10.00014666,-2.42,-5.8531524,0.600329078,90.00000001 +277.61,50.43283629,-2.560923887,50.9655,2.34E-12,10.00036874,-2.3796875,-5.79269756,0.50035413,90.00000001 +277.62,50.43283629,-2.560922479,50.9891,1.08E-11,10.00036877,-2.338125,-5.731032978,0.399942818,90.00000001 +277.63,50.43283629,-2.560921072,51.0123,1.56E-11,10.00036881,-2.295,-5.668171486,0.299182747,90.00000001 +277.64,50.43283629,-2.560919664,51.035,5.47E-12,10.00036884,-2.25125,-5.604126321,0.198161808,90.00000001 +277.65,50.43283629,-2.560918257,51.0573,-1.62E-11,10.00036888,-2.2065625,-5.538910775,0.096968065,90.00000001 +277.66,50.43283629,-2.560916849,51.0792,-3.05E-11,10.00036891,-2.1596875,-5.472538542,-0.004310247,90.00000001 +277.67,50.43283629,-2.560915442,51.1005,-2.81E-11,10.00014691,-2.111875,-5.405023373,-0.105584834,90.00000001 +277.68,50.43283629,-2.560914034,51.1214,-2.34E-11,9.999480847,-2.065,-5.336379476,-0.20676729,90.00000001 +277.69,50.43283629,-2.560912627,51.1418,-2.58E-11,9.999036813,-2.0178125,-5.26662112,-0.307769494,90.00000001 +277.7,50.43283629,-2.56091122,51.1618,-2.34E-11,9.99948091,-1.968125,-5.195762971,-0.408503266,90.00000001 +277.71,50.43283629,-2.560909812,51.1812,-1.17E-11,10.00014704,-1.9165625,-5.123819698,-0.508880831,90.00000001 +277.72,50.43283629,-2.560908405,51.2001,-4.84E-12,10.0003691,-1.865,-5.050806368,-0.60881464,90.00000001 +277.73,50.43283629,-2.560906997,51.2185,-1.02E-11,10.00036913,-1.813125,-4.976738223,-0.708217603,90.00000001 +277.74,50.43283629,-2.56090559,51.2364,-1.56E-11,10.00036916,-1.76,-4.90163079,-0.807002918,90.00000001 +277.75,50.43283629,-2.560904182,51.2537,-8.44E-12,10.00036919,-1.7065625,-4.82549971,-0.905084584,90.00000001 +277.76,50.43283629,-2.560902775,51.2705,4.69E-12,10.00036921,-1.653125,-4.748360913,-1.002376943,90.00000001 +277.77,50.43283629,-2.560901367,51.2868,6.25E-12,10.00036924,-1.598125,-4.67023044,-1.098795255,90.00000001 +277.78,50.43283629,-2.56089996,51.3025,-4.84E-12,10.00014723,-1.5415625,-4.591124678,-1.194255352,90.00000001 +277.79,50.43283629,-2.560898552,51.3176,-1.25E-11,9.999481153,-1.485,-4.511060071,-1.288674098,90.00000001 +277.8,50.43283629,-2.560897145,51.3322,-7.03E-12,9.99903711,-1.4284375,-4.430053407,-1.381969103,90.00000001 +277.81,50.43283629,-2.560895738,51.3462,7.97E-12,9.999481199,-1.37125,-4.348121589,-1.474058947,90.00000001 +277.82,50.43283629,-2.56089433,51.3596,2.42E-11,10.00014732,-1.3134375,-4.265281746,-1.564863419,90.00000001 +277.83,50.43283629,-2.560892923,51.3725,3.20E-11,10.00036937,-1.255,-4.181551127,-1.654303334,90.00000001 +277.84,50.43283629,-2.560891515,51.3847,2.33E-11,10.00036939,-1.19625,-4.096947262,-1.742300656,90.00000001 +277.85,50.43283629,-2.560890108,51.3964,2.34E-12,10.00014738,-1.1365625,-4.011487799,-1.828778665,90.00000001 +277.86,50.43283629,-2.5608887,51.4075,-9.37E-12,9.999481294,-1.075,-3.925190558,-1.913661962,90.00000001 +277.87,50.43283629,-2.560887293,51.4179,2.34E-12,9.999037245,-1.0134375,-3.838073643,-1.996876461,90.00000001 +277.88,50.43283629,-2.560885886,51.4277,2.11E-11,9.999481326,-0.9534375,-3.75015516,-2.078349742,90.00000001 +277.89,50.43283629,-2.560884478,51.437,2.58E-11,10.00014744,-0.8928125,-3.661453501,-2.158010585,90.00000001 +277.9,50.43283629,-2.560883071,51.4456,2.33E-11,10.00036949,-0.83,-3.57198723,-2.235789663,90.00000001 +277.91,50.43283629,-2.560881663,51.4536,2.73E-11,10.0003695,-0.766875,-3.481774968,-2.31161908,90.00000001 +277.92,50.43283629,-2.560880256,51.4609,3.11E-11,10.00014748,-0.705,-3.390835565,-2.385432774,90.00000001 +277.93,50.43283629,-2.560878848,51.4677,2.58E-11,9.999481388,-0.643125,-3.299188043,-2.457166288,90.00000001 +277.94,50.43283629,-2.560877441,51.4738,1.86E-11,9.999037332,-0.5796875,-3.20685154,-2.526757112,90.00000001 +277.95,50.43283629,-2.560876034,51.4793,1.62E-11,9.999481407,-0.515,-3.113845307,-2.594144626,90.00000001 +277.96,50.43283629,-2.560874626,51.4841,1.86E-11,10.00014751,-0.4503125,-3.020188823,-2.659269931,90.00000001 +277.97,50.43283629,-2.560873219,51.4883,2.81E-11,10.00036955,-0.3865625,-2.925901571,-2.722076362,90.00000001 +277.98,50.43283629,-2.560871811,51.4918,4.28E-11,10.00036956,-0.3234375,-2.831003316,-2.782509085,90.00000001 +277.99,50.43283629,-2.560870404,51.4948,5.08E-11,10.00036956,-0.26,-2.735513826,-2.840515447,90.00000001 +278,50.43283629,-2.560868996,51.497,4.20E-11,10.00036957,-0.19625,-2.63945304,-2.896044797,90.00000001 +278.01,50.43283629,-2.560867589,51.4987,1.87E-11,10.00014754,-0.131875,-2.542841068,-2.949048779,90.00000001 +278.02,50.43283629,-2.560866181,51.4997,-4.69E-12,9.999481438,-0.06625,-2.445698022,-2.999481097,90.00000001 +278.03,50.43283629,-2.560864774,51.5,-1.88E-11,9.999037373,-0.000625,-2.348044242,-3.047297863,90.00000001 +278.04,50.43283629,-2.560863367,51.4997,-3.05E-11,9.999481439,0.0634375,-2.249900124,-3.092457365,90.00000001 +278.05,50.43283629,-2.560861959,51.4987,-4.22E-11,10.00014754,0.126875,-2.151286123,-3.134920127,90.00000001 +278.06,50.43283629,-2.560860552,51.4972,-4.00E-11,10.00036957,0.1915625,-2.052222866,-3.17464925,90.00000001 +278.07,50.43283629,-2.560859144,51.4949,-2.19E-11,10.00036956,0.2565625,-1.952731037,-3.211610012,90.00000001 +278.08,50.43283629,-2.560857737,51.492,-8.75E-12,10.00014753,0.3196875,-1.852831376,-3.245770214,90.00000001 +278.09,50.43283629,-2.560856329,51.4885,-9.38E-12,9.999481421,0.3821875,-1.752544797,-3.277100062,90.00000001 +278.1,50.43283629,-2.560854922,51.4844,-4.84E-12,9.999037348,0.4465625,-1.651892213,-3.305572226,90.00000001 +278.11,50.43283629,-2.560853515,51.4796,1.39E-11,9.999481407,0.5115625,-1.55089465,-3.331161839,90.00000001 +278.12,50.43283629,-2.560852107,51.4741,2.56E-11,10.0001475,0.575,-1.449573195,-3.35384667,90.00000001 +278.13,50.43283629,-2.5608507,51.4681,1.17E-11,10.00036952,0.638125,-1.347948989,-3.373606896,90.00000001 +278.14,50.43283629,-2.560849292,51.4614,-1.58E-11,10.00036951,0.701875,-1.246043345,-3.39042527,90.00000001 +278.15,50.43283629,-2.560847885,51.454,-3.12E-11,10.0003695,0.7646875,-1.143877465,-3.404287181,90.00000001 +278.16,50.43283629,-2.560846477,51.4461,-2.59E-11,10.00036949,0.8265625,-1.041472661,-3.415180484,90.00000001 +278.17,50.43283629,-2.56084507,51.4375,-1.17E-11,10.00036947,0.8884375,-0.938850362,-3.423095667,90.00000001 +278.18,50.43283629,-2.560843662,51.4283,-2.34E-12,10.00036946,0.9496875,-0.836032054,-3.428025912,90.00000001 +278.19,50.43283629,-2.560842255,51.4185,2.78E-16,10.00014741,1.01,-0.733039109,-3.429966806,90.00000001 +278.2,50.43283629,-2.560840847,51.4081,-2.34E-12,9.999481295,1.0703125,-0.62989307,-3.428916746,90.00000001 +278.21,50.43283629,-2.56083944,51.3971,-1.17E-11,9.999037212,1.1315625,-0.526615536,-3.424876649,90.00000001 +278.22,50.43283629,-2.560838033,51.3855,-2.36E-11,9.99948126,1.193125,-0.423227938,-3.417850009,90.00000001 +278.23,50.43283629,-2.560836625,51.3732,-2.66E-11,10.00014734,1.2528125,-0.319752046,-3.4078429,90.00000001 +278.24,50.43283629,-2.560835218,51.3604,-2.50E-11,10.00036935,1.31,-0.216209348,-3.394864146,90.00000001 +278.25,50.43283629,-2.56083381,51.347,-2.95E-11,10.00036933,1.366875,-0.112621444,-3.378924975,90.00000001 +278.26,50.43283629,-2.560832403,51.3331,-3.28E-11,10.00036931,1.425,-0.009010105,-3.36003937,90.00000001 +278.27,50.43283629,-2.560830995,51.3185,-2.66E-11,10.00036929,1.483125,0.094603181,-3.338223773,90.00000001 +278.28,50.43283629,-2.560829588,51.3034,-1.89E-11,10.00036926,1.5396875,0.198196701,-3.313497149,90.00000001 +278.29,50.43283629,-2.56082818,51.2877,-1.72E-11,10.00036924,1.595,0.301748796,-3.285881156,90.00000001 +278.3,50.43283629,-2.560826773,51.2715,-1.64E-11,10.00036921,1.6496875,0.405237865,-3.255399801,90.00000001 +278.31,50.43283629,-2.560825365,51.2547,-8.44E-12,10.00036919,1.7034375,0.508642366,-3.22207967,90.00000001 +278.32,50.43283629,-2.560823958,51.2374,5.47E-12,10.00014713,1.7565625,0.611940583,-3.185949868,90.00000001 +278.33,50.43283629,-2.56082255,51.2196,1.33E-11,9.999481,1.81,0.715111031,-3.147041851,90.00000001 +278.34,50.43283629,-2.560821143,51.2012,1.16E-11,9.999036906,1.8628125,0.818132165,-3.105389538,90.00000001 +278.35,50.43283629,-2.560819736,51.1823,1.41E-11,9.999480943,1.913125,0.920982387,-3.061029312,90.00000001 +278.36,50.43283629,-2.560818328,51.1629,2.34E-11,10.00014701,1.961875,1.023640323,-3.013999848,90.00000001 +278.37,50.43283629,-2.560816921,51.1431,2.11E-11,10.00036901,2.0115625,1.12608449,-2.964342111,90.00000001 +278.38,50.43283629,-2.560815513,51.1227,2.34E-12,10.00036898,2.0615625,1.228293457,-2.912099419,90.00000001 +278.39,50.43283629,-2.560814106,51.1018,-1.17E-11,10.00036895,2.1096875,1.330245911,-2.85731732,90.00000001 +278.4,50.43283629,-2.560812698,51.0805,-7.03E-12,10.00036891,2.1565625,1.431920537,-2.800043656,90.00000001 +278.41,50.43283629,-2.560811291,51.0587,4.84E-12,10.00036888,2.203125,1.533296194,-2.740328219,90.00000001 +278.42,50.43283629,-2.560809883,51.0364,5.47E-12,10.00036885,2.248125,1.634351568,-2.678223261,90.00000001 +278.43,50.43283629,-2.560808476,51.0137,-5.47E-12,10.00036881,2.2915625,1.735065688,-2.613782812,90.00000001 +278.44,50.43283629,-2.560807068,50.9906,-1.27E-11,10.00036877,2.335,1.835417413,-2.54706308,90.00000001 +278.45,50.43283629,-2.560805661,50.967,-9.37E-12,10.0001467,2.378125,1.935385886,-2.478122334,90.00000001 +278.46,50.43283629,-2.560804253,50.943,-1.41E-12,9.999480568,2.419375,2.034950137,-2.407020564,90.00000001 +278.47,50.43283629,-2.560802846,50.9186,1.03E-11,9.999036464,2.4584375,2.134089425,-2.333819877,90.00000001 +278.48,50.43283629,-2.560801439,50.8938,2.56E-11,9.999480491,2.4965625,2.232783067,-2.258584044,90.00000001 +278.49,50.43283629,-2.560800031,50.8687,3.11E-11,10.00014655,2.5346875,2.331010378,-2.181378726,90.00000001 +278.5,50.43283629,-2.560798624,50.8431,1.63E-11,10.00036854,2.5715625,2.428750905,-2.102271188,90.00000001 +278.51,50.43283629,-2.560797216,50.8172,-6.25E-12,10.0003685,2.60625,2.525984192,-2.021330472,90.00000001 +278.52,50.43283629,-2.560795809,50.791,-1.87E-11,10.00036846,2.6403125,2.622690014,-1.938627051,90.00000001 +278.53,50.43283629,-2.560794401,50.7644,-2.34E-11,10.00036842,2.6746875,2.718848088,-1.854233175,90.00000001 +278.54,50.43283629,-2.560792994,50.7375,-2.97E-11,10.00036838,2.708125,2.814438361,-1.768222355,90.00000001 +278.55,50.43283629,-2.560791586,50.7102,-3.52E-11,10.00036834,2.7396875,2.909440837,-1.680669648,90.00000001 +278.56,50.43283629,-2.560790179,50.6827,-3.37E-11,10.00014626,2.7696875,3.003835806,-1.591651373,90.00000001 +278.57,50.43283629,-2.560788771,50.6548,-2.66E-11,9.999480117,2.798125,3.097603386,-1.501245107,90.00000001 +278.58,50.43283629,-2.560787364,50.6267,-2.03E-11,9.999036007,2.8246875,3.190724096,-1.409529805,90.00000001 +278.59,50.43283629,-2.560785957,50.5983,-1.87E-11,9.999480028,2.85,3.283178457,-1.316585279,90.00000001 +278.6,50.43283629,-2.560784549,50.5697,-1.95E-11,10.00014608,2.875,3.374947216,-1.222492717,90.00000001 +278.61,50.43283629,-2.560783142,50.5408,-2.27E-11,10.00036807,2.8996875,3.466011123,-1.127334168,90.00000001 +278.62,50.43283629,-2.560781734,50.5117,-2.97E-11,10.00036803,2.923125,3.556351154,-1.031192537,90.00000001 +278.63,50.43283629,-2.560780327,50.4823,-3.59E-11,10.00014595,2.9446875,3.645948575,-0.93415165,90.00000001 +278.64,50.43283629,-2.560778919,50.4528,-3.53E-11,9.999479801,2.9646875,3.734784536,-0.836296188,90.00000001 +278.65,50.43283629,-2.560777512,50.423,-2.58E-11,9.999035688,2.9834375,3.822840528,-0.737711465,90.00000001 +278.66,50.43283629,-2.560776105,50.3931,-9.38E-12,9.999479708,3.00125,3.910098162,-0.638483483,90.00000001 +278.67,50.43283629,-2.560774697,50.363,4.69E-12,10.00014576,3.018125,3.996539273,-0.538698701,90.00000001 +278.68,50.43283629,-2.56077329,50.3327,7.03E-12,10.00036774,3.0328125,4.082145699,-0.438444207,90.00000001 +278.69,50.43283629,-2.560771882,50.3023,4.69E-12,10.0003677,3.045,4.166899679,-0.337807322,90.00000001 +278.7,50.43283629,-2.560770475,50.2718,1.17E-11,10.00036765,3.0565625,4.250783393,-0.236875879,90.00000001 +278.71,50.43283629,-2.560769067,50.2412,2.34E-11,10.0003676,3.068125,4.333779424,-0.135737884,90.00000001 +278.72,50.43283629,-2.56076766,50.2104,2.34E-11,10.00014552,3.078125,4.41587041,-0.034481517,90.00000001 +278.73,50.43283629,-2.560766252,50.1796,9.37E-12,9.999479373,3.08625,4.497039164,0.066804874,90.00000001 +278.74,50.43283629,-2.560764845,50.1487,-7.03E-12,9.999035259,3.0934375,4.577268782,0.168033051,90.00000001 +278.75,50.43283629,-2.560763438,50.1177,-1.64E-11,9.999479277,3.0996875,4.656542478,0.269114724,90.00000001 +278.76,50.43283629,-2.56076203,50.0867,-1.64E-11,10.00014533,3.1046875,4.73484375,0.369961656,90.00000001 +278.77,50.43283629,-2.560760623,50.0556,-9.38E-12,10.00036731,3.108125,4.812156211,0.470486012,90.00000001 +278.78,50.43283629,-2.560759215,50.0245,-2.34E-12,10.00036726,3.1096875,4.888463704,0.570600131,90.00000001 +278.79,50.43283629,-2.560757808,49.9934,-2.34E-12,10.00014518,3.1096875,4.963750301,0.670216636,90.00000001 +278.8,50.43283629,-2.5607564,49.9623,-9.37E-12,9.999479033,3.108125,5.038000303,0.769248724,90.00000001 +278.81,50.43283629,-2.560754993,49.9312,-1.39E-11,9.999034919,3.105,5.111198125,0.867609993,90.00000001 +278.82,50.43283629,-2.560753586,49.9002,-6.25E-12,9.999478937,3.1015625,5.183328584,0.965214728,90.00000001 +278.83,50.43283629,-2.560752178,49.8692,6.25E-12,10.00014499,3.098125,5.254376554,1.061977732,90.00000001 +278.84,50.43283629,-2.560750771,49.8382,8.59E-12,10.00036697,3.0928125,5.324327252,1.15781472,90.00000001 +278.85,50.43283629,-2.560749363,49.8073,3.12E-12,10.00036692,3.0846875,5.393166011,1.252642043,90.00000001 +278.86,50.43283629,-2.560747956,49.7765,2.50E-12,10.00014484,3.0746875,5.46087845,1.346377079,90.00000001 +278.87,50.43283629,-2.560746548,49.7458,1.17E-11,9.999478695,3.0634375,5.527450473,1.43893801,90.00000001 +278.88,50.43283629,-2.560745141,49.7152,2.59E-11,9.999034581,3.0515625,5.592868159,1.53024422,90.00000001 +278.89,50.43283629,-2.560743734,49.6848,3.12E-11,9.999478599,3.0396875,5.65711787,1.620215955,90.00000001 +278.9,50.43283629,-2.560742326,49.6544,1.80E-11,10.00014465,3.0265625,5.720186142,1.70877489,90.00000001 +278.91,50.43283629,-2.560740919,49.6242,-5.47E-12,10.00036664,3.0109375,5.782059797,1.795843791,90.00000001 +278.92,50.43283629,-2.560739511,49.5942,-2.50E-11,10.00036659,2.9934375,5.842726,1.881346626,90.00000001 +278.93,50.43283629,-2.560738104,49.5643,-3.50E-11,10.00036654,2.9746875,5.902171976,1.965208912,90.00000001 +278.94,50.43283629,-2.560736696,49.5347,-3.75E-11,10.0003665,2.955,5.960385405,2.04735748,90.00000001 +278.95,50.43283629,-2.560735289,49.5052,-3.75E-11,10.00014442,2.935,6.017354025,2.12772077,90.00000001 +278.96,50.43283629,-2.560733881,49.476,-3.27E-11,9.999478274,2.914375,6.073066035,2.20622865,90.00000001 +278.97,50.43283629,-2.560732474,49.4469,-1.56E-11,9.999034162,2.8915625,6.127509802,2.282812653,90.00000001 +278.98,50.43283629,-2.560731067,49.4181,6.25E-12,9.999478182,2.86625,6.180673869,2.357406028,90.00000001 +278.99,50.43283629,-2.560729659,49.3896,1.56E-11,10.00014424,2.84,6.232547176,2.429943688,90.00000001 +279,50.43283629,-2.560728252,49.3613,1.03E-11,10.00036623,2.813125,6.283118894,2.500362379,90.00000001 +279.01,50.43283629,-2.560726844,49.3333,3.28E-12,10.00036618,2.7846875,6.332378482,2.568600735,90.00000001 +279.02,50.43283629,-2.560725437,49.3056,1.56E-12,10.00036614,2.755,6.380315627,2.634599285,90.00000001 +279.03,50.43283629,-2.560724029,49.2782,-9.37E-13,10.0003661,2.7246875,6.4269203,2.698300332,90.00000001 +279.04,50.43283629,-2.560722622,49.2511,-1.17E-11,10.00036605,2.6934375,6.47218282,2.75964847,90.00000001 +279.05,50.43283629,-2.560721214,49.2243,-2.97E-11,10.00036601,2.66125,6.516093732,2.818590185,90.00000001 +279.06,50.43283629,-2.560719807,49.1979,-4.45E-11,10.00036597,2.628125,6.558643813,2.875074026,90.00000001 +279.07,50.43283629,-2.560718399,49.1717,-4.47E-11,10.00036593,2.593125,6.59982418,2.929050719,90.00000001 +279.08,50.43283629,-2.560716992,49.146,-3.06E-11,10.00014386,2.55625,6.639626298,2.98047328,90.00000001 +279.09,50.43283629,-2.560715584,49.1206,-1.42E-11,9.999477718,2.5184375,6.6780418,3.02929679,90.00000001 +279.1,50.43283629,-2.560714177,49.0956,-4.69E-12,9.999033612,2.4796875,6.715062666,3.075478735,90.00000001 +279.11,50.43283629,-2.56071277,49.071,-1.56E-12,9.999477639,2.44,6.750681218,3.118978837,90.00000001 +279.12,50.43283629,-2.560711362,49.0468,-2.78E-17,10.0001437,2.4,6.784889949,3.159759108,90.00000001 +279.13,50.43283629,-2.560709955,49.023,-9.38E-13,10.0003657,2.3596875,6.817681756,3.197784025,90.00000001 +279.14,50.43283629,-2.560708547,48.9996,-7.81E-12,10.00036566,2.318125,6.849049763,3.233020471,90.00000001 +279.15,50.43283629,-2.56070714,48.9766,-1.56E-11,10.00036562,2.2746875,6.878987438,3.265437621,90.00000001 +279.16,50.43283629,-2.560705732,48.9541,-1.64E-11,10.00036559,2.2296875,6.907488536,3.295007285,90.00000001 +279.17,50.43283629,-2.560704325,48.932,-7.81E-12,10.00036555,2.1834375,6.934547041,3.321703623,90.00000001 +279.18,50.43283629,-2.560702917,48.9104,5.47E-12,10.00036552,2.1365625,6.960157395,3.345503431,90.00000001 +279.19,50.43283629,-2.56070151,48.8893,1.00E-11,10.00036549,2.0896875,6.984314212,3.366385851,90.00000001 +279.2,50.43283629,-2.560700102,48.8686,-3.91E-12,10.00036546,2.0415625,7.007012451,3.38433278,90.00000001 +279.21,50.43283629,-2.560698695,48.8484,-2.28E-11,10.00014339,1.9915625,7.028247356,3.399328518,90.00000001 +279.22,50.43283629,-2.560697287,48.8288,-2.27E-11,9.999477261,1.9415625,7.048014514,3.411360002,90.00000001 +279.23,50.43283629,-2.56069588,48.8096,-3.13E-12,9.999033165,1.8915625,7.066309744,3.420416688,90.00000001 +279.24,50.43283629,-2.560694473,48.7909,1.17E-11,9.999477201,1.8396875,7.083129321,3.426490728,90.00000001 +279.25,50.43283629,-2.560693065,48.7728,1.02E-11,10.00014327,1.786875,7.098469636,3.429576851,90.00000001 +279.26,50.43283629,-2.560691658,48.7552,6.25E-12,10.00036528,1.735,7.112327537,3.429672306,90.00000001 +279.27,50.43283629,-2.56069025,48.7381,8.44E-12,10.00036525,1.6828125,7.124700102,3.426777035,90.00000001 +279.28,50.43283629,-2.560688843,48.7215,4.69E-12,10.00036522,1.628125,7.135584811,3.420893561,90.00000001 +279.29,50.43283629,-2.560687435,48.7055,-8.59E-12,10.0003652,1.5715625,7.144979313,3.412027039,90.00000001 +279.3,50.43283629,-2.560686028,48.6901,-1.63E-11,10.00036518,1.515,7.152881662,3.400185147,90.00000001 +279.31,50.43283629,-2.56068462,48.6752,-1.09E-11,10.00036515,1.458125,7.159290252,3.385378314,90.00000001 +279.32,50.43283629,-2.560683213,48.6609,-4.69E-12,10.00036513,1.4,7.164203709,3.367619315,90.00000001 +279.33,50.43283629,-2.560681805,48.6472,-7.97E-12,10.00036511,1.341875,7.167621001,3.346923678,90.00000001 +279.34,50.43283629,-2.560680398,48.6341,-1.02E-11,10.00014306,1.2846875,7.169541441,3.323309567,90.00000001 +279.35,50.43283629,-2.56067899,48.6215,3.12E-12,9.999476937,1.2265625,7.169964627,3.296797377,90.00000001 +279.36,50.43283629,-2.560677583,48.6095,2.12E-11,9.999032852,1.1665625,7.168890446,3.267410372,90.00000001 +279.37,50.43283629,-2.560676176,48.5982,2.11E-11,9.9994769,1.1065625,7.166319126,3.235174162,90.00000001 +279.38,50.43283629,-2.560674768,48.5874,2.34E-12,10.00014298,1.0465625,7.162251183,3.200116822,90.00000001 +279.39,50.43283629,-2.560673361,48.5772,-1.17E-11,10.000365,0.9846875,7.156687534,3.162268949,90.00000001 +279.4,50.43283629,-2.560671953,48.5677,-9.37E-12,10.00036498,0.921875,7.149629324,3.121663488,90.00000001 +279.41,50.43283629,-2.560670546,48.5588,-2.50E-12,10.00036497,0.8603125,7.141077986,3.078335904,90.00000001 +279.42,50.43283629,-2.560669138,48.5505,1.56E-12,10.00036496,0.7996875,7.131035297,3.032323955,90.00000001 +279.43,50.43283629,-2.560667731,48.5428,7.66E-12,10.00014291,0.738125,7.119503432,2.983667806,90.00000001 +279.44,50.43283629,-2.560666323,48.5357,1.17E-11,9.999476802,0.675,7.106484685,2.932409856,90.00000001 +279.45,50.43283629,-2.560664916,48.5293,4.53E-12,9.999032726,0.6115625,7.091981863,2.878594738,90.00000001 +279.46,50.43283629,-2.560663509,48.5235,-9.53E-12,9.999476783,0.5484375,7.075998002,2.822269491,90.00000001 +279.47,50.43283629,-2.560662101,48.5183,-1.89E-11,10.00014287,0.4846875,7.058536426,2.763483162,90.00000001 +279.48,50.43283629,-2.560660694,48.5138,-2.11E-11,10.0003649,0.42,7.039600686,2.702287087,90.00000001 +279.49,50.43283629,-2.560659286,48.5099,-1.80E-11,10.00036489,0.3553125,7.019194852,2.638734551,90.00000001 +279.5,50.43283629,-2.560657879,48.5067,-7.03E-12,10.00014286,0.2915625,6.997323162,2.572880959,90.00000001 +279.51,50.43283629,-2.560656471,48.5041,8.44E-12,9.999476753,0.2284375,6.9739902,2.504783837,90.00000001 +279.52,50.43283629,-2.560655064,48.5021,1.80E-11,9.999032684,0.1646875,6.94920078,2.434502484,90.00000001 +279.53,50.43283629,-2.560653657,48.5008,1.95E-11,9.999476748,0.1,6.922960058,2.362098152,90.00000001 +279.54,50.43283629,-2.560652249,48.5001,1.66E-11,10.00014285,0.0353125,6.895273649,2.287634093,90.00000001 +279.55,50.43283629,-2.560650842,48.5001,6.87E-12,10.00036488,-0.0284375,6.866147225,2.211175167,90.00000001 +279.56,50.43283629,-2.560649434,48.5007,-5.47E-12,10.00036488,-0.091875,6.835586859,2.132788066,90.00000001 +279.57,50.43283629,-2.560648027,48.5019,-6.25E-12,10.00014285,-0.156875,6.803598969,2.052541144,90.00000001 +279.58,50.43283629,-2.560646619,48.5038,3.28E-12,9.999476753,-0.223125,6.770190259,1.970504417,90.00000001 +279.59,50.43283629,-2.560645212,48.5064,4.69E-12,9.99903269,-0.288125,6.735367717,1.886749332,90.00000001 +279.6,50.43283629,-2.560643805,48.5096,-5.47E-12,9.999476761,-0.3515625,6.699138507,1.801348998,90.00000001 +279.61,50.43283629,-2.560642397,48.5134,-1.17E-11,10.00014287,-0.415,6.661510306,1.714377844,90.00000001 +279.62,50.43283629,-2.56064099,48.5179,-4.53E-12,10.00036491,-0.4784375,6.622490906,1.625911728,90.00000001 +279.63,50.43283629,-2.560639582,48.523,9.53E-12,10.00036491,-0.5415625,6.582088558,1.536027771,90.00000001 +279.64,50.43283629,-2.560638175,48.5287,1.66E-11,10.00014289,-0.605,6.54031157,1.44480441,90.00000001 +279.65,50.43283629,-2.560636767,48.5351,9.37E-12,9.999476801,-0.6684375,6.497168707,1.352321172,90.00000001 +279.66,50.43283629,-2.56063536,48.5421,-5.31E-12,9.999032746,-0.7315625,6.452669023,1.258658616,90.00000001 +279.67,50.43283629,-2.560633953,48.5497,-1.33E-11,9.999476824,-0.795,6.406821743,1.163898558,90.00000001 +279.68,50.43283629,-2.560632545,48.558,-9.22E-12,10.00014294,-0.858125,6.359636548,1.068123563,90.00000001 +279.69,50.43283629,-2.560631138,48.5669,-2.34E-12,10.00036498,-0.9196875,6.311123181,0.971417111,90.00000001 +279.7,50.43283629,-2.56062973,48.5764,-2.50E-16,10.000365,-0.98,6.261291781,0.873863598,90.00000001 +279.71,50.43283629,-2.560628323,48.5865,-1.88E-22,10.00014298,-1.04,6.210152834,0.775548051,90.00000001 +279.72,50.43283629,-2.560626915,48.5972,2.50E-16,9.999476898,-1.1,6.157716997,0.676556185,90.00000001 +279.73,50.43283629,-2.560625508,48.6085,-1.56E-13,9.99903285,-1.16,6.103995156,0.576974401,90.00000001 +279.74,50.43283629,-2.560624101,48.6204,-7.81E-13,9.999476935,-1.22,6.048998599,0.476889446,90.00000001 +279.75,50.43283629,-2.560622693,48.6329,7.81E-13,10.00014305,-1.2796875,5.992738784,0.376388695,90.00000001 +279.76,50.43283629,-2.560621286,48.646,7.97E-12,10.00036511,-1.338125,5.935227458,0.275559697,90.00000001 +279.77,50.43283629,-2.560619878,48.6597,1.41E-11,10.00036513,-1.395,5.876476652,0.1744904,90.00000001 +279.78,50.43283629,-2.560618471,48.6739,1.09E-11,10.00036515,-1.451875,5.816498571,0.073268926,90.00000001 +279.79,50.43283629,-2.560617063,48.6887,9.38E-12,10.00036517,-1.5096875,5.755305819,-0.028016433,90.00000001 +279.8,50.43283629,-2.560615656,48.7041,2.36E-11,10.0003652,-1.5665625,5.692911173,-0.129277327,90.00000001 +279.81,50.43283629,-2.560614248,48.7201,4.22E-11,10.00036522,-1.6215625,5.629327583,-0.23042552,90.00000001 +279.82,50.43283629,-2.560612841,48.7365,4.16E-11,10.00036525,-1.6765625,5.564568398,-0.331372776,90.00000001 +279.83,50.43283629,-2.560611433,48.7536,2.20E-11,10.00036528,-1.7315625,5.49864714,-0.432031033,90.00000001 +279.84,50.43283629,-2.560610026,48.7712,5.62E-12,10.00014327,-1.784375,5.43157756,-0.53231257,90.00000001 +279.85,50.43283629,-2.560608618,48.7893,1.56E-12,9.999477199,-1.835,5.363373638,-0.632129954,90.00000001 +279.86,50.43283629,-2.560607211,48.8079,3.91E-12,9.999033162,-1.8853125,5.294049698,-0.731396095,90.00000001 +279.87,50.43283629,-2.560605804,48.827,1.25E-11,9.999477258,-1.9365625,5.223620122,-0.83002442,90.00000001 +279.88,50.43283629,-2.560604396,48.8466,2.36E-11,10.00014339,-1.988125,5.152099634,-0.927928984,90.00000001 +279.89,50.43283629,-2.560602989,48.8668,2.34E-11,10.00036545,-2.038125,5.079503246,-1.025024418,90.00000001 +279.9,50.43283629,-2.560601581,48.8874,9.53E-12,10.00036548,-2.08625,5.005846026,-1.121225922,90.00000001 +279.91,50.43283629,-2.560600174,48.9085,-6.25E-12,10.00036552,-2.1334375,4.931143445,-1.216449789,90.00000001 +279.92,50.43283629,-2.560598766,48.9301,-1.48E-11,10.00036555,-2.1796875,4.855411029,-1.310612824,90.00000001 +279.93,50.43283629,-2.560597359,48.9521,-1.48E-11,10.00036559,-2.2246875,4.778664651,-1.403633038,90.00000001 +279.94,50.43283629,-2.560595951,48.9746,-6.09E-12,10.00036562,-2.2684375,4.700920294,-1.495429242,90.00000001 +279.95,50.43283629,-2.560594544,48.9975,7.97E-12,10.00036566,-2.3115625,4.622194174,-1.585921394,90.00000001 +279.96,50.43283629,-2.560593136,49.0208,1.56E-11,10.00036569,-2.355,4.542502792,-1.675030598,90.00000001 +279.97,50.43283629,-2.560591729,49.0446,1.31E-11,10.0001437,-2.3978125,4.461862821,-1.76267916,90.00000001 +279.98,50.43283629,-2.560590321,49.0688,1.41E-11,9.999477635,-2.438125,4.380290992,-1.848790649,90.00000001 +279.99,50.43283629,-2.560588914,49.0934,2.42E-11,9.999033608,-2.4765625,4.297804378,-1.933289949,90.00000001 +280,50.43283629,-2.560587507,49.1183,3.05E-11,9.999477714,-2.515,4.214420283,-2.016103435,90.00000001 +280.01,50.43283629,-2.560586099,49.1437,2.56E-11,10.00014385,-2.553125,4.13015601,-2.0971588,90.00000001 +280.02,50.43283629,-2.560584692,49.1694,1.64E-11,10.00036593,-2.589375,4.045029207,-2.176385399,90.00000001 +280.03,50.43283629,-2.560583284,49.1955,5.47E-12,10.00036597,-2.6234375,3.959057692,-2.253714189,90.00000001 +280.04,50.43283629,-2.560581877,49.2219,-7.03E-12,10.00036601,-2.6565625,3.872259341,-2.329077734,90.00000001 +280.05,50.43283629,-2.560580469,49.2486,-1.27E-11,10.00036605,-2.69,3.784652318,-2.402410259,90.00000001 +280.06,50.43283629,-2.560579062,49.2757,-7.97E-12,10.00036609,-2.723125,3.696254957,-2.47364782,90.00000001 +280.07,50.43283629,-2.560577654,49.3031,1.94E-16,10.00036613,-2.754375,3.60708565,-2.542728368,90.00000001 +280.08,50.43283629,-2.560576247,49.3308,7.97E-12,10.00036618,-2.783125,3.517163018,-2.609591568,90.00000001 +280.09,50.43283629,-2.560574839,49.3588,1.25E-11,10.00036622,-2.81,3.426505912,-2.67417921,90.00000001 +280.1,50.43283629,-2.560573432,49.387,6.25E-12,10.00014423,-2.8365625,3.335133238,-2.736434913,90.00000001 +280.11,50.43283629,-2.560572024,49.4155,-4.84E-12,9.999478178,-2.863125,3.24306402,-2.796304419,90.00000001 +280.12,50.43283629,-2.560570617,49.4443,-4.84E-12,9.999034157,-2.888125,3.150317565,-2.853735474,90.00000001 +280.13,50.43283629,-2.56056921,49.4733,8.59E-12,9.999478269,-2.91125,3.056913184,-2.908678058,90.00000001 +280.14,50.43283629,-2.560567802,49.5025,2.42E-11,10.00014441,-2.9334375,2.962870412,-2.961084216,90.00000001 +280.15,50.43283629,-2.560566395,49.532,3.36E-11,10.00036649,-2.9546875,2.868208903,-3.010908282,90.00000001 +280.16,50.43283629,-2.560564987,49.5616,3.44E-11,10.00036654,-2.9746875,2.772948425,-3.058106769,90.00000001 +280.17,50.43283629,-2.56056358,49.5915,2.80E-11,10.00036659,-2.993125,2.6771088,-3.102638539,90.00000001 +280.18,50.43283629,-2.560562172,49.6215,2.11E-11,10.00036663,-3.0096875,2.580710084,-3.144464802,90.00000001 +280.19,50.43283629,-2.560560765,49.6517,2.11E-11,10.00036668,-3.0246875,2.4837725,-3.183549003,90.00000001 +280.2,50.43283629,-2.560559357,49.682,2.81E-11,10.00036673,-3.038125,2.386316161,-3.219857109,90.00000001 +280.21,50.43283629,-2.56055795,49.7125,3.28E-11,10.00014474,-3.05,2.288361463,-3.253357493,90.00000001 +280.22,50.43283629,-2.560556542,49.743,2.58E-11,9.999478691,-3.0615625,2.18992886,-3.284020877,90.00000001 +280.23,50.43283629,-2.560555135,49.7737,1.41E-11,9.999034673,-3.073125,2.091038923,-3.311820502,90.00000001 +280.24,50.43283629,-2.560553728,49.8045,1.41E-11,9.999478787,-3.083125,1.991712335,-3.336732192,90.00000001 +280.25,50.43283629,-2.56055232,49.8354,2.81E-11,10.00014493,-3.09125,1.891969779,-3.358734229,90.00000001 +280.26,50.43283629,-2.560550913,49.8663,4.22E-11,10.00036702,-3.098125,1.791832112,-3.377807421,90.00000001 +280.27,50.43283629,-2.560549505,49.8974,4.22E-11,10.00036706,-3.103125,1.691320246,-3.393935037,90.00000001 +280.28,50.43283629,-2.560548098,49.9284,2.81E-11,10.00014508,-3.10625,1.590455152,-3.407103154,90.00000001 +280.29,50.43283629,-2.56054669,49.9595,1.16E-11,9.999479029,-3.1084375,1.489257913,-3.417300199,90.00000001 +280.3,50.43283629,-2.560545283,49.9906,-7.81E-13,9.999035012,-3.109375,1.387749674,-3.42451729,90.00000001 +280.31,50.43283629,-2.560543876,50.0217,-1.33E-11,9.999479127,-3.1084375,1.285951632,-3.428748182,90.00000001 +280.32,50.43283629,-2.560542468,50.0528,-2.73E-11,10.00014527,-3.1065625,1.183885045,-3.429989151,90.00000001 +280.33,50.43283629,-2.560541061,50.0838,-3.12E-11,10.00036736,-3.1046875,1.081571169,-3.428239109,90.00000001 +280.34,50.43283629,-2.560539653,50.1149,-1.89E-11,10.0003674,-3.10125,0.979031434,-3.423499602,90.00000001 +280.35,50.43283629,-2.560538246,50.1459,-7.03E-12,10.00014542,-3.0946875,0.876287267,-3.415774756,90.00000001 +280.36,50.43283629,-2.560536838,50.1768,-1.17E-11,9.99947937,-3.0865625,0.773360097,-3.405071332,90.00000001 +280.37,50.43283629,-2.560535431,50.2076,-2.58E-11,9.999035351,-3.0784375,0.670271411,-3.391398553,90.00000001 +280.38,50.43283629,-2.560534024,50.2384,-3.52E-11,9.999479465,-3.0696875,0.567042751,-3.37476851,90.00000001 +280.39,50.43283629,-2.560532616,50.269,-3.28E-11,10.00014561,-3.059375,0.46369566,-3.355195585,90.00000001 +280.4,50.43283629,-2.560531209,50.2996,-1.41E-11,10.00036769,-3.046875,0.36025174,-3.33269685,90.00000001 +280.41,50.43283629,-2.560529801,50.33,1.64E-11,10.00036774,-3.0328125,0.25673259,-3.307291958,90.00000001 +280.42,50.43283629,-2.560528394,50.3602,3.97E-11,10.00014576,-3.0184375,0.153159869,-3.279003084,90.00000001 +280.43,50.43283629,-2.560526986,50.3904,4.37E-11,9.999479703,-3.0028125,0.049555062,-3.247854864,90.00000001 +280.44,50.43283629,-2.560525579,50.4203,3.83E-11,9.999035684,-2.9846875,-0.05406,-3.213874456,90.00000001 +280.45,50.43283629,-2.560524172,50.4501,3.59E-11,9.999479797,-2.965,-0.157663833,-3.177091539,90.00000001 +280.46,50.43283629,-2.560522764,50.4796,3.67E-11,10.00014594,-2.945,-0.261234721,-3.137538086,90.00000001 +280.47,50.43283629,-2.560521357,50.509,3.97E-11,10.00036802,-2.9246875,-0.364751063,-3.095248701,90.00000001 +280.48,50.43283629,-2.560519949,50.5381,4.45E-11,10.00036807,-2.9028125,-0.468191202,-3.050260227,90.00000001 +280.49,50.43283629,-2.560518542,50.5671,4.00E-11,10.00014608,-2.8784375,-0.571533594,-3.002611853,90.00000001 +280.5,50.43283629,-2.560517134,50.5957,1.72E-11,9.999480025,-2.8528125,-0.674756582,-2.952345177,90.00000001 +280.51,50.43283629,-2.560515727,50.6241,-1.25E-11,9.999036003,-2.826875,-0.777838736,-2.899503973,90.00000001 +280.52,50.43283629,-2.56051432,50.6523,-2.91E-11,9.999480113,-2.7996875,-0.8807584,-2.844134363,90.00000001 +280.53,50.43283629,-2.560512912,50.6801,-2.34E-11,10.00014626,-2.77125,-0.983494145,-2.786284648,90.00000001 +280.54,50.43283629,-2.560511505,50.7077,-1.41E-12,10.00036833,-2.741875,-1.086024484,-2.726005248,90.00000001 +280.55,50.43283629,-2.560510097,50.735,2.44E-11,10.00036837,-2.7109375,-1.188327989,-2.663348761,90.00000001 +280.56,50.43283629,-2.56050869,50.7619,4.45E-11,10.00036842,-2.6784375,-1.290383346,-2.598369732,90.00000001 +280.57,50.43283629,-2.560507282,50.7886,5.31E-11,10.00036846,-2.645,-1.392169241,-2.531124941,90.00000001 +280.58,50.43283629,-2.560505875,50.8148,4.45E-11,10.0003685,-2.61125,-1.493664417,-2.461672945,90.00000001 +280.59,50.43283629,-2.560504467,50.8408,2.36E-11,10.00036854,-2.5765625,-1.594847675,-2.390074306,90.00000001 +280.6,50.43283629,-2.56050306,50.8664,7.19E-12,10.00014655,-2.539375,-1.695697816,-2.316391532,90.00000001 +280.61,50.43283629,-2.560501652,50.8916,2.50E-12,9.999480487,-2.5,-1.796193868,-2.240688796,90.00000001 +280.62,50.43283629,-2.560500245,50.9164,2.34E-12,9.99903646,-2.46,-1.896314748,-2.163032159,90.00000001 +280.63,50.43283629,-2.560498838,50.9408,1.56E-12,9.999480565,-2.42,-1.996039656,-2.083489345,90.00000001 +280.64,50.43283629,-2.56049743,50.9648,-2.78E-17,10.0001467,-2.38,-2.095347738,-2.002129682,90.00000001 +280.65,50.43283629,-2.560496023,50.9884,9.37E-13,10.00036877,-2.3396875,-2.194218194,-1.919024159,90.00000001 +280.66,50.43283629,-2.560494615,51.0116,5.47E-12,10.00036881,-2.2978125,-2.292630457,-1.834245198,90.00000001 +280.67,50.43283629,-2.560493208,51.0344,3.91E-12,10.00036884,-2.253125,-2.390563898,-1.747866711,90.00000001 +280.68,50.43283629,-2.5604918,51.0567,-7.19E-12,10.00036888,-2.2065625,-2.487998064,-1.659964099,90.00000001 +280.69,50.43283629,-2.560490393,51.0785,-1.41E-11,10.00036891,-2.16,-2.584912729,-1.570613967,90.00000001 +280.7,50.43283629,-2.560488985,51.0999,-7.03E-12,10.00036895,-2.1134375,-2.681287496,-1.479894236,90.00000001 +280.71,50.43283629,-2.560487578,51.1208,9.38E-12,10.00036898,-2.06625,-2.777102369,-1.387884032,90.00000001 +280.72,50.43283629,-2.56048617,51.1412,2.34E-11,10.00036901,-2.018125,-2.872337236,-1.294663513,90.00000001 +280.73,50.43283629,-2.560484763,51.1612,2.34E-11,10.00014701,-1.968125,-2.966972274,-1.200314094,90.00000001 +280.74,50.43283629,-2.560483355,51.1806,1.17E-11,9.999480939,-1.9165625,-3.060987658,-1.104917939,90.00000001 +280.75,50.43283629,-2.560481948,51.1995,2.50E-12,9.999036903,-1.8653125,-3.154363851,-1.008558298,90.00000001 +280.76,50.43283629,-2.560480541,51.2179,-1.56E-12,9.999480998,-1.8146875,-3.247081256,-0.911319224,90.00000001 +280.77,50.43283629,-2.560479133,51.2358,-7.66E-12,10.00014713,-1.763125,-3.339120566,-0.813285401,90.00000001 +280.78,50.43283629,-2.560477726,51.2532,-1.41E-11,10.00036919,-1.7096875,-3.430462529,-0.71454237,90.00000001 +280.79,50.43283629,-2.560476318,51.27,-1.64E-11,10.00036921,-1.655,-3.521088123,-0.615176305,90.00000001 +280.8,50.43283629,-2.560474911,51.2863,-1.72E-11,10.00036924,-1.6,-3.610978383,-0.515273779,90.00000001 +280.81,50.43283629,-2.560473503,51.302,-1.62E-11,10.00036926,-1.5446875,-3.700114458,-0.414921883,90.00000001 +280.82,50.43283629,-2.560472096,51.3172,-1.00E-11,10.00036928,-1.488125,-3.7884779,-0.314208221,90.00000001 +280.83,50.43283629,-2.560470688,51.3318,-4.53E-12,10.00036931,-1.43,-3.876050145,-0.213220571,90.00000001 +280.84,50.43283629,-2.560469281,51.3458,-7.97E-12,10.00036933,-1.371875,-3.962812915,-0.112046939,90.00000001 +280.85,50.43283629,-2.560467873,51.3592,-1.02E-11,10.00036935,-1.3146875,-4.048748047,-0.010775617,90.00000001 +280.86,50.43283629,-2.560466466,51.3721,3.12E-12,10.00014734,-1.2565625,-4.133837722,0.090505044,90.00000001 +280.87,50.43283629,-2.560465058,51.3844,2.12E-11,9.999481258,-1.1965625,-4.218064065,0.191706865,90.00000001 +280.88,50.43283629,-2.560463651,51.396,2.34E-11,9.99903721,-1.136875,-4.301409543,0.292741441,90.00000001 +280.89,50.43283629,-2.560462244,51.4071,1.41E-11,9.999481294,-1.078125,-4.383856737,0.393520821,90.00000001 +280.9,50.43283629,-2.560460836,51.4176,1.17E-11,10.00014741,-1.0178125,-4.465388402,0.493956999,90.00000001 +280.91,50.43283629,-2.560459429,51.4275,1.41E-11,10.00036946,-0.955,-4.545987521,0.593962428,90.00000001 +280.92,50.43283629,-2.560458021,51.4367,9.37E-12,10.00036947,-0.891875,-4.625637249,0.693449903,90.00000001 +280.93,50.43283629,-2.560456614,51.4453,2.50E-12,10.00036949,-0.8303125,-4.704321027,0.792332735,90.00000001 +280.94,50.43283629,-2.560455206,51.4533,-1.56E-12,10.0003695,-0.7696875,-4.782022298,0.890524638,90.00000001 +280.95,50.43283629,-2.560453799,51.4607,-7.66E-12,10.00036951,-0.708125,-4.85872496,0.987939953,90.00000001 +280.96,50.43283629,-2.560452391,51.4675,-1.17E-11,10.00036952,-0.645,-4.934412914,1.08449377,90.00000001 +280.97,50.43283629,-2.560450984,51.4736,-4.53E-12,10.00036953,-0.5815625,-5.009070403,1.180101919,90.00000001 +280.98,50.43283629,-2.560449576,51.4791,7.19E-12,10.00036954,-0.518125,-5.082681786,1.274680979,90.00000001 +280.99,50.43283629,-2.560448169,51.484,4.84E-12,10.00014751,-0.4534375,-5.155231708,1.368148501,90.00000001 +281,50.43283629,-2.560446761,51.4882,-1.41E-11,9.99948142,-0.3884375,-5.226705041,1.460422953,90.00000001 +281.01,50.43283629,-2.560445354,51.4917,-2.64E-11,9.99903736,-0.325,-5.29708689,1.551423949,90.00000001 +281.02,50.43283629,-2.560443947,51.4947,-1.56E-11,9.999481431,-0.2615625,-5.366362415,1.641072019,90.00000001 +281.03,50.43283629,-2.560442539,51.497,2.50E-12,10.00014753,-0.1965625,-5.434517292,1.729289128,90.00000001 +281.04,50.43283629,-2.560441132,51.4986,4.69E-12,10.00036957,-0.131875,-5.501537254,1.815998211,90.00000001 +281.05,50.43283629,-2.560439724,51.4996,-7.03E-12,10.00036957,-0.0684375,-5.567408321,1.901123754,90.00000001 +281.06,50.43283629,-2.560438317,51.5,-1.64E-11,10.00014754,-0.0046875,-5.632116627,1.984591444,90.00000001 +281.07,50.43283629,-2.560436909,51.4997,-1.87E-11,9.999481439,0.06,-5.695648766,2.066328571,90.00000001 +281.08,50.43283629,-2.560435502,51.4988,-1.87E-11,9.999037371,0.125,-5.757991444,2.146263804,90.00000001 +281.09,50.43283629,-2.560434095,51.4972,-1.86E-11,9.999481434,0.19,-5.819131656,2.22432747,90.00000001 +281.1,50.43283629,-2.560432687,51.495,-1.56E-11,10.00014753,0.2546875,-5.879056624,2.300451502,90.00000001 +281.11,50.43283629,-2.56043128,51.4921,-5.31E-12,10.00036956,0.3184375,-5.937753801,2.374569552,90.00000001 +281.12,50.43283629,-2.560429872,51.4886,9.37E-12,10.00036955,0.3815625,-5.995210983,2.446616875,90.00000001 +281.13,50.43283629,-2.560428465,51.4845,1.66E-11,10.00014751,0.445,-6.05141608,2.516530732,90.00000001 +281.14,50.43283629,-2.560427057,51.4797,9.53E-12,9.999481407,0.5084375,-6.106357461,2.584250161,90.00000001 +281.15,50.43283629,-2.56042565,51.4743,-4.53E-12,9.999037333,0.5715625,-6.16002361,2.649716032,90.00000001 +281.16,50.43283629,-2.560424243,51.4683,-1.41E-11,9.99948139,0.6353125,-6.212403355,2.712871336,90.00000001 +281.17,50.43283629,-2.560422835,51.4616,-1.94E-11,10.00014748,0.6996875,-6.263485636,2.773661012,90.00000001 +281.18,50.43283629,-2.560421428,51.4543,-2.73E-11,10.0003695,0.763125,-6.313259912,2.832031947,90.00000001 +281.19,50.43283629,-2.56042002,51.4463,-3.27E-11,10.00036949,0.825,-6.361715755,2.887933377,90.00000001 +281.2,50.43283629,-2.560418613,51.4378,-2.58E-11,10.00014744,0.8865625,-6.408843023,2.941316427,90.00000001 +281.21,50.43283629,-2.560417205,51.4286,-1.17E-11,9.999481327,0.9484375,-6.454631862,2.992134632,90.00000001 +281.22,50.43283629,-2.560415798,51.4188,-2.34E-12,9.999037245,1.0096875,-6.499072761,3.040343645,90.00000001 +281.23,50.43283629,-2.560414391,51.4084,-2.78E-16,9.999481296,1.07,-6.542156437,3.085901468,90.00000001 +281.24,50.43283629,-2.560412983,51.3974,-2.50E-16,10.00014738,1.13,-6.58387378,3.128768279,90.00000001 +281.25,50.43283629,-2.560411576,51.3858,-2.19E-12,10.00036939,1.1896875,-6.624216254,3.16890678,90.00000001 +281.26,50.43283629,-2.560410168,51.3736,-1.09E-11,10.00036937,1.2484375,-6.663175322,3.206281963,90.00000001 +281.27,50.43283629,-2.560408761,51.3608,-2.42E-11,10.00014732,1.3065625,-6.700742846,3.240861226,90.00000001 +281.28,50.43283629,-2.560407353,51.3475,-3.14E-11,9.999481201,1.365,-6.736911036,3.272614375,90.00000001 +281.29,50.43283629,-2.560405946,51.3335,-2.58E-11,9.999037112,1.4234375,-6.771672271,3.301513794,90.00000001 +281.3,50.43283629,-2.560404539,51.319,-1.09E-11,9.999481155,1.48125,-6.805019332,3.327534214,90.00000001 +281.31,50.43283629,-2.560403131,51.3039,2.50E-12,10.00014723,1.538125,-6.836945285,3.350653003,90.00000001 +281.32,50.43283629,-2.560401724,51.2882,3.12E-12,10.00036924,1.593125,-6.867443427,3.370849937,90.00000001 +281.33,50.43283629,-2.560400316,51.272,-4.69E-12,10.00036921,1.646875,-6.896507399,3.388107484,90.00000001 +281.34,50.43283629,-2.560398909,51.2553,-9.38E-13,10.00036919,1.7015625,-6.924131069,3.402410516,90.00000001 +281.35,50.43283629,-2.560397501,51.238,1.80E-11,10.00036916,1.7565625,-6.950308766,3.4137466,90.00000001 +281.36,50.43283629,-2.560396094,51.2201,3.12E-11,10.0001471,1.8096875,-6.975034989,3.422105882,90.00000001 +281.37,50.43283629,-2.560394686,51.2018,2.34E-11,9.999480973,1.86125,-6.998304524,3.427480971,90.00000001 +281.38,50.43283629,-2.560393279,51.1829,-7.81E-13,9.999036877,1.911875,-7.020112615,3.429867283,90.00000001 +281.39,50.43283629,-2.560391872,51.1635,-2.25E-11,9.999480912,1.9615625,-7.040454623,3.429262698,90.00000001 +281.4,50.43283629,-2.560390464,51.1437,-2.19E-11,10.00014698,2.0115625,-7.059326305,3.425667789,90.00000001 +281.41,50.43283629,-2.560389057,51.1233,-1.56E-12,10.00036898,2.0615625,-7.07672371,3.419085593,90.00000001 +281.42,50.43283629,-2.560387649,51.1024,1.55E-11,10.00036895,2.109375,-7.092643285,3.409521896,90.00000001 +281.43,50.43283629,-2.560386242,51.0811,1.95E-11,10.00036892,2.155,-7.107081593,3.396985064,90.00000001 +281.44,50.43283629,-2.560384834,51.0593,1.89E-11,10.00036888,2.2,-7.12003571,3.381485982,90.00000001 +281.45,50.43283629,-2.560383427,51.0371,1.89E-11,10.00036885,2.245,-7.131502945,3.363038231,90.00000001 +281.46,50.43283629,-2.560382019,51.0144,1.95E-11,10.00036881,2.29,-7.141480775,3.341657852,90.00000001 +281.47,50.43283629,-2.560380612,50.9913,1.56E-11,10.00036878,2.334375,-7.149967254,3.317363525,90.00000001 +281.48,50.43283629,-2.560379204,50.9677,-9.37E-13,10.00036874,2.3765625,-7.156960548,3.290176391,90.00000001 +281.49,50.43283629,-2.560377797,50.9437,-2.11E-11,10.00014667,2.4165625,-7.162459167,3.260120114,90.00000001 +281.5,50.43283629,-2.560376389,50.9194,-2.27E-11,9.999480531,2.4565625,-7.166462022,3.227221049,90.00000001 +281.51,50.43283629,-2.560374982,50.8946,-4.69E-12,9.999036426,2.4965625,-7.168968254,3.19150773,90.00000001 +281.52,50.43283629,-2.560373575,50.8694,1.16E-11,9.999480452,2.534375,-7.169977347,3.153011441,90.00000001 +281.53,50.43283629,-2.560372167,50.8439,1.64E-11,10.00014651,2.57,-7.169489072,3.111765642,90.00000001 +281.54,50.43283629,-2.56037076,50.818,1.72E-11,10.0003685,2.605,-7.167503545,3.067806314,90.00000001 +281.55,50.43283629,-2.560369352,50.7918,1.87E-11,10.00036846,2.64,-7.164021164,3.021171847,90.00000001 +281.56,50.43283629,-2.560367945,50.7652,2.25E-11,10.00036842,2.6746875,-7.159042677,2.971902862,90.00000001 +281.57,50.43283629,-2.560366537,50.7383,2.72E-11,10.00036838,2.7078125,-7.152569113,2.920042333,90.00000001 +281.58,50.43283629,-2.56036513,50.711,2.34E-11,10.00036834,2.738125,-7.144601848,2.865635464,90.00000001 +281.59,50.43283629,-2.560363722,50.6835,1.03E-11,10.00036829,2.7665625,-7.135142544,2.808729754,90.00000001 +281.6,50.43283629,-2.560362315,50.6557,7.81E-13,10.00036825,2.7953125,-7.124193092,2.749374764,90.00000001 +281.61,50.43283629,-2.560360907,50.6276,-5.47E-12,10.00036821,2.824375,-7.111755897,2.687622289,90.00000001 +281.62,50.43283629,-2.5603595,50.5992,-2.11E-11,10.00014613,2.8515625,-7.097833481,2.623526131,90.00000001 +281.63,50.43283629,-2.560358092,50.5705,-4.14E-11,9.999479986,2.87625,-7.082428766,2.557142267,90.00000001 +281.64,50.43283629,-2.560356685,50.5417,-4.77E-11,9.999035874,2.8996875,-7.06554496,2.488528508,90.00000001 +281.65,50.43283629,-2.560355278,50.5125,-3.13E-11,9.999479894,2.921875,-7.047185616,2.417744787,90.00000001 +281.66,50.43283629,-2.56035387,50.4832,-1.56E-12,10.00014595,2.9428125,-7.027354573,2.344852695,90.00000001 +281.67,50.43283629,-2.560352463,50.4537,2.12E-11,10.00036793,2.9634375,-7.006055955,2.269915831,90.00000001 +281.68,50.43283629,-2.560351055,50.4239,2.58E-11,10.00036789,2.9828125,-6.983294233,2.192999628,90.00000001 +281.69,50.43283629,-2.560349648,50.394,2.11E-11,10.00036784,2.9996875,-6.959074104,2.114171063,90.00000001 +281.7,50.43283629,-2.56034824,50.3639,1.64E-11,10.00036779,3.0153125,-6.933400667,2.033498892,90.00000001 +281.71,50.43283629,-2.560346833,50.3337,4.69E-12,10.00036775,3.03125,-6.906279309,1.951053474,90.00000001 +281.72,50.43283629,-2.560345425,50.3033,-1.41E-11,10.0003677,3.04625,-6.877715586,1.866906772,90.00000001 +281.73,50.43283629,-2.560344018,50.2727,-1.87E-11,10.00036765,3.058125,-6.847715631,1.781132068,90.00000001 +281.74,50.43283629,-2.56034261,50.2421,4.72E-16,10.0003676,3.068125,-6.816285573,1.69380419,90.00000001 +281.75,50.43283629,-2.560341203,50.2114,2.11E-11,10.00014552,3.0784375,-6.783432001,1.604999284,90.00000001 +281.76,50.43283629,-2.560339795,50.1805,2.58E-11,9.999479376,3.0878125,-6.749161848,1.514794757,90.00000001 +281.77,50.43283629,-2.560338388,50.1496,2.11E-11,9.999035261,3.0946875,-6.713482162,1.423269333,90.00000001 +281.78,50.43283629,-2.560336981,50.1186,1.88E-11,9.999479278,3.1,-6.676400505,1.330502825,90.00000001 +281.79,50.43283629,-2.560335573,50.0876,1.64E-11,10.00014533,3.1046875,-6.637924556,1.236576077,90.00000001 +281.8,50.43283629,-2.560334166,50.0565,9.38E-12,10.00036731,3.108125,-6.598062335,1.141571023,90.00000001 +281.81,50.43283629,-2.560332758,50.0254,2.78E-16,10.00036726,3.109375,-6.556822208,1.045570512,90.00000001 +281.82,50.43283629,-2.560331351,49.9943,-1.17E-11,10.00036722,3.1084375,-6.514212769,0.948658254,90.00000001 +281.83,50.43283629,-2.560329943,49.9632,-2.58E-11,10.00036717,3.1065625,-6.470242957,0.850918701,90.00000001 +281.84,50.43283629,-2.560328536,49.9322,-3.28E-11,10.00014509,3.105,-6.424921881,0.752437168,90.00000001 +281.85,50.43283629,-2.560327128,49.9011,-3.05E-11,9.999478939,3.1028125,-6.378259052,0.653299541,90.00000001 +281.86,50.43283629,-2.560325721,49.8701,-3.05E-11,9.999034824,3.0978125,-6.330264154,0.553592165,90.00000001 +281.87,50.43283629,-2.560324314,49.8391,-3.05E-11,9.999478841,3.0903125,-6.280947327,0.453402072,90.00000001 +281.88,50.43283629,-2.560322906,49.8083,-1.17E-11,10.00014489,3.0828125,-6.230318771,0.352816581,90.00000001 +281.89,50.43283629,-2.560321499,49.7775,2.34E-11,10.00036688,3.075,-6.178389142,0.251923469,90.00000001 +281.9,50.43283629,-2.560320091,49.7467,4.45E-11,10.00036683,3.0646875,-6.125169213,0.150810628,90.00000001 +281.91,50.43283629,-2.560318684,49.7162,3.28E-11,10.00014475,3.053125,-6.070670097,0.04956635,90.00000001 +281.92,50.43283629,-2.560317276,49.6857,7.03E-12,9.999478601,3.0415625,-6.014903198,-0.051721244,90.00000001 +281.93,50.43283629,-2.560315869,49.6553,-2.34E-12,9.999034488,3.0278125,-5.957880147,-0.152963688,90.00000001 +281.94,50.43283629,-2.560314462,49.6251,9.38E-12,9.999478507,3.01125,-5.899612917,-0.254072748,90.00000001 +281.95,50.43283629,-2.560313054,49.5951,2.58E-11,10.00014456,2.9934375,-5.840113599,-0.354960246,90.00000001 +281.96,50.43283629,-2.560311647,49.5652,3.28E-11,10.00036654,2.975,-5.779394684,-0.455538174,90.00000001 +281.97,50.43283629,-2.560310239,49.5356,2.34E-11,10.0003665,2.95625,-5.717468775,-0.555718927,90.00000001 +281.98,50.43283629,-2.560308832,49.5061,2.34E-12,10.00014442,2.9365625,-5.654348879,-0.655415074,90.00000001 +281.99,50.43283629,-2.560307424,49.4768,-1.42E-11,9.999478275,2.914375,-5.590048118,-0.754539694,90.00000001 +282,50.43283629,-2.560306017,49.4478,-1.95E-11,9.999034163,2.89,-5.524579955,-0.85300633,90.00000001 +282.01,50.43283629,-2.56030461,49.419,-2.03E-11,9.999478184,2.865,-5.457958027,-0.950729095,90.00000001 +282.02,50.43283629,-2.560303202,49.3905,-2.03E-11,10.00014424,2.84,-5.390196314,-1.047622847,90.00000001 +282.03,50.43283629,-2.560301795,49.3622,-2.20E-11,10.00036623,2.8146875,-5.32130891,-1.143603075,90.00000001 +282.04,50.43283629,-2.560300387,49.3342,-2.67E-11,10.00036618,2.7878125,-5.251310255,-1.238586071,90.00000001 +282.05,50.43283629,-2.56029898,49.3064,-2.50E-11,10.00014411,2.758125,-5.180214902,-1.332488983,90.00000001 +282.06,50.43283629,-2.560297572,49.279,-1.31E-11,9.999477964,2.7265625,-5.10803769,-1.425229937,90.00000001 +282.07,50.43283629,-2.560296165,49.2519,-4.69E-12,9.999033856,2.695,-5.034793802,-1.516728031,90.00000001 +282.08,50.43283629,-2.560294758,49.2251,-5.47E-12,9.999477881,2.6628125,-4.960498422,-1.606903567,90.00000001 +282.09,50.43283629,-2.56029335,49.1986,-2.34E-12,10.00014394,2.628125,-4.885167077,-1.695677877,90.00000001 +282.1,50.43283629,-2.560291943,49.1725,9.53E-12,10.00036593,2.5915625,-4.80881558,-1.782973497,90.00000001 +282.11,50.43283629,-2.560290535,49.1468,1.89E-11,10.00036589,2.5553125,-4.731459804,-1.868714339,90.00000001 +282.12,50.43283629,-2.560289128,49.1214,2.36E-11,10.00036585,2.5196875,-4.653115904,-1.952825632,90.00000001 +282.13,50.43283629,-2.56028772,49.0964,2.81E-11,10.00036581,2.4828125,-4.573800325,-2.035234037,90.00000001 +282.14,50.43283629,-2.560286313,49.0717,2.50E-11,10.00014374,2.443125,-4.493529511,-2.115867706,90.00000001 +282.15,50.43283629,-2.560284905,49.0475,1.17E-11,9.999477603,2.4015625,-4.412320249,-2.194656278,90.00000001 +282.16,50.43283629,-2.560283498,49.0237,3.28E-12,9.9990335,2.36,-4.330189614,-2.271531057,90.00000001 +282.17,50.43283629,-2.560282091,49.0003,7.81E-12,9.999477529,2.318125,-4.247154622,-2.346425063,90.00000001 +282.18,50.43283629,-2.560280683,48.9773,1.56E-11,10.00014359,2.2746875,-4.163232692,-2.41927298,90.00000001 +282.19,50.43283629,-2.560279276,48.9548,1.86E-11,10.00036559,2.23,-4.078441298,-2.490011209,90.00000001 +282.2,50.43283629,-2.560277868,48.9327,1.86E-11,10.00036556,2.185,-3.992798145,-2.558578156,90.00000001 +282.21,50.43283629,-2.560276461,48.9111,1.31E-11,10.00036552,2.139375,-3.906321224,-2.624913949,90.00000001 +282.22,50.43283629,-2.560275053,48.8899,-4.69E-12,10.00036549,2.0915625,-3.819028468,-2.688960776,90.00000001 +282.23,50.43283629,-2.560273646,48.8692,-2.42E-11,10.00036546,2.0415625,-3.730938155,-2.750662773,90.00000001 +282.24,50.43283629,-2.560272238,48.8491,-2.58E-11,10.00036542,1.991875,-3.642068734,-2.809966197,90.00000001 +282.25,50.43283629,-2.560270831,48.8294,-1.27E-11,10.00036539,1.9434375,-3.552438655,-2.866819252,90.00000001 +282.26,50.43283629,-2.560269423,48.8102,-1.56E-13,10.00036536,1.894375,-3.462066709,-2.921172434,90.00000001 +282.27,50.43283629,-2.560268016,48.7915,9.22E-12,10.0001433,1.843125,-3.370971748,-2.972978247,90.00000001 +282.28,50.43283629,-2.560266608,48.7733,1.33E-11,9.999477174,1.79,-3.279172851,-3.022191655,90.00000001 +282.29,50.43283629,-2.560265201,48.7557,5.47E-12,9.999033081,1.7365625,-3.186689098,-3.068769628,90.00000001 +282.3,50.43283629,-2.560263794,48.7386,-6.09E-12,9.99947712,1.683125,-3.093539854,-3.112671603,90.00000001 +282.31,50.43283629,-2.560262386,48.722,-4.69E-12,10.00014319,1.628125,-2.999744543,-3.153859247,90.00000001 +282.32,50.43283629,-2.560260979,48.706,8.59E-12,10.0003652,1.5715625,-2.905322818,-3.192296693,90.00000001 +282.33,50.43283629,-2.560259571,48.6906,1.86E-11,10.00036518,1.5153125,-2.81029433,-3.227950425,90.00000001 +282.34,50.43283629,-2.560258164,48.6757,2.27E-11,10.00036515,1.4596875,-2.714678961,-3.260789329,90.00000001 +282.35,50.43283629,-2.560256756,48.6614,2.81E-11,10.00036513,1.403125,-2.61849665,-3.290784758,90.00000001 +282.36,50.43283629,-2.560255349,48.6476,3.14E-11,10.00036511,1.345,-2.521767509,-3.317910585,90.00000001 +282.37,50.43283629,-2.560253941,48.6345,2.42E-11,10.00036509,1.2865625,-2.424511705,-3.342143205,90.00000001 +282.38,50.43283629,-2.560252534,48.6219,1.09E-11,10.00014304,1.2284375,-2.326749578,-3.36346136,90.00000001 +282.39,50.43283629,-2.560251126,48.6099,2.19E-12,9.999476918,1.1696875,-2.228501582,-3.381846545,90.00000001 +282.4,50.43283629,-2.560249719,48.5985,2.34E-12,9.999032835,1.1096875,-2.129788116,-3.397282715,90.00000001 +282.41,50.43283629,-2.560248312,48.5877,1.17E-11,9.999476884,1.0484375,-2.03062992,-3.40975635,90.00000001 +282.42,50.43283629,-2.560246904,48.5775,2.58E-11,10.00014297,0.9865625,-1.931047678,-3.419256678,90.00000001 +282.43,50.43283629,-2.560245497,48.568,3.28E-11,10.00036498,0.925,-1.831062131,-3.425775391,90.00000001 +282.44,50.43283629,-2.560244089,48.559,2.59E-11,10.00036497,0.8634375,-1.730694192,-3.429306701,90.00000001 +282.45,50.43283629,-2.560242682,48.5507,1.02E-11,10.00036496,0.80125,-1.629964831,-3.429847688,90.00000001 +282.46,50.43283629,-2.560241274,48.543,-5.31E-12,10.00036495,0.7384375,-1.528895019,-3.427397721,90.00000001 +282.47,50.43283629,-2.560239867,48.5359,-1.17E-11,10.00036493,0.675,-1.427506012,-3.421959033,90.00000001 +282.48,50.43283629,-2.560238459,48.5295,-6.88E-12,10.00036492,0.611875,-1.325818838,-3.413536382,90.00000001 +282.49,50.43283629,-2.560237052,48.5237,-2.19E-12,10.00036492,0.55,-1.223854753,-3.402137043,90.00000001 +282.5,50.43283629,-2.560235644,48.5185,-6.87E-12,10.00036491,0.488125,-1.121635129,-3.387770985,90.00000001 +282.51,50.43283629,-2.560234237,48.5139,-1.41E-11,10.00014287,0.4246875,-1.019181222,-3.370450758,90.00000001 +282.52,50.43283629,-2.560232829,48.51,-1.72E-11,9.999476762,0.36,-0.916514519,-3.350191486,90.00000001 +282.53,50.43283629,-2.560231422,48.5067,-1.87E-11,9.999032691,0.295,-0.813656391,-3.327010759,90.00000001 +282.54,50.43283629,-2.560230015,48.5041,-2.02E-11,9.999476753,0.23,-0.710628323,-3.300928804,90.00000001 +282.55,50.43283629,-2.560228607,48.5021,-2.03E-11,10.00014285,0.165,-0.60745186,-3.271968423,90.00000001 +282.56,50.43283629,-2.5602272,48.5008,-1.95E-11,10.00036488,0.1,-0.504148543,-3.240154827,90.00000001 +282.57,50.43283629,-2.560225792,48.5001,-1.66E-11,10.00036488,0.0353125,-0.400739975,-3.205515746,90.00000001 +282.58,50.43283629,-2.560224385,48.5001,-6.87E-12,10.00036488,-0.0284375,-0.297247697,-3.168081434,90.00000001 +282.59,50.43283629,-2.560222977,48.5007,7.81E-12,10.00036488,-0.0915625,-0.19369331,-3.127884492,90.00000001 +282.6,50.43283629,-2.56022157,48.5019,1.80E-11,10.00036488,-0.1553125,-0.09009853,-3.084960041,90.00000001 +282.61,50.43283629,-2.560220162,48.5038,2.02E-11,10.00036488,-0.22,0.0135151,-3.039345381,90.00000001 +282.62,50.43283629,-2.560218755,48.5063,1.64E-11,10.00014286,-0.2846875,0.117125923,-2.99108039,90.00000001 +282.63,50.43283629,-2.560217347,48.5095,5.47E-12,9.999476761,-0.3484375,0.220712281,-2.940207181,90.00000001 +282.64,50.43283629,-2.56021594,48.5133,-9.38E-12,9.999032701,-0.4115625,0.324252515,-2.886770043,90.00000001 +282.65,50.43283629,-2.560214533,48.5177,-1.89E-11,9.999476774,-0.4753125,0.427725083,-2.830815558,90.00000001 +282.66,50.43283629,-2.560213125,48.5228,-2.13E-11,10.00014288,-0.54,0.53110827,-2.772392598,90.00000001 +282.67,50.43283629,-2.560211718,48.5285,-1.89E-11,10.00036492,-0.6046875,0.63438059,-2.711552044,90.00000001 +282.68,50.43283629,-2.56021031,48.5349,-1.17E-11,10.00036493,-0.668125,0.737520384,-2.648347007,90.00000001 +282.69,50.43283629,-2.560208903,48.5419,-6.41E-12,10.00014291,-0.73,0.840506167,-2.582832549,90.00000001 +282.7,50.43283629,-2.560207495,48.5495,-1.02E-11,9.999476824,-0.791875,0.943316453,-2.515065851,90.00000001 +282.71,50.43283629,-2.560206088,48.5577,-1.19E-11,9.999032771,-0.8546875,1.045929699,-2.445105928,90.00000001 +282.72,50.43283629,-2.560204681,48.5666,2.34E-12,9.999476851,-0.9165625,1.148324534,-2.373013857,90.00000001 +282.73,50.43283629,-2.560203273,48.5761,2.11E-11,10.00014296,-0.9765625,1.250479586,-2.298852549,90.00000001 +282.74,50.43283629,-2.560201866,48.5861,2.34E-11,10.00036501,-1.036875,1.352373483,-2.222686519,90.00000001 +282.75,50.43283629,-2.560200458,48.5968,1.17E-11,10.00036503,-1.0984375,1.453984913,-2.144582288,90.00000001 +282.76,50.43283629,-2.560199051,48.6081,2.50E-12,10.00014301,-1.1596875,1.555292732,-2.064607979,90.00000001 +282.77,50.43283629,-2.560197643,48.62,3.12E-12,9.999476935,-1.2196875,1.656275741,-1.982833323,90.00000001 +282.78,50.43283629,-2.560196236,48.6325,1.33E-11,9.999032888,-1.2784375,1.756912798,-1.899329537,90.00000001 +282.79,50.43283629,-2.560194829,48.6456,2.72E-11,9.999476974,-1.3365625,1.857183048,-1.814169559,90.00000001 +282.8,50.43283629,-2.560193421,48.6592,3.05E-11,10.00014309,-1.3946875,1.957065405,-1.727427588,90.00000001 +282.81,50.43283629,-2.560192014,48.6735,1.25E-11,10.00036515,-1.451875,2.056539015,-1.639179253,90.00000001 +282.82,50.43283629,-2.560190606,48.6883,-1.88E-11,10.00036517,-1.5078125,2.155583192,-1.549501561,90.00000001 +282.83,50.43283629,-2.560189199,48.7036,-4.47E-11,10.0003652,-1.56375,2.254177196,-1.458472662,90.00000001 +282.84,50.43283629,-2.560187791,48.7196,-5.63E-11,10.00036522,-1.6196875,2.352300401,-1.366171969,90.00000001 +282.85,50.43283629,-2.560186384,48.736,-5.56E-11,10.00014322,-1.6746875,2.44993241,-1.272679924,90.00000001 +282.86,50.43283629,-2.560184976,48.7531,-4.55E-11,9.999477143,-1.7284375,2.547052767,-1.178078118,90.00000001 +282.87,50.43283629,-2.560183569,48.7706,-2.91E-11,9.999033104,-1.78125,2.64364119,-1.082448998,90.00000001 +282.88,50.43283629,-2.560182162,48.7887,-1.33E-11,9.999477198,-1.8334375,2.739677568,-0.98587593,90.00000001 +282.89,50.43283629,-2.560180754,48.8073,-6.25E-12,10.00014333,-1.885,2.835141733,-0.888443197,90.00000001 +282.9,50.43283629,-2.560179347,48.8264,-1.25E-11,10.00036539,-1.9365625,2.930013861,-0.79023571,90.00000001 +282.91,50.43283629,-2.560177939,48.846,-2.13E-11,10.00036542,-1.9878125,3.02427407,-0.691339183,90.00000001 +282.92,50.43283629,-2.560176532,48.8662,-1.17E-11,10.00014342,-2.0365625,3.117902707,-0.591839734,90.00000001 +282.93,50.43283629,-2.560175124,48.8868,1.39E-11,9.999477351,-2.083125,3.210880236,-0.491824221,90.00000001 +282.94,50.43283629,-2.560173717,48.9078,2.97E-11,9.999033319,-2.1303125,3.303187174,-0.39137985,90.00000001 +282.95,50.43283629,-2.56017231,48.9294,2.66E-11,9.999477419,-2.178125,3.394804329,-0.29059411,90.00000001 +282.96,50.43283629,-2.560170902,48.9514,1.72E-11,10.00014355,-2.224375,3.485712448,-0.189555065,90.00000001 +282.97,50.43283629,-2.560169495,48.9739,6.09E-12,10.00036562,-2.2684375,3.575892682,-0.088350665,90.00000001 +282.98,50.43283629,-2.560168087,48.9968,-1.03E-11,10.00036565,-2.31125,3.665326123,0.012930741,90.00000001 +282.99,50.43283629,-2.56016668,49.0201,-2.73E-11,10.00036569,-2.3534375,3.753994092,0.114200916,90.00000001 +283,50.43283629,-2.560165272,49.0439,-3.42E-11,10.00036573,-2.395,3.84187814,0.215371455,90.00000001 +283.01,50.43283629,-2.560163865,49.068,-2.34E-11,10.00036577,-2.43625,3.928959818,0.316354235,90.00000001 +283.02,50.43283629,-2.560162457,49.0926,-7.82E-13,10.00036581,-2.4765625,4.015220963,0.417061136,90.00000001 +283.03,50.43283629,-2.56016105,49.1176,1.41E-11,10.00014381,-2.5146875,4.100643584,0.517404323,90.00000001 +283.04,50.43283629,-2.560159642,49.1429,9.53E-12,9.999477752,-2.5515625,4.185209863,0.617296363,90.00000001 +283.05,50.43283629,-2.560158235,49.1686,-2.34E-12,9.999033726,-2.588125,4.268902152,0.71665011,90.00000001 +283.06,50.43283629,-2.560156828,49.1947,-3.13E-12,9.999477833,-2.623125,4.351702861,0.815378931,90.00000001 +283.07,50.43283629,-2.56015542,49.2211,7.03E-12,10.00014397,-2.6565625,4.433594802,0.913396712,90.00000001 +283.08,50.43283629,-2.560154013,49.2478,1.27E-11,10.00036605,-2.69,4.514560843,1.010617967,90.00000001 +283.09,50.43283629,-2.560152605,49.2749,1.03E-11,10.00036609,-2.7228125,4.594584083,1.106958013,90.00000001 +283.1,50.43283629,-2.560151198,49.3023,1.41E-11,10.00036613,-2.753125,4.673647789,1.202332739,90.00000001 +283.11,50.43283629,-2.56014979,49.33,2.72E-11,10.00036618,-2.7815625,4.75173552,1.29665901,90.00000001 +283.12,50.43283629,-2.560148383,49.3579,3.20E-11,10.00036622,-2.8096875,4.82883083,1.389854549,90.00000001 +283.13,50.43283629,-2.560146975,49.3862,1.72E-11,10.00036626,-2.8365625,4.904917734,1.481838167,90.00000001 +283.14,50.43283629,-2.560145568,49.4147,-2.34E-12,10.00036631,-2.8615625,4.979980305,1.572529594,90.00000001 +283.15,50.43283629,-2.56014416,49.4434,-3.12E-12,10.00036635,-2.8865625,5.054002899,1.661849704,90.00000001 +283.16,50.43283629,-2.560142753,49.4724,1.25E-11,10.00014437,-2.91125,5.126969991,1.749720688,90.00000001 +283.17,50.43283629,-2.560141345,49.5017,1.72E-11,9.999478313,-2.933125,5.198866397,1.836065886,90.00000001 +283.18,50.43283629,-2.560139938,49.5311,-7.81E-13,9.999034293,-2.953125,5.269677105,1.920810011,90.00000001 +283.19,50.43283629,-2.560138531,49.5607,-1.89E-11,9.999478405,-2.973125,5.339387276,2.003879208,90.00000001 +283.2,50.43283629,-2.560137123,49.5906,-1.17E-11,10.00014455,-2.9915625,5.407982413,2.085200942,90.00000001 +283.21,50.43283629,-2.560135716,49.6206,1.64E-11,10.00036663,-3.0078125,5.475448136,2.164704336,90.00000001 +283.22,50.43283629,-2.560134308,49.6507,3.98E-11,10.00036668,-3.0234375,5.541770407,2.242320064,90.00000001 +283.23,50.43283629,-2.560132901,49.6811,4.22E-11,10.00036673,-3.038125,5.606935304,2.317980516,90.00000001 +283.24,50.43283629,-2.560131493,49.7115,2.81E-11,10.00036677,-3.05125,5.670929304,2.39161963,90.00000001 +283.25,50.43283629,-2.560130086,49.7421,1.17E-11,10.00036682,-3.0634375,5.733739,2.463173178,90.00000001 +283.26,50.43283629,-2.560128678,49.7728,-5.55E-17,10.00036687,-3.074375,5.795351272,2.532578879,90.00000001 +283.27,50.43283629,-2.560127271,49.8036,-9.38E-12,10.00014488,-3.083125,5.855753285,2.599776056,90.00000001 +283.28,50.43283629,-2.560125863,49.8345,-1.41E-11,9.999478834,-3.09,5.914932376,2.664706212,90.00000001 +283.29,50.43283629,-2.560124456,49.8654,-4.69E-12,9.999034816,-3.09625,5.972876171,2.727312737,90.00000001 +283.3,50.43283629,-2.560123049,49.8964,1.64E-11,9.999478931,-3.1015625,6.029572637,2.787540972,90.00000001 +283.31,50.43283629,-2.560121641,49.9275,3.05E-11,10.00014508,-3.1046875,6.085009913,2.845338434,90.00000001 +283.32,50.43283629,-2.560120234,49.9585,2.58E-11,10.00036716,-3.1065625,6.139176426,2.900654759,90.00000001 +283.33,50.43283629,-2.560118826,49.9896,1.17E-11,10.00036721,-3.1084375,6.192060832,2.953441647,90.00000001 +283.34,50.43283629,-2.560117419,50.0207,1.56E-13,10.00036726,-3.109375,6.243652129,3.003653032,90.00000001 +283.35,50.43283629,-2.560116011,50.0518,-8.59E-12,10.00036731,-3.108125,6.293939489,3.051245256,90.00000001 +283.36,50.43283629,-2.560114604,50.0829,-1.48E-11,10.00036735,-3.1046875,6.342912426,3.096176721,90.00000001 +283.37,50.43283629,-2.560113196,50.1139,-1.72E-11,10.0003674,-3.1,6.390560742,3.138408294,90.00000001 +283.38,50.43283629,-2.560111789,50.1449,-2.03E-11,10.00036745,-3.0946875,6.436874525,3.177903134,90.00000001 +283.39,50.43283629,-2.560110381,50.1758,-2.80E-11,10.0003675,-3.088125,6.481843977,3.214626749,90.00000001 +283.4,50.43283629,-2.560108974,50.2067,-3.52E-11,10.00014551,-3.0796875,6.525459816,3.248547169,90.00000001 +283.41,50.43283629,-2.560107566,50.2374,-3.75E-11,9.999479463,-3.07,6.567712875,3.279634827,90.00000001 +283.42,50.43283629,-2.560106159,50.2681,-3.98E-11,9.999035446,-3.0596875,6.608594388,3.307862624,90.00000001 +283.43,50.43283629,-2.560104752,50.2986,-4.45E-11,9.99947956,-3.0478125,6.64809576,3.333205866,90.00000001 +283.44,50.43283629,-2.560103344,50.3291,-4.00E-11,10.00014571,-3.0334375,6.686208741,3.355642549,90.00000001 +283.45,50.43283629,-2.560101937,50.3593,-1.95E-11,10.00036779,-3.018125,6.722925423,3.375153022,90.00000001 +283.46,50.43283629,-2.560100529,50.3894,-1.56E-12,10.00036783,-3.003125,6.758238073,3.391720326,90.00000001 +283.47,50.43283629,-2.560099122,50.4194,-6.25E-12,10.00014585,-2.98625,6.792139355,3.405329965,90.00000001 +283.48,50.43283629,-2.560097714,50.4492,-2.19E-11,9.999479795,-2.9665625,6.824622223,3.415970192,90.00000001 +283.49,50.43283629,-2.560096307,50.4787,-2.13E-11,9.999035775,-2.9465625,6.855679859,3.423631554,90.00000001 +283.5,50.43283629,-2.5600949,50.5081,-2.34E-12,9.999479887,-2.9265625,6.88530573,3.42830752,90.00000001 +283.51,50.43283629,-2.560093492,50.5373,1.42E-11,10.00014603,-2.904375,6.913493707,3.429993907,90.00000001 +283.52,50.43283629,-2.560092085,50.5662,1.72E-11,10.00036811,-2.8796875,6.940237887,3.428689282,90.00000001 +283.53,50.43283629,-2.560090677,50.5949,8.59E-12,10.00036816,-2.8534375,6.965532713,3.424394849,90.00000001 +283.54,50.43283629,-2.56008927,50.6233,-5.47E-12,10.00014617,-2.8265625,6.989372857,3.417114217,90.00000001 +283.55,50.43283629,-2.560087862,50.6514,-1.31E-11,9.999480112,-2.8,7.01175339,3.40685386,90.00000001 +283.56,50.43283629,-2.560086455,50.6793,-1.08E-11,9.999036089,-2.7728125,7.032669558,3.393622661,90.00000001 +283.57,50.43283629,-2.560085048,50.7069,-1.25E-11,9.999480198,-2.743125,7.052117064,3.377432191,90.00000001 +283.58,50.43283629,-2.56008364,50.7342,-2.44E-11,10.00014634,-2.7115625,7.070091838,3.358296547,90.00000001 +283.59,50.43283629,-2.560082233,50.7611,-3.05E-11,10.00036842,-2.6796875,7.086590101,3.3362324,90.00000001 +283.6,50.43283629,-2.560080825,50.7878,-1.80E-11,10.00036846,-2.6465625,7.101608413,3.311259004,90.00000001 +283.61,50.43283629,-2.560079418,50.8141,2.34E-12,10.0003685,-2.61125,7.115143682,3.283398186,90.00000001 +283.62,50.43283629,-2.56007801,50.84,1.16E-11,10.00036854,-2.575,7.127192984,3.252674126,90.00000001 +283.63,50.43283629,-2.560076603,50.8656,4.53E-12,10.00014655,-2.5384375,7.137753914,3.219113754,90.00000001 +283.64,50.43283629,-2.560075195,50.8908,-1.19E-11,9.999480486,-2.50125,7.14682418,3.182746232,90.00000001 +283.65,50.43283629,-2.560073788,50.9156,-2.58E-11,9.999036459,-2.463125,7.154401948,3.143603302,90.00000001 +283.66,50.43283629,-2.560072381,50.9401,-2.52E-11,9.999480563,-2.423125,7.160485614,3.101719113,90.00000001 +283.67,50.43283629,-2.560070973,50.9641,-1.27E-11,10.0001467,-2.3815625,7.165073917,3.057130163,90.00000001 +283.68,50.43283629,-2.560069566,50.9877,-5.63E-12,10.00036877,-2.34,7.168165826,3.009875411,90.00000001 +283.69,50.43283629,-2.560068158,51.0109,-8.59E-12,10.00036881,-2.2978125,7.169760826,2.95999594,90.00000001 +283.7,50.43283629,-2.560066751,51.0337,-6.25E-12,10.00014681,-2.253125,7.169858458,2.907535294,90.00000001 +283.71,50.43283629,-2.560065343,51.056,3.91E-12,9.999480744,-2.206875,7.16845878,2.85253931,90.00000001 +283.72,50.43283629,-2.560063936,51.0778,2.19E-12,9.999036713,-2.1615625,7.165562077,2.795055829,90.00000001 +283.73,50.43283629,-2.560062529,51.0992,-1.64E-11,9.999480813,-2.1165625,7.161168923,2.735134986,90.00000001 +283.74,50.43283629,-2.560061121,51.1202,-3.28E-11,10.00014694,-2.069375,7.155280235,2.672829092,90.00000001 +283.75,50.43283629,-2.560059714,51.1406,-3.75E-11,10.00036901,-2.02,7.147897273,2.608192463,90.00000001 +283.76,50.43283629,-2.560058306,51.1606,-3.75E-11,10.00036904,-1.97,7.139021583,2.54128142,90.00000001 +283.77,50.43283629,-2.560056899,51.18,-3.50E-11,10.00036907,-1.9196875,7.128655001,2.472154406,90.00000001 +283.78,50.43283629,-2.560055491,51.199,-2.50E-11,10.0003691,-1.8684375,7.116799644,2.400871581,90.00000001 +283.79,50.43283629,-2.560054084,51.2174,-7.81E-12,10.0001471,-1.81625,7.103458036,2.327495168,90.00000001 +283.8,50.43283629,-2.560052676,51.2353,8.44E-12,9.999481025,-1.7634375,7.088632982,2.252089166,90.00000001 +283.81,50.43283629,-2.560051269,51.2527,1.64E-11,9.999036986,-1.7096875,7.072327577,2.174719295,90.00000001 +283.82,50.43283629,-2.560049862,51.2695,1.72E-11,9.999481079,-1.655,7.054545202,2.09545299,90.00000001 +283.83,50.43283629,-2.560048454,51.2858,1.64E-11,10.0001472,-1.6,7.03528958,2.014359466,90.00000001 +283.84,50.43283629,-2.560047047,51.3015,1.63E-11,10.00036926,-1.545,7.014564722,1.931509425,90.00000001 +283.85,50.43283629,-2.560045639,51.3167,1.86E-11,10.00036928,-1.4896875,6.992374926,1.846975003,90.00000001 +283.86,50.43283629,-2.560044232,51.3313,2.56E-11,10.00036931,-1.433125,6.96872489,1.760830053,90.00000001 +283.87,50.43283629,-2.560042824,51.3454,3.05E-11,10.00036933,-1.375,6.943619541,1.673149577,90.00000001 +283.88,50.43283629,-2.560041417,51.3588,2.41E-11,10.00036935,-1.3165625,6.917064093,1.584010121,90.00000001 +283.89,50.43283629,-2.560040009,51.3717,1.09E-11,10.00036937,-1.2584375,6.889064104,1.493489379,90.00000001 +283.9,50.43283629,-2.560038602,51.384,2.19E-12,10.00036939,-1.1996875,6.859625418,1.401666303,90.00000001 +283.91,50.43283629,-2.560037194,51.3957,1.39E-16,10.00036941,-1.14,6.828754166,1.308620994,90.00000001 +283.92,50.43283629,-2.560035787,51.4068,-2.34E-12,10.00014739,-1.0796875,6.796456879,1.214434467,90.00000001 +283.93,50.43283629,-2.560034379,51.4173,-1.17E-11,9.999481309,-1.0184375,6.762740146,1.119189,90.00000001 +283.94,50.43283629,-2.560032972,51.4272,-2.58E-11,9.999037259,-0.9565625,6.727611187,1.022967556,90.00000001 +283.95,50.43283629,-2.560031565,51.4364,-3.28E-11,9.99948134,-0.895,6.69107722,0.925854075,90.00000001 +283.96,50.43283629,-2.560030157,51.4451,-2.59E-11,10.00014745,-0.8334375,6.653145925,0.827933181,90.00000001 +283.97,50.43283629,-2.56002875,51.4531,-1.02E-11,10.0003695,-0.77125,6.613825149,0.729290361,90.00000001 +283.98,50.43283629,-2.560027342,51.4605,5.31E-12,10.00036951,-0.7084375,6.573123201,0.630011615,90.00000001 +283.99,50.43283629,-2.560025935,51.4673,1.17E-11,10.00036952,-0.645,6.531048561,0.530183459,90.00000001 +284,50.43283629,-2.560024527,51.4734,6.88E-12,10.00036953,-0.581875,6.487609938,0.429892984,90.00000001 +284.01,50.43283629,-2.56002312,51.4789,2.19E-12,10.00036954,-0.52,6.442816498,0.329227622,90.00000001 +284.02,50.43283629,-2.560021712,51.4838,4.53E-12,10.00036955,-0.4578125,6.396677582,0.228275209,90.00000001 +284.03,50.43283629,-2.560020305,51.4881,2.34E-12,10.00036955,-0.393125,6.349202758,0.127123693,90.00000001 +284.04,50.43283629,-2.560018897,51.4917,-6.41E-12,10.00036956,-0.326875,6.300401994,0.025861367,90.00000001 +284.05,50.43283629,-2.56001749,51.4946,-5.47E-12,10.00014753,-0.261875,6.250285491,-0.075423534,90.00000001 +284.06,50.43283629,-2.560016082,51.4969,6.88E-12,9.999481433,-0.1984375,6.198863674,-0.176642716,90.00000001 +284.07,50.43283629,-2.560014675,51.4986,1.64E-11,9.99903737,-0.1346875,6.146147317,-0.277707773,90.00000001 +284.08,50.43283629,-2.560013268,51.4996,1.88E-11,9.999481439,-0.07,6.09214742,-0.378530755,90.00000001 +284.09,50.43283629,-2.56001186,51.5,1.64E-11,10.00014754,-0.0053125,6.03687527,-0.479023599,90.00000001 +284.1,50.43283629,-2.560010453,51.4997,7.03E-12,10.00036957,0.0584375,5.980342384,-0.579098699,90.00000001 +284.11,50.43283629,-2.560009045,51.4988,-4.69E-12,10.00036957,0.121875,5.922560565,-0.678668852,90.00000001 +284.12,50.43283629,-2.560007638,51.4973,-2.50E-12,10.00036957,0.1865625,5.863541901,-0.777647197,90.00000001 +284.13,50.43283629,-2.56000623,51.4951,1.80E-11,10.00036956,0.251875,5.803298712,-0.875947446,90.00000001 +284.14,50.43283629,-2.560004823,51.4922,4.05E-11,10.00036956,0.31625,5.741843545,-0.973483827,90.00000001 +284.15,50.43283629,-2.560003415,51.4888,4.92E-11,10.00036955,0.38,5.67918935,-1.070171315,90.00000001 +284.16,50.43283629,-2.560002008,51.4846,4.20E-11,10.00014751,0.4434375,5.615349075,-1.165925568,90.00000001 +284.17,50.43283629,-2.5600006,51.4799,2.80E-11,9.999481408,0.5065625,5.550336069,-1.260663166,90.00000001 +284.18,50.43283629,-2.559999193,51.4745,1.86E-11,9.999037333,0.5703125,5.484164028,-1.354301429,90.00000001 +284.19,50.43283629,-2.559997786,51.4685,1.41E-11,9.999481389,0.6346875,5.416846643,-1.446758712,90.00000001 +284.2,50.43283629,-2.559996378,51.4618,7.66E-12,10.00014748,0.698125,5.348398011,-1.537954456,90.00000001 +284.21,50.43283629,-2.559994971,51.4545,3.91E-12,10.0003695,0.76,5.278832455,-1.62780902,90.00000001 +284.22,50.43283629,-2.559993563,51.4466,9.37E-12,10.00036949,0.821875,5.208164471,-1.716244139,90.00000001 +284.23,50.43283629,-2.559992156,51.4381,1.50E-11,10.00036947,0.885,5.136408841,-1.803182635,90.00000001 +284.24,50.43283629,-2.559990748,51.4289,1.41E-11,10.00036946,0.9478125,5.063580519,-1.888548763,90.00000001 +284.25,50.43283629,-2.559989341,51.4191,1.72E-11,10.00014741,1.008125,4.989694747,-1.972268038,90.00000001 +284.26,50.43283629,-2.559987933,51.4087,2.58E-11,9.999481297,1.066875,4.914766936,-2.054267466,90.00000001 +284.27,50.43283629,-2.559986526,51.3978,2.44E-11,9.999037213,1.126875,4.838812729,-2.134475484,90.00000001 +284.28,50.43283629,-2.559985119,51.3862,1.42E-11,9.999481261,1.188125,4.761848053,-2.212822306,90.00000001 +284.29,50.43283629,-2.559983711,51.374,1.42E-11,10.00014734,1.248125,4.683888837,-2.289239463,90.00000001 +284.3,50.43283629,-2.559982304,51.3612,2.66E-11,10.00036935,1.3065625,4.604951525,-2.363660378,90.00000001 +284.31,50.43283629,-2.559980896,51.3479,3.45E-11,10.00036933,1.365,4.525052503,-2.436020135,90.00000001 +284.32,50.43283629,-2.559979489,51.3339,3.05E-11,10.00036931,1.423125,4.444208502,-2.506255651,90.00000001 +284.33,50.43283629,-2.559978081,51.3194,2.36E-11,10.00036929,1.4796875,4.362436309,-2.574305676,90.00000001 +284.34,50.43283629,-2.559976674,51.3043,2.11E-11,10.00014723,1.535,4.279753171,-2.640110853,90.00000001 +284.35,50.43283629,-2.559975266,51.2887,2.03E-11,9.999481109,1.59,4.196176218,-2.703613828,90.00000001 +284.36,50.43283629,-2.559973859,51.2725,1.87E-11,9.999037017,1.645,4.111722927,-2.764759254,90.00000001 +284.37,50.43283629,-2.559972452,51.2558,1.50E-11,9.999481057,1.6996875,4.026411001,-2.82349373,90.00000001 +284.38,50.43283629,-2.559971044,51.2385,5.47E-12,10.00014713,1.7534375,3.940258202,-2.879766035,90.00000001 +284.39,50.43283629,-2.559969637,51.2207,-7.97E-12,10.00036913,1.8065625,3.853282464,-2.933527181,90.00000001 +284.4,50.43283629,-2.559968229,51.2024,-1.27E-11,10.00036911,1.8596875,3.765502121,-2.984730299,90.00000001 +284.41,50.43283629,-2.559966822,51.1835,7.82E-13,10.00014704,1.9115625,3.676935336,-3.033330642,90.00000001 +284.42,50.43283629,-2.559965414,51.1641,2.19E-11,9.999480913,1.96125,3.587600674,-3.079285868,90.00000001 +284.43,50.43283629,-2.559964007,51.1443,3.22E-11,9.999036816,2.01,3.497516811,-3.122555869,90.00000001 +284.44,50.43283629,-2.5599626,51.1239,2.64E-11,9.999480851,2.0584375,3.406702485,-3.163103004,90.00000001 +284.45,50.43283629,-2.559961192,51.1031,1.09E-11,10.00014692,2.10625,3.315176774,-3.200891862,90.00000001 +284.46,50.43283629,-2.559959785,51.0818,-5.47E-12,10.00036892,2.1534375,3.222958702,-3.2358895,90.00000001 +284.47,50.43283629,-2.559958377,51.06,-1.56E-11,10.00036888,2.1996875,3.130067575,-3.268065434,90.00000001 +284.48,50.43283629,-2.55995697,51.0378,-1.87E-11,10.00014682,2.245,3.036522762,-3.297391477,90.00000001 +284.49,50.43283629,-2.559955562,51.0151,-2.19E-11,9.999480681,2.2896875,2.942343798,-3.323842245,90.00000001 +284.5,50.43283629,-2.559954155,50.992,-2.97E-11,9.999036578,2.333125,2.847550394,-3.347394478,90.00000001 +284.51,50.43283629,-2.559952748,50.9684,-3.42E-11,9.999480607,2.375,2.752162261,-3.368027777,90.00000001 +284.52,50.43283629,-2.55995134,50.9445,-2.34E-11,10.00014667,2.41625,2.65619945,-3.385724094,90.00000001 +284.53,50.43283629,-2.559949933,50.9201,-7.82E-13,10.00036866,2.4565625,2.559681845,-3.400468017,90.00000001 +284.54,50.43283629,-2.559948525,50.8953,1.41E-11,10.00036863,2.4946875,2.462629727,-3.412246711,90.00000001 +284.55,50.43283629,-2.559947118,50.8702,9.53E-12,10.00014655,2.5315625,2.365063323,-3.421049864,90.00000001 +284.56,50.43283629,-2.55994571,50.8447,-4.69E-12,9.999480414,2.5684375,2.267003028,-3.426869797,90.00000001 +284.57,50.43283629,-2.559944303,50.8188,-1.48E-11,9.999036307,2.6046875,2.168469242,-3.429701412,90.00000001 +284.58,50.43283629,-2.559942896,50.7926,-1.64E-11,9.999480332,2.6396875,2.069482647,-3.429542302,90.00000001 +284.59,50.43283629,-2.559941488,50.766,-8.44E-12,10.00014639,2.6734375,1.970063812,-3.426392581,90.00000001 +284.6,50.43283629,-2.559940081,50.7391,7.97E-12,10.00036838,2.70625,1.870233594,-3.420255,90.00000001 +284.61,50.43283629,-2.559938673,50.7119,2.34E-11,10.00036834,2.738125,1.770012791,-3.411134944,90.00000001 +284.62,50.43283629,-2.559937266,50.6843,2.48E-11,10.0003683,2.768125,1.669422372,-3.399040263,90.00000001 +284.63,50.43283629,-2.559935858,50.6565,1.09E-11,10.00036825,2.79625,1.568483251,-3.383981615,90.00000001 +284.64,50.43283629,-2.559934451,50.6284,-6.09E-12,10.00036821,2.8234375,1.467216628,-3.365972061,90.00000001 +284.65,50.43283629,-2.559933043,50.6,-1.55E-11,10.00036816,2.8496875,1.365643587,-3.34502736,90.00000001 +284.66,50.43283629,-2.559931636,50.5714,-1.48E-11,10.00036812,2.8746875,1.263785327,-3.321165673,90.00000001 +284.67,50.43283629,-2.559930228,50.5425,-7.81E-12,10.00036807,2.898125,1.161663163,-3.294407971,90.00000001 +284.68,50.43283629,-2.559928821,50.5134,-3.91E-12,10.00014599,2.92,1.059298409,-3.264777459,90.00000001 +284.69,50.43283629,-2.559927413,50.4841,-1.16E-11,9.99947985,2.9415625,0.956712436,-3.232299976,90.00000001 +284.7,50.43283629,-2.559926006,50.4546,-2.34E-11,9.999035737,2.963125,0.853926615,-3.197003943,90.00000001 +284.71,50.43283629,-2.559924599,50.4248,-2.58E-11,9.999479756,2.9828125,0.750962547,-3.158920011,90.00000001 +284.72,50.43283629,-2.559923191,50.3949,-2.11E-11,10.00014581,2.9996875,0.647841545,-3.11808147,90.00000001 +284.73,50.43283629,-2.559921784,50.3648,-1.88E-11,10.0003678,3.015,0.544585326,-3.074523958,90.00000001 +284.74,50.43283629,-2.559920376,50.3346,-1.88E-11,10.00036775,3.03,0.441215375,-3.028285347,90.00000001 +284.75,50.43283629,-2.559918969,50.3042,-2.11E-11,10.0003677,3.0446875,0.337753234,-2.979406089,90.00000001 +284.76,50.43283629,-2.559917561,50.2737,-2.58E-11,10.00036765,3.0578125,0.23422062,-2.927928753,90.00000001 +284.77,50.43283629,-2.559916154,50.243,-2.11E-11,10.00036761,3.0684375,0.130639018,-2.873898145,90.00000001 +284.78,50.43283629,-2.559914746,50.2123,2.34E-12,10.00036756,3.0778125,0.027030201,-2.817361535,90.00000001 +284.79,50.43283629,-2.559913339,50.1815,3.28E-11,10.00036751,3.086875,-0.076584289,-2.758368081,90.00000001 +284.8,50.43283629,-2.559911931,50.1505,5.16E-11,10.00036746,3.094375,-0.180182793,-2.696969294,90.00000001 +284.81,50.43283629,-2.559910524,50.1196,5.39E-11,10.00014538,3.0996875,-0.283743654,-2.633218744,90.00000001 +284.82,50.43283629,-2.559909116,50.0885,4.45E-11,9.999479231,3.1034375,-0.387245271,-2.567172008,90.00000001 +284.83,50.43283629,-2.559907709,50.0575,2.81E-11,9.999035117,3.10625,-0.490665987,-2.498886611,90.00000001 +284.84,50.43283629,-2.559906302,50.0264,1.17E-11,9.999479134,3.1084375,-0.593984258,-2.428422142,90.00000001 +284.85,50.43283629,-2.559904894,49.9953,2.50E-16,10.00014518,3.109375,-0.697178483,-2.355840077,90.00000001 +284.86,50.43283629,-2.559903487,49.9642,-1.17E-11,10.00036717,3.1084375,-0.80022712,-2.281203673,90.00000001 +284.87,50.43283629,-2.559902079,49.9331,-2.81E-11,10.00036712,3.10625,-0.903108624,-2.204578074,90.00000001 +284.88,50.43283629,-2.559900672,49.9021,-4.22E-11,10.00036707,3.103125,-1.005801512,-2.126029972,90.00000001 +284.89,50.43283629,-2.559899264,49.871,-4.22E-11,10.00036702,3.098125,-1.10828441,-2.045628007,90.00000001 +284.9,50.43283629,-2.559897857,49.8401,-2.81E-11,10.00036697,3.09125,-1.210535776,-1.963442196,90.00000001 +284.91,50.43283629,-2.559896449,49.8092,-1.17E-11,10.00036693,3.0834375,-1.31253441,-1.879544216,90.00000001 +284.92,50.43283629,-2.559895042,49.7784,-2.34E-12,10.00036688,3.0746875,-1.414258884,-1.794007289,90.00000001 +284.93,50.43283629,-2.559893634,49.7477,-2.34E-12,10.00036683,3.0646875,-1.515688055,-1.706905901,90.00000001 +284.94,50.43283629,-2.559892227,49.7171,-9.38E-12,10.00014475,3.053125,-1.616800668,-1.618316141,90.00000001 +284.95,50.43283629,-2.559890819,49.6866,-1.41E-11,9.999478603,3.04,-1.717575636,-1.528315128,90.00000001 +284.96,50.43283629,-2.559889412,49.6563,-4.69E-12,9.999034489,3.02625,-1.817991875,-1.436981416,90.00000001 +284.97,50.43283629,-2.559888005,49.6261,1.64E-11,9.999478508,3.0115625,-1.91802853,-1.344394645,90.00000001 +284.98,50.43283629,-2.559886597,49.596,3.05E-11,10.00014456,2.9946875,-2.017664573,-1.250635545,90.00000001 +284.99,50.43283629,-2.55988519,49.5662,2.58E-11,10.00036655,2.9765625,-2.116879263,-1.15578582,90.00000001 +285,50.43283629,-2.559883782,49.5365,1.41E-11,10.0003665,2.958125,-2.215651858,-1.059928319,90.00000001 +285.01,50.43283629,-2.559882375,49.507,1.17E-11,10.00036645,2.9378125,-2.313961733,-0.963146465,90.00000001 +285.02,50.43283629,-2.559880967,49.4777,1.42E-11,10.00036641,2.915,-2.411788375,-0.86552477,90.00000001 +285.03,50.43283629,-2.55987956,49.4487,7.81E-12,10.00014433,2.8915625,-2.509111387,-0.767148318,90.00000001 +285.04,50.43283629,-2.559878152,49.4199,-3.12E-12,9.999478185,2.868125,-2.605910372,-0.668102937,90.00000001 +285.05,50.43283629,-2.559876745,49.3913,-5.47E-12,9.999034075,2.8428125,-2.702165161,-0.568474916,90.00000001 +285.06,50.43283629,-2.559875338,49.363,-3.75E-12,9.999478096,2.815,-2.797855588,-0.468351172,90.00000001 +285.07,50.43283629,-2.55987393,49.335,-1.08E-11,10.00014415,2.7865625,-2.892961769,-0.367819023,90.00000001 +285.08,50.43283629,-2.559872523,49.3073,-2.19E-11,10.00036614,2.758125,-2.987463766,-0.266966132,90.00000001 +285.09,50.43283629,-2.559871115,49.2798,-2.20E-11,10.0003661,2.728125,-3.081341927,-0.165880449,90.00000001 +285.1,50.43283629,-2.559869708,49.2527,-9.38E-12,10.00036606,2.69625,-3.174576541,-0.064650151,90.00000001 +285.11,50.43283629,-2.5598683,49.2259,5.47E-12,10.00036601,2.6634375,-3.267148186,0.036636583,90.00000001 +285.12,50.43283629,-2.559866893,49.1994,1.41E-11,10.00014394,2.6296875,-3.359037496,0.137891289,90.00000001 +285.13,50.43283629,-2.559865485,49.1733,1.39E-11,9.9994778,2.5946875,-3.450225333,0.239025845,90.00000001 +285.14,50.43283629,-2.559864078,49.1475,6.88E-12,9.999033694,2.558125,-3.540692676,0.339951903,90.00000001 +285.15,50.43283629,-2.559862671,49.1221,2.19E-12,9.999477719,2.52,-3.63042056,0.440581569,90.00000001 +285.16,50.43283629,-2.559861263,49.0971,9.38E-12,10.00014378,2.4815625,-3.719390306,0.54082701,90.00000001 +285.17,50.43283629,-2.559859856,49.0725,2.19E-11,10.00036577,2.443125,-3.807583293,0.640600849,90.00000001 +285.18,50.43283629,-2.559858448,49.0482,2.34E-11,10.00036574,2.403125,-3.894981071,0.739816054,90.00000001 +285.19,50.43283629,-2.559857041,49.0244,1.08E-11,10.00014367,2.36125,-3.981565479,0.838386109,90.00000001 +285.2,50.43283629,-2.559855633,49.001,-5.47E-12,9.99947753,2.3184375,-4.067318354,0.936225127,90.00000001 +285.21,50.43283629,-2.559854226,48.978,-1.33E-11,9.999033428,2.275,-4.152221875,1.033247737,90.00000001 +285.22,50.43283629,-2.559852819,48.9555,-4.53E-12,9.999477459,2.23125,-4.236258226,1.129369314,90.00000001 +285.23,50.43283629,-2.559851411,48.9334,1.64E-11,10.00014352,2.1865625,-4.319409871,1.224506091,90.00000001 +285.24,50.43283629,-2.559850004,48.9117,3.05E-11,10.00036552,2.1396875,-4.401659453,1.318575104,90.00000001 +285.25,50.43283629,-2.559848596,48.8906,2.81E-11,10.00036549,2.091875,-4.482989838,1.411494248,90.00000001 +285.26,50.43283629,-2.559847189,48.8699,2.34E-11,10.00014342,2.045,-4.56338401,1.503182564,90.00000001 +285.27,50.43283629,-2.559845781,48.8497,2.58E-11,9.999477293,1.9978125,-4.642825181,1.593560067,90.00000001 +285.28,50.43283629,-2.559844374,48.8299,2.58E-11,9.999033196,1.9478125,-4.721296736,1.682548033,90.00000001 +285.29,50.43283629,-2.559842967,48.8107,2.34E-11,9.999477232,1.895,-4.798782287,1.770068711,90.00000001 +285.3,50.43283629,-2.559841559,48.792,2.83E-11,10.0001433,1.841875,-4.875265736,1.856045899,90.00000001 +285.31,50.43283629,-2.559840152,48.7739,3.36E-11,10.00036531,1.79,-4.950730981,1.940404595,90.00000001 +285.32,50.43283629,-2.559838744,48.7562,2.98E-11,10.00036528,1.738125,-5.025162381,2.023071175,90.00000001 +285.33,50.43283629,-2.559837337,48.7391,2.34E-11,10.00014322,1.6846875,-5.098544352,2.103973675,90.00000001 +285.34,50.43283629,-2.559835929,48.7225,2.13E-11,9.999477094,1.63,-5.170861481,2.183041449,90.00000001 +285.35,50.43283629,-2.559834522,48.7065,1.89E-11,9.999033003,1.5746875,-5.242098813,2.260205572,90.00000001 +285.36,50.43283629,-2.559833115,48.691,9.53E-12,9.999477045,1.5184375,-5.312241395,2.335398777,90.00000001 +285.37,50.43283629,-2.559831707,48.6761,-4.53E-12,10.00014312,1.4615625,-5.381274559,2.40855546,90.00000001 +285.38,50.43283629,-2.5598303,48.6618,-1.16E-11,10.00036513,1.405,-5.449183923,2.479611853,90.00000001 +285.39,50.43283629,-2.559828892,48.648,-7.03E-12,10.00036511,1.348125,-5.515955278,2.548506017,90.00000001 +285.4,50.43283629,-2.559827485,48.6348,-6.25E-13,10.00036509,1.2896875,-5.581574702,2.615177792,90.00000001 +285.41,50.43283629,-2.559826077,48.6222,7.81E-13,10.00036507,1.23,-5.646028501,2.679569138,90.00000001 +285.42,50.43283629,-2.55982467,48.6102,1.56E-13,10.00036505,1.17,-5.709303209,2.741623848,90.00000001 +285.43,50.43283629,-2.559823262,48.5988,-2.34E-12,10.00036503,1.1096875,-5.771385536,2.801287834,90.00000001 +285.44,50.43283629,-2.559821855,48.588,-1.17E-11,10.00014298,1.0484375,-5.832262645,2.858509014,90.00000001 +285.45,50.43283629,-2.559820447,48.5778,-2.34E-11,9.999476868,0.986875,-5.891921761,2.913237599,90.00000001 +285.46,50.43283629,-2.55981904,48.5683,-2.09E-11,9.999032787,0.9265625,-5.950350393,2.965425747,90.00000001 +285.47,50.43283629,-2.559817633,48.5593,-1.56E-12,9.999476839,0.8665625,-6.007536394,3.015028021,90.00000001 +285.48,50.43283629,-2.559816225,48.5509,1.56E-11,10.00014293,0.804375,-6.063467789,3.062001106,90.00000001 +285.49,50.43283629,-2.559814818,48.5432,2.25E-11,10.00036495,0.7403125,-6.11813289,3.106304094,90.00000001 +285.5,50.43283629,-2.55981341,48.5361,2.81E-11,10.00036494,0.676875,-6.171520352,3.147898366,90.00000001 +285.51,50.43283629,-2.559812003,48.5297,3.13E-11,10.00036492,0.615,-6.223618889,3.186747597,90.00000001 +285.52,50.43283629,-2.559810595,48.5238,2.58E-11,10.00036492,0.553125,-6.274417785,3.222817983,90.00000001 +285.53,50.43283629,-2.559809188,48.5186,1.86E-11,10.00036491,0.4896875,-6.323906327,3.256077954,90.00000001 +285.54,50.43283629,-2.55980778,48.514,1.64E-11,10.0003649,0.425,-6.372074144,3.286498633,90.00000001 +285.55,50.43283629,-2.559806373,48.5101,1.72E-11,10.00036489,0.36,-6.418911324,3.314053433,90.00000001 +285.56,50.43283629,-2.559804965,48.5068,1.64E-11,10.00036489,0.2953125,-6.464407897,3.338718292,90.00000001 +285.57,50.43283629,-2.559803558,48.5042,8.44E-12,10.00014285,0.2315625,-6.508554525,3.360471781,90.00000001 +285.58,50.43283629,-2.55980215,48.5022,-3.13E-12,9.99947675,0.168125,-6.551341924,3.379294877,90.00000001 +285.59,50.43283629,-2.559800743,48.5008,-1.56E-12,9.999032682,0.1034375,-6.592761158,3.395171136,90.00000001 +285.6,50.43283629,-2.559799336,48.5001,1.66E-11,9.999476747,0.0384375,-6.632803574,3.408086808,90.00000001 +285.61,50.43283629,-2.559797928,48.5001,2.80E-11,10.00014285,-0.025,-6.671460807,3.418030548,90.00000001 +285.62,50.43283629,-2.559796521,48.5006,1.56E-11,10.00036488,-0.0884375,-6.708724779,3.424993704,90.00000001 +285.63,50.43283629,-2.559795113,48.5018,-6.25E-12,10.00036488,-0.15375,-6.744587754,3.428970261,90.00000001 +285.64,50.43283629,-2.559793706,48.5037,-1.78E-11,10.00036488,-0.2196875,-6.77904217,3.429956665,90.00000001 +285.65,50.43283629,-2.559792298,48.5062,-1.64E-11,10.00036489,-0.2846875,-6.812080922,3.427952115,90.00000001 +285.66,50.43283629,-2.559790891,48.5094,-5.63E-12,10.00036489,-0.3484375,-6.84369702,3.422958329,90.00000001 +285.67,50.43283629,-2.559789483,48.5132,8.44E-12,10.0003649,-0.4115625,-6.873883874,3.414979663,90.00000001 +285.68,50.43283629,-2.559788076,48.5176,1.42E-11,10.00036491,-0.475,-6.90263524,3.404023105,90.00000001 +285.69,50.43283629,-2.559786668,48.5227,6.41E-12,10.00036491,-0.5384375,-6.929945101,3.390098168,90.00000001 +285.7,50.43283629,-2.559785261,48.5284,-6.88E-12,10.00014289,-0.6015625,-6.955807671,3.373217055,90.00000001 +285.71,50.43283629,-2.559783853,48.5347,-1.27E-11,9.999476801,-0.665,-6.980217679,3.353394434,90.00000001 +285.72,50.43283629,-2.559782446,48.5417,-7.81E-12,9.999032746,-0.728125,-7.00316991,3.330647552,90.00000001 +285.73,50.43283629,-2.559781039,48.5493,-3.91E-12,9.999476823,-0.79,-7.024659608,3.304996346,90.00000001 +285.74,50.43283629,-2.559779631,48.5575,-1.16E-11,10.00014294,-0.8515625,-7.044682363,3.276463105,90.00000001 +285.75,50.43283629,-2.559778224,48.5663,-2.58E-11,10.00036498,-0.9134375,-7.063233877,3.245072753,90.00000001 +285.76,50.43283629,-2.559776816,48.5758,-3.28E-11,10.000365,-0.975,-7.080310312,3.210852676,90.00000001 +285.77,50.43283629,-2.559775409,48.5858,-2.58E-11,10.00036501,-1.0365625,-7.095908171,3.17383267,90.00000001 +285.78,50.43283629,-2.559774001,48.5965,-1.41E-11,10.00036503,-1.098125,-7.110024075,3.134045048,90.00000001 +285.79,50.43283629,-2.559772594,48.6078,-1.42E-11,10.00036505,-1.158125,-7.122655159,3.091524475,90.00000001 +285.8,50.43283629,-2.559771186,48.6197,-2.66E-11,10.00036507,-1.2165625,-7.133798787,3.046308021,90.00000001 +285.81,50.43283629,-2.559769779,48.6321,-3.44E-11,10.00036509,-1.275,-7.14345261,2.998435163,90.00000001 +285.82,50.43283629,-2.559768371,48.6452,-2.72E-11,10.00036511,-1.3334375,-7.151614623,2.947947612,90.00000001 +285.83,50.43283629,-2.559766964,48.6588,-1.17E-11,10.00014309,-1.3915625,-7.158283107,2.894889428,90.00000001 +285.84,50.43283629,-2.559765556,48.673,-3.13E-12,9.999477017,-1.45,-7.163456629,2.83930685,90.00000001 +285.85,50.43283629,-2.559764149,48.6878,-4.69E-12,9.999032974,-1.5078125,-7.167134216,2.781248349,90.00000001 +285.86,50.43283629,-2.559762742,48.7032,-2.19E-12,9.999477064,-1.563125,-7.169315008,2.720764575,90.00000001 +285.87,50.43283629,-2.559761334,48.7191,7.03E-12,10.00014319,-1.616875,-7.169998604,2.65790824,90.00000001 +285.88,50.43283629,-2.559759927,48.7355,4.06E-12,10.00036525,-1.6715625,-7.169184775,2.592734176,90.00000001 +285.89,50.43283629,-2.559758519,48.7525,-1.55E-11,10.00036527,-1.7265625,-7.166873807,2.525299221,90.00000001 +285.9,50.43283629,-2.559757112,48.7701,-2.95E-11,10.00014327,-1.7796875,-7.163066158,2.45566216,90.00000001 +285.91,50.43283629,-2.559755704,48.7881,-2.42E-11,9.999477197,-1.8315625,-7.157762517,2.383883669,90.00000001 +285.92,50.43283629,-2.559754297,48.8067,-1.02E-11,9.99903316,-1.8834375,-7.150964144,2.310026487,90.00000001 +285.93,50.43283629,-2.55975289,48.8258,-1.56E-12,9.999477256,-1.9346875,-7.142672356,2.234154842,90.00000001 +285.94,50.43283629,-2.559751482,48.8454,1.56E-13,10.00014339,-1.985,-7.132888872,2.156335027,90.00000001 +285.95,50.43283629,-2.559750075,48.8655,2.34E-12,10.00036545,-2.0346875,-7.121615813,2.076634879,90.00000001 +285.96,50.43283629,-2.559748667,48.8861,9.37E-12,10.00036548,-2.083125,-7.108855527,1.99512384,90.00000001 +285.97,50.43283629,-2.55974726,48.9072,1.39E-11,10.00014348,-2.13,-7.094610593,1.911873015,90.00000001 +285.98,50.43283629,-2.559745852,48.9287,6.25E-12,9.999477417,-2.1765625,-7.078884048,1.826955055,90.00000001 +285.99,50.43283629,-2.559744445,48.9507,-6.25E-12,9.999033386,-2.223125,-7.061679214,1.740443929,90.00000001 +286,50.43283629,-2.559743038,48.9732,-8.44E-12,9.999477487,-2.2678125,-7.042999586,1.652415094,90.00000001 +286.01,50.43283629,-2.55974163,48.9961,-4.69E-12,10.00014362,-2.31,-7.022849119,1.562945328,90.00000001 +286.02,50.43283629,-2.559740223,49.0194,-7.97E-12,10.00036569,-2.351875,-7.001232052,1.472112724,90.00000001 +286.03,50.43283629,-2.559738815,49.0431,-1.03E-11,10.00036573,-2.3946875,-6.978152853,1.379996352,90.00000001 +286.04,50.43283629,-2.559737408,49.0673,-2.78E-17,10.00014373,-2.43625,-6.953616337,1.286676596,90.00000001 +286.05,50.43283629,-2.559736,49.0919,1.02E-11,9.999477672,-2.4746875,-6.927627716,1.192234874,90.00000001 +286.06,50.43283629,-2.559734593,49.1168,7.03E-12,9.999033645,-2.511875,-6.900192262,1.096753462,90.00000001 +286.07,50.43283629,-2.559733186,49.1421,2.19E-12,9.999477751,-2.55,-6.87131582,1.00031567,90.00000001 +286.08,50.43283629,-2.559731778,49.1678,4.69E-12,10.00014389,-2.5878125,-6.841004404,0.903005607,90.00000001 +286.09,50.43283629,-2.559730371,49.1939,3.12E-12,10.00036596,-2.623125,-6.809264376,0.804908127,90.00000001 +286.1,50.43283629,-2.559728963,49.2203,-9.38E-12,10.000366,-2.65625,-6.776102266,0.706108775,90.00000001 +286.11,50.43283629,-2.559727556,49.247,-2.44E-11,10.00014401,-2.6884375,-6.741525066,0.606693607,90.00000001 +286.12,50.43283629,-2.559726148,49.2741,-3.14E-11,9.999477957,-2.72,-6.705539936,0.506749428,90.00000001 +286.13,50.43283629,-2.559724741,49.3014,-2.34E-11,9.999033934,-2.75125,-6.668154497,0.406363383,90.00000001 +286.14,50.43283629,-2.559723334,49.3291,-3.75E-12,9.999478044,-2.7815625,-6.629376484,0.305622964,90.00000001 +286.15,50.43283629,-2.559721926,49.3571,1.02E-11,10.00014419,-2.8096875,-6.589214033,0.204616063,90.00000001 +286.16,50.43283629,-2.559720519,49.3853,6.25E-12,10.00036626,-2.8365625,-6.547675453,0.103430685,90.00000001 +286.17,50.43283629,-2.559719111,49.4138,-4.69E-12,10.00036631,-2.863125,-6.504769508,0.002155123,90.00000001 +286.18,50.43283629,-2.559717704,49.4426,-6.25E-12,10.00036635,-2.8878125,-6.460505138,-0.099122272,90.00000001 +286.19,50.43283629,-2.559716296,49.4716,-7.81E-13,10.0003664,-2.9096875,-6.414891567,-0.200313264,90.00000001 +286.2,50.43283629,-2.559714889,49.5008,3.91E-12,10.00014441,-2.9303125,-6.367938363,-0.30132962,90.00000001 +286.21,50.43283629,-2.559713481,49.5302,1.25E-11,9.999478358,-2.9515625,-6.31965521,-0.402083159,90.00000001 +286.22,50.43283629,-2.559712074,49.5598,2.13E-11,9.999034338,-2.9728125,-6.270052363,-0.502486106,90.00000001 +286.23,50.43283629,-2.559710667,49.5897,1.41E-11,9.999478451,-2.99125,-6.21914002,-0.602450855,90.00000001 +286.24,50.43283629,-2.559709259,49.6197,-2.34E-12,10.0001446,-3.0065625,-6.166928955,-0.701890259,90.00000001 +286.25,50.43283629,-2.559707852,49.6498,-4.69E-12,10.00036668,-3.021875,-6.113429995,-0.800717571,90.00000001 +286.26,50.43283629,-2.559706444,49.6801,4.69E-12,10.00036672,-3.038125,-6.058654313,-0.898846735,90.00000001 +286.27,50.43283629,-2.559705037,49.7106,7.03E-12,10.00036677,-3.0528125,-6.002613311,-0.996192035,90.00000001 +286.28,50.43283629,-2.559703629,49.7412,5.55E-17,10.00036682,-3.064375,-5.945318792,-1.092668617,90.00000001 +286.29,50.43283629,-2.559702222,49.7719,-1.17E-11,10.00036687,-3.0734375,-5.886782673,-1.188192427,90.00000001 +286.3,50.43283629,-2.559700814,49.8027,-2.58E-11,10.00036692,-3.0815625,-5.827017159,-1.2826801,90.00000001 +286.31,50.43283629,-2.559699407,49.8335,-3.05E-11,10.00036696,-3.0896875,-5.76603474,-1.376049245,90.00000001 +286.32,50.43283629,-2.559697999,49.8645,-1.64E-11,10.00036701,-3.0965625,-5.703848193,-1.468218445,90.00000001 +286.33,50.43283629,-2.559696592,49.8955,4.69E-12,10.00014503,-3.10125,-5.640470409,-1.55910737,90.00000001 +286.34,50.43283629,-2.559695184,49.9265,1.41E-11,9.999478978,-3.105,-5.575914739,-1.648636667,90.00000001 +286.35,50.43283629,-2.559693777,49.9576,9.37E-12,9.999034961,-3.108125,-5.510194589,-1.736728412,90.00000001 +286.36,50.43283629,-2.55969237,49.9887,2.34E-12,9.999479076,-3.1096875,-5.44332371,-1.823305658,90.00000001 +286.37,50.43283629,-2.559690962,50.0198,2.34E-12,10.00014522,-3.1096875,-5.375316084,-1.908292946,90.00000001 +286.38,50.43283629,-2.559689555,50.0509,9.37E-12,10.0003673,-3.108125,-5.306185861,-1.991616193,90.00000001 +286.39,50.43283629,-2.559688147,50.082,1.63E-11,10.00036735,-3.1046875,-5.235947538,-2.07320269,90.00000001 +286.4,50.43283629,-2.55968674,50.113,1.80E-11,10.0003674,-3.1,-5.164615725,-2.152981391,90.00000001 +286.41,50.43283629,-2.559685332,50.144,1.95E-11,10.00036745,-3.0946875,-5.092205319,-2.230882623,90.00000001 +286.42,50.43283629,-2.559683925,50.1749,2.66E-11,10.0003675,-3.088125,-5.01873156,-2.306838435,90.00000001 +286.43,50.43283629,-2.559682517,50.2058,3.44E-11,10.00036755,-3.0796875,-4.944209633,-2.380782706,90.00000001 +286.44,50.43283629,-2.55968111,50.2365,3.50E-11,10.0003676,-3.0696875,-4.868655178,-2.452650923,90.00000001 +286.45,50.43283629,-2.559679702,50.2672,2.58E-11,10.00036764,-3.0584375,-4.79208401,-2.522380345,90.00000001 +286.46,50.43283629,-2.559678295,50.2977,9.22E-12,10.00014566,-3.04625,-4.714511999,-2.589910239,90.00000001 +286.47,50.43283629,-2.559676887,50.3281,-7.81E-12,9.999479606,-3.0334375,-4.635955474,-2.655181706,90.00000001 +286.48,50.43283629,-2.55967548,50.3584,-1.80E-11,9.999035587,-3.0196875,-4.556430823,-2.718137792,90.00000001 +286.49,50.43283629,-2.559674073,50.3885,-1.56E-11,9.999479701,-3.004375,-4.475954546,-2.77872361,90.00000001 +286.5,50.43283629,-2.559672665,50.4185,1.56E-12,10.00014585,-2.9865625,-4.394543603,-2.836886389,90.00000001 +286.51,50.43283629,-2.559671258,50.4483,2.09E-11,10.00036793,-2.9665625,-4.312214839,-2.892575309,90.00000001 +286.52,50.43283629,-2.55966985,50.4778,2.11E-11,10.00036797,-2.9465625,-4.228985558,-2.945741896,90.00000001 +286.53,50.43283629,-2.559668443,50.5072,2.34E-12,10.00036802,-2.9265625,-4.144873119,-2.996339742,90.00000001 +286.54,50.43283629,-2.559667035,50.5364,-1.42E-11,10.00036806,-2.904375,-4.059895055,-3.044324728,90.00000001 +286.55,50.43283629,-2.559665628,50.5653,-1.95E-11,10.00036811,-2.88,-3.974069129,-3.089654971,90.00000001 +286.56,50.43283629,-2.55966422,50.594,-2.03E-11,10.00036815,-2.855,-3.887413273,-3.132291053,90.00000001 +286.57,50.43283629,-2.559662813,50.6224,-1.80E-11,10.0003682,-2.8296875,-3.799945593,-3.17219573,90.00000001 +286.58,50.43283629,-2.559661405,50.6506,-1.27E-11,10.00036824,-2.8028125,-3.711684367,-3.209334166,90.00000001 +286.59,50.43283629,-2.559659998,50.6785,-1.50E-11,10.00014625,-2.773125,-3.622647986,-3.243674048,90.00000001 +286.6,50.43283629,-2.55965859,50.7061,-2.50E-11,9.999480197,-2.741875,-3.532855015,-3.275185409,90.00000001 +286.61,50.43283629,-2.559657183,50.7333,-2.25E-11,9.999036174,-2.7115625,-3.442324302,-3.30384069,90.00000001 +286.62,50.43283629,-2.559655776,50.7603,-4.69E-12,9.999480282,-2.68125,-3.3510747,-3.329615024,90.00000001 +286.63,50.43283629,-2.559654368,50.787,3.91E-12,10.00014642,-2.6478125,-3.259125287,-3.352485895,90.00000001 +286.64,50.43283629,-2.559652961,50.8133,-4.69E-12,10.0003685,-2.6115625,-3.166495201,-3.372433364,90.00000001 +286.65,50.43283629,-2.559651553,50.8392,-1.39E-11,10.00036854,-2.5753125,-3.073203863,-3.389439954,90.00000001 +286.66,50.43283629,-2.559650146,50.8648,-1.87E-11,10.00036858,-2.5396875,-2.979270699,-3.403490942,90.00000001 +286.67,50.43283629,-2.559648738,50.89,-2.66E-11,10.00036862,-2.503125,-2.884715359,-3.414574066,90.00000001 +286.68,50.43283629,-2.559647331,50.9149,-3.52E-11,10.00014662,-2.4646875,-2.789557612,-3.422679585,90.00000001 +286.69,50.43283629,-2.559645923,50.9393,-3.66E-11,9.999480562,-2.4246875,-2.693817281,-3.42780051,90.00000001 +286.7,50.43283629,-2.559644516,50.9634,-2.72E-11,9.999036533,-2.3834375,-2.597514363,-3.429932314,90.00000001 +286.71,50.43283629,-2.559643109,50.987,-9.38E-12,9.999480637,-2.34125,-2.500669026,-3.429073164,90.00000001 +286.72,50.43283629,-2.559641701,51.0102,8.44E-12,10.00014677,-2.2984375,-2.403301437,-3.425223804,90.00000001 +286.73,50.43283629,-2.559640294,51.033,1.80E-11,10.00036884,-2.2546875,-2.305431938,-3.418387616,90.00000001 +286.74,50.43283629,-2.559638886,51.0553,1.72E-11,10.00036888,-2.2096875,-2.207080982,-3.408570557,90.00000001 +286.75,50.43283629,-2.559637479,51.0772,7.19E-12,10.00014688,-2.1634375,-2.108269139,-3.395781165,90.00000001 +286.76,50.43283629,-2.559636071,51.0986,-7.03E-12,9.999480811,-2.1165625,-2.009016978,-3.380030555,90.00000001 +286.77,50.43283629,-2.559634664,51.1195,-1.17E-11,9.999036777,-2.0696875,-1.90934524,-3.361332593,90.00000001 +286.78,50.43283629,-2.559633257,51.14,2.34E-12,9.999480876,-2.0215625,-1.809274838,-3.339703436,90.00000001 +286.79,50.43283629,-2.559631849,51.16,2.34E-11,10.00014701,-1.97125,-1.708826513,-3.315161992,90.00000001 +286.8,50.43283629,-2.559630442,51.1794,3.50E-11,10.00036907,-1.9203125,-1.60802135,-3.287729747,90.00000001 +286.81,50.43283629,-2.559629034,51.1984,3.67E-11,10.0003691,-1.87,-1.506880376,-3.257430478,90.00000001 +286.82,50.43283629,-2.559627627,51.2168,3.12E-11,10.00014709,-1.819375,-1.405424734,-3.224290771,90.00000001 +286.83,50.43283629,-2.559626219,51.2348,1.50E-11,9.999481024,-1.7665625,-1.303675508,-3.188339388,90.00000001 +286.84,50.43283629,-2.559624812,51.2522,-2.34E-12,9.999036985,-1.7115625,-1.201654128,-3.149607671,90.00000001 +286.85,50.43283629,-2.559623405,51.269,-3.12E-12,9.999481078,-1.656875,-1.099381734,-3.108129537,90.00000001 +286.86,50.43283629,-2.559621997,51.2853,7.03E-12,10.0001472,-1.603125,-0.996879757,-3.063941027,90.00000001 +286.87,50.43283629,-2.55962059,51.3011,7.19E-12,10.00036926,-1.548125,-0.894169566,-3.017080699,90.00000001 +286.88,50.43283629,-2.559619182,51.3163,-6.88E-12,10.00036928,-1.49125,-0.791272706,-2.967589464,90.00000001 +286.89,50.43283629,-2.559617775,51.3309,-2.33E-11,10.00014727,-1.4334375,-0.688210547,-2.915510408,90.00000001 +286.9,50.43283629,-2.559616367,51.345,-3.05E-11,9.999481196,-1.375,-0.585004691,-2.860889024,90.00000001 +286.91,50.43283629,-2.55961496,51.3584,-2.64E-11,9.999037151,-1.316875,-0.481676623,-2.803772867,90.00000001 +286.92,50.43283629,-2.559613553,51.3713,-2.27E-11,9.999481238,-1.26,-0.378248001,-2.744211841,90.00000001 +286.93,50.43283629,-2.559612145,51.3836,-2.56E-11,10.00014736,-1.2028125,-0.274740425,-2.682257743,90.00000001 +286.94,50.43283629,-2.559610738,51.3954,-2.34E-11,10.00036941,-1.143125,-0.171175381,-2.617964716,90.00000001 +286.95,50.43283629,-2.55960933,51.4065,-1.17E-11,10.00036942,-1.0815625,-0.067574642,-2.551388797,90.00000001 +286.96,50.43283629,-2.559607923,51.417,-4.69E-12,10.00014741,-1.02,0.036040191,-2.482588025,90.00000001 +286.97,50.43283629,-2.559606515,51.4269,-1.17E-11,9.999481325,-0.9584375,0.139647519,-2.411622389,90.00000001 +286.98,50.43283629,-2.559605108,51.4362,-2.58E-11,9.999037273,-0.8965625,0.243225683,-2.338553769,90.00000001 +286.99,50.43283629,-2.559603701,51.4448,-3.27E-11,9.999481352,-0.835,0.346753084,-2.263445877,90.00000001 +287,50.43283629,-2.559602293,51.4529,-2.50E-11,10.00014746,-0.7734375,0.450208005,-2.186364261,90.00000001 +287.01,50.43283629,-2.559600886,51.4603,-7.66E-12,10.00036951,-0.71125,0.553568961,-2.107376127,90.00000001 +287.02,50.43283629,-2.559599478,51.4671,9.37E-12,10.00036952,-0.6484375,0.656814294,-2.026550289,90.00000001 +287.03,50.43283629,-2.559598071,51.4733,1.89E-11,10.00036953,-0.5846875,0.759922461,-1.943957277,90.00000001 +287.04,50.43283629,-2.559596663,51.4788,2.36E-11,10.00036954,-0.5203125,0.862871918,-1.859669112,90.00000001 +287.05,50.43283629,-2.559595256,51.4837,3.30E-11,10.00036955,-0.4565625,0.965641181,-1.773759304,90.00000001 +287.06,50.43283629,-2.559593848,51.4879,4.69E-11,10.00036955,-0.3934375,1.068208762,-1.68630274,90.00000001 +287.07,50.43283629,-2.559592441,51.4916,5.56E-11,10.00036956,-0.3296875,1.170553291,-1.59737568,90.00000001 +287.08,50.43283629,-2.559591033,51.4945,5.70E-11,10.00036956,-0.265,1.272653396,-1.507055701,90.00000001 +287.09,50.43283629,-2.559589626,51.4969,5.41E-11,10.00014753,-0.2003125,1.374487649,-1.41542153,90.00000001 +287.1,50.43283629,-2.559588218,51.4985,4.45E-11,9.999481437,-0.1365625,1.476034907,-1.322553093,90.00000001 +287.11,50.43283629,-2.559586811,51.4996,3.05E-11,9.999037373,-0.0734375,1.577273914,-1.228531349,90.00000001 +287.12,50.43283629,-2.559585404,51.5,1.87E-11,9.999481439,-0.009375,1.67818347,-1.133438346,90.00000001 +287.13,50.43283629,-2.559583996,51.4998,4.69E-12,10.00014754,0.05625,1.778742605,-1.03735699,90.00000001 +287.14,50.43283629,-2.559582589,51.4989,-1.88E-11,10.00036957,0.121875,1.878930291,-0.940370992,90.00000001 +287.15,50.43283629,-2.559581181,51.4973,-4.20E-11,10.00036957,0.18625,1.978725559,-0.842564976,90.00000001 +287.16,50.43283629,-2.559579774,51.4952,-5.08E-11,10.00036956,0.25,2.07810761,-0.744024257,90.00000001 +287.17,50.43283629,-2.559578366,51.4923,-4.05E-11,10.00036956,0.31375,2.177055645,-0.64483472,90.00000001 +287.18,50.43283629,-2.559576959,51.4889,-1.41E-11,10.00036955,0.3778125,2.275549095,-0.545082883,90.00000001 +287.19,50.43283629,-2.559575551,51.4848,1.89E-11,10.00036955,0.4421875,2.373567277,-0.444855777,90.00000001 +287.2,50.43283629,-2.559574144,51.48,4.47E-11,10.00036954,0.50625,2.471089736,-0.344240664,90.00000001 +287.21,50.43283629,-2.559572736,51.4747,5.41E-11,10.00036953,0.57,2.568096189,-0.243325435,90.00000001 +287.22,50.43283629,-2.559571329,51.4686,4.69E-11,10.00014749,0.6334375,2.664566353,-0.142197983,90.00000001 +287.23,50.43283629,-2.559569921,51.462,2.98E-11,9.99948138,0.69625,2.760480004,-0.040946543,90.00000001 +287.24,50.43283629,-2.559568514,51.4547,1.25E-11,9.999037302,0.7584375,2.855817201,0.060340592,90.00000001 +287.25,50.43283629,-2.559567107,51.4468,4.69E-12,9.999481355,0.82,2.95055795,0.16157513,90.00000001 +287.26,50.43283629,-2.559565699,51.4383,1.09E-11,10.00014744,0.8815625,3.04468254,0.262668777,90.00000001 +287.27,50.43283629,-2.559564292,51.4292,2.44E-11,10.00036946,0.9434375,3.138171261,0.363533356,90.00000001 +287.28,50.43283629,-2.559562884,51.4194,3.20E-11,10.00036945,1.005,3.231004691,0.464080917,90.00000001 +287.29,50.43283629,-2.559561477,51.4091,2.42E-11,10.00036943,1.06625,3.32316329,0.564223798,90.00000001 +287.3,50.43283629,-2.559560069,51.3981,1.41E-12,10.00036941,1.126875,3.414627924,0.663874681,90.00000001 +287.31,50.43283629,-2.559558662,51.3865,-2.27E-11,10.00036939,1.18625,3.505379454,0.762946647,90.00000001 +287.32,50.43283629,-2.559557254,51.3744,-3.28E-11,10.00036938,1.245,3.595398916,0.861353294,90.00000001 +287.33,50.43283629,-2.559555847,51.3616,-2.66E-11,10.00036936,1.3034375,3.684667516,0.959008851,90.00000001 +287.34,50.43283629,-2.559554439,51.3483,-1.34E-11,10.00036933,1.3615625,3.773166635,1.055828176,90.00000001 +287.35,50.43283629,-2.559553032,51.3344,-7.03E-12,10.00014728,1.42,3.860877821,1.151726757,90.00000001 +287.36,50.43283629,-2.559551624,51.3199,-1.19E-11,9.999481157,1.478125,3.947782627,1.246621001,90.00000001 +287.37,50.43283629,-2.559550217,51.3048,-1.89E-11,9.999037067,1.5346875,4.033863062,1.340428173,90.00000001 +287.38,50.43283629,-2.55954881,51.2892,-2.12E-11,9.999481109,1.59,4.119101019,1.43306651,90.00000001 +287.39,50.43283629,-2.559547402,51.273,-2.11E-11,10.00014718,1.645,4.203478794,1.524455169,90.00000001 +287.4,50.43283629,-2.559545995,51.2563,-1.81E-11,10.00036919,1.6996875,4.286978741,1.614514509,90.00000001 +287.41,50.43283629,-2.559544587,51.239,-1.02E-11,10.00036916,1.753125,4.369583385,1.703165919,90.00000001 +287.42,50.43283629,-2.55954318,51.2212,-4.69E-12,10.00036914,1.805,4.451275478,1.790332166,90.00000001 +287.43,50.43283629,-2.559541772,51.2029,-1.09E-11,10.00036911,1.8565625,4.532038004,1.875937217,90.00000001 +287.44,50.43283629,-2.559540365,51.1841,-2.42E-11,10.00036908,1.9084375,4.611854062,1.959906417,90.00000001 +287.45,50.43283629,-2.559538957,51.1647,-3.36E-11,10.00036905,1.9596875,4.690706977,2.042166597,90.00000001 +287.46,50.43283629,-2.55953755,51.1449,-3.45E-11,10.00014698,2.0096875,4.768580307,2.122645911,90.00000001 +287.47,50.43283629,-2.559536142,51.1245,-2.88E-11,9.999480851,2.058125,4.845457836,2.201274284,90.00000001 +287.48,50.43283629,-2.559534735,51.1037,-2.50E-11,9.999036752,2.105,4.921323349,2.277983077,90.00000001 +287.49,50.43283629,-2.559533328,51.0824,-3.20E-11,9.999480786,2.1515625,4.996161206,2.352705483,90.00000001 +287.5,50.43283629,-2.55953192,51.0607,-4.30E-11,10.00014685,2.198125,5.069955649,2.425376241,90.00000001 +287.51,50.43283629,-2.559530513,51.0384,-3.98E-11,10.00036885,2.2434375,5.142691266,2.495932097,90.00000001 +287.52,50.43283629,-2.559529105,51.0158,-1.56E-11,10.00036881,2.2878125,5.214352931,2.564311401,90.00000001 +287.53,50.43283629,-2.559527698,50.9927,1.56E-11,10.00014675,2.331875,5.284925632,2.630454623,90.00000001 +287.54,50.43283629,-2.55952629,50.9691,3.42E-11,9.999480609,2.374375,5.354394587,2.694304066,90.00000001 +287.55,50.43283629,-2.559524883,50.9452,3.52E-11,9.999036505,2.4146875,5.422745416,2.755803981,90.00000001 +287.56,50.43283629,-2.559523476,50.9208,2.42E-11,9.999480532,2.4534375,5.489963793,2.814900853,90.00000001 +287.57,50.43283629,-2.559522068,50.8961,9.38E-12,10.00014659,2.4915625,5.556035624,2.871543059,90.00000001 +287.58,50.43283629,-2.559520661,50.871,2.19E-12,10.00036859,2.53,5.620947101,2.925681269,90.00000001 +287.59,50.43283629,-2.559519253,50.8455,6.88E-12,10.00036855,2.568125,5.684684817,2.977268211,90.00000001 +287.6,50.43283629,-2.559517846,50.8196,1.39E-11,10.00014647,2.6046875,5.747235307,3.02625891,90.00000001 +287.61,50.43283629,-2.559516438,50.7934,1.41E-11,9.999480333,2.6396875,5.808585508,3.07261068,90.00000001 +287.62,50.43283629,-2.559515031,50.7668,7.81E-12,9.999036226,2.673125,5.868722757,3.116283128,90.00000001 +287.63,50.43283629,-2.559513624,50.7399,2.34E-12,9.99948025,2.7046875,5.927634335,3.157238093,90.00000001 +287.64,50.43283629,-2.559512216,50.7127,1.41E-12,10.00014631,2.735,5.985308037,3.195439883,90.00000001 +287.65,50.43283629,-2.559510809,50.6852,1.56E-12,10.0003683,2.765,6.041731775,3.230855206,90.00000001 +287.66,50.43283629,-2.559509401,50.6574,3.13E-12,10.00036825,2.7946875,6.096893745,3.263453239,90.00000001 +287.67,50.43283629,-2.559507994,50.6293,9.37E-12,10.00014618,2.823125,6.150782489,3.293205447,90.00000001 +287.68,50.43283629,-2.559506586,50.6009,1.56E-11,9.999480033,2.8496875,6.203386718,3.320085934,90.00000001 +287.69,50.43283629,-2.559505179,50.5723,1.48E-11,9.999035922,2.8746875,6.254695432,3.344071208,90.00000001 +287.7,50.43283629,-2.559503772,50.5434,7.81E-12,9.999479943,2.898125,6.304697917,3.36514047,90.00000001 +287.71,50.43283629,-2.559502364,50.5143,3.91E-12,10.000146,2.92,6.353383803,3.383275272,90.00000001 +287.72,50.43283629,-2.559500957,50.485,1.16E-11,10.00036798,2.9415625,6.400742832,3.3984598,90.00000001 +287.73,50.43283629,-2.559499549,50.4555,2.34E-11,10.00036794,2.963125,6.446765152,3.410680818,90.00000001 +287.74,50.43283629,-2.559498142,50.4257,2.58E-11,10.00036789,2.9828125,6.491441135,3.419927669,90.00000001 +287.75,50.43283629,-2.559496734,50.3958,2.11E-11,10.00036784,2.9996875,6.5347615,3.426192275,90.00000001 +287.76,50.43283629,-2.559495327,50.3657,1.87E-11,10.00014576,3.015,6.576717136,3.429469192,90.00000001 +287.77,50.43283629,-2.559493919,50.3355,1.64E-11,9.999479618,3.0296875,6.617299336,3.429755614,90.00000001 +287.78,50.43283629,-2.559492512,50.3051,7.03E-12,9.999035504,3.0434375,6.656499561,3.427051196,90.00000001 +287.79,50.43283629,-2.559491105,50.2746,-9.38E-12,9.999479522,3.05625,6.694309676,3.421358344,90.00000001 +287.8,50.43283629,-2.559489697,50.244,-2.34E-11,10.00014557,3.068125,6.730721774,3.412681987,90.00000001 +287.81,50.43283629,-2.55948829,50.2132,-2.34E-11,10.00036756,3.078125,6.765728235,3.401029745,90.00000001 +287.82,50.43283629,-2.559486882,50.1824,-9.38E-12,10.00036751,3.08625,6.799321782,3.386411758,90.00000001 +287.83,50.43283629,-2.559485475,50.1515,7.03E-12,10.00036746,3.0934375,6.831495368,3.368840746,90.00000001 +287.84,50.43283629,-2.559484067,50.1205,1.64E-11,10.00036741,3.0996875,6.862242231,3.348332123,90.00000001 +287.85,50.43283629,-2.55948266,50.0895,1.64E-11,10.00036737,3.1046875,6.89155607,3.32490365,90.00000001 +287.86,50.43283629,-2.559481252,50.0584,9.38E-12,10.00036732,3.108125,6.919430695,3.298575838,90.00000001 +287.87,50.43283629,-2.559479845,50.0273,2.34E-12,10.00014523,3.1096875,6.945860265,3.269371549,90.00000001 +287.88,50.43283629,-2.559478437,49.9962,2.34E-12,9.999479087,3.1096875,6.970839276,3.237316394,90.00000001 +287.89,50.43283629,-2.55947703,49.9651,9.38E-12,9.999034972,3.108125,6.994362517,3.202438218,90.00000001 +287.9,50.43283629,-2.559475623,49.934,1.41E-11,9.99947899,3.105,7.016425059,3.164767504,90.00000001 +287.91,50.43283629,-2.559474215,49.903,7.03E-12,10.00014504,3.1015625,7.037022376,3.124337023,90.00000001 +287.92,50.43283629,-2.559472808,49.872,-4.69E-12,10.00036702,3.098125,7.056150056,3.081182129,90.00000001 +287.93,50.43283629,-2.5594714,49.841,-7.03E-12,10.00036698,3.0928125,7.073804147,3.035340349,90.00000001 +287.94,50.43283629,-2.559469993,49.8101,-2.34E-12,10.00036693,3.0846875,7.08998098,2.986851732,90.00000001 +287.95,50.43283629,-2.559468585,49.7793,-2.22E-16,10.00036688,3.075,7.104677118,2.935758508,90.00000001 +287.96,50.43283629,-2.559467178,49.7486,2.34E-12,10.00036683,3.0646875,7.117889582,2.88210525,90.00000001 +287.97,50.43283629,-2.55946577,49.718,9.38E-12,10.00036678,3.053125,7.129615564,2.82593877,90.00000001 +287.98,50.43283629,-2.559464363,49.6875,1.41E-11,10.0001447,3.04,7.139852601,2.767308056,90.00000001 +287.99,50.43283629,-2.559462955,49.6572,4.69E-12,9.999478557,3.02625,7.148598573,2.706264216,90.00000001 +288,50.43283629,-2.559461548,49.627,-1.64E-11,9.999034443,3.0115625,7.155851646,2.64286042,90.00000001 +288.01,50.43283629,-2.559460141,49.5969,-3.05E-11,9.999478462,2.9946875,7.16161033,2.577152016,90.00000001 +288.02,50.43283629,-2.559458733,49.5671,-2.58E-11,10.00014451,2.9765625,7.165873365,2.509196357,90.00000001 +288.03,50.43283629,-2.559457326,49.5374,-1.41E-11,10.0003665,2.958125,7.168639949,2.439052571,90.00000001 +288.04,50.43283629,-2.559455918,49.5079,-1.16E-11,10.00036646,2.9378125,7.169909394,2.366781967,90.00000001 +288.05,50.43283629,-2.559454511,49.4786,-1.33E-11,10.00036641,2.915,7.169681586,2.292447454,90.00000001 +288.06,50.43283629,-2.559453103,49.4496,-5.47E-12,10.00036636,2.8915625,7.16795641,2.216113891,90.00000001 +288.07,50.43283629,-2.559451696,49.4208,6.25E-12,10.00036632,2.868125,7.164734325,2.137847799,90.00000001 +288.08,50.43283629,-2.559450288,49.3922,5.62E-12,10.00036627,2.843125,7.16001596,2.057717531,90.00000001 +288.09,50.43283629,-2.559448881,49.3639,-8.44E-12,10.00036623,2.81625,7.15380229,1.975792875,90.00000001 +288.1,50.43283629,-2.559447473,49.3359,-2.42E-11,10.00036619,2.7884375,7.14609469,1.892145334,90.00000001 +288.11,50.43283629,-2.559446066,49.3081,-3.38E-11,10.00014411,2.7596875,7.136894707,1.806847789,90.00000001 +288.12,50.43283629,-2.559444658,49.2807,-3.52E-11,9.999477968,2.7296875,7.126204288,1.719974668,90.00000001 +288.13,50.43283629,-2.559443251,49.2535,-2.95E-11,9.999033859,2.698125,7.114025612,1.631601657,90.00000001 +288.14,50.43283629,-2.559441844,49.2267,-2.25E-11,9.999477883,2.6646875,7.100361313,1.541805935,90.00000001 +288.15,50.43283629,-2.559440436,49.2002,-1.88E-11,10.00014394,2.63,7.085214143,1.450665654,90.00000001 +288.16,50.43283629,-2.559439029,49.1741,-1.48E-11,10.00036593,2.5946875,7.068587366,1.358260453,90.00000001 +288.17,50.43283629,-2.559437621,49.1483,-4.69E-12,10.00036589,2.5584375,7.050484363,1.264670776,90.00000001 +288.18,50.43283629,-2.559436214,49.1229,1.19E-11,10.00036585,2.52125,7.030908974,1.169978271,90.00000001 +288.19,50.43283629,-2.559434806,49.0979,2.81E-11,10.00036581,2.4834375,7.009865323,1.074265556,90.00000001 +288.2,50.43283629,-2.559433399,49.0732,3.67E-11,10.00036578,2.4446875,6.98735765,0.977616056,90.00000001 +288.21,50.43283629,-2.559431991,49.049,3.52E-11,10.00036574,2.4046875,6.963390825,0.880114109,90.00000001 +288.22,50.43283629,-2.559430584,49.0251,2.44E-11,10.0003657,2.3634375,6.937969776,0.781844628,90.00000001 +288.23,50.43283629,-2.559429176,49.0017,7.81E-12,10.00036566,2.32125,6.911099832,0.682893385,90.00000001 +288.24,50.43283629,-2.559427769,48.9787,-5.47E-12,10.00014359,2.278125,6.882786549,0.583346666,90.00000001 +288.25,50.43283629,-2.559426361,48.9561,-4.84E-12,9.99947746,2.233125,6.853035888,0.483291218,90.00000001 +288.26,50.43283629,-2.559424954,48.934,7.03E-12,9.999033359,2.1865625,6.821854092,0.38281436,90.00000001 +288.27,50.43283629,-2.559423547,48.9124,1.41E-11,9.999477391,2.14,6.789247637,0.282003696,90.00000001 +288.28,50.43283629,-2.559422139,48.8912,7.03E-12,10.00014346,2.0934375,6.755223341,0.180947119,90.00000001 +288.29,50.43283629,-2.559420732,48.8705,-9.38E-12,10.00036546,2.04625,6.71978825,0.079732749,90.00000001 +288.3,50.43283629,-2.559419324,48.8503,-2.34E-11,10.00036543,1.998125,6.682949871,-0.021551177,90.00000001 +288.31,50.43283629,-2.559417917,48.8305,-2.34E-11,10.00014336,1.948125,6.644715825,-0.122816311,90.00000001 +288.32,50.43283629,-2.559416509,48.8113,-1.17E-11,9.999477234,1.8965625,6.605094132,-0.223974301,90.00000001 +288.33,50.43283629,-2.559415102,48.7926,-4.84E-12,9.999033139,1.845,6.564093043,-0.324937028,90.00000001 +288.34,50.43283629,-2.559413695,48.7744,-1.02E-11,9.999477176,1.793125,6.521721095,-0.42561637,90.00000001 +288.35,50.43283629,-2.559412287,48.7567,-1.81E-11,10.00014325,1.7396875,6.477987169,-0.525924606,90.00000001 +288.36,50.43283629,-2.55941088,48.7396,-2.11E-11,10.00036525,1.685,6.432900432,-0.625774191,90.00000001 +288.37,50.43283629,-2.559409472,48.723,-2.12E-11,10.00036523,1.63,6.386470282,-0.72507809,90.00000001 +288.38,50.43283629,-2.559408065,48.707,-2.12E-11,10.00014317,1.575,6.338706343,-0.82374973,90.00000001 +288.39,50.43283629,-2.559406657,48.6915,-2.12E-11,9.999477045,1.52,6.289618699,-0.921703053,90.00000001 +288.4,50.43283629,-2.55940525,48.6766,-1.87E-11,9.999032956,1.4646875,6.239217493,-1.018852631,90.00000001 +288.41,50.43283629,-2.559403843,48.6622,-1.09E-11,9.999477,1.408125,6.18751338,-1.115113723,90.00000001 +288.42,50.43283629,-2.559402435,48.6484,-2.34E-12,10.00014308,1.3496875,6.134517019,-1.210402448,90.00000001 +288.43,50.43283629,-2.559401028,48.6352,1.41E-12,10.00036509,1.29,6.080239581,-1.304635728,90.00000001 +288.44,50.43283629,-2.55939962,48.6226,1.56E-12,10.00036507,1.23,6.024692354,-1.397731286,90.00000001 +288.45,50.43283629,-2.559398213,48.6106,3.12E-12,10.00014302,1.1703125,5.967886912,-1.489607991,90.00000001 +288.46,50.43283629,-2.559396805,48.5992,1.19E-11,9.999476902,1.1115625,5.909835229,-1.5801858,90.00000001 +288.47,50.43283629,-2.559395398,48.5884,2.11E-11,9.999032819,1.0528125,5.850549281,-1.669385588,90.00000001 +288.48,50.43283629,-2.559393991,48.5781,1.17E-11,9.999476868,0.9915625,5.790041557,-1.75712972,90.00000001 +288.49,50.43283629,-2.559392583,48.5685,-1.19E-11,10.00014295,0.9284375,5.728324663,-1.843341534,90.00000001 +288.5,50.43283629,-2.559391176,48.5596,-1.95E-11,10.00036497,0.866875,5.665411434,-1.927945971,90.00000001 +288.51,50.43283629,-2.559389768,48.5512,-3.91E-12,10.00036496,0.8065625,5.601315104,-2.010869236,90.00000001 +288.52,50.43283629,-2.559388361,48.5434,1.27E-11,10.00036495,0.744375,5.536048966,-2.092038964,90.00000001 +288.53,50.43283629,-2.559386953,48.5363,1.87E-11,10.00036494,0.68,5.469626713,-2.171384394,90.00000001 +288.54,50.43283629,-2.559385546,48.5298,1.80E-11,10.00014289,0.6153125,5.402062212,-2.248836313,90.00000001 +288.55,50.43283629,-2.559384138,48.524,1.17E-11,9.999476784,0.551875,5.333369557,-2.324327284,90.00000001 +288.56,50.43283629,-2.559382731,48.5188,7.19E-12,9.99903271,0.49,5.26356313,-2.39779136,90.00000001 +288.57,50.43283629,-2.559381324,48.5142,9.37E-12,9.999476768,0.4278125,5.192657425,-2.46916454,90.00000001 +288.58,50.43283629,-2.559379916,48.5102,3.91E-12,10.00014286,0.3634375,5.120667341,-2.538384603,90.00000001 +288.59,50.43283629,-2.559378509,48.5069,-1.87E-11,10.00036489,0.298125,5.047607831,-2.6053911,90.00000001 +288.6,50.43283629,-2.559377101,48.5043,-4.36E-11,10.00036489,0.23375,4.973494193,-2.670125705,90.00000001 +288.61,50.43283629,-2.559375694,48.5022,-5.31E-11,10.00036488,0.17,4.898341955,-2.732531867,90.00000001 +288.62,50.43283629,-2.559374286,48.5009,-4.30E-11,10.00036488,0.10625,4.8221667,-2.79255527,90.00000001 +288.63,50.43283629,-2.559372879,48.5001,-1.89E-11,10.00014285,0.041875,4.744984415,-2.850143487,90.00000001 +288.64,50.43283629,-2.559371471,48.5,2.50E-12,9.999476747,-0.0234375,4.666811199,-2.905246385,90.00000001 +288.65,50.43283629,-2.559370064,48.5006,5.47E-12,9.999032681,-0.088125,4.587663383,-2.957815836,90.00000001 +288.66,50.43283629,-2.559368657,48.5018,-3.13E-12,9.999476749,-0.151875,4.507557523,-3.007806002,90.00000001 +288.67,50.43283629,-2.559367249,48.5036,-9.38E-13,10.00014285,-0.2165625,4.426510294,-3.05517334,90.00000001 +288.68,50.43283629,-2.559365842,48.5061,1.64E-11,10.00036489,-0.2815625,4.344538654,-3.099876538,90.00000001 +288.69,50.43283629,-2.559364434,48.5093,2.67E-11,10.00036489,-0.345,4.261659679,-3.141876579,90.00000001 +288.7,50.43283629,-2.559363027,48.513,1.50E-11,10.0003649,-0.4084375,4.177890728,-3.181136851,90.00000001 +288.71,50.43283629,-2.559361619,48.5174,-2.50E-12,10.00036491,-0.4734375,4.093249278,-3.217623147,90.00000001 +288.72,50.43283629,-2.559360212,48.5225,-6.41E-12,10.00036491,-0.5378125,4.007753031,-3.251303611,90.00000001 +288.73,50.43283629,-2.559358804,48.5282,-4.84E-12,10.00036492,-0.6,3.921419808,-3.282148909,90.00000001 +288.74,50.43283629,-2.559357397,48.5345,-1.08E-11,10.00036493,-0.661875,3.834267599,-3.31013211,90.00000001 +288.75,50.43283629,-2.559355989,48.5414,-1.56E-11,10.00036494,-0.725,3.746314681,-3.335228808,90.00000001 +288.76,50.43283629,-2.559354582,48.549,-7.81E-12,10.00014292,-0.7884375,3.657579447,-3.357417171,90.00000001 +288.77,50.43283629,-2.559353174,48.5572,9.22E-12,9.999476836,-0.85125,3.568080288,-3.376677778,90.00000001 +288.78,50.43283629,-2.559351767,48.566,2.58E-11,9.999032784,-0.9134375,3.477836055,-3.392993897,90.00000001 +288.79,50.43283629,-2.55935036,48.5755,3.52E-11,9.999476864,-0.9746875,3.386865483,-3.406351319,90.00000001 +288.8,50.43283629,-2.559348952,48.5855,3.75E-11,10.00014298,-1.035,3.295187595,-3.416738299,90.00000001 +288.81,50.43283629,-2.559347545,48.5962,3.75E-11,10.00036503,-1.095,3.202821584,-3.424145841,90.00000001 +288.82,50.43283629,-2.559346137,48.6074,3.75E-11,10.00036505,-1.155,3.109786646,-3.428567471,90.00000001 +288.83,50.43283629,-2.55934473,48.6193,3.73E-11,10.00036506,-1.215,3.016102317,-3.42999935,90.00000001 +288.84,50.43283629,-2.559343322,48.6317,3.44E-11,10.00036508,-1.2746875,2.921788135,-3.42844016,90.00000001 +288.85,50.43283629,-2.559341915,48.6448,2.41E-11,10.0003651,-1.3334375,2.826863753,-3.423891391,90.00000001 +288.86,50.43283629,-2.559340507,48.6584,7.03E-12,10.00036513,-1.39125,2.731348996,-3.416356938,90.00000001 +288.87,50.43283629,-2.5593391,48.6726,-9.53E-12,10.00014312,-1.4484375,2.635263859,-3.405843335,90.00000001 +288.88,50.43283629,-2.559337692,48.6874,-1.89E-11,9.999477039,-1.5046875,2.538628339,-3.392359804,90.00000001 +288.89,50.43283629,-2.559336285,48.7027,-2.13E-11,9.999032998,-1.56,2.441462718,-3.375918093,90.00000001 +288.9,50.43283629,-2.559334878,48.7186,-2.11E-11,9.999477089,-1.615,2.343787165,-3.356532524,90.00000001 +288.91,50.43283629,-2.55933347,48.735,-2.03E-11,10.00014321,-1.67,2.245622192,-3.334220001,90.00000001 +288.92,50.43283629,-2.559332063,48.752,-1.88E-11,10.00036527,-1.725,2.146988195,-3.308999946,90.00000001 +288.93,50.43283629,-2.559330655,48.7695,-1.27E-11,10.0003653,-1.779375,2.047905916,-3.280894475,90.00000001 +288.94,50.43283629,-2.559329248,48.7876,3.91E-12,10.00036533,-1.8315625,1.948395866,-3.249927997,90.00000001 +288.95,50.43283629,-2.55932784,48.8062,2.19E-11,10.00036536,-1.8815625,1.84847896,-3.216127498,90.00000001 +288.96,50.43283629,-2.559326433,48.8252,2.36E-11,10.00036539,-1.931875,1.748176051,-3.179522485,90.00000001 +288.97,50.43283629,-2.559325025,48.8448,1.41E-11,10.00036542,-1.983125,1.647507997,-3.140144929,90.00000001 +288.98,50.43283629,-2.559323618,48.8649,1.41E-11,10.00036545,-2.033125,1.546495939,-3.098029093,90.00000001 +288.99,50.43283629,-2.55932221,48.8855,2.58E-11,10.00036548,-2.0815625,1.445160904,-3.053211704,90.00000001 +289,50.43283629,-2.559320803,48.9065,3.06E-11,10.00014348,-2.1296875,1.343524036,-3.005731895,90.00000001 +289.01,50.43283629,-2.559319395,48.9281,1.72E-11,9.999477416,-2.1765625,1.241606589,-2.955631033,90.00000001 +289.02,50.43283629,-2.559317988,48.9501,-3.12E-12,9.999033385,-2.22125,1.13942988,-2.902952835,90.00000001 +289.03,50.43283629,-2.559316581,48.9725,-1.25E-11,9.999477486,-2.265,1.037015164,-2.847743252,90.00000001 +289.04,50.43283629,-2.559315173,48.9954,-6.09E-12,10.00014362,-2.3084375,0.934383927,-2.790050356,90.00000001 +289.05,50.43283629,-2.559313766,49.0187,1.03E-11,10.00036569,-2.35125,0.83155754,-2.729924451,90.00000001 +289.06,50.43283629,-2.559312358,49.0424,2.52E-11,10.00036573,-2.393125,0.728557548,-2.667418079,90.00000001 +289.07,50.43283629,-2.559310951,49.0666,2.34E-11,10.00036576,-2.4334375,0.62540532,-2.60258567,90.00000001 +289.08,50.43283629,-2.559309543,49.0911,1.57E-13,10.0003658,-2.4728125,0.522122516,-2.535483717,90.00000001 +289.09,50.43283629,-2.559308136,49.116,-3.03E-11,10.00014381,-2.511875,0.418730677,-2.466170836,90.00000001 +289.1,50.43283629,-2.559306728,49.1414,-4.67E-11,9.999477749,-2.5496875,0.315251406,-2.394707414,90.00000001 +289.11,50.43283629,-2.559305321,49.167,-3.97E-11,9.999033724,-2.58625,0.211706301,-2.321155733,90.00000001 +289.12,50.43283629,-2.559303914,49.1931,-1.86E-11,9.999477831,-2.6215625,0.108116964,-2.245579965,90.00000001 +289.13,50.43283629,-2.559302506,49.2195,-4.69E-12,10.00014397,-2.6546875,0.004505053,-2.168046055,90.00000001 +289.14,50.43283629,-2.559301099,49.2462,-7.81E-12,10.00036605,-2.686875,-0.099107833,-2.088621557,90.00000001 +289.15,50.43283629,-2.559299691,49.2732,-1.17E-11,10.00036609,-2.7196875,-0.202699977,-2.007375798,90.00000001 +289.16,50.43283629,-2.559298284,49.3006,-1.41E-12,10.0001441,-2.75125,-0.30624978,-1.924379538,90.00000001 +289.17,50.43283629,-2.559296876,49.3283,1.02E-11,9.999478042,-2.7796875,-0.409735641,-1.8397052,90.00000001 +289.18,50.43283629,-2.559295469,49.3562,8.59E-12,9.999034019,-2.806875,-0.513135959,-1.753426579,90.00000001 +289.19,50.43283629,-2.559294062,49.3844,4.69E-12,9.99947813,-2.835,-0.616429077,-1.665618964,90.00000001 +289.2,50.43283629,-2.559292654,49.4129,7.81E-12,10.00014427,-2.8628125,-0.719593509,-1.5763589,90.00000001 +289.21,50.43283629,-2.559291247,49.4417,8.59E-12,10.00036635,-2.8878125,-0.822607596,-1.485724253,90.00000001 +289.22,50.43283629,-2.559289839,49.4707,3.91E-12,10.0003664,-2.9096875,-0.925449968,-1.393794035,90.00000001 +289.23,50.43283629,-2.559288432,49.4999,-1.56E-12,10.00036644,-2.9303125,-1.028099024,-1.300648401,90.00000001 +289.24,50.43283629,-2.559287024,49.5293,-1.16E-11,10.00036649,-2.9515625,-1.130533392,-1.206368539,90.00000001 +289.25,50.43283629,-2.559285617,49.5589,-2.11E-11,10.0001445,-2.9728125,-1.232731645,-1.111036727,90.00000001 +289.26,50.43283629,-2.559284209,49.5888,-1.41E-11,9.99947845,-2.99125,-1.334672468,-1.014736101,90.00000001 +289.27,50.43283629,-2.559282802,49.6188,2.34E-12,9.99903443,-3.0065625,-1.436334547,-0.917550599,90.00000001 +289.28,50.43283629,-2.559281395,49.6489,2.34E-12,9.999478543,-3.0215625,-1.537696682,-0.819564961,90.00000001 +289.29,50.43283629,-2.559279987,49.6792,-1.64E-11,10.00014469,-3.0365625,-1.638737732,-0.720864673,90.00000001 +289.3,50.43283629,-2.55927858,49.7097,-3.05E-11,10.00036677,-3.0496875,-1.739436497,-0.621535793,90.00000001 +289.31,50.43283629,-2.559277172,49.7402,-2.58E-11,10.00036682,-3.0615625,-1.839772007,-0.521664894,90.00000001 +289.32,50.43283629,-2.559275765,49.7709,-1.41E-11,10.00014483,-3.073125,-1.939723291,-0.421339068,90.00000001 +289.33,50.43283629,-2.559274357,49.8017,-1.17E-11,9.999478783,-3.0828125,-2.039269551,-0.320645861,90.00000001 +289.34,50.43283629,-2.55927295,49.8326,-1.41E-11,9.999034765,-3.09,-2.138389874,-0.21967305,90.00000001 +289.35,50.43283629,-2.559271543,49.8635,-7.03E-12,9.999478879,-3.0965625,-2.237063635,-0.1185087,90.00000001 +289.36,50.43283629,-2.559270135,49.8945,2.34E-12,10.00014503,-3.1028125,-2.335270205,-0.017240988,90.00000001 +289.37,50.43283629,-2.559268728,49.9256,-4.69E-12,10.00036711,-3.10625,-2.432989131,0.084041736,90.00000001 +289.38,50.43283629,-2.55926732,49.9567,-2.11E-11,10.00036716,-3.1065625,-2.530199901,0.185251235,90.00000001 +289.39,50.43283629,-2.559265913,49.9877,-2.34E-11,10.00014517,-3.106875,-2.626882289,0.286299161,90.00000001 +289.4,50.43283629,-2.559264505,50.0188,-1.17E-11,9.999479121,-3.1084375,-2.723016127,0.387097391,90.00000001 +289.41,50.43283629,-2.559263098,50.0499,2.34E-12,9.999035104,-3.1090625,-2.818581247,0.487558092,90.00000001 +289.42,50.43283629,-2.559261691,50.081,2.11E-11,9.999479219,-3.1065625,-2.913557768,0.587593658,90.00000001 +289.43,50.43283629,-2.559260283,50.1121,4.22E-11,10.00014537,-3.10125,-3.007925808,0.687116828,90.00000001 +289.44,50.43283629,-2.559258876,50.143,5.16E-11,10.00036745,-3.095,-3.101665714,0.786040799,90.00000001 +289.45,50.43283629,-2.559257468,50.174,4.69E-11,10.0003675,-3.088125,-3.194757834,0.884279341,90.00000001 +289.46,50.43283629,-2.559256061,50.2048,3.98E-11,10.00036755,-3.0796875,-3.287182801,0.981746795,90.00000001 +289.47,50.43283629,-2.559254653,50.2356,3.75E-11,10.00036759,-3.07,-3.378921309,1.078358137,90.00000001 +289.48,50.43283629,-2.559253246,50.2662,3.52E-11,10.00036764,-3.0596875,-3.469954104,1.17402914,90.00000001 +289.49,50.43283629,-2.559251838,50.2968,2.81E-11,10.00036769,-3.048125,-3.560262279,1.268676324,90.00000001 +289.5,50.43283629,-2.559250431,50.3272,2.11E-11,10.00036774,-3.0346875,-3.649826927,1.362217242,90.00000001 +289.51,50.43283629,-2.559249023,50.3575,1.88E-11,10.00036778,-3.02,-3.738629369,1.454570304,90.00000001 +289.52,50.43283629,-2.559247616,50.3876,1.41E-11,10.0001458,-3.004375,-3.826651042,1.545654951,90.00000001 +289.53,50.43283629,-2.559246208,50.4176,-2.34E-12,9.999479746,-2.9865625,-3.91387361,1.635391773,90.00000001 +289.54,50.43283629,-2.559244801,50.4474,-2.11E-11,9.999035726,-2.9665625,-4.000278739,1.723702503,90.00000001 +289.55,50.43283629,-2.559243394,50.4769,-2.11E-11,9.999479839,-2.9465625,-4.085848496,1.810510078,90.00000001 +289.56,50.43283629,-2.559241986,50.5063,-2.34E-12,10.00014598,-2.9265625,-4.170565005,1.895738925,90.00000001 +289.57,50.43283629,-2.559240579,50.5355,1.19E-11,10.00036806,-2.9046875,-4.254410502,1.979314674,90.00000001 +289.58,50.43283629,-2.559239171,50.5644,5.47E-12,10.00036811,-2.88125,-4.337367515,2.061164388,90.00000001 +289.59,50.43283629,-2.559237764,50.5931,-1.48E-11,10.00036815,-2.8565625,-4.419418795,2.141216734,90.00000001 +289.6,50.43283629,-2.559236356,50.6216,-2.89E-11,10.0003682,-2.8296875,-4.500547041,2.219401924,90.00000001 +289.61,50.43283629,-2.559234949,50.6497,-2.48E-11,10.00036824,-2.8015625,-4.580735463,2.295651778,90.00000001 +289.62,50.43283629,-2.559233541,50.6776,-1.08E-11,10.00036828,-2.7734375,-4.659967276,2.369899774,90.00000001 +289.63,50.43283629,-2.559232134,50.7052,-6.25E-13,10.00036833,-2.7446875,-4.738225862,2.442081169,90.00000001 +289.64,50.43283629,-2.559230726,50.7325,6.25E-23,10.00036837,-2.7146875,-4.815494951,2.512133052,90.00000001 +289.65,50.43283629,-2.559229319,50.7595,-4.69E-12,10.00014638,-2.6828125,-4.891758383,2.579994345,90.00000001 +289.66,50.43283629,-2.559227911,50.7862,-3.12E-12,9.999480322,-2.648125,-4.967000232,2.645605805,90.00000001 +289.67,50.43283629,-2.559226504,50.8125,4.69E-12,9.999036297,-2.611875,-5.041204798,2.70891025,90.00000001 +289.68,50.43283629,-2.559225097,50.8384,7.81E-13,9.999480404,-2.5765625,-5.114356555,2.769852505,90.00000001 +289.69,50.43283629,-2.559223689,50.864,-1.86E-11,10.00014654,-2.5415625,-5.18644026,2.828379399,90.00000001 +289.7,50.43283629,-2.559222282,50.8893,-3.20E-11,10.00036862,-2.5046875,-5.257440846,2.884439938,90.00000001 +289.71,50.43283629,-2.559220874,50.9141,-2.34E-11,10.00036865,-2.46625,-5.327343474,2.937985136,90.00000001 +289.72,50.43283629,-2.559219467,50.9386,-9.38E-13,10.00036869,-2.4265625,-5.396133531,2.98896841,90.00000001 +289.73,50.43283629,-2.559218059,50.9627,1.31E-11,10.00036873,-2.3846875,-5.463796696,3.037345242,90.00000001 +289.74,50.43283629,-2.559216652,50.9863,7.03E-12,10.00036877,-2.3415625,-5.530318815,3.08307352,90.00000001 +289.75,50.43283629,-2.559215244,51.0095,-8.44E-12,10.0003688,-2.2984375,-5.595686022,3.12611325,90.00000001 +289.76,50.43283629,-2.559213837,51.0323,-1.56E-11,10.00014681,-2.255,-5.659884626,3.166426961,90.00000001 +289.77,50.43283629,-2.559212429,51.0546,-5.47E-12,9.999480742,-2.21125,-5.722901217,3.203979532,90.00000001 +289.78,50.43283629,-2.559211022,51.0765,1.63E-11,9.999036711,-2.1665625,-5.784722675,3.238738189,90.00000001 +289.79,50.43283629,-2.559209615,51.098,3.05E-11,9.99948081,-2.1196875,-5.845336052,3.270672564,90.00000001 +289.8,50.43283629,-2.559208207,51.1189,2.58E-11,10.00014694,-2.0715625,-5.904728743,3.299754928,90.00000001 +289.81,50.43283629,-2.5592068,51.1394,1.41E-11,10.00036901,-2.023125,-5.962888256,3.32595984,90.00000001 +289.82,50.43283629,-2.559205392,51.1594,1.41E-11,10.00036904,-1.973125,-6.019802503,3.34926444,90.00000001 +289.83,50.43283629,-2.559203985,51.1789,2.59E-11,10.00036907,-1.9215625,-6.075459623,3.369648445,90.00000001 +289.84,50.43283629,-2.559202577,51.1978,3.36E-11,10.0003691,-1.87,-6.129847929,3.387094036,90.00000001 +289.85,50.43283629,-2.55920117,51.2163,2.73E-11,10.00036913,-1.8184375,-6.182956131,3.401586087,90.00000001 +289.86,50.43283629,-2.559199762,51.2342,1.08E-11,10.00036916,-1.76625,-6.234773059,3.413111877,90.00000001 +289.87,50.43283629,-2.559198355,51.2516,-7.03E-12,10.00014715,-1.7134375,-6.285287998,3.421661382,90.00000001 +289.88,50.43283629,-2.559196947,51.2685,-1.80E-11,9.999481077,-1.6596875,-6.33449029,3.427227151,90.00000001 +289.89,50.43283629,-2.55919554,51.2848,-2.11E-11,9.999037036,-1.605,-6.38236968,3.429804315,90.00000001 +289.9,50.43283629,-2.559194133,51.3006,-2.36E-11,9.999481127,-1.5496875,-6.428916256,3.429390697,90.00000001 +289.91,50.43283629,-2.559192725,51.3158,-3.06E-11,10.00014725,-1.493125,-6.474120162,3.425986526,90.00000001 +289.92,50.43283629,-2.559191318,51.3305,-3.30E-11,10.00036931,-1.4353125,-6.51797206,3.419594895,90.00000001 +289.93,50.43283629,-2.55918991,51.3445,-1.64E-11,10.00036933,-1.378125,-6.560462782,3.410221305,90.00000001 +289.94,50.43283629,-2.559188503,51.358,1.00E-11,10.00036935,-1.3215625,-6.601583447,3.397873893,90.00000001 +289.95,50.43283629,-2.559187095,51.371,2.03E-11,10.00036937,-1.2628125,-6.641325462,3.382563544,90.00000001 +289.96,50.43283629,-2.559185688,51.3833,1.39E-11,10.00014736,-1.201875,-6.67968046,3.364303551,90.00000001 +289.97,50.43283629,-2.55918428,51.395,1.41E-11,9.999481275,-1.141875,-6.716640535,3.343109842,90.00000001 +289.98,50.43283629,-2.559182873,51.4061,2.34E-11,9.999037226,-1.083125,-6.752197894,3.319000867,90.00000001 +289.99,50.43283629,-2.559181466,51.4167,2.34E-11,9.999481309,-1.023125,-6.786345205,3.29199771,90.00000001 +290,50.43283629,-2.559180058,51.4266,9.37E-12,10.00014742,-0.96125,-6.819075247,3.262123862,90.00000001 +290.01,50.43283629,-2.559178651,51.4359,-9.38E-12,10.00036947,-0.89875,-6.850381202,3.229405394,90.00000001 +290.02,50.43283629,-2.559177243,51.4446,-2.59E-11,10.00036948,-0.8365625,-6.88025654,3.193870838,90.00000001 +290.03,50.43283629,-2.559175836,51.4526,-3.36E-11,10.00014746,-0.775,-6.908695013,3.155551134,90.00000001 +290.04,50.43283629,-2.559174428,51.4601,-2.98E-11,9.999481377,-0.713125,-6.935690722,3.1144798,90.00000001 +290.05,50.43283629,-2.559173021,51.4669,-2.34E-11,9.999037322,-0.6496875,-6.961237936,3.070692589,90.00000001 +290.06,50.43283629,-2.559171614,51.4731,-1.89E-11,9.999481397,-0.5853125,-6.985331442,3.02422766,90.00000001 +290.07,50.43283629,-2.559170206,51.4786,-1.19E-11,10.0001475,-0.521875,-7.007966139,2.975125578,90.00000001 +290.08,50.43283629,-2.559168799,51.4835,-9.53E-12,10.00036955,-0.4596875,-7.029137331,2.923429143,90.00000001 +290.09,50.43283629,-2.559167391,51.4878,-2.34E-11,10.00036955,-0.3965625,-7.048840547,2.869183447,90.00000001 +290.1,50.43283629,-2.559165984,51.4915,-4.16E-11,10.00014752,-0.3315625,-7.067071721,2.812435759,90.00000001 +290.11,50.43283629,-2.559164576,51.4944,-4.30E-11,9.99948143,-0.266875,-7.083827069,2.753235583,90.00000001 +290.12,50.43283629,-2.559163169,51.4968,-3.06E-11,9.999037368,-0.2034375,-7.099102983,2.691634541,90.00000001 +290.13,50.43283629,-2.559161762,51.4985,-2.11E-11,9.999481437,-0.1396875,-7.112896369,2.627686378,90.00000001 +290.14,50.43283629,-2.559160354,51.4996,-1.87E-11,10.00014754,-0.075,-7.125204305,2.561446784,90.00000001 +290.15,50.43283629,-2.559158947,51.5,-1.87E-11,10.00036957,-0.01,-7.136024269,2.492973629,90.00000001 +290.16,50.43283629,-2.559157539,51.4998,-1.87E-11,10.00036957,0.055,-7.145353913,2.422326501,90.00000001 +290.17,50.43283629,-2.559156132,51.4989,-1.88E-11,10.00014754,0.12,-7.153191403,2.349567106,90.00000001 +290.18,50.43283629,-2.559154724,51.4974,-1.66E-11,9.999481435,0.1846875,-7.159534962,2.274758872,90.00000001 +290.19,50.43283629,-2.559153317,51.4952,-7.81E-12,9.999037365,0.2484375,-7.164383388,2.197967,90.00000001 +290.2,50.43283629,-2.55915191,51.4924,5.47E-12,9.999481427,0.3115625,-7.16773565,2.11925847,90.00000001 +290.21,50.43283629,-2.559150502,51.489,1.50E-11,10.00014752,0.3753125,-7.169591002,2.038701922,90.00000001 +290.22,50.43283629,-2.559149095,51.4849,1.86E-11,10.00036955,0.44,-7.169949043,1.9563676,90.00000001 +290.23,50.43283629,-2.559147687,51.4802,1.70E-11,10.00036954,0.5046875,-7.168809774,1.872327239,90.00000001 +290.24,50.43283629,-2.55914628,51.4748,9.22E-12,10.00036953,0.568125,-7.166173366,1.786654235,90.00000001 +290.25,50.43283629,-2.559144872,51.4688,3.28E-12,10.00036952,0.63,-7.162040392,1.699423244,90.00000001 +290.26,50.43283629,-2.559143465,51.4622,7.81E-12,10.00036951,0.691875,-7.156411769,1.610710298,90.00000001 +290.27,50.43283629,-2.559142057,51.455,1.31E-11,10.0003695,0.755,-7.149288529,1.520592803,90.00000001 +290.28,50.43283629,-2.55914065,51.4471,6.09E-12,10.00014746,0.8184375,-7.140672332,1.429149369,90.00000001 +290.29,50.43283629,-2.559139242,51.4386,-1.09E-11,9.999481343,0.88125,-7.130564841,1.336459638,90.00000001 +290.3,50.43283629,-2.559137835,51.4295,-2.75E-11,9.999037263,0.9434375,-7.11896829,1.24260451,90.00000001 +290.31,50.43283629,-2.559136428,51.4197,-3.67E-11,9.999481314,1.0046875,-7.10588497,1.147665804,90.00000001 +290.32,50.43283629,-2.55913502,51.4094,-3.69E-11,10.0001474,1.0646875,-7.09131769,1.051726313,90.00000001 +290.33,50.43283629,-2.559133613,51.3984,-2.50E-11,10.00036941,1.12375,-7.075269486,0.954869746,90.00000001 +290.34,50.43283629,-2.559132205,51.3869,-7.81E-13,10.00036939,1.183125,-7.057743739,0.857180499,90.00000001 +290.35,50.43283629,-2.559130798,51.3748,2.11E-11,10.00036938,1.2434375,-7.038744057,0.758743772,90.00000001 +290.36,50.43283629,-2.55912939,51.362,2.42E-11,10.00036936,1.303125,-7.018274395,0.659645393,90.00000001 +290.37,50.43283629,-2.559127983,51.3487,1.11E-11,10.00036933,1.36125,-6.99633905,0.559971821,90.00000001 +290.38,50.43283629,-2.559126575,51.3348,-4.69E-12,10.00036931,1.4184375,-6.972942662,0.459809918,90.00000001 +290.39,50.43283629,-2.559125168,51.3203,-1.16E-11,10.00036929,1.475,-6.948089987,0.359247059,90.00000001 +290.4,50.43283629,-2.55912376,51.3053,-4.53E-12,10.00036927,1.5315625,-6.921786354,0.258370963,90.00000001 +290.41,50.43283629,-2.559122353,51.2897,7.19E-12,10.00014721,1.588125,-6.894037149,0.157269524,90.00000001 +290.42,50.43283629,-2.559120945,51.2735,7.03E-12,9.999481084,1.643125,-6.864848272,0.056030975,90.00000001 +290.43,50.43283629,-2.559119538,51.2568,-5.31E-12,9.999036992,1.6965625,-6.834225741,-0.045256447,90.00000001 +290.44,50.43283629,-2.559118131,51.2396,-1.31E-11,9.999481032,1.75,-6.802175914,-0.146504449,90.00000001 +290.45,50.43283629,-2.559116723,51.2218,-6.09E-12,10.0001471,1.8034375,-6.76870561,-0.247624624,90.00000001 +290.46,50.43283629,-2.559115316,51.2035,1.09E-11,10.00036911,1.85625,-6.733821705,-0.348528909,90.00000001 +290.47,50.43283629,-2.559113908,51.1847,2.50E-11,10.00036908,1.908125,-6.697531533,-0.44912924,90.00000001 +290.48,50.43283629,-2.559112501,51.1653,2.42E-11,10.00036905,1.958125,-6.659842713,-0.549337954,90.00000001 +290.49,50.43283629,-2.559111093,51.1455,1.19E-11,10.00036902,2.0065625,-6.62076298,-0.649067618,90.00000001 +290.5,50.43283629,-2.559109686,51.1252,2.19E-12,10.00036898,2.0553125,-6.580300643,-0.748231314,90.00000001 +290.51,50.43283629,-2.559108278,51.1044,-3.13E-12,10.00036895,2.1046875,-6.538464125,-0.846742526,90.00000001 +290.52,50.43283629,-2.559106871,51.0831,-8.59E-12,10.00036892,2.1528125,-6.495262076,-0.944515368,90.00000001 +290.53,50.43283629,-2.559105463,51.0613,-6.25E-12,10.00036889,2.198125,-6.450703606,-1.041464582,90.00000001 +290.54,50.43283629,-2.559104056,51.0391,6.09E-12,10.00014682,2.2415625,-6.404797999,-1.137505601,90.00000001 +290.55,50.43283629,-2.559102648,51.0165,1.55E-11,9.999480682,2.2853125,-6.357554821,-1.232554716,90.00000001 +290.56,50.43283629,-2.559101241,50.9934,1.95E-11,9.999036581,2.3296875,-6.308983928,-1.326529019,90.00000001 +290.57,50.43283629,-2.559099834,50.9699,2.44E-11,9.99948061,2.3728125,-6.259095462,-1.419346577,90.00000001 +290.58,50.43283629,-2.559098426,50.9459,2.11E-11,10.00014667,2.4134375,-6.207899906,-1.510926432,90.00000001 +290.59,50.43283629,-2.559097019,50.9216,1.56E-12,10.00036867,2.453125,-6.15540792,-1.601188714,90.00000001 +290.6,50.43283629,-2.559095611,50.8969,-1.64E-11,10.00036863,2.493125,-6.101630445,-1.690054754,90.00000001 +290.61,50.43283629,-2.559094204,50.8717,-1.16E-11,10.00036859,2.53125,-6.046578712,-1.77744709,90.00000001 +290.62,50.43283629,-2.559092796,50.8462,4.84E-12,10.00036855,2.5665625,-5.990264237,-1.863289403,90.00000001 +290.63,50.43283629,-2.559091389,50.8204,7.19E-12,10.00036851,2.601875,-5.932698766,-1.947506922,90.00000001 +290.64,50.43283629,-2.559089981,50.7942,-2.34E-12,10.00036847,2.638125,-5.873894332,-2.030026195,90.00000001 +290.65,50.43283629,-2.559088574,50.7676,-5.47E-12,10.00014639,2.6728125,-5.813863194,-2.110775257,90.00000001 +290.66,50.43283629,-2.559087166,50.7407,-2.34E-12,9.999480251,2.7046875,-5.752617902,-2.189683692,90.00000001 +290.67,50.43283629,-2.559085759,50.7135,-1.41E-12,9.999036142,2.735,-5.690171289,-2.266682688,90.00000001 +290.68,50.43283629,-2.559084352,50.686,7.81E-13,9.999480165,2.7646875,-5.626536305,-2.341705094,90.00000001 +290.69,50.43283629,-2.559082944,50.6582,8.44E-12,10.00014622,2.793125,-5.561726356,-2.414685479,90.00000001 +290.7,50.43283629,-2.559081537,50.6301,1.31E-11,10.00036821,2.82,-5.495754849,-2.485560243,90.00000001 +290.71,50.43283629,-2.559080129,50.6018,5.47E-12,10.00036817,2.8465625,-5.428635651,-2.554267566,90.00000001 +290.72,50.43283629,-2.559078722,50.5732,-6.25E-12,10.00036812,2.873125,-5.360382741,-2.620747515,90.00000001 +290.73,50.43283629,-2.559077314,50.5443,-5.47E-12,10.00036808,2.898125,-5.291010386,-2.684942165,90.00000001 +290.74,50.43283629,-2.559075907,50.5152,9.22E-12,10.000146,2.92125,-5.220533083,-2.74679548,90.00000001 +290.75,50.43283629,-2.559074499,50.4859,2.34E-11,9.999479852,2.943125,-5.148965555,-2.806253545,90.00000001 +290.76,50.43283629,-2.559073092,50.4563,2.34E-11,9.99903574,2.963125,-5.076322699,-2.863264507,90.00000001 +290.77,50.43283629,-2.559071685,50.4266,9.37E-12,9.99947976,2.98125,-5.002619758,-2.917778691,90.00000001 +290.78,50.43283629,-2.559070277,50.3967,-7.03E-12,10.00014581,2.9984375,-4.927872028,-2.969748484,90.00000001 +290.79,50.43283629,-2.55906887,50.3666,-1.64E-11,10.0003678,3.0146875,-4.852095208,-3.01912868,90.00000001 +290.8,50.43283629,-2.559067462,50.3364,-1.64E-11,10.00036775,3.0296875,-4.775305112,-3.065876077,90.00000001 +290.81,50.43283629,-2.559066055,50.306,-9.38E-12,10.00014567,3.043125,-4.697517727,-3.109950053,90.00000001 +290.82,50.43283629,-2.559064647,50.2755,-4.69E-12,9.999479524,3.055,-4.618749322,-3.151312048,90.00000001 +290.83,50.43283629,-2.55906324,50.2449,-1.17E-11,9.99903541,3.0665625,-4.539016344,-3.189926081,90.00000001 +290.84,50.43283629,-2.559061833,50.2142,-2.34E-11,9.999479427,3.078125,-4.458335464,-3.22575846,90.00000001 +290.85,50.43283629,-2.559060425,50.1833,-2.58E-11,10.00014548,3.0878125,-4.376723527,-3.258777903,90.00000001 +290.86,50.43283629,-2.559059018,50.1524,-1.88E-11,10.00036746,3.094375,-4.294197551,-3.288955647,90.00000001 +290.87,50.43283629,-2.55905761,50.1214,-7.03E-12,10.00036741,3.0984375,-4.210774782,-3.316265394,90.00000001 +290.88,50.43283629,-2.559056203,50.0904,7.03E-12,10.00014533,3.1015625,-4.126472636,-3.340683309,90.00000001 +290.89,50.43283629,-2.559054795,50.0594,1.41E-11,9.999479185,3.105,-4.041308763,-3.362188076,90.00000001 +290.9,50.43283629,-2.559053388,50.0283,9.38E-12,9.999035071,3.108125,-3.955300865,-3.380760961,90.00000001 +290.91,50.43283629,-2.559051981,49.9972,2.34E-12,9.999479089,3.1096875,-3.868466991,-3.396385807,90.00000001 +290.92,50.43283629,-2.559050573,49.9661,2.34E-12,10.00014514,3.1096875,-3.780825247,-3.409048919,90.00000001 +290.93,50.43283629,-2.559049166,49.935,7.03E-12,10.00036712,3.1078125,-3.692393909,-3.418739297,90.00000001 +290.94,50.43283629,-2.559047758,49.9039,4.69E-12,10.00036707,3.103125,-3.603191485,-3.425448518,90.00000001 +290.95,50.43283629,-2.559046351,49.8729,-7.03E-12,10.00014499,3.0965625,-3.513236539,-3.429170624,90.00000001 +290.96,50.43283629,-2.559044943,49.842,-1.64E-11,9.999478846,3.0903125,-3.422547919,-3.42990252,90.00000001 +290.97,50.43283629,-2.559043536,49.8111,-2.11E-11,9.999034732,3.0846875,-3.331144593,-3.427643462,90.00000001 +290.98,50.43283629,-2.559042129,49.7803,-2.58E-11,9.999478749,3.0778125,-3.239045523,-3.422395398,90.00000001 +290.99,50.43283629,-2.559040721,49.7495,-2.58E-11,10.0001448,3.0678125,-3.146270077,-3.414163026,90.00000001 +291,50.43283629,-2.559039314,49.7189,-2.11E-11,10.00036679,3.0546875,-3.052837506,-3.40295345,90.00000001 +291.01,50.43283629,-2.559037906,49.6884,-1.64E-11,10.00036674,3.0403125,-2.958767461,-3.388776412,90.00000001 +291.02,50.43283629,-2.559036499,49.6581,-4.69E-12,10.00036669,3.02625,-2.864079482,-3.371644286,90.00000001 +291.03,50.43283629,-2.559035091,49.6279,1.64E-11,10.00036664,3.0115625,-2.768793335,-3.351572085,90.00000001 +291.04,50.43283629,-2.559033684,49.5978,3.05E-11,10.00014456,2.9946875,-2.672929016,-3.328577283,90.00000001 +291.05,50.43283629,-2.559032276,49.568,2.58E-11,9.999478418,2.9765625,-2.576506464,-3.302679877,90.00000001 +291.06,50.43283629,-2.559030869,49.5383,1.17E-11,9.999034305,2.9584375,-2.479545905,-3.273902499,90.00000001 +291.07,50.43283629,-2.559029462,49.5088,-1.56E-13,9.999478324,2.939375,-2.38206745,-3.242270187,90.00000001 +291.08,50.43283629,-2.559028054,49.4795,-7.81E-12,10.00014438,2.9178125,-2.284091552,-3.207810614,90.00000001 +291.09,50.43283629,-2.559026647,49.4504,-3.91E-12,10.00036637,2.8934375,-2.185638667,-3.170553747,90.00000001 +291.1,50.43283629,-2.559025239,49.4216,1.72E-11,10.00036632,2.868125,-2.086729307,-3.13053213,90.00000001 +291.11,50.43283629,-2.559023832,49.3931,3.66E-11,10.00036628,2.843125,-1.987384212,-3.087780654,90.00000001 +291.12,50.43283629,-2.559022424,49.3647,2.95E-11,10.00036623,2.8165625,-1.887624009,-3.042336564,90.00000001 +291.13,50.43283629,-2.559021017,49.3367,7.81E-13,10.00036619,2.7878125,-1.787469669,-2.994239565,90.00000001 +291.14,50.43283629,-2.559019609,49.309,-2.48E-11,10.00036614,2.75875,-1.686941989,-2.943531482,90.00000001 +291.15,50.43283629,-2.559018202,49.2815,-3.52E-11,10.0003661,2.7296875,-1.586061998,-2.890256606,90.00000001 +291.16,50.43283629,-2.559016794,49.2544,-3.14E-11,10.00036606,2.699375,-1.484850837,-2.834461403,90.00000001 +291.17,50.43283629,-2.559015387,49.2275,-1.50E-11,10.00014398,2.6665625,-1.383329534,-2.776194517,90.00000001 +291.18,50.43283629,-2.559013979,49.201,4.69E-12,9.999477844,2.63125,-1.281519402,-2.715506713,90.00000001 +291.19,50.43283629,-2.559012572,49.1749,1.48E-11,9.999033736,2.5953125,-1.179441585,-2.652450989,90.00000001 +291.2,50.43283629,-2.559011165,49.1491,1.89E-11,9.999477762,2.5596875,-1.077117454,-2.587082234,90.00000001 +291.21,50.43283629,-2.559009757,49.1237,2.66E-11,10.00014382,2.523125,-0.974568436,-2.519457515,90.00000001 +291.22,50.43283629,-2.55900835,49.0986,3.28E-11,10.00036582,2.485,-0.871815847,-2.449635847,90.00000001 +291.23,50.43283629,-2.559006942,49.074,2.48E-11,10.00036578,2.44625,-0.768881172,-2.37767802,90.00000001 +291.24,50.43283629,-2.559005535,49.0497,3.75E-12,10.00036574,2.4065625,-0.665785953,-2.303646831,90.00000001 +291.25,50.43283629,-2.559004127,49.0258,-1.17E-11,10.0003657,2.3646875,-0.562551736,-2.227606794,90.00000001 +291.26,50.43283629,-2.55900272,49.0024,-8.44E-12,10.00036566,2.3215625,-0.459199947,-2.149624316,90.00000001 +291.27,50.43283629,-2.559001312,48.9794,5.47E-12,10.00036563,2.2784375,-0.35575236,-2.069767292,90.00000001 +291.28,50.43283629,-2.558999905,48.9568,1.56E-11,10.00036559,2.2346875,-0.252230403,-1.988105394,90.00000001 +291.29,50.43283629,-2.558998497,48.9347,1.62E-11,10.00036556,2.1896875,-0.148655791,-1.90470984,90.00000001 +291.3,50.43283629,-2.55899709,48.913,9.37E-12,10.00014349,2.143125,-0.045050124,-1.819653338,90.00000001 +291.31,50.43283629,-2.558995682,48.8918,4.69E-12,9.99947736,2.095,0.058564938,-1.733010145,90.00000001 +291.32,50.43283629,-2.558994275,48.8711,1.17E-11,9.999033261,2.0465625,0.16216774,-1.644855661,90.00000001 +291.33,50.43283629,-2.558992868,48.8509,2.34E-11,9.999477295,1.998125,0.265736737,-1.555266891,90.00000001 +291.34,50.43283629,-2.55899146,48.8311,2.11E-11,10.00014336,1.9484375,0.369250157,-1.464321873,90.00000001 +291.35,50.43283629,-2.558990053,48.8119,-2.50E-12,10.00036537,1.8978125,0.472686514,-1.372099962,90.00000001 +291.36,50.43283629,-2.558988645,48.7932,-3.36E-11,10.00036534,1.846875,0.576024151,-1.278681542,90.00000001 +291.37,50.43283629,-2.558987238,48.7749,-5.08E-11,10.00036531,1.7946875,0.679241523,-1.18414809,90.00000001 +291.38,50.43283629,-2.55898583,48.7573,-4.59E-11,10.00036528,1.7415625,0.782317032,-1.088582053,90.00000001 +291.39,50.43283629,-2.558984423,48.7401,-3.05E-11,10.00036525,1.6884375,0.885229133,-0.992066739,90.00000001 +291.4,50.43283629,-2.558983015,48.7235,-1.72E-11,10.00036523,1.634375,0.987956397,-0.894686374,90.00000001 +291.41,50.43283629,-2.558981608,48.7074,-4.69E-12,10.0003652,1.5784375,1.090477283,-0.796525812,90.00000001 +291.42,50.43283629,-2.5589802,48.6919,9.53E-12,10.00036518,1.5215625,1.192770532,-0.697670654,90.00000001 +291.43,50.43283629,-2.558978793,48.677,1.64E-11,10.00014312,1.465,1.294814602,-0.598207128,90.00000001 +291.44,50.43283629,-2.558977385,48.6626,1.09E-11,9.999477001,1.408125,1.396588293,-0.498221925,90.00000001 +291.45,50.43283629,-2.558975978,48.6488,2.34E-12,9.999032914,1.3496875,1.498070348,-0.397802305,90.00000001 +291.46,50.43283629,-2.558974571,48.6356,-3.75E-12,9.999476958,1.2903125,1.599239511,-0.29703576,90.00000001 +291.47,50.43283629,-2.558973163,48.623,-1.33E-11,10.00014304,1.2315625,1.700074697,-0.196010237,90.00000001 +291.48,50.43283629,-2.558971756,48.611,-2.66E-11,10.00036505,1.1734375,1.800554879,-0.094813743,90.00000001 +291.49,50.43283629,-2.558970348,48.5995,-3.53E-11,10.00036503,1.1146875,1.900659028,0.00646537,90.00000001 +291.5,50.43283629,-2.558968941,48.5887,-3.52E-11,10.00036502,1.0546875,2.000366232,0.107738927,90.00000001 +291.51,50.43283629,-2.558967533,48.5784,-2.58E-11,10.000365,0.9934375,2.099655693,0.20891846,90.00000001 +291.52,50.43283629,-2.558966126,48.5688,-9.22E-12,10.00014295,0.93125,2.198506669,0.309915851,90.00000001 +291.53,50.43283629,-2.558964718,48.5598,1.02E-11,9.99947684,0.86875,2.296898534,0.410642977,90.00000001 +291.54,50.43283629,-2.558963311,48.5514,2.73E-11,9.999032761,0.8065625,2.394810661,0.511012005,90.00000001 +291.55,50.43283629,-2.558961904,48.5437,3.19E-11,9.999476815,0.7446875,2.492222711,0.610935443,90.00000001 +291.56,50.43283629,-2.558960496,48.5365,1.41E-11,10.0001429,0.681875,2.589114286,0.710326145,90.00000001 +291.57,50.43283629,-2.558959089,48.53,-1.56E-11,10.00036493,0.618125,2.685465161,0.809097423,90.00000001 +291.58,50.43283629,-2.558957681,48.5242,-3.28E-11,10.00036492,0.5553125,2.781255224,0.90716316,90.00000001 +291.59,50.43283629,-2.558956274,48.5189,-3.06E-11,10.00014287,0.493125,2.876464423,1.004437815,90.00000001 +291.6,50.43283629,-2.558954866,48.5143,-2.34E-11,9.999476768,0.4296875,2.971072933,1.100836589,90.00000001 +291.61,50.43283629,-2.558953459,48.5103,-2.03E-11,9.999032696,0.365,3.06506093,1.196275429,90.00000001 +291.62,50.43283629,-2.558952052,48.507,-1.88E-11,9.999476758,0.3,3.158408875,1.290671085,90.00000001 +291.63,50.43283629,-2.558950644,48.5043,-1.50E-11,10.00014285,0.2353125,3.251097232,1.383941281,90.00000001 +291.64,50.43283629,-2.558949237,48.5023,-5.47E-12,10.00036488,0.1715625,3.343106634,1.476004655,90.00000001 +291.65,50.43283629,-2.558947829,48.5009,5.47E-12,10.00036488,0.108125,3.434417829,1.566780879,90.00000001 +291.66,50.43283629,-2.558946422,48.5001,4.84E-12,10.00014285,0.043125,3.525011795,1.656190886,90.00000001 +291.67,50.43283629,-2.558945014,48.5,-4.84E-12,9.999476747,-0.023125,3.614869683,1.744156695,90.00000001 +291.68,50.43283629,-2.558943607,48.5006,-5.47E-12,9.999032681,-0.088125,3.703972584,1.830601531,90.00000001 +291.69,50.43283629,-2.5589422,48.5018,5.47E-12,9.999476749,-0.1515625,3.792301935,1.915450106,90.00000001 +291.7,50.43283629,-2.558940792,48.5036,1.27E-11,10.00014285,-0.215,3.879839401,1.998628337,90.00000001 +291.71,50.43283629,-2.558939385,48.5061,7.03E-12,10.00036489,-0.2784375,3.966566533,2.080063745,90.00000001 +291.72,50.43283629,-2.558937977,48.5092,-5.62E-12,10.00036489,-0.3415625,4.05246534,2.159685341,90.00000001 +291.73,50.43283629,-2.55893657,48.5129,-1.50E-11,10.00014287,-0.4053125,4.13751783,2.237423624,90.00000001 +291.74,50.43283629,-2.558935162,48.5173,-1.86E-11,9.999476774,-0.47,4.221706243,2.313210814,90.00000001 +291.75,50.43283629,-2.558933755,48.5223,-1.70E-11,9.999032716,-0.5346875,4.305012989,2.386980906,90.00000001 +291.76,50.43283629,-2.558932348,48.528,-6.88E-12,9.99947679,-0.5984375,4.387420764,2.4586695,90.00000001 +291.77,50.43283629,-2.55893094,48.5343,8.44E-12,10.0001429,-0.6615625,4.468912207,2.528214086,90.00000001 +291.78,50.43283629,-2.558929533,48.5412,1.56E-11,10.00036494,-0.725,4.549470417,2.595553988,90.00000001 +291.79,50.43283629,-2.558928125,48.5488,1.02E-11,10.00036496,-0.788125,4.629078491,2.660630591,90.00000001 +291.8,50.43283629,-2.558926718,48.557,2.50E-12,10.00014293,-0.8496875,4.70771987,2.72338706,90.00000001 +291.81,50.43283629,-2.55892531,48.5658,2.78E-17,9.999476849,-0.91,4.785378112,2.783768733,90.00000001 +291.82,50.43283629,-2.558923903,48.5752,2.34E-12,9.999032798,-0.9703125,4.862036942,2.841722841,90.00000001 +291.83,50.43283629,-2.558922496,48.5852,1.17E-11,9.99947688,-1.0315625,4.937680435,2.897198964,90.00000001 +291.84,50.43283629,-2.558921088,48.5958,2.34E-11,10.000143,-1.093125,5.012292775,2.950148744,90.00000001 +291.85,50.43283629,-2.558919681,48.6071,2.11E-11,10.00036505,-1.1534375,5.085858321,3.000525886,90.00000001 +291.86,50.43283629,-2.558918273,48.6189,1.57E-13,10.00036506,-1.213125,5.158361776,3.048286502,90.00000001 +291.87,50.43283629,-2.558916866,48.6313,-2.03E-11,10.00036508,-1.2734375,5.229787955,3.093389052,90.00000001 +291.88,50.43283629,-2.558915458,48.6444,-2.41E-11,10.0003651,-1.3328125,5.300121962,3.135794059,90.00000001 +291.89,50.43283629,-2.558914051,48.658,-1.88E-11,10.00036513,-1.3896875,5.36934913,3.175464626,90.00000001 +291.9,50.43283629,-2.558912643,48.6722,-1.39E-11,10.00036515,-1.4453125,5.437454961,3.212366087,90.00000001 +291.91,50.43283629,-2.558911236,48.6869,-4.53E-12,10.00036517,-1.5015625,5.504425248,3.246466415,90.00000001 +291.92,50.43283629,-2.558909828,48.7022,9.53E-12,10.0003652,-1.5584375,5.570245952,3.277735701,90.00000001 +291.93,50.43283629,-2.558908421,48.7181,1.87E-11,10.00014319,-1.6146875,5.634903437,3.306146788,90.00000001 +291.94,50.43283629,-2.558907013,48.7345,1.80E-11,9.999477113,-1.6696875,5.698384181,3.331674865,90.00000001 +291.95,50.43283629,-2.558905606,48.7515,7.03E-12,9.999033074,-1.7234375,5.760674835,3.354297645,90.00000001 +291.96,50.43283629,-2.558904199,48.769,-8.44E-12,9.999477167,-1.7765625,5.821762449,3.373995418,90.00000001 +291.97,50.43283629,-2.558902791,48.787,-1.33E-11,10.00014329,-1.8296875,5.881634304,3.390751054,90.00000001 +291.98,50.43283629,-2.558901384,48.8056,1.56E-12,10.00036536,-1.8815625,5.940277795,3.404549883,90.00000001 +291.99,50.43283629,-2.558899976,48.8247,2.09E-11,10.00036539,-1.9315625,5.997680775,3.415379931,90.00000001 +292,50.43283629,-2.558898569,48.8442,2.11E-11,10.00036542,-1.9815625,6.053831211,3.423231687,90.00000001 +292.01,50.43283629,-2.558897161,48.8643,2.34E-12,10.00036545,-2.0315625,6.108717417,3.428098333,90.00000001 +292.02,50.43283629,-2.558895754,48.8849,-1.17E-11,10.00036548,-2.0796875,6.162327817,3.42997563,90.00000001 +292.03,50.43283629,-2.558894346,48.9059,-7.19E-12,10.00036551,-2.1265625,6.214651355,3.428861914,90.00000001 +292.04,50.43283629,-2.558892939,48.9274,6.25E-12,10.00036555,-2.1734375,6.265677028,3.424758219,90.00000001 +292.05,50.43283629,-2.558891531,48.9494,1.48E-11,10.00036558,-2.2196875,6.31539418,3.417668095,90.00000001 +292.06,50.43283629,-2.558890124,48.9718,1.48E-11,10.00014358,-2.2646875,6.36379244,3.407597674,90.00000001 +292.07,50.43283629,-2.558888716,48.9947,8.44E-12,9.99947752,-2.308125,6.410861725,3.39455578,90.00000001 +292.08,50.43283629,-2.558887309,49.018,3.75E-12,9.99903349,-2.35,6.45659218,3.378553813,90.00000001 +292.09,50.43283629,-2.558885902,49.0417,1.00E-11,9.999477594,-2.3915625,6.500974236,3.359605641,90.00000001 +292.1,50.43283629,-2.558884494,49.0658,2.11E-11,10.00014373,-2.433125,6.543998668,3.337727878,90.00000001 +292.11,50.43283629,-2.558883087,49.0904,2.09E-11,10.0003658,-2.473125,6.585656481,3.312939603,90.00000001 +292.12,50.43283629,-2.558881679,49.1153,6.88E-12,10.00036584,-2.51125,6.625938966,3.285262361,90.00000001 +292.13,50.43283629,-2.558880272,49.1406,-9.53E-12,10.00036588,-2.5484375,6.664837644,3.254720273,90.00000001 +292.14,50.43283629,-2.558878864,49.1663,-1.89E-11,10.00036592,-2.5846875,6.70234455,3.221340096,90.00000001 +292.15,50.43283629,-2.558877457,49.1923,-1.89E-11,10.00036596,-2.6196875,6.738451663,3.185150821,90.00000001 +292.16,50.43283629,-2.558876049,49.2187,-9.37E-12,10.000366,-2.6534375,6.773151591,3.146184076,90.00000001 +292.17,50.43283629,-2.558874642,49.2454,7.81E-12,10.00036604,-2.68625,6.806437058,3.10447378,90.00000001 +292.18,50.43283629,-2.558873234,49.2724,2.58E-11,10.00036609,-2.7184375,6.838301018,3.060056373,90.00000001 +292.19,50.43283629,-2.558871827,49.2998,3.66E-11,10.0001441,-2.7496875,6.868736937,3.012970529,90.00000001 +292.2,50.43283629,-2.558870419,49.3274,3.67E-11,9.999478041,-2.7796875,6.897738399,2.96325733,90.00000001 +292.21,50.43283629,-2.558869012,49.3554,2.89E-11,9.999034018,-2.808125,6.92529933,2.910960092,90.00000001 +292.22,50.43283629,-2.558867605,49.3836,2.11E-11,9.999478129,-2.8346875,6.951414059,2.856124536,90.00000001 +292.23,50.43283629,-2.558866197,49.4121,1.80E-11,10.00014427,-2.86,6.976077027,2.798798332,90.00000001 +292.24,50.43283629,-2.55886479,49.4408,1.48E-11,10.00036635,-2.8846875,6.999283136,2.739031558,90.00000001 +292.25,50.43283629,-2.558863382,49.4698,7.81E-12,10.00036639,-2.908125,7.021027572,2.676876294,90.00000001 +292.26,50.43283629,-2.558861975,49.499,3.91E-12,10.00036644,-2.93,7.041305694,2.612386743,90.00000001 +292.27,50.43283629,-2.558860567,49.5284,1.39E-11,10.00036649,-2.95125,7.060113377,2.545619169,90.00000001 +292.28,50.43283629,-2.55885916,49.558,3.52E-11,10.00036653,-2.9715625,7.077446611,2.476631785,90.00000001 +292.29,50.43283629,-2.558857752,49.5879,4.92E-11,10.00036658,-2.9896875,7.093301843,2.40548475,90.00000001 +292.3,50.43283629,-2.558856345,49.6178,4.45E-11,10.00014459,-3.0065625,7.107675693,2.332240118,90.00000001 +292.31,50.43283629,-2.558854937,49.648,3.28E-11,9.999478543,-3.023125,7.120565238,2.256961657,90.00000001 +292.32,50.43283629,-2.55885353,49.6783,3.05E-11,9.999034524,-3.0378125,7.131967728,2.179715143,90.00000001 +292.33,50.43283629,-2.558852123,49.7088,3.28E-11,9.999478637,-3.05,7.141880815,2.100567899,90.00000001 +292.34,50.43283629,-2.558850715,49.7393,2.58E-11,10.00014478,-3.0615625,7.150302377,2.019588909,90.00000001 +292.35,50.43283629,-2.558849308,49.77,1.41E-11,10.00036687,-3.073125,7.157230698,1.936848819,90.00000001 +292.36,50.43283629,-2.5588479,49.8008,1.17E-11,10.00036691,-3.0828125,7.162664343,1.852419763,90.00000001 +292.37,50.43283629,-2.558846493,49.8317,1.64E-11,10.00014493,-3.0896875,7.16660211,1.766375311,90.00000001 +292.38,50.43283629,-2.558845085,49.8626,1.87E-11,9.999478878,-3.095,7.169043254,1.678790633,90.00000001 +292.39,50.43283629,-2.558843678,49.8936,1.87E-11,9.99903486,-3.1,7.169987259,1.589741991,90.00000001 +292.4,50.43283629,-2.558842271,49.9246,1.64E-11,9.999478975,-3.1046875,7.169433897,1.499307077,90.00000001 +292.41,50.43283629,-2.558840863,49.9557,9.37E-12,10.00014512,-3.108125,7.167383281,1.407564732,90.00000001 +292.42,50.43283629,-2.558839456,49.9868,2.34E-12,10.0003672,-3.1096875,7.163835812,1.314594995,90.00000001 +292.43,50.43283629,-2.558838048,50.0179,2.34E-12,10.00036725,-3.1096875,7.158792294,1.220478885,90.00000001 +292.44,50.43283629,-2.558836641,50.049,9.38E-12,10.00014527,-3.108125,7.152253814,1.125298506,90.00000001 +292.45,50.43283629,-2.558835233,50.0801,1.64E-11,9.999479218,-3.1046875,7.144221576,1.029136879,90.00000001 +292.46,50.43283629,-2.558833826,50.1111,1.88E-11,9.9990352,-3.1,7.134697414,0.932077829,90.00000001 +292.47,50.43283629,-2.558832419,50.1421,1.87E-11,9.999479315,-3.095,7.123683274,0.834205923,90.00000001 +292.48,50.43283629,-2.558831011,50.173,1.41E-11,10.00014546,-3.089375,7.111181392,0.735606648,90.00000001 +292.49,50.43283629,-2.558829604,50.2039,-2.34E-12,10.00036754,-3.0815625,7.097194461,0.636365888,90.00000001 +292.5,50.43283629,-2.558828196,50.2347,-2.34E-11,10.00036759,-3.07125,7.081725403,0.53657022,90.00000001 +292.51,50.43283629,-2.558826789,50.2653,-3.28E-11,10.00014561,-3.06,7.064777368,0.436306616,90.00000001 +292.52,50.43283629,-2.558825381,50.2959,-2.81E-11,9.999479555,-3.048125,7.046353968,0.335662626,90.00000001 +292.53,50.43283629,-2.558823974,50.3263,-2.11E-11,9.999035537,-3.0346875,7.02645904,0.234725854,90.00000001 +292.54,50.43283629,-2.558822567,50.3566,-1.88E-11,9.99947965,-3.02,7.005096709,0.133584422,90.00000001 +292.55,50.43283629,-2.558821159,50.3867,-1.64E-11,10.0001458,-3.0046875,6.982271446,0.032326508,90.00000001 +292.56,50.43283629,-2.558819752,50.4167,-1.17E-11,10.00036788,-2.9878125,6.957988062,-0.068959596,90.00000001 +292.57,50.43283629,-2.558818344,50.4465,-1.41E-11,10.00036792,-2.968125,6.932251543,-0.170185539,90.00000001 +292.58,50.43283629,-2.558816937,50.4761,-2.34E-11,10.00014594,-2.946875,6.905067331,-0.271263144,90.00000001 +292.59,50.43283629,-2.558815529,50.5054,-2.09E-11,9.999479883,-2.9265625,6.876441099,-0.372104174,90.00000001 +292.6,50.43283629,-2.558814122,50.5346,-3.91E-12,9.999035863,-2.90625,6.846378806,-0.472620681,90.00000001 +292.61,50.43283629,-2.558812715,50.5636,3.91E-12,9.999479974,-2.8828125,6.814886696,-0.572725117,90.00000001 +292.62,50.43283629,-2.558811307,50.5923,-5.47E-12,10.00014612,-2.8565625,6.781971417,-0.672330105,90.00000001 +292.63,50.43283629,-2.5588099,50.6207,-1.31E-11,10.0003682,-2.83,6.747639786,-0.771348786,90.00000001 +292.64,50.43283629,-2.558808492,50.6489,-8.44E-12,10.00036824,-2.803125,6.711899022,-0.869694872,90.00000001 +292.65,50.43283629,-2.558807085,50.6768,-7.81E-13,10.00036828,-2.7746875,6.674756575,-0.967282533,90.00000001 +292.66,50.43283629,-2.558805677,50.7044,1.41E-12,10.00036833,-2.745,6.636220178,-1.064026743,90.00000001 +292.67,50.43283629,-2.55880427,50.7317,2.34E-12,10.00036837,-2.7146875,6.596297912,-1.159843106,90.00000001 +292.68,50.43283629,-2.558802862,50.7587,7.81E-12,10.00036841,-2.683125,6.554998025,-1.254648083,90.00000001 +292.69,50.43283629,-2.558801455,50.7854,1.41E-11,10.00014642,-2.6496875,6.512329285,-1.34835894,90.00000001 +292.7,50.43283629,-2.558800047,50.8117,1.39E-11,9.999480362,-2.6146875,6.468300515,-1.44089403,90.00000001 +292.71,50.43283629,-2.55879864,50.8377,4.53E-12,9.999036337,-2.5784375,6.422920883,-1.532172681,90.00000001 +292.72,50.43283629,-2.558797233,50.8633,-9.53E-12,9.999480443,-2.5415625,6.376199899,-1.622115195,90.00000001 +292.73,50.43283629,-2.558795825,50.8885,-1.42E-11,10.00014658,-2.5046875,6.328147361,-1.710643248,90.00000001 +292.74,50.43283629,-2.558794418,50.9134,-1.56E-13,10.00036865,-2.4665625,6.278773296,-1.797679548,90.00000001 +292.75,50.43283629,-2.55879301,50.9379,2.11E-11,10.00036869,-2.42625,6.22808796,-1.883148292,90.00000001 +292.76,50.43283629,-2.558791603,50.9619,3.12E-11,10.00036873,-2.385,6.176101952,-1.966974825,90.00000001 +292.77,50.43283629,-2.558790195,50.9856,2.58E-11,10.00036877,-2.3434375,6.122826159,-2.049086209,90.00000001 +292.78,50.43283629,-2.558788788,51.0088,1.08E-11,10.0003688,-2.30125,6.068271696,-2.129410709,90.00000001 +292.79,50.43283629,-2.55878738,51.0316,-3.12E-12,10.00036884,-2.258125,6.012449965,-2.207878368,90.00000001 +292.8,50.43283629,-2.558785973,51.054,-3.91E-12,10.00036887,-2.213125,5.955372597,-2.284420716,90.00000001 +292.81,50.43283629,-2.558784565,51.0759,7.19E-12,10.00036891,-2.1665625,5.897051509,-2.358971005,90.00000001 +292.82,50.43283629,-2.558783158,51.0973,1.41E-11,10.00014691,-2.12,5.837498907,-2.431464204,90.00000001 +292.83,50.43283629,-2.55878175,51.1183,9.37E-12,9.999480841,-2.073125,5.776727221,-2.501837172,90.00000001 +292.84,50.43283629,-2.558780343,51.1388,2.34E-12,9.999036808,-2.0246875,5.714749173,-2.570028489,90.00000001 +292.85,50.43283629,-2.558778936,51.1588,2.34E-12,9.999480905,-1.9746875,5.651577654,-2.635978739,90.00000001 +292.86,50.43283629,-2.558777528,51.1783,1.16E-11,10.00014703,-1.9234375,5.587225842,-2.699630339,90.00000001 +292.87,50.43283629,-2.558776121,51.1973,2.50E-11,10.0003691,-1.8715625,5.521707259,-2.760927828,90.00000001 +292.88,50.43283629,-2.558774713,51.2157,3.13E-11,10.00036913,-1.82,5.455035483,-2.819817747,90.00000001 +292.89,50.43283629,-2.558773306,51.2337,2.67E-11,10.00036915,-1.768125,5.387224553,-2.876248705,90.00000001 +292.9,50.43283629,-2.558771898,51.2511,2.11E-11,10.00036918,-1.7146875,5.318288506,-2.930171596,90.00000001 +292.91,50.43283629,-2.558770491,51.268,1.80E-11,10.00036921,-1.6603125,5.248241837,-2.981539325,90.00000001 +292.92,50.43283629,-2.558769083,51.2843,7.03E-12,10.00036923,-1.60625,5.177099157,-3.030307086,90.00000001 +292.93,50.43283629,-2.558767676,51.3001,-1.39E-11,10.00036926,-1.5515625,5.104875249,-3.076432366,90.00000001 +292.94,50.43283629,-2.558766268,51.3154,-2.81E-11,10.00036928,-1.4946875,5.031585295,-3.119874943,90.00000001 +292.95,50.43283629,-2.558764861,51.33,-2.66E-11,10.00014727,-1.436875,4.957244594,-3.160596944,90.00000001 +292.96,50.43283629,-2.558763453,51.3441,-2.34E-11,9.999481195,-1.38,4.881868559,-3.198562904,90.00000001 +292.97,50.43283629,-2.558762046,51.3576,-2.95E-11,9.99903715,-1.323125,4.805473059,-3.233739647,90.00000001 +292.98,50.43283629,-2.558760639,51.3706,-3.67E-11,9.999481236,-1.2646875,4.728073967,-3.266096522,90.00000001 +292.99,50.43283629,-2.558759231,51.3829,-3.83E-11,10.00014735,-1.205,4.649687496,-3.295605281,90.00000001 +293,50.43283629,-2.558757824,51.3947,-3.77E-11,10.00036941,-1.145,4.570330034,-3.322240255,90.00000001 +293.01,50.43283629,-2.558756416,51.4058,-3.52E-11,10.00036942,-1.0846875,4.490018024,-3.345978183,90.00000001 +293.02,50.43283629,-2.558755009,51.4164,-2.58E-11,10.00036944,-1.0234375,4.408768426,-3.366798324,90.00000001 +293.03,50.43283629,-2.558753601,51.4263,-1.17E-11,10.00036946,-0.9615625,4.326598085,-3.384682628,90.00000001 +293.04,50.43283629,-2.558752194,51.4356,-2.34E-12,10.00036947,-0.9003125,4.243524133,-3.399615398,90.00000001 +293.05,50.43283629,-2.558750786,51.4443,2.50E-12,10.00036948,-0.8396875,4.159564043,-3.411583684,90.00000001 +293.06,50.43283629,-2.558749379,51.4524,1.02E-11,10.0003695,-0.778125,4.074735235,-3.420577002,90.00000001 +293.07,50.43283629,-2.558747971,51.4599,1.58E-11,10.00036951,-0.715,3.989055528,-3.426587558,90.00000001 +293.08,50.43283629,-2.558746564,51.4667,9.37E-12,10.00014749,-0.6515625,3.902542682,-3.429610025,90.00000001 +293.09,50.43283629,-2.558745156,51.4729,-4.53E-12,9.999481396,-0.5884375,3.815214919,-3.429641824,90.00000001 +293.1,50.43283629,-2.558743749,51.4785,-1.16E-11,9.999037339,-0.525,3.727090343,-3.426682956,90.00000001 +293.11,50.43283629,-2.558742342,51.4834,-4.53E-12,9.999481413,-0.4615625,3.638187404,-3.420735998,90.00000001 +293.12,50.43283629,-2.558740934,51.4877,7.03E-12,10.00014752,-0.398125,3.548524723,-3.411806049,90.00000001 +293.13,50.43283629,-2.558739527,51.4914,4.06E-12,10.00036956,-0.3334375,3.458120978,-3.39990096,90.00000001 +293.14,50.43283629,-2.558738119,51.4944,-1.80E-11,10.00036956,-0.268125,3.36699502,-3.385031101,90.00000001 +293.15,50.43283629,-2.558736712,51.4967,-4.20E-11,10.00014753,-0.20375,3.275165928,-3.367209478,90.00000001 +293.16,50.43283629,-2.558735304,51.4985,-5.16E-11,9.999481436,-0.14,3.18265284,-3.346451618,90.00000001 +293.17,50.43283629,-2.558733897,51.4995,-4.22E-11,9.999037372,-0.07625,3.089475063,-3.32277557,90.00000001 +293.18,50.43283629,-2.55873249,51.5,-1.87E-11,9.999481439,-0.011875,2.995652135,-3.296201959,90.00000001 +293.19,50.43283629,-2.558731082,51.4998,2.34E-12,10.00014754,0.0534375,2.901203595,-3.266754106,90.00000001 +293.2,50.43283629,-2.558729675,51.4989,4.69E-12,10.00036957,0.118125,2.806149209,-3.234457564,90.00000001 +293.21,50.43283629,-2.558728267,51.4974,-6.87E-12,10.00036957,0.1815625,2.710508745,-3.199340465,90.00000001 +293.22,50.43283629,-2.55872686,51.4953,-1.56E-11,10.00014753,0.2453125,2.614302255,-3.161433577,90.00000001 +293.23,50.43283629,-2.558725452,51.4925,-1.72E-11,9.999481427,0.31,2.517549795,-3.120769845,90.00000001 +293.24,50.43283629,-2.558724045,51.4891,-1.50E-11,9.999037356,0.3746875,2.420271531,-3.077384736,90.00000001 +293.25,50.43283629,-2.558722638,51.485,-6.88E-12,9.999481415,0.4384375,2.32248786,-3.031316122,90.00000001 +293.26,50.43283629,-2.55872123,51.4803,6.41E-12,10.00014751,0.5015625,2.224219181,-2.98260411,90.00000001 +293.27,50.43283629,-2.558719823,51.475,1.42E-11,10.00036953,0.565,2.125486005,-2.93129127,90.00000001 +293.28,50.43283629,-2.558718415,51.469,8.44E-12,10.00036952,0.6284375,2.026308959,-2.877422294,90.00000001 +293.29,50.43283629,-2.558717008,51.4624,-7.81E-12,10.00014748,0.69125,1.926708726,-2.821044164,90.00000001 +293.3,50.43283629,-2.5587156,51.4552,-2.48E-11,9.999481369,0.7534375,1.826706105,-2.762206039,90.00000001 +293.31,50.43283629,-2.558714193,51.4473,-2.95E-11,9.999037291,0.8153125,1.726322009,-2.700959257,90.00000001 +293.32,50.43283629,-2.558712786,51.4389,-1.25E-11,9.999481344,0.878125,1.625577407,-2.63735716,90.00000001 +293.33,50.43283629,-2.558711378,51.4298,1.33E-11,10.00014743,0.9415625,1.524493328,-2.571455268,90.00000001 +293.34,50.43283629,-2.558709971,51.42,2.17E-11,10.00036945,1.0028125,1.423090856,-2.503310991,90.00000001 +293.35,50.43283629,-2.558708563,51.4097,1.34E-11,10.00036943,1.061875,1.321391192,-2.432983802,90.00000001 +293.36,50.43283629,-2.558707156,51.3988,1.25E-11,10.00036941,1.121875,1.21941559,-2.360535065,90.00000001 +293.37,50.43283629,-2.558705748,51.3873,2.19E-11,10.0003694,1.183125,1.117185309,-2.286027863,90.00000001 +293.38,50.43283629,-2.558704341,51.3751,2.25E-11,10.00014734,1.243125,1.01472172,-2.209527226,90.00000001 +293.39,50.43283629,-2.558702933,51.3624,8.44E-12,9.999481223,1.30125,0.91204625,-2.131099846,90.00000001 +293.4,50.43283629,-2.558701526,51.3491,-1.11E-11,9.999037137,1.35875,0.809180273,-2.050814078,90.00000001 +293.41,50.43283629,-2.558700119,51.3352,-3.05E-11,9.999481182,1.41625,0.70614533,-1.968739993,90.00000001 +293.42,50.43283629,-2.558698711,51.3208,-4.70E-11,10.00014726,1.4734375,0.602962907,-1.884949156,90.00000001 +293.43,50.43283629,-2.558697304,51.3057,-5.41E-11,10.00036927,1.53,0.499654549,-1.799514617,90.00000001 +293.44,50.43283629,-2.558695896,51.2902,-4.47E-11,10.00036924,1.58625,0.396241912,-1.712510861,90.00000001 +293.45,50.43283629,-2.558694489,51.274,-2.11E-11,10.00036922,1.641875,0.292746426,-1.624013805,90.00000001 +293.46,50.43283629,-2.558693081,51.2573,2.97E-12,10.00036919,1.69625,0.189189862,-1.534100513,90.00000001 +293.47,50.43283629,-2.558691674,51.2401,1.31E-11,10.00014713,1.75,0.085593821,-1.442849535,90.00000001 +293.48,50.43283629,-2.558690266,51.2223,8.44E-12,9.999481004,1.803125,-0.018020153,-1.350340343,90.00000001 +293.49,50.43283629,-2.558688859,51.204,7.82E-13,9.99903691,1.8546875,-0.121630346,-1.256653607,90.00000001 +293.5,50.43283629,-2.558687452,51.1852,-1.56E-12,9.999480947,1.905,-0.225215156,-1.16187109,90.00000001 +293.51,50.43283629,-2.558686044,51.1659,-7.81E-13,10.00014702,1.955,-0.328752927,-1.066075354,90.00000001 +293.52,50.43283629,-2.558684637,51.1461,-1.56E-13,10.00036902,2.005,-0.432222,-0.969350051,90.00000001 +293.53,50.43283629,-2.558683229,51.1258,-2.19E-12,10.00036899,2.0546875,-0.535600832,-0.871779407,90.00000001 +293.54,50.43283629,-2.558681822,51.105,-8.59E-12,10.00036895,2.103125,-0.638867823,-0.773448562,90.00000001 +293.55,50.43283629,-2.558680414,51.0837,-1.48E-11,10.00036892,2.1496875,-0.742001372,-0.674443288,90.00000001 +293.56,50.43283629,-2.558679007,51.062,-1.72E-11,10.00036889,2.195,-0.844979993,-0.574849874,90.00000001 +293.57,50.43283629,-2.558677599,51.0398,-1.80E-11,10.00036885,2.24,-0.947782144,-0.474755178,90.00000001 +293.58,50.43283629,-2.558676192,51.0172,-1.64E-11,10.00014678,2.2846875,-1.050386394,-0.374246521,90.00000001 +293.59,50.43283629,-2.558674784,50.9941,-7.81E-12,9.999480648,2.3284375,-1.152771202,-0.273411449,90.00000001 +293.6,50.43283629,-2.558673377,50.9706,7.66E-12,9.999036545,2.37125,-1.25491531,-0.172338027,90.00000001 +293.61,50.43283629,-2.55867197,50.9467,2.11E-11,9.999480573,2.413125,-1.356797348,-0.071114261,90.00000001 +293.62,50.43283629,-2.558670562,50.9223,2.09E-11,10.00014663,2.453125,-1.458396057,0.030171442,90.00000001 +293.63,50.43283629,-2.558669155,50.8976,6.88E-12,10.00036863,2.49125,-1.559690183,0.131430903,90.00000001 +293.64,50.43283629,-2.558667747,50.8725,-9.53E-12,10.00036859,2.5284375,-1.660658582,0.232575716,90.00000001 +293.65,50.43283629,-2.55866634,50.847,-1.66E-11,10.00036855,2.565,-1.761280169,0.333517759,90.00000001 +293.66,50.43283629,-2.558664932,50.8212,-7.19E-12,10.00036851,2.60125,-1.861533975,0.434168911,90.00000001 +293.67,50.43283629,-2.558663525,50.795,1.41E-11,10.00036847,2.6365625,-1.961398972,0.534441509,90.00000001 +293.68,50.43283629,-2.558662117,50.7684,2.89E-11,10.00036843,2.6696875,-2.060854361,0.634248065,90.00000001 +293.69,50.43283629,-2.55866071,50.7416,2.58E-11,10.00036838,2.7015625,-2.159879401,0.733501543,90.00000001 +293.7,50.43283629,-2.558659302,50.7144,1.31E-11,10.00036834,2.7334375,-2.258453352,0.832115372,90.00000001 +293.71,50.43283629,-2.558657895,50.6869,3.91E-12,10.00014627,2.7646875,-2.356555644,0.930003607,90.00000001 +293.72,50.43283629,-2.558656487,50.6591,3.28E-12,9.999480124,2.7946875,-2.454165823,1.02708082,90.00000001 +293.73,50.43283629,-2.55865508,50.631,7.97E-12,9.999036014,2.8228125,-2.551263491,1.123262443,90.00000001 +293.74,50.43283629,-2.558653673,50.6026,6.25E-12,9.999480035,2.848125,-2.647828308,1.218464595,90.00000001 +293.75,50.43283629,-2.558652265,50.574,-5.47E-12,10.00014609,2.8715625,-2.743840221,1.312604196,90.00000001 +293.76,50.43283629,-2.558650858,50.5452,-1.56E-11,10.00036808,2.8953125,-2.839279061,1.405599143,90.00000001 +293.77,50.43283629,-2.55864945,50.5161,-2.09E-11,10.00036803,2.9196875,-2.934125005,1.497368475,90.00000001 +293.78,50.43283629,-2.558648043,50.4868,-2.58E-11,10.00036799,2.9428125,-3.02835817,1.587831979,90.00000001 +293.79,50.43283629,-2.558646635,50.4572,-2.58E-11,10.00036794,2.9628125,-3.121958905,1.676910931,90.00000001 +293.8,50.43283629,-2.558645228,50.4275,-2.34E-11,10.00036789,2.98,-3.214907671,1.764527579,90.00000001 +293.81,50.43283629,-2.55864382,50.3976,-2.81E-11,10.00036785,2.996875,-3.307185045,1.85060555,90.00000001 +293.82,50.43283629,-2.558642413,50.3676,-3.05E-11,10.0003678,3.0146875,-3.398771718,1.935069785,90.00000001 +293.83,50.43283629,-2.558641005,50.3373,-1.88E-11,10.00036775,3.03125,-3.489648611,2.017846544,90.00000001 +293.84,50.43283629,-2.558639598,50.3069,-4.69E-12,10.00014567,3.044375,-3.579796759,2.098863751,90.00000001 +293.85,50.43283629,-2.55863819,50.2764,-1.94E-16,9.999479526,3.055,-3.669197312,2.178050701,90.00000001 +293.86,50.43283629,-2.558636783,50.2458,-5.55E-17,9.999035411,3.065,-3.757831591,2.25533841,90.00000001 +293.87,50.43283629,-2.558635376,50.2151,2.22E-16,9.999479429,3.075,-3.84568109,2.330659384,90.00000001 +293.88,50.43283629,-2.558633968,50.1843,2.34E-12,10.00014548,3.0846875,-3.932727474,2.403947963,90.00000001 +293.89,50.43283629,-2.558632561,50.1534,9.38E-12,10.00036747,3.093125,-4.01895258,2.475140318,90.00000001 +293.9,50.43283629,-2.558631153,50.1224,1.64E-11,10.00036742,3.0996875,-4.10433836,2.544174284,90.00000001 +293.91,50.43283629,-2.558629746,50.0914,1.64E-11,10.00036737,3.1046875,-4.188866996,2.6109897,90.00000001 +293.92,50.43283629,-2.558628338,50.0603,9.38E-12,10.00036732,3.108125,-4.272520839,2.675528296,90.00000001 +293.93,50.43283629,-2.558626931,50.0292,2.34E-12,10.00014524,3.1096875,-4.355282415,2.737733808,90.00000001 +293.94,50.43283629,-2.558625523,49.9981,2.34E-12,9.99947909,3.1096875,-4.437134478,2.79755192,90.00000001 +293.95,50.43283629,-2.558624116,49.967,9.38E-12,9.999034975,3.108125,-4.518059839,2.854930549,90.00000001 +293.96,50.43283629,-2.558622709,49.9359,1.41E-11,9.999478992,3.105,-4.598041711,2.909819677,90.00000001 +293.97,50.43283629,-2.558621301,49.9049,7.03E-12,10.00014504,3.1015625,-4.677063362,2.962171346,90.00000001 +293.98,50.43283629,-2.558619894,49.8739,-4.69E-12,10.00036703,3.098125,-4.755108236,3.011940007,90.00000001 +293.99,50.43283629,-2.558618486,49.8429,-7.03E-12,10.00036698,3.0928125,-4.832160058,3.059082173,90.00000001 +294,50.43283629,-2.558617079,49.812,-2.34E-12,10.0001449,3.0846875,-4.90820273,3.103556818,90.00000001 +294.01,50.43283629,-2.558615671,49.7812,8.33E-17,9.99947875,3.075,-4.983220438,3.14532504,90.00000001 +294.02,50.43283629,-2.558614264,49.7505,-5.55E-17,9.999034637,3.065,-5.057197426,3.184350571,90.00000001 +294.03,50.43283629,-2.558612857,49.7199,-2.34E-12,9.999478655,3.0546875,-5.13011828,3.220599261,90.00000001 +294.04,50.43283629,-2.558611449,49.6894,-9.38E-12,10.00014471,3.043125,-5.201967818,3.254039542,90.00000001 +294.05,50.43283629,-2.558610042,49.659,-1.88E-11,10.00036669,3.029375,-5.27273097,3.284642249,90.00000001 +294.06,50.43283629,-2.558608634,49.6288,-2.81E-11,10.00036664,3.013125,-5.342392955,3.312380683,90.00000001 +294.07,50.43283629,-2.558607227,49.5987,-3.28E-11,10.00014456,2.995,-5.410939276,3.337230722,90.00000001 +294.08,50.43283629,-2.558605819,49.5689,-2.58E-11,9.999478418,2.9765625,-5.478355611,3.359170594,90.00000001 +294.09,50.43283629,-2.558604412,49.5392,-1.19E-11,9.999034306,2.9584375,-5.544627805,3.378181276,90.00000001 +294.1,50.43283629,-2.558603005,49.5097,-7.81E-13,9.999478326,2.939375,-5.60974211,3.394246096,90.00000001 +294.11,50.43283629,-2.558601597,49.4804,7.81E-12,10.00014438,2.918125,-5.673684887,3.407351073,90.00000001 +294.12,50.43283629,-2.55860019,49.4513,1.48E-11,10.00036637,2.8946875,-5.736442788,3.417484806,90.00000001 +294.13,50.43283629,-2.558598782,49.4225,1.56E-11,10.00036632,2.8696875,-5.798002691,3.42463847,90.00000001 +294.14,50.43283629,-2.558597375,49.3939,7.03E-12,10.00036628,2.8434375,-5.858351763,3.428805764,90.00000001 +294.15,50.43283629,-2.558595967,49.3656,-6.25E-12,10.00036623,2.8165625,-5.917477398,3.429983078,90.00000001 +294.16,50.43283629,-2.55859456,49.3376,-1.02E-11,10.00014416,2.7896875,-5.975367277,3.42816938,90.00000001 +294.17,50.43283629,-2.558593152,49.3098,3.75E-12,9.999478013,2.7615625,-6.032009254,3.423366332,90.00000001 +294.18,50.43283629,-2.558591745,49.2823,2.34E-11,9.999033904,2.73125,-6.087391527,3.415578002,90.00000001 +294.19,50.43283629,-2.558590338,49.2552,2.89E-11,9.999477928,2.6996875,-6.141502463,3.404811266,90.00000001 +294.2,50.43283629,-2.55858893,49.2283,1.41E-11,10.00014398,2.6665625,-6.194330891,3.391075462,90.00000001 +294.21,50.43283629,-2.558587523,49.2018,-4.69E-12,10.00036598,2.6315625,-6.245865694,3.374382623,90.00000001 +294.22,50.43283629,-2.558586115,49.1757,-3.91E-12,10.00036593,2.5965625,-6.296096159,3.354747245,90.00000001 +294.23,50.43283629,-2.558584708,49.1499,1.62E-11,10.00014386,2.5615625,-6.345011743,3.332186516,90.00000001 +294.24,50.43283629,-2.5585833,49.1244,3.11E-11,9.999477724,2.5246875,-6.392602248,3.306720032,90.00000001 +294.25,50.43283629,-2.558581893,49.0994,2.56E-11,9.999033618,2.4865625,-6.438857704,3.278370023,90.00000001 +294.26,50.43283629,-2.558580486,49.0747,1.27E-11,9.999477645,2.448125,-6.483768542,3.247161241,90.00000001 +294.27,50.43283629,-2.558579078,49.0504,1.03E-11,10.00014371,2.4078125,-6.52732531,3.213120902,90.00000001 +294.28,50.43283629,-2.558577671,49.0265,1.41E-11,10.0003657,2.365,-6.569518896,3.176278684,90.00000001 +294.29,50.43283629,-2.558576263,49.0031,1.08E-11,10.00036567,2.321875,-6.610340592,3.136666674,90.00000001 +294.3,50.43283629,-2.558574856,48.9801,8.59E-12,10.00036563,2.2796875,-6.649781746,3.094319478,90.00000001 +294.31,50.43283629,-2.558573448,48.9575,1.95E-11,10.00036559,2.23625,-6.687834222,3.049273995,90.00000001 +294.32,50.43283629,-2.558572041,48.9353,2.83E-11,10.00036556,2.19,-6.724489999,3.001569471,90.00000001 +294.33,50.43283629,-2.558570633,48.9137,1.41E-11,10.00036553,2.143125,-6.759741457,2.951247505,90.00000001 +294.34,50.43283629,-2.558569226,48.8925,-1.41E-11,10.00036549,2.096875,-6.793581203,2.898352041,90.00000001 +294.35,50.43283629,-2.558567818,48.8717,-3.28E-11,10.00036546,2.049375,-6.826002249,2.842929203,90.00000001 +294.36,50.43283629,-2.558566411,48.8515,-3.75E-11,10.0001434,2,-6.856997719,2.785027235,90.00000001 +294.37,50.43283629,-2.558565003,48.8317,-3.75E-11,9.999477266,1.95,-6.886561253,2.724696727,90.00000001 +294.38,50.43283629,-2.558563596,48.8125,-3.50E-11,9.99903317,1.8996875,-6.914686548,2.661990163,90.00000001 +294.39,50.43283629,-2.558562189,48.7937,-2.50E-11,9.999477206,1.8484375,-6.941367874,2.596962375,90.00000001 +294.4,50.43283629,-2.558560781,48.7755,-7.81E-12,10.00014328,1.79625,-6.966599503,2.529669972,90.00000001 +294.41,50.43283629,-2.558559374,48.7578,8.44E-12,10.00036528,1.7434375,-6.990376335,2.460171681,90.00000001 +294.42,50.43283629,-2.558557966,48.7406,1.64E-11,10.00036526,1.6896875,-7.01269327,2.388528064,90.00000001 +294.43,50.43283629,-2.558556559,48.724,1.48E-11,10.00036523,1.6346875,-7.033545668,2.314801631,90.00000001 +294.44,50.43283629,-2.558555151,48.7079,4.69E-12,10.0003652,1.5784375,-7.052929232,2.239056668,90.00000001 +294.45,50.43283629,-2.558553744,48.6924,-7.19E-12,10.00036518,1.521875,-7.070839892,2.161359179,90.00000001 +294.46,50.43283629,-2.558552336,48.6775,-4.69E-12,10.00036516,1.4665625,-7.087273869,2.081776946,90.00000001 +294.47,50.43283629,-2.558550929,48.6631,1.25E-11,10.0001431,1.41125,-7.102227781,2.00037941,90.00000001 +294.48,50.43283629,-2.558549521,48.6492,1.88E-11,9.99947698,1.353125,-7.115698477,1.917237505,90.00000001 +294.49,50.43283629,-2.558548114,48.636,1.41E-12,9.999032893,1.293125,-7.12768315,1.832423708,90.00000001 +294.5,50.43283629,-2.558546707,48.6234,-2.19E-11,9.99947694,1.23375,-7.138179278,1.746012047,90.00000001 +294.51,50.43283629,-2.558545299,48.6113,-3.20E-11,10.00014302,1.175,-7.147184742,1.658077808,90.00000001 +294.52,50.43283629,-2.558543892,48.5999,-2.33E-11,10.00036503,1.11625,-7.154697537,1.568697767,90.00000001 +294.53,50.43283629,-2.558542484,48.589,-2.34E-12,10.00036502,1.0565625,-7.160716229,1.477949732,90.00000001 +294.54,50.43283629,-2.558541077,48.5787,1.17E-11,10.000365,0.9946875,-7.165239444,1.385912943,90.00000001 +294.55,50.43283629,-2.558539669,48.5691,9.22E-12,10.00036499,0.931875,-7.168266323,1.292667557,90.00000001 +294.56,50.43283629,-2.558538262,48.5601,1.56E-12,10.00036497,0.8703125,-7.169796178,1.198294991,90.00000001 +294.57,50.43283629,-2.558536854,48.5517,-3.91E-12,10.00036496,0.8096875,-7.169828722,1.102877464,90.00000001 +294.58,50.43283629,-2.558535447,48.5439,-1.08E-11,10.00036495,0.748125,-7.168363955,1.006498228,90.00000001 +294.59,50.43283629,-2.558534039,48.5367,-1.64E-11,10.00036494,0.6846875,-7.165402164,0.909241336,90.00000001 +294.6,50.43283629,-2.558532632,48.5302,-1.95E-11,10.00014289,0.6203125,-7.16094398,0.811191584,90.00000001 +294.61,50.43283629,-2.558531224,48.5243,-2.81E-11,9.999476784,0.5565625,-7.154990318,0.712434401,90.00000001 +294.62,50.43283629,-2.558529817,48.5191,-4.20E-11,9.999032711,0.4934375,-7.147542382,0.613056017,90.00000001 +294.63,50.43283629,-2.55852841,48.5144,-4.92E-11,9.99947677,0.43,-7.138601834,0.513143007,90.00000001 +294.64,50.43283629,-2.558527002,48.5105,-4.30E-11,10.00014286,0.3665625,-7.12817045,0.412782516,90.00000001 +294.65,50.43283629,-2.558525595,48.5071,-3.05E-11,10.00036489,0.3034375,-7.116250464,0.312062093,90.00000001 +294.66,50.43283629,-2.558524187,48.5044,-2.02E-11,10.00036488,0.239375,-7.102844341,0.211069573,90.00000001 +294.67,50.43283629,-2.55852278,48.5023,-6.25E-12,10.00036488,0.17375,-7.087954829,0.109892961,90.00000001 +294.68,50.43283629,-2.558521372,48.5009,1.56E-11,10.00036488,0.1084375,-7.071585138,0.008620494,90.00000001 +294.69,50.43283629,-2.558519965,48.5002,2.80E-11,10.00036488,0.045,-7.053738592,-0.092659422,90.00000001 +294.7,50.43283629,-2.558518557,48.5,1.66E-11,10.00036488,-0.0184375,-7.034419028,-0.193858551,90.00000001 +294.71,50.43283629,-2.55851715,48.5005,-3.91E-12,10.00014285,-0.08375,-7.013630343,-0.294888657,90.00000001 +294.72,50.43283629,-2.558515742,48.5017,-1.48E-11,9.99947675,-0.1496875,-6.991377006,-0.39566162,90.00000001 +294.73,50.43283629,-2.558514335,48.5035,-1.50E-11,9.999032686,-0.2146875,-6.9676636,-0.496089548,90.00000001 +294.74,50.43283629,-2.558512928,48.506,-7.03E-12,9.999476755,-0.2784375,-6.942495054,-0.596084893,90.00000001 +294.75,50.43283629,-2.55851152,48.5091,5.63E-12,10.00014286,-0.3415625,-6.915876696,-0.69556045,90.00000001 +294.76,50.43283629,-2.558510113,48.5128,1.27E-11,10.0003649,-0.405,-6.887814025,-0.794429417,90.00000001 +294.77,50.43283629,-2.558508705,48.5172,6.88E-12,10.00036491,-0.4684375,-6.858312944,-0.892605678,90.00000001 +294.78,50.43283629,-2.558507298,48.5222,-6.41E-12,10.00014288,-0.5315625,-6.827379583,-0.990003518,90.00000001 +294.79,50.43283629,-2.55850589,48.5278,-1.42E-11,9.99947679,-0.595,-6.795020359,-1.08653814,90.00000001 +294.8,50.43283629,-2.558504483,48.5341,-8.44E-12,9.999032734,-0.6584375,-6.761242148,-1.182125205,90.00000001 +294.81,50.43283629,-2.558503076,48.541,5.47E-12,9.999476811,-0.7215625,-6.726051882,-1.276681519,90.00000001 +294.82,50.43283629,-2.558501668,48.5485,1.33E-11,10.00014292,-0.785,-6.68945701,-1.370124461,90.00000001 +294.83,50.43283629,-2.558500261,48.5567,9.22E-12,10.00036497,-0.848125,-6.651465153,-1.462372728,90.00000001 +294.84,50.43283629,-2.558498853,48.5655,2.34E-12,10.00036498,-0.9096875,-6.612084159,-1.553345706,90.00000001 +294.85,50.43283629,-2.558497446,48.5749,-2.78E-16,10.000365,-0.97,-6.571322338,-1.642964155,90.00000001 +294.86,50.43283629,-2.558496038,48.5849,-1.67E-16,10.00036501,-1.03,-6.529188225,-1.73114998,90.00000001 +294.87,50.43283629,-2.558494631,48.5955,-2.34E-12,10.00014299,-1.0903125,-6.485690529,-1.817826119,90.00000001 +294.88,50.43283629,-2.558493223,48.6067,-1.17E-11,9.999476913,-1.1515625,-6.440838419,-1.902917169,90.00000001 +294.89,50.43283629,-2.558491816,48.6185,-2.36E-11,9.999032866,-1.213125,-6.394641176,-1.98634882,90.00000001 +294.9,50.43283629,-2.558490409,48.631,-2.66E-11,9.999476952,-1.2728125,-6.347108482,-2.068048304,90.00000001 +294.91,50.43283629,-2.558489001,48.644,-2.28E-11,10.00014307,-1.3296875,-6.298250309,-2.147944461,90.00000001 +294.92,50.43283629,-2.558487594,48.6576,-1.88E-11,10.00036512,-1.3853125,-6.248076853,-2.225967562,90.00000001 +294.93,50.43283629,-2.558486186,48.6717,-1.19E-11,10.00036515,-1.441875,-6.196598543,-2.302049654,90.00000001 +294.94,50.43283629,-2.558484779,48.6864,-7.19E-12,10.00014314,-1.5,-6.143826151,-2.376124216,90.00000001 +294.95,50.43283629,-2.558483371,48.7017,-1.19E-11,9.999477062,-1.558125,-6.089770677,-2.448126848,90.00000001 +294.96,50.43283629,-2.558481964,48.7176,-1.88E-11,9.999033021,-1.6146875,-6.034443466,-2.517994639,90.00000001 +294.97,50.43283629,-2.558480557,48.734,-1.80E-11,9.999477112,-1.6696875,-5.977855977,-2.585666684,90.00000001 +294.98,50.43283629,-2.558479149,48.751,-9.38E-12,10.00014324,-1.723125,-5.920020184,-2.651084026,90.00000001 +294.99,50.43283629,-2.558477742,48.7685,-3.28E-12,10.0003653,-1.775,-5.860948006,-2.71418954,90.00000001 +295,50.43283629,-2.558476334,48.7865,-1.02E-11,10.00036533,-1.8265625,-5.800651876,-2.77492828,90.00000001 +295.01,50.43283629,-2.558474927,48.805,-2.50E-11,10.00014332,-1.8784375,-5.739144284,-2.833247248,90.00000001 +295.02,50.43283629,-2.558473519,48.8241,-3.50E-11,9.999477253,-1.9296875,-5.676438236,-2.889095564,90.00000001 +295.03,50.43283629,-2.558472112,48.8436,-3.75E-11,9.999033218,-1.98,-5.612546681,-2.942424528,90.00000001 +295.04,50.43283629,-2.558470705,48.8637,-3.75E-11,9.999477316,-2.03,-5.547483026,-2.993187672,90.00000001 +295.05,50.43283629,-2.558469297,48.8842,-3.28E-11,10.00014345,-2.079375,-5.481260908,-3.041340706,90.00000001 +295.06,50.43283629,-2.55846789,48.9053,-1.64E-11,10.00036551,-2.1265625,-5.41389402,-3.086841634,90.00000001 +295.07,50.43283629,-2.558466482,48.9268,2.19E-12,10.00036555,-2.1715625,-5.345396572,-3.129650806,90.00000001 +295.08,50.43283629,-2.558465075,48.9487,3.91E-12,10.00036558,-2.216875,-5.275782772,-3.169730923,90.00000001 +295.09,50.43283629,-2.558463667,48.9711,-6.25E-12,10.00036562,-2.263125,-5.205067176,-3.207046919,90.00000001 +295.1,50.43283629,-2.55846226,48.994,-8.44E-12,10.00036565,-2.3078125,-5.133264563,-3.241566366,90.00000001 +295.11,50.43283629,-2.558460852,49.0173,-2.34E-12,10.00036569,-2.3496875,-5.060390004,-3.273259068,90.00000001 +295.12,50.43283629,-2.558459445,49.041,1.56E-12,10.00014369,-2.39,-4.986458567,-3.302097466,90.00000001 +295.13,50.43283629,-2.558458037,49.0651,2.34E-12,9.999477631,-2.43,-4.911485836,-3.328056407,90.00000001 +295.14,50.43283629,-2.55845663,49.0896,2.50E-12,9.999033602,-2.47,-4.835487339,-3.351113203,90.00000001 +295.15,50.43283629,-2.558455223,49.1145,4.84E-12,9.999477707,-2.5096875,-4.758479061,-3.371247799,90.00000001 +295.16,50.43283629,-2.558453815,49.1398,1.19E-11,10.00014385,-2.548125,-4.680477045,-3.388442607,90.00000001 +295.17,50.43283629,-2.558452408,49.1655,1.89E-11,10.00036592,-2.5846875,-4.601497506,-3.40268267,90.00000001 +295.18,50.43283629,-2.558451,49.1915,1.89E-11,10.00036596,-2.6196875,-4.521557059,-3.4139555,90.00000001 +295.19,50.43283629,-2.558449593,49.2179,1.17E-11,10.000366,-2.653125,-4.440672321,-3.422251299,90.00000001 +295.2,50.43283629,-2.558448185,49.2446,6.25E-12,10.00036604,-2.685,-4.35886025,-3.427562904,90.00000001 +295.21,50.43283629,-2.558446778,49.2716,1.17E-11,10.00036609,-2.7165625,-4.276137864,-3.429885561,90.00000001 +295.22,50.43283629,-2.55844537,49.2989,2.20E-11,10.00036613,-2.748125,-4.192522409,-3.429217377,90.00000001 +295.23,50.43283629,-2.558443963,49.3266,2.19E-11,10.00036617,-2.778125,-4.108031474,-3.425558813,90.00000001 +295.24,50.43283629,-2.558442555,49.3545,8.44E-12,10.00036622,-2.80625,-4.022682592,-3.418913132,90.00000001 +295.25,50.43283629,-2.558441148,49.3827,-7.97E-12,10.00014423,-2.8334375,-3.936493583,-3.409286066,90.00000001 +295.26,50.43283629,-2.55843974,49.4112,-1.80E-11,9.999478172,-2.8596875,-3.84948255,-3.396686094,90.00000001 +295.27,50.43283629,-2.558438333,49.4399,-1.80E-11,9.99903415,-2.8846875,-3.761667601,-3.381124159,90.00000001 +295.28,50.43283629,-2.558436926,49.4689,-1.02E-11,9.999478262,-2.908125,-3.673067069,-3.362613841,90.00000001 +295.29,50.43283629,-2.558435518,49.4981,-2.50E-12,10.00014441,-2.9296875,-3.583699404,-3.341171239,90.00000001 +295.3,50.43283629,-2.558434111,49.5275,4.44E-16,10.00036649,-2.95,-3.493583399,-3.31681509,90.00000001 +295.31,50.43283629,-2.558432703,49.5571,4.44E-16,10.00036653,-2.97,-3.402737789,-3.28956665,90.00000001 +295.32,50.43283629,-2.558431296,49.5869,-2.34E-12,10.00036658,-2.9896875,-3.31118154,-3.259449639,90.00000001 +295.33,50.43283629,-2.558429888,49.6169,-7.03E-12,10.00036663,-3.0078125,-3.218933845,-3.226490356,90.00000001 +295.34,50.43283629,-2.558428481,49.6471,-4.69E-12,10.00036667,-3.023125,-3.126013842,-3.190717564,90.00000001 +295.35,50.43283629,-2.558427073,49.6774,7.03E-12,10.00036672,-3.0365625,-3.032441067,-3.152162375,90.00000001 +295.36,50.43283629,-2.558425666,49.7078,1.41E-11,10.00014473,-3.05,-2.938235003,-3.11085842,90.00000001 +295.37,50.43283629,-2.558424258,49.7384,1.17E-11,9.999478684,-3.0628125,-2.843415301,-3.066841797,90.00000001 +295.38,50.43283629,-2.558422851,49.7691,1.41E-11,9.999034666,-3.073125,-2.748001785,-3.020150836,90.00000001 +295.39,50.43283629,-2.558421444,49.7999,2.81E-11,9.999478779,-3.08125,-2.652014395,-2.970826275,90.00000001 +295.4,50.43283629,-2.558420036,49.8307,4.45E-11,10.00014493,-3.0884375,-2.555473184,-2.918911085,90.00000001 +295.41,50.43283629,-2.558418629,49.8617,5.16E-11,10.00036701,-3.095,-2.458398262,-2.864450529,90.00000001 +295.42,50.43283629,-2.558417221,49.8926,4.22E-11,10.00036706,-3.10125,-2.360809971,-2.807492165,90.00000001 +295.43,50.43283629,-2.558415814,49.9237,2.11E-11,10.00036711,-3.1065625,-2.262728591,-2.748085666,90.00000001 +295.44,50.43283629,-2.558414406,49.9548,4.69E-12,10.00036715,-3.109375,-2.164174751,-2.686282714,90.00000001 +295.45,50.43283629,-2.558412999,49.9859,2.34E-12,10.0003672,-3.1096875,-2.065168905,-2.622137339,90.00000001 +295.46,50.43283629,-2.558411591,50.017,1.17E-11,10.00036725,-3.1084375,-1.965731793,-2.555705403,90.00000001 +295.47,50.43283629,-2.558410184,50.0481,2.58E-11,10.0003673,-3.1065625,-1.865884157,-2.487044891,90.00000001 +295.48,50.43283629,-2.558408776,50.0791,3.05E-11,10.00036735,-3.1046875,-1.765646852,-2.41621562,90.00000001 +295.49,50.43283629,-2.558407369,50.1102,1.64E-11,10.00014536,-3.1015625,-1.665040792,-2.343279353,90.00000001 +295.5,50.43283629,-2.558405961,50.1412,-7.03E-12,9.999479314,-3.0959375,-1.564087061,-2.268299689,90.00000001 +295.51,50.43283629,-2.558404554,50.1721,-2.58E-11,9.999035296,-3.0884375,-1.462806629,-2.191342061,90.00000001 +295.52,50.43283629,-2.558403147,50.203,-3.52E-11,9.99947941,-3.0796875,-1.361220754,-2.112473561,90.00000001 +295.53,50.43283629,-2.558401739,50.2337,-3.75E-11,10.00014556,-3.07,-1.259350577,-2.031762944,90.00000001 +295.54,50.43283629,-2.558400332,50.2644,-3.75E-11,10.00036764,-3.06,-1.157217412,-1.949280628,90.00000001 +295.55,50.43283629,-2.558398924,50.2949,-3.28E-11,10.00036769,-3.049375,-1.054842574,-1.86509846,90.00000001 +295.56,50.43283629,-2.558397517,50.3254,-1.64E-11,10.0001457,-3.0365625,-0.95224749,-1.779289894,90.00000001 +295.57,50.43283629,-2.558396109,50.3557,4.69E-12,9.999479648,-3.02125,-0.849453476,-1.691929816,90.00000001 +295.58,50.43283629,-2.558394702,50.3858,1.41E-11,9.999035629,-3.005,-0.746482131,-1.603094314,90.00000001 +295.59,50.43283629,-2.558393295,50.4158,9.37E-12,9.999479743,-2.988125,-0.643354828,-1.51286091,90.00000001 +295.6,50.43283629,-2.558391887,50.4456,-4.44E-16,10.00014589,-2.969375,-0.540093222,-1.42130827,90.00000001 +295.61,50.43283629,-2.55839048,50.4752,-1.17E-11,10.00036797,-2.9484375,-0.436718745,-1.328516208,90.00000001 +295.62,50.43283629,-2.558389072,50.5046,-2.59E-11,10.00036801,-2.9265625,-0.333253167,-1.234565626,90.00000001 +295.63,50.43283629,-2.558387665,50.5337,-3.13E-11,10.00036806,-2.9046875,-0.229717917,-1.13953857,90.00000001 +295.64,50.43283629,-2.558386257,50.5627,-1.80E-11,10.00036811,-2.8815625,-0.126134711,-1.043517719,90.00000001 +295.65,50.43283629,-2.55838485,50.5914,3.12E-12,10.00014612,-2.85625,-0.022525205,-0.946587011,90.00000001 +295.66,50.43283629,-2.558383442,50.6198,1.55E-11,9.999480061,-2.8303125,0.081089055,-0.848830786,90.00000001 +295.67,50.43283629,-2.558382035,50.648,2.02E-11,9.99903604,-2.8046875,0.184686356,-0.750334413,90.00000001 +295.68,50.43283629,-2.558380628,50.6759,2.42E-11,9.99948015,-2.7778125,0.288245097,-0.651183723,90.00000001 +295.69,50.43283629,-2.55837922,50.7036,2.20E-11,10.00014629,-2.748125,0.391743678,-0.551465174,90.00000001 +295.7,50.43283629,-2.558377813,50.7309,9.38E-12,10.00036837,-2.71625,0.495160382,-0.451265742,90.00000001 +295.71,50.43283629,-2.558376405,50.7579,-5.47E-12,10.00036841,-2.6834375,0.598473726,-0.350672802,90.00000001 +295.72,50.43283629,-2.558374998,50.7846,-1.41E-11,10.00014642,-2.6496875,0.701662049,-0.249774075,90.00000001 +295.73,50.43283629,-2.55837359,50.8109,-1.62E-11,9.999480361,-2.615,0.804703868,-0.148657567,90.00000001 +295.74,50.43283629,-2.558372183,50.8369,-1.86E-11,9.999036335,-2.5796875,0.907577638,-0.047411398,90.00000001 +295.75,50.43283629,-2.558370776,50.8625,-2.56E-11,9.999480441,-2.543125,1.010261816,0.053876081,90.00000001 +295.76,50.43283629,-2.558369368,50.8878,-3.03E-11,10.00014658,-2.505,1.112735089,0.155116635,90.00000001 +295.77,50.43283629,-2.558367961,50.9126,-2.33E-11,10.00036865,-2.4665625,1.214975912,0.256221856,90.00000001 +295.78,50.43283629,-2.558366553,50.9371,-1.17E-11,10.00036869,-2.428125,1.31696303,0.357103738,90.00000001 +295.79,50.43283629,-2.558365146,50.9612,-1.00E-11,10.0001467,-2.3878125,1.418675128,0.45767416,90.00000001 +295.8,50.43283629,-2.558363738,50.9849,-1.31E-11,9.999480633,-2.345,1.52009095,0.55784546,90.00000001 +295.81,50.43283629,-2.558362331,51.0081,-6.09E-12,9.999036604,-2.3015625,1.621189353,0.657530376,90.00000001 +295.82,50.43283629,-2.558360924,51.0309,8.59E-12,9.999480706,-2.2584375,1.721949137,0.756641876,90.00000001 +295.83,50.43283629,-2.558359516,51.0533,1.80E-11,10.00014684,-2.2146875,1.822349334,0.855093558,90.00000001 +295.84,50.43283629,-2.558358109,51.0752,1.72E-11,10.00036891,-2.1696875,1.922368972,0.952799592,90.00000001 +295.85,50.43283629,-2.558356701,51.0967,9.53E-12,10.00036894,-2.123125,2.021987139,1.049674838,90.00000001 +295.86,50.43283629,-2.558355294,51.1177,2.34E-12,10.00036897,-2.0746875,2.121183035,1.145634669,90.00000001 +295.87,50.43283629,-2.558353886,51.1382,-8.33E-17,10.00036901,-2.025,2.219935978,1.240595548,90.00000001 +295.88,50.43283629,-2.558352479,51.1582,-1.94E-16,10.000147,-1.975,2.318225283,1.334474568,90.00000001 +295.89,50.43283629,-2.558351071,51.1777,1.56E-13,9.999480935,-1.925,2.41603044,1.427189911,90.00000001 +295.9,50.43283629,-2.558349664,51.1967,-1.56E-12,9.999036899,-1.8746875,2.513331049,1.518660732,90.00000001 +295.91,50.43283629,-2.558348257,51.2152,-7.81E-12,9.999480994,-1.823125,2.610106829,1.608807276,90.00000001 +295.92,50.43283629,-2.558346849,51.2332,-1.27E-11,10.00014712,-1.77,2.706337497,1.697550876,90.00000001 +295.93,50.43283629,-2.558345442,51.2506,-7.03E-12,10.00036918,-1.7165625,2.802002943,1.784814239,90.00000001 +295.94,50.43283629,-2.558344034,51.2675,3.13E-12,10.00036921,-1.663125,2.897083283,1.870521162,90.00000001 +295.95,50.43283629,-2.558342627,51.2839,2.34E-12,10.00036923,-1.608125,2.991558581,1.954596989,90.00000001 +295.96,50.43283629,-2.558341219,51.2997,-9.53E-12,10.00036926,-1.5515625,3.085409125,2.036968381,90.00000001 +295.97,50.43283629,-2.558339812,51.3149,-1.64E-11,10.00036928,-1.495,3.178615321,2.117563489,90.00000001 +295.98,50.43283629,-2.558338404,51.3296,-8.59E-12,10.0003693,-1.4384375,3.271157688,2.196312069,90.00000001 +295.99,50.43283629,-2.558336997,51.3437,7.03E-12,10.00036933,-1.3815625,3.363016917,2.273145423,90.00000001 +296,50.43283629,-2.558335589,51.3572,1.31E-11,10.00036935,-1.3246875,3.454173872,2.347996572,90.00000001 +296.01,50.43283629,-2.558334182,51.3702,-7.81E-13,10.00014734,-1.2665625,3.544609416,2.420800199,90.00000001 +296.02,50.43283629,-2.558332774,51.3826,-2.27E-11,9.999481255,-1.20625,3.634304698,2.491492935,90.00000001 +296.03,50.43283629,-2.558331367,51.3943,-3.50E-11,9.999037207,-1.1453125,3.72324104,2.560012957,90.00000001 +296.04,50.43283629,-2.55832996,51.4055,-3.75E-11,9.999481291,-1.085,3.811399822,2.626300679,90.00000001 +296.05,50.43283629,-2.558328552,51.416,-3.75E-11,10.00014741,-1.025,3.89876265,2.690298174,90.00000001 +296.06,50.43283629,-2.558327145,51.426,-3.75E-11,10.00036946,-0.965,3.985311306,2.751949693,90.00000001 +296.07,50.43283629,-2.558325737,51.4353,-3.27E-11,10.00036947,-0.904375,4.071027625,2.811201494,90.00000001 +296.08,50.43283629,-2.55832433,51.4441,-1.33E-11,10.00036948,-0.841875,4.15589379,2.868001894,90.00000001 +296.09,50.43283629,-2.558322922,51.4522,1.56E-11,10.0003695,-0.778125,4.239892038,2.922301333,90.00000001 +296.1,50.43283629,-2.558321515,51.4596,3.19E-11,10.00036951,-0.7153125,4.323004838,2.974052486,90.00000001 +296.11,50.43283629,-2.558320107,51.4665,2.58E-11,10.00036952,-0.6534375,4.405214828,3.023210259,90.00000001 +296.12,50.43283629,-2.5583187,51.4727,7.81E-12,10.00036953,-0.59125,4.486504819,3.069731682,90.00000001 +296.13,50.43283629,-2.558317292,51.4783,-7.03E-12,10.00036954,-0.528125,4.56685791,3.113576303,90.00000001 +296.14,50.43283629,-2.558315885,51.4833,-4.84E-12,10.00014751,-0.4634375,4.646257255,3.154705792,90.00000001 +296.15,50.43283629,-2.558314477,51.4876,1.41E-11,9.999481419,-0.3984375,4.724686297,3.193084396,90.00000001 +296.16,50.43283629,-2.55831307,51.4912,2.64E-11,9.999037359,-0.335,4.802128647,3.228678539,90.00000001 +296.17,50.43283629,-2.558311663,51.4943,1.56E-11,9.999481431,-0.2715625,4.878568093,3.261457226,90.00000001 +296.18,50.43283629,-2.558310255,51.4967,-2.50E-12,10.00014753,-0.2065625,4.953988762,3.291391864,90.00000001 +296.19,50.43283629,-2.558308848,51.4984,-4.69E-12,10.00036957,-0.141875,5.028374841,3.318456385,90.00000001 +296.2,50.43283629,-2.55830744,51.4995,7.03E-12,10.00036957,-0.0784375,5.101710803,3.342627182,90.00000001 +296.21,50.43283629,-2.558306033,51.5,1.64E-11,10.00036957,-0.0146875,5.17398135,3.363883114,90.00000001 +296.22,50.43283629,-2.558304625,51.4998,1.87E-11,10.00036957,0.05,5.245171356,3.382205732,90.00000001 +296.23,50.43283629,-2.558303218,51.499,1.87E-11,10.00036957,0.115,5.315265982,3.397578992,90.00000001 +296.24,50.43283629,-2.55830181,51.4975,1.86E-11,10.00036957,0.18,5.384250616,3.409989487,90.00000001 +296.25,50.43283629,-2.558300403,51.4954,1.56E-11,10.00036956,0.2446875,5.452110763,3.419426445,90.00000001 +296.26,50.43283629,-2.558298995,51.4926,5.47E-12,10.00036956,0.3084375,5.518832329,3.425881617,90.00000001 +296.27,50.43283629,-2.558297588,51.4892,-8.44E-12,10.00014752,0.3715625,5.58440139,3.429349387,90.00000001 +296.28,50.43283629,-2.55829618,51.4852,-1.66E-11,9.999481416,0.4353125,5.648804195,3.429826661,90.00000001 +296.29,50.43283629,-2.558294773,51.4805,-1.81E-11,9.999037343,0.5,5.71202728,3.427313095,90.00000001 +296.3,50.43283629,-2.558293366,51.4752,-1.66E-11,9.999481401,0.5646875,5.774057524,3.421810924,90.00000001 +296.31,50.43283629,-2.558291958,51.4692,-1.08E-11,10.00014749,0.628125,5.834881922,3.413324789,90.00000001 +296.32,50.43283629,-2.558290551,51.4626,-6.25E-12,10.00036951,0.69,5.89448781,3.401862252,90.00000001 +296.33,50.43283629,-2.558289143,51.4554,-1.03E-11,10.0003695,0.751875,5.952862698,3.387433227,90.00000001 +296.34,50.43283629,-2.558287736,51.4476,-1.50E-11,10.00036949,0.815,6.009994382,3.37005026,90.00000001 +296.35,50.43283629,-2.558286328,51.4391,-1.09E-11,10.00036948,0.878125,6.065870945,3.349728593,90.00000001 +296.36,50.43283629,-2.558284921,51.43,-3.91E-12,10.00014743,0.9396875,6.120480756,3.32648593,90.00000001 +296.37,50.43283629,-2.558283513,51.4203,-6.25E-13,9.999481314,1,6.173812355,3.300342496,90.00000001 +296.38,50.43283629,-2.558282106,51.41,6.25E-13,9.999037233,1.06,6.225854685,3.271321152,90.00000001 +296.39,50.43283629,-2.558280699,51.3991,1.56E-12,9.999481282,1.12,6.276596801,3.239447109,90.00000001 +296.4,50.43283629,-2.558279291,51.3876,1.56E-12,10.00014736,1.18,6.326028105,3.204748269,90.00000001 +296.41,50.43283629,-2.558277884,51.3755,-1.41E-12,10.00036938,1.2396875,6.374138282,3.167254828,90.00000001 +296.42,50.43283629,-2.558276476,51.3628,-1.08E-11,10.00036936,1.2984375,6.420917364,3.126999501,90.00000001 +296.43,50.43283629,-2.558275069,51.3495,-2.41E-11,10.0001473,1.3565625,6.466355495,3.084017353,90.00000001 +296.44,50.43283629,-2.558273661,51.3357,-3.05E-11,9.999481182,1.415,6.510443223,3.038345913,90.00000001 +296.45,50.43283629,-2.558272254,51.3212,-2.56E-11,9.999037093,1.473125,6.553171264,2.990025002,90.00000001 +296.46,50.43283629,-2.558270847,51.3062,-1.86E-11,9.999481136,1.5296875,6.594530852,2.939096732,90.00000001 +296.47,50.43283629,-2.558269439,51.2906,-1.63E-11,10.00014721,1.585,6.634513165,2.885605564,90.00000001 +296.48,50.43283629,-2.558268032,51.2745,-1.41E-11,10.00036922,1.6396875,6.673110009,2.829598022,90.00000001 +296.49,50.43283629,-2.558266624,51.2578,-5.31E-12,10.00036919,1.6934375,6.710313247,2.771123096,90.00000001 +296.5,50.43283629,-2.558265217,51.2406,7.97E-12,10.00014713,1.7465625,6.746115088,2.71023172,90.00000001 +296.51,50.43283629,-2.558263809,51.2229,1.50E-11,9.999481006,1.8,6.78050814,2.64697695,90.00000001 +296.52,50.43283629,-2.558262402,51.2046,1.09E-11,9.999036911,1.853125,6.813485127,2.581413962,90.00000001 +296.53,50.43283629,-2.558260995,51.1858,3.91E-12,9.999480948,1.9046875,6.84503923,2.513599938,90.00000001 +296.54,50.43283629,-2.558259587,51.1665,7.81E-13,10.00014702,1.955,6.875163862,2.443594064,90.00000001 +296.55,50.43283629,-2.55825818,51.1467,-2.19E-12,10.00036902,2.0046875,6.903852661,2.371457303,90.00000001 +296.56,50.43283629,-2.558256772,51.1264,-9.38E-12,10.00036899,2.053125,6.931099669,2.297252622,90.00000001 +296.57,50.43283629,-2.558255365,51.1056,-1.39E-11,10.00014692,2.1,6.956899271,2.221044651,90.00000001 +296.58,50.43283629,-2.558253957,51.0844,-6.25E-12,9.999480789,2.1465625,6.981245966,2.142899969,90.00000001 +296.59,50.43283629,-2.55825255,51.0627,8.59E-12,9.999036688,2.1934375,7.004134713,2.062886585,90.00000001 +296.6,50.43283629,-2.558251143,51.0405,1.80E-11,9.99948072,2.2396875,7.025560699,1.9810744,90.00000001 +296.61,50.43283629,-2.558249735,51.0179,1.73E-11,10.00014678,2.2846875,7.045519569,1.897534632,90.00000001 +296.62,50.43283629,-2.558248328,50.9948,1.03E-11,10.00036878,2.328125,7.064007027,1.812340162,90.00000001 +296.63,50.43283629,-2.55824692,50.9713,4.06E-12,10.00036874,2.3696875,7.081019232,1.725565361,90.00000001 +296.64,50.43283629,-2.558245513,50.9474,2.34E-12,10.00014667,2.41,7.096552691,1.637285857,90.00000001 +296.65,50.43283629,-2.558244105,50.9231,2.50E-12,9.999480537,2.45,7.110604137,1.547578543,90.00000001 +296.66,50.43283629,-2.558242698,50.8984,4.84E-12,9.999036432,2.4896875,7.123170649,1.456521798,90.00000001 +296.67,50.43283629,-2.558241291,50.8733,1.19E-11,9.999480458,2.528125,7.134249532,1.364194863,90.00000001 +296.68,50.43283629,-2.558239883,50.8478,1.66E-11,10.00014652,2.565,7.143838497,1.270678411,90.00000001 +296.69,50.43283629,-2.558238476,50.822,7.19E-12,10.00036851,2.60125,7.151935594,1.176053858,90.00000001 +296.7,50.43283629,-2.558237068,50.7958,-1.41E-11,10.00036847,2.6365625,7.158539104,1.080403768,90.00000001 +296.71,50.43283629,-2.558235661,50.7692,-2.89E-11,10.00036843,2.6696875,7.163647653,0.983811563,90.00000001 +296.72,50.43283629,-2.558234253,50.7424,-2.58E-11,10.00036839,2.7015625,7.167260152,0.886361469,90.00000001 +296.73,50.43283629,-2.558232846,50.7152,-1.31E-11,10.00036834,2.7334375,7.169375856,0.788138398,90.00000001 +296.74,50.43283629,-2.558231438,50.6877,-1.41E-12,10.0003683,2.764375,7.169994364,0.68922812,90.00000001 +296.75,50.43283629,-2.558230031,50.6599,9.38E-12,10.00036826,2.793125,7.169115447,0.589716811,90.00000001 +296.76,50.43283629,-2.558228623,50.6318,1.55E-11,10.00036821,2.82,7.166739391,0.489691271,90.00000001 +296.77,50.43283629,-2.558227216,50.6035,6.25E-12,10.00014614,2.84625,7.162866654,0.389238706,90.00000001 +296.78,50.43283629,-2.558225808,50.5749,-1.56E-11,9.999479992,2.8715625,7.15749804,0.288446721,90.00000001 +296.79,50.43283629,-2.558224401,50.546,-2.80E-11,9.999035881,2.895,7.150634693,0.18740315,90.00000001 +296.8,50.43283629,-2.558222994,50.517,-1.41E-11,9.999479901,2.918125,7.142277989,0.086196229,90.00000001 +296.81,50.43283629,-2.558221586,50.4877,1.17E-11,10.00014595,2.9415625,7.132429704,-0.015085864,90.00000001 +296.82,50.43283629,-2.558220179,50.4581,2.34E-11,10.00036794,2.9625,7.121091958,-0.116354837,90.00000001 +296.83,50.43283629,-2.558218771,50.4284,2.33E-11,10.0003679,2.98,7.108267042,-0.217522338,90.00000001 +296.84,50.43283629,-2.558217364,50.3985,2.97E-11,10.00036785,2.9965625,7.093957593,-0.318500134,90.00000001 +296.85,50.43283629,-2.558215956,50.3685,4.06E-11,10.0003678,3.013125,7.078166762,-0.419200216,90.00000001 +296.86,50.43283629,-2.558214549,50.3382,3.83E-11,10.00036775,3.0284375,7.060897699,-0.519534695,90.00000001 +296.87,50.43283629,-2.558213141,50.3079,1.56E-11,10.00036771,3.0428125,7.042154015,-0.619416193,90.00000001 +296.88,50.43283629,-2.558211734,50.2774,-1.19E-11,10.00036766,3.0565625,7.021939721,-0.718757506,90.00000001 +296.89,50.43283629,-2.558210326,50.2467,-2.09E-11,10.00036761,3.0678125,7.000258998,-0.817472118,90.00000001 +296.9,50.43283629,-2.558208919,50.216,-1.09E-11,10.00014553,3.0765625,6.977116315,-0.915473799,90.00000001 +296.91,50.43283629,-2.558207511,50.1852,-3.13E-12,9.999479383,3.085,6.952516602,-1.012677234,90.00000001 +296.92,50.43283629,-2.558206104,50.1543,-7.81E-12,9.999035268,3.093125,6.926464898,-1.10899757,90.00000001 +296.93,50.43283629,-2.558204697,50.1233,-1.80E-11,9.999479285,3.099375,6.898966706,-1.204350868,90.00000001 +296.94,50.43283629,-2.558203289,50.0923,-2.80E-11,10.00014534,3.103125,6.870027753,-1.298653934,90.00000001 +296.95,50.43283629,-2.558201882,50.0612,-3.28E-11,10.00036732,3.105,6.839654057,-1.39182455,90.00000001 +296.96,50.43283629,-2.558200474,50.0302,-2.58E-11,10.00036727,3.1065625,6.807852035,-1.483781525,90.00000001 +296.97,50.43283629,-2.558199067,49.9991,-1.17E-11,10.00036722,3.1084375,6.774628275,-1.574444534,90.00000001 +296.98,50.43283629,-2.558197659,49.968,-2.50E-16,10.00036717,3.109375,6.739989711,-1.663734677,90.00000001 +296.99,50.43283629,-2.558196252,49.9369,9.37E-12,10.00036713,3.108125,6.703943561,-1.751573978,90.00000001 +297,50.43283629,-2.558194844,49.9058,1.64E-11,10.00036708,3.1046875,6.666497388,-1.837885887,90.00000001 +297.01,50.43283629,-2.558193437,49.8748,1.64E-11,10.00036703,3.0996875,6.627659043,-1.922595176,90.00000001 +297.02,50.43283629,-2.558192029,49.8438,9.38E-12,10.00036698,3.093125,6.587436546,-2.005627876,90.00000001 +297.03,50.43283629,-2.558190622,49.8129,2.34E-12,10.0001449,3.0846875,6.545838378,-2.086911679,90.00000001 +297.04,50.43283629,-2.558189214,49.7821,-1.94E-16,9.999478753,3.075,6.50287319,-2.166375654,90.00000001 +297.05,50.43283629,-2.558187807,49.7514,-2.22E-16,9.999034638,3.065,6.45854992,-2.243950473,90.00000001 +297.06,50.43283629,-2.5581864,49.7208,2.34E-12,9.999478656,3.0546875,6.412877907,-2.319568583,90.00000001 +297.07,50.43283629,-2.558184992,49.6903,9.37E-12,10.00014471,3.043125,6.365866662,-2.393163981,90.00000001 +297.08,50.43283629,-2.558183585,49.6599,1.87E-11,10.00036669,3.029375,6.317525984,-2.464672494,90.00000001 +297.09,50.43283629,-2.558182177,49.6297,2.81E-11,10.00036665,3.013125,6.267865898,-2.534031785,90.00000001 +297.1,50.43283629,-2.55818077,49.5996,3.28E-11,10.0003666,2.995,6.216896948,-2.60118135,90.00000001 +297.11,50.43283629,-2.558179362,49.5698,2.58E-11,10.00036655,2.9765625,6.164629618,-2.66606269,90.00000001 +297.12,50.43283629,-2.558177955,49.5401,1.19E-11,10.00036651,2.9584375,6.111074909,-2.728619139,90.00000001 +297.13,50.43283629,-2.558176547,49.5106,7.81E-13,10.00036646,2.939375,6.056243937,-2.788796208,90.00000001 +297.14,50.43283629,-2.55817514,49.4813,-7.81E-12,10.00014438,2.918125,6.000148275,-2.846541416,90.00000001 +297.15,50.43283629,-2.558173732,49.4522,-1.48E-11,9.999478236,2.8946875,5.942799497,-2.901804398,90.00000001 +297.16,50.43283629,-2.558172325,49.4234,-1.80E-11,9.999034125,2.87,5.884209635,-2.954536913,90.00000001 +297.17,50.43283629,-2.558170918,49.3948,-1.87E-11,9.999478147,2.845,5.82439095,-3.004693065,90.00000001 +297.18,50.43283629,-2.55816951,49.3665,-1.48E-11,10.0001442,2.819375,5.763355933,-3.052229082,90.00000001 +297.19,50.43283629,-2.558168103,49.3384,7.82E-13,10.00036619,2.7915625,5.701117304,-3.097103537,90.00000001 +297.2,50.43283629,-2.558166695,49.3106,1.97E-11,10.00036615,2.7615625,5.637688069,-3.139277242,90.00000001 +297.21,50.43283629,-2.558165288,49.2832,2.11E-11,10.00014407,2.7315625,5.573081462,-3.178713411,90.00000001 +297.22,50.43283629,-2.55816388,49.256,6.25E-12,9.999477929,2.70125,5.507311007,-3.215377782,90.00000001 +297.23,50.43283629,-2.558162473,49.2291,2.34E-12,9.999033822,2.668125,5.440390396,-3.249238213,90.00000001 +297.24,50.43283629,-2.558161066,49.2026,2.12E-11,9.999477845,2.633125,5.372333667,-3.28026531,90.00000001 +297.25,50.43283629,-2.558159658,49.1765,4.23E-11,10.0001439,2.5984375,5.303154972,-3.308431973,90.00000001 +297.26,50.43283629,-2.558158251,49.1506,4.47E-11,10.0003659,2.563125,5.232868749,-3.333713563,90.00000001 +297.27,50.43283629,-2.558156843,49.1252,3.06E-11,10.00036586,2.52625,5.161489724,-3.356088196,90.00000001 +297.28,50.43283629,-2.558155436,49.1001,1.66E-11,10.00014378,2.488125,5.089032851,-3.375536217,90.00000001 +297.29,50.43283629,-2.558154028,49.0754,1.64E-11,9.999477646,2.448125,5.015513142,-3.392040724,90.00000001 +297.3,50.43283629,-2.558152621,49.0511,2.73E-11,9.999033543,2.4065625,4.940946008,-3.405587337,90.00000001 +297.31,50.43283629,-2.558151214,49.0273,3.28E-11,9.999477572,2.365,4.865347034,-3.416164195,90.00000001 +297.32,50.43283629,-2.558149806,49.0038,2.44E-11,10.00014363,2.3234375,4.788731977,-3.423762132,90.00000001 +297.33,50.43283629,-2.558148399,48.9808,7.81E-12,10.00036563,2.28125,4.71111688,-3.428374499,90.00000001 +297.34,50.43283629,-2.558146991,48.9582,-5.47E-12,10.00036559,2.238125,4.632517899,-3.429997287,90.00000001 +297.35,50.43283629,-2.558145584,48.936,-4.84E-12,10.00014353,2.193125,4.552951479,-3.428629064,90.00000001 +297.36,50.43283629,-2.558144176,48.9143,9.38E-12,9.999477395,2.14625,4.472434293,-3.424270975,90.00000001 +297.37,50.43283629,-2.558142769,48.8931,2.58E-11,9.999033295,2.0984375,4.390983014,-3.416926917,90.00000001 +297.38,50.43283629,-2.558141362,48.8723,3.28E-11,9.999477329,2.05,4.308614774,-3.406603249,90.00000001 +297.39,50.43283629,-2.558139954,48.8521,2.34E-11,10.0001434,2.00125,4.22534676,-3.393308966,90.00000001 +297.4,50.43283629,-2.558138547,48.8323,1.94E-16,10.0003654,1.951875,4.141196277,-3.377055643,90.00000001 +297.41,50.43283629,-2.558137139,48.813,-2.36E-11,10.00036537,1.90125,4.056180971,-3.357857547,90.00000001 +297.42,50.43283629,-2.558135732,48.7943,-3.36E-11,10.00014331,1.85,3.970318604,-3.335731292,90.00000001 +297.43,50.43283629,-2.558134324,48.776,-2.97E-11,9.999477178,1.798125,3.883627111,-3.310696245,90.00000001 +297.44,50.43283629,-2.558132917,48.7583,-2.25E-11,9.999033085,1.7446875,3.796124538,-3.282774178,90.00000001 +297.45,50.43283629,-2.55813151,48.7411,-1.88E-11,9.999477124,1.69,3.707829221,-3.251989556,90.00000001 +297.46,50.43283629,-2.558130102,48.7245,-1.72E-11,10.0001432,1.635,3.618759551,-3.218369081,90.00000001 +297.47,50.43283629,-2.558128695,48.7084,-1.64E-11,10.0003652,1.58,3.52893415,-3.1819422,90.00000001 +297.48,50.43283629,-2.558127287,48.6929,-1.39E-11,10.00036518,1.5246875,3.438371753,-3.142740542,90.00000001 +297.49,50.43283629,-2.55812588,48.6779,-4.69E-12,10.00036516,1.4684375,3.347091326,-3.100798427,90.00000001 +297.5,50.43283629,-2.558124472,48.6635,8.59E-12,10.00036513,1.4115625,3.25511189,-3.056152353,90.00000001 +297.51,50.43283629,-2.558123065,48.6497,1.17E-11,10.00036511,1.3546875,3.16245264,-3.00884128,90.00000001 +297.52,50.43283629,-2.558121657,48.6364,-3.75E-12,10.00036509,1.2965625,3.069132998,-2.958906461,90.00000001 +297.53,50.43283629,-2.55812025,48.6237,-2.27E-11,10.00014304,1.2365625,2.975172389,-2.906391441,90.00000001 +297.54,50.43283629,-2.558118842,48.6117,-2.19E-11,9.999476921,1.1765625,2.880590464,-2.851341943,90.00000001 +297.55,50.43283629,-2.558117435,48.6002,-1.56E-13,9.999032837,1.116875,2.785406934,-2.793806094,90.00000001 +297.56,50.43283629,-2.558116028,48.5893,2.34E-11,9.999476886,1.05625,2.689641736,-2.733833971,90.00000001 +297.57,50.43283629,-2.55811462,48.5791,3.52E-11,10.00014297,0.9953125,2.593314869,-2.671477943,90.00000001 +297.58,50.43283629,-2.558113213,48.5694,3.77E-11,10.00036499,0.935,2.496446384,-2.606792326,90.00000001 +297.59,50.43283629,-2.558111805,48.5604,3.36E-11,10.00036497,0.874375,2.399056508,-2.539833498,90.00000001 +297.6,50.43283629,-2.558110398,48.5519,1.56E-11,10.00036496,0.811875,2.301165694,-2.47065996,90.00000001 +297.61,50.43283629,-2.55810899,48.5441,-1.27E-11,10.00036495,0.748125,2.202794284,-2.399331928,90.00000001 +297.62,50.43283629,-2.558107583,48.537,-3.05E-11,10.00036494,0.6853125,2.103962846,-2.325911684,90.00000001 +297.63,50.43283629,-2.558106175,48.5304,-2.97E-11,10.00036493,0.623125,2.004692006,-2.250463169,90.00000001 +297.64,50.43283629,-2.558104768,48.5245,-2.34E-11,10.00036492,0.5596875,1.905002507,-2.173052274,90.00000001 +297.65,50.43283629,-2.55810336,48.5192,-1.89E-11,10.00036491,0.4953125,1.804915202,-2.093746378,90.00000001 +297.66,50.43283629,-2.558101953,48.5146,-9.37E-12,10.00014287,0.4315625,1.704450949,-2.012614752,90.00000001 +297.67,50.43283629,-2.558100545,48.5106,5.31E-12,9.999476763,0.3684375,1.603630774,-1.929728099,90.00000001 +297.68,50.43283629,-2.558099138,48.5072,1.55E-11,9.999032692,0.3046875,1.502475649,-1.845158669,90.00000001 +297.69,50.43283629,-2.558097731,48.5045,1.78E-11,9.999476754,0.24,1.401006771,-1.758980202,90.00000001 +297.7,50.43283629,-2.558096323,48.5024,1.48E-11,10.00014285,0.1753125,1.299245341,-1.671267926,90.00000001 +297.71,50.43283629,-2.558094916,48.501,5.47E-12,10.00036488,0.1115625,1.197212559,-1.582098276,90.00000001 +297.72,50.43283629,-2.558093508,48.5002,-5.47E-12,10.00036488,0.048125,1.094929738,-1.491549,90.00000001 +297.73,50.43283629,-2.558092101,48.5,-5.00E-12,10.00036488,-0.016875,0.992418249,-1.399699052,90.00000001 +297.74,50.43283629,-2.558090693,48.5005,3.91E-12,10.00036488,-0.083125,0.889699521,-1.30662859,90.00000001 +297.75,50.43283629,-2.558089286,48.5017,3.13E-12,10.00036488,-0.148125,0.786794983,-1.212418687,90.00000001 +297.76,50.43283629,-2.558087878,48.5035,-8.44E-12,10.00036488,-0.2115625,0.683726179,-1.117151562,90.00000001 +297.77,50.43283629,-2.558086471,48.5059,-1.41E-11,10.00036489,-0.275,0.580514535,-1.020910294,90.00000001 +297.78,50.43283629,-2.558085063,48.509,-5.62E-12,10.00036489,-0.3384375,0.477181712,-0.923778707,90.00000001 +297.79,50.43283629,-2.558083656,48.5127,8.44E-12,10.00014287,-0.4015625,0.373749193,-0.825841656,90.00000001 +297.8,50.43283629,-2.558082248,48.517,1.66E-11,9.999476773,-0.4653125,0.270238638,-0.727184397,90.00000001 +297.81,50.43283629,-2.558080841,48.522,1.81E-11,9.999032715,-0.53,0.166671589,-0.627893046,90.00000001 +297.82,50.43283629,-2.558079434,48.5276,1.66E-11,9.99947679,-0.5946875,0.063069819,-0.528054119,90.00000001 +297.83,50.43283629,-2.558078026,48.5339,1.08E-11,10.0001429,-0.658125,-0.040545186,-0.427754763,90.00000001 +297.84,50.43283629,-2.558076619,48.5408,6.25E-12,10.00036494,-0.72,-0.144151712,-0.327082411,90.00000001 +297.85,50.43283629,-2.558075211,48.5483,1.02E-11,10.00036495,-0.781875,-0.2477281,-0.226124784,90.00000001 +297.86,50.43283629,-2.558073804,48.5564,1.42E-11,10.00036497,-0.845,-0.35125275,-0.124970002,90.00000001 +297.87,50.43283629,-2.558072396,48.5652,9.38E-12,10.00036498,-0.908125,-0.454704062,-0.023706243,90.00000001 +297.88,50.43283629,-2.558070989,48.5746,2.34E-12,10.000365,-0.9696875,-0.558060434,0.077578142,90.00000001 +297.89,50.43283629,-2.558069581,48.5846,2.78E-16,10.00036501,-1.03,-0.661300267,0.178794918,90.00000001 +297.9,50.43283629,-2.558068174,48.5952,2.78E-16,10.00036503,-1.09,-0.764401959,0.279855792,90.00000001 +297.91,50.43283629,-2.558066766,48.6064,1.67E-16,10.00036505,-1.15,-0.867344026,0.380672643,90.00000001 +297.92,50.43283629,-2.558065359,48.6182,-2.19E-12,10.00014303,-1.2096875,-0.970104981,0.481157523,90.00000001 +297.93,50.43283629,-2.558063951,48.6306,-1.09E-11,9.999476951,-1.2684375,-1.072663337,0.581222769,90.00000001 +297.94,50.43283629,-2.558062544,48.6436,-2.41E-11,9.999032905,-1.3265625,-1.174997667,0.680781233,90.00000001 +297.95,50.43283629,-2.558061137,48.6571,-3.05E-11,9.999476992,-1.385,-1.277086657,0.779746056,90.00000001 +297.96,50.43283629,-2.558059729,48.6713,-2.56E-11,10.00014311,-1.443125,-1.378908878,0.878030949,90.00000001 +297.97,50.43283629,-2.558058322,48.686,-1.86E-11,10.00036517,-1.4996875,-1.480443187,0.975550142,90.00000001 +297.98,50.43283629,-2.558056914,48.7013,-1.63E-11,10.00036519,-1.555,-1.581668271,1.072218665,90.00000001 +297.99,50.43283629,-2.558055507,48.7171,-1.64E-11,10.00014319,-1.61,-1.682563102,1.167952177,90.00000001 +298,50.43283629,-2.558054099,48.7335,-1.72E-11,9.999477112,-1.665,-1.783106481,1.2626672,90.00000001 +298.01,50.43283629,-2.558052692,48.7504,-1.64E-11,9.999033072,-1.7196875,-1.883277551,1.356281227,90.00000001 +298.02,50.43283629,-2.558051285,48.7679,-8.44E-12,9.999477165,-1.7734375,-1.983055287,1.448712498,90.00000001 +298.03,50.43283629,-2.558049877,48.7859,7.81E-12,10.00014329,-1.82625,-2.082418888,1.539880453,90.00000001 +298.04,50.43283629,-2.55804847,48.8044,2.50E-11,10.00036535,-1.8784375,-2.181347614,1.629705683,90.00000001 +298.05,50.43283629,-2.558047062,48.8235,3.50E-11,10.00036538,-1.9296875,-2.279820782,1.718109747,90.00000001 +298.06,50.43283629,-2.558045655,48.843,3.52E-11,10.00014338,-1.9796875,-2.377817822,1.805015585,90.00000001 +298.07,50.43283629,-2.558044247,48.8631,2.58E-11,9.999477314,-2.0284375,-2.475318336,1.890347392,90.00000001 +298.08,50.43283629,-2.55804284,48.8836,9.38E-12,9.999033281,-2.07625,-2.572301871,1.974030858,90.00000001 +298.09,50.43283629,-2.558041433,48.9046,-7.03E-12,9.99947738,-2.1234375,-2.6687482,2.055992871,90.00000001 +298.1,50.43283629,-2.558040025,48.9261,-1.39E-11,10.00014351,-2.17,-2.764637214,2.1361621,90.00000001 +298.11,50.43283629,-2.558038618,48.948,-3.91E-12,10.00036558,-2.21625,-2.859948857,2.214468528,90.00000001 +298.12,50.43283629,-2.55803721,48.9704,1.80E-11,10.00036561,-2.2615625,-2.954663307,2.290843917,90.00000001 +298.13,50.43283629,-2.558035803,48.9933,3.19E-11,10.00014362,-2.3046875,-3.048760624,2.365221631,90.00000001 +298.14,50.43283629,-2.558034395,49.0165,2.81E-11,9.999477555,-2.346875,-3.142221271,2.437536812,90.00000001 +298.15,50.43283629,-2.558032988,49.0402,2.20E-11,9.999033526,-2.39,-3.235025709,2.507726491,90.00000001 +298.16,50.43283629,-2.558031581,49.0643,2.20E-11,9.999477629,-2.4325,-3.327154572,2.575729362,90.00000001 +298.17,50.43283629,-2.558030173,49.0889,1.17E-11,10.00014377,-2.4715625,-3.418588609,2.641486181,90.00000001 +298.18,50.43283629,-2.558028766,49.1138,-1.25E-11,10.00036584,-2.508125,-3.509308684,2.704939538,90.00000001 +298.19,50.43283629,-2.558027358,49.139,-2.83E-11,10.00036588,-2.5453125,-3.599295888,2.766034199,90.00000001 +298.2,50.43283629,-2.558025951,49.1647,-2.66E-11,10.00014389,-2.583125,-3.688531429,2.824716823,90.00000001 +298.21,50.43283629,-2.558024543,49.1907,-1.88E-11,9.999477827,-2.619375,-3.776996686,2.880936244,90.00000001 +298.22,50.43283629,-2.558023136,49.2171,-1.08E-11,9.999033802,-2.653125,-3.864673151,2.934643417,90.00000001 +298.23,50.43283629,-2.558021729,49.2438,-3.75E-12,9.99947791,-2.6846875,-3.951542548,2.985791589,90.00000001 +298.24,50.43283629,-2.558020321,49.2708,2.34E-12,10.00014405,-2.7153125,-4.037586714,3.034336068,90.00000001 +298.25,50.43283629,-2.558018914,49.2981,1.31E-11,10.00036613,-2.7465625,-4.122787658,3.080234571,90.00000001 +298.26,50.43283629,-2.558017506,49.3257,2.27E-11,10.00036617,-2.7778125,-4.207127619,3.123447105,90.00000001 +298.27,50.43283629,-2.558016099,49.3537,1.27E-11,10.00036621,-2.8065625,-4.290588948,3.163935913,90.00000001 +298.28,50.43283629,-2.558014691,49.3819,-1.55E-11,10.00036626,-2.8328125,-4.373154287,3.201665699,90.00000001 +298.29,50.43283629,-2.558013284,49.4103,-3.83E-11,10.00014427,-2.8584375,-4.45480633,3.236603577,90.00000001 +298.3,50.43283629,-2.558011876,49.4391,-4.06E-11,9.999478215,-2.883125,-4.535528062,3.268719122,90.00000001 +298.31,50.43283629,-2.558010469,49.468,-2.73E-11,9.999034195,-2.90625,-4.61530258,3.297984316,90.00000001 +298.32,50.43283629,-2.558009062,49.4972,-1.16E-11,9.999478307,-2.9284375,-4.694113269,3.324373607,90.00000001 +298.33,50.43283629,-2.558007654,49.5266,-2.34E-12,10.00014445,-2.9496875,-4.771943626,3.347863959,90.00000001 +298.34,50.43283629,-2.558006247,49.5562,4.44E-16,10.00036653,-2.97,-4.848777439,3.36843492,90.00000001 +298.35,50.43283629,-2.558004839,49.586,2.34E-12,10.00036658,-2.9896875,-4.924598663,3.386068613,90.00000001 +298.36,50.43283629,-2.558003432,49.616,7.03E-12,10.00036662,-3.0078125,-4.999391427,3.400749568,90.00000001 +298.37,50.43283629,-2.558002024,49.6462,4.69E-12,10.00036667,-3.023125,-5.073140148,3.412465008,90.00000001 +298.38,50.43283629,-2.558000617,49.6765,-9.37E-12,10.00036672,-3.03625,-5.145829413,3.421204734,90.00000001 +298.39,50.43283629,-2.557999209,49.7069,-2.58E-11,10.00036677,-3.0484375,-5.217444038,3.426961127,90.00000001 +298.4,50.43283629,-2.557997802,49.7375,-3.28E-11,10.00036681,-3.06,-5.287969069,3.4297292,90.00000001 +298.41,50.43283629,-2.557996394,49.7681,-2.34E-11,10.00036686,-3.07125,-5.357389724,3.429506434,90.00000001 +298.42,50.43283629,-2.557994987,49.7989,-2.34E-12,10.00014488,-3.0815625,-5.425691622,3.426293115,90.00000001 +298.43,50.43283629,-2.557993579,49.8298,1.17E-11,9.999478826,-3.0896875,-5.492860381,3.420091993,90.00000001 +298.44,50.43283629,-2.557992172,49.8607,4.69E-12,9.999034809,-3.09625,-5.558882079,3.410908568,90.00000001 +298.45,50.43283629,-2.557990765,49.8917,-1.64E-11,9.999478924,-3.1015625,-5.623742849,3.39875069,90.00000001 +298.46,50.43283629,-2.557989357,49.9228,-3.05E-11,10.00014507,-3.1046875,-5.687429171,3.383629131,90.00000001 +298.47,50.43283629,-2.55798795,49.9538,-2.58E-11,10.00036715,-3.1065625,-5.749927751,3.365556953,90.00000001 +298.48,50.43283629,-2.557986542,49.9849,-1.17E-11,10.0003672,-3.1084375,-5.811225526,3.344549971,90.00000001 +298.49,50.43283629,-2.557985135,50.016,2.50E-16,10.00036725,-3.109375,-5.871309662,3.320626463,90.00000001 +298.5,50.43283629,-2.557983727,50.0471,9.38E-12,10.0003673,-3.108125,-5.930167725,3.293807339,90.00000001 +298.51,50.43283629,-2.55798232,50.0782,1.41E-11,10.00036735,-3.105,-5.987787283,3.264115979,90.00000001 +298.52,50.43283629,-2.557980912,50.1092,4.69E-12,10.0003674,-3.10125,-6.044156418,3.231578221,90.00000001 +298.53,50.43283629,-2.557979505,50.1402,-1.64E-11,10.00036744,-3.0965625,-6.09926327,3.196222543,90.00000001 +298.54,50.43283629,-2.557978097,50.1712,-3.05E-11,10.00036749,-3.0896875,-6.153096436,3.158079654,90.00000001 +298.55,50.43283629,-2.55797669,50.202,-2.34E-11,10.00014551,-3.08125,-6.205644515,3.1171829,90.00000001 +298.56,50.43283629,-2.557975282,50.2328,2.22E-16,9.999479457,-3.071875,-6.256896679,3.073567921,90.00000001 +298.57,50.43283629,-2.557973875,50.2635,2.58E-11,9.999035439,-3.0609375,-6.306842155,3.027272759,90.00000001 +298.58,50.43283629,-2.557972468,50.294,4.45E-11,9.999479553,-3.0484375,-6.355470572,2.978337751,90.00000001 +298.59,50.43283629,-2.55797106,50.3245,5.16E-11,10.0001457,-3.035,-6.402771676,2.926805584,90.00000001 +298.6,50.43283629,-2.557969653,50.3547,4.22E-11,10.00036778,-3.02125,-6.448735668,2.872721175,90.00000001 +298.61,50.43283629,-2.557968245,50.3849,2.11E-11,10.00036783,-3.0065625,-6.493352923,2.816131738,90.00000001 +298.62,50.43283629,-2.557966838,50.4149,4.69E-12,10.00036787,-2.989375,-6.536614101,2.757086604,90.00000001 +298.63,50.43283629,-2.55796543,50.4447,-4.44E-16,10.00036792,-2.97,-6.578510208,2.695637224,90.00000001 +298.64,50.43283629,-2.557964023,50.4743,-2.50E-12,10.00036797,-2.9496875,-6.619032476,2.631837228,90.00000001 +298.65,50.43283629,-2.557962615,50.5037,-1.02E-11,10.00036801,-2.928125,-6.658172426,2.565742192,90.00000001 +298.66,50.43283629,-2.557961208,50.5329,-1.56E-11,10.00036806,-2.905,-6.695921922,2.497409813,90.00000001 +298.67,50.43283629,-2.5579598,50.5618,-8.59E-12,10.0003681,-2.8815625,-6.732273058,2.426899678,90.00000001 +298.68,50.43283629,-2.557958393,50.5905,3.91E-12,10.00014612,-2.858125,-6.767218269,2.354273267,90.00000001 +298.69,50.43283629,-2.557956985,50.619,7.03E-12,9.99948006,-2.8328125,-6.800750166,2.279593833,90.00000001 +298.7,50.43283629,-2.557955578,50.6472,5.47E-12,9.999036039,-2.805,-6.832861872,2.20292658,90.00000001 +298.71,50.43283629,-2.557954171,50.6751,1.33E-11,9.999480149,-2.7765625,-6.863546627,2.124338371,90.00000001 +298.72,50.43283629,-2.557952763,50.7027,2.25E-11,10.00014629,-2.7478125,-6.892797956,2.043897675,90.00000001 +298.73,50.43283629,-2.557951356,50.7301,1.17E-11,10.00036837,-2.7165625,-6.9206099,1.961674679,90.00000001 +298.74,50.43283629,-2.557949948,50.7571,-1.56E-11,10.00036841,-2.683125,-6.946976501,1.877741117,90.00000001 +298.75,50.43283629,-2.557948541,50.7837,-3.05E-11,10.00036845,-2.65,-6.971892316,1.7921701,90.00000001 +298.76,50.43283629,-2.557947133,50.8101,-1.89E-11,10.00036849,-2.6165625,-6.995352187,1.705036283,90.00000001 +298.77,50.43283629,-2.557945726,50.8361,2.19E-12,10.0001465,-2.58125,-7.017351131,1.61641564,90.00000001 +298.78,50.43283629,-2.557944318,50.8617,1.16E-11,9.99948044,-2.545,-7.037884563,1.526385464,90.00000001 +298.79,50.43283629,-2.557942911,50.887,6.87E-12,9.999036414,-2.508125,-7.056948301,1.43502425,90.00000001 +298.8,50.43283629,-2.557941504,50.9119,-1.57E-13,9.999480519,-2.4696875,-7.07453822,1.342411695,90.00000001 +298.81,50.43283629,-2.557940096,50.9364,-6.66E-16,10.00014666,-2.4296875,-7.09065071,1.248628531,90.00000001 +298.82,50.43283629,-2.557938689,50.9605,1.00E-11,10.00036873,-2.3884375,-7.105282448,1.153756518,90.00000001 +298.83,50.43283629,-2.557937281,50.9842,2.72E-11,10.00036876,-2.34625,-7.11843034,1.057878448,90.00000001 +298.84,50.43283629,-2.557935874,51.0074,4.36E-11,10.00014677,-2.3034375,-7.130091635,0.961077859,90.00000001 +298.85,50.43283629,-2.557934466,51.0303,5.23E-11,9.999480704,-2.2596875,-7.14026387,0.863439204,90.00000001 +298.86,50.43283629,-2.557933059,51.0526,5.23E-11,9.999036673,-2.2146875,-7.148944983,0.765047626,90.00000001 +298.87,50.43283629,-2.557931652,51.0746,4.38E-11,9.999480773,-2.1684375,-7.156133082,0.665988952,90.00000001 +298.88,50.43283629,-2.557930244,51.096,3.03E-11,10.00014691,-2.1215625,-7.161826793,0.566349472,90.00000001 +298.89,50.43283629,-2.557928837,51.117,2.34E-11,10.00036897,-2.075,-7.166024798,0.466216159,90.00000001 +298.9,50.43283629,-2.557927429,51.1375,2.58E-11,10.000369,-2.0278125,-7.168726294,0.365676275,90.00000001 +298.91,50.43283629,-2.557926022,51.1576,2.36E-11,10.000147,-1.978125,-7.169930651,0.264817483,90.00000001 +298.92,50.43283629,-2.557924614,51.1771,1.25E-11,9.999480934,-1.9265625,-7.169637698,0.163727847,90.00000001 +298.93,50.43283629,-2.557923207,51.1961,3.91E-12,9.999036898,-1.8753125,-7.167847434,0.062495372,90.00000001 +298.94,50.43283629,-2.5579218,51.2146,-7.81E-13,9.999480992,-1.8246875,-7.16456026,-0.038791535,90.00000001 +298.95,50.43283629,-2.557920392,51.2326,-8.44E-12,10.00014712,-1.773125,-7.159776865,-0.140044693,90.00000001 +298.96,50.43283629,-2.557918985,51.2501,-1.55E-11,10.00036918,-1.7196875,-7.153498279,-0.241175698,90.00000001 +298.97,50.43283629,-2.557917577,51.267,-1.70E-11,10.00036921,-1.665,-7.145725705,-0.342096369,90.00000001 +298.98,50.43283629,-2.55791617,51.2834,-1.64E-11,10.0001472,-1.61,-7.13646092,-0.442718759,90.00000001 +298.99,50.43283629,-2.557914762,51.2992,-1.39E-11,9.999481125,-1.5546875,-7.1257057,-0.542955032,90.00000001 +299,50.43283629,-2.557913355,51.3145,-7.03E-12,9.999037083,-1.498125,-7.113462394,-0.642717928,90.00000001 +299.01,50.43283629,-2.557911948,51.3292,-3.13E-12,9.999481172,-1.44,-7.099733581,-0.741920299,90.00000001 +299.02,50.43283629,-2.55791054,51.3433,-9.38E-12,10.00014729,-1.381875,-7.08452201,-0.840475743,90.00000001 +299.03,50.43283629,-2.557909133,51.3568,-1.55E-11,10.00036935,-1.325,-7.067830947,-0.93829826,90.00000001 +299.04,50.43283629,-2.557907725,51.3698,-1.09E-11,10.00036937,-1.268125,-7.049663888,-1.035302536,90.00000001 +299.05,50.43283629,-2.557906318,51.3822,-7.82E-13,10.00036939,-1.209375,-7.030024556,-1.131404059,90.00000001 +299.06,50.43283629,-2.55790491,51.394,1.16E-11,10.00036941,-1.1484375,-7.008917135,-1.226519006,90.00000001 +299.07,50.43283629,-2.557903503,51.4052,2.34E-11,10.00014739,-1.086875,-6.986345921,-1.320564356,90.00000001 +299.08,50.43283629,-2.557902095,51.4157,2.11E-11,9.999481307,-1.0265625,-6.962315784,-1.413458175,90.00000001 +299.09,50.43283629,-2.557900688,51.4257,2.34E-12,9.999037257,-0.9665625,-6.936831596,-1.505119448,90.00000001 +299.1,50.43283629,-2.557899281,51.4351,-1.19E-11,9.999481338,-0.9046875,-6.909898798,-1.595468188,90.00000001 +299.11,50.43283629,-2.557897873,51.4438,-1.02E-11,10.00014745,-0.841875,-6.881522891,-1.684425673,90.00000001 +299.12,50.43283629,-2.557896466,51.4519,-6.25E-12,10.0003695,-0.78,-6.851709892,-1.77191438,90.00000001 +299.13,50.43283629,-2.557895058,51.4594,-1.08E-11,10.00036951,-0.718125,-6.820465987,-1.857857878,90.00000001 +299.14,50.43283629,-2.557893651,51.4663,-1.41E-11,10.00036952,-0.655,-6.787797767,-1.942181337,90.00000001 +299.15,50.43283629,-2.557892243,51.4725,-7.81E-12,10.00036953,-0.591875,-6.753711935,-2.024811133,90.00000001 +299.16,50.43283629,-2.557890836,51.4781,-4.69E-12,10.00036954,-0.5296875,-6.71821571,-2.105675302,90.00000001 +299.17,50.43283629,-2.557889428,51.4831,-1.86E-11,10.00036954,-0.4665625,-6.681316483,-2.184703314,90.00000001 +299.18,50.43283629,-2.557888021,51.4875,-3.75E-11,10.00014752,-0.4015625,-6.643021932,-2.261826183,90.00000001 +299.19,50.43283629,-2.557886613,51.4911,-4.05E-11,9.999481426,-0.336875,-6.603340079,-2.336976702,90.00000001 +299.2,50.43283629,-2.557885206,51.4942,-2.97E-11,9.999037364,-0.2734375,-6.56227923,-2.410089383,90.00000001 +299.21,50.43283629,-2.557883799,51.4966,-2.09E-11,9.999481433,-0.2096875,-6.519847867,-2.481100454,90.00000001 +299.22,50.43283629,-2.557882391,51.4984,-1.88E-11,10.00014754,-0.145,-6.476054983,-2.549947922,90.00000001 +299.23,50.43283629,-2.557880984,51.4995,-1.88E-11,10.00036957,-0.08,-6.430909633,-2.616571799,90.00000001 +299.24,50.43283629,-2.557879576,51.5,-1.87E-11,10.00036957,-0.015,-6.384421213,-2.680913985,90.00000001 +299.25,50.43283629,-2.557878169,51.4998,-1.87E-11,10.00036957,0.05,-6.336599577,-2.742918389,90.00000001 +299.26,50.43283629,-2.557876761,51.499,-1.64E-11,10.00036957,0.1146875,-6.287454581,-2.802530923,90.00000001 +299.27,50.43283629,-2.557875354,51.4975,-6.88E-12,10.00036957,0.1784375,-6.236996537,-2.859699621,90.00000001 +299.28,50.43283629,-2.557873946,51.4954,7.81E-12,10.00036956,0.2415625,-6.185235988,-2.914374577,90.00000001 +299.29,50.43283629,-2.557872539,51.4927,1.80E-11,10.00036956,0.3053125,-6.132183706,-2.966508178,90.00000001 +299.3,50.43283629,-2.557871131,51.4893,2.02E-11,10.00036955,0.37,-6.077850805,-3.016054933,90.00000001 +299.31,50.43283629,-2.557869724,51.4853,1.66E-11,10.00014752,0.4346875,-6.022248632,-3.062971639,90.00000001 +299.32,50.43283629,-2.557868316,51.4806,6.41E-12,9.999481409,0.4984375,-5.965388759,-3.107217446,90.00000001 +299.33,50.43283629,-2.557866909,51.4753,-6.87E-12,9.999037334,0.5615625,-5.907283103,-3.148753677,90.00000001 +299.34,50.43283629,-2.557865502,51.4694,-1.27E-11,9.99948139,0.625,-5.847943813,-3.187544123,90.00000001 +299.35,50.43283629,-2.557864094,51.4628,-7.97E-12,10.00014748,0.688125,-5.787383262,-3.223554979,90.00000001 +299.36,50.43283629,-2.557862687,51.4556,-4.69E-12,10.0003695,0.75,-5.725614057,-3.256754904,90.00000001 +299.37,50.43283629,-2.557861279,51.4478,-1.08E-11,10.00036949,0.811875,-5.662649147,-3.287114849,90.00000001 +299.38,50.43283629,-2.557859872,51.4394,-1.33E-11,10.00036948,0.8746875,-5.598501652,-3.314608343,90.00000001 +299.39,50.43283629,-2.557858464,51.4303,1.56E-12,10.00036946,0.9365625,-5.533184979,-3.339211495,90.00000001 +299.4,50.43283629,-2.557857057,51.4206,2.08E-11,10.00036945,0.9965625,-5.466712822,-3.360902817,90.00000001 +299.41,50.43283629,-2.557855649,51.4104,2.27E-11,10.00036943,1.056875,-5.399098932,-3.379663403,90.00000001 +299.42,50.43283629,-2.557854242,51.3995,1.02E-11,10.00036941,1.1184375,-5.330357575,-3.395476809,90.00000001 +299.43,50.43283629,-2.557852834,51.388,7.81E-13,10.0003694,1.1796875,-5.260503019,-3.408329341,90.00000001 +299.44,50.43283629,-2.557851427,51.3759,1.41E-12,10.00014734,1.2396875,-5.189549874,-3.418209769,90.00000001 +299.45,50.43283629,-2.557850019,51.3632,8.44E-12,9.999481225,1.298125,-5.117512922,-3.425109442,90.00000001 +299.46,50.43283629,-2.557848612,51.3499,1.23E-11,9.999037138,1.355,-5.044407289,-3.4290224,90.00000001 +299.47,50.43283629,-2.557847205,51.3361,7.03E-12,9.999481182,1.411875,-4.970248215,-3.429945148,90.00000001 +299.48,50.43283629,-2.557845797,51.3217,2.19E-12,10.00014726,1.47,-4.895051114,-3.427877,90.00000001 +299.49,50.43283629,-2.55784439,51.3067,6.87E-12,10.00036927,1.528125,-4.818831799,-3.422819616,90.00000001 +299.5,50.43283629,-2.557842982,51.2911,1.62E-11,10.00036924,1.584375,-4.741606084,-3.414777523,90.00000001 +299.51,50.43283629,-2.557841575,51.275,2.81E-11,10.00036922,1.6384375,-4.663390126,-3.403757711,90.00000001 +299.52,50.43283629,-2.557840167,51.2583,4.30E-11,10.00036919,1.6915625,-4.584200368,-3.389769749,90.00000001 +299.53,50.43283629,-2.55783876,51.2412,5.16E-11,10.00036917,1.745,-4.504053199,-3.37282584,90.00000001 +299.54,50.43283629,-2.557837352,51.2234,4.59E-11,10.00036914,1.7984375,-4.422965404,-3.352940824,90.00000001 +299.55,50.43283629,-2.557835945,51.2052,2.97E-11,10.00014708,1.85125,-4.340953944,-3.330131947,90.00000001 +299.56,50.43283629,-2.557834537,51.1864,1.25E-11,9.999480948,1.9034375,-4.25803595,-3.304419205,90.00000001 +299.57,50.43283629,-2.55783313,51.1671,1.56E-13,9.999036852,1.954375,-4.174228669,-3.275824887,90.00000001 +299.58,50.43283629,-2.557831723,51.1473,-1.17E-11,9.999480888,2.0034375,-4.089549689,-3.244374031,90.00000001 +299.59,50.43283629,-2.557830315,51.127,-2.58E-11,10.00014696,2.0515625,-4.004016659,-3.21009408,90.00000001 +299.6,50.43283629,-2.557828908,51.1063,-3.06E-11,10.00036896,2.0996875,-3.917647454,-3.17301483,90.00000001 +299.61,50.43283629,-2.5578275,51.085,-1.48E-11,10.00036892,2.146875,-3.830460122,-3.133168652,90.00000001 +299.62,50.43283629,-2.557826093,51.0633,1.48E-11,10.00014686,2.1928125,-3.74247277,-3.090590325,90.00000001 +299.63,50.43283629,-2.557824685,51.0412,3.83E-11,9.999480721,2.2384375,-3.653703903,-3.045316976,90.00000001 +299.64,50.43283629,-2.557823278,51.0185,4.13E-11,9.99903662,2.283125,-3.564172028,-2.997388025,90.00000001 +299.65,50.43283629,-2.557821871,50.9955,2.72E-11,9.99948065,2.32625,-3.473895767,-2.946845355,90.00000001 +299.66,50.43283629,-2.557820463,50.972,1.02E-11,10.00014671,2.3684375,-3.382894026,-2.89373297,90.00000001 +299.67,50.43283629,-2.557819056,50.9481,9.37E-13,10.00036871,2.4096875,-3.291185828,-2.838097164,90.00000001 +299.68,50.43283629,-2.557817648,50.9238,2.34E-12,10.00036867,2.4496875,-3.198790368,-2.779986524,90.00000001 +299.69,50.43283629,-2.557816241,50.8991,1.33E-11,10.0001466,2.4884375,-3.105726781,-2.719451699,90.00000001 +299.7,50.43283629,-2.557814833,50.874,3.03E-11,9.99948046,2.52625,-3.012014664,-2.656545517,90.00000001 +299.71,50.43283629,-2.557813426,50.8486,4.61E-11,9.999036354,2.5634375,-2.917673496,-2.591322752,90.00000001 +299.72,50.43283629,-2.557812019,50.8227,5.39E-11,9.99948038,2.5996875,-2.822723045,-2.523840298,90.00000001 +299.73,50.43283629,-2.557810611,50.7966,5.23E-11,10.00014644,2.6346875,-2.727183077,-2.454156999,90.00000001 +299.74,50.43283629,-2.557809204,50.77,4.22E-11,10.00036843,2.6684375,-2.63107359,-2.382333703,90.00000001 +299.75,50.43283629,-2.557807796,50.7432,2.34E-11,10.00036839,2.7009375,-2.534414635,-2.308432919,90.00000001 +299.76,50.43283629,-2.557806389,50.716,-1.72E-12,10.00036835,2.731875,-2.437226383,-2.232519163,90.00000001 +299.77,50.43283629,-2.557804981,50.6885,-2.44E-11,10.0003683,2.76125,-2.339529172,-2.15465861,90.00000001 +299.78,50.43283629,-2.557803574,50.6608,-3.38E-11,10.00014623,2.79,-2.241343343,-2.074919214,90.00000001 +299.79,50.43283629,-2.557802166,50.6327,-2.73E-11,9.999480082,2.8184375,-2.142689464,-1.993370418,90.00000001 +299.8,50.43283629,-2.557800759,50.6044,-1.09E-11,9.999035972,2.84625,-2.043588106,-1.910083382,90.00000001 +299.81,50.43283629,-2.557799352,50.5758,1.56E-12,9.999479993,2.8728125,-1.944059951,-1.8251307,90.00000001 +299.82,50.43283629,-2.557797944,50.5469,-7.19E-12,10.00014605,2.8965625,-1.844125856,-1.738586514,90.00000001 +299.83,50.43283629,-2.557796537,50.5178,-3.28E-11,10.00036803,2.918125,-1.743806618,-1.650526224,90.00000001 +299.84,50.43283629,-2.557795129,50.4886,-4.67E-11,10.00036799,2.94,-1.643123208,-1.561026664,90.00000001 +299.85,50.43283629,-2.557793722,50.459,-3.67E-11,10.00014591,2.96125,-1.542096597,-1.470165871,90.00000001 +299.86,50.43283629,-2.557792314,50.4293,-2.19E-11,9.999479765,2.979375,-1.440747983,-1.378023028,90.00000001 +299.87,50.43283629,-2.557790907,50.3994,-1.48E-11,9.999035651,2.9953125,-1.33909851,-1.284678577,90.00000001 +299.88,50.43283629,-2.5577895,50.3694,-6.25E-12,9.99947967,3.0115625,-1.237169375,-1.190213879,90.00000001 +299.89,50.43283629,-2.557788092,50.3392,4.84E-12,10.00014572,3.028125,-1.134981837,-1.094711269,90.00000001 +299.9,50.43283629,-2.557786685,50.3088,4.69E-12,10.00036771,3.043125,-1.032557323,-0.998254053,90.00000001 +299.91,50.43283629,-2.557785277,50.2783,-9.37E-12,10.00036766,3.05625,-0.929917148,-0.900926343,90.00000001 +299.92,50.43283629,-2.55778387,50.2477,-2.34E-11,10.00036761,3.068125,-0.82708274,-0.80281305,90.00000001 +299.93,50.43283629,-2.557782462,50.2169,-2.58E-11,10.00036756,3.0778125,-0.724075643,-0.70399966,90.00000001 +299.94,50.43283629,-2.557781055,50.1861,-2.36E-11,10.00036752,3.085,-0.620917342,-0.604572346,90.00000001 +299.95,50.43283629,-2.557779647,50.1552,-3.12E-11,10.00036747,3.0915625,-0.517629324,-0.504617853,90.00000001 +299.96,50.43283629,-2.55777824,50.1243,-4.37E-11,10.00014539,3.098125,-0.414233245,-0.404223329,90.00000001 +299.97,50.43283629,-2.557776832,50.0932,-4.61E-11,9.999479239,3.1028125,-0.31075065,-0.303476321,90.00000001 +299.98,50.43283629,-2.557775425,50.0622,-3.59E-11,9.999035124,3.1040625,-0.207203139,-0.202464721,90.00000001 +299.99,50.43283629,-2.557774018,50.0311,-1.89E-11,9.999479142,3.10125,-0.103612427,-0.101276536,90.00000001 +300,50.43283629,-2.55777261,50.0001,-4.69E-12,10.00014519,3.094375,-0.000213828,-0.000231303,90.00000001 diff --git a/Radii_of_curvature.m b/Radii_of_curvature.m new file mode 100644 index 0000000..868abc0 --- /dev/null +++ b/Radii_of_curvature.m @@ -0,0 +1,33 @@ +function [R_N,R_E]= Radii_of_curvature(L) +%Radii_of_curvature - Calculates the meridian and transverse radii of +%curvature +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 31/3/2012 by Paul Groves +% +% Inputs: +% L geodetic latitude (rad) +% +% Outputs: +% R_N meridian radius of curvature (m) +% R_E transverse radius of curvature (m) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Parameters +R_0 = 6378137; %WGS84 Equatorial radius in meters +e = 0.0818191908425; %WGS84 eccentricity + +% Calculate meridian radius of curvature using (2.105) +temp = 1 - (e * sin(L))^2; +R_N = R_0 * (1 - e^2) / temp^1.5; + +% Calculate transverse radius of curvature using (2.105) +R_E = R_0 / sqrt(temp); + +% Ends \ No newline at end of file diff --git a/Read_profile.m b/Read_profile.m new file mode 100644 index 0000000..db1d9fa --- /dev/null +++ b/Read_profile.m @@ -0,0 +1,53 @@ +function [in_profile,no_epochs,ok]= Read_profile(filename) +%Read_profile - inputs a motion profile in the following .csv format +% Column 1: time (sec) +% Column 2: latitude (deg)纬度 +% Column 3: longitude (deg)经度 +% Column 4: height (m) +% Column 5: north velocity (m/s) +% Column 6: east velocity (m/s) +% Column 7: down velocity (m/s) +% Column 8: roll angle of body w.r.t NED (deg)横滚角 +% Column 9: pitch angle of body w.r.t NED (deg)俯仰角 +% Column 10: yaw angle of body w.r.t NED (deg)航偏角 +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 31/3/2012 by Paul Groves +% +% Inputs: +% filename Name of file to write +% +% Outputs: +% in_profile Array of data from the file +% no_epochs Number of epochs of data in the file +% ok Indicates file has the expected number of columns +% 表明文件的列数和预期的一致 + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Parameters +deg_to_rad = 0.01745329252; + +% Read in the profile in .csv format +in_profile = csvread(filename); + +% Determine size of file +[no_epochs,no_columns] = size(in_profile); + +% Check number of columns is correct (otherwise return)检验列数是否正确 +if no_columns~=10 + disp('Input file has the wrong number of columns') + ok = false; +else + ok = true; + % Convert degrees to radians 把角度转换为弧度 + in_profile(:,2:3) = deg_to_rad * in_profile(:,2:3); + in_profile(:,8:10) = deg_to_rad * in_profile(:,8:10); +end %if + +% Ends \ No newline at end of file diff --git a/Satellite_positions_and_velocities.m b/Satellite_positions_and_velocities.m new file mode 100644 index 0000000..99019f7 --- /dev/null +++ b/Satellite_positions_and_velocities.m @@ -0,0 +1,75 @@ +function [sat_r_es_e,sat_v_es_e] = Satellite_positions_and_velocities(time,... + GNSS_config) +%Satellite_positions_and_velocities - returns ECEF Cartesian positions and +%ECEF velocities of all satellites in the constellation. Simple circular +%orbits with regularly distributed satellites are modeled. +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 11/4/2012 by Paul Groves +% +% Inputs: +% time Current simulation time(s) +% GNSS_config +% .no_sat Number of satellites in constellation +% .r_os Orbital radius of satellites (m) +% .inclination Inclination angle of satellites (deg) +% .const_delta_lambda Longitude offset of constellation (deg) +% .const_delta_t Timing offset of constellation (s) +% Outputs: +% sat_r_es_e (no_sat x 3) ECEF satellite position +% sat_v_es_e (no_sat x 3) ECEF satellite velocity +% + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants (sone of these could be changed to inputs at a later date) +mu = 3.986004418E14; %WGS84 Earth gravitational constant (m^3 s^-2) +omega_ie = 7.292115E-5; % Earth rotation rate in rad/s + +% Begins + +% Convert inclination angle to degrees +inclination = degtorad(GNSS_config.inclination); + +% Determine orbital angular rate using (8.8) +omega_is = sqrt(mu / GNSS_config.r_os^3); + +% Determine constellation time +const_time = time + GNSS_config.const_delta_t; + +% Loop satellites +for j = 1:GNSS_config.no_sat + + % (Corrected) argument of latitude + u_os_o = 2*pi*(j-1)/GNSS_config.no_sat + omega_is*const_time; + + % Satellite position in the orbital frame from (8.14) + r_os_o = GNSS_config.r_os*[cos(u_os_o);sin(u_os_o);0]; + + % Longitude of the ascending node from (8.16) + Omega = (pi*mod(j,6)/3 + degtorad(GNSS_config.const_delta_lambda)) -... + omega_ie*const_time; + + % ECEF Satellite Position from (8.19) + sat_r_es_e(j,1:3) = [r_os_o(1)*cos(Omega) - r_os_o(2)*... + cos(inclination)*sin(Omega);... + r_os_o(1)*sin(Omega) + r_os_o(2)*cos(inclination)*cos(Omega);... + r_os_o(2)*sin(inclination)]'; + + % Satellite velocity in the orbital frame from (8.25), noting that with + % a circular orbit r_os_o is constant and the time derivative of u_os_o + % is omega_is. + v_os_o = GNSS_config.r_os*omega_is*[-sin(u_os_o);cos(u_os_o);0]; + + % ECEF Satellite velocity from (8.26) + sat_v_es_e(j,1:3) = [v_os_o(1)*cos(Omega) - v_os_o(2)*... + cos(inclination)*sin(Omega) + omega_ie*sat_r_es_e(j,2);... + (v_os_o(1)*sin(Omega) + v_os_o(2)*cos(inclination)*cos(Omega) -... + omega_ie*sat_r_es_e(j,1)); v_os_o(2)*sin(inclination)]'; + +end % for j + +% Ends \ No newline at end of file diff --git a/Skew_symmetric.m b/Skew_symmetric.m new file mode 100644 index 0000000..81e2c3f --- /dev/null +++ b/Skew_symmetric.m @@ -0,0 +1,23 @@ +function A = Skew_symmetric(a) +%Skew_symmetric - Calculates skew-symmetric matrix +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 1/4/2012 by Paul Groves +% +% Inputs: +% a 3-element vector +% Outputs: +% A 3x3matrix + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +A = [ 0, -a(3), a(2);... + a(3), 0, -a(1);... + -a(2), a(1), 0]; + +% Ends \ No newline at end of file diff --git a/Smooth_profile_velocity.m b/Smooth_profile_velocity.m new file mode 100644 index 0000000..22398fc --- /dev/null +++ b/Smooth_profile_velocity.m @@ -0,0 +1,70 @@ +function Smooth_profile_velocity(in_filename,out_filename) +%Smooth_profile_velocity - Adjusts the velocity in a motion profile file to +% remove jitter resulting from numerical rounding in the position input to +% Adjust_profile_velocity +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 2/4/2012 by Paul Groves +% +% Inputs +% in_filename Name of inpit file, e.g. 'In_profile.csv' +% out_filename Name of inpit file, e.g. 'Out_profile.csv' + +% Begins + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Parameters +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; + + +% Input truth motion profile from .csv format file +[in_profile,no_epochs,ok] = Read_profile(in_filename); + +% End script if there is a problem with the file +if ~ok + return; +end %if + +% First epoch +out_profile(1,:) = in_profile(1,:); + +% Main loop +for epoch = 2:(no_epochs-1) + + % Input data from profile + time = in_profile(epoch,1); + L_b = in_profile(epoch,2); + lambda_b = in_profile(epoch,3); + h_b = in_profile(epoch,4); + v_eb_n_current = in_profile(epoch,5:7)'; + eul_nb = in_profile(epoch,8:10)'; + v_eb_n_prev = in_profile(epoch - 1,5:7)'; + v_eb_n_next = in_profile(epoch + 1,5:7)'; + + % Smooth velocity + v_eb_n = 0.5 * v_eb_n_current + 0.25 * v_eb_n_prev + 0.25 * v_eb_n_next; + + % Generate output profile record + out_profile(epoch,1) = time; + out_profile(epoch,2) = L_b; + out_profile(epoch,3) = lambda_b; + out_profile(epoch,4) = h_b; + out_profile(epoch,5:7) = v_eb_n'; + out_profile(epoch,8:10) = eul_nb'; + + +end %epoch + +% Last epoch +out_profile(no_epochs,:) = in_profile(no_epochs,:); + + +% Write output profile +Write_profile(out_filename,out_profile); + +% Ends \ No newline at end of file diff --git a/TC_KF_Epoch.m b/TC_KF_Epoch.m new file mode 100644 index 0000000..ca72903 --- /dev/null +++ b/TC_KF_Epoch.m @@ -0,0 +1,184 @@ +function [est_C_b_e_new,est_v_eb_e_new,est_r_eb_e_new,est_IMU_bias_new,... + est_clock_new,P_matrix_new] = TC_KF_Epoch(GNSS_measurements,... + no_meas,tor_s,est_C_b_e_old,est_v_eb_e_old,est_r_eb_e_old,... + est_IMU_bias_old,est_clock_old,P_matrix_old,meas_f_ib_b,... + est_L_b_old,TC_KF_config) +%TC_KF_Epoch - Implements one cycle of the tightly coupled INS/GNSS +% extended Kalman filter plus closed-loop correction of all inertial states +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 12/4/2012 by Paul Groves +% +% Inputs: +% GNSS_measurements GNSS measurement data: +% Column 1 Pseudo-range measurements (m) +% Column 2 Pseudo-range rate measurements (m/s) +% Columns 3-5 Satellite ECEF position (m) +% Columns 6-8 Satellite ECEF velocity (m/s) +% no_meas Number of satellites for which measurements are +% supplied +% tor_s propagation interval (s) +% est_C_b_e_old prior estimated body to ECEF coordinate +% transformation matrix +% est_v_eb_e_old prior estimated ECEF user velocity (m/s) +% est_r_eb_e_old prior estimated ECEF user position (m) +% est_IMU_bias_old prior estimated IMU biases (body axes) +% est_clock_old prior Kalman filter state estimates +% P_matrix_old previous Kalman filter error covariance matrix +% meas_f_ib_b measured specific force +% est_L_b_old previous latitude solution +% TC_KF_config +% .gyro_noise_PSD Gyro noise PSD (rad^2/s) +% .accel_noise_PSD Accelerometer noise PSD (m^2 s^-3) +% .accel_bias_PSD Accelerometer bias random walk PSD (m^2 s^-5) +% .gyro_bias_PSD Gyro bias random walk PSD (rad^2 s^-3) +% .clock_freq_PSD Receiver clock frequency-drift PSD (m^2/s^3) +% .clock_phase_PSD Receiver clock phase-drift PSD (m^2/s) +% .pseudo_range_SD Pseudo-range measurement noise SD (m) +% .range_rate_SD Pseudo-range rate measurement noise SD (m/s) +% +% Outputs: +% est_C_b_e_new updated estimated body to ECEF coordinate +% transformation matrix +% est_v_eb_e_new updated estimated ECEF user velocity (m/s) +% est_r_eb_e_new updated estimated ECEF user position (m) +% est_IMU_bias_new updated estimated IMU biases +% Rows 1-3 estimated accelerometer biases (m/s^2) +% Rows 4-6 estimated gyro biases (rad/s) +% est_clock_new updated Kalman filter state estimates +% Row 1 estimated receiver clock offset (m) +% Row 2 estimated receiver clock drift (m/s) +% P_matrix_new updated Kalman filter error covariance matrix + + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Constants (sone of these could be changed to inputs at a later date) +c = 299792458; % Speed of light in m/s +omega_ie = 7.292115E-5; % Earth rotation rate in rad/s +R_0 = 6378137; %WGS84 Equatorial radius in meters +e = 0.0818191908425; %WGS84 eccentricity + +% Begins + +% Skew symmetric matrix of Earth rate +Omega_ie = Skew_symmetric([0,0,omega_ie]); + +% SYSTEM PROPAGATION PHASE + +% 1. Determine transition matrix using (14.50) (first-order approx) +Phi_matrix = eye(17); +Phi_matrix(1:3,1:3) = Phi_matrix(1:3,1:3) - Omega_ie * tor_s; +Phi_matrix(1:3,13:15) = est_C_b_e_old * tor_s; +Phi_matrix(4:6,1:3) = -tor_s * Skew_symmetric(est_C_b_e_old * meas_f_ib_b); +Phi_matrix(4:6,4:6) = Phi_matrix(4:6,4:6) - 2 * Omega_ie * tor_s; +geocentric_radius = R_0 / sqrt(1 - (e * sin(est_L_b_old))^2) *... + sqrt(cos(est_L_b_old)^2 + (1 - e^2)^2 * sin(est_L_b_old)^2); % from (2.137) +Phi_matrix(4:6,7:9) = -tor_s * 2 * Gravity_ECEF(est_r_eb_e_old) /... + geocentric_radius * est_r_eb_e_old' / sqrt (est_r_eb_e_old' *... + est_r_eb_e_old); +Phi_matrix(4:6,10:12) = est_C_b_e_old * tor_s; +Phi_matrix(7:9,4:6) = eye(3) * tor_s; +Phi_matrix(16,17) = tor_s; + +% 2. Determine approximate system noise covariance matrix using (14.82) +Q_prime_matrix = zeros(17); +Q_prime_matrix(1:3,1:3) = eye(3) * TC_KF_config.gyro_noise_PSD * tor_s; +Q_prime_matrix(4:6,4:6) = eye(3) * TC_KF_config.accel_noise_PSD * tor_s; +Q_prime_matrix(10:12,10:12) = eye(3) * TC_KF_config.accel_bias_PSD * tor_s; +Q_prime_matrix(13:15,13:15) = eye(3) * TC_KF_config.gyro_bias_PSD * tor_s; +Q_prime_matrix(16,16) = TC_KF_config.clock_phase_PSD * tor_s; +Q_prime_matrix(17,17) = TC_KF_config.clock_freq_PSD * tor_s; + +% 3. Propagate state estimates using (3.14) noting that only the clock +% states are non-zero due to closed-loop correction. +x_est_propagated(1:15,1) = 0; +x_est_propagated(16,1) = est_clock_old(1) + est_clock_old(2) * tor_s; +x_est_propagated(17,1) = est_clock_old(2); + +% 4. Propagate state estimation error covariance matrix using (3.46) +P_matrix_propagated = Phi_matrix * (P_matrix_old + 0.5 * Q_prime_matrix) *... + Phi_matrix' + 0.5 * Q_prime_matrix; + +% MEASUREMENT UPDATE PHASE + +u_as_e_T = zeros(no_meas,3); +pred_meas = zeros(no_meas,2); + +% Loop measurements +for j = 1:no_meas + + % Predict approx range + delta_r = GNSS_measurements(j,3:5)' - est_r_eb_e_old; + approx_range = sqrt(delta_r' * delta_r); + + % Calculate frame rotation during signal transit time using (8.36) + C_e_I = [1, omega_ie * approx_range / c, 0;... + -omega_ie * approx_range / c, 1, 0;... + 0, 0, 1]; + + % Predict pseudo-range using (9.165) + delta_r = C_e_I * GNSS_measurements(j,3:5)' - est_r_eb_e_old; + range = sqrt(delta_r' * delta_r); + pred_meas(j,1) = range + x_est_propagated(16); + + % Predict line of sight + u_as_e_T(j,1:3) = delta_r' / range; + + % Predict pseudo-range rate using (9.165) + range_rate = u_as_e_T(j,1:3) * (C_e_I * (GNSS_measurements(j,6:8)' +... + Omega_ie * GNSS_measurements(j,3:5)') - (est_v_eb_e_old +... + Omega_ie * est_r_eb_e_old)); + pred_meas(j,2) = range_rate + x_est_propagated(17); + +end % for j + +% 5. Set-up measurement matrix using (14.126) +H_matrix = zeros((2 * no_meas),17); +H_matrix(1:no_meas,7:9) = u_as_e_T(1:no_meas,1:3); +H_matrix(1:no_meas,16) = ones(no_meas,1); +H_matrix((no_meas + 1):(2 * no_meas),4:6) = u_as_e_T(1:no_meas,1:3); +H_matrix((no_meas + 1):(2 * no_meas),17) = ones(no_meas,1); + +% 6. Set-up measurement noise covariance matrix assuming all measurements +% are independent and have equal variance for a given measurement type. +R_matrix(1:no_meas,1:no_meas) = eye(no_meas) *... + TC_KF_config.pseudo_range_SD^2; +R_matrix(1:no_meas,(no_meas + 1):(2 * no_meas)) =... + zeros(no_meas); +R_matrix((no_meas + 1):(2 * no_meas),1:no_meas) =... + zeros(no_meas); +R_matrix((no_meas + 1):(2 * no_meas),(no_meas + 1):(2 * no_meas)) =... + eye(no_meas) * TC_KF_config.range_rate_SD^2; + +% 7. Calculate Kalman gain using (3.21) +K_matrix = P_matrix_propagated * H_matrix' * inv(H_matrix *... + P_matrix_propagated * H_matrix' + R_matrix); + +% 8. Formulate measurement innovations using (14.119) +delta_z(1:no_meas,1) = GNSS_measurements(1:no_meas,1) -... + pred_meas(1:no_meas,1); +delta_z((no_meas + 1):(2 * no_meas),1) = GNSS_measurements(1:no_meas,2) -... + pred_meas(1:no_meas,2); + +% 9. Update state estimates using (3.24) +x_est_new = x_est_propagated + K_matrix * delta_z; + +% 10. Update state estimation error covariance matrix using (3.25) +P_matrix_new = (eye(17) - K_matrix * H_matrix) * P_matrix_propagated; + +% CLOSED-LOOP CORRECTION + +% Correct attitude, velocity, and position using (14.7-9) +est_C_b_e_new = (eye(3) - Skew_symmetric(x_est_new(1:3))) * est_C_b_e_old; +est_v_eb_e_new = est_v_eb_e_old - x_est_new(4:6); +est_r_eb_e_new = est_r_eb_e_old - x_est_new(7:9); + +% Update IMU bias and GNSS receiver clock estimates +est_IMU_bias_new = est_IMU_bias_old + x_est_new(10:15); +est_clock_new = x_est_new(16:17)'; + +% Ends \ No newline at end of file diff --git a/Tightly_coupled_INS_GNSS.m b/Tightly_coupled_INS_GNSS.m new file mode 100644 index 0000000..160a733 --- /dev/null +++ b/Tightly_coupled_INS_GNSS.m @@ -0,0 +1,336 @@ +function [out_profile,out_errors,out_IMU_bias_est,out_clock,out_KF_SD] =... + Tightly_coupled_INS_GNSS(in_profile,no_epochs,initialization_errors,... + IMU_errors,GNSS_config,TC_KF_config) +%Tightly_coupled_INS_GNSS - Simulates inertial navigation using ECEF +% navigation equations and kinematic model, GNSS and tightly coupled +% INS/GNSS integration. +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 12/4/2012 by Paul Groves +% +% Inputs: +% in_profile True motion profile array +% no_epochs Number of epochs of profile data +% initialization_errors +% .delta_r_eb_n position error resolved along NED (m) +% .delta_v_eb_n velocity error resolved along NED (m/s) +% .delta_eul_nb_n attitude error as NED Euler angles (rad) +% IMU_errors +% .delta_r_eb_n position error resolved along NED (m) +% .b_a Accelerometer biases (m/s^2) +% .b_g Gyro biases (rad/s) +% .M_a Accelerometer scale factor and cross coupling errors +% .M_g Gyro scale factor and cross coupling errors +% .G_g Gyro g-dependent biases (rad-sec/m) +% .accel_noise_root_PSD Accelerometer noise root PSD (m s^-1.5) +% .gyro_noise_root_PSD Gyro noise root PSD (rad s^-0.5) +% .accel_quant_level Accelerometer quantization level (m/s^2) +% .gyro_quant_level Gyro quantization level (rad/s) +% GNSS_config +% .epoch_interval Interval between GNSS epochs (s) +% .init_est_r_ea_e Initial estimated position (m; ECEF) +% .no_sat Number of satellites in constellation +% .r_os Orbital radius of satellites (m) +% .inclination Inclination angle of satellites (deg) +% .const_delta_lambda Longitude offset of constellation (deg) +% .const_delta_t Timing offset of constellation (s) +% .mask_angle Mask angle (deg) +% .SIS_err_SD Signal in space error SD (m) +% .zenith_iono_err_SD Zenith ionosphere error SD (m) +% .zenith_trop_err_SD Zenith troposphere error SD (m) +% .code_track_err_SD Code tracking error SD (m) +% .rate_track_err_SD Range rate tracking error SD (m/s) +% .rx_clock_offset Receiver clock offset at time=0 (m) +% .rx_clock_drift Receiver clock drift at time=0 (m/s) +% TC_KF_config +% .init_att_unc Initial attitude uncertainty per axis (rad) +% .init_vel_unc Initial velocity uncertainty per axis (m/s) +% .init_pos_unc Initial position uncertainty per axis (m) +% .init_b_a_unc Initial accel. bias uncertainty (m/s^2) +% .init_b_g_unc Initial gyro. bias uncertainty (rad/s) +% .init_clock_offset_unc Initial clock offset uncertainty per axis (m) +% .init_clock_drift_unc Initial clock drift uncertainty per axis (m/s) +% .gyro_noise_PSD Gyro noise PSD (rad^2/s) +% .accel_noise_PSD Accelerometer noise PSD (m^2 s^-3) +% .accel_bias_PSD Accelerometer bias random walk PSD (m^2 s^-5) +% .gyro_bias_PSD Gyro bias random walk PSD (rad^2 s^-3) +% .clock_freq_PSD Receiver clock frequency-drift PSD (m^2/s^3) +% .clock_phase_PSD Receiver clock phase-drift PSD (m^2/s) +% .pseudo_range_SD Pseudo-range measurement noise SD (m) +% .range_rate_SD Pseudo-range rate measurement noise SD (m/s) +% +% Outputs: +% out_profile Navigation solution as a motion profile array +% out_errors Navigation solution error array +% out_IMU_bias_est Kalman filter IMU bias estimate array +% out_clock GNSS Receiver clock estimate array +% out_KF_SD Output Kalman filter state uncertainties +% +% Format of motion profiles: +% Column 1: time (sec) +% Column 2: latitude (rad) +% Column 3: longitude (rad) +% Column 4: height (m) +% Column 5: north velocity (m/s) +% Column 6: east velocity (m/s) +% Column 7: down velocity (m/s) +% Column 8: roll angle of body w.r.t NED (rad) +% Column 9: pitch angle of body w.r.t NED (rad) +% Column 10: yaw angle of body w.r.t NED (rad) +% +% Format of error array: +% Column 1: time (sec) +% Column 2: north position error (m) +% Column 3: east position error (m) +% Column 4: down position error (m) +% Column 5: north velocity error (m/s) +% Column 6: east velocity error (m/s) +% Column 7: down velocity (error m/s) +% Column 8: attitude error about north (rad) +% Column 9: attitude error about east (rad) +% Column 10: attitude error about down = heading error (rad) +% +% Format of output IMU biases array: +% Column 1: time (sec) +% Column 2: estimated X accelerometer bias (m/s^2) +% Column 3: estimated Y accelerometer bias (m/s^2) +% Column 4: estimated Z accelerometer bias (m/s^2) +% Column 5: estimated X gyro bias (rad/s) +% Column 6: estimated Y gyro bias (rad/s) +% Column 7: estimated Z gyro bias (rad/s) +% +% Format of receiver clock array: +% Column 1: time (sec) +% Column 2: estimated clock offset (m) +% Column 3: estimated clock drift (m/s) +% +% Format of KF state uncertainties array: +% Column 1: time (sec) +% Column 2: X attitude error uncertainty (rad) +% Column 3: Y attitude error uncertainty (rad) +% Column 4: Z attitude error uncertainty (rad) +% Column 5: X velocity error uncertainty (m/s) +% Column 6: Y velocity error uncertainty (m/s) +% Column 7: Z velocity error uncertainty (m/s) +% Column 8: X position error uncertainty (m) +% Column 9: Y position error uncertainty (m) +% Column 10: Z position error uncertainty (m) +% Column 11: X accelerometer bias uncertainty (m/s^2) +% Column 12: Y accelerometer bias uncertainty (m/s^2) +% Column 13: Z accelerometer bias uncertainty (m/s^2) +% Column 14: X gyro bias uncertainty (rad/s) +% Column 15: Y gyro bias uncertainty (rad/s) +% Column 16: Z gyro bias uncertainty (rad/s) +% Column 17: clock offset uncertainty (m) +% Column 18: clock drift uncertainty (m/s) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Initialize true navigation solution +old_time = in_profile(1,1); +true_L_b = in_profile(1,2); +true_lambda_b = in_profile(1,3); +true_h_b = in_profile(1,4); +true_v_eb_n = in_profile(1,5:7)'; +true_eul_nb = in_profile(1,8:10)'; +true_C_b_n = Euler_to_CTM(true_eul_nb)'; +[old_true_r_eb_e,old_true_v_eb_e,old_true_C_b_e] =... + NED_to_ECEF(true_L_b,true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); + +% Determine satellite positions and velocities +[sat_r_es_e,sat_v_es_e] = Satellite_positions_and_velocities(old_time,... + GNSS_config); + +% Initialize the GNSS biases. Note that these are assumed constant throughout +% the simulation and are based on the initial elevation angles. Therefore, +% this function is unsuited to simulations longer than about 30 min. +GNSS_biases = Initialize_GNSS_biases(sat_r_es_e,old_true_r_eb_e,true_L_b,... + true_lambda_b,GNSS_config); + +% Generate GNSS measurements +[GNSS_measurements,no_GNSS_meas] = Generate_GNSS_measurements(old_time,... + sat_r_es_e,sat_v_es_e,old_true_r_eb_e,true_L_b,true_lambda_b,... + old_true_v_eb_e,GNSS_biases,GNSS_config); + +% Determine Least-squares GNSS position solution +[old_est_r_eb_e,old_est_v_eb_e,est_clock] = GNSS_LS_position_velocity(... + GNSS_measurements,no_GNSS_meas,GNSS_config.init_est_r_ea_e,[0;0;0]); +[old_est_L_b,old_est_lambda_b,old_est_h_b,old_est_v_eb_n] =... + pv_ECEF_to_NED(old_est_r_eb_e,old_est_v_eb_e); +est_L_b = old_est_L_b; + +% Initialize estimated attitude solution +old_est_C_b_n = Initialize_NED_attitude(true_C_b_n,initialization_errors); +[temp1,temp2,old_est_C_b_e] = NED_to_ECEF(old_est_L_b,... + old_est_lambda_b,old_est_h_b,old_est_v_eb_n,old_est_C_b_n); + +% Initialize output profile record and errors record +out_profile = zeros(no_epochs,10); +out_errors = zeros(no_epochs,10); + +% Generate output profile record +out_profile(1,1) = old_time; +out_profile(1,2) = old_est_L_b; +out_profile(1,3) = old_est_lambda_b; +out_profile(1,4) = old_est_h_b; +out_profile(1,5:7) = old_est_v_eb_n'; +out_profile(1,8:10) = CTM_to_Euler(old_est_C_b_n')'; + +% Determine errors and generate output record +[delta_r_eb_n,delta_v_eb_n,delta_eul_nb_n] = Calculate_errors_NED(... + old_est_L_b,old_est_lambda_b,old_est_h_b,old_est_v_eb_n,old_est_C_b_n,... + true_L_b,true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); +out_errors(1,1) = old_time; +out_errors(1,2:4) = delta_r_eb_n'; +out_errors(1,5:7) = delta_v_eb_n'; +out_errors(1,8:10) = delta_eul_nb_n'; + +% Initialize Kalman filter P matrix and IMU bias states +P_matrix = Initialize_TC_P_matrix(TC_KF_config); +est_IMU_bias = zeros(6,1); + +% Initialize IMU quantization residuals +quant_residuals = [0;0;0;0;0;0]; + +% Generate IMU bias and clock output records +out_IMU_bias_est(1,1) = old_time; +out_IMU_bias_est(1,2:7) = est_IMU_bias'; +out_clock(1,1) = old_time; +out_clock(1,2:3) = est_clock; + +% Generate KF uncertainty record +out_KF_SD(1,1) = old_time; +for i =1:17 + out_KF_SD(1,i+1) = sqrt(P_matrix(i,i)); +end % for i + +% Initialize GNSS model timing +time_last_GNSS = old_time; +GNSS_epoch = 1; + +% Progress bar +dots = '....................'; +bars = '||||||||||||||||||||'; +rewind = '\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b\b'; +fprintf(strcat('Processing: ',dots)); +progress_mark = 0; +progress_epoch = 0; + +% Main loop +for epoch = 2:no_epochs + + % Update progress bar + if (epoch - progress_epoch) > (no_epochs/20) + progress_mark = progress_mark + 1; + progress_epoch = epoch; + fprintf(strcat(rewind,bars(1:progress_mark),... + dots(1:(20 - progress_mark)))); + end % if epoch + + % Input data from motion profile + time = in_profile(epoch,1); + true_L_b = in_profile(epoch,2); + true_lambda_b = in_profile(epoch,3); + true_h_b = in_profile(epoch,4); + true_v_eb_n = in_profile(epoch,5:7)'; + true_eul_nb = in_profile(epoch,8:10)'; + true_C_b_n = Euler_to_CTM(true_eul_nb)'; + [true_r_eb_e,true_v_eb_e,true_C_b_e] =... + NED_to_ECEF(true_L_b,true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); + + % Time interval + tor_i = time - old_time; + + % Calculate specific force and angular rate + [true_f_ib_b,true_omega_ib_b] = Kinematics_ECEF(tor_i,true_C_b_e,... + old_true_C_b_e,true_v_eb_e,old_true_v_eb_e,old_true_r_eb_e); + + % Simulate IMU errors + [meas_f_ib_b,meas_omega_ib_b,quant_residuals] = IMU_model(tor_i,... + true_f_ib_b,true_omega_ib_b,IMU_errors,quant_residuals); + + % Correct IMU errors + meas_f_ib_b = meas_f_ib_b - est_IMU_bias(1:3); + meas_omega_ib_b = meas_omega_ib_b - est_IMU_bias(4:6); + + % Update estimated navigation solution + [est_r_eb_e,est_v_eb_e,est_C_b_e] = Nav_equations_ECEF(tor_i,... + old_est_r_eb_e,old_est_v_eb_e,old_est_C_b_e,meas_f_ib_b,... + meas_omega_ib_b); + + % Determine whether to update GNSS simulation and run Kalman filter + if (time - time_last_GNSS) >= GNSS_config.epoch_interval + GNSS_epoch = GNSS_epoch + 1; + tor_s = time - time_last_GNSS; % KF time interval + time_last_GNSS = time; + + % Determine satellite positions and velocities + [sat_r_es_e,sat_v_es_e] = Satellite_positions_and_velocities(time,... + GNSS_config); + + % Generate GNSS measurements + [GNSS_measurements,no_GNSS_meas] = Generate_GNSS_measurements(... + time,sat_r_es_e,sat_v_es_e,true_r_eb_e,true_L_b,true_lambda_b,... + true_v_eb_e,GNSS_biases,GNSS_config); + + % Run Integration Kalman filter + [est_C_b_e,est_v_eb_e,est_r_eb_e,est_IMU_bias,est_clock,P_matrix] =... + TC_KF_Epoch(GNSS_measurements,no_GNSS_meas,tor_s,est_C_b_e,... + est_v_eb_e,est_r_eb_e,est_IMU_bias,est_clock,P_matrix,... + meas_f_ib_b,est_L_b,TC_KF_config); + + % Generate IMU bias and clock output records + out_IMU_bias_est(GNSS_epoch,1) = time; + out_IMU_bias_est(GNSS_epoch,2:7) = est_IMU_bias'; + out_clock(GNSS_epoch,1) = time; + out_clock(GNSS_epoch,2:3) = est_clock; + + % Generate KF uncertainty output record + out_KF_SD(GNSS_epoch,1) = time; + for i =1:17 + out_KF_SD(GNSS_epoch,i+1) = sqrt(P_matrix(i,i)); + end % for i + + end % if time + + % Convert navigation solution to NED + [est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n] =... + ECEF_to_NED(est_r_eb_e,est_v_eb_e,est_C_b_e); + + % Generate output profile record + out_profile(epoch,1) = time; + out_profile(epoch,2) = est_L_b; + out_profile(epoch,3) = est_lambda_b; + out_profile(epoch,4) = est_h_b; + out_profile(epoch,5:7) = est_v_eb_n'; + out_profile(epoch,8:10) = CTM_to_Euler(est_C_b_n')'; + + % Determine errors and generate output record + [delta_r_eb_n,delta_v_eb_n,delta_eul_nb_n] = Calculate_errors_NED(... + est_L_b,est_lambda_b,est_h_b,est_v_eb_n,est_C_b_n,true_L_b,... + true_lambda_b,true_h_b,true_v_eb_n,true_C_b_n); + out_errors(epoch,1) = time; + out_errors(epoch,2:4) = delta_r_eb_n'; + out_errors(epoch,5:7) = delta_v_eb_n'; + out_errors(epoch,8:10) = delta_eul_nb_n'; + + % Reset old values + old_time = time; + old_true_r_eb_e = true_r_eb_e; + old_true_v_eb_e = true_v_eb_e; + old_true_C_b_e = true_C_b_e; + old_est_r_eb_e = est_r_eb_e; + old_est_v_eb_e = est_v_eb_e; + old_est_C_b_e = est_C_b_e; + +end %epoch + +% Complete progress bar +fprintf(strcat(rewind,bars,'\n')); + +% Ends \ No newline at end of file diff --git a/Update_curvilinear_position.m b/Update_curvilinear_position.m new file mode 100644 index 0000000..afd7955 --- /dev/null +++ b/Update_curvilinear_position.m @@ -0,0 +1,47 @@ +function [L_b,lambda_b,h_b]= Update_curvilinear_position(tor_i,old_L_b,... + old_lambda_b,old_h_b,old_v_eb_n,v_eb_n) +%Update_curvilinear_position - Updates latitude, longitude, and height by +%integrating the velocity +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 31/3/2012 by Paul Groves +% +% Inputs: +% tor_i time interval between epochs (s) +% old_L_b previous latitude (rad) +% old_lambda_b previous longitude (rad) +% old_h_b previous height (m) +% old_v_eb_n previous velocity of body w.r.t earth, resolved about +% north, east, and down (m/s) +% v_eb_n current velocity of body w.r.t earth, resolved about +% north, east, and down (m/s)% +% Outputs: +% L_b current latitude (rad) +% lambda_b current longitude (rad) +% h_b current height (m) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Calculate meridian and transverse radii of curvature +[old_R_N,old_R_E]= Radii_of_curvature(old_L_b); + +% Update height using (5.56) +h_b = old_h_b - 0.5 * tor_i * (old_v_eb_n(3) + v_eb_n(3)); + +% Update latitude using (5.56) +L_b = old_L_b + 0.5 * tor_i * (old_v_eb_n(1) / (old_R_N + old_h_b) +... + v_eb_n(1) / (old_R_N + h_b)); + +% Calculate meridian and transverse radii of curvature +[R_N,R_E]= Radii_of_curvature(L_b); + +% Update longitude using (5.56) +lambda_b = old_lambda_b + 0.5 * tor_i * (old_v_eb_n(2) / ((old_R_E +... + old_h_b) * cos(old_L_b)) + v_eb_n(2) / ((R_E + h_b) * cos(L_b))); + +% Ends \ No newline at end of file diff --git a/Velocity_from_curvilinear.m b/Velocity_from_curvilinear.m new file mode 100644 index 0000000..5cf0d79 --- /dev/null +++ b/Velocity_from_curvilinear.m @@ -0,0 +1,46 @@ +function v_eb_n = Velocity_from_curvilinear(tor_i,old_L_b,... + old_lambda_b,old_h_b,old_v_eb_n,L_b,lambda_b,h_b) +%Velocity_from_curvilinear - updates velocity by differentiating +%latitude, longitude, and height +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 31/3/2012 by Paul Groves +% +% Inputs: +% tor_i time interval between epochs (s) +% old_L_b previous latitude (rad) +% old_lambda_b previous longitude (rad) +% old_h_b previous height (m) +% old_v_eb_n previous velocity of body w.r.t earth, resolved about +% north, east, and down (m/s) +% L_b current latitude (rad) +% lambda_b current longitude (rad) +% h_b current height (m) +% Outputs: +% v_eb_n current velocity of body w.r.t earth, resolved about +% north, east, and down (m/s)% + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Calculate meridian and transverse radii of curvature +[old_R_N,old_R_E]= Radii_of_curvature(old_L_b); +[R_N,R_E]= Radii_of_curvature(L_b); + +% Differentiate latitude, longitude, and height +lat_rate = (L_b - old_L_b) / tor_i; +long_rate = (lambda_b - old_lambda_b) / tor_i; +ht_rate = (h_b - old_h_b) / tor_i; + +% Derive the current velocity using (5.56) +v_eb_n(1,1) = (old_R_N + h_b) * (2 * lat_rate - old_v_eb_n(1) / (old_R_N +... + old_h_b)); +v_eb_n(2,1) = ((R_E + h_b) * cos(L_b)) * (2 * long_rate - old_v_eb_n(2) /... + ((old_R_E + old_h_b) * cos(old_L_b))); +v_eb_n(3,1) = -2 * ht_rate - old_v_eb_n(3); + +% Ends \ No newline at end of file diff --git a/Write_errors.m b/Write_errors.m new file mode 100644 index 0000000..75f82ec --- /dev/null +++ b/Write_errors.m @@ -0,0 +1,38 @@ +function Write_errors(filename,out_errors) +%Write_errors - outputs the errors in the following .csv format +% Column 1: time (sec) +% Column 2: north position error (m) +% Column 3: east position error (m) +% Column 4: down position error (m) +% Column 5: north velocity (m/s) +% Column 6: east velocity (m/s) +% Column 7: down velocity (m/s) +% Column 8: roll component of NED attitude error (deg) +% Column 9: pitch component of NED attitude error (deg) +% Column 10: yaw component of NED attitude error (deg) +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 31/3/2012 by Paul Groves +% +% Inputs: +% filename Name of file to write +% out_errors Array of data to write + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Parameters +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; + +% Convert attitude errors from radians to degrees +out_errors(:,8:10) = rad_to_deg * out_errors(:,8:10); + +% Write output profile +dlmwrite(filename,out_errors,'newline','pc','precision',12); + +% Ends \ No newline at end of file diff --git a/Write_profile.m b/Write_profile.m new file mode 100644 index 0000000..709b324 --- /dev/null +++ b/Write_profile.m @@ -0,0 +1,39 @@ +function Write_profile(filename,out_profile) +%Write_profile - outputs a motion profile in the following .csv format +% Column 1: time (sec) +% Column 2: latitude (deg) +% Column 3: longitude (deg) +% Column 4: height (m) +% Column 5: north velocity (m/s) +% Column 6: east velocity (m/s) +% Column 7: down velocity (m/s) +% Column 8: roll angle of body w.r.t NED (deg) +% Column 9: pitch angle of body w.r.t NED (deg) +% Column 10: yaw angle of body w.r.t NED (deg) +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 31/3/2012 by Paul Groves +% +% Inputs: +% filename Name of file to write +% out_profile Array of data to write + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Begins + +% Parameters +deg_to_rad = 0.01745329252; +rad_to_deg = 1/deg_to_rad; + +% Convert output profile from radians to degrees +out_profile(:,2:3) = rad_to_deg * out_profile(:,2:3); +out_profile(:,8:10) = rad_to_deg * out_profile(:,8:10); + +% Write output profile +dlmwrite(filename,out_profile,'newline','pc','precision',12); + +% Ends \ No newline at end of file diff --git a/pv_ECEF_to_NED.m b/pv_ECEF_to_NED.m new file mode 100644 index 0000000..30f8697 --- /dev/null +++ b/pv_ECEF_to_NED.m @@ -0,0 +1,80 @@ +function [L_b,lambda_b,h_b,v_eb_n] = pv_ECEF_to_NED(r_eb_e,v_eb_e) +%pv_ECEF_to_NED - Converts Cartesian to curvilinear position and velocity +%resolving axes from ECEF to NED +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 11/4/2012 by Paul Groves +% +% Inputs: +% r_eb_e Cartesian position of body frame w.r.t. ECEF frame, resolved +% along ECEF-frame axes (m) +% v_eb_e velocity of body frame w.r.t. ECEF frame, resolved along +% ECEF-frame axes (m/s) +% +% Outputs: +% L_b latitude (rad) +% lambda_b longitude (rad) +% h_b height (m) +% v_eb_n velocity of body frame w.r.t. ECEF frame, resolved along +% north, east, and down (m/s) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Parameters +R_0 = 6378137; %WGS84 Equatorial radius in meters +e = 0.0818191908425; %WGS84 eccentricity + +% Begins + +% Convert position using Borkowski closed-form exact solution +% From (2.113) +lambda_b = atan2(r_eb_e(2),r_eb_e(1)); + +% From (C.29) and (C.30) +k1 = sqrt(1 - e^2) * abs (r_eb_e(3)); +k2 = e^2 * R_0; +beta = sqrt(r_eb_e(1)^2 + r_eb_e(2)^2); +E = (k1 - k2) / beta; +F = (k1 + k2) / beta; + +% From (C.31) +P = 4/3 * (E*F + 1); + +% From (C.32) +Q = 2 * (E^2 - F^2); + +% From (C.33) +D = P^3 + Q^2; + +% From (C.34) +V = (sqrt(D) - Q)^(1/3) - (sqrt(D) + Q)^(1/3); + +% From (C.35) +G = 0.5 * (sqrt(E^2 + V) + E); + +% From (C.36) +T = sqrt(G^2 + (F - V * G) / (2 * G - E)) - G; + +% From (C.37) +L_b = sign(r_eb_e(3)) * atan((1 - T^2) / (2 * T * sqrt (1 - e^2))); + +% From (C.38) +h_b = (beta - R_0 * T) * cos(L_b) +... + (r_eb_e(3) - sign(r_eb_e(3)) * R_0 * sqrt(1 - e^2)) * sin (L_b); + +% Calculate ECEF to NED coordinate transformation matrix using (2.150) +cos_lat = cos(L_b); +sin_lat = sin(L_b); +cos_long = cos(lambda_b); +sin_long = sin(lambda_b); +C_e_n = [-sin_lat * cos_long, -sin_lat * sin_long, cos_lat;... + -sin_long, cos_long, 0;... + -cos_lat * cos_long, -cos_lat * sin_long, -sin_lat]; + +% Transform velocity using (2.73) +v_eb_n = C_e_n * v_eb_e; + +% Ends \ No newline at end of file diff --git a/pv_NED_to_ECEF.m b/pv_NED_to_ECEF.m new file mode 100644 index 0000000..6577b70 --- /dev/null +++ b/pv_NED_to_ECEF.m @@ -0,0 +1,52 @@ +function [r_eb_e,v_eb_e] = pv_NED_to_ECEF(L_b,lambda_b,h_b,v_eb_n) +%pv_NED_to_ECEF - Converts curvilinear to Cartesian position and velocity +%resolving axes from NED to ECEF +% +% Software for use with "Principles of GNSS, Inertial, and Multisensor +% Integrated Navigation Systems," Second Edition. +% +% This function created 11/4/2012 by Paul Groves +% +% Inputs: +% L_b latitude (rad) +% lambda_b longitude (rad) +% h_b height (m) +% v_eb_n velocity of body frame w.r.t. ECEF frame, resolved along +% north, east, and down (m/s) +% +% Outputs: +% r_eb_e Cartesian position of body frame w.r.t. ECEF frame, resolved +% along ECEF-frame axes (m) +% v_eb_e velocity of body frame w.r.t. ECEF frame, resolved along +% ECEF-frame axes (m/s) + +% Copyright 2012, Paul Groves +% License: BSD; see license.txt for details + +% Parameters +R_0 = 6378137; %WGS84 Equatorial radius in meters +e = 0.0818191908425; %WGS84 eccentricity + +% Begins + +% Calculate transverse radius of curvature using (2.105) +R_E = R_0 / sqrt(1 - (e * sin(L_b))^2); + +% Convert position using (2.112) +cos_lat = cos(L_b); +sin_lat = sin(L_b); +cos_long = cos(lambda_b); +sin_long = sin(lambda_b); +r_eb_e = [(R_E + h_b) * cos_lat * cos_long;... + (R_E + h_b) * cos_lat * sin_long;... + ((1 - e^2) * R_E + h_b) * sin_lat]; + +% Calculate ECEF to NED coordinate transformation matrix using (2.150) +C_e_n = [-sin_lat * cos_long, -sin_lat * sin_long, cos_lat;... + -sin_long, cos_long, 0;... + -cos_lat * cos_long, -cos_lat * sin_long, -sin_lat]; + +% Transform velocity using (2.73) +v_eb_e = C_e_n' * v_eb_n; + +% Ends \ No newline at end of file